From 1af1d2d29a99720202fa21ab583b4a50f66e9315 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 23 Jul 2022 21:04:41 +0200
Subject: [PATCH 001/324] Add TEB to CMake config

For now teb_extension has to be built locally and then made available
through a environment variable. The goal is to make teb_extension
available through axii.
---
 CMakeLists.txt                                         | 4 ++++
 source/armarx/navigation/local_planning/CMakeLists.txt | 5 +++++
 2 files changed, 9 insertions(+)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 072b8adb..5e107a70 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -3,6 +3,10 @@ cmake_minimum_required(VERSION 3.18)
 # default settings
 set(ARMARX_ENABLE_DEPENDENCY_VERSION_CHECK_DEFAULT FALSE)
 
+# Find teb_extension locally with CMake
+# TODO(SALt): make teb_extension available through axii
+find_package(teb_extension REQUIRED)
+
 find_package("ArmarXCore" REQUIRED)
 include(${ArmarXCore_USE_FILE})
 
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index d857c412..49c0e9ad 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -12,3 +12,8 @@ armarx_add_library(local_planning
         ./TimedElasticBands.h
         core.h
 )
+
+target_link_libraries(local_planning
+    PUBLIC
+        teb_extension::obstacles
+)
-- 
GitLab


From 0a7c5a83a43c9a5fa383aeca0481be07dc5d3fab Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 23 Jul 2022 21:22:38 +0200
Subject: [PATCH 002/324] Start implementing teb into TimedElasticBands

---
 .../local_planning/TimedElasticBands.cpp      | 89 ++++++++++++++++++-
 .../local_planning/TimedElasticBands.h        |  9 ++
 2 files changed, 96 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index b069cba6..a9eee9b3 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,7 +1,14 @@
 #include "TimedElasticBands.h"
 
+#include <VirtualRobot/Robot.h>
+
+#include <ArmarXCore/core/logging/Logging.h>
+
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
+#include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
+#include <teb_local_planner/homotopy_class_planner.h>
+
 
 namespace armarx::navigation::loc_plan
 {
@@ -29,14 +36,92 @@ namespace armarx::navigation::loc_plan
     // TimedElasticBands
 
     TimedElasticBands::TimedElasticBands(const Params& params, const core::Scene& ctx) :
-        LocalPlanner(ctx), params(params)
+        LocalPlanner(ctx), params(params), scene(ctx)
     {
+        //TODO (SALt): init configuration, robot footprint
+        auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(0.2);
+
+        hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
+        hcp_->initialize(
+            cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);
+
+        ros::Time::init(); // we have to init time before we can use the planner
     }
 
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::Trajectory& goal)
     {
-        // TODO implement
+
+
+        //TODO (SALt): convert scene and trajectories
+
+        const core::Pose currentPose{scene.robot->getGlobalPose()};
+        const core::Pose currentTarget = goal.points().end()->waypoint.pose;
+
+        //TODO (SALt): convert Pose to PoseSE2
+
+        const teb_local_planner::PoseSE2 start;
+        const teb_local_planner::PoseSE2 end;
+        bool planToDestination = true;
+
+
+        core::Twist currentVelocity = core::Twist::Zero();
+        if (scene.platformVelocity.has_value())
+        {
+            currentVelocity = scene.platformVelocity.value();
+        }
+
+        geometry_msgs::Twist velocity_start;
+        velocity_start.linear.x = currentVelocity.linear.x();
+        velocity_start.linear.y = currentVelocity.linear.y();
+        velocity_start.angular.z = currentVelocity.angular.z();
+
+        //TODO (SALt): fill obstacles
+
+        try
+        {
+            hcp_->plan(start, end, &velocity_start, !planToDestination);
+        }
+        catch (std::exception& e)
+        {
+            ARMARX_DEBUG << "Caugth exception while planning: " << e.what();
+            return {};
+        }
+        ARMARX_VERBOSE << "Planned successfully (found " << hcp_->getTrajectoryContainer().size()
+                       << " Trajectories)";
+
+
+        // TODO implement return result
         return {};
     }
+
+    core::Trajectory
+    TimedElasticBands::convertTrajectory(teb_local_planner::TimedElasticBand& teb)
+    {
+        core::TrajectoryPoints trajectory;
+        trajectory.reserve(teb.poses().size());
+
+        teb_local_planner::PoseSequence::const_iterator poseIt = teb.poses().begin();
+        for (const teb_local_planner::VertexTimeDiff* timeDiff : teb.timediffs())
+        {
+            Eigen::Vector2d position = poseIt[0]->pose().position();
+            double theta = poseIt[0]->pose().theta();
+
+            Eigen::Vector2d diff = poseIt[1]->pose().position() - position;
+            float velocity = diff.norm() / timeDiff->dt();
+
+            //TODO (SALt): convert to Pose
+            core::Pose pose{};
+
+            trajectory.push_back({.waypoint = {pose}, .velocity = velocity});
+            poseIt++;
+        }
+        //TODO (SALt): convert to Pose
+        core::Pose end{};
+        trajectory.push_back({.waypoint = {end}, .velocity = 0});
+
+        return trajectory;
+    }
+
+
 } // namespace armarx::navigation::loc_plan
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index e43747cd..bfc87997 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -26,6 +26,8 @@
 
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
+#include <teb_local_planner/homotopy_class_planner.h>
+#include <teb_local_planner/teb_config.h>
 
 namespace armarx::navigation::loc_plan
 {
@@ -49,9 +51,16 @@ namespace armarx::navigation::loc_plan
 
         std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) override;
 
+    private:
+        core::Trajectory convertTrajectory(teb_local_planner::TimedElasticBand& teb);
+
     protected:
         const Params params;
 
     private:
+        const core::Scene& scene;
+        teb_local_planner::TebConfig cfg_;
+        teb_local_planner::ObstContainer teb_obstacles;
+        std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
     };
 } // namespace armarx::navigation::loc_plan
-- 
GitLab


From ad47b2641daf34148d403e90aeba3c44421bc701 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 25 Jul 2022 10:32:15 +0200
Subject: [PATCH 003/324] Setup ros_conversions file

---
 .../navigation/local_planning/CMakeLists.txt  |  2 +
 .../local_planning/ros_conversions.cpp        |  6 +++
 .../local_planning/ros_conversions.h          | 38 +++++++++++++++++++
 3 files changed, 46 insertions(+)
 create mode 100644 source/armarx/navigation/local_planning/ros_conversions.cpp
 create mode 100644 source/armarx/navigation/local_planning/ros_conversions.h

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 49c0e9ad..6e94d8e4 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -7,9 +7,11 @@ armarx_add_library(local_planning
     SOURCES 
         ./LocalPlanner.cpp
         ./TimedElasticBands.cpp
+        ./ros_conversions.cpp
     HEADERS
         ./LocalPlanner.h
         ./TimedElasticBands.h
+        ./ros_conversions.h
         core.h
 )
 
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
new file mode 100644
index 00000000..fc8ae25f
--- /dev/null
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -0,0 +1,6 @@
+#include "ros_conversions.h"
+
+namespace armarx::navigation::conv
+{
+
+} // namespace armarx::navigation::conv
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
new file mode 100644
index 00000000..4dab534f
--- /dev/null
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -0,0 +1,38 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/core/types.h>
+#include <geometry_msgs/Twist.h>
+#include <teb_local_planner/pose_se2.h>
+
+namespace armarx::navigation::conv
+{
+
+    teb_local_planner::PoseSE2 convertToRos(const core::Pose& pose);
+
+    core::Pose convertFromRos(const teb_local_planner::PoseSE2& pose);
+
+    geometry_msgs::Twist convertToRos(const core::Twist& velocity);
+
+} // namespace armarx::navigation::conv
-- 
GitLab


From e796e887b99139d955c5b81b6ecb1a7b7e4f4f5e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 25 Jul 2022 11:50:14 +0200
Subject: [PATCH 004/324] implement ros_conversions

---
 .../local_planning/TimedElasticBands.h        |  3 -
 .../local_planning/ros_conversions.cpp        | 88 +++++++++++++++++++
 .../local_planning/ros_conversions.h          | 12 ++-
 3 files changed, 97 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index bfc87997..27c88483 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -51,9 +51,6 @@ namespace armarx::navigation::loc_plan
 
         std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) override;
 
-    private:
-        core::Trajectory convertTrajectory(teb_local_planner::TimedElasticBand& teb);
-
     protected:
         const Params params;
 
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index fc8ae25f..f883056c 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -1,6 +1,94 @@
 #include "ros_conversions.h"
 
+#include <armarx/navigation/conversions/eigen.h>
+
 namespace armarx::navigation::conv
 {
+    teb_local_planner::PoseSE2
+    toRos(const core::Pose& pose)
+    {
+        core::Pose2D pose2D = to2D(pose);
+
+        Eigen::Vector2d pos = pose2D.translation();
+        double theta = Eigen::Rotation2Dd(pose2D.linear()).angle();
+
+        return {pos, theta};
+    }
+
+
+    core::Pose
+    fromRos(const teb_local_planner::PoseSE2& pose)
+    {
+        Eigen::Vector2d pos = pose.position();
+        double theta = pose.theta();
+
+        core::Pose2D ret;
+        ret.translation() = pos;
+        ret.linear() = Eigen::Rotation2D(theta).toRotationMatrix();
+
+        return to3D(ret);
+    }
+
+    geometry_msgs::Twist
+    toRos(const core::Twist& velocity)
+    {
+        geometry_msgs::Twist ret;
+        ret.linear.x = velocity.linear.x();
+        ret.linear.y = velocity.linear.y();
+        ret.angular.z = velocity.angular.z();
+
+        return ret;
+    }
+
+    teb_local_planner::TimedElasticBand
+    toRos(const core::Trajectory& trajectory)
+    {
+        teb_local_planner::TimedElasticBand teb;
+
+        bool first = true;
+        teb_local_planner::PoseSE2 lastPose;
+        for (core::TrajectoryPoint point : trajectory.points())
+        {
+            teb_local_planner::PoseSE2 pose = toRos(point.waypoint.pose);
+            teb.addPose(pose);
+
+            if (!first)
+            {
+                Eigen::Vector2d distance = pose.position() - lastPose.position();
+                double timeDiff = distance.norm() / point.velocity;
+                teb.addTimeDiff(timeDiff);
+
+                first = false;
+            }
+
+            lastPose = pose;
+        }
+
+        return teb;
+    }
+
+    core::Trajectory
+    fromRos(const teb_local_planner::TimedElasticBand& teb)
+    {
+        core::TrajectoryPoints trajectory;
+        trajectory.reserve(teb.poses().size());
+
+        teb_local_planner::PoseSequence::const_iterator poseIt = teb.poses().begin();
+        for (const teb_local_planner::VertexTimeDiff* timeDiff : teb.timediffs())
+        {
+            Eigen::Vector2d distance = poseIt[1]->pose().position() - poseIt[0]->pose().position();
+            float velocity = distance.norm() / timeDiff->dt();
+
+            core::Pose pose = fromRos(poseIt[0]->pose());
+
+            trajectory.push_back({.waypoint = {pose}, .velocity = velocity});
+            poseIt++;
+        }
+        core::Pose end = fromRos(teb.poses().end()[0]->pose());
+        trajectory.push_back({.waypoint = {end}, .velocity = 0});
+
+        return {trajectory};
+    }
+
 
 } // namespace armarx::navigation::conv
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 4dab534f..62aea35b 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -25,14 +25,20 @@
 #include <armarx/navigation/core/types.h>
 #include <geometry_msgs/Twist.h>
 #include <teb_local_planner/pose_se2.h>
+#include <teb_local_planner/timed_elastic_band.h>
 
 namespace armarx::navigation::conv
 {
 
-    teb_local_planner::PoseSE2 convertToRos(const core::Pose& pose);
+    teb_local_planner::PoseSE2 toRos(const core::Pose& pose);
 
-    core::Pose convertFromRos(const teb_local_planner::PoseSE2& pose);
+    core::Pose fromRos(const teb_local_planner::PoseSE2& pose);
+
+    geometry_msgs::Twist toRos(const core::Twist& velocity);
+
+    teb_local_planner::TimedElasticBand toRos(const core::Trajectory& trajectory);
+
+    core::Trajectory fromRos(const teb_local_planner::TimedElasticBand& teb);
 
-    geometry_msgs::Twist convertToRos(const core::Twist& velocity);
 
 } // namespace armarx::navigation::conv
-- 
GitLab


From 676ddce88e34210d771a88b1e1e421740df03469 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 25 Jul 2022 11:50:33 +0200
Subject: [PATCH 005/324] Use ros_conversions for TimedElasticBands

---
 .../local_planning/TimedElasticBands.cpp      | 60 ++++---------------
 .../local_planning/TimedElasticBands.h        |  1 +
 2 files changed, 13 insertions(+), 48 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index a9eee9b3..a5fecc5f 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -6,10 +6,10 @@
 
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
+#include <armarx/navigation/local_planning/ros_conversions.h>
 #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 
-
 namespace armarx::navigation::loc_plan
 {
 
@@ -51,30 +51,22 @@ namespace armarx::navigation::loc_plan
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::Trajectory& goal)
     {
-
-
-        //TODO (SALt): convert scene and trajectories
-
-        const core::Pose currentPose{scene.robot->getGlobalPose()};
-        const core::Pose currentTarget = goal.points().end()->waypoint.pose;
-
-        //TODO (SALt): convert Pose to PoseSE2
-
-        const teb_local_planner::PoseSE2 start;
-        const teb_local_planner::PoseSE2 end;
+        teb_local_planner::TimedElasticBand globalPath = conv::toRos(goal);
+        teb_globalPath = globalPath.poses();
+        hcp_->setGlobalPath(&teb_globalPath);
+
+        //TODO (SALt): calculate target pose
+        const teb_local_planner::PoseSE2 start =
+            conv::toRos(static_cast<core::Pose>(scene.robot->getGlobalPose()));
+        const teb_local_planner::PoseSE2 end = conv::toRos(goal.points().end()->waypoint.pose);
         bool planToDestination = true;
 
-
         core::Twist currentVelocity = core::Twist::Zero();
         if (scene.platformVelocity.has_value())
         {
             currentVelocity = scene.platformVelocity.value();
         }
-
-        geometry_msgs::Twist velocity_start;
-        velocity_start.linear.x = currentVelocity.linear.x();
-        velocity_start.linear.y = currentVelocity.linear.y();
-        velocity_start.angular.z = currentVelocity.angular.z();
+        geometry_msgs::Twist velocity_start = conv::toRos(currentVelocity);
 
         //TODO (SALt): fill obstacles
 
@@ -90,37 +82,9 @@ namespace armarx::navigation::loc_plan
         ARMARX_VERBOSE << "Planned successfully (found " << hcp_->getTrajectoryContainer().size()
                        << " Trajectories)";
 
+        core::Trajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
 
-        // TODO implement return result
-        return {};
-    }
-
-    core::Trajectory
-    TimedElasticBands::convertTrajectory(teb_local_planner::TimedElasticBand& teb)
-    {
-        core::TrajectoryPoints trajectory;
-        trajectory.reserve(teb.poses().size());
-
-        teb_local_planner::PoseSequence::const_iterator poseIt = teb.poses().begin();
-        for (const teb_local_planner::VertexTimeDiff* timeDiff : teb.timediffs())
-        {
-            Eigen::Vector2d position = poseIt[0]->pose().position();
-            double theta = poseIt[0]->pose().theta();
-
-            Eigen::Vector2d diff = poseIt[1]->pose().position() - position;
-            float velocity = diff.norm() / timeDiff->dt();
-
-            //TODO (SALt): convert to Pose
-            core::Pose pose{};
-
-            trajectory.push_back({.waypoint = {pose}, .velocity = velocity});
-            poseIt++;
-        }
-        //TODO (SALt): convert to Pose
-        core::Pose end{};
-        trajectory.push_back({.waypoint = {end}, .velocity = 0});
-
-        return trajectory;
+        return {{.trajectory = best}};
     }
 
 
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 27c88483..c3963709 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -58,6 +58,7 @@ namespace armarx::navigation::loc_plan
         const core::Scene& scene;
         teb_local_planner::TebConfig cfg_;
         teb_local_planner::ObstContainer teb_obstacles;
+        teb_local_planner::PoseSequence teb_globalPath;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
     };
 } // namespace armarx::navigation::loc_plan
-- 
GitLab


From 28f3cabb8550e4823fde1cdcd8620cb1a7cbc70b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 25 Jul 2022 12:28:52 +0200
Subject: [PATCH 006/324] Fix conversion dependency, Eigen casts

---
 source/armarx/navigation/local_planning/CMakeLists.txt |  1 +
 .../navigation/local_planning/ros_conversions.cpp      | 10 +++++-----
 2 files changed, 6 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 6e94d8e4..04e5feb9 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -4,6 +4,7 @@ armarx_add_library(local_planning
         ArmarXCoreInterfaces
         ArmarXCore
         armarx_navigation::core
+        armarx_navigation::conversions
     SOURCES 
         ./LocalPlanner.cpp
         ./TimedElasticBands.cpp
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index f883056c..bd2befd4 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -9,8 +9,8 @@ namespace armarx::navigation::conv
     {
         core::Pose2D pose2D = to2D(pose);
 
-        Eigen::Vector2d pos = pose2D.translation();
-        double theta = Eigen::Rotation2Dd(pose2D.linear()).angle();
+        Eigen::Vector2d pos = pose2D.translation().cast<double>();
+        double theta = Eigen::Rotation2Df(pose2D.linear()).angle();
 
         return {pos, theta};
     }
@@ -23,8 +23,8 @@ namespace armarx::navigation::conv
         double theta = pose.theta();
 
         core::Pose2D ret;
-        ret.translation() = pos;
-        ret.linear() = Eigen::Rotation2D(theta).toRotationMatrix();
+        ret.translation() = pos.cast<float>();
+        ret.linear() = Eigen::Rotation2Df(theta).toRotationMatrix();
 
         return to3D(ret);
     }
@@ -47,7 +47,7 @@ namespace armarx::navigation::conv
 
         bool first = true;
         teb_local_planner::PoseSE2 lastPose;
-        for (core::TrajectoryPoint point : trajectory.points())
+        for (const core::TrajectoryPoint& point : trajectory.points())
         {
             teb_local_planner::PoseSE2 pose = toRos(point.waypoint.pose);
             teb.addPose(pose);
-- 
GitLab


From e416d8eb0a6af6e7bc8406138c014b872d77800a Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 25 Jul 2022 12:29:40 +0200
Subject: [PATCH 007/324] Init with default config

---
 .../local_planning/TimedElasticBands.cpp      | 28 +++++++++++++++++++
 .../local_planning/TimedElasticBands.h        |  3 ++
 2 files changed, 31 insertions(+)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index a5fecc5f..0621d44a 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -39,6 +39,7 @@ namespace armarx::navigation::loc_plan
         LocalPlanner(ctx), params(params), scene(ctx)
     {
         //TODO (SALt): init configuration, robot footprint
+        initConfig();
         auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(0.2);
 
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
@@ -48,6 +49,33 @@ namespace armarx::navigation::loc_plan
         ros::Time::init(); // we have to init time before we can use the planner
     }
 
+    void
+    TimedElasticBands::initConfig()
+    {
+        cfg_.robot.max_vel_x = 1.0;
+        cfg_.robot.max_vel_x_backwards = 1.0;
+        cfg_.robot.max_vel_y = 1.0;
+        cfg_.robot.max_vel_theta = 1.0;
+        cfg_.robot.acc_lim_x = 1.0;
+        cfg_.robot.acc_lim_y = 1.0;
+        cfg_.robot.acc_lim_theta = 1.0;
+
+        cfg_.optim.weight_max_vel_x = 1.0;
+        cfg_.optim.weight_max_vel_y = 1.0;
+        cfg_.optim.weight_max_vel_theta = 1.0;
+        cfg_.optim.weight_acc_lim_x = 1.0;
+        cfg_.optim.weight_acc_lim_y = 1.0;
+        cfg_.optim.weight_acc_lim_theta = 1.0;
+
+        cfg_.optim.weight_optimaltime = 0.6;
+        cfg_.optim.weight_shortest_path = 0.6;
+
+        cfg_.hcp.selection_cost_hysteresis = 1.0;
+        cfg_.hcp.switching_blocking_period = 0;
+
+        cfg_.pse.weight_global_path = 0.25;
+    }
+
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::Trajectory& goal)
     {
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index c3963709..8c3b7ade 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -51,6 +51,9 @@ namespace armarx::navigation::loc_plan
 
         std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) override;
 
+    private:
+        void initConfig();
+
     protected:
         const Params params;
 
-- 
GitLab


From 19ef414f34f44a2cb1bf7a6dfa75eb66052fc2e4 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 25 Jul 2022 20:30:36 +0200
Subject: [PATCH 008/324] renaming trajectory to globaltrajectory; will add
 trajectory for local planner soon

---
 .../smoothing/CircularPathSmoothing.cpp       |  8 +--
 .../smoothing/CircularPathSmoothing.h         |  2 +-
 .../NavigationMemory/NavigationMemory.cpp     | 12 ++--
 source/armarx/navigation/core/Graph.h         |  2 +-
 source/armarx/navigation/core/Trajectory.cpp  | 68 +++++++++----------
 source/armarx/navigation/core/Trajectory.h    | 40 +++++++----
 .../navigation/core/aron/Trajectory.xml       | 25 ++++++-
 .../navigation/core/aron_conversions.cpp      | 20 +++---
 .../armarx/navigation/core/aron_conversions.h |  8 +--
 .../navigation/global_planning/AStar.cpp      |  4 +-
 .../global_planning/GlobalPlanner.h           |  2 +-
 .../global_planning/Point2Point.cpp           | 12 ++--
 .../navigation/global_planning/SPFA.cpp       |  4 +-
 .../optimization/OrientationOptimizer.cpp     |  8 +--
 .../optimization/OrientationOptimizer.h       |  6 +-
 .../navigation/local_planning/LocalPlanner.h  |  4 +-
 .../local_planning/TimedElasticBands.cpp      |  2 +-
 .../local_planning/TimedElasticBands.h        |  4 +-
 .../memory/client/stack_result/Writer.cpp     |  2 +-
 .../PlatformTrajectoryController.h            |  2 +-
 .../PlatformTrajectoryControllerConfig.xml    |  2 +-
 source/armarx/navigation/server/Navigator.cpp | 12 ++--
 source/armarx/navigation/server/StackResult.h |  2 +-
 .../server/execution/ExecutorInterface.h      |  4 +-
 .../execution/PlatformControllerExecutor.cpp  |  2 +-
 .../execution/PlatformControllerExecutor.h    |  3 +-
 .../introspection/ArvizIntrospector.cpp       |  4 +-
 .../server/introspection/ArvizIntrospector.h  |  6 +-
 .../trajectory_control/TrajectoryController.h |  4 +-
 .../TrajectoryFollowingController.cpp         |  2 +-
 .../TrajectoryFollowingController.h           |  2 +-
 .../trajectory_control/WaypointController.cpp |  2 +-
 .../trajectory_control/WaypointController.h   |  2 +-
 .../armarx/navigation/util/Visualization.cpp  |  4 +-
 source/armarx/navigation/util/Visualization.h |  4 +-
 35 files changed, 159 insertions(+), 131 deletions(-)

diff --git a/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.cpp b/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.cpp
index 083dcfcc..3da33720 100644
--- a/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.cpp
+++ b/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.cpp
@@ -68,10 +68,10 @@ namespace armarx::navigation::algorithm
         return points;
     }
 
-    core::Trajectory
-    CircularPathSmoothing::smooth(const core::Trajectory& trajectory)
+    core::GlobalTrajectory
+    CircularPathSmoothing::smooth(const core::GlobalTrajectory& trajectory)
     {
-        core::TrajectoryPoints points;
+        core::GlobalTrajectoryPoints points;
         const auto& p = trajectory.points();
 
         points.push_back(p.front());
@@ -107,7 +107,7 @@ namespace armarx::navigation::algorithm
                 const Eigen::Vector2f prePos = at + Eigen::Vector2f(prev - at).normalized() * l;
                 const Eigen::Vector2f postPos = at + Eigen::Vector2f(next - at).normalized() * l;
 
-                const auto tpProj = [&](const Eigen::Vector2f& pos) -> core::TrajectoryPoint
+                const auto tpProj = [&](const Eigen::Vector2f& pos) -> core::GlobalTrajectoryPoint
                 {
                     const auto proj =
                         trajectory.getProjection(navigation::conv::to3D(pos),
diff --git a/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.h b/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.h
index 4e4d45bf..a36cf05d 100644
--- a/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.h
+++ b/source/armarx/navigation/algorithms/smoothing/CircularPathSmoothing.h
@@ -41,7 +41,7 @@ namespace armarx::navigation::algorithm
         /// circular path smoothing
         Points smooth(const Points& p);
 
-        core::Trajectory smooth(const core::Trajectory& trajectory);
+        core::GlobalTrajectory smooth(const core::GlobalTrajectory& trajectory);
     };
 
 } // namespace armarx::navigation::algorithm
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
index c3bec2c6..f35c33fa 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
@@ -108,13 +108,13 @@ namespace armarx::navigation
                                        algorithms::arondto::Costmap::ToAronType());
 
         workingMemory().addCoreSegment("Results_GlobalPlanner",
-                                       navigation::core::arondto::Trajectory::ToAronType());
+                                       navigation::core::arondto::GlobalTrajectory::ToAronType());
         workingMemory().addCoreSegment("Results_LocalPlanner",
-                                       navigation::core::arondto::Trajectory::ToAronType());
-        workingMemory().addCoreSegment("Results_TrajectoryController",
-                                       navigation::core::arondto::Twist::ToAronType());
-        workingMemory().addCoreSegment("Results_SafetyController",
-                                       navigation::core::arondto::Twist::ToAronType());
+                                       navigation::core::arondto::LocalTrajectory::ToAronType());
+        // workingMemory().addCoreSegment("Results_TrajectoryController",
+        //                                navigation::core::arondto::Twist::ToAronType());
+        // workingMemory().addCoreSegment("Results_SafetyController",
+        //                                navigation::core::arondto::Twist::ToAronType());
 
         workingMemory().addCoreSegment("Events"); //, armem::example::ExampleData::ToAronType());
         // workingMemory.addCoreSegment("Exceptions");  //, armem::example::ExampleData::ToAronType());
diff --git a/source/armarx/navigation/core/Graph.h b/source/armarx/navigation/core/Graph.h
index 904f51c6..92097dff 100644
--- a/source/armarx/navigation/core/Graph.h
+++ b/source/armarx/navigation/core/Graph.h
@@ -73,7 +73,7 @@ namespace armarx::navigation::core
             return m_value;
         }
 
-        std::optional<core::Trajectory> trajectory = std::nullopt;
+        std::optional<core::GlobalTrajectory> trajectory = std::nullopt;
 
         float m_value{0.F};
     };
diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index a5bbc1ea..5b200574 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -136,16 +136,16 @@ namespace armarx::navigation::core
     namespace conv
     {
 
-        TrajectoryPoint
+        GlobalTrajectoryPoint
         toTrajectoryPoint(const Pose& pose, const float velocity)
         {
-            return TrajectoryPoint{.waypoint = {.pose = pose}, .velocity = velocity};
+            return GlobalTrajectoryPoint{.waypoint = {.pose = pose}, .velocity = velocity};
         }
 
-        TrajectoryPoints
+        GlobalTrajectoryPoints
         toTrajectoryPoints(const Path& path, const float velocity)
         {
-            TrajectoryPoints trajectoryPoints;
+            GlobalTrajectoryPoints trajectoryPoints;
             trajectoryPoints.reserve(path.size());
 
             std::transform(path.begin(),
@@ -159,7 +159,7 @@ namespace armarx::navigation::core
     } // namespace conv
 
     Projection
-    Trajectory::getProjection(const Position& point,
+    GlobalTrajectory::getProjection(const Position& point,
                               const VelocityInterpolation& velocityInterpolation) const
     {
         float distance = std::numeric_limits<float>::max();
@@ -237,9 +237,9 @@ namespace armarx::navigation::core
     }
 
     std::vector<Eigen::Vector3f>
-    Trajectory::positions() const noexcept
+    GlobalTrajectory::positions() const noexcept
     {
-        const auto toPosition = [](const TrajectoryPoint& wp)
+        const auto toPosition = [](const GlobalTrajectoryPoint& wp)
         { return wp.waypoint.pose.translation(); };
 
         std::vector<Eigen::Vector3f> positions;
@@ -251,7 +251,7 @@ namespace armarx::navigation::core
     }
 
     std::vector<Pose>
-    Trajectory::poses() const noexcept
+    GlobalTrajectory::poses() const noexcept
     {
         std::vector<Pose> poses;
         poses.reserve(pts.size());
@@ -259,20 +259,20 @@ namespace armarx::navigation::core
         std::transform(pts.begin(),
                        pts.end(),
                        std::back_inserter(poses),
-                       [](const core::TrajectoryPoint& pt) -> core::Pose
+                       [](const core::GlobalTrajectoryPoint& pt) -> core::Pose
                        { return pt.waypoint.pose; });
 
         return poses;
     }
 
-    Trajectory
-    Trajectory::FromPath(const Path& path, const float velocity)
+    GlobalTrajectory
+    GlobalTrajectory::FromPath(const Path& path, const float velocity)
     {
         return {conv::toTrajectoryPoints(path, velocity)};
     }
 
-    Trajectory
-    Trajectory::FromPath(const Pose& start,
+    GlobalTrajectory
+    GlobalTrajectory::FromPath(const Pose& start,
                          const Positions& waypoints,
                          const Pose& goal,
                          const float velocity)
@@ -331,7 +331,7 @@ namespace armarx::navigation::core
     {
         core::Positions resampledPath;
 
-        const auto toPoint = [](const TrajectoryPoint& wp) -> Pose { return wp.waypoint.pose; };
+        const auto toPoint = [](const GlobalTrajectoryPoint& wp) -> Pose { return wp.waypoint.pose; };
 
         const core::Path originalPath = pts | ranges::views::transform(toPoint) | ranges::to_vector;
 
@@ -424,8 +424,8 @@ namespace armarx::navigation::core
         return resampledPath;
     }
 
-    Trajectory
-    Trajectory::resample(const float eps) const
+    GlobalTrajectory
+    GlobalTrajectory::resample(const float eps) const
     {
         ARMARX_CHECK_GREATER_EQUAL(pts.size(), 2);
 
@@ -438,14 +438,14 @@ namespace armarx::navigation::core
             ARMARX_DEBUG << "The resampled path contains no points. This means that it is likely "
                             "very short.";
 
-            const core::Trajectory testTrajectory = core::Trajectory::FromPath(
+            const core::GlobalTrajectory testTrajectory = core::GlobalTrajectory::FromPath(
                 pts.front().waypoint.pose, resampledPathForward, pts.back().waypoint.pose, 0.F);
 
             ARMARX_CHECK_LESS_EQUAL(testTrajectory.length(), eps)
                 << "The resampled trajectory is only allowed to contains no points if it is "
                    "shorter than eps";
 
-            return Trajectory({pts.front(), pts.back()});
+            return GlobalTrajectory({pts.front(), pts.back()});
         }
 
 
@@ -488,12 +488,12 @@ namespace armarx::navigation::core
             ranges::to_vector;
 
 
-        auto resampledTrajectory = Trajectory::FromPath(
+        auto resampledTrajectory = GlobalTrajectory::FromPath(
             pts.front().waypoint.pose, resampledPath, pts.back().waypoint.pose, 0.F);
 
         // set velocity based on original trajectory
         {
-            const auto setVelocityInPlace = [&](TrajectoryPoint& pt)
+            const auto setVelocityInPlace = [&](GlobalTrajectoryPoint& pt)
             {
                 const auto projection = getProjection(pt.waypoint.pose.translation(),
                                                       VelocityInterpolation::LinearInterpolation);
@@ -520,7 +520,7 @@ namespace armarx::navigation::core
     }
 
     float
-    Trajectory::length() const
+    GlobalTrajectory::length() const
     {
         namespace r = ::ranges;
 
@@ -541,18 +541,18 @@ namespace armarx::navigation::core
     }
 
     void
-    Trajectory::setMaxVelocity(float maxVelocity)
+    GlobalTrajectory::setMaxVelocity(float maxVelocity)
     {
         ARMARX_CHECK_GREATER_EQUAL(maxVelocity, 0.F) << "maxVelocity must be positive!";
 
         std::for_each(pts.begin(),
                       pts.end(),
-                      [&maxVelocity](TrajectoryPoint& pt)
+                      [&maxVelocity](GlobalTrajectoryPoint& pt)
                       { pt.velocity = std::clamp(pt.velocity, -maxVelocity, maxVelocity); });
     }
 
     bool
-    Trajectory::hasMaxDistanceBetweenWaypoints(const float maxDistance) const
+    GlobalTrajectory::hasMaxDistanceBetweenWaypoints(const float maxDistance) const
     {
         namespace r = ::ranges;
 
@@ -569,21 +569,21 @@ namespace armarx::navigation::core
             rng, [&maxDistance](const auto& dist) -> bool { return dist > maxDistance; });
     }
 
-    const std::vector<TrajectoryPoint>&
-    Trajectory::points() const
+    const std::vector<GlobalTrajectoryPoint>&
+    GlobalTrajectory::points() const
     {
         return pts;
     }
 
-    std::vector<TrajectoryPoint>&
-    Trajectory::mutablePoints()
+    std::vector<GlobalTrajectoryPoint>&
+    GlobalTrajectory::mutablePoints()
     {
         return pts;
     }
 
 
     float
-    Trajectory::duration(const core::VelocityInterpolation interpolation) const
+    GlobalTrajectory::duration(const core::VelocityInterpolation interpolation) const
     {
 
         float dur = 0;
@@ -618,16 +618,16 @@ namespace armarx::navigation::core
     }
 
     bool
-    Trajectory::isValid() const noexcept
+    GlobalTrajectory::isValid() const noexcept
     {
-        const auto isValid = [](const TrajectoryPoint& pt) -> bool
+        const auto isValid = [](const GlobalTrajectoryPoint& pt) -> bool
         { return std::isfinite(pt.velocity) and pt.velocity < 3000; };
 
         return std::all_of(pts.begin(), pts.end(), isValid);
     }
 
-    Trajectory::Indices
-    Trajectory::allConnectedPointsInRange(std::size_t idx, float radius) const
+    GlobalTrajectory::Indices
+    GlobalTrajectory::allConnectedPointsInRange(std::size_t idx, float radius) const
     {
         const core::Position referencePosition = pts.at(idx).waypoint.pose.translation();
 
@@ -639,7 +639,7 @@ namespace armarx::navigation::core
             return posDiff <= radius;
         };
 
-        Trajectory::Indices indices;
+        GlobalTrajectory::Indices indices;
 
 
         // traverse from query point to start
diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h
index fd5f7e4f..245f5dc9 100644
--- a/source/armarx/navigation/core/Trajectory.h
+++ b/source/armarx/navigation/core/Trajectory.h
@@ -24,26 +24,27 @@
 
 #include <cstddef>
 #include <memory>
+#include "ArmarXCore/core/time/DateTime.h"
 
 #include <armarx/navigation/core/basic_types.h>
 
 namespace armarx::navigation::core
 {
 
-    struct TrajectoryPoint
+    struct GlobalTrajectoryPoint
     {
         Waypoint waypoint;
         float velocity; // [mm/s]
     };
 
-    using TrajectoryPoints = std::vector<TrajectoryPoint>;
+    using GlobalTrajectoryPoints = std::vector<GlobalTrajectoryPoint>;
 
     struct Projection
     {
-        TrajectoryPoint projection;
+        GlobalTrajectoryPoint projection;
 
-        TrajectoryPoint wayPointBefore;
-        TrajectoryPoint wayPointAfter;
+        GlobalTrajectoryPoint wayPointBefore;
+        GlobalTrajectoryPoint wayPointAfter;
 
         enum class Segment
         {
@@ -61,14 +62,14 @@ namespace armarx::navigation::core
         LastWaypoint
     };
 
-    using TrajectoryPtr = std::shared_ptr<class Trajectory>;
+    using GlobalTrajectoryPtr = std::shared_ptr<class GlobalTrajectory>;
 
-    class Trajectory
+    class GlobalTrajectory
     {
     public:
-        Trajectory() = default;
+        GlobalTrajectory() = default;
 
-        Trajectory(const std::vector<TrajectoryPoint>& points) : pts(points)
+        GlobalTrajectory(const std::vector<GlobalTrajectoryPoint>& points) : pts(points)
         {
         }
 
@@ -82,15 +83,15 @@ namespace armarx::navigation::core
         //! Note: the velocity will not be set!
         // currently, only 2D version
         // y is pointing forward
-        static Trajectory FromPath(const Path& path, float velocity);
+        static GlobalTrajectory FromPath(const Path& path, float velocity);
 
         //! Note: the velocity will not be set!
         // currently, only 2D version
         // y is pointing forward
-        static Trajectory
+        static GlobalTrajectory
         FromPath(const Pose& start, const Positions& waypoints, const Pose& goal, float velocity);
 
-        Trajectory resample(float eps) const;
+        GlobalTrajectory resample(float eps) const;
 
         float length() const;
 
@@ -98,9 +99,9 @@ namespace armarx::navigation::core
 
         bool hasMaxDistanceBetweenWaypoints(float maxDistance) const;
 
-        const std::vector<TrajectoryPoint>& points() const;
+        const std::vector<GlobalTrajectoryPoint>& points() const;
 
-        std::vector<TrajectoryPoint>& mutablePoints();
+        std::vector<GlobalTrajectoryPoint>& mutablePoints();
 
         float duration(core::VelocityInterpolation interpolation) const;
 
@@ -118,7 +119,16 @@ namespace armarx::navigation::core
 
 
     private:
-        std::vector<TrajectoryPoint> pts;
+        std::vector<GlobalTrajectoryPoint> pts;
     };
 
+    struct LocalTrajectoryPoint
+    {
+        core::Pose pose;
+        DateTime timestamp;
+    };
+
+    using LocalTrajectory = std::vector<LocalTrajectoryPoint>;
+
+
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/aron/Trajectory.xml b/source/armarx/navigation/core/aron/Trajectory.xml
index 7e3c96c5..b0a19a9c 100644
--- a/source/armarx/navigation/core/aron/Trajectory.xml
+++ b/source/armarx/navigation/core/aron/Trajectory.xml
@@ -8,7 +8,8 @@
     </AronIncludes>
 
     <GenerateTypes>
-        <Object name='armarx::navigation::core::arondto::TrajectoryPoint'>
+        <!-- Global trajectory  -->
+        <Object name='armarx::navigation::core::arondto::GlobalTrajectoryPoint'>
             <ObjectChild key='velocity'>
                 <float />
             </ObjectChild>
@@ -17,10 +18,28 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::core::arondto::Trajectory'>
+        <Object name='armarx::navigation::core::arondto::GlobalTrajectory'>
             <ObjectChild key='points'>
                 <List>
-                    <armarx::navigation::core::arondto::TrajectoryPoint />
+                    <armarx::navigation::core::arondto::GlobalTrajectoryPoint />
+                </List>
+            </ObjectChild>
+        </Object>
+
+        <!-- Local trajectory  -->
+        <Object name='armarx::navigation::core::arondto::LocalTrajectoryPoint'>
+            <ObjectChild key='pose'>
+                <Pose />
+            </ObjectChild>
+            <ObjectChild key='timestamp'>
+                <Time />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::core::arondto::LocalTrajectory'>
+            <ObjectChild key='points'>
+                <List>
+                    <armarx::navigation::core::arondto::LocalTrajectoryPoint />
                 </List>
             </ObjectChild>
         </Object>
diff --git a/source/armarx/navigation/core/aron_conversions.cpp b/source/armarx/navigation/core/aron_conversions.cpp
index 7b93cdc2..aae32397 100644
--- a/source/armarx/navigation/core/aron_conversions.cpp
+++ b/source/armarx/navigation/core/aron_conversions.cpp
@@ -16,27 +16,27 @@ namespace armarx::navigation::core
 
 
     void
-    toAron(arondto::TrajectoryPoint& dto, const TrajectoryPoint& bo)
+    toAron(arondto::GlobalTrajectoryPoint& dto, const GlobalTrajectoryPoint& bo)
     {
         dto.pose = bo.waypoint.pose.matrix();
         dto.velocity = bo.velocity;
     }
 
     void
-    fromAron(const arondto::TrajectoryPoint& dto, TrajectoryPoint& bo)
+    fromAron(const arondto::GlobalTrajectoryPoint& dto, GlobalTrajectoryPoint& bo)
     {
         bo.waypoint.pose = core::Pose(dto.pose);
         bo.velocity = dto.velocity;
     }
 
     void
-    toAron(arondto::Trajectory& dto, const Trajectory& bo)
+    toAron(arondto::GlobalTrajectory& dto, const GlobalTrajectory& bo)
     {
         dto.points = bo.points() |
                      ranges::views::transform(
-                         [](const TrajectoryPoint& boTp) -> arondto::TrajectoryPoint
+                         [](const GlobalTrajectoryPoint& boTp) -> arondto::GlobalTrajectoryPoint
                          {
-                             arondto::TrajectoryPoint dtoTp;
+                             arondto::GlobalTrajectoryPoint dtoTp;
                              toAron(dtoTp, boTp);
                              return dtoTp;
                          }) |
@@ -44,15 +44,15 @@ namespace armarx::navigation::core
     }
 
     void
-    fromAron(const arondto::Trajectory& dto, Trajectory& bo)
+    fromAron(const arondto::GlobalTrajectory& dto, GlobalTrajectory& bo)
     {
-        bo = Trajectory(
+        bo = GlobalTrajectory(
             dto.points |
             ranges::views::
-                transform( //static_cast<TrajectoryPoint (*)(const arondto::TrajectoryPoint&)>(&fromAron)
-                    [](const arondto::TrajectoryPoint& dto) -> TrajectoryPoint
+                transform( //static_cast<TrajectoryPoint (*)(const arondto::GlobalTrajectoryPoint&)>(&fromAron)
+                    [](const arondto::GlobalTrajectoryPoint& dto) -> GlobalTrajectoryPoint
                     {
-                        TrajectoryPoint bo;
+                        GlobalTrajectoryPoint bo;
                         fromAron(dto, bo);
                         return bo;
                     }) |
diff --git a/source/armarx/navigation/core/aron_conversions.h b/source/armarx/navigation/core/aron_conversions.h
index 50f6cb44..0863383f 100644
--- a/source/armarx/navigation/core/aron_conversions.h
+++ b/source/armarx/navigation/core/aron_conversions.h
@@ -41,11 +41,11 @@ namespace armarx::navigation::core
         return dto;
     }
 
-    void toAron(arondto::TrajectoryPoint& dto, const TrajectoryPoint& bo);
-    void fromAron(const arondto::TrajectoryPoint& dto, TrajectoryPoint& bo);
+    void toAron(arondto::GlobalTrajectoryPoint& dto, const GlobalTrajectoryPoint& bo);
+    void fromAron(const arondto::GlobalTrajectoryPoint& dto, GlobalTrajectoryPoint& bo);
 
-    void toAron(arondto::Trajectory& dto, const Trajectory& bo);
-    void fromAron(const arondto::Trajectory& dto, Trajectory& bo);
+    void toAron(arondto::GlobalTrajectory& dto, const GlobalTrajectory& bo);
+    void fromAron(const arondto::GlobalTrajectory& dto, GlobalTrajectory& bo);
 
     void toAron(arondto::Twist& dto, const Twist& bo);
     void fromAron(const arondto::Twist& dto, Twist& bo);
diff --git a/source/armarx/navigation/global_planning/AStar.cpp b/source/armarx/navigation/global_planning/AStar.cpp
index 3dcd307c..eafc77da 100644
--- a/source/armarx/navigation/global_planning/AStar.cpp
+++ b/source/armarx/navigation/global_planning/AStar.cpp
@@ -236,12 +236,12 @@ namespace armarx::navigation::global_planning
 
         ARMARX_TRACE;
         auto trajectory =
-            core::Trajectory::FromPath(start, conv::to3D(smoothPlan), goal, params.linearVelocity);
+            core::GlobalTrajectory::FromPath(start, conv::to3D(smoothPlan), goal, params.linearVelocity);
 
         // TODO(fabian.reister): resampling of trajectory
 
         // FIXME param
-        std::optional<core::Trajectory> resampledTrajectory;
+        std::optional<core::GlobalTrajectory> resampledTrajectory;
 
         if (params.resampleDistance < 0)
         {
diff --git a/source/armarx/navigation/global_planning/GlobalPlanner.h b/source/armarx/navigation/global_planning/GlobalPlanner.h
index 1a028db1..6af2c754 100644
--- a/source/armarx/navigation/global_planning/GlobalPlanner.h
+++ b/source/armarx/navigation/global_planning/GlobalPlanner.h
@@ -37,7 +37,7 @@ namespace armarx::navigation::global_planning
 
     struct GlobalPlannerResult
     {
-        core::Trajectory trajectory;
+        core::GlobalTrajectory trajectory;
     };
 
 
diff --git a/source/armarx/navigation/global_planning/Point2Point.cpp b/source/armarx/navigation/global_planning/Point2Point.cpp
index e6714c9a..aa84b2d5 100644
--- a/source/armarx/navigation/global_planning/Point2Point.cpp
+++ b/source/armarx/navigation/global_planning/Point2Point.cpp
@@ -60,16 +60,16 @@ namespace armarx::navigation::global_planning
     std::optional<GlobalPlannerResult>
     Point2Point::plan(const core::Pose& goal)
     {
-        std::vector<core::TrajectoryPoint> trajectory;
+        std::vector<core::GlobalTrajectoryPoint> trajectory;
 
         if (params.includeStartPose)
         {
-            trajectory.push_back(core::TrajectoryPoint{
+            trajectory.push_back(core::GlobalTrajectoryPoint{
                 .waypoint = core::Waypoint{.pose = core::Pose(scene.robot->getGlobalPose())},
                 .velocity = params.velocity});
         }
 
-        trajectory.push_back(core::TrajectoryPoint{.waypoint = core::Waypoint{.pose = goal},
+        trajectory.push_back(core::GlobalTrajectoryPoint{.waypoint = core::Waypoint{.pose = goal},
                                                    .velocity = params.velocity});
 
         return GlobalPlannerResult{.trajectory = trajectory};
@@ -78,15 +78,15 @@ namespace armarx::navigation::global_planning
     std::optional<GlobalPlannerResult>
     Point2Point::plan(const core::Pose& start, const core::Pose& goal)
     {
-        std::vector<core::TrajectoryPoint> trajectory;
+        std::vector<core::GlobalTrajectoryPoint> trajectory;
 
         if (params.includeStartPose)
         {
-            trajectory.push_back(core::TrajectoryPoint{.waypoint = core::Waypoint{.pose = start},
+            trajectory.push_back(core::GlobalTrajectoryPoint{.waypoint = core::Waypoint{.pose = start},
                                                        .velocity = params.velocity});
         }
 
-        trajectory.push_back(core::TrajectoryPoint{.waypoint = core::Waypoint{.pose = goal},
+        trajectory.push_back(core::GlobalTrajectoryPoint{.waypoint = core::Waypoint{.pose = goal},
                                                    .velocity = params.velocity});
 
         return GlobalPlannerResult{.trajectory = trajectory};
diff --git a/source/armarx/navigation/global_planning/SPFA.cpp b/source/armarx/navigation/global_planning/SPFA.cpp
index e5c1c7cd..ed53c513 100644
--- a/source/armarx/navigation/global_planning/SPFA.cpp
+++ b/source/armarx/navigation/global_planning/SPFA.cpp
@@ -155,12 +155,12 @@ namespace armarx::navigation::global_planning
         // smoothPlan.pop_back();
 
         ARMARX_TRACE;
-        auto trajectory = core::Trajectory::FromPath(start, wpts, goal, params.linearVelocity);
+        auto trajectory = core::GlobalTrajectory::FromPath(start, wpts, goal, params.linearVelocity);
 
         // TODO(fabian.reister): resampling of trajectory
 
         // FIXME param
-        std::optional<core::Trajectory> resampledTrajectory;
+        std::optional<core::GlobalTrajectory> resampledTrajectory;
 
         try
         {
diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
index 2a7b5712..4b2182bf 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
@@ -31,7 +31,7 @@
 
 namespace armarx::navigation::global_planning::optimization
 {
-    OrientationOptimizer::OrientationOptimizer(const core::Trajectory& trajectory,
+    OrientationOptimizer::OrientationOptimizer(const core::GlobalTrajectory& trajectory,
                                                const Params& params) :
         trajectory(trajectory), params(params)
     {
@@ -45,7 +45,7 @@ namespace armarx::navigation::global_planning::optimization
         namespace r = ::ranges;
         namespace rv = ::ranges::views;
 
-        const auto toYaw = [](const core::TrajectoryPoint& pt) -> double
+        const auto toYaw = [](const core::GlobalTrajectoryPoint& pt) -> double
         { return simox::math::mat4f_to_xyyaw(pt.waypoint.pose.matrix()).z(); };
 
         std::vector<double> orientations =
@@ -218,9 +218,9 @@ namespace armarx::navigation::global_planning::optimization
             // TODO write to file
         }
 
-        const auto applyOrientation = [](const auto& p) -> core::TrajectoryPoint
+        const auto applyOrientation = [](const auto& p) -> core::GlobalTrajectoryPoint
         {
-            core::TrajectoryPoint tp = p.first;
+            core::GlobalTrajectoryPoint tp = p.first;
             const float yaw = p.second;
 
             tp.waypoint.pose.linear() = simox::math::rpy_to_mat3f(0.F, 0.F, yaw);
diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
index 62ef5548..46434a42 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
@@ -45,12 +45,12 @@ namespace armarx::navigation::global_planning::optimization
     public:
         using Params = OrientationOptimizerParams;
 
-        OrientationOptimizer(const core::Trajectory& trajectory, const Params& params);
+        OrientationOptimizer(const core::GlobalTrajectory& trajectory, const Params& params);
 
 
         struct OptimizationResult
         {
-            std::optional<core::Trajectory> trajectory;
+            std::optional<core::GlobalTrajectory> trajectory;
 
             operator bool() const noexcept
             {
@@ -63,7 +63,7 @@ namespace armarx::navigation::global_planning::optimization
 
     protected:
     private:
-        core::Trajectory trajectory;
+        core::GlobalTrajectory trajectory;
 
         const Params params;
     };
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h
index 5e7d06bf..46aa7ede 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.h
+++ b/source/armarx/navigation/local_planning/LocalPlanner.h
@@ -38,7 +38,7 @@ namespace armarx::navigation::loc_plan
 {
     struct LocalPlannerResult
     {
-        core::Trajectory trajectory;
+        core::GlobalTrajectory trajectory;
     };
 
     struct LocalPlannerParams
@@ -55,7 +55,7 @@ namespace armarx::navigation::loc_plan
         LocalPlanner(const core::Scene& context);
         virtual ~LocalPlanner() = default;
 
-        virtual std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) = 0;
+        virtual std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) = 0;
 
     protected:
     private:
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index b069cba6..3965d109 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -34,7 +34,7 @@ namespace armarx::navigation::loc_plan
     }
 
     std::optional<LocalPlannerResult>
-    TimedElasticBands::plan(const core::Trajectory& goal)
+    TimedElasticBands::plan(const core::GlobalTrajectory& goal)
     {
         // TODO implement
         return {};
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 8b965d15..6d9a90ae 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -50,9 +50,9 @@ namespace armarx::navigation::loc_plan
         TimedElasticBands(const Params& params, const core::Scene& ctx);
         ~TimedElasticBands() override = default;
 
-        void init(const core::Trajectory& initialTrajectory);
+        void init(const core::GlobalTrajectory& initialTrajectory);
 
-        std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) override;
+        std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
 
     protected:
         const Params params;
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.cpp b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
index 759b42f6..e693495e 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.cpp
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
@@ -72,7 +72,7 @@ namespace armarx::navigation::memory::client::stack_result
                               .withTimestamp(timestamp);
 
 
-        core::arondto::Trajectory aronDto;
+        core::arondto::GlobalTrajectory aronDto;
         // FIXME create Aron type
         core::toAron(aronDto, result.trajectory);
 
diff --git a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h b/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h
index 2b47dc98..daee089b 100644
--- a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h
+++ b/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h
@@ -44,7 +44,7 @@ namespace armarx::navigation::platform_controller::platform_trajectory
 {
     struct Targets
     {
-        core::Trajectory trajectory;
+        core::GlobalTrajectory trajectory;
     };
 
     struct Config
diff --git a/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml b/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml
index a6551b53..3ca40737 100644
--- a/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml
+++ b/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml
@@ -24,7 +24,7 @@
 
         <Object name='armarx::navigation::platform_controller::platform_trajectory::arondto::Targets'>
           <ObjectChild key='trajectory'>
-                <armarx::navigation::core::arondto::Trajectory />
+                <armarx::navigation::core::arondto::GlobalTrajectory />
           </ObjectChild>
         </Object>
 
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index e43dfa69..79744022 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -284,7 +284,7 @@ namespace armarx::navigation::server
         return shortestPath;
     }
 
-    core::Trajectory
+    core::GlobalTrajectory
     convertToTrajectory(const GraphPath& shortestPath, const core::Graph& graph)
     {
         ARMARX_TRACE;
@@ -294,7 +294,7 @@ namespace armarx::navigation::server
 
         // ARMARX_CHECK_EQUAL(shortestPath.size() - 1, shortestPath.edges.size());
 
-        std::vector<core::TrajectoryPoint> trajectoryPoints;
+        std::vector<core::GlobalTrajectoryPoint> trajectoryPoints;
 
         // TODO add the start
         // trajectoryPoints.push_back(core::TrajectoryPoint{
@@ -337,7 +337,7 @@ namespace armarx::navigation::server
                     // we have a trajectory
                     // FIXME trajectory points can be invalid => more points than expected. Why?
                     ARMARX_TRACE;
-                    const std::vector<core::TrajectoryPoint> edgeTrajectoryPoints =
+                    const std::vector<core::GlobalTrajectoryPoint> edgeTrajectoryPoints =
                         edge.attrib().trajectory->points();
 
                     // if trajectory is being initialized, include the start, otherwise skip it
@@ -376,11 +376,11 @@ namespace armarx::navigation::server
                     // FIXME variable
                     const float point2pointVelocity = 400;
 
-                    const core::TrajectoryPoint currentTrajPt = {
+                    const core::GlobalTrajectoryPoint currentTrajPt = {
                         .waypoint = {.pose = graph.vertex(shortestPath.at(i)).attrib().getPose()},
                         .velocity = point2pointVelocity};
 
-                    const core::TrajectoryPoint nextTrajPt{
+                    const core::GlobalTrajectoryPoint nextTrajPt{
                         .waypoint = {.pose =
                                          graph.vertex(shortestPath.at(i + 1)).attrib().getPose()},
                         .velocity = 0};
@@ -591,7 +591,7 @@ namespace armarx::navigation::server
 
         // convert graph / vertex chain to trajectory
         ARMARX_TRACE;
-        core::Trajectory globalPlanTrajectory = convertToTrajectory(shortestPath, graph);
+        core::GlobalTrajectory globalPlanTrajectory = convertToTrajectory(shortestPath, graph);
 
         // globalPlanTrajectory.setMaxVelocity(1000); // FIXME
 
diff --git a/source/armarx/navigation/server/StackResult.h b/source/armarx/navigation/server/StackResult.h
index c7f84cd3..f5299e64 100644
--- a/source/armarx/navigation/server/StackResult.h
+++ b/source/armarx/navigation/server/StackResult.h
@@ -35,7 +35,7 @@ namespace armarx::navigation::server
     struct StackResult
     {
         // TODO make struct, add timestamp
-        using LocalPlannerResult = core::TrajectoryPtr;
+        using LocalPlannerResult = core::GlobalTrajectoryPtr;
         using SafetyControllerResult = std::optional<core::Twist>;
 
         global_planning::GlobalPlannerResult globalPlan;
diff --git a/source/armarx/navigation/server/execution/ExecutorInterface.h b/source/armarx/navigation/server/execution/ExecutorInterface.h
index ea77fd7a..57e35506 100644
--- a/source/armarx/navigation/server/execution/ExecutorInterface.h
+++ b/source/armarx/navigation/server/execution/ExecutorInterface.h
@@ -2,7 +2,7 @@
 
 namespace armarx::navigation::core
 {
-    class Trajectory;
+    class GlobalTrajectory;
 } // namespace armarx::navigation::core
 
 namespace armarx::navigation::server
@@ -17,7 +17,7 @@ namespace armarx::navigation::server
     public:
         virtual ~ExecutorInterface() = default;
 
-        virtual void execute(const core::Trajectory& trajectory) = 0;
+        virtual void execute(const core::GlobalTrajectory& trajectory) = 0;
         
         virtual void start() = 0;
         virtual void stop() = 0;
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index 5f089038..d2bb7a47 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -70,7 +70,7 @@ namespace armarx::navigation::server
 
 
     void
-    PlatformControllerExecutor::execute(const core::Trajectory& trajectory)
+    PlatformControllerExecutor::execute(const core::GlobalTrajectory& trajectory)
     {
         ARMARX_INFO << "Received trajectory for execution with " << trajectory.points().size()
                     << " points";
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
index d256904c..721d1b62 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
@@ -5,7 +5,6 @@
 #include <armarx/control/client/ComponentPlugin.h>
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/core/types.h>
-#include <armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/controller_descriptions.h>
 #include <armarx/navigation/server/execution/ExecutorInterface.h>
 
@@ -32,7 +31,7 @@ namespace armarx::navigation::server
         PlatformControllerExecutor(ControllerComponentPlugin& controllerComponentPlugin);
         ~PlatformControllerExecutor() override;
 
-        void execute(const core::Trajectory& trajectory) override;
+        void execute(const core::GlobalTrajectory& trajectory) override;
 
         void start() override;
         void stop() override;
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 0f107c99..43f3e5fb 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -120,7 +120,7 @@ namespace armarx::navigation::server
     // private methods
 
     void
-    ArvizIntrospector::drawGlobalTrajectory(const core::Trajectory& trajectory)
+    ArvizIntrospector::drawGlobalTrajectory(const core::GlobalTrajectory& trajectory)
     {
         auto layer = arviz.layer("global_planner");
 
@@ -151,7 +151,7 @@ namespace armarx::navigation::server
     }
 
     void
-    ArvizIntrospector::drawLocalTrajectory(const core::Trajectory& trajectory)
+    ArvizIntrospector::drawLocalTrajectory(const core::GlobalTrajectory& trajectory)
     {
         auto layer = arviz.layer("local_planner");
 
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index a3daddc4..c9a4719a 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -40,7 +40,7 @@
 // forward declaration
 namespace armarx::navigation::core
 {
-    struct Trajectory;
+    struct GlobalTrajectory;
 }
 
 namespace armarx::navigation::server
@@ -70,8 +70,8 @@ namespace armarx::navigation::server
         ArvizIntrospector& operator=(ArvizIntrospector&&) noexcept;
 
     private:
-        void drawGlobalTrajectory(const core::Trajectory& trajectory);
-        void drawLocalTrajectory(const core::Trajectory& trajectory);
+        void drawGlobalTrajectory(const core::GlobalTrajectory& trajectory);
+        void drawLocalTrajectory(const core::GlobalTrajectory& trajectory);
         void drawRawVelocity(const core::Twist& twist);
         void drawSafeVelocity(const core::Twist& twist);
 
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryController.h b/source/armarx/navigation/trajectory_control/TrajectoryController.h
index 72d5927d..9ef9dbc2 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryController.h
+++ b/source/armarx/navigation/trajectory_control/TrajectoryController.h
@@ -42,7 +42,7 @@ namespace armarx::navigation::traj_ctrl
     struct TrajectoryControllerResult
     {
         core::Twist twist;
-        core::TrajectoryPoint dropPoint;
+        core::GlobalTrajectoryPoint dropPoint;
     };
 
     struct TrajectoryControllerParams
@@ -64,7 +64,7 @@ namespace armarx::navigation::traj_ctrl
         TrajectoryController() = default;
         virtual ~TrajectoryController() = default;
 
-        virtual TrajectoryControllerResult control(const core::Trajectory& goal) = 0;
+        virtual TrajectoryControllerResult control(const core::GlobalTrajectory& goal) = 0;
 
     };
     using TrajectoryControllerPtr = std::shared_ptr<TrajectoryController>;
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp
index b7fcdb2d..15282bf6 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp
@@ -127,7 +127,7 @@ namespace armarx::navigation::traj_ctrl
     }
 
     TrajectoryControllerResult
-    TrajectoryFollowingController::control(const core::Trajectory& trajectory)
+    TrajectoryFollowingController::control(const core::GlobalTrajectory& trajectory)
     {
         ARMARX_CHECK_NOT_NULL(robot) << "Robot not available";
 
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h b/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h
index ffb81732..cb7dc596 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h
+++ b/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h
@@ -51,7 +51,7 @@ namespace armarx::navigation::traj_ctrl
         TrajectoryFollowingController(const VirtualRobot::RobotPtr& robot, const Params& params);
         ~TrajectoryFollowingController() override = default;
 
-        TrajectoryControllerResult control(const core::Trajectory& trajectory) override;
+        TrajectoryControllerResult control(const core::GlobalTrajectory& trajectory) override;
 
         //    protected:
         core::Twist applyTwistLimits(core::Twist twist);
diff --git a/source/armarx/navigation/trajectory_control/WaypointController.cpp b/source/armarx/navigation/trajectory_control/WaypointController.cpp
index 527bd4f3..a23f6cd4 100644
--- a/source/armarx/navigation/trajectory_control/WaypointController.cpp
+++ b/source/armarx/navigation/trajectory_control/WaypointController.cpp
@@ -46,7 +46,7 @@ namespace armarx::navigation::traj_ctrl
     }
 
     TrajectoryControllerResult
-    WaypointController::control(const core::Trajectory& goal)
+    WaypointController::control(const core::GlobalTrajectory& goal)
     {
         return {}; // TODO implement
     }
diff --git a/source/armarx/navigation/trajectory_control/WaypointController.h b/source/armarx/navigation/trajectory_control/WaypointController.h
index ec5d4372..78726abe 100644
--- a/source/armarx/navigation/trajectory_control/WaypointController.h
+++ b/source/armarx/navigation/trajectory_control/WaypointController.h
@@ -42,7 +42,7 @@ namespace armarx::navigation::traj_ctrl
         WaypointController(const Params& params);
         ~WaypointController() override = default;
 
-        TrajectoryControllerResult control(const core::Trajectory& goal) override;
+        TrajectoryControllerResult control(const core::GlobalTrajectory& goal) override;
 
     protected:
     private:
diff --git a/source/armarx/navigation/util/Visualization.cpp b/source/armarx/navigation/util/Visualization.cpp
index 31ffe3ec..fb91bf23 100644
--- a/source/armarx/navigation/util/Visualization.cpp
+++ b/source/armarx/navigation/util/Visualization.cpp
@@ -23,7 +23,7 @@ namespace armarx::navigation::util
     }
 
     void
-    Visualization::visualize(const core::Trajectory& trajectory)
+    Visualization::visualize(const core::GlobalTrajectory& trajectory)
     {
         // TODO(fabian.reister): more finegrained locking
         std::lock_guard g{paramsMutex};
@@ -60,7 +60,7 @@ namespace armarx::navigation::util
 
 
     void
-    Visualization::visualizeTrajectory(const core::Trajectory& trajectory)
+    Visualization::visualizeTrajectory(const core::GlobalTrajectory& trajectory)
     {
         if (!params.enableTrajectoryVisualization)
         {
diff --git a/source/armarx/navigation/util/Visualization.h b/source/armarx/navigation/util/Visualization.h
index 10db349a..6f249d7e 100644
--- a/source/armarx/navigation/util/Visualization.h
+++ b/source/armarx/navigation/util/Visualization.h
@@ -44,7 +44,7 @@ namespace armarx::navigation::util
         void failed();
 
 
-        void visualize(const core::Trajectory& trajectory);
+        void visualize(const core::GlobalTrajectory& trajectory);
 
         void
         updateParams(const Params& params)
@@ -54,7 +54,7 @@ namespace armarx::navigation::util
         }
 
     private:
-        void visualizeTrajectory(const core::Trajectory& trajectory);
+        void visualizeTrajectory(const core::GlobalTrajectory& trajectory);
 
         void asyncHideDelayed();
 
-- 
GitLab


From 6b5d9741de4a6146a4c7af497df0f3b7cff5f754 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 25 Jul 2022 21:08:41 +0200
Subject: [PATCH 009/324] distinguishing local and global trajectory type

---
 .../navigation/common/controller_types.h      | 10 ++--
 .../navigation/core/aron_conversions.cpp      | 47 +++++++++++++++-
 .../armarx/navigation/core/aron_conversions.h |  6 +++
 .../platform_controller/CMakeLists.txt        | 12 ++---
 ...=> PlatformGlobalTrajectoryController.cpp} | 14 ++---
 ...h => PlatformGlobalTrajectoryController.h} | 24 +--------
 ...tformGlobalTrajectoryControllerConfig.xml} |  8 +--
 ...latformLocalTrajectoryControllerConfig.xml | 43 +++++++++++++++
 .../platform_controller/aron_conversions.cpp  | 53 +++++++++++++------
 .../platform_controller/aron_conversions.h    |  4 +-
 .../controller_descriptions.h                 | 27 +++++++---
 .../execution/PlatformControllerExecutor.cpp  |  2 +-
 .../execution/PlatformControllerExecutor.h    |  2 +-
 13 files changed, 184 insertions(+), 68 deletions(-)
 rename source/armarx/navigation/platform_controller/{PlatformTrajectoryController.cpp => PlatformGlobalTrajectoryController.cpp} (94%)
 rename source/armarx/navigation/platform_controller/{PlatformTrajectoryController.h => PlatformGlobalTrajectoryController.h} (82%)
 rename source/armarx/navigation/platform_controller/aron/{PlatformTrajectoryControllerConfig.xml => PlatformGlobalTrajectoryControllerConfig.xml} (91%)
 create mode 100644 source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml

diff --git a/source/armarx/navigation/common/controller_types.h b/source/armarx/navigation/common/controller_types.h
index 905ea6de..444fca1e 100644
--- a/source/armarx/navigation/common/controller_types.h
+++ b/source/armarx/navigation/common/controller_types.h
@@ -7,12 +7,16 @@ namespace armarx::navigation::common
 
     enum class ControllerType
     {
-        PlatformTrajectory
+        PlatformGlobalTrajectory,
+        PlatformLocalTrajectory
     };
 
-    constexpr const char* PlatformTrajectoryControllerName=  "PlatformTrajectory";
+    constexpr const char* PlatformGlobalTrajectoryControllerName = "PlatformGlobalTrajectory";
+    constexpr const char* PlatformLocalTrajectoryControllerName = "PlatformLocalTrajectory";
 
     inline const simox::meta::EnumNames<ControllerType> ControllerTypeNames{
-        {ControllerType::PlatformTrajectory, PlatformTrajectoryControllerName}};
+        {ControllerType::PlatformGlobalTrajectory, PlatformGlobalTrajectoryControllerName},
+        {ControllerType::PlatformLocalTrajectory, PlatformLocalTrajectoryControllerName}};
+
 
 } // namespace armarx::navigation::common
diff --git a/source/armarx/navigation/core/aron_conversions.cpp b/source/armarx/navigation/core/aron_conversions.cpp
index aae32397..fae8aa97 100644
--- a/source/armarx/navigation/core/aron_conversions.cpp
+++ b/source/armarx/navigation/core/aron_conversions.cpp
@@ -3,8 +3,8 @@
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
 
-#include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/core/Trajectory.h>
 
 #include <armarx/navigation/core/Trajectory.h>
@@ -59,6 +59,51 @@ namespace armarx::navigation::core
             ranges::to_vector);
     }
 
+
+    void
+    toAron(arondto::LocalTrajectoryPoint& dto, const LocalTrajectoryPoint& bo)
+    {
+        dto.pose = bo.pose.matrix();
+        dto.timestamp = bo.timestamp;
+    }
+
+    void
+    fromAron(const arondto::LocalTrajectoryPoint& dto, LocalTrajectoryPoint& bo)
+    {
+        bo.pose = core::Pose(dto.pose);
+        bo.timestamp = dto.timestamp;
+    }
+
+    void
+    toAron(arondto::LocalTrajectory& dto, const LocalTrajectory& bo)
+    {
+        dto.points = bo |
+                     ranges::views::transform(
+                         [](const LocalTrajectoryPoint& boTp) -> arondto::LocalTrajectoryPoint
+                         {
+                             arondto::LocalTrajectoryPoint dtoTp;
+                             toAron(dtoTp, boTp);
+                             return dtoTp;
+                         }) |
+                     ranges::to_vector;
+    }
+
+    void
+    fromAron(const arondto::LocalTrajectory& dto, LocalTrajectory& bo)
+    {
+        bo =
+            dto.points |
+            ranges::views::
+                transform( //static_cast<TrajectoryPoint (*)(const arondto::GlobalTrajectoryPoint&)>(&fromAron)
+                    [](const arondto::LocalTrajectoryPoint& dto) -> LocalTrajectoryPoint
+                    {
+                        LocalTrajectoryPoint bo;
+                        fromAron(dto, bo);
+                        return bo;
+                    }) |
+            ranges::to_vector;
+    }
+
     void
     toAron(arondto::Twist& dto, const Twist& bo)
     {
diff --git a/source/armarx/navigation/core/aron_conversions.h b/source/armarx/navigation/core/aron_conversions.h
index 0863383f..2fd54753 100644
--- a/source/armarx/navigation/core/aron_conversions.h
+++ b/source/armarx/navigation/core/aron_conversions.h
@@ -47,6 +47,12 @@ namespace armarx::navigation::core
     void toAron(arondto::GlobalTrajectory& dto, const GlobalTrajectory& bo);
     void fromAron(const arondto::GlobalTrajectory& dto, GlobalTrajectory& bo);
 
+    void toAron(arondto::LocalTrajectoryPoint& dto, const LocalTrajectoryPoint& bo);
+    void fromAron(const arondto::LocalTrajectoryPoint& dto, LocalTrajectoryPoint& bo);
+
+    void toAron(arondto::LocalTrajectory& dto, const LocalTrajectory& bo);
+    void fromAron(const arondto::LocalTrajectory& dto, LocalTrajectory& bo);
+
     void toAron(arondto::Twist& dto, const Twist& bo);
     void fromAron(const arondto::Twist& dto, Twist& bo);
 
diff --git a/source/armarx/navigation/platform_controller/CMakeLists.txt b/source/armarx/navigation/platform_controller/CMakeLists.txt
index 509c8f9a..a5a21b12 100644
--- a/source/armarx/navigation/platform_controller/CMakeLists.txt
+++ b/source/armarx/navigation/platform_controller/CMakeLists.txt
@@ -1,18 +1,19 @@
 armarx_add_aron_library(platform_controller_aron
   ARON_FILES
-    aron/PlatformTrajectoryControllerConfig.xml
+    aron/PlatformLocalTrajectoryControllerConfig.xml
+    aron/PlatformGlobalTrajectoryControllerConfig.xml
   DEPENDENCIES
     armarx_control::common_aron
 )
 
 armarx_add_library(platform_controller
   SOURCES
-    # WholeBodyImpedanceController.cpp
-    PlatformTrajectoryController.cpp
+    # PlatformLocalTrajectoryController.cpp
+    PlatformGlobalTrajectoryController.cpp
     aron_conversions.cpp
   HEADERS
-    # WholeBodyImpedanceController.h
-    PlatformTrajectoryController.h
+    # PlatformLocalTrajectoryController.h
+    PlatformGlobalTrajectoryController.h
     aron_conversions.h
   DEPENDENCIES_PUBLIC
     Simox::VirtualRobot
@@ -20,5 +21,4 @@ armarx_add_library(platform_controller
     armarx_control::client
     armarx_navigation::core
     armarx_navigation::trajectory_control
-    # armarx_control::njoint_qp_controller_aron
 )
diff --git a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
similarity index 94%
rename from source/armarx/navigation/platform_controller/PlatformTrajectoryController.cpp
rename to source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
index b5da2a90..a8758b6c 100644
--- a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.cpp
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
@@ -1,4 +1,4 @@
-#include "PlatformTrajectoryController.h"
+#include "PlatformGlobalTrajectoryController.h"
 
 #include "ArmarXCore/core/ArmarXObjectScheduler.h"
 #include "ArmarXCore/core/logging/Logging.h"
@@ -11,13 +11,13 @@
 #include <armarx/control/common/type.h>
 // #include <armarx/control/common/utils.h>
 #include <armarx/navigation/common/controller_types.h>
-#include <armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/aron_conversions.h>
 
-namespace armarx::navigation::platform_controller::platform_trajectory
+namespace armarx::navigation::platform_controller::platform_global_trajectory
 {
     const NJointControllerRegistration<Controller> Registration(
-        common::ControllerTypeNames.to_name(common::ControllerType::PlatformTrajectory));
+        common::ControllerTypeNames.to_name(common::ControllerType::PlatformGlobalTrajectory));
 
     Controller::Controller(const RobotUnitPtr& robotUnit,
                            const NJointControllerConfigPtr& config,
@@ -25,7 +25,7 @@ namespace armarx::navigation::platform_controller::platform_trajectory
     {
         ARMARX_IMPORTANT << "Creating "
                          << common::ControllerTypeNames.to_name(
-                                common::ControllerType::PlatformTrajectory);
+                                common::ControllerType::PlatformGlobalTrajectory);
         // config
         ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
         ARMARX_CHECK_EXPRESSION(cfg);
@@ -57,7 +57,7 @@ namespace armarx::navigation::platform_controller::platform_trajectory
     Controller::getClassName(const Ice::Current& iceCurrent) const
     {
         return armarx::navigation::common::ControllerTypeNames.to_name(
-            armarx::navigation::common::ControllerType::PlatformTrajectory);
+            armarx::navigation::common::ControllerType::PlatformGlobalTrajectory);
     }
 
     void
@@ -130,7 +130,7 @@ namespace armarx::navigation::platform_controller::platform_trajectory
         datafields["trajectory_points"] = new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.points().size());
 
         debugObservers->setDebugChannel(
-            common::ControllerTypeNames.to_name(common::ControllerType::PlatformTrajectory),
+            common::ControllerTypeNames.to_name(common::ControllerType::PlatformGlobalTrajectory),
             datafields);
     }
 
diff --git a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
similarity index 82%
rename from source/armarx/navigation/platform_controller/PlatformTrajectoryController.h
rename to source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
index daee089b..65d7d79a 100644
--- a/source/armarx/navigation/platform_controller/PlatformTrajectoryController.h
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
@@ -40,7 +40,7 @@ namespace armarx
 } // namespace armarx
 
 
-namespace armarx::navigation::platform_controller::platform_trajectory
+namespace armarx::navigation::platform_controller::platform_global_trajectory
 {
     struct Targets
     {
@@ -112,15 +112,6 @@ namespace armarx::navigation::platform_controller::platform_trajectory
         void rtPreActivateController() override;
 
     private:
-        // [[nodiscard]] bool initializeQPIK();
-
-        // void updateDebugStatus();
-
-        // struct DebugStatus
-        // {
-        //     std::map<std::string, float> data;
-        // };
-
         TripleBuffer<Config> configBuffer;
 
         // internal
@@ -133,17 +124,6 @@ namespace armarx::navigation::platform_controller::platform_trajectory
 
 
         Devices getDevices(const VirtualRobot::RobotNodeSet& rns);
-
-        // NameValueMap getJointVelocities(const NameValueMap& initialJointValues,
-        //                                 const NameValueMap& targetJointValues,
-        //                                 const std::set<std::string>& joints);
-
-        // Eigen::VectorXd toOptikRobotState(const NameValueMap& jointValues) const;
-
-        // NameValueMap getJointValuesWithVirtualPlatformJoints();
-
-        // NameValueMap getPlatformJointVelocity(const NameValueMap& initialJointAngles,
-        //                                       const NameValueMap& targetJointAngles) const;
     };
 
-}  // namespace armarx::navigation::platform_controller::platform_trajectory
+}  // namespace armarx::navigation::platform_controller::platform_global_trajectory
diff --git a/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml b/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
similarity index 91%
rename from source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml
rename to source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
index 3ca40737..515b1148 100644
--- a/source/armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.xml
+++ b/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
@@ -16,26 +16,26 @@
     </CodeIncludes>
     <GenerateTypes>
 
-        <Object name='armarx::navigation::platform_controller::platform_trajectory::arondto::Params'>
+        <Object name='armarx::navigation::platform_controller::platform_global_trajectory::arondto::Params'>
           <ObjectChild key='twistLimits'>
                 <armarx::navigation::core::arondto::TwistLimits />
           </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::platform_controller::platform_trajectory::arondto::Targets'>
+        <Object name='armarx::navigation::platform_controller::platform_global_trajectory::arondto::Targets'>
           <ObjectChild key='trajectory'>
                 <armarx::navigation::core::arondto::GlobalTrajectory />
           </ObjectChild>
         </Object>
 
 
-        <Object name='armarx::navigation::platform_controller::platform_trajectory::arondto::Config'>
+        <Object name='armarx::navigation::platform_controller::platform_global_trajectory::arondto::Config'>
             <ObjectChild key='params'>
                 <armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams />
             </ObjectChild>
 
             <ObjectChild key='targets'>
-                <armarx::navigation::platform_controller::platform_trajectory::arondto::Targets />
+                <armarx::navigation::platform_controller::platform_global_trajectory::arondto::Targets />
             </ObjectChild>
         </Object>
 
diff --git a/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml b/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml
new file mode 100644
index 00000000..a1479eef
--- /dev/null
+++ b/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml
@@ -0,0 +1,43 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <AronIncludes>
+        <Include include="../../core/aron/TwistLimits.xml" />
+        <Include include="../../core/aron/PIDParams.xml" />
+        <Include include="../../core/aron/Trajectory.xml" />
+        <Include include="../../trajectory_control/aron/TrajectoryFollowingControllerParams.xml" />
+        <!-- <Include include="<armarx/control/common/control_law/aron/TaskspaceImpedanceControllerConfig.xml>" /> -->
+    </AronIncludes>
+    <CodeIncludes>
+        <Include include="<Eigen/Core>" />
+        <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
+        <Include include="<armarx/navigation/core/aron/PIDParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/core/aron/Trajectory.aron.generated.h>" />
+        <Include include="<armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>" />
+    </CodeIncludes>
+    <GenerateTypes>
+
+        <Object name='armarx::navigation::platform_controller::platform_local_trajectory::arondto::Params'>
+          <ObjectChild key='twistLimits'>
+                <armarx::navigation::core::arondto::TwistLimits />
+          </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::platform_controller::platform_local_trajectory::arondto::Targets'>
+          <ObjectChild key='trajectory'>
+                <armarx::navigation::core::arondto::LocalTrajectory />
+          </ObjectChild>
+        </Object>
+
+
+        <Object name='armarx::navigation::platform_controller::platform_local_trajectory::arondto::Config'>
+            <ObjectChild key='params'>
+                <armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams />
+            </ObjectChild>
+
+            <ObjectChild key='targets'>
+                <armarx::navigation::platform_controller::platform_local_trajectory::arondto::Targets />
+            </ObjectChild>
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/platform_controller/aron_conversions.cpp b/source/armarx/navigation/platform_controller/aron_conversions.cpp
index 0f32b69e..8b502245 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.cpp
+++ b/source/armarx/navigation/platform_controller/aron_conversions.cpp
@@ -24,27 +24,50 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions/eigen.h>
 
 #include <armarx/control/common/aron_conversions.h>
-#include <armarx/navigation/platform_controller/PlatformTrajectoryController.h>
 #include <armarx/navigation/core/aron_conversions.h>
+#include <armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h>
+#include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/trajectory_control/aron_conversions.h>
-#include <armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.aron.generated.h>
 
 
-
-namespace armarx::navigation::platform_controller::platform_trajectory
+namespace armarx::navigation::platform_controller
 {
 
-    void
-    fromAron(const arondto::Targets& dto, Targets& bo)
+    namespace platform_global_trajectory
     {
-        fromAron(dto.trajectory, bo.trajectory);
-    }
 
-    void
-    fromAron(const arondto::Config& dto, Config& bo)
-    {
-        fromAron(dto.params, bo.params);
-        fromAron(dto.targets, bo.targets);
-    }
+        void
+        fromAron(const arondto::Targets& dto, Targets& bo)
+        {
+            fromAron(dto.trajectory, bo.trajectory);
+        }
+
+        void
+        fromAron(const arondto::Config& dto, Config& bo)
+        {
+            fromAron(dto.params, bo.params);
+            fromAron(dto.targets, bo.targets);
+        }
+
+    } // namespace platform_global_trajectory
+
+    // namespace platform_local_trajectory
+    // {
+
+    //     void
+    //     fromAron(const arondto::Targets& dto, Targets& bo)
+    //     {
+    //         fromAron(dto.trajectory, bo.trajectory);
+    //     }
+
+    //     void
+    //     fromAron(const arondto::Config& dto, Config& bo)
+    //     {
+    //         fromAron(dto.params, bo.params);
+    //         fromAron(dto.targets, bo.targets);
+    //     }
+
+    // } // namespace platform_local_trajectory
 
-} // namespace armarx::navigation::platform_controller::platform_trajectory
+} // namespace armarx::navigation::platform_controller
diff --git a/source/armarx/navigation/platform_controller/aron_conversions.h b/source/armarx/navigation/platform_controller/aron_conversions.h
index bd5518b1..1e338a7c 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.h
+++ b/source/armarx/navigation/platform_controller/aron_conversions.h
@@ -22,7 +22,7 @@
 #pragma once
 
 
-namespace armarx::navigation::platform_controller::platform_trajectory
+namespace armarx::navigation::platform_controller::platform_global_trajectory
 {
     namespace arondto
     {
@@ -32,4 +32,4 @@ namespace armarx::navigation::platform_controller::platform_trajectory
     struct Config;
 
     void fromAron(const arondto::Config& dto, Config& bo);
-}  // namespace armarx::navigation::platform_controller::platform_trajectory
+} // namespace armarx::navigation::platform_controller::platform_global_trajectory
diff --git a/source/armarx/navigation/platform_controller/controller_descriptions.h b/source/armarx/navigation/platform_controller/controller_descriptions.h
index d352bed1..cb602115 100644
--- a/source/armarx/navigation/platform_controller/controller_descriptions.h
+++ b/source/armarx/navigation/platform_controller/controller_descriptions.h
@@ -23,22 +23,37 @@
 
 #include <armarx/control/client/ControllerDescription.h>
 #include <armarx/navigation/common/controller_types.h>
-#include <armarx/navigation/platform_controller/PlatformTrajectoryController.h>
-#include <armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h>
+// #include <armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h>
+#include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
 
 namespace armarx::control::client
 {
     template <>
-    struct ControllerDescription<armarx::navigation::common::ControllerType::PlatformTrajectory>
+    struct ControllerDescription<armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>
     {
         using AronDTO =
-            armarx::navigation::platform_controller::platform_trajectory::arondto::Config;
+            armarx::navigation::platform_controller::platform_global_trajectory::arondto::Config;
 
-        using BO = armarx::navigation::platform_controller::platform_trajectory::Config;
+        using BO = armarx::navigation::platform_controller::platform_global_trajectory::Config;
 
         // constexpr static const char* name = armarx::navigation::common::ControllerTypeNames.to_name(armarx::navigation::common::ControllerType::PlatformTrajectory);
         constexpr static const char* name =
-            armarx::navigation::common::PlatformTrajectoryControllerName;
+            armarx::navigation::common::PlatformGlobalTrajectoryControllerName;
     };
 
+    // template <>
+    // struct ControllerDescription<armarx::navigation::common::ControllerType::PlatformLocalTrajectory>
+    // {
+    //     using AronDTO =
+    //         armarx::navigation::platform_controller::platform_local_trajectory::arondto::Config;
+
+    //     using BO = armarx::navigation::platform_controller::platform_local_trajectory::Config;
+
+    //     // constexpr static const char* name = armarx::navigation::common::ControllerTypeNames.to_name(armarx::navigation::common::ControllerType::PlatformTrajectory);
+    //     constexpr static const char* name =
+    //         armarx::navigation::common::PlatformLocalTrajectoryControllerName;
+    // };
+
 } // namespace armarx::control::client
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index d2bb7a47..9d173d95 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -45,7 +45,7 @@ namespace armarx::navigation::server
         {
             ARMARX_TRACE;
             auto builder = controllerPlugin.createControllerBuilder<
-                armarx::navigation::common::ControllerType::PlatformTrajectory>();
+                armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>();
 
             ARMARX_TRACE;
 
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
index 721d1b62..f852ea09 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
@@ -38,7 +38,7 @@ namespace armarx::navigation::server
 
     private:
         std::optional<armarx::control::client::ControllerWrapper<
-            armarx::navigation::common::ControllerType::PlatformTrajectory>>
+            armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>>
             ctrl;
 
         ControllerComponentPlugin& controllerPlugin;
-- 
GitLab


From 4754489619945c83b36cefc9c2ed144df6624220 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 25 Jul 2022 23:23:14 +0200
Subject: [PATCH 010/324] restructured trajectory following

---
 .../components/example_client/Component.cpp   |   8 +-
 .../client/NavigationStackConfig.cpp          |   4 +-
 .../navigation/client/NavigationStackConfig.h |   5 +-
 .../services/EventSubscriptionInterface.h     |   8 +-
 .../client/services/SimpleEventHandler.cpp    |  21 +-
 .../client/services/SimpleEventHandler.h      |   7 +-
 .../components/Navigator/RemoteGui.cpp        |   4 +-
 source/armarx/navigation/core/Trajectory.h    |   2 +-
 .../factories/TrajectoryControllerFactory.cpp |  21 +-
 .../factories/TrajectoryControllerFactory.h   |  15 +-
 .../navigation/local_planning/LocalPlanner.h  |   4 +-
 .../memory/client/stack_result/Writer.cpp     |  22 +-
 .../memory/client/stack_result/Writer.h       |  16 +-
 .../platform_controller/CMakeLists.txt        |   4 +-
 .../PlatformGlobalTrajectoryController.cpp    |  11 +-
 .../PlatformGlobalTrajectoryController.h      |   7 +-
 .../PlatformLocalTrajectoryController.cpp     | 168 +++++++++++++++
 .../PlatformLocalTrajectoryController.h       | 129 ++++++++++++
 ...atformGlobalTrajectoryControllerConfig.xml |  13 +-
 ...latformLocalTrajectoryControllerConfig.xml |  13 +-
 .../platform_controller/aron_conversions.cpp  |  32 +--
 .../platform_controller/aron_conversions.h    |  32 ++-
 .../controller_descriptions.h                 |  22 +-
 .../navigation/server/NavigationStack.h       |   3 +-
 source/armarx/navigation/server/Navigator.cpp |   4 +-
 source/armarx/navigation/server/Navigator.h   |   2 +-
 source/armarx/navigation/server/StackResult.h |  11 +-
 .../EventPublishingInterface.h                |   6 +-
 .../event_publishing/MemoryPublisher.cpp      |  11 +-
 .../server/event_publishing/MemoryPublisher.h |   4 +-
 .../server/execution/ExecutorInterface.h      |   9 +-
 .../execution/PlatformControllerExecutor.cpp  |  19 +-
 .../execution/PlatformControllerExecutor.h    |   4 +-
 .../introspection/ArvizIntrospector.cpp       |  21 +-
 .../server/introspection/ArvizIntrospector.h  |  10 +-
 .../introspection/IntrospectorInterface.h     |   2 +-
 .../NavigationGroup/NavigateToLocation.cpp    |   6 +-
 .../trajectory_control/CMakeLists.txt         |  70 +++++--
 .../TrajectoryController.cpp                  |   9 -
 .../global/TrajectoryController.h             |  77 +++++++
 .../TrajectoryFollowingController.cpp         |  16 +-
 .../TrajectoryFollowingController.h           |   6 +-
 .../{ => global}/WaypointController.cpp       |  14 +-
 .../{ => global}/WaypointController.h         |   6 +-
 .../aron/TrajectoryControllerParams.xml       |  19 ++
 .../TrajectoryFollowingControllerParams.xml   |   8 +-
 .../aron/WaypointControllerParams.xml         |   4 +-
 .../{ => global}/aron_conversions.cpp         |  16 +-
 .../{ => global}/aron_conversions.h           |   6 +-
 .../trajectory_control/{ => global}/core.h    |   6 +-
 .../{ => local}/TrajectoryController.h        |   8 +-
 .../local/TrajectoryFollowingController.cpp   | 197 ++++++++++++++++++
 .../local/TrajectoryFollowingController.h     |  71 +++++++
 .../aron/TrajectoryControllerParams.xml       |   4 +-
 .../TrajectoryFollowingControllerParams.xml   |  31 +++
 .../local/aron_conversions.cpp                |  35 ++++
 .../local/aron_conversions.h                  |  45 ++++
 .../trajectory_control/local/core.h           |  36 ++++
 58 files changed, 1105 insertions(+), 259 deletions(-)
 create mode 100644 source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
 create mode 100644 source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h
 delete mode 100644 source/armarx/navigation/trajectory_control/TrajectoryController.cpp
 create mode 100644 source/armarx/navigation/trajectory_control/global/TrajectoryController.h
 rename source/armarx/navigation/trajectory_control/{ => global}/TrajectoryFollowingController.cpp (93%)
 rename source/armarx/navigation/trajectory_control/{ => global}/TrajectoryFollowingController.h (90%)
 rename source/armarx/navigation/trajectory_control/{ => global}/WaypointController.cpp (66%)
 rename source/armarx/navigation/trajectory_control/{ => global}/WaypointController.h (90%)
 create mode 100644 source/armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.xml
 rename source/armarx/navigation/trajectory_control/{ => global}/aron/TrajectoryFollowingControllerParams.xml (77%)
 rename source/armarx/navigation/trajectory_control/{ => global}/aron/WaypointControllerParams.xml (81%)
 rename source/armarx/navigation/trajectory_control/{ => global}/aron_conversions.cpp (74%)
 rename source/armarx/navigation/trajectory_control/{ => global}/aron_conversions.h (93%)
 rename source/armarx/navigation/trajectory_control/{ => global}/core.h (89%)
 rename source/armarx/navigation/trajectory_control/{ => local}/TrajectoryController.h (89%)
 create mode 100644 source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
 create mode 100644 source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h
 rename source/armarx/navigation/trajectory_control/{ => local}/aron/TrajectoryControllerParams.xml (72%)
 create mode 100644 source/armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.xml
 create mode 100644 source/armarx/navigation/trajectory_control/local/aron_conversions.cpp
 create mode 100644 source/armarx/navigation/trajectory_control/local/aron_conversions.h
 create mode 100644 source/armarx/navigation/trajectory_control/local/core.h

diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index 29001741..afbf7503 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -40,7 +40,7 @@
 #include <armarx/navigation/global_planning/Point2Point.h>
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::components::example_client
@@ -108,7 +108,7 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::AStarParams())
-                .trajectoryController(traj_ctrl::TrajectoryFollowingControllerParams()));
+                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));  // FIXME
 
         // Example of registering a lambda as callback.
         getNavigator().onGoalReached([&]() { ARMARX_IMPORTANT << "Goal reached! (lambda-style)"; });
@@ -207,7 +207,7 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::AStarParams())
-                .trajectoryController(traj_ctrl::TrajectoryFollowingControllerParams()));
+                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));  // FIXME
 
         // Example of registering a lambda as callback.
         getNavigator().onGoalReached([&]() { ARMARX_IMPORTANT << "Goal reached! (lambda-style)"; });
@@ -283,7 +283,7 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::Point2PointParams())
-                .trajectoryController(traj_ctrl::TrajectoryFollowingControllerParams()));
+                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
         Clock::WaitFor(Duration::Seconds(1));
 
diff --git a/source/armarx/navigation/client/NavigationStackConfig.cpp b/source/armarx/navigation/client/NavigationStackConfig.cpp
index 5e23bb7f..314a8e29 100644
--- a/source/armarx/navigation/client/NavigationStackConfig.cpp
+++ b/source/armarx/navigation/client/NavigationStackConfig.cpp
@@ -88,12 +88,12 @@ namespace armarx::navigation::client
     }
 
     NavigationStackConfig&
-    NavigationStackConfig::trajectoryController(const traj_ctrl::TrajectoryControllerParams& params)
+    NavigationStackConfig::trajectoryController(const traj_ctrl::local::TrajectoryControllerParams& params)
     {
         aron::data::DictPtr element(new aron::data::Dict);
         element->addElement(core::NAME_KEY,
                             std::make_shared<aron::data::String>(
-                                traj_ctrl::AlgorithmNames.to_name(params.algorithm())));
+                                traj_ctrl::local::AlgorithmNames.to_name(params.algorithm())));
         element->addElement(core::PARAMS_KEY, params.toAron());
 
         dict.addElement(core::StackLayerNames.to_name(core::StackLayer::TrajectoryController),
diff --git a/source/armarx/navigation/client/NavigationStackConfig.h b/source/armarx/navigation/client/NavigationStackConfig.h
index 2e3d6901..e37dfa4a 100644
--- a/source/armarx/navigation/client/NavigationStackConfig.h
+++ b/source/armarx/navigation/client/NavigationStackConfig.h
@@ -33,7 +33,8 @@
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/safety_control/SafetyController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 
 namespace armarx::navigation::client
@@ -64,7 +65,7 @@ namespace armarx::navigation::client
         NavigationStackConfig& localPlanner(const loc_plan::LocalPlannerParams& params);
 
         NavigationStackConfig&
-        trajectoryController(const traj_ctrl::TrajectoryControllerParams& params);
+        trajectoryController(const traj_ctrl::local::TrajectoryControllerParams& params);
 
         NavigationStackConfig& safetyController(const safe_ctrl::SafetyControllerParams& params);
 
diff --git a/source/armarx/navigation/client/services/EventSubscriptionInterface.h b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
index 91fe8722..82bd26cf 100644
--- a/source/armarx/navigation/client/services/EventSubscriptionInterface.h
+++ b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
@@ -1,14 +1,11 @@
 #pragma once
 
-
-// STD/STL
 #include <functional>
 
-// Navigation
 #include <armarx/navigation/core/events.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 
 namespace armarx::navigation::client
@@ -18,7 +15,7 @@ namespace armarx::navigation::client
         std::function<void(const global_planning::GlobalPlannerResult&)>;
     using LocalTrajectoryUpdatedCallback = std::function<void(const loc_plan::LocalPlannerResult&)>;
     using TrajectoryControllerUpdatedCallback =
-        std::function<void(const traj_ctrl::TrajectoryControllerResult&)>;
+        std::function<void(const traj_ctrl::local::TrajectoryControllerResult&)>;
     using GlobalPlanningFailedCallback =
         std::function<void(const core::GlobalPlanningFailedEvent&)>;
 
@@ -54,7 +51,6 @@ namespace armarx::navigation::client
         virtual void onGlobalPlanningFailed(const GlobalPlanningFailedCallback& callback) = 0;
 
         // Non-API.
-    public:
         virtual ~EventSubscriptionInterface() = default;
     };
 
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.cpp b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
index cda19d47..0c2b8055 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.cpp
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
@@ -55,7 +55,8 @@ armarx::navigation::client::SimpleEventHandler::SimpleEventHandler::onMovementSt
 }
 
 void
-armarx::navigation::client::SimpleEventHandler::onGlobalPlanningFailed(const GlobalPlanningFailedCallback& callback)
+armarx::navigation::client::SimpleEventHandler::onGlobalPlanningFailed(
+    const GlobalPlanningFailedCallback& callback)
 {
     subscriptions.globalPlanningFailedCallbacks.push_back(callback);
 }
@@ -143,15 +144,15 @@ namespace armarx::navigation::client
         }
     }
 
-    void
-    SimpleEventHandler::trajectoryControllerUpdated(
-        const traj_ctrl::TrajectoryControllerResult& event)
-    {
-        for (const auto& callback : subscriptions.trajectoryControllerUpdatedCallbacks)
-        {
-            callback(event);
-        }
-    }
+    // void
+    // SimpleEventHandler::trajectoryControllerUpdated(
+    //     const traj_ctrl::local::TrajectoryControllerResult& event)
+    // {
+    //     for (const auto& callback : subscriptions.trajectoryControllerUpdatedCallbacks)
+    //     {
+    //         callback(event);
+    //     }
+    // }
 
     void
     SimpleEventHandler::globalPlanningFailed(const core::GlobalPlanningFailedEvent& event)
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.h b/source/armarx/navigation/client/services/SimpleEventHandler.h
index 3f5fea9a..faa56a89 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.h
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.h
@@ -14,8 +14,9 @@ namespace armarx::navigation::client
         virtual public server::EventPublishingInterface
     {
 
-        // EventSubscriptionInterface
     public:
+
+        // EventSubscriptionInterface
         void onGoalReached(const OnGoalReachedCallback& callback) override;
         void onWaypointReached(const OnWaypointReachedCallback& callback) override;
         void
@@ -28,11 +29,9 @@ namespace armarx::navigation::client
         void onGlobalPlanningFailed(const GlobalPlanningFailedCallback& callback) override;
 
         // EventPublishingInterface
-    public:
         void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& event) override;
         void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& event) override;
-        void
-        trajectoryControllerUpdated(const traj_ctrl::TrajectoryControllerResult& event) override;
+        // void trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& event) override;
         void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) override;
 
         void movementStarted(const core::MovementStartedEvent& event) override;
diff --git a/source/armarx/navigation/components/Navigator/RemoteGui.cpp b/source/armarx/navigation/components/Navigator/RemoteGui.cpp
index 9ab923ba..83e93879 100644
--- a/source/armarx/navigation/components/Navigator/RemoteGui.cpp
+++ b/source/armarx/navigation/components/Navigator/RemoteGui.cpp
@@ -23,7 +23,7 @@
 #include <armarx/navigation/global_planning/AStar.h>
 #include <armarx/navigation/global_planning/Point2Point.h>
 #include <armarx/navigation/server/Navigator.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 #include <armarx/navigation/util/util.h>
 
 namespace armarx::navigation::components
@@ -254,7 +254,7 @@ namespace armarx::navigation::components
 
             client::NavigationStackConfig cfg;
             cfg.globalPlanner(global_planning::SPFAParams());
-            cfg.trajectoryController(traj_ctrl::TrajectoryFollowingControllerParams());
+            cfg.trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams());
 
             const auto stackConfig = cfg.toAron();
 
diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h
index 245f5dc9..747c1cc3 100644
--- a/source/armarx/navigation/core/Trajectory.h
+++ b/source/armarx/navigation/core/Trajectory.h
@@ -124,8 +124,8 @@ namespace armarx::navigation::core
 
     struct LocalTrajectoryPoint
     {
-        core::Pose pose;
         DateTime timestamp;
+        core::Pose pose;
     };
 
     using LocalTrajectory = std::vector<LocalTrajectoryPoint>;
diff --git a/source/armarx/navigation/factories/TrajectoryControllerFactory.cpp b/source/armarx/navigation/factories/TrajectoryControllerFactory.cpp
index 3b8f6a39..0e628b27 100644
--- a/source/armarx/navigation/factories/TrajectoryControllerFactory.cpp
+++ b/source/armarx/navigation/factories/TrajectoryControllerFactory.cpp
@@ -5,17 +5,16 @@
 #include <RobotAPI/libraries/aron/core/data/variant/primitive/String.h>
 
 #include <armarx/navigation/core/constants.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
-#include <armarx/navigation/trajectory_control/WaypointController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 namespace armarx::navigation::fac
 {
-    traj_ctrl::TrajectoryControllerPtr
+    traj_ctrl::local::TrajectoryControllerPtr
     TrajectoryControllerFactory::create(const VirtualRobot::RobotPtr& robot,
                                         const aron::data::DictPtr& params)
     {
-        namespace layer = traj_ctrl;
+        namespace layer = traj_ctrl::local;
 
         if (not params)
         {
@@ -31,16 +30,12 @@ namespace armarx::navigation::fac
         const auto algoParams = aron::data::Dict::DynamicCast(params->getElement(core::PARAMS_KEY));
         ARMARX_CHECK_NOT_NULL(algoParams);
 
-        traj_ctrl::TrajectoryControllerPtr controller;
+        traj_ctrl::local::TrajectoryControllerPtr controller;
         switch (algo)
         {
-            case traj_ctrl::Algorithms::WaypointController:
-                controller = std::make_shared<traj_ctrl::WaypointController>(
-                    traj_ctrl::WaypointControllerParams::FromAron(algoParams));
-                break;
-            case traj_ctrl::Algorithms::TrajectoryFollowingController:
-                controller = std::make_shared<traj_ctrl::TrajectoryFollowingController>(
-                    robot, traj_ctrl::TrajectoryFollowingControllerParams::FromAron(algoParams));
+            case traj_ctrl::local::Algorithms::TrajectoryFollowingController:
+                controller = std::make_shared<traj_ctrl::local::TrajectoryFollowingController>(
+                    robot, traj_ctrl::local::TrajectoryFollowingControllerParams::FromAron(algoParams));
                 break;
         }
 
diff --git a/source/armarx/navigation/factories/TrajectoryControllerFactory.h b/source/armarx/navigation/factories/TrajectoryControllerFactory.h
index cd35d860..e2528c95 100644
--- a/source/armarx/navigation/factories/TrajectoryControllerFactory.h
+++ b/source/armarx/navigation/factories/TrajectoryControllerFactory.h
@@ -22,27 +22,26 @@
 
 #pragma once
 
-// #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 #include <VirtualRobot/VirtualRobot.h>
+
 #include <RobotAPI/libraries/aron/core/data/variant/forward_declarations.h>
 
 #include <armarx/navigation/core/fwd.h>
 #include <armarx/navigation/factories/fwd.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 namespace armarx::navigation::fac
 {
 
     /**
-        * @brief Factory to create a traj_ctrl::TrajectoryController
-        *
-        */
+    * @brief Factory to create a traj_ctrl::TrajectoryController
+    *
+    */
     class TrajectoryControllerFactory
     {
     public:
-        static traj_ctrl::TrajectoryControllerPtr create(const VirtualRobot::RobotPtr& robot,
-                                                         const aron::data::DictPtr& params);
+        static traj_ctrl::local::TrajectoryControllerPtr create(const VirtualRobot::RobotPtr& robot,
+                                                                const aron::data::DictPtr& params);
 
-    protected:
-    private:
     };
 } // namespace armarx::navigation::fac
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h
index 46aa7ede..6ae1c69c 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.h
+++ b/source/armarx/navigation/local_planning/LocalPlanner.h
@@ -28,7 +28,7 @@
 
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
-#include "core.h"
+#include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/core/DynamicScene.h>
 #include <armarx/navigation/core/StaticScene.h>
 #include <armarx/navigation/core/Trajectory.h>
@@ -38,7 +38,7 @@ namespace armarx::navigation::loc_plan
 {
     struct LocalPlannerResult
     {
-        core::GlobalTrajectory trajectory;
+        core::LocalTrajectory trajectory;
     };
 
     struct LocalPlannerParams
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.cpp b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
index e693495e..4a3a3a75 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.cpp
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
@@ -4,6 +4,7 @@
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/core/aron/Trajectory.aron.generated.h>
 #include <armarx/navigation/core/aron/Twist.aron.generated.h>
 #include <armarx/navigation/core/aron_conversions.h>
@@ -17,8 +18,8 @@ namespace armarx::navigation::memory::client::stack_result
         armem::Commit commit;
 
         storePrepare(result.globalPlan, clientID, commit);
-        // FIXME storePrepare(result.localTrajectory, clientID, commit);
-        storePrepare(result.controlVelocity, clientID, commit);
+        storePrepare(result.localTrajectory, clientID, commit);
+        // storePrepare(result.controlVelocity, clientID, commit);
         // FIXME storePrepare(result.safeVelocity, clientID, commit);
 
         std::lock_guard g{memoryWriterMutex()};
@@ -45,7 +46,7 @@ namespace armarx::navigation::memory::client::stack_result
     }
 
     bool
-    Writer::store(const armarx::navigation::traj_ctrl::TrajectoryControllerResult& result,
+    Writer::store(const armarx::navigation::loc_plan::LocalPlannerResult& result,
                   const std::string& clientID)
     {
         armem::Commit commit;
@@ -55,6 +56,7 @@ namespace armarx::navigation::memory::client::stack_result
         return updateResult.allSuccess();
     }
 
+
     bool
     Writer::storePrepare(const armarx::navigation::global_planning::GlobalPlannerResult& result,
                          const std::string& clientID,
@@ -84,8 +86,9 @@ namespace armarx::navigation::memory::client::stack_result
         return true;
     }
 
+
     bool
-    Writer::storePrepare(const armarx::navigation::traj_ctrl::TrajectoryControllerResult& result,
+    Writer::storePrepare(const loc_plan::LocalPlannerResult& result,
                          const std::string& clientID,
                          armem::Commit& commit)
     {
@@ -95,15 +98,15 @@ namespace armarx::navigation::memory::client::stack_result
         armem::EntityUpdate update;
         update.entityID = armem::MemoryID()
                               .withMemoryName(properties().memoryName)
-                              .withCoreSegmentName("Results_TrajectoryController")
+                              .withCoreSegmentName("Results_LocalPlanner")
                               .withProviderSegmentName(clientID)
-                              .withEntityName("velocity")
+                              .withEntityName("trajectory")
                               .withTimestamp(timestamp);
 
 
-        core::arondto::Twist aronDto;
-        // FIXME own type
-        core::toAron(aronDto, result.twist);
+        core::arondto::LocalTrajectory aronDto;
+        // FIXME create Aron type
+        toAron(aronDto, result.trajectory);
 
         update.timeCreated = timestamp;
         update.instancesData = {aronDto.toAron()};
@@ -113,6 +116,7 @@ namespace armarx::navigation::memory::client::stack_result
         return true;
     }
 
+
     std::string
     Writer::propertyPrefix() const
     {
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.h b/source/armarx/navigation/memory/client/stack_result/Writer.h
index 1ece5594..2e29333f 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.h
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.h
@@ -24,9 +24,10 @@
 #include <RobotAPI/libraries/armem/client/util/SimpleWriterBase.h>
 #include <RobotAPI/libraries/armem/core/Commit.h>
 
+#include "armarx/navigation/local_planning/LocalPlanner.h"
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/server/StackResult.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 namespace armarx::navigation::memory::client::stack_result
 {
@@ -40,7 +41,8 @@ namespace armarx::navigation::memory::client::stack_result
 
         bool store(const armarx::navigation::global_planning::GlobalPlannerResult& result,
                    const std::string& clientID);
-        bool store(const armarx::navigation::traj_ctrl::TrajectoryControllerResult& result,
+
+        bool store(const armarx::navigation::loc_plan::LocalPlannerResult& result,
                    const std::string& clientID);
 
 
@@ -49,18 +51,10 @@ namespace armarx::navigation::memory::client::stack_result
                           const std::string& clientID,
                           armem::Commit& commit);
 
-        // bool storePrepare(const server::StackResult::LocalPlannerResult& result,
-        //                   const std::string& clientID,
-        //                   armem::Commit& commit);
-
-        bool storePrepare(const armarx::navigation::traj_ctrl::TrajectoryControllerResult& result,
+        bool storePrepare(const loc_plan::LocalPlannerResult& result,
                           const std::string& clientID,
                           armem::Commit& commit);
 
-        // bool storePrepare(const server::StackResult::SafetyControllerResult& result,
-        //                   const std::string& clientID,
-        //                   armem::Commit& commit);
-
     protected:
         std::string propertyPrefix() const override;
         Properties defaultProperties() const override;
diff --git a/source/armarx/navigation/platform_controller/CMakeLists.txt b/source/armarx/navigation/platform_controller/CMakeLists.txt
index a5a21b12..dd919b00 100644
--- a/source/armarx/navigation/platform_controller/CMakeLists.txt
+++ b/source/armarx/navigation/platform_controller/CMakeLists.txt
@@ -8,11 +8,11 @@ armarx_add_aron_library(platform_controller_aron
 
 armarx_add_library(platform_controller
   SOURCES
-    # PlatformLocalTrajectoryController.cpp
+    PlatformLocalTrajectoryController.cpp
     PlatformGlobalTrajectoryController.cpp
     aron_conversions.cpp
   HEADERS
-    # PlatformLocalTrajectoryController.h
+    PlatformLocalTrajectoryController.h
     PlatformGlobalTrajectoryController.h
     aron_conversions.h
   DEPENDENCIES_PUBLIC
diff --git a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
index a8758b6c..3e46aa55 100644
--- a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
@@ -105,7 +105,7 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
         }
 
         // update controller
-        const armarx::navigation::traj_ctrl::TrajectoryControllerResult result =
+        const armarx::navigation::traj_ctrl::global::TrajectoryControllerResult result =
             trajectoryFollowingController->control(
                 configBuffer.getUpToDateReadBuffer().targets.trajectory);
 
@@ -118,8 +118,8 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
     }
 
     void
-    Controller::onPublish(const SensorAndControl& sac,
-                          const DebugDrawerInterfacePrx& debugDrawer,
+    Controller::onPublish(const SensorAndControl& /*sac*/,
+                          const DebugDrawerInterfacePrx& /*debugDrawer*/,
                           const DebugObserverInterfacePrx& debugObservers)
     {
         StringVariantBaseMap datafields;
@@ -127,7 +127,8 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
         datafields["vx"] = new Variant(rtGetControlStruct().platformVelocityTargets.x);
         datafields["vy"] = new Variant(rtGetControlStruct().platformVelocityTargets.y);
         datafields["vyaw"] = new Variant(rtGetControlStruct().platformVelocityTargets.yaw);
-        datafields["trajectory_points"] = new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.points().size());
+        datafields["trajectory_points"] =
+            new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.points().size());
 
         debugObservers->setDebugChannel(
             common::ControllerTypeNames.to_name(common::ControllerType::PlatformGlobalTrajectory),
@@ -166,4 +167,4 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
 
     Controller::~Controller() = default;
 
-} // namespace armarx::navigation::platform_controller::platform_trajectory
+} // namespace armarx::navigation::platform_controller::platform_global_trajectory
diff --git a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
index 65d7d79a..e9fee601 100644
--- a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
@@ -29,9 +29,10 @@
 #include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
 #include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValueHolonomicPlatform.h>
 
+#include "armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h"
 #include <armarx/control/interface/ConfigurableNJointControllerInterface.h>
 #include <armarx/navigation/core/types.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 namespace armarx
 {
@@ -49,7 +50,7 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
 
     struct Config
     {
-        using Params = traj_ctrl::TrajectoryFollowingControllerParams;
+        using Params = traj_ctrl::global::TrajectoryFollowingControllerParams;
 
         Params params;
         Targets targets;
@@ -120,7 +121,7 @@ namespace armarx::navigation::platform_controller::platform_global_trajectory
 
         ControlTargetHolonomicPlatformVelocity* platformTarget;
 
-        std::optional<traj_ctrl::TrajectoryFollowingController> trajectoryFollowingController;
+        std::optional<traj_ctrl::global::TrajectoryFollowingController> trajectoryFollowingController;
 
 
         Devices getDevices(const VirtualRobot::RobotNodeSet& rns);
diff --git a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
new file mode 100644
index 00000000..eff20f7b
--- /dev/null
+++ b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
@@ -0,0 +1,168 @@
+#include "PlatformLocalTrajectoryController.h"
+
+#include "ArmarXCore/core/ArmarXObjectScheduler.h"
+#include "ArmarXCore/core/logging/Logging.h"
+#include "ArmarXCore/core/time/CycleUtil.h"
+
+#include "RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h"
+#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTargetHolonomicPlatformVelocity.h>
+
+#include <armarx/control/common/aron_conversions.h>
+#include <armarx/control/common/type.h>
+#include <armarx/navigation/common/controller_types.h>
+#include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/aron_conversions.h>
+
+namespace armarx::navigation::platform_controller::platform_local_trajectory
+{
+    const NJointControllerRegistration<Controller> Registration(
+        common::ControllerTypeNames.to_name(common::ControllerType::PlatformLocalTrajectory));
+
+    Controller::Controller(const RobotUnitPtr& robotUnit,
+                           const NJointControllerConfigPtr& config,
+                           const VirtualRobot::RobotPtr&)
+    {
+        ARMARX_IMPORTANT << "Creating "
+                         << common::ControllerTypeNames.to_name(
+                                common::ControllerType::PlatformLocalTrajectory);
+        // config
+        ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
+        ARMARX_CHECK_EXPRESSION(cfg);
+        ARMARX_CHECK_EXPRESSION(!cfg->nodeSetName.empty());
+
+        ARMARX_CHECK_EXPRESSION(robotUnit);
+
+        const auto robot = useSynchronizedRtRobot();
+
+        platformTarget = useControlTarget(robotUnit->getRobotPlatformName(),
+                                          ControlModes::HolonomicPlatformVelocity)
+                             ->asA<ControlTargetHolonomicPlatformVelocity>();
+        ARMARX_CHECK_EXPRESSION(platformTarget)
+            << "The actuator " << robotUnit->getRobotPlatformName() << " has no control mode "
+            << ControlModes::HolonomicPlatformVelocity;
+
+        const auto configData = ::armarx::fromAron<arondto::Config, Config>(cfg->config);
+        const auto trajectoryFollowingControllerParams = configData.params;
+
+        reinitTripleBuffer({});
+        configBuffer.reinitAllBuffers(configData);
+
+        trajectoryFollowingController.emplace(robot, trajectoryFollowingControllerParams);
+
+        ARMARX_INFO << "Init done.";
+    }
+
+    std::string
+    Controller::getClassName(const Ice::Current& iceCurrent) const
+    {
+        return armarx::navigation::common::ControllerTypeNames.to_name(
+            armarx::navigation::common::ControllerType::PlatformLocalTrajectory);
+    }
+
+    void
+    Controller::rtRun(const IceUtil::Time& sensorValuesTimestamp,
+                      const IceUtil::Time& timeSinceLastIteration)
+    {
+        rtUpdateControlStruct();
+
+        platformTarget->velocityX = rtGetControlStruct().platformVelocityTargets.x;
+        platformTarget->velocityY = rtGetControlStruct().platformVelocityTargets.y;
+        platformTarget->velocityRotation = rtGetControlStruct().platformVelocityTargets.yaw;
+    }
+
+    void
+    Controller::updateConfig(const ::armarx::aron::data::dto::DictPtr& dto,
+                             const Ice::Current& iceCurrent)
+    {
+        ARMARX_IMPORTANT << "Controller::updateConfig";
+
+        // TODO maybe update pid controller
+
+        auto updateConfig = ::armarx::fromAron<arondto::Config, Config>(dto);
+        configBuffer.reinitAllBuffers(updateConfig);
+
+        ARMARX_INFO << "Trajectory with " << updateConfig.targets.trajectory.size();
+
+        ARMARX_IMPORTANT << "done Controller::updateConfig";
+    }
+
+    void
+    Controller::additionalTask()
+    {
+        ARMARX_CHECK(trajectoryFollowingController.has_value());
+
+        // if trajectory is empty, set velocity to 0
+        if (configBuffer.getUpToDateReadBuffer().targets.trajectory.empty())
+        {
+            ARMARX_INFO << deactivateSpam(1) << "Trajectory is empty!";
+
+            getWriterControlStruct().platformVelocityTargets.x = 0;
+            getWriterControlStruct().platformVelocityTargets.y = 0;
+            getWriterControlStruct().platformVelocityTargets.yaw = 0;
+            writeControlStruct();
+            return;
+        }
+
+        // update controller
+        const auto result =
+            trajectoryFollowingController->control(configBuffer.getUpToDateReadBuffer().targets.trajectory);
+
+        // store result
+        getWriterControlStruct().platformVelocityTargets.x = result.twist.linear.x();
+        getWriterControlStruct().platformVelocityTargets.y = result.twist.linear.y();
+        getWriterControlStruct().platformVelocityTargets.yaw = result.twist.angular.z();
+
+        writeControlStruct();
+    }
+
+    void
+    Controller::onPublish(const SensorAndControl& sac,
+                          const DebugDrawerInterfacePrx& debugDrawer,
+                          const DebugObserverInterfacePrx& debugObservers)
+    {
+        StringVariantBaseMap datafields;
+
+        datafields["vx"] = new Variant(rtGetControlStruct().platformVelocityTargets.x);
+        datafields["vy"] = new Variant(rtGetControlStruct().platformVelocityTargets.y);
+        datafields["vyaw"] = new Variant(rtGetControlStruct().platformVelocityTargets.yaw);
+        datafields["trajectory_points"] =
+            new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.size());
+
+        debugObservers->setDebugChannel(
+            common::ControllerTypeNames.to_name(common::ControllerType::PlatformLocalTrajectory),
+            datafields);
+    }
+
+    void
+    Controller::onInitNJointController()
+    {
+        runTask("PlatformTrajectoryControllerAdditionalTask",
+                [&]
+                {
+                    CycleUtil c(10);
+                    getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
+                    ARMARX_IMPORTANT << "Create a new thread alone PlatformTrajectory controller";
+                    while (getState() == eManagedIceObjectStarted)
+                    {
+                        if (isControllerActive() and rtReady.load())
+                        {
+                            ARMARX_VERBOSE << "additional task";
+                            additionalTask();
+                        }
+                        c.waitForCycleDuration();
+                    }
+                });
+
+        ARMARX_INFO << "PlatformTrajectoryVelocityController::onInitNJointController";
+    }
+
+    void
+    Controller::rtPreActivateController()
+    {
+        rtReady.store(true);
+    }
+
+
+    Controller::~Controller() = default;
+
+} // namespace armarx::navigation::platform_controller::platform_local_trajectory
diff --git a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h
new file mode 100644
index 00000000..8aa75fb7
--- /dev/null
+++ b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h
@@ -0,0 +1,129 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+
+#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
+#include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerWithTripleBuffer.h>
+#include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
+#include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValueHolonomicPlatform.h>
+
+#include <armarx/control/interface/ConfigurableNJointControllerInterface.h>
+#include <armarx/navigation/core/types.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
+
+namespace armarx
+{
+    class ControlTargetHolonomicPlatformVelocity;
+    class SensorValueHolonomicPlatformWithAbsolutePosition;
+} // namespace armarx
+
+
+namespace armarx::navigation::platform_controller::platform_local_trajectory
+{
+    struct Targets
+    {
+        core::LocalTrajectory trajectory;
+    };
+
+    struct Config
+    {
+        using Params = traj_ctrl::local::TrajectoryFollowingControllerParams;
+
+        Params params;
+        Targets targets;
+    };
+
+    struct Target
+    {
+        struct
+        {
+            double x = 0;
+            double y = 0;
+            double yaw = 0;
+        } platformVelocityTargets;
+
+        void
+        reset()
+        {
+            platformVelocityTargets.x = 0;
+            platformVelocityTargets.y = 0;
+            platformVelocityTargets.yaw = 0;
+        }
+    };
+
+    struct Devices
+    {
+        ControlTargetHolonomicPlatformVelocity* platformTarget;
+    };
+
+    using NameValueMap = std::map<std::string, float>;
+
+    class Controller :
+        virtual public NJointControllerWithTripleBuffer<Target>,
+        virtual public armarx::control::ConfigurableNJointControllerInterface
+    {
+    public:
+        using ConfigPtrT = control::ConfigurableNJointControllerConfigPtr;
+
+        Controller(const RobotUnitPtr& robotUnit,
+                   const NJointControllerConfigPtr& config,
+                   const VirtualRobot::RobotPtr&);
+
+        ~Controller() override;
+
+        std::string getClassName(const Ice::Current& iceCurrent = Ice::emptyCurrent) const override;
+
+        void rtRun(const IceUtil::Time& sensorValuesTimestamp,
+                   const IceUtil::Time& timeSinceLastIteration) override;
+
+        void updateConfig(const ::armarx::aron::data::dto::DictPtr& dto,
+                          const Ice::Current& iceCurrent = Ice::emptyCurrent) override;
+
+    protected:
+        void additionalTask();
+        void onPublish(const SensorAndControl& sac,
+                       const DebugDrawerInterfacePrx& debugDrawer,
+                       const DebugObserverInterfacePrx& debugObservers) override;
+
+
+        void onInitNJointController() override;
+        void rtPreActivateController() override;
+
+    private:
+        TripleBuffer<Config> configBuffer;
+
+        // internal
+        std::atomic_bool rtFirstRun = true;
+        std::atomic_bool rtReady = false;
+
+        ControlTargetHolonomicPlatformVelocity* platformTarget;
+
+        std::optional<traj_ctrl::local::TrajectoryFollowingController> trajectoryFollowingController;
+
+
+        Devices getDevices(const VirtualRobot::RobotNodeSet& rns);
+    };
+
+}  // namespace armarx::navigation::platform_controller::platform_local_trajectory
diff --git a/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml b/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
index 515b1148..455dfa22 100644
--- a/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
+++ b/source/armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.xml
@@ -1,18 +1,17 @@
 <?xml version="1.0" encoding="UTF-8" ?>
 <AronTypeDefinition>
     <AronIncludes>
-        <Include include="../../core/aron/TwistLimits.xml" />
-        <Include include="../../core/aron/PIDParams.xml" />
-        <Include include="../../core/aron/Trajectory.xml" />
-        <Include include="../../trajectory_control/aron/TrajectoryFollowingControllerParams.xml" />
-        <!-- <Include include="<armarx/control/common/control_law/aron/TaskspaceImpedanceControllerConfig.xml>" /> -->
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
+        <Include include="armarx/navigation/core/aron/PIDParams.xml" />
+        <Include include="armarx/navigation/core/aron/Trajectory.xml" />
+        <Include include="armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.xml" />
     </AronIncludes>
     <CodeIncludes>
         <Include include="<Eigen/Core>" />
         <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/PIDParams.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/Trajectory.aron.generated.h>" />
-        <Include include="<armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>" />
     </CodeIncludes>
     <GenerateTypes>
 
@@ -31,7 +30,7 @@
 
         <Object name='armarx::navigation::platform_controller::platform_global_trajectory::arondto::Config'>
             <ObjectChild key='params'>
-                <armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams />
+                <armarx::navigation::traj_ctrl::global::arondto::TrajectoryFollowingControllerParams />
             </ObjectChild>
 
             <ObjectChild key='targets'>
diff --git a/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml b/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml
index a1479eef..01899f98 100644
--- a/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml
+++ b/source/armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.xml
@@ -1,18 +1,17 @@
 <?xml version="1.0" encoding="UTF-8" ?>
 <AronTypeDefinition>
     <AronIncludes>
-        <Include include="../../core/aron/TwistLimits.xml" />
-        <Include include="../../core/aron/PIDParams.xml" />
-        <Include include="../../core/aron/Trajectory.xml" />
-        <Include include="../../trajectory_control/aron/TrajectoryFollowingControllerParams.xml" />
-        <!-- <Include include="<armarx/control/common/control_law/aron/TaskspaceImpedanceControllerConfig.xml>" /> -->
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
+        <Include include="armarx/navigation/core/aron/PIDParams.xml" />
+        <Include include="armarx/navigation/core/aron/Trajectory.xml" />
+        <Include include="armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.xml" />
     </AronIncludes>
     <CodeIncludes>
         <Include include="<Eigen/Core>" />
         <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/PIDParams.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/Trajectory.aron.generated.h>" />
-        <Include include="<armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.aron.generated.h>" />
     </CodeIncludes>
     <GenerateTypes>
 
@@ -31,7 +30,7 @@
 
         <Object name='armarx::navigation::platform_controller::platform_local_trajectory::arondto::Config'>
             <ObjectChild key='params'>
-                <armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams />
+                <armarx::navigation::traj_ctrl::local::arondto::TrajectoryFollowingControllerParams />
             </ObjectChild>
 
             <ObjectChild key='targets'>
diff --git a/source/armarx/navigation/platform_controller/aron_conversions.cpp b/source/armarx/navigation/platform_controller/aron_conversions.cpp
index 8b502245..f3245428 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.cpp
+++ b/source/armarx/navigation/platform_controller/aron_conversions.cpp
@@ -26,9 +26,11 @@
 #include <armarx/control/common/aron_conversions.h>
 #include <armarx/navigation/core/aron_conversions.h>
 #include <armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h>
+#include <armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h>
 #include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
-#include <armarx/navigation/trajectory_control/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/local/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/global/aron_conversions.h>
 
 
 namespace armarx::navigation::platform_controller
@@ -52,22 +54,22 @@ namespace armarx::navigation::platform_controller
 
     } // namespace platform_global_trajectory
 
-    // namespace platform_local_trajectory
-    // {
+    namespace platform_local_trajectory
+    {
 
-    //     void
-    //     fromAron(const arondto::Targets& dto, Targets& bo)
-    //     {
-    //         fromAron(dto.trajectory, bo.trajectory);
-    //     }
+        void
+        fromAron(const arondto::Targets& dto, Targets& bo)
+        {
+            fromAron(dto.trajectory, bo.trajectory);
+        }
 
-    //     void
-    //     fromAron(const arondto::Config& dto, Config& bo)
-    //     {
-    //         fromAron(dto.params, bo.params);
-    //         fromAron(dto.targets, bo.targets);
-    //     }
+        void
+        fromAron(const arondto::Config& dto, Config& bo)
+        {
+            fromAron(dto.params, bo.params);
+            fromAron(dto.targets, bo.targets);
+        }
 
-    // } // namespace platform_local_trajectory
+    } // namespace platform_local_trajectory
 
 } // namespace armarx::navigation::platform_controller
diff --git a/source/armarx/navigation/platform_controller/aron_conversions.h b/source/armarx/navigation/platform_controller/aron_conversions.h
index 1e338a7c..4e158dc1 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.h
+++ b/source/armarx/navigation/platform_controller/aron_conversions.h
@@ -22,14 +22,32 @@
 #pragma once
 
 
-namespace armarx::navigation::platform_controller::platform_global_trajectory
+namespace armarx::navigation::platform_controller
 {
-    namespace arondto
+    namespace platform_global_trajectory
     {
-        class Config;
-    }
+        namespace arondto
+        {
+            class Config;
+        }
 
-    struct Config;
+        struct Config;
 
-    void fromAron(const arondto::Config& dto, Config& bo);
-} // namespace armarx::navigation::platform_controller::platform_global_trajectory
+        void fromAron(const arondto::Config& dto, Config& bo);
+
+    } // namespace platform_global_trajectory
+
+    namespace platform_local_trajectory
+    {
+        namespace arondto
+        {
+            class Config;
+        }
+
+        struct Config;
+
+        void fromAron(const arondto::Config& dto, Config& bo);
+
+    } // namespace platform_local_trajectory
+
+} // namespace armarx::navigation::platform_controller
diff --git a/source/armarx/navigation/platform_controller/controller_descriptions.h b/source/armarx/navigation/platform_controller/controller_descriptions.h
index cb602115..30ce76d9 100644
--- a/source/armarx/navigation/platform_controller/controller_descriptions.h
+++ b/source/armarx/navigation/platform_controller/controller_descriptions.h
@@ -24,7 +24,7 @@
 #include <armarx/control/client/ControllerDescription.h>
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h>
-// #include <armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h>
+#include <armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h>
 #include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
 
@@ -43,17 +43,17 @@ namespace armarx::control::client
             armarx::navigation::common::PlatformGlobalTrajectoryControllerName;
     };
 
-    // template <>
-    // struct ControllerDescription<armarx::navigation::common::ControllerType::PlatformLocalTrajectory>
-    // {
-    //     using AronDTO =
-    //         armarx::navigation::platform_controller::platform_local_trajectory::arondto::Config;
+    template <>
+    struct ControllerDescription<armarx::navigation::common::ControllerType::PlatformLocalTrajectory>
+    {
+        using AronDTO =
+            armarx::navigation::platform_controller::platform_local_trajectory::arondto::Config;
 
-    //     using BO = armarx::navigation::platform_controller::platform_local_trajectory::Config;
+        using BO = armarx::navigation::platform_controller::platform_local_trajectory::Config;
 
-    //     // constexpr static const char* name = armarx::navigation::common::ControllerTypeNames.to_name(armarx::navigation::common::ControllerType::PlatformTrajectory);
-    //     constexpr static const char* name =
-    //         armarx::navigation::common::PlatformLocalTrajectoryControllerName;
-    // };
+        // constexpr static const char* name = armarx::navigation::common::ControllerTypeNames.to_name(armarx::navigation::common::ControllerType::PlatformTrajectory);
+        constexpr static const char* name =
+            armarx::navigation::common::PlatformLocalTrajectoryControllerName;
+    };
 
 } // namespace armarx::control::client
diff --git a/source/armarx/navigation/server/NavigationStack.h b/source/armarx/navigation/server/NavigationStack.h
index c2a76f9a..2bed9fdf 100644
--- a/source/armarx/navigation/server/NavigationStack.h
+++ b/source/armarx/navigation/server/NavigationStack.h
@@ -25,7 +25,8 @@
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/safety_control/SafetyController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 namespace armarx::navigation::server
 {
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 79744022..4a25256e 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -605,7 +605,7 @@ namespace armarx::navigation::server
         // the following is similar to moveToAbsolute
         // TODO(fabian.reister): remove code duplication
 
-        srv.executor->execute(globalPlan->trajectory);
+        // srv.executor->execute(globalPlan->trajectory);
 
         ARMARX_TRACE;
         srv.publisher->globalTrajectoryUpdated(globalPlan.value());
@@ -700,7 +700,7 @@ namespace armarx::navigation::server
         ARMARX_TRACE;
         srv.publisher->globalTrajectoryUpdated(globalPlan.value());
         srv.introspector->onGlobalPlannerResult(globalPlan.value());
-        srv.executor->execute(globalPlan->trajectory);
+        // srv.executor->execute(globalPlan->trajectory);
 
         ARMARX_INFO << "Global planning completed. Will now start all required threads";
         ARMARX_TRACE;
diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index a0affd5d..f7ef3948 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -47,7 +47,7 @@
 #include <armarx/navigation/server/execution/ExecutorInterface.h>
 #include <armarx/navigation/server/introspection/IntrospectorInterface.h>
 #include <armarx/navigation/server/monitoring/GoalReachedMonitor.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 namespace armarx::navigation::server
 {
diff --git a/source/armarx/navigation/server/StackResult.h b/source/armarx/navigation/server/StackResult.h
index f5299e64..64abee03 100644
--- a/source/armarx/navigation/server/StackResult.h
+++ b/source/armarx/navigation/server/StackResult.h
@@ -24,9 +24,11 @@
 
 #include <optional>
 
+#include "armarx/navigation/local_planning/LocalPlanner.h"
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 
 namespace armarx::navigation::server
@@ -35,13 +37,12 @@ namespace armarx::navigation::server
     struct StackResult
     {
         // TODO make struct, add timestamp
-        using LocalPlannerResult = core::GlobalTrajectoryPtr;
         using SafetyControllerResult = std::optional<core::Twist>;
 
         global_planning::GlobalPlannerResult globalPlan;
-        LocalPlannerResult localTrajectory;
-        traj_ctrl::TrajectoryControllerResult controlVelocity;
-        SafetyControllerResult safeVelocity;
+        loc_plan::LocalPlannerResult localTrajectory;
+        // traj_ctrl::global::TrajectoryControllerResult controlVelocity;
+        // SafetyControllerResult safeVelocity;
 
         // core::TrajectoryPtr trajectory() const;
         // core::Twist velocity() const;
diff --git a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
index 416d8cc6..775d77aa 100644
--- a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
+++ b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
@@ -4,7 +4,7 @@
 #include <armarx/navigation/core/events.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 
 namespace armarx::navigation::server
@@ -20,8 +20,8 @@ namespace armarx::navigation::server
         // TODO(fabian.reister): fwd
         virtual void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& res) = 0;
         virtual void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& res) = 0;
-        virtual void
-        trajectoryControllerUpdated(const traj_ctrl::TrajectoryControllerResult& res) = 0;
+        // virtual void
+        // trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& res) = 0;
 
         virtual void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) = 0;
 
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
index 6226169b..30bc7e6b 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
@@ -57,11 +57,12 @@ namespace armarx::navigation::server
         // resultWriter->store(res, clientId);
     }
 
-    void
-    MemoryPublisher::trajectoryControllerUpdated(const traj_ctrl::TrajectoryControllerResult& res)
-    {
-        resultWriter->store(res, clientId);
-    }
+    // void
+    // MemoryPublisher::trajectoryControllerUpdated(
+    //     const traj_ctrl::local::TrajectoryControllerResult& res)
+    // {
+    //     resultWriter->store(res, clientId);
+    // }
 
     // TODO(fabian.reister): event with message or reason (enum)
     void
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
index 57204aba..61db181e 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
@@ -18,7 +18,8 @@ namespace armarx::navigation::server
 
         void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& res) override;
         void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& res) override;
-        void trajectoryControllerUpdated(const traj_ctrl::TrajectoryControllerResult& res) override;
+        // void trajectoryControllerUpdated(
+        //     const traj_ctrl::local::TrajectoryControllerResult& res) override;
 
         void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) override;
 
@@ -36,7 +37,6 @@ namespace armarx::navigation::server
         void internalError(const core::InternalErrorEvent& event) override;
 
         // Non-API.
-    public:
         ~MemoryPublisher() override = default;
 
     private:
diff --git a/source/armarx/navigation/server/execution/ExecutorInterface.h b/source/armarx/navigation/server/execution/ExecutorInterface.h
index 57e35506..65426bf5 100644
--- a/source/armarx/navigation/server/execution/ExecutorInterface.h
+++ b/source/armarx/navigation/server/execution/ExecutorInterface.h
@@ -1,9 +1,6 @@
 #pragma once
 
-namespace armarx::navigation::core
-{
-    class GlobalTrajectory;
-} // namespace armarx::navigation::core
+#include "armarx/navigation/core/Trajectory.h"
 
 namespace armarx::navigation::server
 {
@@ -17,8 +14,8 @@ namespace armarx::navigation::server
     public:
         virtual ~ExecutorInterface() = default;
 
-        virtual void execute(const core::GlobalTrajectory& trajectory) = 0;
-        
+        virtual void execute(const core::LocalTrajectory& trajectory) = 0;
+
         virtual void start() = 0;
         virtual void stop() = 0;
     };
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index 9d173d95..9ba41405 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -8,10 +8,11 @@
 #include <armarx/control/memory/config/util.h>
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/core/aron_conversions.h>
-#include <armarx/navigation/platform_controller/aron/PlatformTrajectoryControllerConfig.aron.generated.h>
+#include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/aron_conversions.h>
 #include <armarx/navigation/platform_controller/controller_descriptions.h>
 #include <armarx/navigation/platform_controller/json_conversions.h>
+#include <armarx/navigation/trajectory_control/local/aron_conversions.h>
 
 
 namespace armarx::navigation::server
@@ -45,16 +46,16 @@ namespace armarx::navigation::server
         {
             ARMARX_TRACE;
             auto builder = controllerPlugin.createControllerBuilder<
-                armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>();
+                armarx::navigation::common::ControllerType::PlatformLocalTrajectory>();
 
             ARMARX_TRACE;
 
-            const armarx::PackagePath configPath("armarx_navigation", "controller_config/PlatformTrajectory/default.json");
+            const armarx::PackagePath configPath(
+                "armarx_navigation", "controller_config/PlatformTrajectory/default.json");
 
-            auto ctrlWrapper =
-                builder.withNodeSet("PlatformPlanning")
-                    .withConfig(configPath.toSystemPath())
-                    .create();
+            auto ctrlWrapper = builder.withNodeSet("PlatformPlanning")
+                                   .withConfig(configPath.toSystemPath())
+                                   .create();
 
             ARMARX_TRACE;
             ARMARX_CHECK(ctrlWrapper.has_value());
@@ -70,9 +71,9 @@ namespace armarx::navigation::server
 
 
     void
-    PlatformControllerExecutor::execute(const core::GlobalTrajectory& trajectory)
+    PlatformControllerExecutor::execute(const core::LocalTrajectory& trajectory)
     {
-        ARMARX_INFO << "Received trajectory for execution with " << trajectory.points().size()
+        ARMARX_INFO << "Received trajectory for execution with " << trajectory.size()
                     << " points";
 
         toAron(ctrl->config.targets.trajectory, trajectory);
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
index f852ea09..2e5fe975 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
@@ -31,14 +31,14 @@ namespace armarx::navigation::server
         PlatformControllerExecutor(ControllerComponentPlugin& controllerComponentPlugin);
         ~PlatformControllerExecutor() override;
 
-        void execute(const core::GlobalTrajectory& trajectory) override;
+        void execute(const core::LocalTrajectory& trajectory) override;
 
         void start() override;
         void stop() override;
 
     private:
         std::optional<armarx::control::client::ControllerWrapper<
-            armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>>
+            armarx::navigation::common::ControllerType::PlatformLocalTrajectory>>
             ctrl;
 
         ControllerComponentPlugin& controllerPlugin;
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 43f3e5fb..a57ba285 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -7,16 +7,19 @@
 
 #include <Eigen/Geometry>
 
+#include <SimoxUtility/algorithm/apply.hpp>
 #include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/ColorMap.h>
 #include <SimoxUtility/color/cmaps/colormaps.h>
 #include <VirtualRobot/Robot.h>
+
 #include <ArmarXCore/core/logging/Logging.h>
 
 #include <RobotAPI/components/ArViz/Client/Elements.h>
 #include <RobotAPI/components/ArViz/Client/elements/Color.h>
 #include <RobotAPI/components/ArViz/Client/elements/Path.h>
 
+#include "armarx/navigation/core/Trajectory.h"
 #include "range/v3/algorithm/max.hpp"
 #include "range/v3/algorithm/max_element.hpp"
 #include <armarx/navigation/core/basic_types.h>
@@ -128,10 +131,11 @@ namespace armarx::navigation::server
             viz::Path("path").points(trajectory.positions()).color(simox::color::Color::blue()));
 
         const auto cmap = simox::color::cmaps::viridis();
-       
-       const float maxVelocity = ranges::max_element(trajectory.points(), [](const auto& a, const auto& b){
-           return a.velocity < b.velocity;
-       })->velocity;
+
+        const float maxVelocity = ranges::max_element(trajectory.points(),
+                                                      [](const auto& a, const auto& b)
+                                                      { return a.velocity < b.velocity; })
+                                      ->velocity;
 
 
         for (const auto& [idx, tp] : trajectory.points() | ranges::views::enumerate)
@@ -151,11 +155,16 @@ namespace armarx::navigation::server
     }
 
     void
-    ArvizIntrospector::drawLocalTrajectory(const core::GlobalTrajectory& trajectory)
+    ArvizIntrospector::drawLocalTrajectory(const core::LocalTrajectory& trajectory)
     {
         auto layer = arviz.layer("local_planner");
 
-        layer.add(viz::Path("path").points(trajectory.positions()).color(simox::Color::blue()));
+        const std::vector<Eigen::Vector3f> points =
+            simox::alg::apply(trajectory,
+                              [](const core::LocalTrajectoryPoint& pt) -> Eigen::Vector3f
+                              { return pt.pose.translation(); });
+
+        layer.add(viz::Path("path").points(points).color(simox::Color::blue()));
 
         layers.emplace_back(std::move(layer));
     }
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index c9a4719a..f27ea0be 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -34,13 +34,13 @@
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/safety_control/SafetyController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 #include <armarx/navigation/util/Visualization.h>
 
 // forward declaration
 namespace armarx::navigation::core
 {
-    struct GlobalTrajectory;
+    class GlobalTrajectory;
 }
 
 namespace armarx::navigation::server
@@ -57,8 +57,8 @@ namespace armarx::navigation::server
         
         void onGoal(const core::Pose& goal) override;
 
-        void success();
-        void failure();
+        void success() override;
+        void failure() override;
 
         void onGlobalShortestPath(const std::vector<core::Pose>& path) override;
 
@@ -71,7 +71,7 @@ namespace armarx::navigation::server
 
     private:
         void drawGlobalTrajectory(const core::GlobalTrajectory& trajectory);
-        void drawLocalTrajectory(const core::GlobalTrajectory& trajectory);
+        void drawLocalTrajectory(const core::LocalTrajectory& trajectory);
         void drawRawVelocity(const core::Twist& twist);
         void drawSafeVelocity(const core::Twist& twist);
 
diff --git a/source/armarx/navigation/server/introspection/IntrospectorInterface.h b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
index 18eaa36b..f92ed9e8 100644
--- a/source/armarx/navigation/server/introspection/IntrospectorInterface.h
+++ b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
@@ -25,7 +25,7 @@
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/safety_control/SafetyController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
 
 namespace armarx::navigation::server
 {
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
index 3cf8a00a..32448b96 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
@@ -36,8 +36,8 @@
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 //#include <ArmarXCore/core/time/TimeUtil.h>
 //#include <ArmarXCore/observers/variant/DatafieldRef.h>
@@ -67,7 +67,7 @@ namespace armarx::navigation::statecharts::navigation_group
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::AStarParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            armarx::navigation::traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
         client::IceNavigator iceNavigator(getNavigator());
diff --git a/source/armarx/navigation/trajectory_control/CMakeLists.txt b/source/armarx/navigation/trajectory_control/CMakeLists.txt
index 07c8a589..8057dd3a 100644
--- a/source/armarx/navigation/trajectory_control/CMakeLists.txt
+++ b/source/armarx/navigation/trajectory_control/CMakeLists.txt
@@ -1,34 +1,66 @@
-armarx_add_aron_library(trajectory_control_aron
+armarx_add_aron_library(trajectory_control_local_aron
     ARON_FILES
-        aron/TrajectoryControllerParams.xml
-        aron/TrajectoryFollowingControllerParams.xml
-        aron/WaypointControllerParams.xml
+        local/aron/TrajectoryControllerParams.xml
+        local/aron/TrajectoryFollowingControllerParams.xml
 )
 
-armarx_add_library(trajectory_control
+armarx_add_aron_library(trajectory_control_global_aron
+    ARON_FILES
+        global/aron/TrajectoryControllerParams.xml
+        global/aron/TrajectoryFollowingControllerParams.xml
+        global/aron/WaypointControllerParams.xml
+)
+
+
+armarx_add_library(trajectory_control_local
     SOURCES
-        ./TrajectoryController.cpp
-        ./TrajectoryFollowingController.cpp
-        ./WaypointController.cpp
-        ./aron_conversions.cpp
+        local/TrajectoryFollowingController.cpp
+        local/aron_conversions.cpp
     HEADERS
-        ./TrajectoryController.h
-        ./TrajectoryFollowingController.h
-        ./WaypointController.h
-        ./aron_conversions.h
-        ./core.h
+        local/TrajectoryController.h
+        local/TrajectoryFollowingController.h
+        local/aron_conversions.h
+        local/core.h
     DEPENDENCIES
         ArmarXCoreInterfaces
         ArmarXCore
         RobotAPICore
         armarx_navigation::core
-        armarx_navigation::trajectory_control_aron
+        armarx_navigation::trajectory_control_local_aron
+    OBJECT
 )
 
-armarx_add_test(trajectory_control_test
-    TEST_FILES
-        test/trajectory_controlTest.cpp
+armarx_add_library(trajectory_control_global
+    SOURCES
+        global/aron_conversions.cpp
+        global/TrajectoryFollowingController.cpp
+        global/WaypointController.cpp
+    HEADERS
+        global/TrajectoryController.h
+        global/aron_conversions.h
+        global/TrajectoryFollowingController.h
+        global/WaypointController.h
+        global/core.h
     DEPENDENCIES
+        ArmarXCoreInterfaces
         ArmarXCore
-        armarx_navigation::trajectory_control
+        RobotAPICore
+        armarx_navigation::core
+        armarx_navigation::trajectory_control_global_aron
+    OBJECT
+)
+
+armarx_add_library(trajectory_control
+    DEPENDENCIES
+        armarx_navigation::trajectory_control_local
+        armarx_navigation::trajectory_control_global
 )
+
+
+# armarx_add_test(trajectory_control_test
+#     TEST_FILES
+#         test/trajectory_controlTest.cpp
+#     DEPENDENCIES
+#         ArmarXCore
+#         armarx_navigation::trajectory_control
+# )
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryController.cpp b/source/armarx/navigation/trajectory_control/TrajectoryController.cpp
deleted file mode 100644
index be79e84e..00000000
--- a/source/armarx/navigation/trajectory_control/TrajectoryController.cpp
+++ /dev/null
@@ -1,9 +0,0 @@
-#include "TrajectoryController.h"
-
-namespace armarx::navigation::traj_ctrl
-{
-    // TrajectoryController::TrajectoryController(const core::Scene& context) : context(context)
-    // {
-    // }
-
-} // namespace armarx::navigation::traj_ctrl
diff --git a/source/armarx/navigation/trajectory_control/global/TrajectoryController.h b/source/armarx/navigation/trajectory_control/global/TrajectoryController.h
new file mode 100644
index 00000000..ddd84342
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/global/TrajectoryController.h
@@ -0,0 +1,77 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @author     Christian R. G. Dreher ( c dot dreher at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <cmath>
+#include <limits>
+#include <memory>
+
+#include <VirtualRobot/VirtualRobot.h>
+
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+#include <armarx/navigation/core/DynamicScene.h>
+#include <armarx/navigation/core/StaticScene.h>
+#include <armarx/navigation/core/Trajectory.h>
+#include <armarx/navigation/core/types.h>
+#include <armarx/navigation/trajectory_control/global/core.h>
+
+namespace armarx::navigation::traj_ctrl
+{
+    namespace global
+    {
+
+        struct TrajectoryControllerResult
+        {
+            core::Twist twist;
+            core::GlobalTrajectoryPoint dropPoint;
+        };
+
+        struct TrajectoryControllerParams
+        {
+            core::TwistLimits limits{
+                .linear = 500.F,                // [mm/s]
+                .angular = 2.F * M_PIf32 / 10.F // [rad/s]
+            };
+
+            virtual ~TrajectoryControllerParams() = default;
+
+            virtual Algorithms algorithm() const = 0;
+            virtual aron::data::DictPtr toAron() const = 0;
+        };
+
+        class TrajectoryController
+        {
+        public:
+            TrajectoryController() = default;
+            virtual ~TrajectoryController() = default;
+
+            virtual TrajectoryControllerResult control(const core::GlobalTrajectory& goal) = 0;
+        };
+        using TrajectoryControllerPtr = std::shared_ptr<TrajectoryController>;
+
+    } // namespace global
+
+
+
+} // namespace armarx::navigation::traj_ctrl
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
similarity index 93%
rename from source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp
rename to source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
index 15282bf6..8a6db3f4 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
@@ -14,12 +14,12 @@
 #include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>
-#include <armarx/navigation/trajectory_control/aron_conversions.h>
-#include <armarx/navigation/trajectory_control/core.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/global/core.h>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
     // TrajectoryFollowingControllerParams
 
@@ -35,7 +35,7 @@ namespace armarx::navigation::traj_ctrl
         arondto::TrajectoryFollowingControllerParams dto;
 
         TrajectoryFollowingControllerParams bo;
-        armarx::navigation::traj_ctrl::toAron(dto, bo);
+        armarx::navigation::traj_ctrl::global::toAron(dto, bo);
 
         return dto.toAron();
     }
@@ -47,7 +47,7 @@ namespace armarx::navigation::traj_ctrl
         dto.fromAron(dict);
 
         TrajectoryFollowingControllerParams bo;
-        armarx::navigation::traj_ctrl::fromAron(dto, bo);
+        armarx::navigation::traj_ctrl::global::fromAron(dto, bo);
 
         return bo;
     }
@@ -217,4 +217,4 @@ namespace armarx::navigation::traj_ctrl
                                           .dropPoint = projectedPose.projection};
     }
 
-} // namespace armarx::navigation::traj_ctrl
+} // namespace armarx::navigation::traj_ctrl::global
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h
similarity index 90%
rename from source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h
rename to source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h
index cb7dc596..a8d416f6 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryFollowingController.h
+++ b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h
@@ -24,10 +24,10 @@
 
 #include <RobotAPI/libraries/core/MultiDimPIDController.h>
 
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
     // using arondto::TrajectoryFollowingControllerParams;
 
diff --git a/source/armarx/navigation/trajectory_control/WaypointController.cpp b/source/armarx/navigation/trajectory_control/global/WaypointController.cpp
similarity index 66%
rename from source/armarx/navigation/trajectory_control/WaypointController.cpp
rename to source/armarx/navigation/trajectory_control/global/WaypointController.cpp
index a23f6cd4..ae8f0884 100644
--- a/source/armarx/navigation/trajectory_control/WaypointController.cpp
+++ b/source/armarx/navigation/trajectory_control/global/WaypointController.cpp
@@ -1,11 +1,11 @@
 #include "WaypointController.h"
 
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/aron/WaypointControllerParams.aron.generated.h>
-#include <armarx/navigation/trajectory_control/aron_conversions.h>
-#include <armarx/navigation/trajectory_control/core.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/aron/WaypointControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/global/core.h>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
     // WaypointControllerParams
 
@@ -21,7 +21,7 @@ namespace armarx::navigation::traj_ctrl
         arondto::WaypointControllerParams dto;
 
         WaypointControllerParams bo;
-        armarx::navigation::traj_ctrl::toAron(dto, bo);
+        armarx::navigation::traj_ctrl::global::toAron(dto, bo);
 
         return dto.toAron();
     }
@@ -33,7 +33,7 @@ namespace armarx::navigation::traj_ctrl
         dto.fromAron(dict);
 
         WaypointControllerParams bo;
-        armarx::navigation::traj_ctrl::fromAron(dto, bo);
+        armarx::navigation::traj_ctrl::global::fromAron(dto, bo);
 
         return bo;
     }
diff --git a/source/armarx/navigation/trajectory_control/WaypointController.h b/source/armarx/navigation/trajectory_control/global/WaypointController.h
similarity index 90%
rename from source/armarx/navigation/trajectory_control/WaypointController.h
rename to source/armarx/navigation/trajectory_control/global/WaypointController.h
index 78726abe..c87fe9ad 100644
--- a/source/armarx/navigation/trajectory_control/WaypointController.h
+++ b/source/armarx/navigation/trajectory_control/global/WaypointController.h
@@ -22,9 +22,9 @@
 
 #pragma once
 
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
 
     struct WaypointControllerParams : public TrajectoryControllerParams
@@ -50,4 +50,4 @@ namespace armarx::navigation::traj_ctrl
     };
     using WaypointControllerPtr = std::shared_ptr<WaypointController>;
 
-} // namespace armarx::navigation::traj_ctrl
+} // namespace armarx::navigation::traj_ctrl::global
diff --git a/source/armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.xml b/source/armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.xml
new file mode 100644
index 00000000..b8400d15
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.xml
@@ -0,0 +1,19 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <CodeIncludes>
+        <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
+    </CodeIncludes>
+    <AronIncludes>
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
+    </AronIncludes>
+
+    <GenerateTypes>
+
+        <Object name='armarx::navigation::traj_ctrl::global::arondto::TrajectoryControllerParams'>
+            <!-- <ObjectChild key='limits'>
+                <armarx::navigation::core::arondto::TwistLimits />
+            </ObjectChild> -->
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.xml b/source/armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.xml
similarity index 77%
rename from source/armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.xml
rename to source/armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.xml
index 357cfb65..263c5b43 100644
--- a/source/armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.xml
+++ b/source/armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.xml
@@ -1,20 +1,20 @@
 <?xml version="1.0" encoding="UTF-8" ?>
 <AronTypeDefinition>
     <CodeIncludes>
-        <Include include="<armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/PIDParams.aron.generated.h>" />
         <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
     </CodeIncludes>
     <AronIncludes>
         <Include include="TrajectoryControllerParams.xml" />
-        <Include include="../../core/aron/PIDParams.xml" />
-        <Include include="../../core/aron/TwistLimits.xml" />
+        <Include include="armarx/navigation/core/aron/PIDParams.xml" />
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
     </AronIncludes>
 
     <GenerateTypes>
 
         <!-- <Object name='armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams' extends="armarx::navigation::traj_ctrl::arondto::TrajectoryControllerParams"> -->
-        <Object name='armarx::navigation::traj_ctrl::arondto::TrajectoryFollowingControllerParams'>
+        <Object name='armarx::navigation::traj_ctrl::global::arondto::TrajectoryFollowingControllerParams'>
             <ObjectChild key='pidPos'>
                 <armarx::navigation::core::arondto::PIDParams />
             </ObjectChild>
diff --git a/source/armarx/navigation/trajectory_control/aron/WaypointControllerParams.xml b/source/armarx/navigation/trajectory_control/global/aron/WaypointControllerParams.xml
similarity index 81%
rename from source/armarx/navigation/trajectory_control/aron/WaypointControllerParams.xml
rename to source/armarx/navigation/trajectory_control/global/aron/WaypointControllerParams.xml
index 9f1e482d..8fe8b856 100644
--- a/source/armarx/navigation/trajectory_control/aron/WaypointControllerParams.xml
+++ b/source/armarx/navigation/trajectory_control/global/aron/WaypointControllerParams.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0" encoding="UTF-8" ?>
 <AronTypeDefinition>
     <CodeIncludes>
-        <Include include="<armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.aron.generated.h>" />
     </CodeIncludes>
     <AronIncludes>
         <Include include="TrajectoryControllerParams.xml" />
@@ -10,7 +10,7 @@
     <GenerateTypes>
 
         <!-- <Object name='armarx::navigation::traj_ctrl::arondto::WaypointControllerParams' extends="armarx::navigation::traj_ctrl::arondto::TrajectoryControllerParams"> -->
-        <Object name='armarx::navigation::traj_ctrl::arondto::WaypointControllerParams'>
+        <Object name='armarx::navigation::traj_ctrl::global::arondto::WaypointControllerParams'>
             <ObjectChild key='includeStartPose'>
                 <bool />
             </ObjectChild>
diff --git a/source/armarx/navigation/trajectory_control/aron_conversions.cpp b/source/armarx/navigation/trajectory_control/global/aron_conversions.cpp
similarity index 74%
rename from source/armarx/navigation/trajectory_control/aron_conversions.cpp
rename to source/armarx/navigation/trajectory_control/global/aron_conversions.cpp
index 2cc2d0b4..d32a6132 100644
--- a/source/armarx/navigation/trajectory_control/aron_conversions.cpp
+++ b/source/armarx/navigation/trajectory_control/global/aron_conversions.cpp
@@ -5,15 +5,15 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
 
 #include <armarx/navigation/core/aron_conversions.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
-#include <armarx/navigation/trajectory_control/WaypointController.h>
-#include <armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.aron.generated.h>
-#include <armarx/navigation/trajectory_control/aron/TrajectoryFollowingControllerParams.aron.generated.h>
-#include <armarx/navigation/trajectory_control/aron/WaypointControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/global/WaypointController.h>
+#include <armarx/navigation/trajectory_control/global/aron/TrajectoryControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/global/aron/WaypointControllerParams.aron.generated.h>
 
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
 
     void
@@ -67,4 +67,4 @@ namespace armarx::navigation::traj_ctrl
     }
 
 
-} // namespace armarx::navigation::traj_ctrl
+}  // namespace armarx::navigation::traj_ctrl::global
diff --git a/source/armarx/navigation/trajectory_control/aron_conversions.h b/source/armarx/navigation/trajectory_control/global/aron_conversions.h
similarity index 93%
rename from source/armarx/navigation/trajectory_control/aron_conversions.h
rename to source/armarx/navigation/trajectory_control/global/aron_conversions.h
index f8496c98..3f0dbd61 100644
--- a/source/armarx/navigation/trajectory_control/aron_conversions.h
+++ b/source/armarx/navigation/trajectory_control/global/aron_conversions.h
@@ -22,9 +22,8 @@
 
 #pragma once
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
-    struct PIDParams;
 
     struct TrajectoryControllerParams;
     struct TrajectoryFollowingControllerParams;
@@ -32,7 +31,6 @@ namespace armarx::navigation::traj_ctrl
 
     namespace arondto
     {
-        class PIDParams;
 
         class TrajectoryControllerParams;
         class TrajectoryFollowingControllerParams;
@@ -51,4 +49,4 @@ namespace armarx::navigation::traj_ctrl
     void toAron(arondto::WaypointControllerParams& dto, const WaypointControllerParams& bo);
     void fromAron(const arondto::WaypointControllerParams& dto, WaypointControllerParams& bo);
 
-}  // namespace armarx::navigation::traj_ctrl
+} // namespace armarx::navigation::traj_ctrl::global
diff --git a/source/armarx/navigation/trajectory_control/core.h b/source/armarx/navigation/trajectory_control/global/core.h
similarity index 89%
rename from source/armarx/navigation/trajectory_control/core.h
rename to source/armarx/navigation/trajectory_control/global/core.h
index 0cb07330..2c2d4674 100644
--- a/source/armarx/navigation/trajectory_control/core.h
+++ b/source/armarx/navigation/trajectory_control/global/core.h
@@ -24,17 +24,17 @@
 
 #include <SimoxUtility/meta/enum/EnumNames.hpp>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::global
 {
 
     enum class Algorithms
     {
         WaypointController,
-        TrajectoryFollowingController
+        TrajectoryFollowingController,
     };
 
     const inline simox::meta::EnumNames<Algorithms> AlgorithmNames{
         {Algorithms::WaypointController, "WaypointController"},
         {Algorithms::TrajectoryFollowingController, "TrajectoryFollowingController"}};
 
-} // namespace armarx::navigation::traj_ctrl
+} // namespace armarx::navigation::traj_ctrl::global
diff --git a/source/armarx/navigation/trajectory_control/TrajectoryController.h b/source/armarx/navigation/trajectory_control/local/TrajectoryController.h
similarity index 89%
rename from source/armarx/navigation/trajectory_control/TrajectoryController.h
rename to source/armarx/navigation/trajectory_control/local/TrajectoryController.h
index 9ef9dbc2..4a5c3bbe 100644
--- a/source/armarx/navigation/trajectory_control/TrajectoryController.h
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryController.h
@@ -36,13 +36,12 @@
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
 
-namespace armarx::navigation::traj_ctrl
+namespace armarx::navigation::traj_ctrl::local
 {
 
     struct TrajectoryControllerResult
     {
         core::Twist twist;
-        core::GlobalTrajectoryPoint dropPoint;
     };
 
     struct TrajectoryControllerParams
@@ -64,9 +63,8 @@ namespace armarx::navigation::traj_ctrl
         TrajectoryController() = default;
         virtual ~TrajectoryController() = default;
 
-        virtual TrajectoryControllerResult control(const core::GlobalTrajectory& goal) = 0;
-
+        virtual TrajectoryControllerResult control(const core::LocalTrajectory& goal) = 0;
     };
     using TrajectoryControllerPtr = std::shared_ptr<TrajectoryController>;
 
-} // namespace armarx::navigation::traj_ctrl
+} // namespace armarx::navigation::traj_ctrl::local
diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
new file mode 100644
index 00000000..df64d939
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
@@ -0,0 +1,197 @@
+#include "TrajectoryFollowingController.h"
+
+#include <algorithm>
+
+#include <SimoxUtility/math/convert/mat4f_to_pos.h>
+#include <SimoxUtility/math/convert/mat4f_to_rpy.h>
+#include <SimoxUtility/math/convert/mat4f_to_xyyaw.h>
+#include <VirtualRobot/Robot.h>
+
+#include "ArmarXCore/core/time/Clock.h"
+#include "ArmarXCore/core/time/DateTime.h"
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/interface/serialization/Eigen/Eigen_fdi.h>
+
+#include <RobotAPI/libraries/core/MultiDimPIDController.h>
+
+#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/core/Trajectory.h>
+#include <armarx/navigation/core/types.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.aron.generated.h>
+#include <armarx/navigation/trajectory_control/local/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/local/core.h>
+
+namespace armarx::navigation::traj_ctrl::local
+{
+    // TrajectoryFollowingControllerParams
+
+    Algorithms
+    TrajectoryFollowingControllerParams::algorithm() const
+    {
+        return Algorithms::TrajectoryFollowingController;
+    }
+
+    aron::data::DictPtr
+    TrajectoryFollowingControllerParams::toAron() const
+    {
+        arondto::TrajectoryFollowingControllerParams dto;
+
+        TrajectoryFollowingControllerParams bo;
+        armarx::navigation::traj_ctrl::local::toAron(dto, bo);
+
+        return dto.toAron();
+    }
+
+    TrajectoryFollowingControllerParams
+    TrajectoryFollowingControllerParams::FromAron(const aron::data::DictPtr& dict)
+    {
+        arondto::TrajectoryFollowingControllerParams dto;
+        dto.fromAron(dict);
+
+        TrajectoryFollowingControllerParams bo;
+        armarx::navigation::traj_ctrl::local::fromAron(dto, bo);
+
+        return bo;
+    }
+
+    // TrajectoryFollowingController
+
+    TrajectoryFollowingController::TrajectoryFollowingController(
+        const VirtualRobot::RobotPtr& robot,
+        const Params& params) :
+        robot(robot),
+        params(params),
+        pidPos(params.pidPos.Kp,
+               params.pidPos.Ki,
+               params.pidPos.Kd,
+               std::numeric_limits<double>::max(),
+               std::numeric_limits<double>::max(),
+               false,
+               std::vector<bool>{false, false, false}),
+        pidPosTarget(params.pidPos.Kp / 2,
+                     params.pidPos.Ki,
+                     params.pidPos.Kd,
+                     std::numeric_limits<double>::max(),
+                     std::numeric_limits<double>::max(),
+                     false,
+                     std::vector<bool>{false, false, false}),
+        pidOri(params.pidOri.Kp,
+               params.pidOri.Ki,
+               params.pidOri.Kd,
+               std::numeric_limits<double>::max(),
+               std::numeric_limits<double>::max(),
+               false,
+               std::vector<bool>{true, true, true}),
+        pidOriTarget(params.pidOri.Kp,
+                     params.pidOri.Ki,
+                     params.pidOri.Kd,
+                     std::numeric_limits<double>::max(),
+                     std::numeric_limits<double>::max(),
+                     false,
+                     std::vector<bool>{true, true, true})
+    {
+        ARMARX_IMPORTANT << "Trajectory following controller params: "
+                         << VAROUT(params.limits.linear) << ", " << VAROUT(params.limits.angular);
+    }
+
+    core::Twist
+    TrajectoryFollowingController::applyTwistLimits(core::Twist twist)
+    {
+        const core::Twist limits{.linear = Eigen::Vector3f::Ones() * params.limits.linear,
+                                 .angular = Eigen::Vector3f::Ones() * params.limits.angular};
+
+        // for all entries, scale should be less than 1
+        const auto scalePos = twist.linear.cwiseAbs().cwiseQuotient(limits.linear.cwiseAbs());
+        const auto scaleOri = twist.angular.cwiseAbs().cwiseQuotient(limits.angular.cwiseAbs());
+
+        const float scaleMax = std::max(scalePos.maxCoeff(), scaleOri.maxCoeff());
+
+        if (scaleMax < 1.0F) // both linear and angular velocity in bounds?
+        {
+            return twist;
+        }
+
+        // scale such that no limit is violated
+        twist.linear /= scaleMax;
+        twist.angular /= scaleMax;
+
+        constexpr float eps = 0.001;
+
+        // pedantic checks
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.x()), params.limits.linear + eps);
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.y()), params.limits.linear + eps);
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.z()), params.limits.linear + eps);
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.x()), params.limits.angular + eps);
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.y()), params.limits.angular + eps);
+        ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.z()), params.limits.angular + eps);
+
+        return twist;
+    }
+
+    core::Pose
+    evaluateTrajectoryAt(const core::LocalTrajectory& trajectory, const DateTime& timestamp)
+    {
+        const auto cmp = [](const core::LocalTrajectoryPoint& lhs,
+                            const DateTime& timestamp) -> bool
+        { return lhs.timestamp < timestamp; };
+
+        const auto lower = std::lower_bound(trajectory.begin(), trajectory.end(), timestamp, cmp);
+        // const auto upper = std::upper_bound(trajectory.begin(), trajectory.end(), timestamp, cmp);
+
+        const std::size_t pos = std::distance(trajectory.begin(), lower);
+
+        if (pos == 0)
+        {
+            return trajectory.front().pose;
+        }
+
+        return trajectory.at(pos - 1).pose;
+    }
+
+    TrajectoryControllerResult
+    TrajectoryFollowingController::control(const core::LocalTrajectory& trajectory)
+    {
+        ARMARX_CHECK_NOT_NULL(robot) << "Robot not available";
+
+        if (trajectory.empty())
+        {
+            ARMARX_INFO << "Trajectory is empty.";
+            return TrajectoryControllerResult{.twist = core::Twist::Zero()};
+        }
+
+        const core::Pose currentPose(robot->getGlobalPose());
+
+        // TOOD maybe set via arg?
+        const DateTime timestamp = Clock::Now();
+
+        const core::Pose targetPose = evaluateTrajectoryAt(trajectory, timestamp);
+
+        using simox::math::mat4f_to_pos;
+        using simox::math::mat4f_to_rpy;
+
+        pidPos.update(mat4f_to_pos(currentPose.matrix()), mat4f_to_pos(targetPose.matrix()));
+        pidOri.update(mat4f_to_rpy(currentPose.matrix()), mat4f_to_rpy(targetPose.matrix()));
+
+        const core::Twist twist{.linear = pidPos.getControlValue(),
+                                .angular = pidOri.getControlValue()};
+
+        const auto twistLimited = applyTwistLimits(twist);
+        ARMARX_VERBOSE << deactivateSpam(1) << "Twist limited " << twistLimited.linear.transpose();
+        ARMARX_VERBOSE << deactivateSpam(1) << "Twist angular " << twistLimited.angular.transpose();
+
+        // convert to the robot's base frame
+        const core::Pose global_T_robot(robot->getGlobalPose());
+
+        const auto& twistGlobal = twistLimited;
+
+        core::Twist twistLocal;
+        twistLocal.linear = global_T_robot.linear().inverse() * twistGlobal.linear;
+        // TODO if not in 2D, then this must be changed!
+        twistLocal.angular = twistGlobal.angular;
+
+        return TrajectoryControllerResult{.twist = twistLocal};
+    }
+
+} // namespace armarx::navigation::traj_ctrl::local
diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h
new file mode 100644
index 00000000..6484ebfe
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h
@@ -0,0 +1,71 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @author     Christian R. G. Dreher ( c dot dreher at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <RobotAPI/libraries/core/MultiDimPIDController.h>
+
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.aron.generated.h>
+
+namespace armarx::navigation::traj_ctrl::local
+{
+    // using arondto::LocalTrajectoryFollowingControllerParams;
+
+    struct TrajectoryFollowingControllerParams : public TrajectoryControllerParams
+    {
+
+        core::PIDParams pidPos;
+        core::PIDParams pidOri;
+
+        Algorithms algorithm() const override;
+        aron::data::DictPtr toAron() const override;
+
+        static TrajectoryFollowingControllerParams FromAron(const aron::data::DictPtr& dict);
+    };
+
+    class TrajectoryFollowingController : virtual public TrajectoryController
+    {
+    public:
+        using Params = TrajectoryFollowingControllerParams;
+
+        TrajectoryFollowingController(const VirtualRobot::RobotPtr& robot, const Params& params);
+        ~TrajectoryFollowingController() override = default;
+
+        TrajectoryControllerResult control(const core::LocalTrajectory& trajectory) override;
+
+        //    protected:
+        core::Twist applyTwistLimits(core::Twist twist);
+
+    private:
+        const VirtualRobot::RobotPtr robot;
+        const Params params;
+
+
+        MultiDimPIDControllerTemplate<3> pidPos;
+        MultiDimPIDControllerTemplate<3> pidPosTarget;
+        MultiDimPIDControllerTemplate<3> pidOri;
+        MultiDimPIDControllerTemplate<3> pidOriTarget;
+    };
+    using LocalTrajectoryFollowingControllerPtr = std::shared_ptr<TrajectoryFollowingController>;
+
+}  // namespace armarx::navigation::traj_ctrl::local
diff --git a/source/armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.xml b/source/armarx/navigation/trajectory_control/local/aron/TrajectoryControllerParams.xml
similarity index 72%
rename from source/armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.xml
rename to source/armarx/navigation/trajectory_control/local/aron/TrajectoryControllerParams.xml
index b40e68ba..85f4487f 100644
--- a/source/armarx/navigation/trajectory_control/aron/TrajectoryControllerParams.xml
+++ b/source/armarx/navigation/trajectory_control/local/aron/TrajectoryControllerParams.xml
@@ -4,12 +4,12 @@
         <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
     </CodeIncludes>
     <AronIncludes>
-        <Include include="../../core/aron/TwistLimits.xml" />
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
     </AronIncludes>
 
     <GenerateTypes>
 
-        <Object name='armarx::navigation::traj_ctrl::arondto::TrajectoryControllerParams'>
+        <Object name='armarx::navigation::traj_ctrl::local::arondto::TrajectoryControllerParams'>
             <!-- <ObjectChild key='limits'>
                 <armarx::navigation::core::arondto::TwistLimits />
             </ObjectChild> -->
diff --git a/source/armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.xml b/source/armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.xml
new file mode 100644
index 00000000..db25d84b
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/aron/TrajectoryFollowingControllerParams.xml
@@ -0,0 +1,31 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <CodeIncludes>
+        <Include include="<armarx/navigation/trajectory_control/local/aron/TrajectoryControllerParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/core/aron/PIDParams.aron.generated.h>" />
+        <Include include="<armarx/navigation/core/aron/TwistLimits.aron.generated.h>" />
+    </CodeIncludes>
+    <AronIncludes>
+        <Include include="TrajectoryControllerParams.xml" />
+        <Include include="armarx/navigation/core/aron/PIDParams.xml" />
+        <Include include="armarx/navigation/core/aron/TwistLimits.xml" />
+    </AronIncludes>
+
+    <GenerateTypes>
+
+        <!-- <Object name='armarx::navigation::traj_ctrl::arondto::LocalTrajectoryFollowingControllerParams' extends="armarx::navigation::traj_ctrl::arondto::TrajectoryControllerParams"> -->
+        <Object name='armarx::navigation::traj_ctrl::local::arondto::TrajectoryFollowingControllerParams'>
+            <ObjectChild key='pidPos'>
+                <armarx::navigation::core::arondto::PIDParams />
+            </ObjectChild>
+            <ObjectChild key='pidOri'>
+                <armarx::navigation::core::arondto::PIDParams />
+            </ObjectChild>
+            <ObjectChild key='limits'>
+                <armarx::navigation::core::arondto::TwistLimits />
+            </ObjectChild>
+
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/trajectory_control/local/aron_conversions.cpp b/source/armarx/navigation/trajectory_control/local/aron_conversions.cpp
new file mode 100644
index 00000000..8cfc96a7
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/aron_conversions.cpp
@@ -0,0 +1,35 @@
+#include "aron_conversions.h"
+
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
+
+#include <armarx/navigation/core/aron_conversions.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
+
+
+namespace armarx::navigation::traj_ctrl::local
+{
+
+
+    void
+    toAron(arondto::TrajectoryFollowingControllerParams& dto,
+           const TrajectoryFollowingControllerParams& bo)
+    {
+        core::toAron(dto.pidOri, bo.pidOri);
+        core::toAron(dto.pidPos, bo.pidPos);
+        core::toAron(dto.limits, bo.limits);
+    }
+
+    void
+    fromAron(const arondto::TrajectoryFollowingControllerParams& dto,
+             TrajectoryFollowingControllerParams& bo)
+    {
+        core::fromAron(dto.pidOri, bo.pidOri);
+        core::fromAron(dto.pidPos, bo.pidPos);
+        core::fromAron(dto.limits, bo.limits);
+    }
+
+
+} // namespace armarx::navigation::traj_ctrl::local
diff --git a/source/armarx/navigation/trajectory_control/local/aron_conversions.h b/source/armarx/navigation/trajectory_control/local/aron_conversions.h
new file mode 100644
index 00000000..91b8f9bb
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/aron_conversions.h
@@ -0,0 +1,45 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @author     Christian R. G. Dreher ( c dot dreher at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+namespace armarx::navigation::traj_ctrl::local
+{
+    struct TrajectoryControllerParams;
+    struct TrajectoryFollowingControllerParams;
+
+    namespace arondto
+    {
+        class TrajectoryControllerParams;
+        class TrajectoryFollowingControllerParams;
+    } // namespace arondto
+
+
+    void toAron(arondto::TrajectoryControllerParams& dto, const TrajectoryControllerParams& bo);
+    void fromAron(const arondto::TrajectoryControllerParams& dto, TrajectoryControllerParams& bo);
+
+    void toAron(arondto::TrajectoryFollowingControllerParams& dto,
+                const TrajectoryFollowingControllerParams& bo);
+    void fromAron(const arondto::TrajectoryFollowingControllerParams& dto,
+                  TrajectoryFollowingControllerParams& bo);
+
+} // namespace armarx::navigation::traj_ctrl::local
diff --git a/source/armarx/navigation/trajectory_control/local/core.h b/source/armarx/navigation/trajectory_control/local/core.h
new file mode 100644
index 00000000..3a3aa676
--- /dev/null
+++ b/source/armarx/navigation/trajectory_control/local/core.h
@@ -0,0 +1,36 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @author     Christian R. G. Dreher ( c dot dreher at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <SimoxUtility/meta/enum/EnumNames.hpp>
+
+namespace armarx::navigation::traj_ctrl::local
+{
+    enum class Algorithms
+    {
+        TrajectoryFollowingController
+    };
+
+    const inline simox::meta::EnumNames<Algorithms> AlgorithmNames{
+        {Algorithms::TrajectoryFollowingController, "TrajectoryFollowingController"}};
+} // namespace armarx::navigation::traj_ctrl::local
-- 
GitLab


From cca9f99c9221100bc3a1d7ec54f47a9162f0f45d Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Tue, 26 Jul 2022 01:11:19 +0200
Subject: [PATCH 011/324] Calculate target position for planning (wip)

---
 .../local_planning/TimedElasticBands.cpp      | 82 +++++++++++++++++--
 .../local_planning/TimedElasticBands.h        |  9 ++
 2 files changed, 84 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 0621d44a..5b8dca2c 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,5 +1,6 @@
 #include "TimedElasticBands.h"
 
+#include <VirtualRobot/MathTools.h>
 #include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/logging/Logging.h>
@@ -79,15 +80,16 @@ namespace armarx::navigation::loc_plan
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::Trajectory& goal)
     {
-        teb_local_planner::TimedElasticBand globalPath = conv::toRos(goal);
+        const teb_local_planner::TimedElasticBand globalPath = conv::toRos(goal);
         teb_globalPath = globalPath.poses();
         hcp_->setGlobalPath(&teb_globalPath);
 
-        //TODO (SALt): calculate target pose
-        const teb_local_planner::PoseSE2 start =
-            conv::toRos(static_cast<core::Pose>(scene.robot->getGlobalPose()));
-        const teb_local_planner::PoseSE2 end = conv::toRos(goal.points().end()->waypoint.pose);
-        bool planToDestination = true;
+        const core::Pose currentPose{scene.robot->getGlobalPose()};
+
+        const teb_local_planner::PoseSE2 start = conv::toRos(currentPose);
+
+        const FindTargetResult target = findTarget(currentPose, goal);
+        const teb_local_planner::PoseSE2 end = conv::toRos(target.target);
 
         core::Twist currentVelocity = core::Twist::Zero();
         if (scene.platformVelocity.has_value())
@@ -100,7 +102,7 @@ namespace armarx::navigation::loc_plan
 
         try
         {
-            hcp_->plan(start, end, &velocity_start, !planToDestination);
+            hcp_->plan(start, end, &velocity_start, !planToDest);
         }
         catch (std::exception& e)
         {
@@ -116,4 +118,70 @@ namespace armarx::navigation::loc_plan
     }
 
 
+    TimedElasticBands::FindTargetResult
+    TimedElasticBands::findTarget(const core::Pose& currentPose, const core::Trajectory& globalPath)
+    {
+        float distance = std::numeric_limits<float>::max();
+
+        const core::Position point = currentPose.translation();
+        core::Position projection;
+
+        size_t closestSegment = -1;
+        for (size_t i = 0; i < globalPath.points().size() - 1; i++)
+        {
+            const auto& wpBefore = globalPath.points().at(i);
+            const auto& wpAfter = globalPath.points().at(i + 1);
+
+            // FIXME remove after finding the bug
+            if ((wpBefore.waypoint.pose.translation() - wpAfter.waypoint.pose.translation())
+                    .norm() < 1.F)
+            {
+                // ARMARX_WARNING << "Trajectory segment " << i << " too small ...";
+                continue;
+            }
+
+            const auto closestPoint =
+                VirtualRobot::MathTools::nearestPointOnSegment<core::Position>(
+                    wpBefore.waypoint.pose.translation(),
+                    wpAfter.waypoint.pose.translation(),
+                    point);
+
+            const float currentDistance = (closestPoint - point).norm();
+
+            // 'less equal' to accept following segment if the closest point is the waypoint
+            if (currentDistance <= distance)
+            {
+                closestSegment = i;
+                projection = closestPoint;
+                distance = currentDistance;
+            }
+        }
+
+        //TODO (SALt): parameter to set planning distance
+        float remaining = 5.F;
+        core::Position closestPoint = projection;
+        for (size_t i = closestSegment; i < globalPath.points().size() - 1; i++)
+        {
+            const core::Position& segEnd =
+                globalPath.points().at(i + 1).waypoint.pose.translation();
+
+            const float segmentDistance = (segEnd - closestPoint).norm();
+
+            if (segmentDistance < remaining)
+            {
+                closestPoint = segEnd;
+                remaining -= segmentDistance;
+            }
+            else
+            {
+                const core::Position dest =
+                    closestPoint + remaining * (segEnd - closestPoint).normalized();
+
+                return {projection, dest, false};
+            }
+        }
+
+        return {projection, globalPath.points().end()[0].waypoint.pose.translation(), true};
+    }
+
 } // namespace armarx::navigation::loc_plan
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 8c3b7ade..8ab68d1c 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -52,7 +52,16 @@ namespace armarx::navigation::loc_plan
         std::optional<LocalPlannerResult> plan(const core::Trajectory& goal) override;
 
     private:
+        struct FindTargetResult
+        {
+            core::Pose projection;
+            core::Pose target;
+            bool planToDestination;
+        };
+
         void initConfig();
+        FindTargetResult findTarget(const core::Pose& currentPose,
+                                    const core::Trajectory& globalPath);
 
     protected:
         const Params params;
-- 
GitLab


From 4eaccefaeb67b34d55de71ff847e04b4e9fd54fb Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:18:45 +0200
Subject: [PATCH 012/324] cmake: teb

---
 CMakeLists.txt                                       |  7 +++----
 .../armarx/navigation/local_planning/CMakeLists.txt  | 12 ++++++------
 2 files changed, 9 insertions(+), 10 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 22d07b6c..b41b5959 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -3,10 +3,6 @@ cmake_minimum_required(VERSION 3.18)
 # default settings
 set(ARMARX_ENABLE_DEPENDENCY_VERSION_CHECK_DEFAULT FALSE)
 
-# Find teb_extension locally with CMake
-# TODO(SALt): make teb_extension available through axii
-find_package(teb_extension REQUIRED)
-
 find_package("ArmarXCore" REQUIRED)
 include(${ArmarXCore_USE_FILE})
 
@@ -36,6 +32,9 @@ armarx_find_package(PUBLIC VTK QUIET)
 armarx_find_package(PUBLIC SemanticObjectRelations QUIET)
 armarx_find_package(PUBLIC OpenCV QUIET)  # Required as RobotAPI is a legacy project.
 armarx_find_package(PUBLIC range-v3 QUIET)
+# human aware navigation
+armarx_find_package(PUBLIC teb_local_planner QUIET)
+armarx_find_package(PUBLIC teb_extension QUIET)
 
 add_subdirectory(etc)
 
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 04e5feb9..6d47bd30 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -1,10 +1,15 @@
 
 armarx_add_library(local_planning
-    DEPENDENCIES
+    DEPENDENCIES_PUBLIC
         ArmarXCoreInterfaces
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
+        # teb_extension::obstacles
+    DEPENDENCIES_PRIVATE
+        range-v3::range-v3
+    DEPENDENCIES_LEGACY
+        teb_local_planner
     SOURCES 
         ./LocalPlanner.cpp
         ./TimedElasticBands.cpp
@@ -15,8 +20,3 @@ armarx_add_library(local_planning
         ./ros_conversions.h
         core.h
 )
-
-target_link_libraries(local_planning
-    PUBLIC
-        teb_extension::obstacles
-)
-- 
GitLab


From e63b21d5644c25d98f6ddbe0fe91598293340f33 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:22:51 +0200
Subject: [PATCH 013/324] ros_conversions: new types

---
 .../local_planning/ros_conversions.cpp        | 36 +++++++++++--------
 .../local_planning/ros_conversions.h          |  4 +--
 2 files changed, 23 insertions(+), 17 deletions(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index bd2befd4..0160c6ef 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -1,7 +1,13 @@
 #include "ros_conversions.h"
+#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+#include "ArmarXCore/core/time/Clock.h"
+#include "ArmarXCore/core/time/Duration.h"
 
+#include "armarx/navigation/core/Trajectory.h"
 #include <armarx/navigation/conversions/eigen.h>
 
+#include <range/v3/view/zip.hpp>
+
 namespace armarx::navigation::conv
 {
     teb_local_planner::PoseSE2
@@ -41,13 +47,13 @@ namespace armarx::navigation::conv
     }
 
     teb_local_planner::TimedElasticBand
-    toRos(const core::Trajectory& trajectory)
+    toRos(const core::GlobalTrajectory& trajectory)
     {
         teb_local_planner::TimedElasticBand teb;
 
         bool first = true;
         teb_local_planner::PoseSE2 lastPose;
-        for (const core::TrajectoryPoint& point : trajectory.points())
+        for (const core::GlobalTrajectoryPoint& point : trajectory.points())
         {
             teb_local_planner::PoseSE2 pose = toRos(point.waypoint.pose);
             teb.addPose(pose);
@@ -67,27 +73,27 @@ namespace armarx::navigation::conv
         return teb;
     }
 
-    core::Trajectory
+    core::LocalTrajectory
     fromRos(const teb_local_planner::TimedElasticBand& teb)
     {
-        core::TrajectoryPoints trajectory;
+        core::LocalTrajectory trajectory;
         trajectory.reserve(teb.poses().size());
 
-        teb_local_planner::PoseSequence::const_iterator poseIt = teb.poses().begin();
-        for (const teb_local_planner::VertexTimeDiff* timeDiff : teb.timediffs())
-        {
-            Eigen::Vector2d distance = poseIt[1]->pose().position() - poseIt[0]->pose().position();
-            float velocity = distance.norm() / timeDiff->dt();
+        // TODO this timestamp should be given via the argument list
+        DateTime timestamp = Clock::Now();
 
-            core::Pose pose = fromRos(poseIt[0]->pose());
+        ARMARX_CHECK_EQUAL(teb.poses().size(), teb.timediffs().size());
+
+        for (const auto& [poseVertex, timediff]: ranges::views::zip(teb.poses(), teb.timediffs()))
+        {
+            const core::Pose pose = fromRos(poseVertex->pose());
+            const Duration dt = Duration::SecondsDouble(timediff->dt());
+            timestamp += dt;
 
-            trajectory.push_back({.waypoint = {pose}, .velocity = velocity});
-            poseIt++;
+            trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {pose}});
         }
-        core::Pose end = fromRos(teb.poses().end()[0]->pose());
-        trajectory.push_back({.waypoint = {end}, .velocity = 0});
 
-        return {trajectory};
+        return trajectory;
     }
 
 
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 62aea35b..99884212 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -36,9 +36,9 @@ namespace armarx::navigation::conv
 
     geometry_msgs::Twist toRos(const core::Twist& velocity);
 
-    teb_local_planner::TimedElasticBand toRos(const core::Trajectory& trajectory);
+    teb_local_planner::TimedElasticBand toRos(const core::GlobalTrajectory& trajectory);
 
-    core::Trajectory fromRos(const teb_local_planner::TimedElasticBand& teb);
+    core::LocalTrajectory fromRos(const teb_local_planner::TimedElasticBand& teb);
 
 
 } // namespace armarx::navigation::conv
-- 
GitLab


From 8caceb367803a5813e1d92b34cf66d40f08450c6 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:23:13 +0200
Subject: [PATCH 014/324] TimedElasticBands: fixing build due to api changes

---
 .../local_planning/TimedElasticBands.cpp      | 21 ++++++++++++-------
 .../local_planning/TimedElasticBands.h        |  3 ++-
 2 files changed, 15 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index c3fdb8ae..7ebf586f 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -8,7 +8,7 @@
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
-#include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
+// #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 
 namespace armarx::navigation::loc_plan
@@ -92,14 +92,19 @@ namespace armarx::navigation::loc_plan
         const teb_local_planner::PoseSE2 end = conv::toRos(target.target);
 
         core::Twist currentVelocity = core::Twist::Zero();
-        if (scene.platformVelocity.has_value())
-        {
-            currentVelocity = scene.platformVelocity.value();
-        }
+        
+        // FIXME: again, add to scene
+        // if (scene.platformVelocity.has_value())
+        // {
+        //     currentVelocity = scene.platformVelocity.value();
+        // }
         geometry_msgs::Twist velocity_start = conv::toRos(currentVelocity);
 
         //TODO (SALt): fill obstacles
 
+        // TODO (SALt): implement
+        bool planToDest = true;
+
         try
         {
             hcp_->plan(start, end, &velocity_start, !planToDest);
@@ -112,14 +117,14 @@ namespace armarx::navigation::loc_plan
         ARMARX_VERBOSE << "Planned successfully (found " << hcp_->getTrajectoryContainer().size()
                        << " Trajectories)";
 
-        core::Trajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
+        core::LocalTrajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
 
         return {{.trajectory = best}};
     }
 
 
     TimedElasticBands::FindTargetResult
-    TimedElasticBands::findTarget(const core::Pose& currentPose, const core::Trajectory& globalPath)
+    TimedElasticBands::findTarget(const core::Pose& currentPose, const core::GlobalTrajectory& globalPath)
     {
         float distance = std::numeric_limits<float>::max();
 
@@ -181,7 +186,7 @@ namespace armarx::navigation::loc_plan
             }
         }
 
-        return {projection, globalPath.points().end()[0].waypoint.pose.translation(), true};
+        return {projection, globalPath.points().back().waypoint.pose.translation(), true};
     }
 
 } // namespace armarx::navigation::loc_plan
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 99b2ae44..0197b949 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -66,13 +66,14 @@ namespace armarx::navigation::loc_plan
 
         void initConfig();
         FindTargetResult findTarget(const core::Pose& currentPose,
-                                    const core::Trajectory& globalPath);
+                                    const core::GlobalTrajectory& globalPath);
 
     protected:
         const Params params;
 
     private:
         const core::Scene& scene;
+        
         teb_local_planner::TebConfig cfg_;
         teb_local_planner::ObstContainer teb_obstacles;
         teb_local_planner::PoseSequence teb_globalPath;
-- 
GitLab


From 0f11491f66a2951b99764a1a93ef6d13977d5490 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:30:35 +0200
Subject: [PATCH 015/324] ros_conversions: 2D version

---
 .../navigation/local_planning/ros_conversions.cpp      | 10 ++++++++--
 .../armarx/navigation/local_planning/ros_conversions.h |  1 +
 2 files changed, 9 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 0160c6ef..2742d26b 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -4,6 +4,7 @@
 #include "ArmarXCore/core/time/Duration.h"
 
 #include "armarx/navigation/core/Trajectory.h"
+#include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/conversions/eigen.h>
 
 #include <range/v3/view/zip.hpp>
@@ -14,9 +15,14 @@ namespace armarx::navigation::conv
     toRos(const core::Pose& pose)
     {
         core::Pose2D pose2D = to2D(pose);
+        return toRos(pose2D);
+    }
 
-        Eigen::Vector2d pos = pose2D.translation().cast<double>();
-        double theta = Eigen::Rotation2Df(pose2D.linear()).angle();
+    teb_local_planner::PoseSE2
+    toRos(const core::Pose2D& pose)
+    {
+        Eigen::Vector2d pos = pose.translation().cast<double>();
+        double theta = Eigen::Rotation2Df(pose.linear()).angle();
 
         return {pos, theta};
     }
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 99884212..25a28c40 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -31,6 +31,7 @@ namespace armarx::navigation::conv
 {
 
     teb_local_planner::PoseSE2 toRos(const core::Pose& pose);
+    teb_local_planner::PoseSE2 toRos(const core::Pose2D& pose);
 
     core::Pose fromRos(const teb_local_planner::PoseSE2& pose);
 
-- 
GitLab


From 3aada4c0a52f698d30af0a8d3b163c94da6b50fa Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:30:57 +0200
Subject: [PATCH 016/324] TEB: using builtin trajectory projection method

---
 .../local_planning/TimedElasticBands.cpp      | 64 ++-----------------
 .../local_planning/TimedElasticBands.h        |  5 +-
 2 files changed, 8 insertions(+), 61 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 7ebf586f..147e7622 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -5,6 +5,8 @@
 
 #include <ArmarXCore/core/logging/Logging.h>
 
+#include "armarx/navigation/conversions/eigen.h"
+#include "armarx/navigation/core/Trajectory.h"
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
@@ -126,67 +128,11 @@ namespace armarx::navigation::loc_plan
     TimedElasticBands::FindTargetResult
     TimedElasticBands::findTarget(const core::Pose& currentPose, const core::GlobalTrajectory& globalPath)
     {
-        float distance = std::numeric_limits<float>::max();
 
-        const core::Position point = currentPose.translation();
-        core::Position projection;
+        const core::Projection projection = globalPath.getProjection(
+            currentPose.translation(), core::VelocityInterpolation::LinearInterpolation);
 
-        size_t closestSegment = -1;
-        for (size_t i = 0; i < globalPath.points().size() - 1; i++)
-        {
-            const auto& wpBefore = globalPath.points().at(i);
-            const auto& wpAfter = globalPath.points().at(i + 1);
-
-            // FIXME remove after finding the bug
-            if ((wpBefore.waypoint.pose.translation() - wpAfter.waypoint.pose.translation())
-                    .norm() < 1.F)
-            {
-                // ARMARX_WARNING << "Trajectory segment " << i << " too small ...";
-                continue;
-            }
-
-            const auto closestPoint =
-                VirtualRobot::MathTools::nearestPointOnSegment<core::Position>(
-                    wpBefore.waypoint.pose.translation(),
-                    wpAfter.waypoint.pose.translation(),
-                    point);
-
-            const float currentDistance = (closestPoint - point).norm();
-
-            // 'less equal' to accept following segment if the closest point is the waypoint
-            if (currentDistance <= distance)
-            {
-                closestSegment = i;
-                projection = closestPoint;
-                distance = currentDistance;
-            }
-        }
-
-        //TODO (SALt): parameter to set planning distance
-        float remaining = 5.F;
-        core::Position closestPoint = projection;
-        for (size_t i = closestSegment; i < globalPath.points().size() - 1; i++)
-        {
-            const core::Position& segEnd =
-                globalPath.points().at(i + 1).waypoint.pose.translation();
-
-            const float segmentDistance = (segEnd - closestPoint).norm();
-
-            if (segmentDistance < remaining)
-            {
-                closestPoint = segEnd;
-                remaining -= segmentDistance;
-            }
-            else
-            {
-                const core::Position dest =
-                    closestPoint + remaining * (segEnd - closestPoint).normalized();
-
-                return {projection, dest, false};
-            }
-        }
-
-        return {projection, globalPath.points().back().waypoint.pose.translation(), true};
+        return {conv::to2D(projection.projection.waypoint.pose), conv::to2D(globalPath.points().back().waypoint.pose), true};
     }
 
 } // namespace armarx::navigation::loc_plan
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 0197b949..2ecd7862 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -24,6 +24,7 @@
 
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
+#include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/core.h>
@@ -59,8 +60,8 @@ namespace armarx::navigation::loc_plan
     private:
         struct FindTargetResult
         {
-            core::Pose projection;
-            core::Pose target;
+            core::Pose2D projection;
+            core::Pose2D target;
             bool planToDestination;
         };
 
-- 
GitLab


From 62db52410bc801f2fef89b6d7e2b2a0e1c843d23 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 09:46:50 +0200
Subject: [PATCH 017/324] navigator component: new property to conditinally
 disable platform executor (plan-only mode)

---
 .../components/Navigator/Navigator.cpp        | 20 +++++++++--
 .../components/Navigator/Navigator.h          |  1 +
 source/armarx/navigation/server/Navigator.cpp | 19 +++++++---
 .../server/execution/DummyExecutor.h          | 36 +++++--------------
 4 files changed, 42 insertions(+), 34 deletions(-)

diff --git a/source/armarx/navigation/components/Navigator/Navigator.cpp b/source/armarx/navigation/components/Navigator/Navigator.cpp
index 3829c503..7aeac32d 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.cpp
+++ b/source/armarx/navigation/components/Navigator/Navigator.cpp
@@ -69,6 +69,7 @@
 #include <RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
+#include "armarx/navigation/server/execution/ExecutorInterface.h"
 #include "armarx/navigation/server/scene_provider/SceneProvider.h"
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
@@ -182,7 +183,11 @@ namespace armarx::navigation::components
         initializeScene();
 
         ARMARX_TRACE;
-        executor.emplace(server::PlatformControllerExecutor(getControlComponentPlugin()));
+
+        if(not params.disableExecutor)
+        {
+            executor.emplace(server::PlatformControllerExecutor(getControlComponentPlugin()));
+        }
 
         ARMARX_TRACE;
         introspector = server::ArvizIntrospector(getArvizClient(), scene().robot);
@@ -254,13 +259,19 @@ namespace armarx::navigation::components
             std::make_unique<server::MemoryPublisher>(
                 &resultsWriterPlugin->get(), &eventsWriterPlugin->get(), callerId));
 
+        server::ExecutorInterface* executorPtr = nullptr;
+        if(executor.has_value())
+        {
+            executorPtr = &executor.value();
+        }
+
         navigators.emplace(
             std::piecewise_construct,
             std::forward_as_tuple(callerId),
             std::forward_as_tuple(
                 server::Navigator::Config{.stack = std::move(stack),
                                           .general = server::Navigator::Config::General{}},
-                server::Navigator::InjectedServices{.executor = &executor.value(),
+                server::Navigator::InjectedServices{.executor = executorPtr,
                                                     .publisher =
                                                         memoryPublishers.at(callerId).get(),
                                                     .introspector = &(introspector.value()),
@@ -433,6 +444,11 @@ namespace armarx::navigation::components
                       "Threshold for each cell to be considered occupied. Increase this value to "
                       "reduce noise.");
 
+        def->optional(params.disableExecutor,
+                      "p.disableExecutor",
+                      "If the executor is disabled, the navigator will only plan the trajectory "
+                      "but won't execute it.");
+
         return def;
     }
 
diff --git a/source/armarx/navigation/components/Navigator/Navigator.h b/source/armarx/navigation/components/Navigator/Navigator.h
index 7c725c31..d20a2101 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.h
+++ b/source/armarx/navigation/components/Navigator/Navigator.h
@@ -214,6 +214,7 @@ namespace armarx::navigation::components
         struct Parameters
         {
             float occupiedGridThreshold{0.55F};
+            bool disableExecutor{false};
         };
 
         Parameters params;
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 4a25256e..0fd9321f 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -59,7 +59,7 @@ namespace armarx::navigation::server
         config{config}, srv{services}
     {
         ARMARX_CHECK_NOT_NULL(srv.sceneProvider) << "The scene provider must be set!";
-        ARMARX_CHECK_NOT_NULL(services.executor) << "The executor service must be set!";
+        // ARMARX_CHECK_NOT_NULL(services.executor) << "The executor service must be set!";
         ARMARX_CHECK_NOT_NULL(services.publisher) << "The publisher service must be set!";
     }
 
@@ -796,6 +796,12 @@ namespace armarx::navigation::server
     void
     Navigator::updateExecutor(const std::optional<loc_plan::LocalPlannerResult>& localPlan)
     {
+        if(srv.executor == nullptr)
+        {
+            return;
+        }
+
+
         if (isPaused() or isStopped())
         {
             // [[unlikely]]
@@ -924,8 +930,10 @@ namespace armarx::navigation::server
 
         executorEnabled.store(false);
 
-        ARMARX_CHECK_NOT_NULL(srv.executor);
-        srv.executor->stop();
+        if(srv.executor != nullptr)
+        {
+            srv.executor->stop();
+        }
     }
 
     void
@@ -935,7 +943,10 @@ namespace armarx::navigation::server
 
         executorEnabled.store(true);
 
-         srv.executor->start();
+        if(srv.executor != nullptr)
+        {
+            srv.executor->start();
+        }
     }
 
     void
diff --git a/source/armarx/navigation/server/execution/DummyExecutor.h b/source/armarx/navigation/server/execution/DummyExecutor.h
index ae5e40c6..2848cc6a 100644
--- a/source/armarx/navigation/server/execution/DummyExecutor.h
+++ b/source/armarx/navigation/server/execution/DummyExecutor.h
@@ -1,15 +1,11 @@
 #pragma once
 
-// STD/STL
 #include <chrono>
 
-// Eigen
 #include <Eigen/Geometry>
 
-// Simox
 #include <VirtualRobot/Robot.h>
 
-// Navigation
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/server/execution/ExecutorInterface.h>
 
@@ -20,39 +16,23 @@ namespace armarx::navigation::server
     {
 
     public:
-        struct Params
-        {
-        };
+        DummyExecutor() = default;
+
+        ~DummyExecutor() override = default;
 
-        DummyExecutor(const VirtualRobot::RobotPtr& robot, const Params& params) : robot(robot)
+        void
+        execute(const core::LocalTrajectory& trajectory) override
         {
         }
 
-        ~DummyExecutor() override
+        void
+        start() override
         {
         }
-
         void
-        move(const core::Twist& twist) override
+        stop() override
         {
-            this->twist = twist;
-            //const auto now = std::chrono::time_point_cast<std::chrono::microseconds>(std::chrono::steady_clock::now());
-
-            //const float dt = now - lastUpdated;
-
-            //lastUpdated = now;
-
-            const core::Pose diff; // TODO
-
-            robot->setGlobalPose(robot->getGlobalPose() * diff.matrix());
         }
-
-    private:
-        VirtualRobot::RobotPtr robot;
-
-        core::Twist twist;
-
-        std::chrono::microseconds lastUpdated;
     };
 
 } // namespace armarx::navigation::server
-- 
GitLab


From d9d6526e0cd0d1304f6ee987cdfff75f1557d0c5 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 26 Jul 2022 17:25:43 +0200
Subject: [PATCH 018/324] dynamic scene provider component

---
 .../navigation/components/CMakeLists.txt      |   2 +
 .../dynamic_scene_provider/CMakeLists.txt     |  34 +++
 .../dynamic_scene_provider/Component.cpp      | 289 ++++++++++++++++++
 .../dynamic_scene_provider/Component.h        | 177 +++++++++++
 .../ComponentInterface.ice                    |  35 +++
 5 files changed, 537 insertions(+)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/Component.h
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/ComponentInterface.ice

diff --git a/source/armarx/navigation/components/CMakeLists.txt b/source/armarx/navigation/components/CMakeLists.txt
index d0cdc317..3f13b407 100644
--- a/source/armarx/navigation/components/CMakeLists.txt
+++ b/source/armarx/navigation/components/CMakeLists.txt
@@ -3,3 +3,5 @@ add_subdirectory(NavigationMemory)
 add_subdirectory(Navigator)
 
 add_subdirectory(dynamic_distance_to_obstacle_costmap_provider)
+
+add_subdirectory(dynamic_scene_provider)
\ No newline at end of file
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
new file mode 100644
index 00000000..9e1fc7a9
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -0,0 +1,34 @@
+armarx_add_component(dynamic_scene_provider
+    ICE_FILES
+        ComponentInterface.ice
+    ICE_DEPENDENCIES
+        ArmarXCoreInterfaces
+        # RobotAPIInterfaces
+    # ARON_FILES
+        # aron/my_type.xml
+    SOURCES
+        Component.cpp
+    HEADERS
+        Component.h
+    DEPENDENCIES
+        # ArmarXCore
+        ArmarXCore
+        ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
+        # ArmarXGui
+        ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
+        # RobotAPI
+        armem
+        armem_robot
+        armem_robot_state
+        # VisionX
+        armem_human
+        armem_vision
+        ## RobotAPICore
+        ## RobotAPIInterfaces
+        ## RobotAPIComponentPlugins  # For ArViz and other plugins.
+    # DEPENDENCIES_LEGACY
+        ## Add libraries that do not provide any targets but ${FOO_*} variables.
+        # FOO
+    # If you need a separate shared component library you can enable it with the following flag.
+    # SHARED_COMPONENT_LIBRARY
+)
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
new file mode 100644
index 00000000..101a897a
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -0,0 +1,289 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::dynamic_scene_provider
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#include "Component.h"
+
+#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+#include "ArmarXCore/core/services/tasks/PeriodicTask.h"
+#include "ArmarXCore/core/time/Clock.h"
+#include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
+
+#include "VisionX/libraries/armem_human/client/HumanPoseReader.h"
+
+#include <armarx/navigation/core/basic_types.h>
+
+// Include headers you only need in function definitions in the .cpp.
+
+// #include <Eigen/Core>
+
+// #include <SimoxUtility/color/Color.h>
+
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+
+    const std::string Component::defaultName = "dynamic_scene_provider";
+
+
+    Component::Component()
+    {
+        addPlugin(humanPoseReaderPlugin);
+        addPlugin(laserScannerFeaturesReaderPlugin);
+    }
+
+    armarx::PropertyDefinitionsPtr
+    Component::createPropertyDefinitions()
+    {
+        armarx::PropertyDefinitionsPtr def =
+            new armarx::ComponentPropertyDefinitions(getConfigIdentifier());
+
+        // Publish to a topic (passing the TopicListenerPrx).
+        // def->topic(myTopicListener);
+
+        // Subscribe to a topic (passing the topic name).
+        // def->topic<PlatformUnitListener>("MyTopic");
+
+        // Use (and depend on) another component (passing the ComponentInterfacePrx).
+        // def->component(myComponentProxy)
+
+
+        // Add a required property. (The component won't start without a value being set.)
+        // def->required(properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
+
+        // Add an optionalproperty.
+        def->optional(
+            properties.taskPeriodMs, "p.taskPeriodMs", "Update rate of the running task.");
+
+        return def;
+    }
+
+
+    void
+    Component::onInitComponent()
+    {
+        // Topics and properties defined above are automagically registered.
+
+        // Keep debug observer data until calling `sendDebugObserverBatch()`.
+        // (Requies the armarx::DebugObserverComponentPluginUser.)
+        // setDebugObserverBatchModeEnabled(true);
+    }
+
+
+    void
+    Component::onConnectComponent()
+    {
+        // Do things after connecting to topics and components.
+
+        /* (Requies the armarx::DebugObserverComponentPluginUser.)
+        // Use the debug observer to log data over time.
+        // The data can be viewed in the ObserverView and the LivePlotter.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        {
+            setDebugObserverDatafield("numBoxes", properties.numBoxes);
+            setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+            sendDebugObserverBatch();
+        }
+        */
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        // Draw boxes in ArViz.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        drawBoxes(properties, arviz);
+        */
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        // Setup the remote GUI.
+        {
+            createRemoteGuiTab();
+            RemoteGui_startRunningTask();
+        }
+        */
+
+        robot = virtualRobotReaderPlugin->get().getRobot(properties.robot.name);
+        ARMARX_CHECK_NOT_NULL(robot);
+
+        task = new PeriodicTask<Component>(
+            this, &Component::runPeriodically, properties.taskPeriodMs, false, "runningTask");
+    }
+
+
+    void
+    Component::onDisconnectComponent()
+    {
+    }
+
+
+    void
+    Component::onExitComponent()
+    {
+    }
+
+
+    std::string
+    Component::getDefaultName() const
+    {
+        return Component::defaultName;
+    }
+
+
+    std::string
+    Component::GetDefaultName()
+    {
+        return Component::defaultName;
+    }
+
+    void
+    Component::runPeriodically()
+    {
+        // obtain data from perception
+
+        const DateTime timestamp = Clock::Now();
+
+        //
+        // Robot
+        //
+
+        ARMARX_CHECK(virtualRobotReaderPlugin->get().synchronizeRobot(*robot, timestamp));
+        const core::Pose global_T_robot(robot->getGlobalPose());
+
+        ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
+
+        //
+        // Human
+        //
+
+        const armem::human::client::Reader::Query humanPoseQuery{.providerName = "", // all
+                                                        .timestamp = timestamp};
+
+        const armem::human::client::Reader::Result humanPoseResult =
+            humanPoseReaderPlugin->get().query(humanPoseQuery);
+        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success);
+
+        ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
+
+        //
+        // Laser scanner features
+        //
+        
+        const armem::vision::laser_scanner_features::client::Reader::Query laserFeaturesQuery
+        {
+            .providerName = properties.laserScannerFeatures.providerName,
+            .name = properties.laserScannerFeatures.name,
+            .timestamp = timestamp
+        };
+
+        const armem::vision::laser_scanner_features::client::Reader::Result laserFeaturesResult =
+            laserScannerFeaturesReaderPlugin->get().queryData(laserFeaturesQuery);
+
+        ARMARX_CHECK_EQUAL(laserFeaturesResult.status, armem::vision::laser_scanner_features::client::Reader::Result::Success);
+        
+        ARMARX_INFO << laserFeaturesResult.features.size() << " clusters/features";
+
+
+    }
+
+
+    /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+    void
+    Component::createRemoteGuiTab()
+    {
+        using namespace armarx::RemoteGui::Client;
+
+        // Setup the widgets.
+
+        tab.boxLayerName.setValue(properties.boxLayerName);
+
+        tab.numBoxes.setValue(properties.numBoxes);
+        tab.numBoxes.setRange(0, 100);
+
+        tab.drawBoxes.setLabel("Draw Boxes");
+
+        // Setup the layout.
+
+        GridLayout grid;
+        int row = 0;
+        {
+            grid.add(Label("Box Layer"), {row, 0}).add(tab.boxLayerName, {row, 1});
+            ++row;
+
+            grid.add(Label("Num Boxes"), {row, 0}).add(tab.numBoxes, {row, 1});
+            ++row;
+
+            grid.add(tab.drawBoxes, {row, 0}, {2, 1});
+            ++row;
+        }
+
+        VBoxLayout root = {grid, VSpacer()};
+        RemoteGui_createTab(getName(), root, &tab);
+    }
+
+
+    void
+    Component::RemoteGui_update()
+    {
+        if (tab.boxLayerName.hasValueChanged() || tab.numBoxes.hasValueChanged())
+        {
+            std::scoped_lock lock(propertiesMutex);
+            properties.boxLayerName = tab.boxLayerName.getValue();
+            properties.numBoxes = tab.numBoxes.getValue();
+
+            {
+                setDebugObserverDatafield("numBoxes", properties.numBoxes);
+                setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+                sendDebugObserverBatch();
+            }
+        }
+        if (tab.drawBoxes.wasClicked())
+        {
+            // Lock shared variables in methods running in seperate threads
+            // and pass them to functions. This way, the called functions do
+            // not need to think about locking.
+            std::scoped_lock lock(propertiesMutex, arvizMutex);
+            drawBoxes(properties, arviz);
+        }
+    }
+    */
+
+
+    /* (Requires the armarx::ArVizComponentPluginUser.)
+    void
+    Component::drawBoxes(const Component::Properties& p, viz::Client& arviz)
+    {
+        // Draw something in ArViz (requires the armarx::ArVizComponentPluginUser.
+        // See the ArVizExample in RobotAPI for more examples.
+
+        viz::Layer layer = arviz.layer(p.boxLayerName);
+        for (int i = 0; i < p.numBoxes; ++i)
+        {
+            layer.add(viz::Box("box_" + std::to_string(i))
+                      .position(Eigen::Vector3f(i * 100, 0, 0))
+                      .size(20).color(simox::Color::blue()));
+        }
+        arviz.commit(layer);
+    }
+    */
+
+
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
new file mode 100644
index 00000000..c6792742
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -0,0 +1,177 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::dynamic_scene_provider
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#pragma once
+
+
+// #include <mutex>
+
+#include <VirtualRobot/VirtualRobot.h>
+#include "ArmarXCore/core/services/tasks/TaskUtil.h"
+#include <ArmarXCore/core/Component.h>
+
+#include "RobotAPI/libraries/armem/client/plugins/PluginUser.h"
+#include "RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h"
+#include "RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h"
+#include "RobotAPI/libraries/armem_vision/client/laser_scanner_features/Reader.h"
+
+#include "VisionX/libraries/armem_human/client/HumanPoseReader.h"
+
+// #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h>
+
+// #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
+
+// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
+
+#include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
+
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+
+    class Component :
+        virtual public armarx::Component,
+        virtual public armarx::navigation::components::dynamic_scene_provider::ComponentInterface,
+        // , virtual public armarx::DebugObserverComponentPluginUser
+        // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
+        // , virtual public armarx::ArVizComponentPluginUser
+        virtual public armarx::armem::client::plugins::PluginUser
+    {
+    public:
+        Component();
+
+        /// @see armarx::ManagedIceObject::getDefaultName()
+        std::string getDefaultName() const override;
+
+        /// Get the component's default name.
+        static std::string GetDefaultName();
+
+
+    protected:
+        /// @see PropertyUser::createPropertyDefinitions()
+        armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
+
+        /// @see armarx::ManagedIceObject::onInitComponent()
+        void onInitComponent() override;
+
+        /// @see armarx::ManagedIceObject::onConnectComponent()
+        void onConnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onDisconnectComponent()
+        void onDisconnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onExitComponent()
+        void onExitComponent() override;
+
+
+        /* (Requires armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// This function should be called once in onConnect() or when you
+        /// need to re-create the Remote GUI tab.
+        void createRemoteGuiTab();
+
+        /// After calling `RemoteGui_startRunningTask`, this function is
+        /// called periodically in a separate thread. If you update variables,
+        /// make sure to synchronize access to them.
+        void RemoteGui_update() override;
+        */
+
+
+    private:
+        // Private methods go here.
+
+        // Forward declare `Properties` if you used it before its defined.
+        // struct Properties;
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        /// Draw some boxes in ArViz.
+        void drawBoxes(const Properties& p, viz::Client& arviz);
+        */
+
+        void runPeriodically();
+
+        VirtualRobot::RobotPtr robot = nullptr;
+
+
+    private:
+        static const std::string defaultName;
+
+
+        // Private member variables go here.
+
+
+        /// Properties shown in the Scenario GUI.
+        struct Properties
+        {
+            int taskPeriodMs = 100;
+
+            struct
+            {
+                std::string providerName = "LaserScannerFeatureExtraction";
+                std::string name = ""; // all
+            } laserScannerFeatures;
+
+            struct
+            {
+                std::string name = "Armar6";
+            } robot;
+        };
+        Properties properties;
+        /* Use a mutex if you access variables from different threads
+         * (e.g. ice functions and RemoteGui_update()).
+        std::mutex propertiesMutex;
+        */
+
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// Tab shown in the Remote GUI.
+        struct RemoteGuiTab : armarx::RemoteGui::Client::Tab
+        {
+            armarx::RemoteGui::Client::LineEdit boxLayerName;
+            armarx::RemoteGui::Client::IntSpinBox numBoxes;
+
+            armarx::RemoteGui::Client::Button drawBoxes;
+        };
+        RemoteGuiTab tab;
+        */
+
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+         * When used from different threads, an ArViz client needs to be synchronized.
+        /// Protects the arviz client inherited from the ArViz plugin.
+        std::mutex arvizMutex;
+        */
+
+        PeriodicTask<Component>::pointer_type task;
+
+        armem::client::plugins::ReaderWriterPlugin<armem::human::client::Reader>*
+            humanPoseReaderPlugin = nullptr;
+
+        armem::client::plugins::ReaderWriterPlugin<
+            armem::vision::laser_scanner_features::client::Reader>* laserScannerFeaturesReaderPlugin =
+            nullptr;
+
+        armem::client::plugins::ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin = nullptr;
+
+    };
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/ComponentInterface.ice b/source/armarx/navigation/components/dynamic_scene_provider/ComponentInterface.ice
new file mode 100644
index 00000000..a66c4f56
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/ComponentInterface.ice
@@ -0,0 +1,35 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * package    navigation::dynamic_scene_provider
+ * author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * date       2022
+ * copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *            GNU General Public License
+ */
+
+
+#pragma once
+
+
+module armarx {  module navigation {  module components {  module dynamic_scene_provider 
+{
+
+    interface ComponentInterface
+    {
+	// Define your interface here.
+    };
+
+};};};};
-- 
GitLab


From 75d0d119e6d44c28342281a39c50a8197fa32b92 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 08:54:50 +0200
Subject: [PATCH 019/324] more scene features

---
 .../dynamic_scene_provider/CMakeLists.txt     |   3 +
 .../dynamic_scene_provider/Component.cpp      | 151 +++++++++++++++---
 .../dynamic_scene_provider/Component.h        |  37 ++++-
 3 files changed, 163 insertions(+), 28 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 9e1fc7a9..f42f1a64 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -23,6 +23,9 @@ armarx_add_component(dynamic_scene_provider
         # VisionX
         armem_human
         armem_vision
+        # navigation
+        armarx_navigation::util
+        armarx_navigation::memory
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 101a897a..19292c31 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -23,20 +23,20 @@
 
 #include "Component.h"
 
-#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
-#include "ArmarXCore/core/services/tasks/PeriodicTask.h"
-#include "ArmarXCore/core/time/Clock.h"
-#include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
-
-#include "VisionX/libraries/armem_human/client/HumanPoseReader.h"
+#include <VirtualRobot/SceneObjectSet.h>
 
-#include <armarx/navigation/core/basic_types.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+#include <ArmarXCore/core/time/Clock.h>
+#include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
-// Include headers you only need in function definitions in the .cpp.
+#include <RobotAPI/libraries/ArmarXObjects/forward_declarations.h>
 
-// #include <Eigen/Core>
+#include <VisionX/libraries/armem_human/client/HumanPoseReader.h>
 
-// #include <SimoxUtility/color/Color.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/util/util.h>
 
 
 namespace armarx::navigation::components::dynamic_scene_provider
@@ -49,6 +49,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
     {
         addPlugin(humanPoseReaderPlugin);
         addPlugin(laserScannerFeaturesReaderPlugin);
+        addPlugin(virtualRobotReaderPlugin);
+        addPlugin(costmapReaderPlugin);
+        addPlugin(occupancyGridReaderPlugin);
     }
 
     armarx::PropertyDefinitionsPtr
@@ -71,8 +74,17 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // def->required(properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
 
         // Add an optionalproperty.
-        def->optional(
-            properties.taskPeriodMs, "p.taskPeriodMs", "Update rate of the running task.");
+        def->optional(properties.taskPeriodMs, "p.taskPeriodMs", "Update rate of the running task.");
+        
+        def->optional(properties.laserScannerFeatures.providerName, "p.laserScannerFeatures.providerName", "");
+        def->optional(properties.laserScannerFeatures.name, "p.laserScannerFeatures.name", "");
+        
+        def->optional(properties.robot.name, "p.robot.name", "");
+        
+        def->optional(properties.occupancyGrid.providerName, "p.occupancyGrid.providerName", "");
+        def->optional(properties.occupancyGrid.name, "p.occupancyGrid.name", "");
+        def->optional(properties.occupancyGrid.freespaceThreshold, "p.occupancyGrid.freespaceThreshold", "");
+        def->optional(properties.occupancyGrid.occupiedThreshold, "p.occupancyGrid.occupiedThreshold", "");
 
         return def;
     }
@@ -173,7 +185,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         //
 
         const armem::human::client::Reader::Query humanPoseQuery{.providerName = "", // all
-                                                        .timestamp = timestamp};
+                                                                 .timestamp = timestamp};
 
         const armem::human::client::Reader::Result humanPoseResult =
             humanPoseReaderPlugin->get().query(humanPoseQuery);
@@ -184,22 +196,121 @@ namespace armarx::navigation::components::dynamic_scene_provider
         //
         // Laser scanner features
         //
-        
-        const armem::vision::laser_scanner_features::client::Reader::Query laserFeaturesQuery
-        {
+
+        const armem::vision::laser_scanner_features::client::Reader::Query laserFeaturesQuery{
             .providerName = properties.laserScannerFeatures.providerName,
             .name = properties.laserScannerFeatures.name,
-            .timestamp = timestamp
-        };
+            .timestamp = timestamp};
 
         const armem::vision::laser_scanner_features::client::Reader::Result laserFeaturesResult =
             laserScannerFeaturesReaderPlugin->get().queryData(laserFeaturesQuery);
 
-        ARMARX_CHECK_EQUAL(laserFeaturesResult.status, armem::vision::laser_scanner_features::client::Reader::Result::Success);
-        
+        ARMARX_CHECK_EQUAL(laserFeaturesResult.status,
+                           armem::vision::laser_scanner_features::client::Reader::Result::Success);
+
         ARMARX_INFO << laserFeaturesResult.features.size() << " clusters/features";
 
+        //
+        //  Objects in the scene (both static and dynamic)
+        //
+
+        const objpose::ObjectPoseSeq objectPoses = ObjectPoseClientPluginUser::getObjectPoses();
+
+        // remove those objects that belong to an object dataset. the manipulation object / distance computation is broken
+        const auto objectPosesStatic =
+            armarx::navigation::util::filterObjects(objectPoses, {"KIT", "HOPE", "MDB", "YCB"});
+
+        const auto objects = armarx::navigation::util::asSceneObjects(objectPosesStatic);
+        ARMARX_INFO << objects->getSize() << " objects in the scene";
 
+        // ARMARX_INFO << "Creating costmap";
+        // ARMARX_CHECK_NOT_NULL(scene.robot);
+
+        // algorithms::CostmapBuilder costmapBuilder(
+        //     scene.robot,
+        //     objects,
+        //     algorithms::Costmap::Parameters{.binaryGrid = false, .cellSize = 100},
+        //     "Platform-navigation-colmodel");
+
+        // // const auto costmap = costmapBuilder.create();
+
+        //
+        //  Costmaps
+        //
+
+        const memory::client::costmap::Reader::Query costmapQuery{.providerName =
+                                                                      "navigator", // TODO check
+                                                                  .name = "distance_to_obstacles",
+                                                                  .timestamp = timestamp};
+
+        const memory::client::costmap::Reader::Result costmapResult =
+            costmapReaderPlugin->get().query(costmapQuery);
+
+        ARMARX_CHECK_EQUAL(costmapResult.status, memory::client::costmap::Reader::Result::Success);
+
+        ARMARX_TRACE;
+        ARMARX_CHECK(costmapResult.costmap.has_value());
+        const auto grid = costmapResult.costmap->getGrid();
+
+
+        //
+        // Occupancy grid: from SLAM component
+        //
+
+        const armem::vision::occupancy_grid::client::Reader::Result result =
+            occupancyGridReaderPlugin->get().query(
+                armem::vision::occupancy_grid::client::Reader::Query{
+                    .providerName = properties.occupancyGrid.providerName,
+                    .timestamp = armem::Time::Now()});
+
+        if (result and result.occupancyGrid.has_value())
+        {
+            ARMARX_INFO << "Occupancy grid available!";
+
+            const auto occupancyGridSceneElements = util::asSceneObjects(
+                result.occupancyGrid.value(),
+                OccupancyGridHelper::Params{
+                    .freespaceThreshold = properties.occupancyGrid.freespaceThreshold,
+                    .occupiedThreshold = properties.occupancyGrid.occupiedThreshold});
+            ARMARX_INFO << occupancyGridSceneElements->getSize()
+                        << " scene elements from occupancy grid";
+
+            auto occupancyGridObstacles =
+                std::make_shared<VirtualRobot::SceneObjectSet>("OccupancyGridObstacles");
+            occupancyGridObstacles->addSceneObjects(occupancyGridSceneElements);
+
+            // draw
+            // auto layer = arviz.layer("occupancy_grid");
+
+            // for (const auto& sceneObject : occupancyGridSceneElements->getSceneObjects())
+            // {
+            //     const Eigen::Isometry3f world_T_obj(sceneObject->getGlobalPose());
+            //     ARMARX_INFO << world_T_obj.translation();
+            //     ARMARX_INFO << layer.size();
+            //     layer.add(viz::Box("box_" + std::to_string(layer.size()))
+            //                   .pose(world_T_obj)
+            //                   .size(result.occupancyGrid->resolution)
+            //                   .color(viz::Color::orange()));
+            // }
+
+            // ARMARX_INFO << "Creating costmap";
+
+            // algorithms::CostmapBuilder costmapBuilder(
+            //     getRobot(),
+            //     scene.objects,
+            //     algorithms::Costmap::Parameters{.binaryGrid = false, .cellSize = 100},
+            //     "Platform-navigation-colmodel");
+
+            // const auto costmap = costmapBuilder.create();
+
+            // ARMARX_INFO << "Done";
+
+            // ARMARX_TRACE;
+            // ARMARX_INFO << "Saving costmap.";
+            // algorithms::save(costmap, "/tmp/navigation-costmap");
+
+            // arviz.commit({layer});
+        }
     }
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index c6792742..c31f150f 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -27,6 +27,7 @@
 // #include <mutex>
 
 #include <VirtualRobot/VirtualRobot.h>
+
 #include "ArmarXCore/core/services/tasks/TaskUtil.h"
 #include <ArmarXCore/core/Component.h>
 
@@ -41,8 +42,11 @@
 
 // #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
 
-// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
+#include "RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h"
+#include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
+#include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
+#include "armarx/navigation/memory/client/costmap/Reader.h"
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
 
 
@@ -54,8 +58,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         virtual public armarx::navigation::components::dynamic_scene_provider::ComponentInterface,
         // , virtual public armarx::DebugObserverComponentPluginUser
         // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
-        // , virtual public armarx::ArVizComponentPluginUser
-        virtual public armarx::armem::client::plugins::PluginUser
+        virtual public armarx::ArVizComponentPluginUser,
+        virtual public armarx::armem::client::plugins::PluginUser,
+        virtual public ObjectPoseClientPluginUser
     {
     public:
         Component();
@@ -130,10 +135,20 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 std::string name = ""; // all
             } laserScannerFeatures;
 
+
             struct
             {
                 std::string name = "Armar6";
             } robot;
+
+            struct
+            {
+                std::string providerName = "CartographerMappingAndLocalization";
+                std::string name = ""; // all
+
+                float freespaceThreshold = 0.45F;
+                float occupiedThreshold = 0.55;
+            } occupancyGrid;
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
@@ -163,15 +178,21 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         PeriodicTask<Component>::pointer_type task;
 
-        armem::client::plugins::ReaderWriterPlugin<armem::human::client::Reader>*
-            humanPoseReaderPlugin = nullptr;
+        template <typename T>
+        using ReaderWriterPlugin = armem::client::plugins::ReaderWriterPlugin<T>;
+
+        ReaderWriterPlugin<armem::human::client::Reader>* humanPoseReaderPlugin = nullptr;
+
+        ReaderWriterPlugin<armem::vision::laser_scanner_features::client::Reader>*
+            laserScannerFeaturesReaderPlugin = nullptr;
 
-        armem::client::plugins::ReaderWriterPlugin<
-            armem::vision::laser_scanner_features::client::Reader>* laserScannerFeaturesReaderPlugin =
+        ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin =
             nullptr;
 
-        armem::client::plugins::ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin = nullptr;
+        ReaderWriterPlugin<memory::client::costmap::Reader>* costmapReaderPlugin = nullptr;
 
+        ReaderWriterPlugin<armem::vision::occupancy_grid::client::Reader>*
+            occupancyGridReaderPlugin = nullptr;
     };
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 92f52d8b9fb6396676e3d680f58ee0d6f7a50b9f Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 09:22:21 +0200
Subject: [PATCH 020/324] new scenario human aware navigation

---
 .../HumanAwareNavigation.scx                  |  12 +
 .../config/MemoryNameSystem.cfg               | 196 +++++
 .../config/ObjectMemory.cfg                   | 775 ++++++++++++++++++
 .../config/RemoteGuiProviderApp.cfg           | 196 +++++
 .../config/RobotStateComponent.cfg            | 316 +++++++
 .../config/VisionMemory.cfg                   | 366 +++++++++
 .../XMLRemoteStateOfferer.NavigationGroup.cfg | 227 +++++
 .../config/control_memory.cfg                 | 375 +++++++++
 .../config/example_client.cfg                 | 262 ++++++
 .../HumanAwareNavigation/config/global.cfg    |   3 +
 .../config/navigation_memory.cfg              | 393 +++++++++
 .../HumanAwareNavigation/config/navigator.cfg | 411 ++++++++++
 12 files changed, 3532 insertions(+)
 create mode 100644 scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
 create mode 100644 scenarios/HumanAwareNavigation/config/MemoryNameSystem.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/RemoteGuiProviderApp.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/VisionMemory.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/XMLRemoteStateOfferer.NavigationGroup.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/control_memory.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/example_client.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/global.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/navigation_memory.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/navigator.cfg

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
new file mode 100644
index 00000000..ae2dfe63
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -0,0 +1,12 @@
+<?xml version="1.0" encoding="utf-8"?>
+<scenario name="HumanAwareNavigation" creation="2021-07-09.11:39:42" globalConfigName="./config/global.cfg" package="armarx_navigation" deploymentType="local" nodeName="NodeMain">
+	<application name="ObjectMemory" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="RemoteGuiProviderApp" instance="" package="ArmarXGui" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="RobotStateComponent" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
+</scenario>
diff --git a/scenarios/HumanAwareNavigation/config/MemoryNameSystem.cfg b/scenarios/HumanAwareNavigation/config/MemoryNameSystem.cfg
new file mode 100644
index 00000000..b8bc70a6
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/MemoryNameSystem.cfg
@@ -0,0 +1,196 @@
+# ==================================================================
+# MemoryNameSystem properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.MemoryNameSystem.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.MemoryNameSystem.EnableProfiling = false
+
+
+# ArmarX.MemoryNameSystem.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.MemoryNameSystem.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.MemoryNameSystem.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.MemoryNameSystem.ObjectName = ""
+
+
+# ArmarX.MemoryNameSystem.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.MemoryNameSystem.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
new file mode 100644
index 00000000..579926b6
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
@@ -0,0 +1,775 @@
+# ==================================================================
+# ObjectMemory properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.ObjectMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.ObjectMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.ObjectMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.EnableProfiling = false
+
+
+# ArmarX.ObjectMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ObjectMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ObjectMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.ObjectName = ""
+
+
+# ArmarX.ObjectMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.ObjectMemory.cmp.KinematicUnitObserverName:  Name of the kinematic unit observer.
+#  Attributes:
+#  - Default:            KinematicUnitObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.cmp.KinematicUnitObserverName = KinematicUnitObserver
+
+
+# ArmarX.ObjectMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Object
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.MemoryName = Object
+
+
+# ArmarX.ObjectMemory.mem.attachments.CoreSegmentName:  Name of the object instance core segment.
+#  Attributes:
+#  - Default:            Attachments
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.attachments.CoreSegmentName = Attachments
+
+
+# ArmarX.ObjectMemory.mem.attachments.MaxHistorySize:  Maximal size of object poses history (-1 for infinite).
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.attachments.MaxHistorySize = -1
+
+
+# ArmarX.ObjectMemory.mem.cls.Floor.EntityName:  Object class entity of the floor.
+#  Attributes:
+#  - Default:            Building/floor-20x20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.Floor.EntityName = Building/floor-20x20
+
+
+# ArmarX.ObjectMemory.mem.cls.Floor.Height:  Height (z) of the floor plane. 
+# Set slightly below 0 to avoid z-fighting when drawing planes on the ground.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.Floor.Height = -1
+
+
+# ArmarX.ObjectMemory.mem.cls.Floor.LayerName:  Layer to draw the floor on.
+#  Attributes:
+#  - Default:            Floor
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.Floor.LayerName = Floor
+
+
+# ArmarX.ObjectMemory.mem.cls.Floor.Show:  Whether to show the floor.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.cls.Floor.Show = true
+
+
+# ArmarX.ObjectMemory.mem.cls.LoadFromObjectsPackage:  If true, load the objects from the objects package on startup.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.cls.LoadFromObjectsPackage = true
+
+
+# ArmarX.ObjectMemory.mem.cls.ObjectsPackage:  Name of the objects package to load from.
+#  Attributes:
+#  - Default:            PriorKnowledgeData
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.ObjectsPackage = PriorKnowledgeData
+
+
+# ArmarX.ObjectMemory.mem.cls.seg.CoreMaxHistorySize:  Maximal size of the Class entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.seg.CoreMaxHistorySize = -1
+
+
+# ArmarX.ObjectMemory.mem.cls.seg.CoreSegmentName:  Name of the Class core segment.
+#  Attributes:
+#  - Default:            Class
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.cls.seg.CoreSegmentName = Class
+
+
+# ArmarX.ObjectMemory.mem.inst.DiscardSnapshotsWhileAttached:  If true, no new snapshots are stored while an object is attached to a robot node.
+# If false, new snapshots are stored, but the attachment is kept in the new snapshots.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.DiscardSnapshotsWhileAttached = true
+
+
+# ArmarX.ObjectMemory.mem.inst.calibration.offset:  Offset for the node to be calibrated.
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.calibration.offset = 0
+
+
+# ArmarX.ObjectMemory.mem.inst.calibration.robotNode:  Robot node which can be calibrated.
+#  Attributes:
+#  - Default:            Neck_2_Pitch
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.calibration.robotNode = Neck_2_Pitch
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.delaySeconds:  Duration after latest localization before decay starts.
+#  Attributes:
+#  - Default:            5
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.decay.delaySeconds = 5
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.durationSeconds:  How long to reach minimal confidence.
+#  Attributes:
+#  - Default:            20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.decay.durationSeconds = 20
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.enabled:  If true, object poses decay over time when not localized anymore.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.decay.enabled = false
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.maxConfidence:  Confidence when decay starts.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.decay.maxConfidence = 1
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.minConfidence:  Confidence after decay duration.
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.decay.minConfidence = 0
+
+
+# ArmarX.ObjectMemory.mem.inst.decay.removeObjectsBelowConfidence:  Remove objects whose confidence is lower than this value.
+#  Attributes:
+#  - Default:            0.100000001
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.decay.removeObjectsBelowConfidence = 0.100000001
+
+
+# ArmarX.ObjectMemory.mem.inst.head.checkHeadVelocity:  If true, check whether the head is moving and discard updates in the meantime.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.head.checkHeadVelocity = true
+
+
+# ArmarX.ObjectMemory.mem.inst.head.discardIntervalAfterMoveMS:  For how long new updates are ignored after moving the head.
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.head.discardIntervalAfterMoveMS = 100
+
+
+# ArmarX.ObjectMemory.mem.inst.head.maxJointVelocity:  If a head joint's velocity is higher, the head is considered moving.
+#  Attributes:
+#  - Default:            0.0500000007
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.head.maxJointVelocity = 0.0500000007
+
+
+# ArmarX.ObjectMemory.mem.inst.scene.10_Package:  ArmarX package containing the scene snapshots.
+# Scene snapshots are expected to be located in Package/data/Package/Scenes/*.json.
+#  Attributes:
+#  - Default:            PriorKnowledgeData
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.scene.10_Package = PriorKnowledgeData
+
+
+# ArmarX.ObjectMemory.mem.inst.scene.11_Directory:  Directory in Package/data/Package/ containing the scene snapshots.
+#  Attributes:
+#  - Default:            scenes
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.scene.11_Directory = scenes
+
+
+# ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad:  Scene to load on startup (e.g. 'Scene_2021-06-24_20-20-03').
+# You can also specify paths relative to 'Package/scenes/'. 
+# You can also specify a ; separated list of scenes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = ""
+
+
+# ArmarX.ObjectMemory.mem.inst.seg.CoreMaxHistorySize:  Maximal size of the Instance entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            64
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.seg.CoreMaxHistorySize = 64
+
+
+# ArmarX.ObjectMemory.mem.inst.seg.CoreSegmentName:  Name of the Instance core segment.
+#  Attributes:
+#  - Default:            Instance
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.seg.CoreSegmentName = Instance
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.alpha:  Alpha of objects (1 = solid, 0 = transparent).
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.alpha = 1
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.alphaByConfidence:  If true, use the pose confidence as alpha (if < 1.0).
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.alphaByConfidence = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.enabled:  Enable or disable visualization of objects.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.enabled = true
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.frequenzyHz:  Frequency of visualization.
+#  Attributes:
+#  - Default:            25
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.frequenzyHz = 25
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.position:  Enable showing pose gaussians (orientation part).
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.position = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.positionDisplaced:  Displace center orientation (co)variance circle arrows along their rotation axis.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.positionDisplaced = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.positionScale:  Scaling of pose gaussians (orientation part).
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.gaussians.positionScale = 100
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.inGlobalFrame:  If true, show global poses. If false, show poses in robot frame.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.inGlobalFrame = true
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.objectFrames:  Enable showing object frames.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.objectFrames = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.objectFramesScale:  Scaling of object frames.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.objectFramesScale = 1
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.oobbs:  Enable showing oriented bounding boxes.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.oobbs = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show:  Show arrows linearly predicting object positions.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeOffset:  The offset (in seconds) to the current time to make predictions for.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeOffset = 1
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeWindow:  The time window (in seconds) into the past to perform the regression on.
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeWindow = 2
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels:  Prefer articulated object models if available.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
+
+
+# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
+
+
+# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
+# ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.storagepath = Default value not mapped.
+
+
+# ArmarX.ObjectMemory.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment:  
+#  Attributes:
+#  - Default:            Description
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment = Description
+
+
+# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment:  
+#  Attributes:
+#  - Default:            Proprioception
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment = Proprioception
+
+
+# ArmarX.ObjectMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ObjectMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ObjectMemory.prediction.TimeWindow:  Duration of time window into the past to use for predictions when requested via the PredictingMemoryInterface (in seconds).
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.prediction.TimeWindow = 2
+
+
+# ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.tpc.pub.DebugObserver = DebugObserver
+
+
+# ArmarX.ObjectMemory.tpc.sub.ObjectPoseTopic:  Name of the `ObjectPoseTopic` topic to subscribe to.
+#  Attributes:
+#  - Default:            ObjectPoseTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.tpc.sub.ObjectPoseTopic = ObjectPoseTopic
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
diff --git a/scenarios/HumanAwareNavigation/config/RemoteGuiProviderApp.cfg b/scenarios/HumanAwareNavigation/config/RemoteGuiProviderApp.cfg
new file mode 100644
index 00000000..4b6abea4
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/RemoteGuiProviderApp.cfg
@@ -0,0 +1,196 @@
+# ==================================================================
+# RemoteGuiProviderApp properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteGuiProvider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RemoteGuiProvider.EnableProfiling = false
+
+
+# ArmarX.RemoteGuiProvider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.RemoteGuiProvider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.RemoteGuiProvider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteGuiProvider.ObjectName = ""
+
+
+# ArmarX.RemoteGuiProvider.TopicName:  Name of the topic on which updates to the remote state are reported.
+#  Attributes:
+#  - Default:            RemoteGuiTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteGuiProvider.TopicName = RemoteGuiTopic
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg b/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
new file mode 100644
index 00000000..22eb7df3
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
@@ -0,0 +1,316 @@
+# ==================================================================
+# RobotStateComponent properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.RobotStateComponent.AgentName:  Name of the agent for which the sensor values are provided
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.RobotStateComponent.AgentName = Armar6
+
+
+# ArmarX.RobotStateComponent.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RobotStateComponent.EnableProfiling = false
+
+
+# ArmarX.RobotStateComponent.GlobalRobotPoseLocalizationTopicName:  Topic where the global robot pose can be reported.
+#  Attributes:
+#  - Default:            GlobalRobotPoseLocalization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.GlobalRobotPoseLocalizationTopicName = GlobalRobotPoseLocalization
+
+
+# ArmarX.RobotStateComponent.HistoryLength:  Number of entries in the robot state history
+#  Attributes:
+#  - Default:            10000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.HistoryLength = 10000
+
+
+# ArmarX.RobotStateComponent.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.RobotStateComponent.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.RobotStateComponent.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.ObjectName = ""
+
+
+# ArmarX.RobotStateComponent.PlatformTopicName:  Topic where platform state is published.
+#  Attributes:
+#  - Default:            PlatformState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.PlatformTopicName = PlatformState
+
+
+# ArmarX.RobotStateComponent.RobotFileName:  Filename of VirtualRobot robot model (e.g. robot_model.xml)
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.RobotStateComponent.RobotFileName = Armar6RT/robotmodel/Armar6-SH/Armar6-SH.xml
+
+
+# ArmarX.RobotStateComponent.RobotModelScaling:  Scaling of the robot model
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.RobotModelScaling = 1
+
+
+# ArmarX.RobotStateComponent.RobotNodeSetName:  Set of nodes that is controlled by the KinematicUnit
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.RobotStateComponent.RobotNodeSetName = Robot
+
+
+# ArmarX.RobotStateComponent.RobotStateReportingTopic:  Name of the topic on which updates of the robot state are reported.
+#  Attributes:
+#  - Default:            RobotStateUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.RobotStateReportingTopic = RobotStateUpdates
+
+
+# ArmarX.RobotStateComponent.TopicPrefix:  Prefix for the sensor value topic name.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateComponent.TopicPrefix = ""
+
+
+# ArmarX.RobotStateObserver.CreateUpdateFrequenciesChannel:  If true, an additional channel is created that shows the update frequency of every other channel in that observer.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RobotStateObserver.CreateUpdateFrequenciesChannel = false
+
+
+# ArmarX.RobotStateObserver.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RobotStateObserver.EnableProfiling = false
+
+
+# ArmarX.RobotStateObserver.MaxHistoryRecordFrequency:  The Observer history is written with this maximum frequency. Everything faster is being skipped.
+#  Attributes:
+#  - Default:            50
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateObserver.MaxHistoryRecordFrequency = 50
+
+
+# ArmarX.RobotStateObserver.MaxHistorySize:  Maximum number of entries in the Observer history
+#  Attributes:
+#  - Default:            5000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateObserver.MaxHistorySize = 5000
+
+
+# ArmarX.RobotStateObserver.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.RobotStateObserver.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.RobotStateObserver.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateObserver.ObjectName = ""
+
+
+# ArmarX.RobotStateObserver.TCPsToReport:  comma seperated list of nodesets' endeffectors, which poses and velocities that should be reported. * for all, empty for none
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateObserver.TCPsToReport = ""
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/VisionMemory.cfg b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
new file mode 100644
index 00000000..22e0d3e6
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
@@ -0,0 +1,366 @@
+# ==================================================================
+# VisionMemory properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.VisionMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.EnableProfiling = false
+
+
+# ArmarX.VisionMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.VisionMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.VisionMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.ObjectName = ""
+
+
+# ArmarX.VisionMemory.imageDepthMaxHistorySize:  
+#  Attributes:
+#  - Default:            20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.imageDepthMaxHistorySize = 20
+
+
+# ArmarX.VisionMemory.imageRGBMaxHistorySize:  
+#  Attributes:
+#  - Default:            20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.imageRGBMaxHistorySize = 20
+
+
+# ArmarX.VisionMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Vision
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.MemoryName = Vision
+
+
+# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
+
+
+# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
+# ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.storagepath = Default value not mapped.
+
+
+# ArmarX.VisionMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.VisionMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.VisionMemory.occupancyGridMaxHistorySize:  
+#  Attributes:
+#  - Default:            20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.occupancyGridMaxHistorySize = 20
+
+
+# ArmarX.VisionMemory.pointCloudMaxHistorySize:  
+#  Attributes:
+#  - Default:            20
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.pointCloudMaxHistorySize = 20
+
+
diff --git a/scenarios/HumanAwareNavigation/config/XMLRemoteStateOfferer.NavigationGroup.cfg b/scenarios/HumanAwareNavigation/config/XMLRemoteStateOfferer.NavigationGroup.cfg
new file mode 100644
index 00000000..f366c706
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/XMLRemoteStateOfferer.NavigationGroup.cfg
@@ -0,0 +1,227 @@
+# ==================================================================
+# XMLRemoteStateOfferer properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.ApplicationName = NavigationGroupApp
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_USER_CONFIG_DIR is set, the cache path will be made relative to ARMARX_USER_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${HOME}/.armarx)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Debug
+
+
+# ArmarX.XMLStateComponent.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.XMLStateComponent.EnableProfiling = false
+
+
+# ArmarX.XMLStateComponent.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.XMLStateComponent.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.XMLStateComponent.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.XMLStateComponent.ObjectName = NavigationGroupXMLStateComponent
+
+
+# ArmarX.XMLStateComponent.StateReportingTopic:  Topic on which state changes are published. Leave empty to disable reporting.
+#  Attributes:
+#  - Default:            StateReportingTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.XMLStateComponent.StateReportingTopic = StateReportingTopic
+
+
+# ArmarX.XMLStateComponent.StatesToEnter:  List of states that are directly entered and executed. Seperated by comma. These must not need any input parameters!
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.XMLStateComponent.StatesToEnter = NavigateToLocation
+
+
+# ArmarX.XMLStateComponent.XMLRemoteStateOffererName:  Name of the RemoteStateOfferer to start. The default name is [StatechartGroupName]RemoteStateOfferer.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.XMLStateComponent.XMLRemoteStateOffererName = ""
+
+
+# ArmarX.XMLStateComponent.XMLStatechartGroupDefinitionFile:  Path to statechart group definition file (*.scgxml) - relative to projects' source dir
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.XMLStateComponent.XMLStatechartGroupDefinitionFile = armarx/navigation/statecharts/NavigationGroup/NavigationGroup.scgxml
+
+
+# ArmarX.XMLStateComponent.XMLStatechartProfile:  Profile to use for state execution. Should be the same for all Statechart Groups in one scenario. This profile name is also added as a prefix to the Ice identifier of the RemoteStateOfferer of this statechart group.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.XMLStateComponent.XMLStatechartProfile = Armar3a
+
+
diff --git a/scenarios/HumanAwareNavigation/config/control_memory.cfg b/scenarios/HumanAwareNavigation/config/control_memory.cfg
new file mode 100644
index 00000000..0d5c0948
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/control_memory.cfg
@@ -0,0 +1,375 @@
+# ==================================================================
+# control_memory properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.EnableProfiling = false
+
+
+# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ObjectName = ""
+
+
+# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Control
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.MemoryName = Control
+
+
+# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq = 10
+
+
+# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.ControlMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.enabled = false
+
+
+# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled = true
+
+
+# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
+# ArmarX.ControlMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.storagepath = Default value not mapped.
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
+
+
+# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.snapshotToLoad = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
new file mode 100644
index 00000000..ba425c4c
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -0,0 +1,262 @@
+# ==================================================================
+# example_client properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.ExampleClient.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ExampleClient.EnableProfiling = false
+
+
+# ArmarX.ExampleClient.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ExampleClient.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ExampleClient.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.ObjectName = ""
+
+
+# ArmarX.ExampleClient.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.ExampleClient.mem.robot_state.descriptionSegment:  
+#  Attributes:
+#  - Default:            Description
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.descriptionSegment = Description
+
+
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment:  
+#  Attributes:
+#  - Default:            Proprioception
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment = Proprioception
+
+
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
+#  Attributes:
+#  - Default:            navigator
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.ExampleClient.nav.NavigatorName = navigator
+
+
+# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.relativeMovement = 200
+
+
+# ArmarX.ExampleClient.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.robotName = Armar6
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/global.cfg b/scenarios/HumanAwareNavigation/config/global.cfg
new file mode 100644
index 00000000..4fe03bb6
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/global.cfg
@@ -0,0 +1,3 @@
+# ==================================================================
+# Global Config from Scenario HumanAwareNavigation
+# ==================================================================
diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
new file mode 100644
index 00000000..8e727c26
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -0,0 +1,393 @@
+# ==================================================================
+# navigation_memory properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.NavigationMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.NavigationMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.NavigationMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.EnableProfiling = false
+
+
+# ArmarX.NavigationMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.NavigationMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.ObjectName = ""
+
+
+# ArmarX.NavigationMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.NavigationMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.MemoryName = Navigation
+
+
+# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq = 10
+
+
+# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.NavigationMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.enabled = false
+
+
+# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled = true
+
+
+# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
+# ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.storagepath = Default value not mapped.
+
+
+# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.NavigationMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.NavigationMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.p.locationGraph.visuFrequency = 2
+
+
+# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges = true
+
+
+# ArmarX.NavigationMemory.p.locationGraph.visuLocation:  Enable visualization of locations.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.p.locationGraph.visuLocation = true
+
+
+# ArmarX.NavigationMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
new file mode 100644
index 00000000..d481cf59
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -0,0 +1,411 @@
+# ==================================================================
+# navigator properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.Navigator.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.Navigator.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.Navigator.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.Navigator.EnableProfiling = false
+
+
+# ArmarX.Navigator.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Navigator.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.Navigator.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.ObjectMemoryName = ObjectMemory
+
+
+# ArmarX.Navigator.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.Navigator.ObjectName = navigator
+
+
+# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.Navigator.RobotUnitName = Armar6Unit
+
+
+# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+#  Attributes:
+#  - Default:            Armar6PlatformUnit
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
+
+
+# ArmarX.Navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.cmp.RemoteGui = RemoteGuiProvider
+
+
+# ArmarX.Navigator.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.Navigator.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.Navigator.mem.nav.costmap.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.costmap.Provider = ""
+
+
+# ArmarX.Navigator.mem.nav.events.CoreSegment:  
+#  Attributes:
+#  - Default:            Events
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.events.CoreSegment = Events
+
+
+# ArmarX.Navigator.mem.nav.events.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.events.Memory = Navigation
+
+
+# ArmarX.Navigator.mem.nav.events.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.events.Provider = ""
+
+
+# ArmarX.Navigator.mem.nav.graph.CoreSegment:  
+#  Attributes:
+#  - Default:            Location
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.graph.CoreSegment = Location
+
+
+# ArmarX.Navigator.mem.nav.graph.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.graph.Memory = Navigation
+
+
+# ArmarX.Navigator.mem.nav.param.CoreSegment:  
+#  Attributes:
+#  - Default:            Parameterization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.param.CoreSegment = Parameterization
+
+
+# ArmarX.Navigator.mem.nav.param.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.param.Memory = Navigation
+
+
+# ArmarX.Navigator.mem.nav.param.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.param.Provider = ""
+
+
+# ArmarX.Navigator.mem.nav.stack_result.CoreSegment:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.stack_result.CoreSegment = ""
+
+
+# ArmarX.Navigator.mem.nav.stack_result.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.stack_result.Memory = Navigation
+
+
+# ArmarX.Navigator.mem.nav.stack_result.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
+
+
+# ArmarX.Navigator.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.Navigator.mem.robot_state.descriptionSegment:  
+#  Attributes:
+#  - Default:            Description
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.robot_state.descriptionSegment = Description
+
+
+# ArmarX.Navigator.mem.robot_state.localizationSegment:  
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.Navigator.mem.robot_state.proprioceptionSegment:  
+#  Attributes:
+#  - Default:            Proprioception
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.robot_state.proprioceptionSegment = Proprioception
+
+
+# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.Navigator.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.Navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
+#  Attributes:
+#  - Default:            0.550000012
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
+# ArmarX.Navigator.p.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.p.robotName = Armar6
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Verbose
-- 
GitLab


From 511646c40187332ebe2a7ceeff028ca586d3cc79 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 12:03:03 +0200
Subject: [PATCH 021/324] scenario update

---
 .../HumanAwareNavigation.scx                  |   5 +-
 .../config/ObjectMemory.cfg                   | 125 +-----
 .../config/VisionMemory.cfg                   |  97 +----
 .../config/control_memory.cfg                 | 371 -----------------
 ..._distance_to_obstacle_costmap_provider.cfg | 270 +++++++++++++
 .../config/dynamic_scene_provider.cfg         | 374 ++++++++++++++++++
 .../config/example_client.cfg                 |  18 +-
 .../HumanAwareNavigation/config/global.cfg    |   1 +
 .../config/navigation_memory.cfg              | 103 +----
 .../HumanAwareNavigation/config/navigator.cfg |  28 +-
 ...ulatedObjectLocalizerDynamicSimulation.cfg |   8 +
 .../HandUnitDynamicSimulationApp.LeftHand.cfg |  17 -
 ...HandUnitDynamicSimulationApp.RightHand.cfg |  17 -
 .../config/ObjectMemory.cfg                   | 115 +-----
 .../SelfLocalizationDynamicSimulationApp.cfg  |  18 +-
 .../config/SimulatorViewerApp.cfg             |  74 +++-
 .../config/VisionMemory.cfg                   |  97 +----
 .../config/ObjectMemory.cfg                   |  10 +
 .../config/VisionMemory.cfg                   |  16 +
 .../config/control_memory.cfg                 | 371 -----------------
 .../config/example_client.cfg                 |  68 +---
 .../config/navigation_memory.cfg              |  97 +----
 .../PlatformNavigation/config/navigator.cfg   |  21 +-
 23 files changed, 824 insertions(+), 1497 deletions(-)
 create mode 100644 scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
index ae2dfe63..3c4d6c5a 100644
--- a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -6,7 +6,10 @@
 	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="dynamic_scene_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
+
diff --git a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
index 579926b6..2af60bde 100644
--- a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
+++ b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
@@ -513,74 +513,21 @@
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.ObjectMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.ObjectMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..enabled = false
 
 
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -591,40 +538,6 @@
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -641,15 +554,7 @@
 # ArmarX.ObjectMemory.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  
+# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -657,14 +562,6 @@
 # ArmarX.ObjectMemory.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.ObjectMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
@@ -691,6 +588,14 @@
 # ArmarX.ObjectMemory.prediction.TimeWindow = 2
 
 
+# ArmarX.ObjectMemory.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.robotName = Armar6
+
+
 # ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
 #  Attributes:
 #  - Default:            DebugObserver
@@ -773,3 +678,5 @@
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/VisionMemory.cfg b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
index 22e0d3e6..4c7327ed 100644
--- a/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
+++ b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
@@ -210,74 +210,21 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.VisionMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.VisionMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..enabled = false
 
 
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -288,40 +235,6 @@
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
diff --git a/scenarios/HumanAwareNavigation/config/control_memory.cfg b/scenarios/HumanAwareNavigation/config/control_memory.cfg
index 0d5c0948..dd21987d 100644
--- a/scenarios/HumanAwareNavigation/config/control_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/control_memory.cfg
@@ -2,374 +2,3 @@
 # control_memory properties
 # ==================================================================
 
-# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.AdditionalPackages = Default value not mapped.
-
-
-# ArmarX.ApplicationName:  Application name
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ApplicationName = ""
-
-
-# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
-#  Attributes:
-#  - Default:            mongo/.cache
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.CachePath = mongo/.cache
-
-
-# ArmarX.Config:  Comma-separated list of configuration files 
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Config = ""
-
-
-# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
-#  Attributes:
-#  - Default:            ArVizStorage
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
-
-
-# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
-#  Attributes:
-#  - Default:            ArVizTopic
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
-
-
-# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.EnableProfiling = false
-
-
-# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ObjectName = ""
-
-
-# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
-#  Attributes:
-#  - Default:            RemoteGuiProvider
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
-
-
-# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
-#  Attributes:
-#  - Default:            Control
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.MemoryName = Control
-
-
-# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
-#  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.storagepath = Default value not mapped.
-
-
-# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
-
-
-# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
-#  Attributes:
-#  - Default:            2
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
-
-
-# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.p.snapshotToLoad = ""
-
-
-# ArmarX.DataPath:  Semicolon-separated search list for data files
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DataPath = ""
-
-
-# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DefaultPackages = Default value not mapped.
-
-
-# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
-#  Attributes:
-#  - Default:            ./config/dependencies.cfg
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DependenciesConfig = ./config/dependencies.cfg
-
-
-# ArmarX.DisableLogging:  Turn logging off in whole application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.DisableLogging = false
-
-
-# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.EnableProfiling = false
-
-
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoadLibraries = ""
-
-
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoggingGroup = ""
-
-
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
-
-
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
-#  Attributes:
-#  - Default:            3000
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
-
-
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
-
-
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
-
-
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ThreadPoolSize = 1
-
-
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.TopicSuffix = ""
-
-
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
-
-
-# ArmarX.Verbosity:  Global logging level for whole application
-#  Attributes:
-#  - Default:            Info
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
-
-
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
new file mode 100644
index 00000000..27479d20
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
@@ -0,0 +1,270 @@
+# ==================================================================
+# dynamic_distance_to_obstacle_costmap_provider properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.EnableProfiling = false
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ObjectName = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.CoreSegment:  Name of the mapping memory core segment to use.
+#  Attributes:
+#  - Default:            LaserScannerFeatures
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.CoreSegment = LaserScannerFeatures
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.MemoryName:  
+#  Attributes:
+#  - Default:            Vision
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.MemoryName = Vision
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs:  
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs = 100
+
+
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
new file mode 100644
index 00000000..98cd68b7
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
@@ -0,0 +1,374 @@
+# ==================================================================
+# dynamic_scene_provider properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.dynamic_scene_provider.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.dynamic_scene_provider.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.dynamic_scene_provider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_scene_provider.EnableProfiling = false
+
+
+# ArmarX.dynamic_scene_provider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.dynamic_scene_provider.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.ObjectMemoryName = ObjectMemory
+
+
+# ArmarX.dynamic_scene_provider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.ObjectName = ""
+
+
+# ArmarX.dynamic_scene_provider.mem.human.pose.CoreSegment:  
+#  Attributes:
+#  - Default:            Pose
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.human.pose.CoreSegment = Pose
+
+
+# ArmarX.dynamic_scene_provider.mem.human.pose.Memory:  
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.human.pose.Memory = Human
+
+
+# ArmarX.dynamic_scene_provider.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.dynamic_scene_provider.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.dynamic_scene_provider.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.dynamic_scene_provider.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.dynamic_scene_provider.mem.vision.laser_scanner_features.CoreSegment:  Name of the mapping memory core segment to use.
+#  Attributes:
+#  - Default:            LaserScannerFeatures
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.vision.laser_scanner_features.CoreSegment = LaserScannerFeatures
+
+
+# ArmarX.dynamic_scene_provider.mem.vision.laser_scanner_features.MemoryName:  
+#  Attributes:
+#  - Default:            Vision
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.vision.laser_scanner_features.MemoryName = Vision
+
+
+# ArmarX.dynamic_scene_provider.mem.vision.occupancy_grid.CoreSegment:  
+#  Attributes:
+#  - Default:            OccupancyGrid
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.vision.occupancy_grid.CoreSegment = OccupancyGrid
+
+
+# ArmarX.dynamic_scene_provider.mem.vision.occupancy_grid.Memory:  
+#  Attributes:
+#  - Default:            Vision
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.vision.occupancy_grid.Memory = Vision
+
+
+# ArmarX.dynamic_scene_provider.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_scene_provider.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.dynamic_scene_provider.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.dynamic_scene_provider.p.laserScannerFeatures.name:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.laserScannerFeatures.name = ""
+
+
+# ArmarX.dynamic_scene_provider.p.laserScannerFeatures.providerName:  
+#  Attributes:
+#  - Default:            LaserScannerFeatureExtraction
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.laserScannerFeatures.providerName = LaserScannerFeatureExtraction
+
+
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.freespaceThreshold:  
+#  Attributes:
+#  - Default:            0.449999988
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.freespaceThreshold = 0.449999988
+
+
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.name:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.name = ""
+
+
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.occupiedThreshold:  
+#  Attributes:
+#  - Default:            0.550000012
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.occupiedThreshold = 0.550000012
+
+
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.providerName:  
+#  Attributes:
+#  - Default:            CartographerMappingAndLocalization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.occupancyGrid.providerName = CartographerMappingAndLocalization
+
+
+# ArmarX.dynamic_scene_provider.p.robot.name:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.robot.name = Armar6
+
+
+# ArmarX.dynamic_scene_provider.p.taskPeriodMs:  Update rate of the running task.
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.taskPeriodMs = 100
+
+
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
index ba425c4c..eef85301 100644
--- a/scenarios/HumanAwareNavigation/config/example_client.cfg
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -110,15 +110,7 @@
 # ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -126,14 +118,6 @@
 # ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
diff --git a/scenarios/HumanAwareNavigation/config/global.cfg b/scenarios/HumanAwareNavigation/config/global.cfg
index 4fe03bb6..b127ca30 100644
--- a/scenarios/HumanAwareNavigation/config/global.cfg
+++ b/scenarios/HumanAwareNavigation/config/global.cfg
@@ -1,3 +1,4 @@
 # ==================================================================
 # Global Config from Scenario HumanAwareNavigation
 # ==================================================================
+
diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index 8e727c26..aeb9f55b 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -123,7 +123,7 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.NavigationMemory.MinimumLoggingLevel = Undefined
+ArmarX.NavigationMemory.MinimumLoggingLevel = Verbose
 
 
 # ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
@@ -150,74 +150,21 @@
 # ArmarX.NavigationMemory.mem.MemoryName = Navigation
 
 
-# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.NavigationMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.NavigationMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.NavigationMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.NavigationMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.NavigationMemory.mem.ltm..enabled = false
 
 
 # ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -228,40 +175,6 @@
 # ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -320,7 +233,7 @@
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+# ArmarX.NavigationMemory.p.snapshotToLoad = ""
 
 
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
@@ -388,6 +301,6 @@ ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graph
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+ArmarX.Verbosity = Verbose
 
 
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index d481cf59..f6a497b2 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -285,15 +285,7 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.Navigator.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  
+# ArmarX.Navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -301,14 +293,6 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
@@ -335,14 +319,6 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
-# ArmarX.Navigator.p.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.p.robotName = Armar6
-
-
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -409,3 +385,5 @@ ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 ArmarX.Verbosity = Verbose
+
+
diff --git a/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg b/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
index 7c4574e0..a64fd58d 100644
--- a/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
+++ b/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
@@ -133,6 +133,14 @@ ArmarX.ArticulatedObjectLocalizerDynamicSimulation.mem.obj.articulated.ProviderN
 # ArmarX.ArticulatedObjectLocalizerDynamicSimulation.objects = Default value not mapped.
 
 
+# ArmarX.ArticulatedObjectLocalizerDynamicSimulation.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
+#  Attributes:
+#  - Default:            MemoryUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ArticulatedObjectLocalizerDynamicSimulation.tpc.sub.MemoryListener = MemoryUpdates
+
+
 # ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
 #  Attributes:
 #  - Default:            mongo/.cache
diff --git a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
index aa21b8fd..18e2d2db 100644
--- a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
+++ b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
@@ -139,23 +139,6 @@ ArmarX.HandUnitDynamicSimulation.ObjectName = LeftHandUnit
 # ArmarX.HandUnitDynamicSimulation.SimulatorProxyName = Simulator
 
 
-# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory:  Require the legacy MemoryX working memory to be available before starting.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory = false
-
-
-# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName:  Name of the object pose storage (only used if necessary).
-#  Attributes:
-#  - Default:            ObjectMemory
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName = ObjectMemory
-
-
 # ArmarX.HandUnitDynamicSimulation.inheritFrom:  No Description
 #  Attributes:
 #  - Default:            RobotConfig
diff --git a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
index b92bb000..85cc4345 100644
--- a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
+++ b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
@@ -139,23 +139,6 @@ ArmarX.HandUnitDynamicSimulation.ObjectName = RightHandUnit
 # ArmarX.HandUnitDynamicSimulation.SimulatorProxyName = Simulator
 
 
-# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory:  Require the legacy MemoryX working memory to be available before starting.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory = false
-
-
-# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName:  Name of the object pose storage (only used if necessary).
-#  Attributes:
-#  - Default:            ObjectMemory
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName = ObjectMemory
-
-
 # ArmarX.HandUnitDynamicSimulation.inheritFrom:  No Description
 #  Attributes:
 #  - Default:            RobotConfig
diff --git a/scenarios/NavigationSimulation/config/ObjectMemory.cfg b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
index 57b383ba..ed320714 100644
--- a/scenarios/NavigationSimulation/config/ObjectMemory.cfg
+++ b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
@@ -513,74 +513,21 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.ObjectMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.ObjectMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..enabled = false
 
 
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -591,40 +538,6 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -641,15 +554,7 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  
+# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -657,14 +562,6 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.ObjectMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
diff --git a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
index 23b096b3..1dab8f00 100644
--- a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
+++ b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
@@ -175,6 +175,14 @@ ArmarX.SelfLocalizationDynamicSimulation.RobotName = Armar6
 # ArmarX.SelfLocalizationDynamicSimulation.cmp.Simulator = Simulator
 
 
+# ArmarX.SelfLocalizationDynamicSimulation.cmp.WorkingMemory:  Ice object name of the `WorkingMemory` component.
+#  Attributes:
+#  - Default:            WorkingMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SelfLocalizationDynamicSimulation.cmp.WorkingMemory = WorkingMemory
+
+
 # ArmarX.SelfLocalizationDynamicSimulation.cycleTime:  
 #  Attributes:
 #  - Default:            30
@@ -183,7 +191,7 @@ ArmarX.SelfLocalizationDynamicSimulation.RobotName = Armar6
 # ArmarX.SelfLocalizationDynamicSimulation.cycleTime = 30
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.longterm_memory:  Which legacy long-term memory to use if longterm_memory.updateor longterm_memory.retrieve_initial_pose are set
+# ArmarX.SelfLocalizationDynamicSimulation.longterm_memory:  Ice object name of the `LongtermMemory` component.
 #  Attributes:
 #  - Default:            LongtermMemory
 #  - Case sensitivity:   yes
@@ -299,6 +307,14 @@ ArmarX.SelfLocalizationDynamicSimulation.mem.robot_state.Memory = RobotState
 # ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.PlatformUnit = PlatformUnit
 
 
+# ArmarX.SelfLocalizationDynamicSimulation.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
+#  Attributes:
+#  - Default:            MemoryUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SelfLocalizationDynamicSimulation.tpc.sub.MemoryListener = MemoryUpdates
+
+
 # ArmarX.SelfLocalizationDynamicSimulation.working_memory.update:  If enabled, updates the global pose in the working memory
 #  Attributes:
 #  - Default:            true
diff --git a/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg b/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
index 74604be7..d514a485 100644
--- a/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
+++ b/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
@@ -117,14 +117,73 @@
 # ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel:  No Description
+# ArmarX.SimulatorViewer_EntityDrawer.CommonStorageName:  Name of the the CommonStorage memory component
 #  Attributes:
-#  - Default:            Verbose
-#  - Case sensitivity:   no
+#  - Default:            CommonStorage
+#  - Case sensitivity:   yes
 #  - Required:           no
+# ArmarX.SimulatorViewer_EntityDrawer.CommonStorageName = CommonStorage
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerSelectionTopic:  Name of the DebugDrawerSelectionTopic
+#  Attributes:
+#  - Default:            DebugDrawerSelections
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerSelectionTopic = DebugDrawerSelections
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerTopic:  Name of the DebugDrawerTopic
+#  Attributes:
+#  - Default:            DebugDrawerUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerTopic = DebugDrawerUpdates
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimulatorViewer_EntityDrawer.EnableProfiling = false
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel = Verbose
 
 
+# ArmarX.SimulatorViewer_EntityDrawer.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulatorViewer_EntityDrawer.ObjectName = ""
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.PriorKnowledgeName:  Name of the the PriorKnowledge memory component
+#  Attributes:
+#  - Default:            PriorKnowledge
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulatorViewer_EntityDrawer.PriorKnowledgeName = PriorKnowledge
+
+
+# ArmarX.SimulatorViewer_EntityDrawer.ShowDebugDrawing:  The simulator implements the DebugDrawerInterface. The debug visualizations (e.g. coordinate systems) can enabled/disbaled with this flag.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimulatorViewer_EntityDrawer.ShowDebugDrawing = true
+
+
 # ArmarX.SimulatorViewer_PhysicsWorldVisualization.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
@@ -324,15 +383,6 @@ ArmarX.SimulatorViewer_SimulationWindow.Camera.z = 6000
 # ArmarX.UpdateRate = 30
 
 
-# ArmarX.UseDebugDrawer:  Whether to create the debug drawer component for the viewer.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseDebugDrawer = false
-
-
 # ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
 #  - Default:            false
diff --git a/scenarios/NavigationSimulation/config/VisionMemory.cfg b/scenarios/NavigationSimulation/config/VisionMemory.cfg
index 22e0d3e6..4c7327ed 100644
--- a/scenarios/NavigationSimulation/config/VisionMemory.cfg
+++ b/scenarios/NavigationSimulation/config/VisionMemory.cfg
@@ -210,74 +210,21 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.VisionMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.VisionMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..enabled = false
 
 
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -288,40 +235,6 @@
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index 579926b6..5e0858b9 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -691,6 +691,14 @@
 # ArmarX.ObjectMemory.prediction.TimeWindow = 2
 
 
+# ArmarX.ObjectMemory.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.robotName = Armar6
+
+
 # ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
 #  Attributes:
 #  - Default:            DebugObserver
@@ -773,3 +781,5 @@
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/PlatformNavigation/config/VisionMemory.cfg b/scenarios/PlatformNavigation/config/VisionMemory.cfg
index 22e0d3e6..9c59a9f6 100644
--- a/scenarios/PlatformNavigation/config/VisionMemory.cfg
+++ b/scenarios/PlatformNavigation/config/VisionMemory.cfg
@@ -364,3 +364,19 @@
 # ArmarX.VisionMemory.pointCloudMaxHistorySize = 20
 
 
+# ArmarX.VisionMemory.tpc.pub.MemoryListener:  Name of the `MemoryListener` topic to publish data to.
+#  Attributes:
+#  - Default:            MemoryUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.tpc.pub.MemoryListener = MemoryUpdates
+
+
+# ArmarX.VisionMemory.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
+#  Attributes:
+#  - Default:            MemoryUpdates
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.tpc.sub.MemoryListener = MemoryUpdates
+
+
diff --git a/scenarios/PlatformNavigation/config/control_memory.cfg b/scenarios/PlatformNavigation/config/control_memory.cfg
index 0d5c0948..dd21987d 100644
--- a/scenarios/PlatformNavigation/config/control_memory.cfg
+++ b/scenarios/PlatformNavigation/config/control_memory.cfg
@@ -2,374 +2,3 @@
 # control_memory properties
 # ==================================================================
 
-# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.AdditionalPackages = Default value not mapped.
-
-
-# ArmarX.ApplicationName:  Application name
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ApplicationName = ""
-
-
-# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
-#  Attributes:
-#  - Default:            mongo/.cache
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.CachePath = mongo/.cache
-
-
-# ArmarX.Config:  Comma-separated list of configuration files 
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Config = ""
-
-
-# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
-#  Attributes:
-#  - Default:            ArVizStorage
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
-
-
-# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
-#  Attributes:
-#  - Default:            ArVizTopic
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
-
-
-# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.EnableProfiling = false
-
-
-# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.ObjectName = ""
-
-
-# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
-#  Attributes:
-#  - Default:            RemoteGuiProvider
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
-
-
-# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
-#  Attributes:
-#  - Default:            Control
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.MemoryName = Control
-
-
-# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
-#  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.imageExtractor.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.pngConverter.Enabled = true
-
-
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ControlMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.storagepath = Default value not mapped.
-
-
-# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
-
-
-# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
-#  Attributes:
-#  - Default:            2
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
-
-
-# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.p.snapshotToLoad = ""
-
-
-# ArmarX.DataPath:  Semicolon-separated search list for data files
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DataPath = ""
-
-
-# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DefaultPackages = Default value not mapped.
-
-
-# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
-#  Attributes:
-#  - Default:            ./config/dependencies.cfg
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DependenciesConfig = ./config/dependencies.cfg
-
-
-# ArmarX.DisableLogging:  Turn logging off in whole application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.DisableLogging = false
-
-
-# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.EnableProfiling = false
-
-
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoadLibraries = ""
-
-
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoggingGroup = ""
-
-
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
-
-
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
-#  Attributes:
-#  - Default:            3000
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
-
-
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
-
-
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
-
-
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ThreadPoolSize = 1
-
-
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.TopicSuffix = ""
-
-
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
-
-
-# ArmarX.Verbosity:  Global logging level for whole application
-#  Attributes:
-#  - Default:            Info
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
-
-
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index ba425c4c..fa27dee3 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -102,80 +102,14 @@
 # ArmarX.ExampleClient.ObjectName = ""
 
 
-# ArmarX.ExampleClient.mem.robot_state.Memory:  
-#  Attributes:
-#  - Default:            RobotState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
-
-
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  
-#  Attributes:
-#  - Default:            Localization
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
-
-
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment = Proprioception
-
-
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
-
-
 # ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
-#  - Default:            navigator
+#  - Default:            Navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
-# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
-#  Attributes:
-#  - Default:            200
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.relativeMovement = 200
-
-
-# ArmarX.ExampleClient.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.robotName = Armar6
-
-
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index 8e727c26..d66f1082 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -150,74 +150,21 @@
 # ArmarX.NavigationMemory.mem.MemoryName = Navigation
 
 
-# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.NavigationMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.NavigationMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.NavigationMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.NavigationMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.NavigationMemory.mem.ltm..enabled = false
 
 
 # ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -228,40 +175,6 @@
 # ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index d481cf59..0501ba1e 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -142,17 +142,18 @@
 ArmarX.Navigator.ObjectName = navigator
 
 
-# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+# ArmarX.Navigator.RobotUnitName:  No Description
 #  Attributes:
-#  - Case sensitivity:   yes
-#  - Required:           yes
+#  - Default:            Armar6Unit
+#  - Case sensitivity:   no
+#  - Required:           no
 ArmarX.Navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+# ArmarX.Navigator.cmp.PlatformUnit:  Ice object name of the `PlatformUnit` component.
 #  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
+#  - Default:            PlatformUnit
+#  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 
@@ -335,12 +336,12 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
-# ArmarX.Navigator.p.robotName:  
+# ArmarX.Navigator.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
 #  Attributes:
-#  - Default:            Armar6
+#  - Default:            MemoryUpdates
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.p.robotName = Armar6
+# ArmarX.Navigator.tpc.sub.MemoryListener = MemoryUpdates
 
 
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
@@ -409,3 +410,5 @@ ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 ArmarX.Verbosity = Verbose
+
+
-- 
GitLab


From a8c9c8f18ebc2fd99bf207f7723227f3e163b421 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 12:04:36 +0200
Subject: [PATCH 022/324] json at() instead of []

---
 .../navigation/algorithms/persistence.cpp     | 38 ++++++++++---------
 .../algorithms/test/algorithms_spfa_test.cpp  |  4 +-
 .../NavigationMemory/NavigationMemory.cpp     |  8 +++-
 .../NavigationMemory/NavigationMemory.h       |  3 +-
 4 files changed, 29 insertions(+), 24 deletions(-)

diff --git a/source/armarx/navigation/algorithms/persistence.cpp b/source/armarx/navigation/algorithms/persistence.cpp
index 7b55a46e..a7c0e965 100644
--- a/source/armarx/navigation/algorithms/persistence.cpp
+++ b/source/armarx/navigation/algorithms/persistence.cpp
@@ -48,20 +48,22 @@ namespace armarx::navigation::algorithms
     load(const std::filesystem::path& directory)
     {
         // load
-        std::ifstream ifs(directory / "costmap.json");
+        const auto filename = directory / "costmap.json";
+        std::ifstream ifs(filename);
+        ARMARX_VERBOSE << "Loading costmap info " << filename.string();
         const nlohmann::json j = nlohmann::json::parse(ifs);
 
         // params
-        const auto& jParam = j["params"];
+        const auto& jParam = j.at("params");
 
-        const Costmap::Parameters params{.binaryGrid = jParam["binary_grid"],
-                                         .cellSize = jParam["cell_size"]};
+        const Costmap::Parameters params{.binaryGrid = jParam.at("binary_grid"),
+                                         .cellSize = jParam.at("cell_size")};
 
         // scene bounds
-        const auto& jSceneBounds = j["scene_bounds"];
+        const auto& jSceneBounds = j.at("scene_bounds");
 
-        const std::vector<float> boundsMin = jSceneBounds["min"];
-        const std::vector<float> boundsMax = jSceneBounds["max"];
+        const std::vector<float> boundsMin = jSceneBounds.at("min");
+        const std::vector<float> boundsMax = jSceneBounds.at("max");
 
         ARMARX_CHECK_EQUAL(boundsMin.size(), 2);
         ARMARX_CHECK_EQUAL(boundsMax.size(), 2);
@@ -71,7 +73,7 @@ namespace armarx::navigation::algorithms
 
 
         // grid
-        const std::string gridFilename = j["grid_filename"];
+        const std::string gridFilename = j.at("grid_filename");
         cv::Mat gridMat = cv::imread((directory / gridFilename).string(), cv::IMREAD_ANYCOLOR | cv::IMREAD_ANYDEPTH);
 
         Eigen::MatrixXf grid;
@@ -79,9 +81,9 @@ namespace armarx::navigation::algorithms
 
         // mask, if any
         std::optional<Costmap::Mask> optMask;
-        if (not j["mask_filename"].empty())
+        if (not j.at("mask_filename").empty())
         {
-            const std::string maskFilename = j["grid_filename"];
+            const std::string maskFilename = j.at("grid_filename");
             cv::Mat maskMat = cv::imread((directory / maskFilename).string(), cv::IMREAD_ANYCOLOR | cv::IMREAD_ANYDEPTH);
 
             Eigen::Matrix<std::uint8_t, Eigen::Dynamic, Eigen::Dynamic> mask;
@@ -111,17 +113,17 @@ namespace armarx::navigation::algorithms
 
         // params
         {
-            auto& jParam = j["params"];
-            jParam["binary_grid"] = costmap.params().binaryGrid;
-            jParam["cell_size"] = costmap.params().cellSize;
+            auto& jParam = j.at("params");
+            jParam.at("binary_grid") = costmap.params().binaryGrid;
+            jParam.at("cell_size") = costmap.params().cellSize;
         }
 
         // scene bounds
         {
-            auto& jSceneBounds = j["scene_bounds"];
-            jSceneBounds["min"] = std::vector<float>{costmap.getLocalSceneBounds().min.x(),
+            auto& jSceneBounds = j.at("scene_bounds");
+            jSceneBounds.at("min") = std::vector<float>{costmap.getLocalSceneBounds().min.x(),
                                                      costmap.getLocalSceneBounds().min.y()};
-            jSceneBounds["max"] = std::vector<float>{costmap.getLocalSceneBounds().max.x(),
+            jSceneBounds.at("max") = std::vector<float>{costmap.getLocalSceneBounds().max.x(),
                                                      costmap.getLocalSceneBounds().max.y()};
         }
 
@@ -135,7 +137,7 @@ namespace armarx::navigation::algorithms
             const std::string gridFilename = "grid.exr";
             cv::imwrite((directory / gridFilename).string(), grid);
 
-            j["grid_filename"] = gridFilename;
+            j.at("grid_filename") = gridFilename;
 
             // for debugging purpose, also save a png image
             const std::string gridDebuggingFilename = "grid.png";
@@ -160,7 +162,7 @@ namespace armarx::navigation::algorithms
                 const std::string maskFilename = "mask.ppm";
                 cv::imwrite((directory / maskFilename).string(), mask);
 
-                j["mask_filename"] = maskFilename;
+                j.at("mask_filename") = maskFilename;
             }
         }
 
diff --git a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
index 6a0db3eb..74baecbd 100644
--- a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
+++ b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
@@ -155,7 +155,7 @@ BOOST_AUTO_TEST_CASE(testGrid)
     std::ifstream fs(testExrMetaFilename);
     auto j = nlohmann::json::parse(fs);
 
-    const float cellSize = j["cell_size"]; // [mm]
+    const float cellSize = j.at("cell_size"); // [mm]
     BOOST_REQUIRE_GT(cellSize, 0);
 
     std::vector<float> sceneBoundsMinV(j["scene_bounds"]["min"]);
@@ -209,7 +209,7 @@ BOOST_AUTO_TEST_CASE(testSPFAPlanWObstacleDistance)
     std::ifstream fs(testExrMetaFilename);
     const auto j = nlohmann::json::parse(fs);
 
-    const float cellSize = j["cell_size"]; // [mm]
+    const float cellSize = j.at("cell_size"); // [mm]
     BOOST_REQUIRE_GT(cellSize, 0);
 
     std::vector<float> sceneBoundsMinV(j["scene_bounds"]["min"]);
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
index f35c33fa..0189ad50 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
@@ -163,7 +163,8 @@ namespace armarx::navigation
                                                       (std::istreambuf_iterator<char>()));
 
                             // parse location as json. All files in Location folder must be valid json objects!
-                            nlohmann::json j = nlohmann::json::parse(content);
+                            ARMARX_INFO << "Parsing file `" << location << "`";
+                            const nlohmann::json j = nlohmann::json::parse(content);
 
                             if (j.find("globalRobotPose") == j.end())
                             {
@@ -239,7 +240,8 @@ namespace armarx::navigation
                                                               (std::istreambuf_iterator<char>()));
 
                                     // parse vertice. Each vertice must be a valid json object
-                                    nlohmann::json j = nlohmann::json::parse(content);
+                                    ARMARX_INFO << "Parsing file `" << location << "`";
+                                    const nlohmann::json j = nlohmann::json::parse(content);
                                     if (j.find("location") == j.end())
                                     {
                                         ARMARX_WARNING
@@ -438,6 +440,8 @@ namespace armarx::navigation
         CycleUtil cycle(static_cast<int>(1000 / p.visuFrequency));
         while (tasks.visuTask and not tasks.visuTask->isStopped())
         {
+            ARMARX_TRACE;
+
             {
                 std::scoped_lock lock(propertiesMutex);
                 p = properties.locationGraph;
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
index 11bd41fd..0b4b95a5 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
@@ -50,9 +50,8 @@ namespace armarx::navigation
      * Detailed description of class NavigationMemory.
      */
     class NavigationMemory :
-        virtual public armarx::Component
+        virtual public armarx::Component,
         // , virtual public armarx::DebugObserverComponentPluginUser
-        ,
         virtual public armarx::LightweightRemoteGuiComponentPluginUser,
         virtual public armarx::ArVizComponentPluginUser,
         virtual public armarx::armem::server::ReadWritePluginUser
-- 
GitLab


From c76a4e57c33195a6ee247035d9b3ebe86b4ff97e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 13:15:29 +0200
Subject: [PATCH 023/324] test: json stuff

---
 .../navigation/algorithms/test/algorithms_spfa_test.cpp   | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
index 74baecbd..e2a24383 100644
--- a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
+++ b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
@@ -158,8 +158,8 @@ BOOST_AUTO_TEST_CASE(testGrid)
     const float cellSize = j.at("cell_size"); // [mm]
     BOOST_REQUIRE_GT(cellSize, 0);
 
-    std::vector<float> sceneBoundsMinV(j["scene_bounds"]["min"]);
-    std::vector<float> sceneBoundsMaxV(j["scene_bounds"]["max"]);
+    const std::vector<float> sceneBoundsMinV(j.at("scene_bounds").at("min"));
+    const std::vector<float> sceneBoundsMaxV(j.at("scene_bounds").at("max"));
     BOOST_REQUIRE_EQUAL(sceneBoundsMinV.size(), 2);
     BOOST_REQUIRE_EQUAL(sceneBoundsMaxV.size(), 2);
 
@@ -212,8 +212,8 @@ BOOST_AUTO_TEST_CASE(testSPFAPlanWObstacleDistance)
     const float cellSize = j.at("cell_size"); // [mm]
     BOOST_REQUIRE_GT(cellSize, 0);
 
-    std::vector<float> sceneBoundsMinV(j["scene_bounds"]["min"]);
-    std::vector<float> sceneBoundsMaxV(j["scene_bounds"]["max"]);
+    std::vector<float> sceneBoundsMinV(j.at("scene_bounds"]["min"));
+    std::vector<float> sceneBoundsMaxV(j.at("scene_bounds"]["max"));
     BOOST_REQUIRE_EQUAL(sceneBoundsMinV.size(), 2);
     BOOST_REQUIRE_EQUAL(sceneBoundsMaxV.size(), 2);
 
-- 
GitLab


From e936618ab24f8c586901b3f07364e0c20a05f216 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 14:10:12 +0200
Subject: [PATCH 024/324] dynamic scene lib

---
 source/armarx/navigation/CMakeLists.txt           |  1 +
 .../navigation/dynamic_scene/CMakeLists.txt       | 15 +++++++++++++++
 2 files changed, 16 insertions(+)
 create mode 100644 source/armarx/navigation/dynamic_scene/CMakeLists.txt

diff --git a/source/armarx/navigation/CMakeLists.txt b/source/armarx/navigation/CMakeLists.txt
index 9026c247..dfd3bf35 100644
--- a/source/armarx/navigation/CMakeLists.txt
+++ b/source/armarx/navigation/CMakeLists.txt
@@ -3,6 +3,7 @@ add_subdirectory(core)
 add_subdirectory(util)
 add_subdirectory(conversions)
 add_subdirectory(algorithms)
+add_subdirectory(dynamic_scene)
 add_subdirectory(global_planning)
 add_subdirectory(local_planning)
 add_subdirectory(trajectory_control)
diff --git a/source/armarx/navigation/dynamic_scene/CMakeLists.txt b/source/armarx/navigation/dynamic_scene/CMakeLists.txt
new file mode 100644
index 00000000..5a8b485a
--- /dev/null
+++ b/source/armarx/navigation/dynamic_scene/CMakeLists.txt
@@ -0,0 +1,15 @@
+
+armarx_add_library(dynamic_scene
+DEPENDENCIES_PUBLIC
+    ArmarXCoreInterfaces
+    ArmarXCore
+    armarx_navigation::core
+    armarx_navigation::conversions
+DEPENDENCIES_PRIVATE
+    range-v3::range-v3
+SOURCES 
+    #LocalPlanner.cpp
+HEADERS
+    #LocalPlanner.h
+INTERFACE # TODO SALt: remove this line once you added some source files!
+)
-- 
GitLab


From 5ace94ff2a735e6e044c51209049b610528e25b6 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 14:10:35 +0200
Subject: [PATCH 025/324] arviz drawer

---
 .../dynamic_scene_provider/ArVizDrawer.cpp    | 62 +++++++++++++++++++
 .../dynamic_scene_provider/ArVizDrawer.h      | 52 ++++++++++++++++
 .../dynamic_scene_provider/CMakeLists.txt     |  3 +
 3 files changed, 117 insertions(+)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.cpp
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.cpp b/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.cpp
new file mode 100644
index 00000000..01e6728c
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.cpp
@@ -0,0 +1,62 @@
+#include "ArVizDrawer.h"
+
+#include <iomanip>
+#include <sstream>
+
+#include <ArmarXCore/core/logging/Logging.h>
+
+
+#include <RobotAPI/components/ArViz/Client/Client.h>
+#include <RobotAPI/components/ArViz/Client/Elements.h>
+#include <RobotAPI/components/ArViz/Client/Layer.h>
+#include <RobotAPI/components/ArViz/Client/elements/Color.h>
+#include <RobotAPI/components/ArViz/Client/elements/Mesh.h>
+#include <RobotAPI/components/ArViz/Client/elements/PointCloud.h>
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+
+    ArVizDrawer::ArVizDrawer(armarx::viz::Client& arviz) :
+        arviz(arviz)
+    {
+    }
+
+    ArVizDrawer::~ArVizDrawer()
+    {
+        // make sure, the Arviz Ice calls are handled.
+        // {
+        //     std::unique_lock g{layerMtx};
+        //     g.lock();
+        // }
+    }
+
+    inline std::string
+    nameWithId(const std::string& name, const int id, const unsigned int idWidth = 6)
+    {
+        std::stringstream ss;
+        ss << name << "_" << std::setw(static_cast<int>(idWidth)) << std::setfill('0') << id;
+        return ss.str();
+    }
+
+    inline std::string nameWithIds(const std::string& name,
+                                   const int id,
+                                   const int subId,
+                                   const unsigned int idWidth = 6)
+    {
+        std::stringstream ss;
+        ss << name << "_" << std::setw(static_cast<int>(idWidth)) << std::setfill('0') << id << "_"
+           << std::setw(static_cast<int>(idWidth)) << std::setfill('0') << subId;
+        return ss.str();
+    }
+
+    void ArVizDrawer::visualizeFoo()
+    {
+        auto layer = arviz.layer("my_layer_name");
+
+        // TODO: populate layer, e.g.
+        // odomLayer.add(viz::Pose("odom").pose(odomPose.translation() * 1000, odomPose.linear()));
+       
+        arviz.commit(layer);
+    }
+
+}  // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h b/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h
new file mode 100644
index 00000000..832fdeea
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h
@@ -0,0 +1,52 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <mutex>
+
+#include <Eigen/Geometry>
+
+#include <RobotAPI/components/ArViz/Client/Client.h>
+
+
+namespace armarx::viz
+{
+    struct Client;
+} // namespace armarx::viz
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+
+    class ArVizDrawer
+    {
+    public:
+        ArVizDrawer(armarx::viz::Client& arviz);
+        virtual ~ArVizDrawer();
+
+        void visualizeFoo();
+
+    private:
+        viz::Client& arviz;
+    };
+
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index f42f1a64..146e5b7b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -8,8 +8,10 @@ armarx_add_component(dynamic_scene_provider
         # aron/my_type.xml
     SOURCES
         Component.cpp
+        ArVizDrawer.cpp
     HEADERS
         Component.h
+        ArVizDrawer.h
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
@@ -26,6 +28,7 @@ armarx_add_component(dynamic_scene_provider
         # navigation
         armarx_navigation::util
         armarx_navigation::memory
+        armarx_navigation::dynamic_scene
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
-- 
GitLab


From c13ba30d4a8b45eedcbb58094291fdcce27a6476 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 14:12:01 +0200
Subject: [PATCH 026/324] using arviz drawer

---
 .../components/dynamic_scene_provider/Component.cpp           | 3 +++
 .../navigation/components/dynamic_scene_provider/Component.h  | 4 ++++
 2 files changed, 7 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 19292c31..9f8cd9f7 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -34,6 +34,7 @@
 
 #include <VisionX/libraries/armem_human/client/HumanPoseReader.h>
 
+#include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/memory/client/costmap/Reader.h>
 #include <armarx/navigation/util/util.h>
@@ -104,6 +105,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
     void
     Component::onConnectComponent()
     {
+        arvizDrawer.emplace(ArVizDrawer(getArvizClient()));
+
         // Do things after connecting to topics and components.
 
         /* (Requies the armarx::DebugObserverComponentPluginUser.)
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index c31f150f..1d7d92fc 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -46,6 +46,7 @@
 #include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
+#include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
 #include "armarx/navigation/memory/client/costmap/Reader.h"
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
 
@@ -176,6 +177,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         std::mutex arvizMutex;
         */
 
+        std::optional<ArVizDrawer> arvizDrawer;
+
+
         PeriodicTask<Component>::pointer_type task;
 
         template <typename T>
-- 
GitLab


From 23f455dd0f0884e4bd159ba65a599c85843fd71e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 21:16:20 +0200
Subject: [PATCH 027/324] scenario update

---
 .../config/control_memory.cfg                 | 284 ++++++++++++++++++
 1 file changed, 284 insertions(+)

diff --git a/scenarios/HumanAwareNavigation/config/control_memory.cfg b/scenarios/HumanAwareNavigation/config/control_memory.cfg
index dd21987d..4aad1c46 100644
--- a/scenarios/HumanAwareNavigation/config/control_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/control_memory.cfg
@@ -2,3 +2,287 @@
 # control_memory properties
 # ==================================================================
 
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.EnableProfiling = false
+
+
+# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ObjectName = ""
+
+
+# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Control
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.MemoryName = Control
+
+
+# ArmarX.ControlMemory.mem.ltm..configuration:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm..configuration = ""
+
+
+# ArmarX.ControlMemory.mem.ltm..enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm..enabled = false
+
+
+# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.ControlMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.storagepath = Default value not mapped.
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
+
+
+# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.snapshotToLoad = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
-- 
GitLab


From fd4655a24ff22df987b6eac5d5b368148e9954a9 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 21:36:56 +0200
Subject: [PATCH 028/324] fix: convert trajectory

---
 .../local_planning/ros_conversions.cpp        | 22 +++++++++++++++----
 1 file changed, 18 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 2742d26b..a591346c 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -7,6 +7,7 @@
 #include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/conversions/eigen.h>
 
+#include <range/v3/view/drop.hpp>
 #include <range/v3/view/zip.hpp>
 
 namespace armarx::navigation::conv
@@ -82,23 +83,36 @@ namespace armarx::navigation::conv
     core::LocalTrajectory
     fromRos(const teb_local_planner::TimedElasticBand& teb)
     {
+        const auto& tebPoses = teb.poses();
+
+        if(tebPoses.empty())
+        {
+            return {};
+        }
+
         core::LocalTrajectory trajectory;
-        trajectory.reserve(teb.poses().size());
+        trajectory.reserve(tebPoses.size());
 
         // TODO this timestamp should be given via the argument list
         DateTime timestamp = Clock::Now();
 
-        ARMARX_CHECK_EQUAL(teb.poses().size(), teb.timediffs().size());
+        ARMARX_CHECK_EQUAL(tebPoses.size(), teb.timediffs().size()-1);
+
+        // add the first pose at this timestamp
+        trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {fromRos(tebPoses.front()->pose())}});
 
-        for (const auto& [poseVertex, timediff]: ranges::views::zip(teb.poses(), teb.timediffs()))
+        // all consecutive poses
+        for (const auto& [poseVertex, timediff]: ranges::views::zip(tebPoses | ranges::views::drop(1), teb.timediffs()))
         {
             const core::Pose pose = fromRos(poseVertex->pose());
             const Duration dt = Duration::SecondsDouble(timediff->dt());
-            timestamp += dt;
 
+            timestamp += dt; 
             trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {pose}});
         }
 
+        ARMARX_CHECK_EQUAL(trajectory.size(), tebPoses.size());
+
         return trajectory;
     }
 
-- 
GitLab


From 02cb170ede8db29e1419e0ea349cd685949dfac2 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 21:39:46 +0200
Subject: [PATCH 029/324] scenario: dry run

---
 .../HumanAwareNavigation/config/navigation_memory.cfg    | 8 ++++----
 scenarios/HumanAwareNavigation/config/navigator.cfg      | 9 +++++++++
 2 files changed, 13 insertions(+), 4 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index aeb9f55b..c024b256 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -150,21 +150,21 @@ ArmarX.NavigationMemory.MinimumLoggingLevel = Verbose
 # ArmarX.NavigationMemory.mem.MemoryName = Navigation
 
 
-# ArmarX.NavigationMemory.mem.ltm..configuration:  
+# ArmarX.NavigationMemory.mem.ltm.configuration:  
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm..configuration = ""
+# ArmarX.NavigationMemory.mem.ltm.configuration = ""
 
 
-# ArmarX.NavigationMemory.mem.ltm..enabled:  
+# ArmarX.NavigationMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm..enabled = false
+# ArmarX.NavigationMemory.mem.ltm.enabled = false
 
 
 # ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index f6a497b2..a9085fcd 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -311,6 +311,15 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
+# ArmarX.Navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+ArmarX.Navigator.p.disableExecutor = 1
+
+
 # ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
 #  Attributes:
 #  - Default:            0.550000012
-- 
GitLab


From 7c13fc042659265c71dc17bbc17a5144604144f7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 21:54:39 +0200
Subject: [PATCH 030/324] local planning: aron + renaming namespace loc_plan ->
 local_planning

---
 .../client/NavigationStackConfig.cpp          |  4 +--
 .../navigation/client/NavigationStackConfig.h |  2 +-
 .../services/EventSubscriptionInterface.h     |  2 +-
 .../client/services/SimpleEventHandler.cpp    |  2 +-
 .../client/services/SimpleEventHandler.h      |  2 +-
 .../components/Navigator/RemoteGui.cpp        |  2 ++
 .../factories/LocalPlannerFactory.cpp         | 12 ++++----
 .../factories/LocalPlannerFactory.h           |  4 +--
 source/armarx/navigation/factories/fwd.h      |  4 +--
 .../navigation/local_planning/CMakeLists.txt  | 19 ++++++++----
 .../local_planning/LocalPlanner.cpp           |  4 +--
 .../navigation/local_planning/LocalPlanner.h  |  4 +--
 .../local_planning/TimedElasticBands.cpp      | 30 ++++++++++++++-----
 .../local_planning/TimedElasticBands.h        |  4 +--
 .../local_planning/aron/TimedElasticBands.xml | 14 +++++++++
 .../local_planning/aron_conversions.cpp       | 25 ++++++++++++++++
 .../local_planning/aron_conversions.h         | 22 ++++++++++++++
 .../armarx/navigation/local_planning/core.h   |  4 +--
 .../memory/client/stack_result/Writer.cpp     |  4 +--
 .../memory/client/stack_result/Writer.h       |  4 +--
 .../navigation/server/NavigationStack.h       |  2 +-
 source/armarx/navigation/server/Navigator.cpp |  6 ++--
 source/armarx/navigation/server/Navigator.h   |  8 ++---
 source/armarx/navigation/server/StackResult.h |  2 +-
 .../EventPublishingInterface.h                |  2 +-
 .../event_publishing/MemoryPublisher.cpp      |  2 +-
 .../server/event_publishing/MemoryPublisher.h |  2 +-
 .../introspection/ArvizIntrospector.cpp       |  2 +-
 .../server/introspection/ArvizIntrospector.h  |  2 +-
 .../introspection/IntrospectorInterface.h     |  2 +-
 .../introspection/MemoryIntrospector.cpp      |  2 +-
 .../server/introspection/MemoryIntrospector.h |  2 +-
 32 files changed, 144 insertions(+), 58 deletions(-)
 create mode 100644 source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
 create mode 100644 source/armarx/navigation/local_planning/aron_conversions.cpp
 create mode 100644 source/armarx/navigation/local_planning/aron_conversions.h

diff --git a/source/armarx/navigation/client/NavigationStackConfig.cpp b/source/armarx/navigation/client/NavigationStackConfig.cpp
index 314a8e29..cb70009d 100644
--- a/source/armarx/navigation/client/NavigationStackConfig.cpp
+++ b/source/armarx/navigation/client/NavigationStackConfig.cpp
@@ -74,12 +74,12 @@ namespace armarx::navigation::client
     }
 
     NavigationStackConfig&
-    NavigationStackConfig::localPlanner(const loc_plan::LocalPlannerParams& params)
+    NavigationStackConfig::localPlanner(const local_planning::LocalPlannerParams& params)
     {
         aron::data::DictPtr element(new aron::data::Dict);
         element->addElement(core::NAME_KEY,
                             std::make_shared<aron::data::String>(
-                                loc_plan::AlgorithmNames.to_name(params.algorithm())));
+                                local_planning::AlgorithmNames.to_name(params.algorithm())));
         element->addElement(core::PARAMS_KEY, params.toAron());
 
         dict.addElement(core::StackLayerNames.to_name(core::StackLayer::LocalPlanner), element);
diff --git a/source/armarx/navigation/client/NavigationStackConfig.h b/source/armarx/navigation/client/NavigationStackConfig.h
index e37dfa4a..8125abe5 100644
--- a/source/armarx/navigation/client/NavigationStackConfig.h
+++ b/source/armarx/navigation/client/NavigationStackConfig.h
@@ -62,7 +62,7 @@ namespace armarx::navigation::client
 
         NavigationStackConfig& globalPlanner(const global_planning::GlobalPlannerParams& params);
 
-        NavigationStackConfig& localPlanner(const loc_plan::LocalPlannerParams& params);
+        NavigationStackConfig& localPlanner(const local_planning::LocalPlannerParams& params);
 
         NavigationStackConfig&
         trajectoryController(const traj_ctrl::local::TrajectoryControllerParams& params);
diff --git a/source/armarx/navigation/client/services/EventSubscriptionInterface.h b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
index 82bd26cf..115babcf 100644
--- a/source/armarx/navigation/client/services/EventSubscriptionInterface.h
+++ b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
@@ -13,7 +13,7 @@ namespace armarx::navigation::client
 
     using GlobalTrajectoryUpdatedCallback =
         std::function<void(const global_planning::GlobalPlannerResult&)>;
-    using LocalTrajectoryUpdatedCallback = std::function<void(const loc_plan::LocalPlannerResult&)>;
+    using LocalTrajectoryUpdatedCallback = std::function<void(const local_planning::LocalPlannerResult&)>;
     using TrajectoryControllerUpdatedCallback =
         std::function<void(const traj_ctrl::local::TrajectoryControllerResult&)>;
     using GlobalPlanningFailedCallback =
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.cpp b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
index 0c2b8055..c849f30a 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.cpp
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
@@ -136,7 +136,7 @@ namespace armarx::navigation::client
     }
 
     void
-    SimpleEventHandler::localTrajectoryUpdated(const loc_plan::LocalPlannerResult& event)
+    SimpleEventHandler::localTrajectoryUpdated(const local_planning::LocalPlannerResult& event)
     {
         for (const auto& callback : subscriptions.localTrajectoryUpdatedCallbacks)
         {
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.h b/source/armarx/navigation/client/services/SimpleEventHandler.h
index faa56a89..6bb0e690 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.h
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.h
@@ -30,7 +30,7 @@ namespace armarx::navigation::client
 
         // EventPublishingInterface
         void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& event) override;
-        void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& event) override;
+        void localTrajectoryUpdated(const local_planning::LocalPlannerResult& event) override;
         // void trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& event) override;
         void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) override;
 
diff --git a/source/armarx/navigation/components/Navigator/RemoteGui.cpp b/source/armarx/navigation/components/Navigator/RemoteGui.cpp
index 83e93879..cc082cef 100644
--- a/source/armarx/navigation/components/Navigator/RemoteGui.cpp
+++ b/source/armarx/navigation/components/Navigator/RemoteGui.cpp
@@ -16,6 +16,7 @@
 #include <ArmarXGui/libraries/RemoteGui/WidgetProxy.h>
 
 #include "Navigator.h"
+#include "armarx/navigation/local_planning/TimedElasticBands.h"
 #include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/core/types.h>
@@ -254,6 +255,7 @@ namespace armarx::navigation::components
 
             client::NavigationStackConfig cfg;
             cfg.globalPlanner(global_planning::SPFAParams());
+            cfg.localPlanner(local_planning::TimedElasticBandsParams());
             cfg.trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams());
 
             const auto stackConfig = cfg.toAron();
diff --git a/source/armarx/navigation/factories/LocalPlannerFactory.cpp b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
index aed7f192..1dcb347b 100644
--- a/source/armarx/navigation/factories/LocalPlannerFactory.cpp
+++ b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
@@ -10,10 +10,10 @@
 
 namespace armarx::navigation::fac
 {
-    loc_plan::LocalPlannerPtr
+    local_planning::LocalPlannerPtr
     LocalPlannerFactory::create(const aron::data::DictPtr& params, const core::Scene& ctx)
     {
-        namespace layer = loc_plan;
+        namespace layer = local_planning;
 
         if (not params)
         {
@@ -29,12 +29,12 @@ namespace armarx::navigation::fac
         const auto algoParams = aron::data::Dict::DynamicCast(params->getElement(core::PARAMS_KEY));
         ARMARX_CHECK_NOT_NULL(algoParams);
 
-        loc_plan::LocalPlannerPtr localPlanner;
+        local_planning::LocalPlannerPtr localPlanner;
         switch (algo)
         {
-            case loc_plan::Algorithms::TimedElasticBands:
-                localPlanner = std::make_shared<loc_plan::TimedElasticBands>(
-                    loc_plan::TimedElasticBandsParams::FromAron(algoParams), ctx);
+            case local_planning::Algorithms::TimedElasticBands:
+                localPlanner = std::make_shared<local_planning::TimedElasticBands>(
+                    local_planning::TimedElasticBandsParams::FromAron(algoParams), ctx);
                 break;
         }
 
diff --git a/source/armarx/navigation/factories/LocalPlannerFactory.h b/source/armarx/navigation/factories/LocalPlannerFactory.h
index 4e3b0e09..124e4c88 100644
--- a/source/armarx/navigation/factories/LocalPlannerFactory.h
+++ b/source/armarx/navigation/factories/LocalPlannerFactory.h
@@ -31,13 +31,13 @@ namespace armarx::navigation::fac
 {
 
     /**
-     * @brief Factory to create a loc_plan::LocalPlanner
+     * @brief Factory to create a local_planning::LocalPlanner
      *
      */
     class LocalPlannerFactory
     {
     public:
-        static loc_plan::LocalPlannerPtr create(const aron::data::DictPtr& params,
+        static local_planning::LocalPlannerPtr create(const aron::data::DictPtr& params,
                                                 const core::Scene& ctx);
 
     protected:
diff --git a/source/armarx/navigation/factories/fwd.h b/source/armarx/navigation/factories/fwd.h
index 7975180e..79d60ad1 100644
--- a/source/armarx/navigation/factories/fwd.h
+++ b/source/armarx/navigation/factories/fwd.h
@@ -32,11 +32,11 @@ namespace armarx::navigation
         using GlobalPlannerPtr = std::shared_ptr<GlobalPlanner>;
     } // namespace global_planning
 
-    namespace loc_plan
+    namespace local_planning
     {
         class LocalPlanner;
         using LocalPlannerPtr = std::shared_ptr<LocalPlanner>;
-    } // namespace loc_plan
+    } // namespace local_planning
 
     namespace traj_ctrl
     {
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 6d47bd30..5cd3b287 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -1,3 +1,7 @@
+armarx_add_aron_library(local_planning_aron
+    ARON_FILES
+        aron/TimedElasticBands.xml
+)
 
 armarx_add_library(local_planning
     DEPENDENCIES_PUBLIC
@@ -5,18 +9,21 @@ armarx_add_library(local_planning
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
+        armarx_navigation::local_planning_aron
         # teb_extension::obstacles
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
     DEPENDENCIES_LEGACY
         teb_local_planner
     SOURCES 
-        ./LocalPlanner.cpp
-        ./TimedElasticBands.cpp
-        ./ros_conversions.cpp
+        LocalPlanner.cpp
+        TimedElasticBands.cpp
+        ros_conversions.cpp
+        aron_conversions.cpp
     HEADERS
-        ./LocalPlanner.h
-        ./TimedElasticBands.h
-        ./ros_conversions.h
+        LocalPlanner.h
+        TimedElasticBands.h
+        ros_conversions.h
         core.h
+        aron_conversions.h
 )
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.cpp b/source/armarx/navigation/local_planning/LocalPlanner.cpp
index 7205dd80..b98a0a53 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.cpp
+++ b/source/armarx/navigation/local_planning/LocalPlanner.cpp
@@ -1,8 +1,8 @@
 #include "LocalPlanner.h"
 
-namespace armarx::navigation::loc_plan
+namespace armarx::navigation::local_planning
 {
     LocalPlanner::LocalPlanner(const core::Scene& context) : context(context)
     {
     }
-} // namespace armarx::navigation::loc_plan
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h
index 6ae1c69c..8c2554d6 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.h
+++ b/source/armarx/navigation/local_planning/LocalPlanner.h
@@ -34,7 +34,7 @@
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
 
-namespace armarx::navigation::loc_plan
+namespace armarx::navigation::local_planning
 {
     struct LocalPlannerResult
     {
@@ -64,4 +64,4 @@ namespace armarx::navigation::loc_plan
 
     using LocalPlannerPtr = std::shared_ptr<LocalPlanner>;
 
-} // namespace armarx::navigation::loc_plan
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 147e7622..1d5f211f 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -13,7 +13,7 @@
 // #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 
-namespace armarx::navigation::loc_plan
+namespace armarx::navigation::local_planning
 {
 
     // TimedElasticBandsParams
@@ -27,15 +27,28 @@ namespace armarx::navigation::loc_plan
     aron::data::DictPtr
     TimedElasticBandsParams::toAron() const
     {
-        return nullptr; // TODO implement
+        arondto::TimedElasticBandsParams dto;
+
+        TimedElasticBandsParams bo;
+        toAron(dto, bo);
+
+        return dto.toAron();
     }
 
     TimedElasticBandsParams
     TimedElasticBandsParams::FromAron(const aron::data::DictPtr& dict)
     {
-        return TimedElasticBandsParams(); // TODO implement
+        ARMARX_CHECK_NOT_NULL(dict);
+        arondto::TimedElasticBandsParams dto;
+        dto.fromAron(dict);
+
+        TimedElasticBandsParams bo;
+        fromAron(dto, bo);
+
+        return bo;
     }
 
+
     // TimedElasticBands
 
     TimedElasticBands::TimedElasticBands(const Params& params, const core::Scene& ctx) :
@@ -94,7 +107,7 @@ namespace armarx::navigation::loc_plan
         const teb_local_planner::PoseSE2 end = conv::toRos(target.target);
 
         core::Twist currentVelocity = core::Twist::Zero();
-        
+
         // FIXME: again, add to scene
         // if (scene.platformVelocity.has_value())
         // {
@@ -126,13 +139,16 @@ namespace armarx::navigation::loc_plan
 
 
     TimedElasticBands::FindTargetResult
-    TimedElasticBands::findTarget(const core::Pose& currentPose, const core::GlobalTrajectory& globalPath)
+    TimedElasticBands::findTarget(const core::Pose& currentPose,
+                                  const core::GlobalTrajectory& globalPath)
     {
 
         const core::Projection projection = globalPath.getProjection(
             currentPose.translation(), core::VelocityInterpolation::LinearInterpolation);
 
-        return {conv::to2D(projection.projection.waypoint.pose), conv::to2D(globalPath.points().back().waypoint.pose), true};
+        return {conv::to2D(projection.projection.waypoint.pose),
+                conv::to2D(globalPath.points().back().waypoint.pose),
+                true};
     }
 
-} // namespace armarx::navigation::loc_plan
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 2ecd7862..e0497708 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -31,7 +31,7 @@
 #include <teb_local_planner/homotopy_class_planner.h>
 #include <teb_local_planner/teb_config.h>
 
-namespace armarx::navigation::loc_plan
+namespace armarx::navigation::local_planning
 {
     // TODO(SALt): Implement
 
@@ -80,4 +80,4 @@ namespace armarx::navigation::loc_plan
         teb_local_planner::PoseSequence teb_globalPath;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
     };
-} // namespace armarx::navigation::loc_plan
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
new file mode 100644
index 00000000..2c352aca
--- /dev/null
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -0,0 +1,14 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <AronIncludes>
+        <!-- <Include include="armarx/navigation/local_planning/aron/LocalPlannerParams.xml" /> -->
+    </AronIncludes>
+
+    <GenerateTypes>
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
+            <ObjectChild key='foo'>
+                <float />
+            </ObjectChild>
+        </Object>
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
new file mode 100644
index 00000000..44599c44
--- /dev/null
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -0,0 +1,25 @@
+#include "aron_conversions.h"
+
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
+
+#include <armarx/navigation/local_planning/TimedElasticBands.h>
+#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+
+namespace armarx::navigation::local_planning
+{
+
+
+    void
+    toAron(arondto::TimedElasticBandsParams& dto, const TimedElasticBandsParams& bo)
+    {
+    }
+
+    void
+    fromAron(const arondto::TimedElasticBandsParams& dto, TimedElasticBandsParams& bo)
+    {
+    }
+
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron_conversions.h b/source/armarx/navigation/local_planning/aron_conversions.h
new file mode 100644
index 00000000..1b7d2382
--- /dev/null
+++ b/source/armarx/navigation/local_planning/aron_conversions.h
@@ -0,0 +1,22 @@
+#pragma once
+
+namespace armarx::navigation::local_planning
+{
+    // struct LocalPlannerParams;
+    struct TimedElasticBandsParams;
+
+    namespace arondto
+    {
+        struct LocalPlannerParams;
+        struct TimedElasticBandsParams;
+
+    } // namespace arondto
+
+} // namespace armarx::navigation::local_planning
+
+namespace armarx::navigation::local_planning
+{
+    void toAron(arondto::TimedElasticBandsParams& dto, const TimedElasticBandsParams& bo);
+    void fromAron(const arondto::TimedElasticBandsParams& dto, TimedElasticBandsParams& bo);
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/core.h b/source/armarx/navigation/local_planning/core.h
index d2fa0f3e..f8d1e102 100644
--- a/source/armarx/navigation/local_planning/core.h
+++ b/source/armarx/navigation/local_planning/core.h
@@ -24,7 +24,7 @@
 
 #include <SimoxUtility/meta/enum/EnumNames.hpp>
 
-namespace armarx::navigation::loc_plan
+namespace armarx::navigation::local_planning
 {
 
     enum class Algorithms
@@ -35,4 +35,4 @@ namespace armarx::navigation::loc_plan
     const inline simox::meta::EnumNames<Algorithms> AlgorithmNames{
         {Algorithms::TimedElasticBands, "TimedElasticBands"}};
 
-} // namespace armarx::navigation::loc_plan
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.cpp b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
index 4a3a3a75..4ecb1efd 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.cpp
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
@@ -46,7 +46,7 @@ namespace armarx::navigation::memory::client::stack_result
     }
 
     bool
-    Writer::store(const armarx::navigation::loc_plan::LocalPlannerResult& result,
+    Writer::store(const armarx::navigation::local_planning::LocalPlannerResult& result,
                   const std::string& clientID)
     {
         armem::Commit commit;
@@ -88,7 +88,7 @@ namespace armarx::navigation::memory::client::stack_result
 
 
     bool
-    Writer::storePrepare(const loc_plan::LocalPlannerResult& result,
+    Writer::storePrepare(const local_planning::LocalPlannerResult& result,
                          const std::string& clientID,
                          armem::Commit& commit)
     {
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.h b/source/armarx/navigation/memory/client/stack_result/Writer.h
index 2e29333f..1c2b3183 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.h
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.h
@@ -42,7 +42,7 @@ namespace armarx::navigation::memory::client::stack_result
         bool store(const armarx::navigation::global_planning::GlobalPlannerResult& result,
                    const std::string& clientID);
 
-        bool store(const armarx::navigation::loc_plan::LocalPlannerResult& result,
+        bool store(const armarx::navigation::local_planning::LocalPlannerResult& result,
                    const std::string& clientID);
 
 
@@ -51,7 +51,7 @@ namespace armarx::navigation::memory::client::stack_result
                           const std::string& clientID,
                           armem::Commit& commit);
 
-        bool storePrepare(const loc_plan::LocalPlannerResult& result,
+        bool storePrepare(const local_planning::LocalPlannerResult& result,
                           const std::string& clientID,
                           armem::Commit& commit);
 
diff --git a/source/armarx/navigation/server/NavigationStack.h b/source/armarx/navigation/server/NavigationStack.h
index 2bed9fdf..c5d80fc2 100644
--- a/source/armarx/navigation/server/NavigationStack.h
+++ b/source/armarx/navigation/server/NavigationStack.h
@@ -34,7 +34,7 @@ namespace armarx::navigation::server
     struct NavigationStack
     {
         global_planning::GlobalPlannerPtr globalPlanner;
-        loc_plan::LocalPlannerPtr localPlanner = nullptr;
+        local_planning::LocalPlannerPtr localPlanner = nullptr;
         // traj_ctrl::TrajectoryControllerPtr trajectoryControl;
         // safe_ctrl::SafetyControllerPtr safetyControl = nullptr;
     };
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 0fd9321f..af121508 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -774,7 +774,7 @@ namespace armarx::navigation::server
         srv.sceneProvider->synchronize(armarx::Clock::Now());
     }
 
-    std::optional<loc_plan::LocalPlannerResult>
+    std::optional<local_planning::LocalPlannerResult>
     Navigator::updateLocalPlanner()
     {
         ARMARX_CHECK(hasLocalPlanner());
@@ -794,7 +794,7 @@ namespace armarx::navigation::server
     }
 
     void
-    Navigator::updateExecutor(const std::optional<loc_plan::LocalPlannerResult>& localPlan)
+    Navigator::updateExecutor(const std::optional<local_planning::LocalPlannerResult>& localPlan)
     {
         if(srv.executor == nullptr)
         {
@@ -835,7 +835,7 @@ namespace armarx::navigation::server
     }
 
     void
-    Navigator::updateIntrospector(const std::optional<loc_plan::LocalPlannerResult>& localPlan)
+    Navigator::updateIntrospector(const std::optional<local_planning::LocalPlannerResult>& localPlan)
     {
         ARMARX_CHECK_NOT_NULL(srv.introspector);
 
diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index f7ef3948..5c236f3a 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -120,9 +120,9 @@ namespace armarx::navigation::server
 
         void updateScene();
 
-        std::optional<loc_plan::LocalPlannerResult> updateLocalPlanner();
-        void updateExecutor(const std::optional<loc_plan::LocalPlannerResult>& localPlan);
-        void updateIntrospector(const std::optional<loc_plan::LocalPlannerResult>& localPlan);
+        std::optional<local_planning::LocalPlannerResult> updateLocalPlanner();
+        void updateExecutor(const std::optional<local_planning::LocalPlannerResult>& localPlan);
+        void updateIntrospector(const std::optional<local_planning::LocalPlannerResult>& localPlan);
 
         void updateMonitor();
 
@@ -154,7 +154,7 @@ namespace armarx::navigation::server
 
 
         std::optional<global_planning::GlobalPlannerResult> globalPlan;
-        std::optional<loc_plan::LocalPlannerResult> localPlan;
+        std::optional<local_planning::LocalPlannerResult> localPlan;
     };
 
 } // namespace armarx::navigation::server
diff --git a/source/armarx/navigation/server/StackResult.h b/source/armarx/navigation/server/StackResult.h
index 64abee03..a742ce4b 100644
--- a/source/armarx/navigation/server/StackResult.h
+++ b/source/armarx/navigation/server/StackResult.h
@@ -40,7 +40,7 @@ namespace armarx::navigation::server
         using SafetyControllerResult = std::optional<core::Twist>;
 
         global_planning::GlobalPlannerResult globalPlan;
-        loc_plan::LocalPlannerResult localTrajectory;
+        local_planning::LocalPlannerResult localTrajectory;
         // traj_ctrl::global::TrajectoryControllerResult controlVelocity;
         // SafetyControllerResult safeVelocity;
 
diff --git a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
index 775d77aa..6ead929f 100644
--- a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
+++ b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
@@ -19,7 +19,7 @@ namespace armarx::navigation::server
     public:
         // TODO(fabian.reister): fwd
         virtual void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& res) = 0;
-        virtual void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& res) = 0;
+        virtual void localTrajectoryUpdated(const local_planning::LocalPlannerResult& res) = 0;
         // virtual void
         // trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& res) = 0;
 
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
index 30bc7e6b..36f4e960 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
@@ -52,7 +52,7 @@ namespace armarx::navigation::server
     }
 
     void
-    MemoryPublisher::localTrajectoryUpdated(const loc_plan::LocalPlannerResult& res)
+    MemoryPublisher::localTrajectoryUpdated(const local_planning::LocalPlannerResult& res)
     {
         // resultWriter->store(res, clientId);
     }
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
index 61db181e..831510f4 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
@@ -17,7 +17,7 @@ namespace armarx::navigation::server
                         const std::string& clientId);
 
         void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& res) override;
-        void localTrajectoryUpdated(const loc_plan::LocalPlannerResult& res) override;
+        void localTrajectoryUpdated(const local_planning::LocalPlannerResult& res) override;
         // void trajectoryControllerUpdated(
         //     const traj_ctrl::local::TrajectoryControllerResult& res) override;
 
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index a57ba285..4bfc1894 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -55,7 +55,7 @@ namespace armarx::navigation::server
     }
 
     void
-    ArvizIntrospector::onLocalPlannerResult(const loc_plan::LocalPlannerResult& result)
+    ArvizIntrospector::onLocalPlannerResult(const local_planning::LocalPlannerResult& result)
     {
         std::lock_guard g{mtx};
 
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index f27ea0be..4681016c 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -53,7 +53,7 @@ namespace armarx::navigation::server
         ~ArvizIntrospector() override = default;
 
         void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) override;
-        void onLocalPlannerResult(const loc_plan::LocalPlannerResult& result) override;
+        void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) override;
         
         void onGoal(const core::Pose& goal) override;
 
diff --git a/source/armarx/navigation/server/introspection/IntrospectorInterface.h b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
index f92ed9e8..178b1915 100644
--- a/source/armarx/navigation/server/introspection/IntrospectorInterface.h
+++ b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
@@ -43,7 +43,7 @@ namespace armarx::navigation::server
         virtual void failure() = 0;
 
         virtual void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) = 0;
-        virtual void onLocalPlannerResult(const loc_plan::LocalPlannerResult& result) = 0;
+        virtual void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) = 0;
 
         virtual void onGlobalShortestPath(const std::vector<core::Pose>& path) = 0;
 
diff --git a/source/armarx/navigation/server/introspection/MemoryIntrospector.cpp b/source/armarx/navigation/server/introspection/MemoryIntrospector.cpp
index aaf84a09..c0b97ecf 100644
--- a/source/armarx/navigation/server/introspection/MemoryIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/MemoryIntrospector.cpp
@@ -17,7 +17,7 @@ namespace armarx::navigation::server
     }
 
     void
-    MemoryIntrospector::onLocalPlannerResult(const loc_plan::LocalPlannerResult& result)
+    MemoryIntrospector::onLocalPlannerResult(const local_planning::LocalPlannerResult& result)
     {
         // TODO(fabian.reister): implement
     }
diff --git a/source/armarx/navigation/server/introspection/MemoryIntrospector.h b/source/armarx/navigation/server/introspection/MemoryIntrospector.h
index 9d473a74..592bf116 100644
--- a/source/armarx/navigation/server/introspection/MemoryIntrospector.h
+++ b/source/armarx/navigation/server/introspection/MemoryIntrospector.h
@@ -39,7 +39,7 @@ namespace armarx::navigation::server
 
 
         void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) override;
-        void onLocalPlannerResult(const loc_plan::LocalPlannerResult& result) override;
+        void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) override;
 
         void onGoal(const core::Pose& goal) override;
 
-- 
GitLab


From ade96bd61d1a712543c7958ac4e8a9aa58123f22 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 21:56:24 +0200
Subject: [PATCH 031/324] teb aron

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 4 +++-
 1 file changed, 3 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 1d5f211f..5521a4c1 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -8,6 +8,8 @@
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/Trajectory.h"
 #include <armarx/navigation/local_planning/LocalPlanner.h>
+#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+#include <armarx/navigation/local_planning/aron_conversions.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
 // #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
@@ -30,7 +32,7 @@ namespace armarx::navigation::local_planning
         arondto::TimedElasticBandsParams dto;
 
         TimedElasticBandsParams bo;
-        toAron(dto, bo);
+        armarx::navigation::local_planning::toAron(dto, bo);
 
         return dto.toAron();
     }
-- 
GitLab


From d4238547e5e4c130d34e8d73fd90b8370f19fdba Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:02:57 +0200
Subject: [PATCH 032/324] minor fix

---
 source/armarx/navigation/local_planning/ros_conversions.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index a591346c..40933271 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -96,7 +96,7 @@ namespace armarx::navigation::conv
         // TODO this timestamp should be given via the argument list
         DateTime timestamp = Clock::Now();
 
-        ARMARX_CHECK_EQUAL(tebPoses.size(), teb.timediffs().size()-1);
+        ARMARX_CHECK_EQUAL(tebPoses.size()-1, teb.timediffs().size());
 
         // add the first pose at this timestamp
         trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {fromRos(tebPoses.front()->pose())}});
-- 
GitLab


From 5b334eeffdc99a7900be7bc082d77a14c9ada296 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:17:32 +0200
Subject: [PATCH 033/324] mm to m and reverse for ros <-> armarx

---
 .../navigation/local_planning/ros_conversions.cpp    | 12 ++++++------
 1 file changed, 6 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 40933271..4e08d37b 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -25,14 +25,14 @@ namespace armarx::navigation::conv
         Eigen::Vector2d pos = pose.translation().cast<double>();
         double theta = Eigen::Rotation2Df(pose.linear()).angle();
 
-        return {pos, theta};
+        return {pos / 1000., theta}; // [mm] to [m]
     }
 
 
     core::Pose
     fromRos(const teb_local_planner::PoseSE2& pose)
     {
-        Eigen::Vector2d pos = pose.position();
+        Eigen::Vector2d pos = pose.position() * 1000; // [m] to [mm]
         double theta = pose.theta();
 
         core::Pose2D ret;
@@ -46,9 +46,9 @@ namespace armarx::navigation::conv
     toRos(const core::Twist& velocity)
     {
         geometry_msgs::Twist ret;
-        ret.linear.x = velocity.linear.x();
-        ret.linear.y = velocity.linear.y();
-        ret.angular.z = velocity.angular.z();
+        ret.linear.x = velocity.linear.x(); // [mm] to [m]
+        ret.linear.y = velocity.linear.y(); // [mm] to [m]
+        ret.angular.z = velocity.angular.z(); // [mm] to [m]
 
         return ret;
     }
@@ -68,7 +68,7 @@ namespace armarx::navigation::conv
             if (!first)
             {
                 Eigen::Vector2d distance = pose.position() - lastPose.position();
-                double timeDiff = distance.norm() / point.velocity;
+                double timeDiff = distance.norm() / (point.velocity / 1000); // [mm/s] -> [m/s]
                 teb.addTimeDiff(timeDiff);
 
                 first = false;
-- 
GitLab


From f324942a50dd312939fe33e4710a73f0e8ccbd83 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:18:41 +0200
Subject: [PATCH 034/324] visu

---
 source/armarx/navigation/components/Navigator/Navigator.cpp   | 3 ---
 .../navigation/server/introspection/ArvizIntrospector.cpp     | 4 +++-
 2 files changed, 3 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/components/Navigator/Navigator.cpp b/source/armarx/navigation/components/Navigator/Navigator.cpp
index 7aeac32d..8b56fd6d 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.cpp
+++ b/source/armarx/navigation/components/Navigator/Navigator.cpp
@@ -59,10 +59,7 @@
 #include "ArmarXGui/libraries/RemoteGui/Client/Widgets.h"
 
 #include <RobotAPI/components/ArViz/Client/Client.h>
-#include <RobotAPI/components/ArViz/Client/Elements.h>
-#include <RobotAPI/components/ArViz/Client/elements/Color.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
-#include <RobotAPI/interface/ArViz/Elements.h>
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem_vision/OccupancyGridHelper.h>
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 4bfc1894..a9d0dacd 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -60,6 +60,8 @@ namespace armarx::navigation::server
         std::lock_guard g{mtx};
 
         drawLocalTrajectory(result.trajectory);
+        arviz.commit(layers);
+
     }
 
     // void
@@ -164,7 +166,7 @@ namespace armarx::navigation::server
                               [](const core::LocalTrajectoryPoint& pt) -> Eigen::Vector3f
                               { return pt.pose.translation(); });
 
-        layer.add(viz::Path("path").points(points).color(simox::Color::blue()));
+        layer.add(viz::Path("path").points(points).color(simox::Color::green()));
 
         layers.emplace_back(std::move(layer));
     }
-- 
GitLab


From 0df94b17744618adcc94ab252042738805bdc072 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:46:55 +0200
Subject: [PATCH 035/324] platform velocity

---
 source/armarx/navigation/core/types.h                 |  1 +
 .../navigation/local_planning/TimedElasticBands.cpp   |  9 +--------
 .../navigation/local_planning/ros_conversions.cpp     |  6 +++---
 .../server/scene_provider/SceneProvider.cpp           | 11 +++++++++++
 4 files changed, 16 insertions(+), 11 deletions(-)

diff --git a/source/armarx/navigation/core/types.h b/source/armarx/navigation/core/types.h
index 7d338dfd..9ce943ac 100644
--- a/source/armarx/navigation/core/types.h
+++ b/source/armarx/navigation/core/types.h
@@ -84,6 +84,7 @@ namespace armarx::navigation::core
         std::optional<core::DynamicScene> dynamicScene = std::nullopt;
 
         VirtualRobot::RobotPtr robot;
+        core::Twist platformVelocity = core::Twist::Zero();
 
         std::optional<core::SceneGraph> graph;
     };
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 5521a4c1..5c7e567c 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -108,14 +108,7 @@ namespace armarx::navigation::local_planning
         const FindTargetResult target = findTarget(currentPose, goal);
         const teb_local_planner::PoseSE2 end = conv::toRos(target.target);
 
-        core::Twist currentVelocity = core::Twist::Zero();
-
-        // FIXME: again, add to scene
-        // if (scene.platformVelocity.has_value())
-        // {
-        //     currentVelocity = scene.platformVelocity.value();
-        // }
-        geometry_msgs::Twist velocity_start = conv::toRos(currentVelocity);
+        geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity);
 
         //TODO (SALt): fill obstacles
 
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 4e08d37b..50043e80 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -46,9 +46,9 @@ namespace armarx::navigation::conv
     toRos(const core::Twist& velocity)
     {
         geometry_msgs::Twist ret;
-        ret.linear.x = velocity.linear.x(); // [mm] to [m]
-        ret.linear.y = velocity.linear.y(); // [mm] to [m]
-        ret.angular.z = velocity.angular.z(); // [mm] to [m]
+        ret.linear.x = velocity.linear.x() / 1000; // [mm] to [m]
+        ret.linear.y = velocity.linear.y() / 1000; // [mm] to [m]
+        ret.angular.z = velocity.angular.z();
 
         return ret;
     }
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index 804c4d03..b51208e2 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -1,8 +1,12 @@
 #include "SceneProvider.h"
 
 #include <VirtualRobot/SceneObjectSet.h>
+
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
+#include "RobotAPI/libraries/armem_robot/types.h"
+
+#include "armarx/navigation/core/types.h"
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
 #include <armarx/navigation/util/util.h>
 
@@ -47,6 +51,13 @@ namespace armarx::navigation::server::scene_provider
         scn.dynamicScene = getDynamicScene(timestamp);
         // scn.graph = getSceneGraph(timestamp);
 
+        const auto platformState = srv.virtualRobotReader->queryPlatformState(
+            armem::robot::RobotDescription{.name = scn.robot->getName()}, timestamp);
+        ARMARX_CHECK(platformState.has_value());
+
+        scn.platformVelocity = core::Twist{.linear = platformState->twist.linear,
+                                           .angular = platformState->twist.angular};
+
         return true; // TODO(fabian.reister): return false if sync fails
     }
 
-- 
GitLab


From 64b7566bbb940540c27fc9f402cb1dd2078e45ef Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:47:18 +0200
Subject: [PATCH 036/324] minor

---
 scenarios/HumanAwareNavigation/config/navigator.cfg | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index a9085fcd..0484c3f0 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -317,7 +317,7 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-ArmarX.Navigator.p.disableExecutor = 1
+ArmarX.Navigator.p.disableExecutor = false
 
 
 # ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
-- 
GitLab


From 42f236ada432ad520ff522a286a703ef0ca6914f Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 27 Jul 2022 22:47:22 +0200
Subject: [PATCH 037/324] large replanning period due to velocity issues

---
 source/armarx/navigation/server/Navigator.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index 5c236f3a..9f320724 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -67,7 +67,7 @@ namespace armarx::navigation::server
             {
                 struct
                 {
-                    int replanningUpdatePeriod{100}; // [ms]
+                    int replanningUpdatePeriod{20000}; // [ms]
                 } tasks;
             };
 
-- 
GitLab


From 53a68d11052b4ef19b1cb90a2a50eb009b29e692 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 28 Jul 2022 09:08:26 +0200
Subject: [PATCH 038/324] replanning 10Hz

---
 source/armarx/navigation/server/Navigator.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index 9f320724..5c236f3a 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -67,7 +67,7 @@ namespace armarx::navigation::server
             {
                 struct
                 {
-                    int replanningUpdatePeriod{20000}; // [ms]
+                    int replanningUpdatePeriod{100}; // [ms]
                 } tasks;
             };
 
-- 
GitLab


From 71f14d0a8b938d0b15a81d9ffc1838f2e761e938 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 29 Jul 2022 09:46:43 +0200
Subject: [PATCH 039/324] ros conversion: ROS: x pointing forward, ArmarX: y
 pointing forward

---
 .../local_planning/ros_conversions.cpp        | 36 ++++++++++++++-----
 1 file changed, 27 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 50043e80..6b3ad309 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -1,4 +1,7 @@
 #include "ros_conversions.h"
+
+#include <cmath>
+
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 #include "ArmarXCore/core/time/Clock.h"
 #include "ArmarXCore/core/time/Duration.h"
@@ -6,7 +9,6 @@
 #include "armarx/navigation/core/Trajectory.h"
 #include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/conversions/eigen.h>
-
 #include <range/v3/view/drop.hpp>
 #include <range/v3/view/zip.hpp>
 
@@ -25,6 +27,10 @@ namespace armarx::navigation::conv
         Eigen::Vector2d pos = pose.translation().cast<double>();
         double theta = Eigen::Rotation2Df(pose.linear()).angle();
 
+        // we change it such that x is pointing forward.
+        // ROS: x pointing forward, ArmarX: y pointing forward
+        theta += M_PI_2;
+
         return {pos / 1000., theta}; // [mm] to [m]
     }
 
@@ -35,6 +41,11 @@ namespace armarx::navigation::conv
         Eigen::Vector2d pos = pose.position() * 1000; // [m] to [mm]
         double theta = pose.theta();
 
+        // we change it such that x is pointing forward.
+        // ROS: x pointing forward, ArmarX: y pointing forward
+        theta -= M_PI_2;
+
+
         core::Pose2D ret;
         ret.translation() = pos.cast<float>();
         ret.linear() = Eigen::Rotation2Df(theta).toRotationMatrix();
@@ -46,8 +57,12 @@ namespace armarx::navigation::conv
     toRos(const core::Twist& velocity)
     {
         geometry_msgs::Twist ret;
-        ret.linear.x = velocity.linear.x() / 1000; // [mm] to [m]
-        ret.linear.y = velocity.linear.y() / 1000; // [mm] to [m]
+
+        // we change it such that x is pointing forward.
+        // ROS: x pointing forward, ArmarX: y pointing forward
+
+        ret.linear.x = velocity.linear.y() / 1000; // [mm] to [m]
+        ret.linear.y = -velocity.linear.x() / 1000; // [mm] to [m]
         ret.angular.z = velocity.angular.z();
 
         return ret;
@@ -85,7 +100,7 @@ namespace armarx::navigation::conv
     {
         const auto& tebPoses = teb.poses();
 
-        if(tebPoses.empty())
+        if (tebPoses.empty())
         {
             return {};
         }
@@ -96,19 +111,22 @@ namespace armarx::navigation::conv
         // TODO this timestamp should be given via the argument list
         DateTime timestamp = Clock::Now();
 
-        ARMARX_CHECK_EQUAL(tebPoses.size()-1, teb.timediffs().size());
+        ARMARX_CHECK_EQUAL(tebPoses.size() - 1, teb.timediffs().size());
 
         // add the first pose at this timestamp
-        trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {fromRos(tebPoses.front()->pose())}});
+        trajectory.push_back(core::LocalTrajectoryPoint{
+            .timestamp = timestamp, .pose = {fromRos(tebPoses.front()->pose())}});
 
         // all consecutive poses
-        for (const auto& [poseVertex, timediff]: ranges::views::zip(tebPoses | ranges::views::drop(1), teb.timediffs()))
+        for (const auto& [poseVertex, timediff] :
+             ranges::views::zip(tebPoses | ranges::views::drop(1), teb.timediffs()))
         {
             const core::Pose pose = fromRos(poseVertex->pose());
             const Duration dt = Duration::SecondsDouble(timediff->dt());
 
-            timestamp += dt; 
-            trajectory.push_back(core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {pose}});
+            timestamp += dt;
+            trajectory.push_back(
+                core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {pose}});
         }
 
         ARMARX_CHECK_EQUAL(trajectory.size(), tebPoses.size());
-- 
GitLab


From 34f7bb2aca20646663541668c150a5bf44f1605e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 29 Jul 2022 17:28:00 +0200
Subject: [PATCH 040/324] Fix cmake

---
 source/armarx/navigation/platform_controller/CMakeLists.txt | 1 -
 1 file changed, 1 deletion(-)

diff --git a/source/armarx/navigation/platform_controller/CMakeLists.txt b/source/armarx/navigation/platform_controller/CMakeLists.txt
index dd919b00..78b24397 100644
--- a/source/armarx/navigation/platform_controller/CMakeLists.txt
+++ b/source/armarx/navigation/platform_controller/CMakeLists.txt
@@ -17,7 +17,6 @@ armarx_add_library(platform_controller
     aron_conversions.h
   DEPENDENCIES_PUBLIC
     Simox::VirtualRobot
-    armarx_control::common
     armarx_control::client
     armarx_navigation::core
     armarx_navigation::trajectory_control
-- 
GitLab


From 6b4729453013d6908b3c0334fff8ec6aed95b999 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 29 Jul 2022 19:35:03 +0200
Subject: [PATCH 041/324] Visualize velocity along LocalTrajectory in ArViz

---
 .../introspection/ArvizIntrospector.cpp       | 29 +++++++++++++++++--
 1 file changed, 26 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index a9d0dacd..c4e5551a 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -3,8 +3,6 @@
 #include <iterator>
 #include <string>
 
-#include <range/v3/view/enumerate.hpp>
-
 #include <Eigen/Geometry>
 
 #include <SimoxUtility/algorithm/apply.hpp>
@@ -26,6 +24,7 @@
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/server/StackResult.h>
 #include <armarx/navigation/util/Visualization.h>
+#include <range/v3/view/enumerate.hpp>
 
 namespace armarx::navigation::server
 {
@@ -61,7 +60,6 @@ namespace armarx::navigation::server
 
         drawLocalTrajectory(result.trajectory);
         arviz.commit(layers);
-
     }
 
     // void
@@ -168,7 +166,32 @@ namespace armarx::navigation::server
 
         layer.add(viz::Path("path").points(points).color(simox::Color::green()));
 
+
+        // Visualize trajectory speed
+        auto velLayer = arviz.layer("local_planner_velocity");
+
+        simox::ColorMap cm = simox::color::cmaps::inferno();
+        cm.set_vmin(0);
+        cm.set_vmax(1);
+
+        for (size_t i = 0; i < trajectory.size() - 1; i++)
+        {
+            const core::LocalTrajectoryPoint start = trajectory.at(i);
+            const core::LocalTrajectoryPoint end = trajectory.at(i + 1);
+
+            const Duration dT = end.timestamp - start.timestamp;
+            const Eigen::Vector3f distance = end.pose.translation() - start.pose.translation();
+            const float speed = distance.norm() / 1000 / dT.toSecondsDouble();
+
+            const Eigen::Vector3f pos = start.pose.translation() + distance / 2;
+            const simox::Color color = cm.at(speed);
+
+            velLayer.add(
+                viz::Sphere("velocity_" + std::to_string(i)).position(pos).radius(50).color(color));
+        }
+
         layers.emplace_back(std::move(layer));
+        layers.emplace_back(std::move(velLayer));
     }
 
     void
-- 
GitLab


From 402ec880f3a4709a3b0c7e72218eebca2cc5fcea Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 29 Jul 2022 19:35:28 +0200
Subject: [PATCH 042/324] Use next point in LocalTrajectoryController

TODO: interpolate point
---
 .../local/TrajectoryFollowingController.cpp               | 8 ++------
 1 file changed, 2 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
index df64d939..52617b9c 100644
--- a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
@@ -142,12 +142,8 @@ namespace armarx::navigation::traj_ctrl::local
 
         const std::size_t pos = std::distance(trajectory.begin(), lower);
 
-        if (pos == 0)
-        {
-            return trajectory.front().pose;
-        }
-
-        return trajectory.at(pos - 1).pose;
+        //TODO: interpolate
+        return trajectory.at(pos).pose;
     }
 
     TrajectoryControllerResult
-- 
GitLab


From 1d6dd4badb3e6ba2f5cdac2f0e277f5e14efd096 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 31 Jul 2022 00:01:02 +0200
Subject: [PATCH 043/324] Implement evaluate method for LocalTrajectory

Convert LocalTrajectory to a proper class so the evaluate method can be
implemented. Let LocalTrajectoryController use evaluate method.
---
 source/armarx/navigation/core/Trajectory.cpp  | 41 +++++++++++++++++++
 source/armarx/navigation/core/Trajectory.h    | 30 +++++++++++++-
 .../navigation/core/aron_conversions.cpp      |  2 +-
 .../local_planning/ros_conversions.cpp        |  4 +-
 .../PlatformLocalTrajectoryController.cpp     |  6 +--
 .../execution/PlatformControllerExecutor.cpp  |  2 +-
 .../introspection/ArvizIntrospector.cpp       |  8 ++--
 .../local/TrajectoryFollowingController.cpp   | 24 ++---------
 8 files changed, 85 insertions(+), 32 deletions(-)

diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index 5b200574..6734b686 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -676,4 +676,45 @@ namespace armarx::navigation::core
     }
 
 
+    const std::vector<LocalTrajectoryPoint>&
+    LocalTrajectory::points() const
+    {
+        return pts;
+    }
+
+    std::vector<LocalTrajectoryPoint>&
+    LocalTrajectory::mutablePoints()
+    {
+        return pts;
+    }
+
+    Evaluation
+    LocalTrajectory::evaluate(armarx::core::time::DateTime timestamp) const
+    {
+        const auto cmp = [](const core::LocalTrajectoryPoint& lhs,
+                            const DateTime& timestamp) -> bool
+        { return lhs.timestamp < timestamp; };
+
+        const auto lower = std::lower_bound(pts.begin(), pts.end(), timestamp, cmp);
+
+        if (lower == pts.end() - 1)
+        {
+            // if we arrived at the last point, the velocity is 0
+            return {lower->pose, 0};
+        }
+
+        const Duration d1 = timestamp - lower->timestamp;
+        const Duration dT = lower[1].timestamp - lower->timestamp;
+
+        // fraction of time between segment end points
+        const float t = d1 / dT;
+        math::LinearInterpolatedPose ip(lower->pose.matrix(), lower[1].pose.matrix(), 0, 1, true);
+
+        const Eigen::Vector3f distance = lower[1].pose.translation() - lower->pose.translation();
+        const float speed = distance.norm() / 1000 / dT.toSecondsDouble();
+
+        return {static_cast<core::Pose>(ip.Get(t)), speed};
+    }
+
+
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h
index 747c1cc3..19745b6d 100644
--- a/source/armarx/navigation/core/Trajectory.h
+++ b/source/armarx/navigation/core/Trajectory.h
@@ -122,13 +122,41 @@ namespace armarx::navigation::core
         std::vector<GlobalTrajectoryPoint> pts;
     };
 
+
     struct LocalTrajectoryPoint
     {
         DateTime timestamp;
         core::Pose pose;
     };
 
-    using LocalTrajectory = std::vector<LocalTrajectoryPoint>;
+    using LocalTrajectoryPoints = std::vector<LocalTrajectoryPoint>;
+
+    struct Evaluation
+    {
+        core::Pose pose;
+        float velocity; // [mm/s]
+    };
+
+
+    class LocalTrajectory
+    {
+    public:
+        LocalTrajectory() = default;
+
+        LocalTrajectory(const std::vector<LocalTrajectoryPoint>& points) : pts(points)
+        {
+        }
+
+        const std::vector<LocalTrajectoryPoint>& points() const;
+
+        std::vector<LocalTrajectoryPoint>& mutablePoints();
+
+        Evaluation evaluate(DateTime timestamp) const;
+
+
+    private:
+        std::vector<LocalTrajectoryPoint> pts;
+    };
 
 
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/aron_conversions.cpp b/source/armarx/navigation/core/aron_conversions.cpp
index fae8aa97..5da2122f 100644
--- a/source/armarx/navigation/core/aron_conversions.cpp
+++ b/source/armarx/navigation/core/aron_conversions.cpp
@@ -77,7 +77,7 @@ namespace armarx::navigation::core
     void
     toAron(arondto::LocalTrajectory& dto, const LocalTrajectory& bo)
     {
-        dto.points = bo |
+        dto.points = bo.points() |
                      ranges::views::transform(
                          [](const LocalTrajectoryPoint& boTp) -> arondto::LocalTrajectoryPoint
                          {
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 6b3ad309..86a9aab1 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -105,7 +105,7 @@ namespace armarx::navigation::conv
             return {};
         }
 
-        core::LocalTrajectory trajectory;
+        core::LocalTrajectoryPoints trajectory;
         trajectory.reserve(tebPoses.size());
 
         // TODO this timestamp should be given via the argument list
@@ -131,7 +131,7 @@ namespace armarx::navigation::conv
 
         ARMARX_CHECK_EQUAL(trajectory.size(), tebPoses.size());
 
-        return trajectory;
+        return {trajectory};
     }
 
 
diff --git a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
index eff20f7b..c27f2f23 100644
--- a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
+++ b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
@@ -81,7 +81,7 @@ namespace armarx::navigation::platform_controller::platform_local_trajectory
         auto updateConfig = ::armarx::fromAron<arondto::Config, Config>(dto);
         configBuffer.reinitAllBuffers(updateConfig);
 
-        ARMARX_INFO << "Trajectory with " << updateConfig.targets.trajectory.size();
+        ARMARX_INFO << "Trajectory with " << updateConfig.targets.trajectory.points().size();
 
         ARMARX_IMPORTANT << "done Controller::updateConfig";
     }
@@ -92,7 +92,7 @@ namespace armarx::navigation::platform_controller::platform_local_trajectory
         ARMARX_CHECK(trajectoryFollowingController.has_value());
 
         // if trajectory is empty, set velocity to 0
-        if (configBuffer.getUpToDateReadBuffer().targets.trajectory.empty())
+        if (configBuffer.getUpToDateReadBuffer().targets.trajectory.points().empty())
         {
             ARMARX_INFO << deactivateSpam(1) << "Trajectory is empty!";
 
@@ -126,7 +126,7 @@ namespace armarx::navigation::platform_controller::platform_local_trajectory
         datafields["vy"] = new Variant(rtGetControlStruct().platformVelocityTargets.y);
         datafields["vyaw"] = new Variant(rtGetControlStruct().platformVelocityTargets.yaw);
         datafields["trajectory_points"] =
-            new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.size());
+            new Variant(configBuffer.getUpToDateReadBuffer().targets.trajectory.points().size());
 
         debugObservers->setDebugChannel(
             common::ControllerTypeNames.to_name(common::ControllerType::PlatformLocalTrajectory),
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index 9ba41405..ef507743 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -73,7 +73,7 @@ namespace armarx::navigation::server
     void
     PlatformControllerExecutor::execute(const core::LocalTrajectory& trajectory)
     {
-        ARMARX_INFO << "Received trajectory for execution with " << trajectory.size()
+        ARMARX_INFO << "Received trajectory for execution with " << trajectory.points().size()
                     << " points";
 
         toAron(ctrl->config.targets.trajectory, trajectory);
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index c4e5551a..694ff174 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -160,7 +160,7 @@ namespace armarx::navigation::server
         auto layer = arviz.layer("local_planner");
 
         const std::vector<Eigen::Vector3f> points =
-            simox::alg::apply(trajectory,
+            simox::alg::apply(trajectory.points(),
                               [](const core::LocalTrajectoryPoint& pt) -> Eigen::Vector3f
                               { return pt.pose.translation(); });
 
@@ -174,10 +174,10 @@ namespace armarx::navigation::server
         cm.set_vmin(0);
         cm.set_vmax(1);
 
-        for (size_t i = 0; i < trajectory.size() - 1; i++)
+        for (size_t i = 0; i < trajectory.points().size() - 1; i++)
         {
-            const core::LocalTrajectoryPoint start = trajectory.at(i);
-            const core::LocalTrajectoryPoint end = trajectory.at(i + 1);
+            const core::LocalTrajectoryPoint start = trajectory.points().at(i);
+            const core::LocalTrajectoryPoint end = trajectory.points().at(i + 1);
 
             const Duration dT = end.timestamp - start.timestamp;
             const Eigen::Vector3f distance = end.pose.translation() - start.pose.translation();
diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
index 52617b9c..e4e2cbc4 100644
--- a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
@@ -130,28 +130,12 @@ namespace armarx::navigation::traj_ctrl::local
         return twist;
     }
 
-    core::Pose
-    evaluateTrajectoryAt(const core::LocalTrajectory& trajectory, const DateTime& timestamp)
-    {
-        const auto cmp = [](const core::LocalTrajectoryPoint& lhs,
-                            const DateTime& timestamp) -> bool
-        { return lhs.timestamp < timestamp; };
-
-        const auto lower = std::lower_bound(trajectory.begin(), trajectory.end(), timestamp, cmp);
-        // const auto upper = std::upper_bound(trajectory.begin(), trajectory.end(), timestamp, cmp);
-
-        const std::size_t pos = std::distance(trajectory.begin(), lower);
-
-        //TODO: interpolate
-        return trajectory.at(pos).pose;
-    }
-
     TrajectoryControllerResult
     TrajectoryFollowingController::control(const core::LocalTrajectory& trajectory)
     {
         ARMARX_CHECK_NOT_NULL(robot) << "Robot not available";
 
-        if (trajectory.empty())
+        if (trajectory.points().empty())
         {
             ARMARX_INFO << "Trajectory is empty.";
             return TrajectoryControllerResult{.twist = core::Twist::Zero()};
@@ -162,13 +146,13 @@ namespace armarx::navigation::traj_ctrl::local
         // TOOD maybe set via arg?
         const DateTime timestamp = Clock::Now();
 
-        const core::Pose targetPose = evaluateTrajectoryAt(trajectory, timestamp);
+        const core::Evaluation target = trajectory.evaluate(timestamp);
 
         using simox::math::mat4f_to_pos;
         using simox::math::mat4f_to_rpy;
 
-        pidPos.update(mat4f_to_pos(currentPose.matrix()), mat4f_to_pos(targetPose.matrix()));
-        pidOri.update(mat4f_to_rpy(currentPose.matrix()), mat4f_to_rpy(targetPose.matrix()));
+        pidPos.update(mat4f_to_pos(currentPose.matrix()), mat4f_to_pos(target.pose.matrix()));
+        pidOri.update(mat4f_to_rpy(currentPose.matrix()), mat4f_to_rpy(target.pose.matrix()));
 
         const core::Twist twist{.linear = pidPos.getControlValue(),
                                 .angular = pidOri.getControlValue()};
-- 
GitLab


From 244b4eae00973ccfa61ac53562b0336b092e1eb8 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 31 Jul 2022 01:44:34 +0200
Subject: [PATCH 044/324] Adjust global path weight

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 5c7e567c..e945c0ec 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -91,7 +91,7 @@ namespace armarx::navigation::local_planning
         cfg_.hcp.selection_cost_hysteresis = 1.0;
         cfg_.hcp.switching_blocking_period = 0;
 
-        cfg_.pse.weight_global_path = 0.25;
+        cfg_.pse.weight_global_path = 0.6;
     }
 
     std::optional<LocalPlannerResult>
-- 
GitLab


From 7d3c0042c5b2430c2c91017f36c67d7273746e13 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 31 Jul 2022 05:57:08 +0200
Subject: [PATCH 045/324] Fix trajectory evaluation velocity unit

---
 source/armarx/navigation/core/Trajectory.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index 6734b686..ce659b7c 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -711,7 +711,7 @@ namespace armarx::navigation::core
         math::LinearInterpolatedPose ip(lower->pose.matrix(), lower[1].pose.matrix(), 0, 1, true);
 
         const Eigen::Vector3f distance = lower[1].pose.translation() - lower->pose.translation();
-        const float speed = distance.norm() / 1000 / dT.toSecondsDouble();
+        const float speed = distance.norm() / dT.toSecondsDouble();
 
         return {static_cast<core::Pose>(ip.Get(t)), speed};
     }
-- 
GitLab


From 9784df96d9555f70225155975987bfaaaec2fcae Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 31 Jul 2022 06:19:55 +0200
Subject: [PATCH 046/324] Implement TebObstacleManager

Add static obstacles to teb for optimization.
---
 .../navigation/local_planning/CMakeLists.txt  |  2 +
 .../local_planning/TebObstacleManager.cpp     | 39 +++++++++++++++
 .../local_planning/TebObstacleManager.h       | 49 +++++++++++++++++++
 .../local_planning/TimedElasticBands.cpp      | 25 ++++++++--
 .../local_planning/TimedElasticBands.h        |  5 +-
 .../local_planning/ros_conversions.cpp        |  8 +++
 .../local_planning/ros_conversions.h          |  2 +
 7 files changed, 124 insertions(+), 6 deletions(-)
 create mode 100644 source/armarx/navigation/local_planning/TebObstacleManager.cpp
 create mode 100644 source/armarx/navigation/local_planning/TebObstacleManager.h

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 5cd3b287..9d0cd30a 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -18,11 +18,13 @@ armarx_add_library(local_planning
     SOURCES 
         LocalPlanner.cpp
         TimedElasticBands.cpp
+        TebObstacleManager.cpp
         ros_conversions.cpp
         aron_conversions.cpp
     HEADERS
         LocalPlanner.h
         TimedElasticBands.h
+        TebObstacleManager.h
         ros_conversions.h
         core.h
         aron_conversions.h
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
new file mode 100644
index 00000000..2db7ec86
--- /dev/null
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -0,0 +1,39 @@
+#include "TebObstacleManager.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+
+#include <armarx/navigation/local_planning/ros_conversions.h>
+
+namespace armarx::navigation::local_planning
+{
+
+    void
+    TebObstacleManager::clear()
+    {
+        container.clear();
+    }
+
+    size_t
+    TebObstacleManager::size()
+    {
+        return container.size();
+    }
+
+    void
+    TebObstacleManager::addBoxObstacle(const VirtualRobot::BoundingBox& bbox)
+    {
+        auto obst = boost::make_shared<teb_local_planner::PolygonObstacle>();
+
+        const Eigen::Vector2d min = conv::toRos(bbox.getMin());
+        const Eigen::Vector2d max = conv::toRos(bbox.getMin());
+
+        obst->pushBackVertex(min);
+        obst->pushBackVertex(max);
+        obst->pushBackVertex(min.x(), max.y());
+        obst->pushBackVertex(max.x(), min.y());
+
+        obst->finalizePolygon();
+        container.push_back(obst);
+    }
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
new file mode 100644
index 00000000..52783b65
--- /dev/null
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -0,0 +1,49 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+#pragma once
+
+#include <VirtualRobot/CollisionDetection/CollisionModel.h>
+
+#include <teb_local_planner/obstacles.h>
+
+namespace armarx::navigation::local_planning
+{
+
+
+    class TebObstacleManager
+    {
+    public:
+        TebObstacleManager(teb_local_planner::ObstContainer& container) : container(container)
+        {
+        }
+
+        void clear();
+
+        size_t size();
+
+        void addBoxObstacle(const VirtualRobot::BoundingBox& bbox);
+
+    private:
+        teb_local_planner::ObstContainer& container;
+    };
+
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index e945c0ec..eeb9c238 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -2,6 +2,7 @@
 
 #include <VirtualRobot/MathTools.h>
 #include <VirtualRobot/Robot.h>
+#include <VirtualRobot/SceneObjectSet.h>
 
 #include <ArmarXCore/core/logging/Logging.h>
 
@@ -54,7 +55,7 @@ namespace armarx::navigation::local_planning
     // TimedElasticBands
 
     TimedElasticBands::TimedElasticBands(const Params& params, const core::Scene& ctx) :
-        LocalPlanner(ctx), params(params), scene(ctx)
+        LocalPlanner(ctx), params(params), scene(ctx), obstManager(teb_obstacles)
     {
         //TODO (SALt): init configuration, robot footprint
         initConfig();
@@ -111,13 +112,11 @@ namespace armarx::navigation::local_planning
         geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity);
 
         //TODO (SALt): fill obstacles
-
-        // TODO (SALt): implement
-        bool planToDest = true;
+        fillObstacles();
 
         try
         {
-            hcp_->plan(start, end, &velocity_start, !planToDest);
+            hcp_->plan(start, end, &velocity_start, !target.planToDestination);
         }
         catch (std::exception& e)
         {
@@ -137,6 +136,7 @@ namespace armarx::navigation::local_planning
     TimedElasticBands::findTarget(const core::Pose& currentPose,
                                   const core::GlobalTrajectory& globalPath)
     {
+        // TODO (SALt): implement
 
         const core::Projection projection = globalPath.getProjection(
             currentPose.translation(), core::VelocityInterpolation::LinearInterpolation);
@@ -146,4 +146,19 @@ namespace armarx::navigation::local_planning
                 true};
     }
 
+    void
+    TimedElasticBands::fillObstacles()
+    {
+        obstManager.clear();
+
+        if (scene.staticScene.has_value())
+        {
+            for (auto& obst : scene.staticScene.value().objects->getCollisionModels())
+            {
+                obstManager.addBoxObstacle(obst->getGlobalBoundingBox());
+            }
+        }
+        ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";
+    }
+
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index e0497708..26826650 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -27,6 +27,7 @@
 #include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
+#include <armarx/navigation/local_planning/TebObstacleManager.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 #include <teb_local_planner/teb_config.h>
@@ -68,15 +69,17 @@ namespace armarx::navigation::local_planning
         void initConfig();
         FindTargetResult findTarget(const core::Pose& currentPose,
                                     const core::GlobalTrajectory& globalPath);
+        void fillObstacles();
 
     protected:
         const Params params;
 
     private:
         const core::Scene& scene;
-        
+
         teb_local_planner::TebConfig cfg_;
         teb_local_planner::ObstContainer teb_obstacles;
+        TebObstacleManager obstManager;
         teb_local_planner::PoseSequence teb_globalPath;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
     };
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 86a9aab1..3ad81d9c 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -14,6 +14,14 @@
 
 namespace armarx::navigation::conv
 {
+
+    Eigen::Vector2d
+    toRos(const Eigen::Vector3f& vec)
+    {
+        return conv::to2D(vec).cast<double>() / 1000;
+    }
+
+
     teb_local_planner::PoseSE2
     toRos(const core::Pose& pose)
     {
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 25a28c40..60b1fb4f 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -30,6 +30,8 @@
 namespace armarx::navigation::conv
 {
 
+    Eigen::Vector2d toRos(const Eigen::Vector3f& vec);
+
     teb_local_planner::PoseSE2 toRos(const core::Pose& pose);
     teb_local_planner::PoseSE2 toRos(const core::Pose2D& pose);
 
-- 
GitLab


From 70c56140ef6e01ceaa94e6d4e7c993343a8f5fac Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 2 Aug 2022 14:12:32 +0200
Subject: [PATCH 047/324] local trajectory: evaluate returns twist; platform
 controller used feed forward term

---
 source/armarx/navigation/core/CMakeLists.txt  |  1 +
 source/armarx/navigation/core/Trajectory.cpp  | 33 ++++++++++++++++---
 source/armarx/navigation/core/Trajectory.h    |  4 +--
 source/armarx/navigation/core/basic_types.cpp | 18 ++++++++++
 source/armarx/navigation/core/basic_types.h   | 10 ++++++
 source/armarx/navigation/core/types.cpp       | 24 +++++++-------
 source/armarx/navigation/core/types.h         | 10 +-----
 .../local/TrajectoryFollowingController.cpp   | 11 ++++++-
 8 files changed, 82 insertions(+), 29 deletions(-)
 create mode 100644 source/armarx/navigation/core/basic_types.cpp

diff --git a/source/armarx/navigation/core/CMakeLists.txt b/source/armarx/navigation/core/CMakeLists.txt
index 4ee7e461..d95cd0ed 100644
--- a/source/armarx/navigation/core/CMakeLists.txt
+++ b/source/armarx/navigation/core/CMakeLists.txt
@@ -13,6 +13,7 @@ armarx_add_library(core
     SOURCES
         StaticScene.cpp
         Trajectory.cpp
+        basic_types.cpp
         types.cpp
         Graph.cpp
         aron_conversions.cpp
diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index ce659b7c..e1774afa 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -689,7 +689,7 @@ namespace armarx::navigation::core
     }
 
     Evaluation
-    LocalTrajectory::evaluate(armarx::core::time::DateTime timestamp) const
+    LocalTrajectory::evaluate(const armarx::core::time::DateTime& timestamp) const
     {
         const auto cmp = [](const core::LocalTrajectoryPoint& lhs,
                             const DateTime& timestamp) -> bool
@@ -700,20 +700,43 @@ namespace armarx::navigation::core
         if (lower == pts.end() - 1)
         {
             // if we arrived at the last point, the velocity is 0
-            return {lower->pose, 0};
+            return {lower->pose, core::Twist::Zero()};
         }
 
         const Duration d1 = timestamp - lower->timestamp;
         const Duration dT = lower[1].timestamp - lower->timestamp;
 
+        // the waypoint before this timestamp
+        const auto& global_T_wp_before = lower->pose;
+
+        // the waypoint after this timestamp
+        const auto& global_T_wp_after = lower[1].pose;
+
         // fraction of time between segment end points
         const float t = d1 / dT;
-        math::LinearInterpolatedPose ip(lower->pose.matrix(), lower[1].pose.matrix(), 0, 1, true);
+        math::LinearInterpolatedPose ip(global_T_wp_before.matrix(), global_T_wp_after.matrix(), 0, 1, true);
+
+        const core::Pose wp_before_T_wp_after = global_T_wp_before.inverse() * global_T_wp_after;
 
+        const Eigen::Matrix3f& global_R_wp_before = global_T_wp_before.linear();
+
+        // the movement direction in the global frame
+        const Eigen::Vector3f global_V_linear_movement_direction = global_R_wp_before * wp_before_T_wp_after.translation().normalized();
         const Eigen::Vector3f distance = lower[1].pose.translation() - lower->pose.translation();
-        const float speed = distance.norm() / dT.toSecondsDouble();
+        const float linearVelocity = static_cast<float>(distance.norm()) / dT.toSecondsDouble();
+
+
+        // angular velocity
+
+        Eigen::AngleAxisf angleAx(wp_before_T_wp_after.linear());
+
+        const core::Twist feedforwardTwist
+        {
+            .linear = linearVelocity * global_V_linear_movement_direction,
+            .angular = angleAx.axis() * angleAx.angle() / dT.toSecondsDouble()
+        };
 
-        return {static_cast<core::Pose>(ip.Get(t)), speed};
+        return {static_cast<core::Pose>(ip.Get(t)), feedforwardTwist};
     }
 
 
diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h
index 19745b6d..5b2ba33a 100644
--- a/source/armarx/navigation/core/Trajectory.h
+++ b/source/armarx/navigation/core/Trajectory.h
@@ -134,7 +134,7 @@ namespace armarx::navigation::core
     struct Evaluation
     {
         core::Pose pose;
-        float velocity; // [mm/s]
+        core::Twist feedforwardTwist; // [mm/s]
     };
 
 
@@ -151,7 +151,7 @@ namespace armarx::navigation::core
 
         std::vector<LocalTrajectoryPoint>& mutablePoints();
 
-        Evaluation evaluate(DateTime timestamp) const;
+        Evaluation evaluate(const DateTime& timestamp) const;
 
 
     private:
diff --git a/source/armarx/navigation/core/basic_types.cpp b/source/armarx/navigation/core/basic_types.cpp
new file mode 100644
index 00000000..460c560b
--- /dev/null
+++ b/source/armarx/navigation/core/basic_types.cpp
@@ -0,0 +1,18 @@
+#include "basic_types.h"
+
+namespace armarx::navigation::core
+{
+    core::Pose
+    Twist::poseDiff(const float dt) const
+    {
+        return core::Pose(Eigen::Translation3f(linear * dt)) *
+               core::Pose(Eigen::AngleAxisf(angular.norm() * dt, angular.normalized()));
+    }
+
+    Twist
+    Twist::Zero()
+    {
+        static const core::Twist zero{Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero()};
+        return zero;
+    }
+} // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/basic_types.h b/source/armarx/navigation/core/basic_types.h
index 0917270d..6121a739 100644
--- a/source/armarx/navigation/core/basic_types.h
+++ b/source/armarx/navigation/core/basic_types.h
@@ -50,4 +50,14 @@ namespace armarx::navigation::core
         Pose pose;
     };
 
+    struct Twist
+    {
+        LinearVelocity linear;
+        AngularVelocity angular;
+
+        Pose poseDiff(float dt) const;
+
+        static Twist Zero();
+    };
+
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/types.cpp b/source/armarx/navigation/core/types.cpp
index 346cd4de..7a25d928 100644
--- a/source/armarx/navigation/core/types.cpp
+++ b/source/armarx/navigation/core/types.cpp
@@ -2,17 +2,17 @@
 
 namespace armarx::navigation::core
 {
-    core::Pose
-    Twist::poseDiff(const float dt) const
-    {
-        return core::Pose(Eigen::Translation3f(linear * dt)) *
-               core::Pose(Eigen::AngleAxisf(angular.norm() * dt, angular.normalized()));
-    }
+    // core::Pose
+    // Twist::poseDiff(const float dt) const
+    // {
+    //     return core::Pose(Eigen::Translation3f(linear * dt)) *
+    //            core::Pose(Eigen::AngleAxisf(angular.norm() * dt, angular.normalized()));
+    // }
 
-    Twist
-    Twist::Zero()
-    {
-        static const core::Twist zero{Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero()};
-        return zero;
-    }
+    // Twist
+    // Twist::Zero()
+    // {
+    //     static const core::Twist zero{Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero()};
+    //     return zero;
+    // }
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/types.h b/source/armarx/navigation/core/types.h
index 9ce943ac..ade2630f 100644
--- a/source/armarx/navigation/core/types.h
+++ b/source/armarx/navigation/core/types.h
@@ -58,15 +58,7 @@ namespace armarx::navigation::core
     };
 
 
-    struct Twist
-    {
-        LinearVelocity linear;
-        AngularVelocity angular;
-
-        Pose poseDiff(float dt) const;
-
-        static Twist Zero();
-    };
+    
 
 
     class TimeServerInterface;
diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
index e4e2cbc4..a16cb656 100644
--- a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
@@ -154,9 +154,18 @@ namespace armarx::navigation::traj_ctrl::local
         pidPos.update(mat4f_to_pos(currentPose.matrix()), mat4f_to_pos(target.pose.matrix()));
         pidOri.update(mat4f_to_rpy(currentPose.matrix()), mat4f_to_rpy(target.pose.matrix()));
 
-        const core::Twist twist{.linear = pidPos.getControlValue(),
+
+        const core::Twist& twistFeedForward = target.feedforwardTwist;
+
+        const core::Twist twistError{.linear = pidPos.getControlValue(),
                                 .angular = pidOri.getControlValue()};
 
+        const core::Twist twist
+        {
+            .linear = twistFeedForward.linear + twistError.linear,
+            .angular = twistFeedForward.angular + twistError.angular
+        };
+
         const auto twistLimited = applyTwistLimits(twist);
         ARMARX_VERBOSE << deactivateSpam(1) << "Twist limited " << twistLimited.linear.transpose();
         ARMARX_VERBOSE << deactivateSpam(1) << "Twist angular " << twistLimited.angular.transpose();
-- 
GitLab


From 1d26f4fc4b567a2cb73c5c48fcdba3aaa2bd6b7e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 2 Aug 2022 18:25:07 +0200
Subject: [PATCH 048/324] teb: config update

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index eeb9c238..f0495713 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -93,6 +93,8 @@ namespace armarx::navigation::local_planning
         cfg_.hcp.switching_blocking_period = 0;
 
         cfg_.pse.weight_global_path = 0.6;
+
+        cfg_.trajectory.global_plan_overwrite_orientation = true;
     }
 
     std::optional<LocalPlannerResult>
-- 
GitLab


From 103dc370a69c6c25042e4bcdbdd247ee758a6734 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 2 Aug 2022 18:25:34 +0200
Subject: [PATCH 049/324] faster!

---
 .../controller_config/PlatformTrajectory/default.json         | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/data/armarx_navigation/controller_config/PlatformTrajectory/default.json b/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
index 4cd38813..c9ffcb3f 100644
--- a/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
+++ b/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
@@ -11,8 +11,8 @@
       "Kd": 0
     },
     "limits": {
-      "linear": 300,
-      "angular": 0.2
+      "linear": 500,
+      "angular": 0.5
     }
   },
   "targets": {
-- 
GitLab


From 4eaa0f8b4b376a8906056e32a4ed3e8aff92d81f Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 3 Aug 2022 15:01:24 +0200
Subject: [PATCH 050/324] Small fix (add const to iterator)

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index eeb9c238..70b692b0 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -153,7 +153,7 @@ namespace armarx::navigation::local_planning
 
         if (scene.staticScene.has_value())
         {
-            for (auto& obst : scene.staticScene.value().objects->getCollisionModels())
+            for (const auto& obst : scene.staticScene.value().objects->getCollisionModels())
             {
                 obstManager.addBoxObstacle(obst->getGlobalBoundingBox());
             }
-- 
GitLab


From 169d91b4471301ccdb78d71463c2e63f849f9ec3 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 3 Aug 2022 15:01:49 +0200
Subject: [PATCH 051/324] Add teb default config as json

---
 .../TimedElasticBands/default.json            | 150 ++++++++++++++++++
 1 file changed, 150 insertions(+)
 create mode 100644 data/armarx_navigation/local_planner_config/TimedElasticBands/default.json

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
new file mode 100644
index 00000000..344df69e
--- /dev/null
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -0,0 +1,150 @@
+
+{
+  "odom_topic": "odom",
+  "map_frame": "odom",
+
+  "pse": {
+    "pse_costum_obstacle_penalties": true,
+    "pse_costum_obstacle_penalties_dynamic": true,
+    "weight_global_path": 0.1,
+    "lrk_use_alternative_approach": false,
+    "lrk_enable_collision_check": true,
+    "hybrid_homotopy_calculation": true,
+    "robot_diff_circumscribed_inscribed_radius": 0.0
+  },
+
+  "trajectory": {
+    "teb_autosize": true,
+    "dt_ref": 0.3,
+    "dt_hysteresis": 0.1,
+    "min_samples": 3,
+    "max_samples": 500,
+    "global_plan_overwrite_orientation": true,
+    "allow_init_with_backwards_motion": false,
+    "global_plan_viapoint_sep": -1,
+    "via_points_ordered": false,
+    "max_global_plan_lookahead_dist": 1,
+    "global_plan_prune_distance": 1,
+    "exact_arc_length": false,
+    "force_reinit_new_goal_dist": 1,
+    "force_reinit_new_goal_angular": 0.5 * M_PI,
+    "feasibility_check_no_poses": 5,
+    "feasibility_check_lookahead_distance": -1,
+    "publish_feedback": false,
+    "min_resolution_collision_check_angular": M_PI,
+    "control_look_ahead_poses": 1
+  },
+
+  "robot": {
+    "max_vel_x": 0.4,
+    "max_vel_x_backwards": 0.2,
+    "max_vel_y": 0.0,
+    "max_vel_theta": 0.3,
+    "acc_lim_x": 0.5,
+    "acc_lim_y": 0.5,
+    "acc_lim_theta": 0.5,
+    "min_turning_radius": 0,
+    "wheelbase": 1.0,
+    "cmd_angle_instead_rotvel": false,
+    "is_footprint_dynamic": false,
+    "use_proportional_saturation": false,
+    "transform_tolerance": 0.5
+  },
+
+  "goal_tolerance": {
+    "xy_goal_tolerance": 0.2,
+    "yaw_goal_tolerance": 0.2,
+    "free_goal_vel": false,
+    "complete_global_plan": true
+
+  },
+
+  "obstacles": {
+    "min_obstacle_dist": 0.5,
+    "inflation_dist": 0.0,
+    "dynamic_obstacle_inflation_dist": 0.6,
+    "include_dynamic_obstacles": true,
+    "include_costmap_obstacles": true,
+    "costmap_obstacles_behind_robot_dist": 1.5,
+    "obstacle_poses_affected": 25,
+    "legacy_obstacle_association": false,
+    "obstacle_association_force_inclusion_factor": 1.5,
+    "obstacle_association_cutoff_factor": 5,
+    "costmap_converter_plugin": "",
+    "costmap_converter_spin_thread": true,
+    "costmap_converter_rate": 5,
+    "obstacle_proximity_ratio_max_vel": 1,
+    "obstacle_proximity_lower_bound": 0,
+    "obstacle_proximity_upper_bound": 0.5
+  },
+
+  "optim": {
+    "no_inner_iterations": 5,
+    "no_outer_iterations": 4,
+    "optimization_activate": true,
+    "optimization_verbose": false,
+    "penalty_epsilon": 0.05,
+    "weight_max_vel_x": 2,
+    "weight_max_vel_y": 2,
+    "weight_max_vel_theta": 1,
+    "weight_acc_lim_x": 1,
+    "weight_acc_lim_y": 1,
+    "weight_acc_lim_theta": 1,
+    "weight_kinematics_nh": 1000,
+    "weight_kinematics_forward_drive": 1,
+    "weight_kinematics_turning_radius": 1,
+    "weight_optimaltime": 1,
+    "weight_shortest_path": 0,
+    "weight_obstacle": 50,
+    "weight_inflation": 0.1,
+    "weight_dynamic_obstacle": 50,
+    "weight_dynamic_obstacle_inflation": 0.1,
+    "weight_velocity_obstacle_ratio": 0,
+    "weight_viapoint": 1,
+    "weight_prefer_rotdir": 50,
+    "weight_adapt_factor": 2.0,
+    "obstacle_cost_exponent": 1.0
+  },
+
+  "hcp": {
+    "enable_homotopy_class_planning": true,
+    "enable_multithreading": true,
+    "simple_exploration": false,
+    "max_number_classes": 5,
+    "max_number_plans_in_current_class" 0,
+    "selection_cost_hysteresis": 1.0,
+    "selection_prefer_initial_plan": 0.95,
+    "selection_obst_cost_scale": 100.0,
+    "selection_viapoint_cost_scale": 1.0,
+    "selection_alternative_time_cost": false,
+    "selection_dropping_probability": 0.0,
+    "switching_blocking_period": 0.0,
+
+    "obstacle_keypoint_offset": 0.1,
+    "obstacle_heading_threshold": 0.45,
+    "roadmap_graph_no_samples": 20,
+    "roadmap_graph_area_width": 10,
+    "roadmap_graph_area_length_scale": 1.0,
+    "h_signature_prescaler": 1,
+    "h_signature_threshold": 0.1,
+
+    "viapoints_all_candidates": true,
+
+    "visualize_hc_graph": false,
+    "visualize_with_time_as_z_axis_scale": 0.0,
+    "delete_detours_backwards": true,
+    "detours_orientation_tolerance": M_PI / 2.0,
+    "length_start_orientation_vector": 0.4,
+    "max_ratio_detours_duration_best_duration": 3.0,
+  },
+
+  "recovery": {
+    "shrink_horizon_backup": true,
+    "shrink_horizon_min_duration": 10,
+    "oscillation_recovery": true,
+    "oscillation_v_eps": 0.1,
+    "oscillation_omega_eps": 0.1,
+    "oscillation_recovery_min_duration": 10,
+    "oscillation_filter_duration": 10
+  }
+}
-- 
GitLab


From 5a5cf7af9691ffee16d214603c5788ffe02909c7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 3 Aug 2022 15:14:26 +0200
Subject: [PATCH 052/324] human tracker skeleton

---
 .../dynamic_scene_provider/CMakeLists.txt     |  2 +
 .../dynamic_scene_provider/Component.cpp      | 11 ++++++
 .../dynamic_scene_provider/Component.h        |  4 ++
 .../dynamic_scene_provider/HumanTracker.cpp   |  6 +++
 .../dynamic_scene_provider/HumanTracker.h     | 37 +++++++++++++++++++
 5 files changed, 60 insertions(+)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 146e5b7b..42507ca0 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -9,9 +9,11 @@ armarx_add_component(dynamic_scene_provider
     SOURCES
         Component.cpp
         ArVizDrawer.cpp
+        HumanTracker.cpp
     HEADERS
         Component.h
         ArVizDrawer.h
+        HumanTracker.h
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 9f8cd9f7..a4d10991 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -137,6 +137,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         robot = virtualRobotReaderPlugin->get().getRobot(properties.robot.name);
         ARMARX_CHECK_NOT_NULL(robot);
 
+        humanTracker.reset();
+
         task = new PeriodicTask<Component>(
             this, &Component::runPeriodically, properties.taskPeriodMs, false, "runningTask");
     }
@@ -314,6 +316,15 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
             // arviz.commit({layer});
         }
+
+        // here ends: data fetching
+        
+        humanTracker.update(HumanTracker::Measurements{
+            .humanPoses = humanPoseResult.humanPoses
+        });
+
+
+
     }
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index 1d7d92fc..171b8638 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -47,6 +47,7 @@
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
 #include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
+#include "armarx/navigation/components/dynamic_scene_provider/HumanTracker.h"
 #include "armarx/navigation/memory/client/costmap/Reader.h"
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
 
@@ -197,6 +198,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ReaderWriterPlugin<armem::vision::occupancy_grid::client::Reader>*
             occupancyGridReaderPlugin = nullptr;
+
+
+        HumanTracker humanTracker;
     };
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
new file mode 100644
index 00000000..866fa4aa
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -0,0 +1,6 @@
+#include "HumanTracker.h"
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+  
+}
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
new file mode 100644
index 00000000..770901f1
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -0,0 +1,37 @@
+#pragma once
+
+
+#include "VisionX/libraries/armem_human/types.h"
+#include "armarx/navigation/core/basic_types.h"
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+
+    class HumanTracker
+    {
+    public:
+        HumanTracker() = default;
+
+        struct Measurements
+        {
+            std::vector<armem::human::HumanPose> humanPoses;
+        };
+
+        void update(const Measurements& measurements);
+
+        struct TrackedHuman
+        {
+            // TODO ...
+            core::Pose2D global_T_human;
+
+            Eigen::Vector2f linearVelocity;
+        };
+
+        std::vector<TrackedHuman> getTrackedHumans() const;
+
+        void reset();
+
+    private:
+        std::vector<TrackedHuman> trackedHumans;
+    };
+} // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 807b0e196049a0f9169b65b04a875d4966cdc8dc Mon Sep 17 00:00:00 2001
From: Marius Baden <marius.baden@student.kit.edu>
Date: Wed, 3 Aug 2022 17:40:28 +0200
Subject: [PATCH 053/324] Add skeleton for HumanTracker.cpp

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 27 +++++++++++++++++++
 1 file changed, 27 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 866fa4aa..699a0954 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -2,5 +2,32 @@
 
 namespace armarx::navigation::components::dynamic_scene_provider
 {
+
+HumanTracker::HumanTracker()
+{
+
+}
+
+
+void HumanTracker::update(const Measurements &measurements)
+{
+    this->trackedHumans = HumanTracker::TrackedHuman{
+            .global_T_human = ;// pose here;
+            .linearVelocity = 0;
+    }
+}
+
+
+std::vector<HumanTracker::TrackedHuman> HumanTracker::getTrackedHumans() const
+{
+
+}
+
+
+void HumanTracker::reset()
+{
+
+}
+
   
 }
-- 
GitLab


From fde23ddbaddfa53441b9a3e284a26b56bdb7b60d Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 3 Aug 2022 17:43:15 +0200
Subject: [PATCH 054/324] Fix json formatting

---
 .../TimedElasticBands/default.json                    | 11 +++++------
 1 file changed, 5 insertions(+), 6 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 344df69e..6849fbb4 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -1,4 +1,3 @@
-
 {
   "odom_topic": "odom",
   "map_frame": "odom",
@@ -27,11 +26,11 @@
     "global_plan_prune_distance": 1,
     "exact_arc_length": false,
     "force_reinit_new_goal_dist": 1,
-    "force_reinit_new_goal_angular": 0.5 * M_PI,
+    "force_reinit_new_goal_angular": 1.5707963267948966,
     "feasibility_check_no_poses": 5,
     "feasibility_check_lookahead_distance": -1,
     "publish_feedback": false,
-    "min_resolution_collision_check_angular": M_PI,
+    "min_resolution_collision_check_angular": 3.141592653589793,
     "control_look_ahead_poses": 1
   },
 
@@ -111,7 +110,7 @@
     "enable_multithreading": true,
     "simple_exploration": false,
     "max_number_classes": 5,
-    "max_number_plans_in_current_class" 0,
+    "max_number_plans_in_current_class": 0,
     "selection_cost_hysteresis": 1.0,
     "selection_prefer_initial_plan": 0.95,
     "selection_obst_cost_scale": 100.0,
@@ -133,9 +132,9 @@
     "visualize_hc_graph": false,
     "visualize_with_time_as_z_axis_scale": 0.0,
     "delete_detours_backwards": true,
-    "detours_orientation_tolerance": M_PI / 2.0,
+    "detours_orientation_tolerance": 1.5707963267948966,
     "length_start_orientation_vector": 0.4,
-    "max_ratio_detours_duration_best_duration": 3.0,
+    "max_ratio_detours_duration_best_duration": 3.0
   },
 
   "recovery": {
-- 
GitLab


From 890b1d9621569d6710b3193e527ca07fecc66ac1 Mon Sep 17 00:00:00 2001
From: Marius Baden <marius.baden@student.kit.edu>
Date: Wed, 3 Aug 2022 17:47:52 +0200
Subject: [PATCH 055/324] Create tracked human

---
 .../components/dynamic_scene_provider/HumanTracker.cpp       | 5 ++++-
 1 file changed, 4 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 699a0954..94ee8e37 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -12,7 +12,10 @@ HumanTracker::HumanTracker()
 void HumanTracker::update(const Measurements &measurements)
 {
     this->trackedHumans = HumanTracker::TrackedHuman{
-            .global_T_human = ;// pose here;
+            .global_T_human = core::Pose2D{
+                .x = 0;
+                .y = 0;
+            };
             .linearVelocity = 0;
     }
 }
-- 
GitLab


From 7db0cd2896eb4521cfc4a4e053c2a3601866ed1b Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 3 Aug 2022 18:07:16 +0200
Subject: [PATCH 056/324] Fix broken test

---
 .../navigation/algorithms/test/algorithms_spfa_test.cpp       | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
index e2a24383..98a6934a 100644
--- a/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
+++ b/source/armarx/navigation/algorithms/test/algorithms_spfa_test.cpp
@@ -212,8 +212,8 @@ BOOST_AUTO_TEST_CASE(testSPFAPlanWObstacleDistance)
     const float cellSize = j.at("cell_size"); // [mm]
     BOOST_REQUIRE_GT(cellSize, 0);
 
-    std::vector<float> sceneBoundsMinV(j.at("scene_bounds"]["min"));
-    std::vector<float> sceneBoundsMaxV(j.at("scene_bounds"]["max"));
+    std::vector<float> sceneBoundsMinV(j.at("scene_bounds").at("min"));
+    std::vector<float> sceneBoundsMaxV(j.at("scene_bounds").at("max"));
     BOOST_REQUIRE_EQUAL(sceneBoundsMinV.size(), 2);
     BOOST_REQUIRE_EQUAL(sceneBoundsMaxV.size(), 2);
 
-- 
GitLab


From 427dd3b3cacf5c72348d78938a37961422338b04 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 3 Aug 2022 18:14:42 +0200
Subject: [PATCH 057/324] Add teb config to aron

---
 .../local_planning/aron/TimedElasticBands.xml | 517 +++++++++++++++++-
 1 file changed, 515 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 2c352aca..23dd0836 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -5,10 +5,523 @@
     </AronIncludes>
 
     <GenerateTypes>
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
-            <ObjectChild key='foo'>
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::pse'>
+            <ObjectChild key='pse_costum_obstacle_penalties'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='pse_costum_obstacle_penalties_dynamic'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='weight_global_path'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='lrk_use_alternative_approach'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='lrk_enable_collision_check'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='hybrid_homotopy_calculation'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='robot_diff_circumscribed_inscribed_radius'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::trajectory'>
+            <ObjectChild key='teb_autosize'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='dt_ref'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='dt_hysteresis'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='min_samples'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='max_samples'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='global_plan_overwrite_orientation'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='allow_init_with_backwards_motion'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='global_plan_viapoint_sep'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='via_points_ordered'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='max_global_plan_lookahead_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='global_plan_prune_distance'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='exact_arc_length'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='force_reinit_new_goal_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='force_reinit_new_goal_angular'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='feasibility_check_no_poses'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='feasibility_check_lookahead_distance'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='publish_feedback'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='min_resolution_collision_check_angular'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='control_look_ahead_poses'>
+                <int />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::robot'>
+            <ObjectChild key='max_vel_x'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='max_vel_x_backwards'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='max_vel_y'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='max_vel_theta'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='acc_lim_x'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='acc_lim_y'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='acc_lim_theta'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='min_turning_radius'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='wheelbase'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='cmd_angle_instead_rotvel'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='is_footprint_dynamic'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='use_proportional_saturation'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='transform_tolerance'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::goal_tolerance'>
+            <ObjectChild key='xy_goal_tolerance'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='yaw_goal_tolerance'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='free_goal_vel'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='complete_global_plan'>
+                <bool />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::obstacles'>
+            <ObjectChild key='min_obstacle_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='inflation_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='dynamic_obstacle_inflation_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='include_dynamic_obstacles'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='include_costmap_obstacles'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='costmap_obstacles_behind_robot_dist'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_poses_affected'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='legacy_obstacle_association'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_association_force_inclusion_factor'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_association_cutoff_factor'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='costmap_converter_plugin'>
+                <string />
+            </ObjectChild>
+
+            <ObjectChild key='costmap_converter_spin_thread'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='costmap_converter_rate'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_proximity_ratio_max_vel'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_proximity_lower_bound'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_proximity_upper_bound'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::optim'>
+            <ObjectChild key='no_inner_iterations'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='no_outer_iterations'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='optimization_activate'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='optimization_verbose'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='penalty_epsilon'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_max_vel_x'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_max_vel_y'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_max_vel_theta'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_acc_lim_x'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_acc_lim_y'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_acc_lim_theta'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_kinematics_nh'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_kinematics_forward_drive'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_kinematics_turning_radius'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_optimaltime'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_shortest_path'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_obstacle'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_inflation'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_dynamic_obstacle'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_dynamic_obstacle_inflation'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_velocity_obstacle_ratio'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_viapoint'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_prefer_rotdir'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_adapt_factor'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_cost_exponent'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::hcp'>
+            <ObjectChild key='enable_homotopy_class_planning'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='enable_multithreading'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='simple_exploration'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='max_number_classes'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='max_number_plans_in_current_class'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='selection_cost_hysteresis'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='selection_prefer_initial_plan'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='selection_obst_cost_scale'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='selection_viapoint_cost_scale'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='selection_alternative_time_cost'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='selection_dropping_probability'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='switching_blocking_period'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_keypoint_offset'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='obstacle_heading_threshold'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='roadmap_graph_no_samples'>
+                <int />
+            </ObjectChild>
+
+            <ObjectChild key='roadmap_graph_area_width'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='roadmap_graph_area_length_scale'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='h_signature_prescaler'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='h_signature_threshold'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='viapoints_all_candidates'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='visualize_hc_graph'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='visualize_with_time_as_z_axis_scale'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='delete_detours_backwards'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='detours_orientation_tolerance'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='length_start_orientation_vector'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='max_ratio_detours_duration_best_duration'>
                 <float />
             </ObjectChild>
         </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::recovery'>
+            <ObjectChild key='shrink_horizon_backup'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='shrink_horizon_min_duration'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='oscillation_recovery'>
+                <bool />
+            </ObjectChild>
+
+            <ObjectChild key='oscillation_v_eps'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='oscillation_omega_eps'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='oscillation_recovery_min_duration'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='oscillation_filter_duration'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
+            <ObjectChild key='odom_topic'>
+                <string />
+            </ObjectChild>
+            <ObjectChild key='map_frame'>
+                <string />
+            </ObjectChild>
+
+            <ObjectChild key='pse'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::pse />
+            </ObjectChild>
+            <ObjectChild key='trajectory'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::trajectory />
+            </ObjectChild>
+            <ObjectChild key='robot'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::robot />
+            </ObjectChild>
+            <ObjectChild key='goal_tolerance'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::goal_tolerance />
+            </ObjectChild>
+            <ObjectChild key='obstacles'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::obstacles />
+            </ObjectChild>
+            <ObjectChild key='optim'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::optim />
+            </ObjectChild>
+            <ObjectChild key='hcp'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::hcp />
+            </ObjectChild>
+            <ObjectChild key='recovery'>
+                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::recovery />
+            </ObjectChild>
+        </Object>
+
     </GenerateTypes>
 </AronTypeDefinition>
-- 
GitLab


From c9bb2065192b0609ae2a28ca8df5d772443fafac Mon Sep 17 00:00:00 2001
From: Marius Baden <marius.baden@student.kit.edu>
Date: Wed, 3 Aug 2022 18:32:26 +0200
Subject: [PATCH 058/324] Create basic tracked humans from OpenPose

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 25 +++++++++++++++++++
 1 file changed, 25 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 94ee8e37..41649ff4 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -11,6 +11,31 @@ HumanTracker::HumanTracker()
 
 void HumanTracker::update(const Measurements &measurements)
 {
+    trackedHumans.clear();
+
+    foreach (humanPose, measurements.humanPoses) {
+
+        const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
+        ARMARX_CHECK_NOT_EMPTY(keypoints);
+
+        const Eigen::Vector3f centerPos = Eigen::Vector3f::Zero();
+        for (const auto& [_, v] : keypoints)
+        {
+            centerPos += v.positionGlobal;
+        }
+        centerPos /= static_cast<float>(keypoints.size());
+
+        const HumanTracker::TrackedHuman newHuman = HumanTracker::TrackedHuman{
+            .global_T_human = core::Pose2D{
+                .x = centerPos.x;
+                .y = centerPos.y;
+            };;
+            .linearVelocity = 0; //TODO more sophisticated guess
+        }
+        trackedHumans.push_back(newHuman);
+    }
+
+
     this->trackedHumans = HumanTracker::TrackedHuman{
             .global_T_human = core::Pose2D{
                 .x = 0;
-- 
GitLab


From 200aa17151c68628106f6bd27498b647518d55d2 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 3 Aug 2022 19:34:30 +0200
Subject: [PATCH 059/324] setup aron dto

---
 .../TimedElasticBands/default.json            |  1 -
 .../local_planning/TimedElasticBands.cpp      | 11 ++-----
 .../local_planning/TimedElasticBands.h        |  4 +--
 .../local_planning/aron/TimedElasticBands.xml | 32 +++++++++----------
 .../local_planning/aron_conversions.cpp       |  2 ++
 .../local_planning/aron_conversions.h         |  4 +++
 6 files changed, 26 insertions(+), 28 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 6849fbb4..1a09f281 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -55,7 +55,6 @@
     "yaw_goal_tolerance": 0.2,
     "free_goal_vel": false,
     "complete_global_plan": true
-
   },
 
   "obstacles": {
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 70b692b0..37e77cd1 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -30,23 +30,16 @@ namespace armarx::navigation::local_planning
     aron::data::DictPtr
     TimedElasticBandsParams::toAron() const
     {
-        arondto::TimedElasticBandsParams dto;
-
-        TimedElasticBandsParams bo;
-        armarx::navigation::local_planning::toAron(dto, bo);
-
-        return dto.toAron();
+        return cfg.toAron();
     }
 
     TimedElasticBandsParams
     TimedElasticBandsParams::FromAron(const aron::data::DictPtr& dict)
     {
         ARMARX_CHECK_NOT_NULL(dict);
-        arondto::TimedElasticBandsParams dto;
-        dto.fromAron(dict);
 
         TimedElasticBandsParams bo;
-        fromAron(dto, bo);
+        bo.cfg.fromAron(dict);
 
         return bo;
     }
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 26826650..654343d5 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -28,6 +28,7 @@
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/TebObstacleManager.h>
+#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 #include <teb_local_planner/teb_config.h>
@@ -38,8 +39,7 @@ namespace armarx::navigation::local_planning
 
     struct TimedElasticBandsParams : public LocalPlannerParams
     {
-        bool includeStartPose{false};
-
+        arondto::TimedElasticBandsParams cfg;
 
         Algorithms algorithm() const override;
         aron::data::DictPtr toAron() const override;
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 23dd0836..9a2adb44 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -5,7 +5,7 @@
     </AronIncludes>
 
     <GenerateTypes>
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::pse'>
+        <Object name='armarx::navigation::local_planning::arondto::pse'>
             <ObjectChild key='pse_costum_obstacle_penalties'>
                 <bool />
             </ObjectChild>
@@ -35,7 +35,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::trajectory'>
+        <Object name='armarx::navigation::local_planning::arondto::trajectory'>
             <ObjectChild key='teb_autosize'>
                 <bool />
             </ObjectChild>
@@ -113,7 +113,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::robot'>
+        <Object name='armarx::navigation::local_planning::arondto::robot'>
             <ObjectChild key='max_vel_x'>
                 <float />
             </ObjectChild>
@@ -167,7 +167,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::goal_tolerance'>
+        <Object name='armarx::navigation::local_planning::arondto::goal_tolerance'>
             <ObjectChild key='xy_goal_tolerance'>
                 <float />
             </ObjectChild>
@@ -185,7 +185,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::obstacles'>
+        <Object name='armarx::navigation::local_planning::arondto::obstacles'>
             <ObjectChild key='min_obstacle_dist'>
                 <float />
             </ObjectChild>
@@ -251,7 +251,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::optim'>
+        <Object name='armarx::navigation::local_planning::arondto::optim'>
             <ObjectChild key='no_inner_iterations'>
                 <int />
             </ObjectChild>
@@ -353,7 +353,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::hcp'>
+        <Object name='armarx::navigation::local_planning::arondto::hcp'>
             <ObjectChild key='enable_homotopy_class_planning'>
                 <bool />
             </ObjectChild>
@@ -459,7 +459,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams::recovery'>
+        <Object name='armarx::navigation::local_planning::arondto::recovery'>
             <ObjectChild key='shrink_horizon_backup'>
                 <bool />
             </ObjectChild>
@@ -498,28 +498,28 @@
             </ObjectChild>
 
             <ObjectChild key='pse'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::pse />
+                <armarx::navigation::local_planning::arondto::pse />
             </ObjectChild>
             <ObjectChild key='trajectory'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::trajectory />
+                <armarx::navigation::local_planning::arondto::trajectory />
             </ObjectChild>
             <ObjectChild key='robot'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::robot />
+                <armarx::navigation::local_planning::arondto::robot />
             </ObjectChild>
             <ObjectChild key='goal_tolerance'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::goal_tolerance />
+                <armarx::navigation::local_planning::arondto::goal_tolerance />
             </ObjectChild>
             <ObjectChild key='obstacles'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::obstacles />
+                <armarx::navigation::local_planning::arondto::obstacles />
             </ObjectChild>
             <ObjectChild key='optim'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::optim />
+                <armarx::navigation::local_planning::arondto::optim />
             </ObjectChild>
             <ObjectChild key='hcp'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::hcp />
+                <armarx::navigation::local_planning::arondto::hcp />
             </ObjectChild>
             <ObjectChild key='recovery'>
-                <armarx::navigation::local_planning::arondto::TimedElasticBandsParams::recovery />
+                <armarx::navigation::local_planning::arondto::recovery />
             </ObjectChild>
         </Object>
 
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 44599c44..87ead8dc 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -14,11 +14,13 @@ namespace armarx::navigation::local_planning
     void
     toAron(arondto::TimedElasticBandsParams& dto, const TimedElasticBandsParams& bo)
     {
+        dto = bo.cfg;
     }
 
     void
     fromAron(const arondto::TimedElasticBandsParams& dto, TimedElasticBandsParams& bo)
     {
+        bo.cfg = dto;
     }
 
 
diff --git a/source/armarx/navigation/local_planning/aron_conversions.h b/source/armarx/navigation/local_planning/aron_conversions.h
index 1b7d2382..22eb26d1 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.h
+++ b/source/armarx/navigation/local_planning/aron_conversions.h
@@ -1,5 +1,7 @@
 #pragma once
 
+#include <teb_local_planner/teb_config.h>
+
 namespace armarx::navigation::local_planning
 {
     // struct LocalPlannerParams;
@@ -19,4 +21,6 @@ namespace armarx::navigation::local_planning
     void toAron(arondto::TimedElasticBandsParams& dto, const TimedElasticBandsParams& bo);
     void fromAron(const arondto::TimedElasticBandsParams& dto, TimedElasticBandsParams& bo);
 
+    void toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo);
+
 } // namespace armarx::navigation::local_planning
-- 
GitLab


From ea2b32b7c94dcfe016a68e11c784cdf6a578d2ad Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 4 Aug 2022 05:03:05 +0200
Subject: [PATCH 060/324] remove unused config parameters

---
 .../TimedElasticBands/default.json            | 45 ++-----------------
 1 file changed, 4 insertions(+), 41 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 1a09f281..33389b94 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -1,7 +1,4 @@
 {
-  "odom_topic": "odom",
-  "map_frame": "odom",
-
   "pse": {
     "pse_costum_obstacle_penalties": true,
     "pse_costum_obstacle_penalties_dynamic": true,
@@ -20,18 +17,12 @@
     "max_samples": 500,
     "global_plan_overwrite_orientation": true,
     "allow_init_with_backwards_motion": false,
-    "global_plan_viapoint_sep": -1,
-    "via_points_ordered": false,
-    "max_global_plan_lookahead_dist": 1,
-    "global_plan_prune_distance": 1,
     "exact_arc_length": false,
     "force_reinit_new_goal_dist": 1,
     "force_reinit_new_goal_angular": 1.5707963267948966,
     "feasibility_check_no_poses": 5,
     "feasibility_check_lookahead_distance": -1,
-    "publish_feedback": false,
-    "min_resolution_collision_check_angular": 3.141592653589793,
-    "control_look_ahead_poses": 1
+    "min_resolution_collision_check_angular": 3.141592653589793
   },
 
   "robot": {
@@ -42,19 +33,11 @@
     "acc_lim_x": 0.5,
     "acc_lim_y": 0.5,
     "acc_lim_theta": 0.5,
-    "min_turning_radius": 0,
-    "wheelbase": 1.0,
-    "cmd_angle_instead_rotvel": false,
-    "is_footprint_dynamic": false,
-    "use_proportional_saturation": false,
-    "transform_tolerance": 0.5
+    "min_turning_radius": 0
   },
 
   "goal_tolerance": {
-    "xy_goal_tolerance": 0.2,
-    "yaw_goal_tolerance": 0.2,
-    "free_goal_vel": false,
-    "complete_global_plan": true
+    "xy_goal_tolerance": 0.2
   },
 
   "obstacles": {
@@ -62,15 +45,8 @@
     "inflation_dist": 0.0,
     "dynamic_obstacle_inflation_dist": 0.6,
     "include_dynamic_obstacles": true,
-    "include_costmap_obstacles": true,
-    "costmap_obstacles_behind_robot_dist": 1.5,
-    "obstacle_poses_affected": 25,
-    "legacy_obstacle_association": false,
     "obstacle_association_force_inclusion_factor": 1.5,
     "obstacle_association_cutoff_factor": 5,
-    "costmap_converter_plugin": "",
-    "costmap_converter_spin_thread": true,
-    "costmap_converter_rate": 5,
     "obstacle_proximity_ratio_max_vel": 1,
     "obstacle_proximity_lower_bound": 0,
     "obstacle_proximity_upper_bound": 0.5
@@ -105,7 +81,6 @@
   },
 
   "hcp": {
-    "enable_homotopy_class_planning": true,
     "enable_multithreading": true,
     "simple_exploration": false,
     "max_number_classes": 5,
@@ -118,7 +93,6 @@
     "selection_dropping_probability": 0.0,
     "switching_blocking_period": 0.0,
 
-    "obstacle_keypoint_offset": 0.1,
     "obstacle_heading_threshold": 0.45,
     "roadmap_graph_no_samples": 20,
     "roadmap_graph_area_width": 10,
@@ -128,21 +102,10 @@
 
     "viapoints_all_candidates": true,
 
-    "visualize_hc_graph": false,
-    "visualize_with_time_as_z_axis_scale": 0.0,
     "delete_detours_backwards": true,
     "detours_orientation_tolerance": 1.5707963267948966,
     "length_start_orientation_vector": 0.4,
     "max_ratio_detours_duration_best_duration": 3.0
-  },
-
-  "recovery": {
-    "shrink_horizon_backup": true,
-    "shrink_horizon_min_duration": 10,
-    "oscillation_recovery": true,
-    "oscillation_v_eps": 0.1,
-    "oscillation_omega_eps": 0.1,
-    "oscillation_recovery_min_duration": 10,
-    "oscillation_filter_duration": 10
   }
+
 }
-- 
GitLab


From 55075b4716e905a01e4adfdfbeb3ee1630410124 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 4 Aug 2022 05:10:20 +0200
Subject: [PATCH 061/324] adjust aron file

---
 .../local_planning/aron/TimedElasticBands.xml | 138 ------------------
 1 file changed, 138 deletions(-)

diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 9a2adb44..b4bd0e76 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -64,22 +64,6 @@
                 <bool />
             </ObjectChild>
 
-            <ObjectChild key='global_plan_viapoint_sep'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='via_points_ordered'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='max_global_plan_lookahead_dist'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='global_plan_prune_distance'>
-                <float />
-            </ObjectChild>
-
             <ObjectChild key='exact_arc_length'>
                 <bool />
             </ObjectChild>
@@ -100,17 +84,9 @@
                 <float />
             </ObjectChild>
 
-            <ObjectChild key='publish_feedback'>
-                <bool />
-            </ObjectChild>
-
             <ObjectChild key='min_resolution_collision_check_angular'>
                 <float />
             </ObjectChild>
-
-            <ObjectChild key='control_look_ahead_poses'>
-                <int />
-            </ObjectChild>
         </Object>
 
         <Object name='armarx::navigation::local_planning::arondto::robot'>
@@ -145,44 +121,12 @@
             <ObjectChild key='min_turning_radius'>
                 <float />
             </ObjectChild>
-
-            <ObjectChild key='wheelbase'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='cmd_angle_instead_rotvel'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='is_footprint_dynamic'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='use_proportional_saturation'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='transform_tolerance'>
-                <float />
-            </ObjectChild>
         </Object>
 
         <Object name='armarx::navigation::local_planning::arondto::goal_tolerance'>
             <ObjectChild key='xy_goal_tolerance'>
                 <float />
             </ObjectChild>
-
-            <ObjectChild key='yaw_goal_tolerance'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='free_goal_vel'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='complete_global_plan'>
-                <bool />
-            </ObjectChild>
         </Object>
 
         <Object name='armarx::navigation::local_planning::arondto::obstacles'>
@@ -202,22 +146,6 @@
                 <bool />
             </ObjectChild>
 
-            <ObjectChild key='include_costmap_obstacles'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='costmap_obstacles_behind_robot_dist'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='obstacle_poses_affected'>
-                <int />
-            </ObjectChild>
-
-            <ObjectChild key='legacy_obstacle_association'>
-                <bool />
-            </ObjectChild>
-
             <ObjectChild key='obstacle_association_force_inclusion_factor'>
                 <float />
             </ObjectChild>
@@ -226,18 +154,6 @@
                 <float />
             </ObjectChild>
 
-            <ObjectChild key='costmap_converter_plugin'>
-                <string />
-            </ObjectChild>
-
-            <ObjectChild key='costmap_converter_spin_thread'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='costmap_converter_rate'>
-                <int />
-            </ObjectChild>
-
             <ObjectChild key='obstacle_proximity_ratio_max_vel'>
                 <float />
             </ObjectChild>
@@ -354,10 +270,6 @@
         </Object>
 
         <Object name='armarx::navigation::local_planning::arondto::hcp'>
-            <ObjectChild key='enable_homotopy_class_planning'>
-                <bool />
-            </ObjectChild>
-
             <ObjectChild key='enable_multithreading'>
                 <bool />
             </ObjectChild>
@@ -402,9 +314,6 @@
                 <float />
             </ObjectChild>
 
-            <ObjectChild key='obstacle_keypoint_offset'>
-                <float />
-            </ObjectChild>
 
             <ObjectChild key='obstacle_heading_threshold'>
                 <float />
@@ -434,13 +343,6 @@
                 <bool />
             </ObjectChild>
 
-            <ObjectChild key='visualize_hc_graph'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='visualize_with_time_as_z_axis_scale'>
-                <float />
-            </ObjectChild>
 
             <ObjectChild key='delete_detours_backwards'>
                 <bool />
@@ -459,44 +361,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::recovery'>
-            <ObjectChild key='shrink_horizon_backup'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='shrink_horizon_min_duration'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='oscillation_recovery'>
-                <bool />
-            </ObjectChild>
-
-            <ObjectChild key='oscillation_v_eps'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='oscillation_omega_eps'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='oscillation_recovery_min_duration'>
-                <float />
-            </ObjectChild>
-
-            <ObjectChild key='oscillation_filter_duration'>
-                <float />
-            </ObjectChild>
-        </Object>
-
         <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
-            <ObjectChild key='odom_topic'>
-                <string />
-            </ObjectChild>
-            <ObjectChild key='map_frame'>
-                <string />
-            </ObjectChild>
-
             <ObjectChild key='pse'>
                 <armarx::navigation::local_planning::arondto::pse />
             </ObjectChild>
@@ -518,9 +383,6 @@
             <ObjectChild key='hcp'>
                 <armarx::navigation::local_planning::arondto::hcp />
             </ObjectChild>
-            <ObjectChild key='recovery'>
-                <armarx::navigation::local_planning::arondto::recovery />
-            </ObjectChild>
         </Object>
 
     </GenerateTypes>
-- 
GitLab


From 953dcbc965c024a4f7f1bd1b67a690d00cd14a46 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 4 Aug 2022 05:56:15 +0200
Subject: [PATCH 062/324] Read config from dto, read default config

---
 .../local_planning/TimedElasticBands.cpp      |  58 +++++----
 .../local_planning/TimedElasticBands.h        |   2 +-
 .../local_planning/aron/TimedElasticBands.xml |   1 +
 .../local_planning/aron_conversions.cpp       | 118 ++++++++++++++++++
 4 files changed, 154 insertions(+), 25 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 37e77cd1..8084e1fb 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,11 +1,15 @@
 #include "TimedElasticBands.h"
 
+#include <SimoxUtility/json/json.hpp>
 #include <VirtualRobot/MathTools.h>
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/SceneObjectSet.h>
 
+#include <ArmarXCore/core/PackagePath.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
+#include "RobotAPI/libraries/aron/core/data/rw/reader/nlohmannJSON/NlohmannJSONReaderWithoutTypeCheck.h"
+
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/Trajectory.h"
 #include <armarx/navigation/local_planning/LocalPlanner.h>
@@ -51,7 +55,14 @@ namespace armarx::navigation::local_planning
         LocalPlanner(ctx), params(params), scene(ctx), obstManager(teb_obstacles)
     {
         //TODO (SALt): init configuration, robot footprint
-        initConfig();
+        if (false)
+        {
+            toTebCfg(params.cfg, cfg_);
+        }
+        else
+        {
+            initDefaultConfig();
+        }
         auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(0.2);
 
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
@@ -62,30 +73,29 @@ namespace armarx::navigation::local_planning
     }
 
     void
-    TimedElasticBands::initConfig()
+    TimedElasticBands::initDefaultConfig()
     {
-        cfg_.robot.max_vel_x = 1.0;
-        cfg_.robot.max_vel_x_backwards = 1.0;
-        cfg_.robot.max_vel_y = 1.0;
-        cfg_.robot.max_vel_theta = 1.0;
-        cfg_.robot.acc_lim_x = 1.0;
-        cfg_.robot.acc_lim_y = 1.0;
-        cfg_.robot.acc_lim_theta = 1.0;
-
-        cfg_.optim.weight_max_vel_x = 1.0;
-        cfg_.optim.weight_max_vel_y = 1.0;
-        cfg_.optim.weight_max_vel_theta = 1.0;
-        cfg_.optim.weight_acc_lim_x = 1.0;
-        cfg_.optim.weight_acc_lim_y = 1.0;
-        cfg_.optim.weight_acc_lim_theta = 1.0;
-
-        cfg_.optim.weight_optimaltime = 0.6;
-        cfg_.optim.weight_shortest_path = 0.6;
-
-        cfg_.hcp.selection_cost_hysteresis = 1.0;
-        cfg_.hcp.switching_blocking_period = 0;
-
-        cfg_.pse.weight_global_path = 0.6;
+        arondto::TimedElasticBandsParams dto;
+
+        const armarx::PackagePath configPath("armarx_navigation",
+                                             "local_planner_config/TimedElasticBands/default.json");
+        const std::filesystem::path file = configPath.toSystemPath();
+
+        ARMARX_CHECK(std::filesystem::is_regular_file(file)) << file;
+
+        ARMARX_INFO << "Loading config from file `" << file << "`.";
+        std::ifstream ifs{file};
+
+        nlohmann::json jsonConfig;
+        ifs >> jsonConfig;
+
+        ARMARX_INFO << "Initializing config";
+
+        armarx::aron::data::reader::NlohmannJSONReaderWithoutTypeCheck reader;
+
+        dto.read(reader, jsonConfig);
+
+        toTebCfg(params.cfg, cfg_);
     }
 
     std::optional<LocalPlannerResult>
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 654343d5..caf2c832 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -66,7 +66,7 @@ namespace armarx::navigation::local_planning
             bool planToDestination;
         };
 
-        void initConfig();
+        void initDefaultConfig();
         FindTargetResult findTarget(const core::Pose& currentPose,
                                     const core::GlobalTrajectory& globalPath);
         void fillObstacles();
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index b4bd0e76..b0f90f17 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -339,6 +339,7 @@
                 <float />
             </ObjectChild>
 
+
             <ObjectChild key='viapoints_all_candidates'>
                 <bool />
             </ObjectChild>
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 87ead8dc..4a93ffcd 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -23,5 +23,123 @@ namespace armarx::navigation::local_planning
         bo.cfg = dto;
     }
 
+    void
+    toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo)
+    {
+        bo.pse.pse_costum_obstacle_penalties = dto.pse.pse_costum_obstacle_penalties;
+        bo.pse.pse_costum_obstacle_penalties_dynamic =
+            dto.pse.pse_costum_obstacle_penalties_dynamic;
+        bo.pse.weight_global_path = dto.pse.weight_global_path;
+        bo.pse.lrk_use_alternative_approach = dto.pse.lrk_use_alternative_approach;
+        bo.pse.lrk_enable_collision_check = dto.pse.lrk_enable_collision_check;
+        bo.pse.hybrid_homotopy_calculation = dto.pse.hybrid_homotopy_calculation;
+        bo.pse.robot_diff_circumscribed_inscribed_radius =
+            dto.pse.robot_diff_circumscribed_inscribed_radius;
+
+        // Trajectory
+        bo.trajectory.teb_autosize = bo.trajectory.teb_autosize;
+        bo.trajectory.dt_ref = dto.trajectory.dt_ref;
+        bo.trajectory.dt_hysteresis = dto.trajectory.dt_hysteresis;
+        bo.trajectory.min_samples = dto.trajectory.min_samples;
+        bo.trajectory.max_samples = dto.trajectory.max_samples;
+        bo.trajectory.global_plan_overwrite_orientation =
+            dto.trajectory.global_plan_overwrite_orientation;
+        bo.trajectory.allow_init_with_backwards_motion =
+            dto.trajectory.allow_init_with_backwards_motion;
+        bo.trajectory.exact_arc_length = dto.trajectory.exact_arc_length;
+        bo.trajectory.force_reinit_new_goal_dist = dto.trajectory.force_reinit_new_goal_dist;
+        bo.trajectory.force_reinit_new_goal_angular = dto.trajectory.force_reinit_new_goal_angular;
+        bo.trajectory.feasibility_check_no_poses = dto.trajectory.feasibility_check_no_poses;
+        bo.trajectory.feasibility_check_lookahead_distance =
+            dto.trajectory.feasibility_check_lookahead_distance;
+        bo.trajectory.min_resolution_collision_check_angular =
+            dto.trajectory.min_resolution_collision_check_angular;
+
+        // Robot
+        bo.robot.max_vel_x = dto.robot.max_vel_x;
+        bo.robot.max_vel_x_backwards = dto.robot.max_vel_x_backwards;
+        bo.robot.max_vel_y = dto.robot.max_vel_y;
+        bo.robot.max_vel_theta = dto.robot.max_vel_theta;
+        bo.robot.acc_lim_x = dto.robot.acc_lim_x;
+        bo.robot.acc_lim_y = dto.robot.acc_lim_y;
+        bo.robot.acc_lim_theta = dto.robot.acc_lim_theta;
+        bo.robot.min_turning_radius = dto.robot.min_turning_radius;
+
+        // GoalTolerance
+        bo.goal_tolerance.xy_goal_tolerance = dto.goal_tolerance.xy_goal_tolerance;
+
+        // Obstacles
+        bo.obstacles.min_obstacle_dist = dto.obstacles.min_obstacle_dist;
+        bo.obstacles.inflation_dist = dto.obstacles.inflation_dist;
+        bo.obstacles.dynamic_obstacle_inflation_dist =
+            dto.obstacles.dynamic_obstacle_inflation_dist;
+        bo.obstacles.include_dynamic_obstacles = dto.obstacles.include_dynamic_obstacles;
+        bo.obstacles.obstacle_association_force_inclusion_factor =
+            dto.obstacles.obstacle_association_force_inclusion_factor;
+        bo.obstacles.obstacle_association_cutoff_factor =
+            dto.obstacles.obstacle_association_cutoff_factor;
+        bo.obstacles.obstacle_proximity_ratio_max_vel =
+            dto.obstacles.obstacle_proximity_ratio_max_vel;
+        bo.obstacles.obstacle_proximity_lower_bound = dto.obstacles.obstacle_proximity_lower_bound;
+        bo.obstacles.obstacle_proximity_upper_bound = dto.obstacles.obstacle_proximity_upper_bound;
+
+        // Optimization
+        bo.optim.no_inner_iterations = dto.optim.no_inner_iterations;
+        bo.optim.no_outer_iterations = dto.optim.no_outer_iterations;
+        bo.optim.optimization_activate = dto.optim.optimization_activate;
+        bo.optim.optimization_verbose = dto.optim.optimization_verbose;
+        bo.optim.penalty_epsilon = dto.optim.penalty_epsilon;
+        bo.optim.weight_max_vel_x = dto.optim.weight_max_vel_x;
+        bo.optim.weight_max_vel_y = dto.optim.weight_max_vel_y;
+        bo.optim.weight_max_vel_theta = dto.optim.weight_max_vel_theta;
+        bo.optim.weight_acc_lim_x = dto.optim.weight_acc_lim_x;
+        bo.optim.weight_acc_lim_y = dto.optim.weight_acc_lim_y;
+        bo.optim.weight_acc_lim_theta = dto.optim.weight_acc_lim_theta;
+        bo.optim.weight_kinematics_nh = dto.optim.weight_kinematics_nh;
+        bo.optim.weight_kinematics_forward_drive = dto.optim.weight_kinematics_forward_drive;
+        bo.optim.weight_kinematics_turning_radius = dto.optim.weight_kinematics_turning_radius;
+        bo.optim.weight_optimaltime = dto.optim.weight_optimaltime;
+        bo.optim.weight_shortest_path = dto.optim.weight_shortest_path;
+        bo.optim.weight_obstacle = dto.optim.weight_obstacle;
+        bo.optim.weight_inflation = dto.optim.weight_inflation;
+        bo.optim.weight_dynamic_obstacle = dto.optim.weight_dynamic_obstacle;
+        bo.optim.weight_dynamic_obstacle_inflation = dto.optim.weight_dynamic_obstacle_inflation;
+        bo.optim.weight_velocity_obstacle_ratio = dto.optim.weight_velocity_obstacle_ratio;
+        bo.optim.weight_viapoint = dto.optim.weight_viapoint;
+        bo.optim.weight_prefer_rotdir = dto.optim.weight_prefer_rotdir;
+        bo.optim.weight_adapt_factor = dto.optim.weight_adapt_factor;
+        bo.optim.obstacle_cost_exponent = dto.optim.obstacle_cost_exponent;
+
+        // Homotopy Class Planner
+        bo.hcp.enable_multithreading = dto.hcp.enable_multithreading;
+        bo.hcp.simple_exploration = dto.hcp.simple_exploration;
+        bo.hcp.max_number_classes = dto.hcp.max_number_classes;
+        bo.hcp.max_number_plans_in_current_class = dto.hcp.max_number_plans_in_current_class;
+        bo.hcp.selection_cost_hysteresis = dto.hcp.selection_cost_hysteresis;
+        bo.hcp.selection_prefer_initial_plan = dto.hcp.selection_prefer_initial_plan;
+        bo.hcp.selection_obst_cost_scale = dto.hcp.selection_obst_cost_scale;
+        bo.hcp.selection_viapoint_cost_scale = dto.hcp.selection_viapoint_cost_scale;
+        bo.hcp.selection_alternative_time_cost = dto.hcp.selection_alternative_time_cost;
+        bo.hcp.selection_dropping_probability = dto.hcp.selection_dropping_probability;
+        bo.hcp.switching_blocking_period = dto.hcp.switching_blocking_period;
+
+        bo.hcp.obstacle_heading_threshold = dto.hcp.obstacle_heading_threshold;
+        bo.hcp.roadmap_graph_no_samples = dto.hcp.roadmap_graph_no_samples;
+        bo.hcp.roadmap_graph_area_width = dto.hcp.roadmap_graph_area_width;
+        bo.hcp.roadmap_graph_area_length_scale = dto.hcp.roadmap_graph_area_length_scale;
+        bo.hcp.h_signature_prescaler = dto.hcp.h_signature_prescaler;
+        bo.hcp.h_signature_threshold = dto.hcp.h_signature_threshold;
+
+        bo.hcp.viapoints_all_candidates = dto.hcp.viapoints_all_candidates;
+
+        bo.hcp.delete_detours_backwards = dto.hcp.delete_detours_backwards;
+        bo.hcp.detours_orientation_tolerance = dto.hcp.detours_orientation_tolerance;
+        bo.hcp.length_start_orientation_vector = dto.hcp.length_start_orientation_vector;
+        bo.hcp.max_ratio_detours_duration_best_duration =
+            dto.hcp.max_ratio_detours_duration_best_duration;
+
+        bo.checkParameters();
+    }
+
 
 } // namespace armarx::navigation::local_planning
-- 
GitLab


From 71d8734bef4ee0b2adff6bd828a14b95b2d706e8 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 4 Aug 2022 15:09:28 +0200
Subject: [PATCH 063/324] param update

---
 .../controller_config/PlatformTrajectory/default.json         | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/data/armarx_navigation/controller_config/PlatformTrajectory/default.json b/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
index c9ffcb3f..e69bb829 100644
--- a/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
+++ b/data/armarx_navigation/controller_config/PlatformTrajectory/default.json
@@ -1,12 +1,12 @@
 {
   "params": {
     "pidPos": {
-      "Kp": 1,
+      "Kp": 0.1,
       "Ki": 0,
       "Kd": 0
     },
     "pidOri": {
-      "Kp": 1,
+      "Kp": 0.1,
       "Ki": 0,
       "Kd": 0
     },
-- 
GitLab


From 9caeef85ca3ef52917efb51e47907da4a49af14a Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 4 Aug 2022 20:47:59 +0200
Subject: [PATCH 064/324] Implement getSubTrajectory for GlobalTrajectory

---
 source/armarx/navigation/core/Trajectory.cpp | 151 +++++++++++++------
 source/armarx/navigation/core/Trajectory.h   |  20 +++
 2 files changed, 125 insertions(+), 46 deletions(-)

diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index e1774afa..fc5c9b0b 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -6,18 +6,6 @@
 #include <iterator>
 #include <limits>
 
-#include <range/v3/action/insert.hpp>
-#include <range/v3/numeric/accumulate.hpp>
-#include <range/v3/range/conversion.hpp>
-#include <range/v3/view/all.hpp>
-#include <range/v3/view/concat.hpp>
-#include <range/v3/view/for_each.hpp>
-#include <range/v3/view/group_by.hpp>
-#include <range/v3/view/reverse.hpp>
-#include <range/v3/view/sliding.hpp>
-#include <range/v3/view/transform.hpp>
-#include <range/v3/view/zip.hpp>
-
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
@@ -34,6 +22,17 @@
 #include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/types.h>
+#include <range/v3/action/insert.hpp>
+#include <range/v3/numeric/accumulate.hpp>
+#include <range/v3/range/conversion.hpp>
+#include <range/v3/view/all.hpp>
+#include <range/v3/view/concat.hpp>
+#include <range/v3/view/for_each.hpp>
+#include <range/v3/view/group_by.hpp>
+#include <range/v3/view/reverse.hpp>
+#include <range/v3/view/sliding.hpp>
+#include <range/v3/view/transform.hpp>
+#include <range/v3/view/zip.hpp>
 
 // FIXME move to simox
 
@@ -158,13 +157,14 @@ namespace armarx::navigation::core
 
     } // namespace conv
 
-    Projection
-    GlobalTrajectory::getProjection(const Position& point,
-                              const VelocityInterpolation& velocityInterpolation) const
+
+    GlobalTrajectory::InternalProjection
+    GlobalTrajectory::projectInternal(const Position& point,
+                                      const VelocityInterpolation& velocityInterpolation) const
     {
         float distance = std::numeric_limits<float>::max();
 
-        Projection bestProj;
+        InternalProjection bestProj;
 
         for (size_t i = 0; i < pts.size() - 1; i++)
         {
@@ -198,26 +198,9 @@ namespace armarx::navigation::core
                 math::LinearInterpolatedPose ip(
                     wpBefore.waypoint.pose.matrix(), wpAfter.waypoint.pose.matrix(), 0, 1, true);
 
-                bestProj.wayPointBefore = wpBefore;
-                bestProj.wayPointAfter = wpAfter;
+                bestProj.indexBefore = i;
                 bestProj.projection.waypoint.pose = ip.Get(t);
 
-                bestProj.segment = [&]
-                {
-                    if (i == 0)
-                    {
-                        return Projection::Segment::FIRST;
-                    }
-
-                    if (i == (pts.size() - 2))
-                    {
-                        return Projection::Segment::FINAL;
-                    }
-
-                    return Projection::Segment::INTERMEDIATE;
-                }();
-
-
                 switch (velocityInterpolation)
                 {
                     case VelocityInterpolation::LinearInterpolation:
@@ -236,6 +219,82 @@ namespace armarx::navigation::core
         return bestProj;
     }
 
+    Projection
+    GlobalTrajectory::getProjection(const Position& point,
+                                    const VelocityInterpolation& velocityInterpolation) const
+    {
+        InternalProjection intProj = projectInternal(point, velocityInterpolation);
+
+        const auto& wpBefore = pts.at(intProj.indexBefore);
+        const auto& wpAfter = pts.at(intProj.indexBefore + 1);
+
+        Projection bestProj;
+
+        bestProj.wayPointBefore = wpBefore;
+        bestProj.wayPointAfter = wpAfter;
+        bestProj.projection = intProj.projection;
+
+        bestProj.segment = [&]
+        {
+            if (intProj.indexBefore == 0)
+            {
+                return Projection::Segment::FIRST;
+            }
+
+            if (intProj.indexBefore == (pts.size() - 2))
+            {
+                return Projection::Segment::FINAL;
+            }
+
+            return Projection::Segment::INTERMEDIATE;
+        }();
+
+        return bestProj;
+    }
+
+    std::pair<GlobalTrajectory, bool>
+    GlobalTrajectory::getSubTrajectory(const Position& point, float distance) const
+    {
+        const InternalProjection intProj =
+            projectInternal(point, VelocityInterpolation::LinearInterpolation);
+
+        GlobalTrajectory subTraj{};
+        subTraj.mutablePoints().push_back(intProj.projection);
+
+        float remainingDistance = distance;
+        GlobalTrajectoryPoint lastWp = intProj.projection;
+        for (size_t i = intProj.indexBefore + 1; i < pts.size(); i++)
+        {
+            const auto& nextWp = pts.at(i);
+
+            const float segmentDistance =
+                (nextWp.waypoint.pose.translation() - lastWp.waypoint.pose.translation()).norm();
+
+            if (segmentDistance < remainingDistance)
+            {
+                subTraj.mutablePoints().push_back(nextWp);
+                lastWp = nextWp;
+                remainingDistance -= segmentDistance;
+            }
+            else
+            {
+                // fraction of distance between segment end points
+                const float t = remainingDistance / segmentDistance;
+
+                math::LinearInterpolatedPose ip(
+                    lastWp.waypoint.pose.matrix(), nextWp.waypoint.pose.matrix(), 0, 1, true);
+                const float velocity = lastWp.velocity + (nextWp.velocity - lastWp.velocity) * t;
+
+                subTraj.mutablePoints().push_back({{static_cast<Pose>(ip.Get(t))}, velocity});
+
+                return {subTraj, false};
+            }
+        }
+
+        // remaining trajectory is shorter than the specified distance
+        return {subTraj, true};
+    }
+
     std::vector<Eigen::Vector3f>
     GlobalTrajectory::positions() const noexcept
     {
@@ -273,9 +332,9 @@ namespace armarx::navigation::core
 
     GlobalTrajectory
     GlobalTrajectory::FromPath(const Pose& start,
-                         const Positions& waypoints,
-                         const Pose& goal,
-                         const float velocity)
+                               const Positions& waypoints,
+                               const Pose& goal,
+                               const float velocity)
     {
         // currently, only 2D version
 
@@ -331,7 +390,8 @@ namespace armarx::navigation::core
     {
         core::Positions resampledPath;
 
-        const auto toPoint = [](const GlobalTrajectoryPoint& wp) -> Pose { return wp.waypoint.pose; };
+        const auto toPoint = [](const GlobalTrajectoryPoint& wp) -> Pose
+        { return wp.waypoint.pose; };
 
         const core::Path originalPath = pts | ranges::views::transform(toPoint) | ranges::to_vector;
 
@@ -601,7 +661,7 @@ namespace armarx::navigation::core
 
             constexpr int nSamples = 100;
 
-            for(int j = 0; j < nSamples; j++)
+            for (int j = 0; j < nSamples; j++)
             {
                 const float progress = static_cast<float>(j) / nSamples;
 
@@ -675,7 +735,6 @@ namespace armarx::navigation::core
         return indices;
     }
 
-
     const std::vector<LocalTrajectoryPoint>&
     LocalTrajectory::points() const
     {
@@ -714,14 +773,16 @@ namespace armarx::navigation::core
 
         // fraction of time between segment end points
         const float t = d1 / dT;
-        math::LinearInterpolatedPose ip(global_T_wp_before.matrix(), global_T_wp_after.matrix(), 0, 1, true);
+        math::LinearInterpolatedPose ip(
+            global_T_wp_before.matrix(), global_T_wp_after.matrix(), 0, 1, true);
 
         const core::Pose wp_before_T_wp_after = global_T_wp_before.inverse() * global_T_wp_after;
 
         const Eigen::Matrix3f& global_R_wp_before = global_T_wp_before.linear();
 
         // the movement direction in the global frame
-        const Eigen::Vector3f global_V_linear_movement_direction = global_R_wp_before * wp_before_T_wp_after.translation().normalized();
+        const Eigen::Vector3f global_V_linear_movement_direction =
+            global_R_wp_before * wp_before_T_wp_after.translation().normalized();
         const Eigen::Vector3f distance = lower[1].pose.translation() - lower->pose.translation();
         const float linearVelocity = static_cast<float>(distance.norm()) / dT.toSecondsDouble();
 
@@ -730,11 +791,9 @@ namespace armarx::navigation::core
 
         Eigen::AngleAxisf angleAx(wp_before_T_wp_after.linear());
 
-        const core::Twist feedforwardTwist
-        {
+        const core::Twist feedforwardTwist{
             .linear = linearVelocity * global_V_linear_movement_direction,
-            .angular = angleAx.axis() * angleAx.angle() / dT.toSecondsDouble()
-        };
+            .angular = angleAx.axis() * angleAx.angle() / dT.toSecondsDouble()};
 
         return {static_cast<core::Pose>(ip.Get(t)), feedforwardTwist};
     }
diff --git a/source/armarx/navigation/core/Trajectory.h b/source/armarx/navigation/core/Trajectory.h
index 5b2ba33a..20da0ba1 100644
--- a/source/armarx/navigation/core/Trajectory.h
+++ b/source/armarx/navigation/core/Trajectory.h
@@ -24,6 +24,7 @@
 
 #include <cstddef>
 #include <memory>
+
 #include "ArmarXCore/core/time/DateTime.h"
 
 #include <armarx/navigation/core/basic_types.h>
@@ -76,6 +77,15 @@ namespace armarx::navigation::core
         Projection getProjection(const Position& point,
                                  const VelocityInterpolation& velocityInterpolation) const;
 
+        /**
+         * @brief Project point onto the trajectory and return a new trajectory along the old one
+         *        from that point for the specified distance.
+         * @return The subtrajectory and whether the subtrajectory ends at the same point,
+         *         as this trajectory
+         */
+        std::pair<GlobalTrajectory, bool> getSubTrajectory(const Position& point,
+                                                           const float distance) const;
+
         [[nodiscard]] std::vector<Position> positions() const noexcept;
 
         [[nodiscard]] std::vector<Pose> poses() const noexcept;
@@ -117,6 +127,16 @@ namespace armarx::navigation::core
          */
         Indices allConnectedPointsInRange(std::size_t idx, float radius) const;
 
+    private:
+        struct InternalProjection
+        {
+            GlobalTrajectoryPoint projection;
+            size_t indexBefore;
+        };
+        InternalProjection
+        projectInternal(const Position& point,
+                        const VelocityInterpolation& velocityInterpolation) const;
+
 
     private:
         std::vector<GlobalTrajectoryPoint> pts;
-- 
GitLab


From d78448a362511fce82ea8e53bc8aad14b381cbf5 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 4 Aug 2022 20:48:28 +0200
Subject: [PATCH 065/324] Use subtrajectory as goal for planning

---
 .../local_planning/TimedElasticBands.cpp      | 33 +++++++------------
 .../local_planning/TimedElasticBands.h        |  9 -----
 2 files changed, 12 insertions(+), 30 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index f0495713..3ff39fd6 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -100,16 +100,20 @@ namespace armarx::navigation::local_planning
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::GlobalTrajectory& goal)
     {
-        const teb_local_planner::TimedElasticBand globalPath = conv::toRos(goal);
+        const core::Pose currentPose{scene.robot->getGlobalPose()};
+
+        // TODO (SALt): put distance parameter into config (note: distance is in mm)
+        // prune global trajectory
+        const auto& [prunedGoal, planToDest] =
+            goal.getSubTrajectory(currentPose.translation(), 2000);
+
+        const teb_local_planner::TimedElasticBand globalPath = conv::toRos(prunedGoal);
         teb_globalPath = globalPath.poses();
         hcp_->setGlobalPath(&teb_globalPath);
 
-        const core::Pose currentPose{scene.robot->getGlobalPose()};
-
         const teb_local_planner::PoseSE2 start = conv::toRos(currentPose);
-
-        const FindTargetResult target = findTarget(currentPose, goal);
-        const teb_local_planner::PoseSE2 end = conv::toRos(target.target);
+        const teb_local_planner::PoseSE2 end =
+            conv::toRos(prunedGoal.points().back().waypoint.pose);
 
         geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity);
 
@@ -118,7 +122,8 @@ namespace armarx::navigation::local_planning
 
         try
         {
-            hcp_->plan(start, end, &velocity_start, !target.planToDestination);
+            // TODO (SALt): free goal velocity is not respected inside homotopy planner
+            hcp_->plan(start, end, &velocity_start, !planToDest);
         }
         catch (std::exception& e)
         {
@@ -134,20 +139,6 @@ namespace armarx::navigation::local_planning
     }
 
 
-    TimedElasticBands::FindTargetResult
-    TimedElasticBands::findTarget(const core::Pose& currentPose,
-                                  const core::GlobalTrajectory& globalPath)
-    {
-        // TODO (SALt): implement
-
-        const core::Projection projection = globalPath.getProjection(
-            currentPose.translation(), core::VelocityInterpolation::LinearInterpolation);
-
-        return {conv::to2D(projection.projection.waypoint.pose),
-                conv::to2D(globalPath.points().back().waypoint.pose),
-                true};
-    }
-
     void
     TimedElasticBands::fillObstacles()
     {
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 26826650..f8c005ac 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -59,16 +59,7 @@ namespace armarx::navigation::local_planning
         std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
 
     private:
-        struct FindTargetResult
-        {
-            core::Pose2D projection;
-            core::Pose2D target;
-            bool planToDestination;
-        };
-
         void initConfig();
-        FindTargetResult findTarget(const core::Pose& currentPose,
-                                    const core::GlobalTrajectory& globalPath);
         void fillObstacles();
 
     protected:
-- 
GitLab


From b63a6c0e677e188f0abe5885d1d9b4aa75d26875 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 20:05:22 +0200
Subject: [PATCH 066/324] Fix config parameters

Upstream merge of teb_local_planner added a new parameter.
Other parameter is only used when an initial plan is used which we do not do.
---
 .../local_planner_config/TimedElasticBands/default.json         | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 33389b94..ed871ab9 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -29,6 +29,7 @@
     "max_vel_x": 0.4,
     "max_vel_x_backwards": 0.2,
     "max_vel_y": 0.0,
+    "max_vel_trans": 0.5,
     "max_vel_theta": 0.3,
     "acc_lim_x": 0.5,
     "acc_lim_y": 0.5,
@@ -86,7 +87,6 @@
     "max_number_classes": 5,
     "max_number_plans_in_current_class": 0,
     "selection_cost_hysteresis": 1.0,
-    "selection_prefer_initial_plan": 0.95,
     "selection_obst_cost_scale": 100.0,
     "selection_viapoint_cost_scale": 1.0,
     "selection_alternative_time_cost": false,
-- 
GitLab


From 4c95256a7ca6e27dc9d297b1f7cdcc2ef3eed484 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 20:06:38 +0200
Subject: [PATCH 067/324] Adjust default velocity

---
 .../local_planner_config/TimedElasticBands/default.json     | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index ed871ab9..a689e85d 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -26,9 +26,9 @@
   },
 
   "robot": {
-    "max_vel_x": 0.4,
-    "max_vel_x_backwards": 0.2,
-    "max_vel_y": 0.0,
+    "max_vel_x": 0.5,
+    "max_vel_x_backwards": 0.5,
+    "max_vel_y": 0.5,
     "max_vel_trans": 0.5,
     "max_vel_theta": 0.3,
     "acc_lim_x": 0.5,
-- 
GitLab


From 2522bc14e273f676d6276cf2962c9e9b2c6f91aa Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 20:07:11 +0200
Subject: [PATCH 068/324] Implement paramter changes in aron and add conversion

---
 .../navigation/local_planning/aron/TimedElasticBands.xml  | 8 ++++----
 .../armarx/navigation/local_planning/aron_conversions.cpp | 2 +-
 2 files changed, 5 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index b0f90f17..452a953b 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -102,6 +102,10 @@
                 <float />
             </ObjectChild>
 
+            <ObjectChild key='max_vel_trans'>
+                <float />
+            </ObjectChild>
+
             <ObjectChild key='max_vel_theta'>
                 <float />
             </ObjectChild>
@@ -290,10 +294,6 @@
                 <float />
             </ObjectChild>
 
-            <ObjectChild key='selection_prefer_initial_plan'>
-                <float />
-            </ObjectChild>
-
             <ObjectChild key='selection_obst_cost_scale'>
                 <float />
             </ObjectChild>
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 4a93ffcd..000eabca 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -59,6 +59,7 @@ namespace armarx::navigation::local_planning
         bo.robot.max_vel_x = dto.robot.max_vel_x;
         bo.robot.max_vel_x_backwards = dto.robot.max_vel_x_backwards;
         bo.robot.max_vel_y = dto.robot.max_vel_y;
+        bo.robot.max_vel_trans = dto.robot.max_vel_trans;
         bo.robot.max_vel_theta = dto.robot.max_vel_theta;
         bo.robot.acc_lim_x = dto.robot.acc_lim_x;
         bo.robot.acc_lim_y = dto.robot.acc_lim_y;
@@ -116,7 +117,6 @@ namespace armarx::navigation::local_planning
         bo.hcp.max_number_classes = dto.hcp.max_number_classes;
         bo.hcp.max_number_plans_in_current_class = dto.hcp.max_number_plans_in_current_class;
         bo.hcp.selection_cost_hysteresis = dto.hcp.selection_cost_hysteresis;
-        bo.hcp.selection_prefer_initial_plan = dto.hcp.selection_prefer_initial_plan;
         bo.hcp.selection_obst_cost_scale = dto.hcp.selection_obst_cost_scale;
         bo.hcp.selection_viapoint_cost_scale = dto.hcp.selection_viapoint_cost_scale;
         bo.hcp.selection_alternative_time_cost = dto.hcp.selection_alternative_time_cost;
-- 
GitLab


From 8ae12c873c0fff8334c02e6c924eaf4dfdff2edd Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 21:23:18 +0200
Subject: [PATCH 069/324] Fix bug in loadDefaultConfig

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 8084e1fb..0d61b9ed 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -95,7 +95,7 @@ namespace armarx::navigation::local_planning
 
         dto.read(reader, jsonConfig);
 
-        toTebCfg(params.cfg, cfg_);
+        toTebCfg(dto, cfg_);
     }
 
     std::optional<LocalPlannerResult>
-- 
GitLab


From 97748d9d2b10c7ac6958933f1f188bf925063cbf Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 21:26:18 +0200
Subject: [PATCH 070/324] Increase default velocity limit

---
 .../local_planner_config/TimedElasticBands/default.json         | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index a689e85d..f862ff02 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -30,7 +30,7 @@
     "max_vel_x_backwards": 0.5,
     "max_vel_y": 0.5,
     "max_vel_trans": 0.5,
-    "max_vel_theta": 0.3,
+    "max_vel_theta": 0.5,
     "acc_lim_x": 0.5,
     "acc_lim_y": 0.5,
     "acc_lim_theta": 0.5,
-- 
GitLab


From cecccfb086433209b563212207fe04c9c69ac1f6 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 11 Aug 2022 22:39:48 +0200
Subject: [PATCH 071/324] Add new config parameters

---
 .../TimedElasticBands/default.json            | 201 +++++++++---------
 .../local_planning/TimedElasticBands.cpp      |  34 ++-
 .../local_planning/TimedElasticBands.h        |   4 +-
 .../local_planning/aron/TimedElasticBands.xml |  16 +-
 .../local_planning/aron_conversions.cpp       | 184 ++++++++--------
 5 files changed, 230 insertions(+), 209 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index f862ff02..e2c40a1b 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -1,111 +1,114 @@
 {
-  "pse": {
-    "pse_costum_obstacle_penalties": true,
-    "pse_costum_obstacle_penalties_dynamic": true,
-    "weight_global_path": 0.1,
-    "lrk_use_alternative_approach": false,
-    "lrk_enable_collision_check": true,
-    "hybrid_homotopy_calculation": true,
-    "robot_diff_circumscribed_inscribed_radius": 0.0
-  },
+  "robot_footprint_radius": 0.2,
+  "planning_distance": 2,
+  "teb_config": {
+    "pse": {
+      "pse_costum_obstacle_penalties": true,
+      "pse_costum_obstacle_penalties_dynamic": true,
+      "weight_global_path": 0.1,
+      "lrk_use_alternative_approach": false,
+      "lrk_enable_collision_check": true,
+      "hybrid_homotopy_calculation": true,
+      "robot_diff_circumscribed_inscribed_radius": 0.0
+    },
 
-  "trajectory": {
-    "teb_autosize": true,
-    "dt_ref": 0.3,
-    "dt_hysteresis": 0.1,
-    "min_samples": 3,
-    "max_samples": 500,
-    "global_plan_overwrite_orientation": true,
-    "allow_init_with_backwards_motion": false,
-    "exact_arc_length": false,
-    "force_reinit_new_goal_dist": 1,
-    "force_reinit_new_goal_angular": 1.5707963267948966,
-    "feasibility_check_no_poses": 5,
-    "feasibility_check_lookahead_distance": -1,
-    "min_resolution_collision_check_angular": 3.141592653589793
-  },
+    "trajectory": {
+      "teb_autosize": true,
+      "dt_ref": 0.3,
+      "dt_hysteresis": 0.1,
+      "min_samples": 3,
+      "max_samples": 500,
+      "global_plan_overwrite_orientation": true,
+      "allow_init_with_backwards_motion": false,
+      "exact_arc_length": false,
+      "force_reinit_new_goal_dist": 1,
+      "force_reinit_new_goal_angular": 1.5707963267948966,
+      "feasibility_check_no_poses": 5,
+      "feasibility_check_lookahead_distance": -1,
+      "min_resolution_collision_check_angular": 3.141592653589793
+    },
 
-  "robot": {
-    "max_vel_x": 0.5,
-    "max_vel_x_backwards": 0.5,
-    "max_vel_y": 0.5,
-    "max_vel_trans": 0.5,
-    "max_vel_theta": 0.5,
-    "acc_lim_x": 0.5,
-    "acc_lim_y": 0.5,
-    "acc_lim_theta": 0.5,
-    "min_turning_radius": 0
-  },
+    "robot": {
+      "max_vel_x": 0.5,
+      "max_vel_x_backwards": 0.5,
+      "max_vel_y": 0.5,
+      "max_vel_trans": 0.5,
+      "max_vel_theta": 0.5,
+      "acc_lim_x": 0.5,
+      "acc_lim_y": 0.5,
+      "acc_lim_theta": 0.5,
+      "min_turning_radius": 0
+    },
 
-  "goal_tolerance": {
-    "xy_goal_tolerance": 0.2
-  },
+    "goal_tolerance": {
+      "xy_goal_tolerance": 0.2
+    },
 
-  "obstacles": {
-    "min_obstacle_dist": 0.5,
-    "inflation_dist": 0.0,
-    "dynamic_obstacle_inflation_dist": 0.6,
-    "include_dynamic_obstacles": true,
-    "obstacle_association_force_inclusion_factor": 1.5,
-    "obstacle_association_cutoff_factor": 5,
-    "obstacle_proximity_ratio_max_vel": 1,
-    "obstacle_proximity_lower_bound": 0,
-    "obstacle_proximity_upper_bound": 0.5
-  },
+    "obstacles": {
+      "min_obstacle_dist": 0.5,
+      "inflation_dist": 0.0,
+      "dynamic_obstacle_inflation_dist": 0.6,
+      "include_dynamic_obstacles": true,
+      "obstacle_association_force_inclusion_factor": 1.5,
+      "obstacle_association_cutoff_factor": 5,
+      "obstacle_proximity_ratio_max_vel": 1,
+      "obstacle_proximity_lower_bound": 0,
+      "obstacle_proximity_upper_bound": 0.5
+    },
 
-  "optim": {
-    "no_inner_iterations": 5,
-    "no_outer_iterations": 4,
-    "optimization_activate": true,
-    "optimization_verbose": false,
-    "penalty_epsilon": 0.05,
-    "weight_max_vel_x": 2,
-    "weight_max_vel_y": 2,
-    "weight_max_vel_theta": 1,
-    "weight_acc_lim_x": 1,
-    "weight_acc_lim_y": 1,
-    "weight_acc_lim_theta": 1,
-    "weight_kinematics_nh": 1000,
-    "weight_kinematics_forward_drive": 1,
-    "weight_kinematics_turning_radius": 1,
-    "weight_optimaltime": 1,
-    "weight_shortest_path": 0,
-    "weight_obstacle": 50,
-    "weight_inflation": 0.1,
-    "weight_dynamic_obstacle": 50,
-    "weight_dynamic_obstacle_inflation": 0.1,
-    "weight_velocity_obstacle_ratio": 0,
-    "weight_viapoint": 1,
-    "weight_prefer_rotdir": 50,
-    "weight_adapt_factor": 2.0,
-    "obstacle_cost_exponent": 1.0
-  },
+    "optim": {
+      "no_inner_iterations": 5,
+      "no_outer_iterations": 4,
+      "optimization_activate": true,
+      "optimization_verbose": false,
+      "penalty_epsilon": 0.05,
+      "weight_max_vel_x": 2,
+      "weight_max_vel_y": 2,
+      "weight_max_vel_theta": 1,
+      "weight_acc_lim_x": 1,
+      "weight_acc_lim_y": 1,
+      "weight_acc_lim_theta": 1,
+      "weight_kinematics_nh": 1000,
+      "weight_kinematics_forward_drive": 1,
+      "weight_kinematics_turning_radius": 1,
+      "weight_optimaltime": 1,
+      "weight_shortest_path": 0,
+      "weight_obstacle": 50,
+      "weight_inflation": 0.1,
+      "weight_dynamic_obstacle": 50,
+      "weight_dynamic_obstacle_inflation": 0.1,
+      "weight_velocity_obstacle_ratio": 0,
+      "weight_viapoint": 1,
+      "weight_prefer_rotdir": 50,
+      "weight_adapt_factor": 2.0,
+      "obstacle_cost_exponent": 1.0
+    },
 
-  "hcp": {
-    "enable_multithreading": true,
-    "simple_exploration": false,
-    "max_number_classes": 5,
-    "max_number_plans_in_current_class": 0,
-    "selection_cost_hysteresis": 1.0,
-    "selection_obst_cost_scale": 100.0,
-    "selection_viapoint_cost_scale": 1.0,
-    "selection_alternative_time_cost": false,
-    "selection_dropping_probability": 0.0,
-    "switching_blocking_period": 0.0,
+    "hcp": {
+      "enable_multithreading": true,
+      "simple_exploration": false,
+      "max_number_classes": 5,
+      "max_number_plans_in_current_class": 0,
+      "selection_cost_hysteresis": 1.0,
+      "selection_obst_cost_scale": 100.0,
+      "selection_viapoint_cost_scale": 1.0,
+      "selection_alternative_time_cost": false,
+      "selection_dropping_probability": 0.0,
+      "switching_blocking_period": 0.0,
 
-    "obstacle_heading_threshold": 0.45,
-    "roadmap_graph_no_samples": 20,
-    "roadmap_graph_area_width": 10,
-    "roadmap_graph_area_length_scale": 1.0,
-    "h_signature_prescaler": 1,
-    "h_signature_threshold": 0.1,
+      "obstacle_heading_threshold": 0.45,
+      "roadmap_graph_no_samples": 20,
+      "roadmap_graph_area_width": 10,
+      "roadmap_graph_area_length_scale": 1.0,
+      "h_signature_prescaler": 1,
+      "h_signature_threshold": 0.1,
 
-    "viapoints_all_candidates": true,
+      "viapoints_all_candidates": true,
 
-    "delete_detours_backwards": true,
-    "detours_orientation_tolerance": 1.5707963267948966,
-    "length_start_orientation_vector": 0.4,
-    "max_ratio_detours_duration_best_duration": 3.0
+      "delete_detours_backwards": true,
+      "detours_orientation_tolerance": 1.5707963267948966,
+      "length_start_orientation_vector": 0.4,
+      "max_ratio_detours_duration_best_duration": 3.0
+    }
   }
-
 }
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 35881b66..446b5743 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -51,19 +51,18 @@ namespace armarx::navigation::local_planning
 
     // TimedElasticBands
 
-    TimedElasticBands::TimedElasticBands(const Params& params, const core::Scene& ctx) :
-        LocalPlanner(ctx), params(params), scene(ctx), obstManager(teb_obstacles)
+    TimedElasticBands::TimedElasticBands(const Params& i_params, const core::Scene& ctx) :
+        LocalPlanner(ctx), params(i_params), scene(ctx), obstManager(teb_obstacles)
     {
-        //TODO (SALt): init configuration, robot footprint
-        if (false)
+        //TODO (SALt): find proper place to init with default config
+        if (true)
         {
-            toTebCfg(params.cfg, cfg_);
+            readDefaultConfig(params.cfg);
         }
-        else
-        {
-            initDefaultConfig();
-        }
-        auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(0.2);
+        toTebCfg(params.cfg, cfg_);
+
+        auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(
+            params.cfg.robot_footprint_radius);
 
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
         hcp_->initialize(
@@ -73,10 +72,8 @@ namespace armarx::navigation::local_planning
     }
 
     void
-    TimedElasticBands::initDefaultConfig()
+    TimedElasticBands::readDefaultConfig(arondto::TimedElasticBandsParams& target)
     {
-        arondto::TimedElasticBandsParams dto;
-
         const armarx::PackagePath configPath("armarx_navigation",
                                              "local_planner_config/TimedElasticBands/default.json");
         const std::filesystem::path file = configPath.toSystemPath();
@@ -89,13 +86,10 @@ namespace armarx::navigation::local_planning
         nlohmann::json jsonConfig;
         ifs >> jsonConfig;
 
-        ARMARX_INFO << "Initializing config";
+        ARMARX_INFO << "Reading config";
 
         armarx::aron::data::reader::NlohmannJSONReaderWithoutTypeCheck reader;
-
-        dto.read(reader, jsonConfig);
-
-        toTebCfg(dto, cfg_);
+        target.read(reader, jsonConfig);
     }
 
     std::optional<LocalPlannerResult>
@@ -103,10 +97,9 @@ namespace armarx::navigation::local_planning
     {
         const core::Pose currentPose{scene.robot->getGlobalPose()};
 
-        // TODO (SALt): put distance parameter into config (note: distance is in mm)
         // prune global trajectory
         const auto& [prunedGoal, planToDest] =
-            goal.getSubTrajectory(currentPose.translation(), 2000);
+            goal.getSubTrajectory(currentPose.translation(), params.cfg.planning_distance * 1000);
 
         const teb_local_planner::TimedElasticBand globalPath = conv::toRos(prunedGoal);
         teb_globalPath = globalPath.poses();
@@ -124,6 +117,7 @@ namespace armarx::navigation::local_planning
         try
         {
             // TODO (SALt): free goal velocity is not respected inside homotopy planner
+            ARMARX_VERBOSE << "Plan to dest: " << planToDest << ", freeGoal Vel: " << !planToDest;
             hcp_->plan(start, end, &velocity_start, !planToDest);
         }
         catch (std::exception& e)
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 6bded067..9eba4d52 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -59,11 +59,11 @@ namespace armarx::navigation::local_planning
         std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
 
     private:
-        void initDefaultConfig();
+        void readDefaultConfig(arondto::TimedElasticBandsParams& target);
         void fillObstacles();
 
     protected:
-        const Params params;
+        Params params;
 
     private:
         const core::Scene& scene;
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 452a953b..4c3c9249 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -362,7 +362,7 @@
             </ObjectChild>
         </Object>
 
-        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
+        <Object name='armarx::navigation::local_planning::arondto::teb_config'>
             <ObjectChild key='pse'>
                 <armarx::navigation::local_planning::arondto::pse />
             </ObjectChild>
@@ -386,5 +386,19 @@
             </ObjectChild>
         </Object>
 
+        <Object name='armarx::navigation::local_planning::arondto::TimedElasticBandsParams'>
+            <ObjectChild key='robot_footprint_radius'>
+                <float />
+            </ObjectChild>
+            <ObjectChild key='planning_distance'>
+                <float />
+            </ObjectChild>
+            <ObjectChild key='teb_config'>
+                <armarx::navigation::local_planning::arondto::teb_config />
+            </ObjectChild>
+        </Object>
+
+
+
     </GenerateTypes>
 </AronTypeDefinition>
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 000eabca..220a02b3 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -26,117 +26,127 @@ namespace armarx::navigation::local_planning
     void
     toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo)
     {
-        bo.pse.pse_costum_obstacle_penalties = dto.pse.pse_costum_obstacle_penalties;
+        bo.pse.pse_costum_obstacle_penalties = dto.teb_config.pse.pse_costum_obstacle_penalties;
         bo.pse.pse_costum_obstacle_penalties_dynamic =
-            dto.pse.pse_costum_obstacle_penalties_dynamic;
-        bo.pse.weight_global_path = dto.pse.weight_global_path;
-        bo.pse.lrk_use_alternative_approach = dto.pse.lrk_use_alternative_approach;
-        bo.pse.lrk_enable_collision_check = dto.pse.lrk_enable_collision_check;
-        bo.pse.hybrid_homotopy_calculation = dto.pse.hybrid_homotopy_calculation;
+            dto.teb_config.pse.pse_costum_obstacle_penalties_dynamic;
+        bo.pse.weight_global_path = dto.teb_config.pse.weight_global_path;
+        bo.pse.lrk_use_alternative_approach = dto.teb_config.pse.lrk_use_alternative_approach;
+        bo.pse.lrk_enable_collision_check = dto.teb_config.pse.lrk_enable_collision_check;
+        bo.pse.hybrid_homotopy_calculation = dto.teb_config.pse.hybrid_homotopy_calculation;
         bo.pse.robot_diff_circumscribed_inscribed_radius =
-            dto.pse.robot_diff_circumscribed_inscribed_radius;
+            dto.teb_config.pse.robot_diff_circumscribed_inscribed_radius;
 
         // Trajectory
         bo.trajectory.teb_autosize = bo.trajectory.teb_autosize;
-        bo.trajectory.dt_ref = dto.trajectory.dt_ref;
-        bo.trajectory.dt_hysteresis = dto.trajectory.dt_hysteresis;
-        bo.trajectory.min_samples = dto.trajectory.min_samples;
-        bo.trajectory.max_samples = dto.trajectory.max_samples;
+        bo.trajectory.dt_ref = dto.teb_config.trajectory.dt_ref;
+        bo.trajectory.dt_hysteresis = dto.teb_config.trajectory.dt_hysteresis;
+        bo.trajectory.min_samples = dto.teb_config.trajectory.min_samples;
+        bo.trajectory.max_samples = dto.teb_config.trajectory.max_samples;
         bo.trajectory.global_plan_overwrite_orientation =
-            dto.trajectory.global_plan_overwrite_orientation;
+            dto.teb_config.trajectory.global_plan_overwrite_orientation;
         bo.trajectory.allow_init_with_backwards_motion =
-            dto.trajectory.allow_init_with_backwards_motion;
-        bo.trajectory.exact_arc_length = dto.trajectory.exact_arc_length;
-        bo.trajectory.force_reinit_new_goal_dist = dto.trajectory.force_reinit_new_goal_dist;
-        bo.trajectory.force_reinit_new_goal_angular = dto.trajectory.force_reinit_new_goal_angular;
-        bo.trajectory.feasibility_check_no_poses = dto.trajectory.feasibility_check_no_poses;
+            dto.teb_config.trajectory.allow_init_with_backwards_motion;
+        bo.trajectory.exact_arc_length = dto.teb_config.trajectory.exact_arc_length;
+        bo.trajectory.force_reinit_new_goal_dist =
+            dto.teb_config.trajectory.force_reinit_new_goal_dist;
+        bo.trajectory.force_reinit_new_goal_angular =
+            dto.teb_config.trajectory.force_reinit_new_goal_angular;
+        bo.trajectory.feasibility_check_no_poses =
+            dto.teb_config.trajectory.feasibility_check_no_poses;
         bo.trajectory.feasibility_check_lookahead_distance =
-            dto.trajectory.feasibility_check_lookahead_distance;
+            dto.teb_config.trajectory.feasibility_check_lookahead_distance;
         bo.trajectory.min_resolution_collision_check_angular =
-            dto.trajectory.min_resolution_collision_check_angular;
+            dto.teb_config.trajectory.min_resolution_collision_check_angular;
 
         // Robot
-        bo.robot.max_vel_x = dto.robot.max_vel_x;
-        bo.robot.max_vel_x_backwards = dto.robot.max_vel_x_backwards;
-        bo.robot.max_vel_y = dto.robot.max_vel_y;
-        bo.robot.max_vel_trans = dto.robot.max_vel_trans;
-        bo.robot.max_vel_theta = dto.robot.max_vel_theta;
-        bo.robot.acc_lim_x = dto.robot.acc_lim_x;
-        bo.robot.acc_lim_y = dto.robot.acc_lim_y;
-        bo.robot.acc_lim_theta = dto.robot.acc_lim_theta;
-        bo.robot.min_turning_radius = dto.robot.min_turning_radius;
+        bo.robot.max_vel_x = dto.teb_config.robot.max_vel_x;
+        bo.robot.max_vel_x_backwards = dto.teb_config.robot.max_vel_x_backwards;
+        bo.robot.max_vel_y = dto.teb_config.robot.max_vel_y;
+        bo.robot.max_vel_trans = dto.teb_config.robot.max_vel_trans;
+        bo.robot.max_vel_theta = dto.teb_config.robot.max_vel_theta;
+        bo.robot.acc_lim_x = dto.teb_config.robot.acc_lim_x;
+        bo.robot.acc_lim_y = dto.teb_config.robot.acc_lim_y;
+        bo.robot.acc_lim_theta = dto.teb_config.robot.acc_lim_theta;
+        bo.robot.min_turning_radius = dto.teb_config.robot.min_turning_radius;
 
         // GoalTolerance
-        bo.goal_tolerance.xy_goal_tolerance = dto.goal_tolerance.xy_goal_tolerance;
+        bo.goal_tolerance.xy_goal_tolerance = dto.teb_config.goal_tolerance.xy_goal_tolerance;
 
         // Obstacles
-        bo.obstacles.min_obstacle_dist = dto.obstacles.min_obstacle_dist;
-        bo.obstacles.inflation_dist = dto.obstacles.inflation_dist;
+        bo.obstacles.min_obstacle_dist = dto.teb_config.obstacles.min_obstacle_dist;
+        bo.obstacles.inflation_dist = dto.teb_config.obstacles.inflation_dist;
         bo.obstacles.dynamic_obstacle_inflation_dist =
-            dto.obstacles.dynamic_obstacle_inflation_dist;
-        bo.obstacles.include_dynamic_obstacles = dto.obstacles.include_dynamic_obstacles;
+            dto.teb_config.obstacles.dynamic_obstacle_inflation_dist;
+        bo.obstacles.include_dynamic_obstacles = dto.teb_config.obstacles.include_dynamic_obstacles;
         bo.obstacles.obstacle_association_force_inclusion_factor =
-            dto.obstacles.obstacle_association_force_inclusion_factor;
+            dto.teb_config.obstacles.obstacle_association_force_inclusion_factor;
         bo.obstacles.obstacle_association_cutoff_factor =
-            dto.obstacles.obstacle_association_cutoff_factor;
+            dto.teb_config.obstacles.obstacle_association_cutoff_factor;
         bo.obstacles.obstacle_proximity_ratio_max_vel =
-            dto.obstacles.obstacle_proximity_ratio_max_vel;
-        bo.obstacles.obstacle_proximity_lower_bound = dto.obstacles.obstacle_proximity_lower_bound;
-        bo.obstacles.obstacle_proximity_upper_bound = dto.obstacles.obstacle_proximity_upper_bound;
+            dto.teb_config.obstacles.obstacle_proximity_ratio_max_vel;
+        bo.obstacles.obstacle_proximity_lower_bound =
+            dto.teb_config.obstacles.obstacle_proximity_lower_bound;
+        bo.obstacles.obstacle_proximity_upper_bound =
+            dto.teb_config.obstacles.obstacle_proximity_upper_bound;
 
         // Optimization
-        bo.optim.no_inner_iterations = dto.optim.no_inner_iterations;
-        bo.optim.no_outer_iterations = dto.optim.no_outer_iterations;
-        bo.optim.optimization_activate = dto.optim.optimization_activate;
-        bo.optim.optimization_verbose = dto.optim.optimization_verbose;
-        bo.optim.penalty_epsilon = dto.optim.penalty_epsilon;
-        bo.optim.weight_max_vel_x = dto.optim.weight_max_vel_x;
-        bo.optim.weight_max_vel_y = dto.optim.weight_max_vel_y;
-        bo.optim.weight_max_vel_theta = dto.optim.weight_max_vel_theta;
-        bo.optim.weight_acc_lim_x = dto.optim.weight_acc_lim_x;
-        bo.optim.weight_acc_lim_y = dto.optim.weight_acc_lim_y;
-        bo.optim.weight_acc_lim_theta = dto.optim.weight_acc_lim_theta;
-        bo.optim.weight_kinematics_nh = dto.optim.weight_kinematics_nh;
-        bo.optim.weight_kinematics_forward_drive = dto.optim.weight_kinematics_forward_drive;
-        bo.optim.weight_kinematics_turning_radius = dto.optim.weight_kinematics_turning_radius;
-        bo.optim.weight_optimaltime = dto.optim.weight_optimaltime;
-        bo.optim.weight_shortest_path = dto.optim.weight_shortest_path;
-        bo.optim.weight_obstacle = dto.optim.weight_obstacle;
-        bo.optim.weight_inflation = dto.optim.weight_inflation;
-        bo.optim.weight_dynamic_obstacle = dto.optim.weight_dynamic_obstacle;
-        bo.optim.weight_dynamic_obstacle_inflation = dto.optim.weight_dynamic_obstacle_inflation;
-        bo.optim.weight_velocity_obstacle_ratio = dto.optim.weight_velocity_obstacle_ratio;
-        bo.optim.weight_viapoint = dto.optim.weight_viapoint;
-        bo.optim.weight_prefer_rotdir = dto.optim.weight_prefer_rotdir;
-        bo.optim.weight_adapt_factor = dto.optim.weight_adapt_factor;
-        bo.optim.obstacle_cost_exponent = dto.optim.obstacle_cost_exponent;
+        bo.optim.no_inner_iterations = dto.teb_config.optim.no_inner_iterations;
+        bo.optim.no_outer_iterations = dto.teb_config.optim.no_outer_iterations;
+        bo.optim.optimization_activate = dto.teb_config.optim.optimization_activate;
+        bo.optim.optimization_verbose = dto.teb_config.optim.optimization_verbose;
+        bo.optim.penalty_epsilon = dto.teb_config.optim.penalty_epsilon;
+        bo.optim.weight_max_vel_x = dto.teb_config.optim.weight_max_vel_x;
+        bo.optim.weight_max_vel_y = dto.teb_config.optim.weight_max_vel_y;
+        bo.optim.weight_max_vel_theta = dto.teb_config.optim.weight_max_vel_theta;
+        bo.optim.weight_acc_lim_x = dto.teb_config.optim.weight_acc_lim_x;
+        bo.optim.weight_acc_lim_y = dto.teb_config.optim.weight_acc_lim_y;
+        bo.optim.weight_acc_lim_theta = dto.teb_config.optim.weight_acc_lim_theta;
+        bo.optim.weight_kinematics_nh = dto.teb_config.optim.weight_kinematics_nh;
+        bo.optim.weight_kinematics_forward_drive =
+            dto.teb_config.optim.weight_kinematics_forward_drive;
+        bo.optim.weight_kinematics_turning_radius =
+            dto.teb_config.optim.weight_kinematics_turning_radius;
+        bo.optim.weight_optimaltime = dto.teb_config.optim.weight_optimaltime;
+        bo.optim.weight_shortest_path = dto.teb_config.optim.weight_shortest_path;
+        bo.optim.weight_obstacle = dto.teb_config.optim.weight_obstacle;
+        bo.optim.weight_inflation = dto.teb_config.optim.weight_inflation;
+        bo.optim.weight_dynamic_obstacle = dto.teb_config.optim.weight_dynamic_obstacle;
+        bo.optim.weight_dynamic_obstacle_inflation =
+            dto.teb_config.optim.weight_dynamic_obstacle_inflation;
+        bo.optim.weight_velocity_obstacle_ratio =
+            dto.teb_config.optim.weight_velocity_obstacle_ratio;
+        bo.optim.weight_viapoint = dto.teb_config.optim.weight_viapoint;
+        bo.optim.weight_prefer_rotdir = dto.teb_config.optim.weight_prefer_rotdir;
+        bo.optim.weight_adapt_factor = dto.teb_config.optim.weight_adapt_factor;
+        bo.optim.obstacle_cost_exponent = dto.teb_config.optim.obstacle_cost_exponent;
 
         // Homotopy Class Planner
-        bo.hcp.enable_multithreading = dto.hcp.enable_multithreading;
-        bo.hcp.simple_exploration = dto.hcp.simple_exploration;
-        bo.hcp.max_number_classes = dto.hcp.max_number_classes;
-        bo.hcp.max_number_plans_in_current_class = dto.hcp.max_number_plans_in_current_class;
-        bo.hcp.selection_cost_hysteresis = dto.hcp.selection_cost_hysteresis;
-        bo.hcp.selection_obst_cost_scale = dto.hcp.selection_obst_cost_scale;
-        bo.hcp.selection_viapoint_cost_scale = dto.hcp.selection_viapoint_cost_scale;
-        bo.hcp.selection_alternative_time_cost = dto.hcp.selection_alternative_time_cost;
-        bo.hcp.selection_dropping_probability = dto.hcp.selection_dropping_probability;
-        bo.hcp.switching_blocking_period = dto.hcp.switching_blocking_period;
-
-        bo.hcp.obstacle_heading_threshold = dto.hcp.obstacle_heading_threshold;
-        bo.hcp.roadmap_graph_no_samples = dto.hcp.roadmap_graph_no_samples;
-        bo.hcp.roadmap_graph_area_width = dto.hcp.roadmap_graph_area_width;
-        bo.hcp.roadmap_graph_area_length_scale = dto.hcp.roadmap_graph_area_length_scale;
-        bo.hcp.h_signature_prescaler = dto.hcp.h_signature_prescaler;
-        bo.hcp.h_signature_threshold = dto.hcp.h_signature_threshold;
-
-        bo.hcp.viapoints_all_candidates = dto.hcp.viapoints_all_candidates;
-
-        bo.hcp.delete_detours_backwards = dto.hcp.delete_detours_backwards;
-        bo.hcp.detours_orientation_tolerance = dto.hcp.detours_orientation_tolerance;
-        bo.hcp.length_start_orientation_vector = dto.hcp.length_start_orientation_vector;
+        bo.hcp.enable_multithreading = dto.teb_config.hcp.enable_multithreading;
+        bo.hcp.simple_exploration = dto.teb_config.hcp.simple_exploration;
+        bo.hcp.max_number_classes = dto.teb_config.hcp.max_number_classes;
+        bo.hcp.max_number_plans_in_current_class =
+            dto.teb_config.hcp.max_number_plans_in_current_class;
+        bo.hcp.selection_cost_hysteresis = dto.teb_config.hcp.selection_cost_hysteresis;
+        bo.hcp.selection_obst_cost_scale = dto.teb_config.hcp.selection_obst_cost_scale;
+        bo.hcp.selection_viapoint_cost_scale = dto.teb_config.hcp.selection_viapoint_cost_scale;
+        bo.hcp.selection_alternative_time_cost = dto.teb_config.hcp.selection_alternative_time_cost;
+        bo.hcp.selection_dropping_probability = dto.teb_config.hcp.selection_dropping_probability;
+        bo.hcp.switching_blocking_period = dto.teb_config.hcp.switching_blocking_period;
+
+        bo.hcp.obstacle_heading_threshold = dto.teb_config.hcp.obstacle_heading_threshold;
+        bo.hcp.roadmap_graph_no_samples = dto.teb_config.hcp.roadmap_graph_no_samples;
+        bo.hcp.roadmap_graph_area_width = dto.teb_config.hcp.roadmap_graph_area_width;
+        bo.hcp.roadmap_graph_area_length_scale = dto.teb_config.hcp.roadmap_graph_area_length_scale;
+        bo.hcp.h_signature_prescaler = dto.teb_config.hcp.h_signature_prescaler;
+        bo.hcp.h_signature_threshold = dto.teb_config.hcp.h_signature_threshold;
+
+        bo.hcp.viapoints_all_candidates = dto.teb_config.hcp.viapoints_all_candidates;
+
+        bo.hcp.delete_detours_backwards = dto.teb_config.hcp.delete_detours_backwards;
+        bo.hcp.detours_orientation_tolerance = dto.teb_config.hcp.detours_orientation_tolerance;
+        bo.hcp.length_start_orientation_vector = dto.teb_config.hcp.length_start_orientation_vector;
         bo.hcp.max_ratio_detours_duration_best_duration =
-            dto.hcp.max_ratio_detours_duration_best_duration;
+            dto.teb_config.hcp.max_ratio_detours_duration_best_duration;
 
         bo.checkParameters();
     }
-- 
GitLab


From 73bdc265aa93c8ddcee893f1c63f8db50faeb74e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 12 Aug 2022 01:17:11 +0200
Subject: [PATCH 072/324] adjust config

---
 .../local_planner_config/TimedElasticBands/default.json    | 7 ++++---
 1 file changed, 4 insertions(+), 3 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index e2c40a1b..4b298708 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -1,6 +1,7 @@
 {
-  "robot_footprint_radius": 0.2,
-  "planning_distance": 2,
+  "robot_footprint_radius": 0.5,
+  "planning_distance": 3,
+
   "teb_config": {
     "pse": {
       "pse_costum_obstacle_penalties": true,
@@ -45,7 +46,7 @@
     },
 
     "obstacles": {
-      "min_obstacle_dist": 0.5,
+      "min_obstacle_dist": 0.3,
       "inflation_dist": 0.0,
       "dynamic_obstacle_inflation_dist": 0.6,
       "include_dynamic_obstacles": true,
-- 
GitLab


From 753dd2f4e3f22625f870b10f0070fb4251f1c4d6 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 12 Aug 2022 01:17:44 +0200
Subject: [PATCH 073/324] Remove todo, change velocity visualization upper
 limit

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp   | 2 --
 .../navigation/server/introspection/ArvizIntrospector.cpp       | 2 +-
 2 files changed, 1 insertion(+), 3 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 446b5743..dc02d4c5 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -116,8 +116,6 @@ namespace armarx::navigation::local_planning
 
         try
         {
-            // TODO (SALt): free goal velocity is not respected inside homotopy planner
-            ARMARX_VERBOSE << "Plan to dest: " << planToDest << ", freeGoal Vel: " << !planToDest;
             hcp_->plan(start, end, &velocity_start, !planToDest);
         }
         catch (std::exception& e)
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 694ff174..cb1f306e 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -172,7 +172,7 @@ namespace armarx::navigation::server
 
         simox::ColorMap cm = simox::color::cmaps::inferno();
         cm.set_vmin(0);
-        cm.set_vmax(1);
+        cm.set_vmax(0.6);
 
         for (size_t i = 0; i < trajectory.points().size() - 1; i++)
         {
-- 
GitLab


From d56f1cd7d9b4c0b8964049a6b3874e8e1c803064 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 12 Aug 2022 01:48:00 +0200
Subject: [PATCH 074/324] Adjust default config

---
 .../local_planner_config/TimedElasticBands/default.json       | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 4b298708..0dcf777b 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -6,7 +6,7 @@
     "pse": {
       "pse_costum_obstacle_penalties": true,
       "pse_costum_obstacle_penalties_dynamic": true,
-      "weight_global_path": 0.1,
+      "weight_global_path": 0.3,
       "lrk_use_alternative_approach": false,
       "lrk_enable_collision_check": true,
       "hybrid_homotopy_calculation": true,
@@ -73,7 +73,7 @@
       "weight_kinematics_forward_drive": 1,
       "weight_kinematics_turning_radius": 1,
       "weight_optimaltime": 1,
-      "weight_shortest_path": 0,
+      "weight_shortest_path": 1,
       "weight_obstacle": 50,
       "weight_inflation": 0.1,
       "weight_dynamic_obstacle": 50,
-- 
GitLab


From 81972ba7a4bf41755af799e97e1a518c90bac3b6 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 12 Aug 2022 15:43:29 +0200
Subject: [PATCH 075/324] Add comment

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 4 ++--
 source/armarx/navigation/local_planning/ros_conversions.cpp   | 2 +-
 2 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index dc02d4c5..de0514f6 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -98,8 +98,8 @@ namespace armarx::navigation::local_planning
         const core::Pose currentPose{scene.robot->getGlobalPose()};
 
         // prune global trajectory
-        const auto& [prunedGoal, planToDest] =
-            goal.getSubTrajectory(currentPose.translation(), params.cfg.planning_distance * 1000);
+        const auto& [prunedGoal, planToDest] = goal.getSubTrajectory(
+            currentPose.translation(), params.cfg.planning_distance * 1000); // [m] to [mm]
 
         const teb_local_planner::TimedElasticBand globalPath = conv::toRos(prunedGoal);
         teb_globalPath = globalPath.poses();
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 3ad81d9c..c23adf1a 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -18,7 +18,7 @@ namespace armarx::navigation::conv
     Eigen::Vector2d
     toRos(const Eigen::Vector3f& vec)
     {
-        return conv::to2D(vec).cast<double>() / 1000;
+        return conv::to2D(vec).cast<double>() / 1000; // [mm] to [m]
     }
 
 
-- 
GitLab


From 0769a954b13ec5b5cb31a106f9d93fcb9350deff Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 12 Aug 2022 15:47:42 +0200
Subject: [PATCH 076/324] Fix vertex order of PolygonObstacle

---
 source/armarx/navigation/local_planning/TebObstacleManager.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 2db7ec86..8c323174 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -28,8 +28,8 @@ namespace armarx::navigation::local_planning
         const Eigen::Vector2d max = conv::toRos(bbox.getMin());
 
         obst->pushBackVertex(min);
-        obst->pushBackVertex(max);
         obst->pushBackVertex(min.x(), max.y());
+        obst->pushBackVertex(max);
         obst->pushBackVertex(max.x(), min.y());
 
         obst->finalizePolygon();
-- 
GitLab


From d9ac7dd679063784a83409494616f420e5c9a3c9 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 13 Aug 2022 22:05:35 +0200
Subject: [PATCH 077/324] New ros conversion (vector: ros -> armar)

---
 source/armarx/navigation/local_planning/ros_conversions.cpp | 6 ++++++
 source/armarx/navigation/local_planning/ros_conversions.h   | 1 +
 2 files changed, 7 insertions(+)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 3ad81d9c..53b2a886 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -21,6 +21,12 @@ namespace armarx::navigation::conv
         return conv::to2D(vec).cast<double>() / 1000;
     }
 
+    Eigen::Vector3f
+    fromRos(const Eigen::Vector2d& vec)
+    {
+        return conv::to3D(vec.cast<float>()) * 1000; // [m] to [mm]
+    }
+
 
     teb_local_planner::PoseSE2
     toRos(const core::Pose& pose)
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 60b1fb4f..1f4dcaa4 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -31,6 +31,7 @@ namespace armarx::navigation::conv
 {
 
     Eigen::Vector2d toRos(const Eigen::Vector3f& vec);
+    Eigen::Vector3f fromRos(const Eigen::Vector2d& vec);
 
     teb_local_planner::PoseSE2 toRos(const core::Pose& pose);
     teb_local_planner::PoseSE2 toRos(const core::Pose2D& pose);
-- 
GitLab


From 0020842f88582ae4df75d697d6b2939d2829a49a Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 13 Aug 2022 22:06:09 +0200
Subject: [PATCH 078/324] Teb obstacle visualization draft

---
 .../local_planning/TebObstacleManager.cpp     | 15 ++++++++++-
 .../local_planning/TebObstacleManager.h       |  4 ++-
 .../local_planning/TimedElasticBands.cpp      | 25 +++++++++++++++++--
 .../local_planning/TimedElasticBands.h        |  5 ++++
 .../local_planning/ros_conversions.cpp        |  1 -
 5 files changed, 45 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 8c323174..72c3714f 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -20,7 +20,7 @@ namespace armarx::navigation::local_planning
     }
 
     void
-    TebObstacleManager::addBoxObstacle(const VirtualRobot::BoundingBox& bbox)
+    TebObstacleManager::addBoxObstacle(const VirtualRobot::BoundingBox& bbox, viz::Layer* visLayer)
     {
         auto obst = boost::make_shared<teb_local_planner::PolygonObstacle>();
 
@@ -34,6 +34,19 @@ namespace armarx::navigation::local_planning
 
         obst->finalizePolygon();
         container.push_back(obst);
+
+        if (visLayer)
+        {
+            const Eigen::Vector3f min = conv::fromRos(min);
+            const Eigen::Vector3f max = conv::fromRos(max);
+
+            visLayer->add(viz::Polygon("pol")
+                              .addPoint(min)
+                              .addPoint(Eigen::Vector3f(min.x(), max.y()))
+                              .addPoint(max)
+                              .addPoint(Eigen::Vector3f(max.x(), min.y()))
+                              .color(simox::Color::gray()));
+        }
     }
 
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
index 52783b65..185778f7 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.h
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -22,6 +22,8 @@
 
 #include <VirtualRobot/CollisionDetection/CollisionModel.h>
 
+#include <RobotAPI/components/ArViz/Client/Layer.h>
+
 #include <teb_local_planner/obstacles.h>
 
 namespace armarx::navigation::local_planning
@@ -39,7 +41,7 @@ namespace armarx::navigation::local_planning
 
         size_t size();
 
-        void addBoxObstacle(const VirtualRobot::BoundingBox& bbox);
+        void addBoxObstacle(const VirtualRobot::BoundingBox& bbox, viz::Layer* visLayer = nullptr);
 
     private:
         teb_local_planner::ObstContainer& container;
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 3ff39fd6..06befc6a 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -138,19 +138,40 @@ namespace armarx::navigation::local_planning
         return {{.trajectory = best}};
     }
 
+    void
+    TimedElasticBands::setVisualization(viz::ScopedClient* vis)
+    {
+        arviz = vis;
+    }
+
 
     void
     TimedElasticBands::fillObstacles()
     {
         obstManager.clear();
 
-        if (scene.staticScene.has_value())
+        viz::Layer* visPtr = nullptr;
+        viz::Layer visLayer;
+        if (arviz)
+        {
+            visLayer = arviz->layer("local_planner_obstacles");
+            visPtr = &visLayer;
+        }
+
+
+        if (scene.staticScene)
         {
             for (auto& obst : scene.staticScene.value().objects->getCollisionModels())
             {
-                obstManager.addBoxObstacle(obst->getGlobalBoundingBox());
+                obstManager.addBoxObstacle(obst->getGlobalBoundingBox(), visPtr);
             }
         }
+
+        if (arviz)
+        {
+            arviz->commit(visLayer);
+        }
+
         ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";
     }
 
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index f8c005ac..c7ee122b 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -22,6 +22,7 @@
 
 #pragma once
 
+#include <RobotAPI/components/ArViz/Client/ScopedClient.h>
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
 #include "armarx/navigation/core/basic_types.h"
@@ -58,6 +59,8 @@ namespace armarx::navigation::local_planning
 
         std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
 
+        void setVisualization(viz::ScopedClient* vis);
+
     private:
         void initConfig();
         void fillObstacles();
@@ -73,5 +76,7 @@ namespace armarx::navigation::local_planning
         TebObstacleManager obstManager;
         teb_local_planner::PoseSequence teb_globalPath;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
+
+        viz::ScopedClient* arviz;
     };
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 53b2a886..9955ceef 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -148,5 +148,4 @@ namespace armarx::navigation::conv
         return {trajectory};
     }
 
-
 } // namespace armarx::navigation::conv
-- 
GitLab


From fc47ac5cfba574a8662823bcd7fe1d296396ff92 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 17:22:33 +0200
Subject: [PATCH 079/324] Implement basic version of human tracker.

Uses average position of KeypointMap.
Missing angle (currently set to 0).
Missing velocity (currently set to 0).
---
 .../dynamic_scene_provider/HumanTracker.cpp   | 77 +++++++++----------
 .../dynamic_scene_provider/HumanTracker.h     |  3 +-
 2 files changed, 37 insertions(+), 43 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 41649ff4..1cd4c42f 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -1,61 +1,54 @@
+
 #include "HumanTracker.h"
 
+#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+
 namespace armarx::navigation::components::dynamic_scene_provider
 {
 
-HumanTracker::HumanTracker()
-{
+    void
+    HumanTracker::update(const Measurements& measurements)
+    {
+        trackedHumans.clear();
 
-}
+        for (const armem::human::HumanPose& humanPose : measurements.humanPoses)
+        {
 
+            const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
+            ARMARX_CHECK_NOT_EMPTY(keypoints);
 
-void HumanTracker::update(const Measurements &measurements)
-{
-    trackedHumans.clear();
+            Eigen::Vector3f centerPos = Eigen::Vector3f::Zero();
+            for (const auto& [_, v] : keypoints)
+            {
+                centerPos += v.positionGlobal;
+            }
+            centerPos /= static_cast<float>(keypoints.size());
 
-    foreach (humanPose, measurements.humanPoses) {
+            core::Pose2D pose = core::Pose2D::Identity();
+            pose.translation() = Eigen::Vector2f{centerPos.x(), centerPos.y()};
+            pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
 
-        const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
-        ARMARX_CHECK_NOT_EMPTY(keypoints);
+            const HumanTracker::TrackedHuman newHuman = {
+                .global_T_human = pose,
+                .linearVelocity = Eigen::Vector2f::Zero() //TODO more sophisticated guess
+            };
 
-        const Eigen::Vector3f centerPos = Eigen::Vector3f::Zero();
-        for (const auto& [_, v] : keypoints)
-        {
-            centerPos += v.positionGlobal;
-        }
-        centerPos /= static_cast<float>(keypoints.size());
-
-        const HumanTracker::TrackedHuman newHuman = HumanTracker::TrackedHuman{
-            .global_T_human = core::Pose2D{
-                .x = centerPos.x;
-                .y = centerPos.y;
-            };;
-            .linearVelocity = 0; //TODO more sophisticated guess
+            trackedHumans.push_back(newHuman);
         }
-        trackedHumans.push_back(newHuman);
     }
 
-
-    this->trackedHumans = HumanTracker::TrackedHuman{
-            .global_T_human = core::Pose2D{
-                .x = 0;
-                .y = 0;
-            };
-            .linearVelocity = 0;
+    const std::vector<HumanTracker::TrackedHuman>&
+    HumanTracker::getTrackedHumans() const
+    {
+        return trackedHumans;
     }
-}
-
-
-std::vector<HumanTracker::TrackedHuman> HumanTracker::getTrackedHumans() const
-{
-
-}
 
 
-void HumanTracker::reset()
-{
+    void
+    HumanTracker::reset()
+    {
+        trackedHumans.clear();
+    }
 
-}
 
-  
-}
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 770901f1..556d516b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -2,6 +2,7 @@
 
 
 #include "VisionX/libraries/armem_human/types.h"
+
 #include "armarx/navigation/core/basic_types.h"
 
 namespace armarx::navigation::components::dynamic_scene_provider
@@ -27,7 +28,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             Eigen::Vector2f linearVelocity;
         };
 
-        std::vector<TrackedHuman> getTrackedHumans() const;
+        const std::vector<TrackedHuman>& getTrackedHumans() const;
 
         void reset();
 
-- 
GitLab


From a818cb35e89b380fa44f0ede6db4c88a01175c48 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 18:04:16 +0200
Subject: [PATCH 080/324] Setup of new library human

---
 source/armarx/navigation/CMakeLists.txt       |  1 +
 source/armarx/navigation/human/CMakeLists.txt | 13 ++++++
 source/armarx/navigation/human/types.h        | 42 +++++++++++++++++++
 3 files changed, 56 insertions(+)
 create mode 100644 source/armarx/navigation/human/CMakeLists.txt
 create mode 100644 source/armarx/navigation/human/types.h

diff --git a/source/armarx/navigation/CMakeLists.txt b/source/armarx/navigation/CMakeLists.txt
index dfd3bf35..ca819773 100644
--- a/source/armarx/navigation/CMakeLists.txt
+++ b/source/armarx/navigation/CMakeLists.txt
@@ -15,6 +15,7 @@ add_subdirectory(location)
 add_subdirectory(memory)
 add_subdirectory(server)
 add_subdirectory(platform_controller)
+add_subdirectory(human)
 
 # Components.
 add_subdirectory(components)
diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
new file mode 100644
index 00000000..d8258b10
--- /dev/null
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -0,0 +1,13 @@
+armarx_add_aron_library(human_aron
+    ARON_FILES
+)
+
+armarx_add_library(human
+    DEPENDENCIES_PUBLIC
+      armarx_navigation::core
+    DEPENDENCIES_PRIVATE
+    SOURCES
+        #types.cpp
+    HEADERS
+        types.h
+)
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
new file mode 100644
index 00000000..8acd8c84
--- /dev/null
+++ b/source/armarx/navigation/human/types.h
@@ -0,0 +1,42 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <SimoxUtility/shapes.h>
+
+#include <armarx/navigation/core/basic_types.h>
+
+namespace armarx::navigation::human
+{
+    struct Human
+    {
+        core::Pose2D global_T_human;
+        Eigen::Vector2f linearVelocity;
+    };
+
+    struct HumanGroup
+    {
+        std::vector<Eigen::Vector2f> vertices;
+        std::vector<Human> humans;
+    };
+
+} // namespace armarx::navigation::human
-- 
GitLab


From 6d1259a9e9a4808d49a5036a8a1f54577103a10e Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 18:45:48 +0200
Subject: [PATCH 081/324] Change usage of TrackedHuman to Human

---
 .../dynamic_scene_provider/CMakeLists.txt           |  1 +
 .../dynamic_scene_provider/HumanTracker.cpp         |  4 ++--
 .../dynamic_scene_provider/HumanTracker.h           | 13 +++----------
 3 files changed, 6 insertions(+), 12 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 42507ca0..c53238db 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -31,6 +31,7 @@ armarx_add_component(dynamic_scene_provider
         armarx_navigation::util
         armarx_navigation::memory
         armarx_navigation::dynamic_scene
+        armarx_navigation::human
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 1cd4c42f..030c8b63 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -28,7 +28,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             pose.translation() = Eigen::Vector2f{centerPos.x(), centerPos.y()};
             pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
 
-            const HumanTracker::TrackedHuman newHuman = {
+            const human::Human newHuman = {
                 .global_T_human = pose,
                 .linearVelocity = Eigen::Vector2f::Zero() //TODO more sophisticated guess
             };
@@ -37,7 +37,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         }
     }
 
-    const std::vector<HumanTracker::TrackedHuman>&
+    const std::vector<human::Human>&
     HumanTracker::getTrackedHumans() const
     {
         return trackedHumans;
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 556d516b..da448f63 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -4,6 +4,7 @@
 #include "VisionX/libraries/armem_human/types.h"
 
 #include "armarx/navigation/core/basic_types.h"
+#include "armarx/navigation/human/types.h"
 
 namespace armarx::navigation::components::dynamic_scene_provider
 {
@@ -20,19 +21,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         void update(const Measurements& measurements);
 
-        struct TrackedHuman
-        {
-            // TODO ...
-            core::Pose2D global_T_human;
-
-            Eigen::Vector2f linearVelocity;
-        };
-
-        const std::vector<TrackedHuman>& getTrackedHumans() const;
+        const std::vector<human::Human>& getTrackedHumans() const;
 
         void reset();
 
     private:
-        std::vector<TrackedHuman> trackedHumans;
+        std::vector<human::Human> trackedHumans;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 2801d2d74daf89f9b251153f91a1b4e322a4dd37 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 18:53:32 +0200
Subject: [PATCH 082/324] Add detection time to Human/HumanGroup

---
 source/armarx/navigation/human/CMakeLists.txt | 3 ++-
 source/armarx/navigation/human/types.h        | 4 +++-
 2 files changed, 5 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index d8258b10..c173b591 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -4,7 +4,8 @@ armarx_add_aron_library(human_aron
 
 armarx_add_library(human
     DEPENDENCIES_PUBLIC
-      armarx_navigation::core
+        ArmarXCore
+        armarx_navigation::core
     DEPENDENCIES_PRIVATE
     SOURCES
         #types.cpp
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 8acd8c84..3dc3f663 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -21,7 +21,7 @@
 
 #pragma once
 
-#include <SimoxUtility/shapes.h>
+#include <ArmarXCore/core/time.h>
 
 #include <armarx/navigation/core/basic_types.h>
 
@@ -31,12 +31,14 @@ namespace armarx::navigation::human
     {
         core::Pose2D global_T_human;
         Eigen::Vector2f linearVelocity;
+        DateTime detectionTime;
     };
 
     struct HumanGroup
     {
         std::vector<Eigen::Vector2f> vertices;
         std::vector<Human> humans;
+        DateTime detectionTime;
     };
 
 } // namespace armarx::navigation::human
-- 
GitLab


From f5badc149a3e53f15a366160ccfb66dcfd078213 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 18:54:25 +0200
Subject: [PATCH 083/324] Add detection time to Measurement

---
 .../components/dynamic_scene_provider/HumanTracker.h           | 3 +++
 1 file changed, 3 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index da448f63..612db064 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -1,6 +1,8 @@
 #pragma once
 
 
+#include <ArmarXCore/core/time.h>
+
 #include "VisionX/libraries/armem_human/types.h"
 
 #include "armarx/navigation/core/basic_types.h"
@@ -16,6 +18,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         struct Measurements
         {
+            DateTime detectionTime;
             std::vector<armem::human::HumanPose> humanPoses;
         };
 
-- 
GitLab


From 4f4bc5da793efdb980c0ac68a163b3f23fa9cb11 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 19:21:50 +0200
Subject: [PATCH 084/324] Add proxemic zone struct, rename parameter

---
 source/armarx/navigation/human/types.h | 7 ++++++-
 1 file changed, 6 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 3dc3f663..ae490622 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -29,7 +29,7 @@ namespace armarx::navigation::human
 {
     struct Human
     {
-        core::Pose2D global_T_human;
+        core::Pose2D pose;
         Eigen::Vector2f linearVelocity;
         DateTime detectionTime;
     };
@@ -41,4 +41,9 @@ namespace armarx::navigation::human
         DateTime detectionTime;
     };
 
+    struct ProxemicZone
+    {
+        core::Pose2D pose;
+    };
+
 } // namespace armarx::navigation::human
-- 
GitLab


From 5713e4727272100328fdc5f0ff200c481adbbb94 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 19:26:18 +0200
Subject: [PATCH 085/324] Define HumanTracker::getAssociatedHumans()

---
 .../dynamic_scene_provider/HumanTracker.cpp           | 11 ++++++++---
 .../components/dynamic_scene_provider/HumanTracker.h  |  3 +++
 2 files changed, 11 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 030c8b63..ea338135 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -30,8 +30,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
             const human::Human newHuman = {
                 .global_T_human = pose,
-                .linearVelocity = Eigen::Vector2f::Zero() //TODO more sophisticated guess
-            };
+                .linearVelocity = Eigen::Vector2f::Zero(), //TODO more sophisticated guess
+                .detectionTime = measurements.detectionTime};
 
             trackedHumans.push_back(newHuman);
         }
@@ -44,11 +44,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
     }
 
 
+    std::map<armem::human::HumanPose&, human::Human&>
+    HumanTracker::getAssociatedHumans(const Measurements& measurements) const
+    {
+    }
+
+
     void
     HumanTracker::reset()
     {
         trackedHumans.clear();
     }
 
-
 } // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 612db064..209fd345 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -30,5 +30,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     private:
         std::vector<human::Human> trackedHumans;
+
+        std::map<armem::human::HumanPose&, human::Human&>
+        getAssociatedHumans(const Measurements& measurements) const;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 38637b2df2dc2d5ec4bf8481860bd2f0b8090954 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 19:30:00 +0200
Subject: [PATCH 086/324] Rename global_T_human to pose

---
 .../components/dynamic_scene_provider/HumanTracker.cpp          | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index ea338135..fd15dc3b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -29,7 +29,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
 
             const human::Human newHuman = {
-                .global_T_human = pose,
+                .pose = pose,
                 .linearVelocity = Eigen::Vector2f::Zero(), //TODO more sophisticated guess
                 .detectionTime = measurements.detectionTime};
 
-- 
GitLab


From 14fe938221a9a23b28d8c065984dbff4a1ee4f19 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 19:51:42 +0200
Subject: [PATCH 087/324] Implement HumanTracker::mostRecentTrackedHumans()

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 26 +++++++++++++++++++
 1 file changed, 26 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index fd15dc3b..dcd76e7d 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -49,6 +49,32 @@ namespace armarx::navigation::components::dynamic_scene_provider
     {
     }
 
+    std::vector<human::Human>
+    HumanTracker::mostRecentTrackedHumans() const
+    {
+        if (trackedHumans.empty())
+        {
+            return {};
+        }
+
+        std::sort(trackedHumans.begin(),
+                  trackedHumans.end(),
+                  [](human::Human a, human::Human b) -> bool
+                  { return a.detectionTime.operator<=(b.detectionTime); });
+        DateTime mostRecentTime = trackedHumans.back().detectionTime;
+
+        std::vector<human::Human> mostRecentHumans;
+
+        for (human::Human trackedHuman : trackedHumans)
+        {
+            if (trackedHuman.detectionTime == mostRecentTime)
+            {
+                mostRecentHumans.push_back(trackedHuman);
+            }
+        }
+
+        return mostRecentHumans;
+    }
 
     void
     HumanTracker::reset()
-- 
GitLab


From da681818071ad9467bb3055c44f059e6e7e92806 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 20:13:35 +0200
Subject: [PATCH 088/324] Implement HumanTracker::getMeasurementPositions()

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 40 ++++++++++++++-----
 .../dynamic_scene_provider/HumanTracker.h     |  5 +++
 2 files changed, 34 insertions(+), 11 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index dcd76e7d..6bae4e5d 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -11,18 +11,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
     {
         trackedHumans.clear();
 
+        auto positions = getMeasurementPositions(measurements);
+
         for (const armem::human::HumanPose& humanPose : measurements.humanPoses)
         {
-
-            const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
-            ARMARX_CHECK_NOT_EMPTY(keypoints);
-
-            Eigen::Vector3f centerPos = Eigen::Vector3f::Zero();
-            for (const auto& [_, v] : keypoints)
-            {
-                centerPos += v.positionGlobal;
-            }
-            centerPos /= static_cast<float>(keypoints.size());
+            auto centerPos = positions.find(humanPose);
 
             core::Pose2D pose = core::Pose2D::Identity();
             pose.translation() = Eigen::Vector2f{centerPos.x(), centerPos.y()};
@@ -44,13 +37,38 @@ namespace armarx::navigation::components::dynamic_scene_provider
     }
 
 
+    std::map<const armem::human::HumanPose&, armarx::navigation::core::Position>
+    HumanTracker::getMeasurementPositions(const Measurements& measurements) const
+    {
+        std::map<armem::human::HumanPose&, armarx::navigation::core::Position> map;
+
+        for (const armem::human::HumanPose& humanPose : measurements.humanPoses)
+        {
+
+            const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
+            ARMARX_CHECK_NOT_EMPTY(keypoints);
+
+            auto centerPos = armarx::navigation::core::Position::Zero();
+            for (const auto& [_, v] : keypoints)
+            {
+                centerPos += v.positionGlobal;
+            }
+            centerPos /= static_cast<float>(keypoints.size());
+
+            map.insert(
+                std::pair<const armem::human::HumanPose&, armarx::navigation::core::Position>(
+                    humanPose, centerPos));
+        }
+    }
+
+
     std::map<armem::human::HumanPose&, human::Human&>
     HumanTracker::getAssociatedHumans(const Measurements& measurements) const
     {
     }
 
     std::vector<human::Human>
-    HumanTracker::mostRecentTrackedHumans() const
+    HumanTracker::getMostRecentTrackedHumans() const
     {
         if (trackedHumans.empty())
         {
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 209fd345..76c6ce50 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -31,7 +31,12 @@ namespace armarx::navigation::components::dynamic_scene_provider
     private:
         std::vector<human::Human> trackedHumans;
 
+        std::map<const armem::human::HumanPose&, armarx::navigation::core::Position>
+        getMeasurementPositions(const Measurements& measurements) const;
+
         std::map<armem::human::HumanPose&, human::Human&>
         getAssociatedHumans(const Measurements& measurements) const;
+
+        std::vector<human::Human> getMostRecentTrackedHumans() const;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 65284dbe483f3d49765b38f89938606d59906ba0 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 20:31:55 +0200
Subject: [PATCH 089/324] Add estimateAt to Human

---
 source/armarx/navigation/human/types.cpp | 14 ++++++++++++++
 source/armarx/navigation/human/types.h   |  2 ++
 2 files changed, 16 insertions(+)
 create mode 100644 source/armarx/navigation/human/types.cpp

diff --git a/source/armarx/navigation/human/types.cpp b/source/armarx/navigation/human/types.cpp
new file mode 100644
index 00000000..5b6d3d88
--- /dev/null
+++ b/source/armarx/navigation/human/types.cpp
@@ -0,0 +1,14 @@
+#include "types.h"
+
+namespace armarx::navigation::human
+{
+    core::Pose2D
+    Human::estimateAt(DateTime& time) const
+    {
+        double dt = (time - detectionTime).toSecondsDouble();
+        core::Pose2D estimation{pose};
+        estimation.translation() += linearVelocity * dt;
+        return estimation;
+    }
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index ae490622..867849a1 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -32,6 +32,8 @@ namespace armarx::navigation::human
         core::Pose2D pose;
         Eigen::Vector2f linearVelocity;
         DateTime detectionTime;
+
+        core::Pose2D estimateAt(DateTime& time) const;
     };
 
     struct HumanGroup
-- 
GitLab


From 1dbc8494f02c1ccf30e75d25e5a780e96211cbe0 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 20:36:21 +0200
Subject: [PATCH 090/324] Add aron conversion

---
 source/armarx/navigation/human/CMakeLists.txt |  8 ++-
 source/armarx/navigation/human/aron/Human.xml | 34 +++++++++
 .../navigation/human/aron_conversions.cpp     | 69 +++++++++++++++++++
 .../navigation/human/aron_conversions.h       | 46 +++++++++++++
 source/armarx/navigation/human/shapes.h       | 48 +++++++++++++
 source/armarx/navigation/human/types.h        |  4 +-
 6 files changed, 207 insertions(+), 2 deletions(-)
 create mode 100644 source/armarx/navigation/human/aron/Human.xml
 create mode 100644 source/armarx/navigation/human/aron_conversions.cpp
 create mode 100644 source/armarx/navigation/human/aron_conversions.h
 create mode 100644 source/armarx/navigation/human/shapes.h

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index c173b591..670c1869 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -1,14 +1,20 @@
 armarx_add_aron_library(human_aron
     ARON_FILES
+        aron/Human.xml
 )
 
 armarx_add_library(human
     DEPENDENCIES_PUBLIC
         ArmarXCore
         armarx_navigation::core
+        armarx_navigation::conversions
     DEPENDENCIES_PRIVATE
+        range-v3::range-v3
     SOURCES
-        #types.cpp
+        types.cpp
+        aron_conversions.cpp
     HEADERS
         types.h
+        aron_conversions.h
+        shapes.h
 )
diff --git a/source/armarx/navigation/human/aron/Human.xml b/source/armarx/navigation/human/aron/Human.xml
new file mode 100644
index 00000000..57d104d8
--- /dev/null
+++ b/source/armarx/navigation/human/aron/Human.xml
@@ -0,0 +1,34 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <GenerateTypes>
+
+        <Object name='armarx::navigation::human::arondto::Human'>
+            <ObjectChild key='pose'>
+                <Pose />
+            </ObjectChild>
+            <ObjectChild key='linearVelocity'>
+                <Position />
+            </ObjectChild>
+            <ObjectChild key='detectionTime'>
+                <Time />
+            </ObjectChild>
+        </Object>
+
+        <Object name='armarx::navigation::human::arondto::HumanGroup'>
+            <ObjectChild key='shape'>
+                <List>
+                    <Position />
+                </List>
+            </ObjectChild>
+            <ObjectChild key='humans'>
+                <List>
+                    <armarx::navigation::human::arondto::Human />
+                </List>
+            </ObjectChild>
+            <ObjectChild key='detectionTime'>
+                <Time />
+            </ObjectChild>
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/human/aron_conversions.cpp b/source/armarx/navigation/human/aron_conversions.cpp
new file mode 100644
index 00000000..e09a3ca3
--- /dev/null
+++ b/source/armarx/navigation/human/aron_conversions.cpp
@@ -0,0 +1,69 @@
+#include "aron_conversions.h"
+
+#include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
+#include <armarx/navigation/human/types.h>
+#include <range/v3/range/conversion.hpp>
+#include <range/v3/view/transform.hpp>
+
+namespace armarx::navigation::human
+{
+    void
+    toAron(arondto::Human& dto, const Human& bo)
+    {
+        dto.pose = conv::to3D(bo.pose).matrix();
+        dto.linearVelocity = conv::to3D(bo.linearVelocity);
+        dto.detectionTime = bo.detectionTime;
+    }
+
+    void
+    fromAron(const arondto::Human& dto, Human& bo)
+    {
+        bo.pose = conv::to2D(core::Pose(dto.pose));
+        bo.linearVelocity = conv::to2D(dto.linearVelocity);
+        bo.detectionTime = dto.detectionTime;
+    }
+
+
+    void
+    toAron(arondto::HumanGroup& dto, const HumanGroup& bo)
+    {
+        dto.shape = bo.shape.vertices |
+                    ranges::views::transform([](const Eigen::Vector2f& boVer) -> Eigen::Vector3f
+                                             { return conv::to3D(boVer); }) |
+                    ranges::to_vector;
+
+        dto.humans = bo.humans |
+                     ranges::views::transform(
+                         [](const Human& boHuman) -> arondto::Human
+                         {
+                             arondto::Human dtoHuman;
+                             toAron(dtoHuman, boHuman);
+                             return dtoHuman;
+                         }) |
+                     ranges::to_vector;
+        dto.detectionTime = bo.detectionTime;
+    }
+
+    void
+    fromAron(const arondto::HumanGroup& dto, HumanGroup& bo)
+    {
+        bo.shape.vertices =
+            dto.shape |
+            ranges::views::transform([](const Eigen::Vector3f& dtoVer) -> Eigen::Vector2f
+                                     { return conv::to2D(dtoVer); }) |
+            ranges::to_vector;
+
+        bo.humans = dto.humans |
+                    ranges::views::transform(
+                        [](const arondto::Human& dtoHuman) -> Human
+                        {
+                            Human boHuman;
+                            fromAron(dtoHuman, boHuman);
+                            return boHuman;
+                        }) |
+                    ranges::to_vector;
+        bo.detectionTime = dto.detectionTime;
+    }
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/aron_conversions.h b/source/armarx/navigation/human/aron_conversions.h
new file mode 100644
index 00000000..71159748
--- /dev/null
+++ b/source/armarx/navigation/human/aron_conversions.h
@@ -0,0 +1,46 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+namespace armarx::navigation::human
+{
+    struct Human;
+    struct HumanGroup;
+
+    namespace arondto
+    {
+        struct Human;
+        struct HumanGroup;
+
+    } // namespace arondto
+
+} // namespace armarx::navigation::human
+
+namespace armarx::navigation::human
+{
+    void toAron(arondto::Human& dto, const Human& bo);
+    void fromAron(const arondto::Human& dto, Human& bo);
+
+    void toAron(arondto::HumanGroup& dto, const HumanGroup& bo);
+    void fromAron(const arondto::HumanGroup& dto, HumanGroup& bo);
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/shapes.h b/source/armarx/navigation/human/shapes.h
new file mode 100644
index 00000000..f6fd25a5
--- /dev/null
+++ b/source/armarx/navigation/human/shapes.h
@@ -0,0 +1,48 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <SimoxUtility/shapes.h>
+
+#include <armarx/navigation/core/basic_types.h>
+
+namespace armarx::navigation::human::shapes
+{
+
+    /**
+     * @brief An axis oriented ellipse with half-axes a and b along the x- and y-axis respectively.
+     */
+    struct Ellipse
+    {
+        float a;
+        float b;
+    };
+
+    /**
+     * @brief A polygon with arbitrarily many vertices. The polygon will always be closed automatically.
+     */
+    struct Polygon
+    {
+        std::vector<Eigen::Vector2f> vertices;
+    };
+
+} // namespace armarx::navigation::human::shapes
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 867849a1..6b66e7c6 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -24,6 +24,7 @@
 #include <ArmarXCore/core/time.h>
 
 #include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/shapes.h>
 
 namespace armarx::navigation::human
 {
@@ -38,7 +39,7 @@ namespace armarx::navigation::human
 
     struct HumanGroup
     {
-        std::vector<Eigen::Vector2f> vertices;
+        shapes::Polygon shape;
         std::vector<Human> humans;
         DateTime detectionTime;
     };
@@ -46,6 +47,7 @@ namespace armarx::navigation::human
     struct ProxemicZone
     {
         core::Pose2D pose;
+        shapes::Ellipse shape;
     };
 
 } // namespace armarx::navigation::human
-- 
GitLab


From 00272e81f240f1a4c58da85ce223e0c4e7043121 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 15 Aug 2022 22:52:19 +0200
Subject: [PATCH 091/324] Fix const

---
 source/armarx/navigation/human/types.cpp | 2 +-
 source/armarx/navigation/human/types.h   | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/types.cpp b/source/armarx/navigation/human/types.cpp
index 5b6d3d88..6296ba6e 100644
--- a/source/armarx/navigation/human/types.cpp
+++ b/source/armarx/navigation/human/types.cpp
@@ -3,7 +3,7 @@
 namespace armarx::navigation::human
 {
     core::Pose2D
-    Human::estimateAt(DateTime& time) const
+    Human::estimateAt(const DateTime& time) const
     {
         double dt = (time - detectionTime).toSecondsDouble();
         core::Pose2D estimation{pose};
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 6b66e7c6..625fa764 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -34,7 +34,7 @@ namespace armarx::navigation::human
         Eigen::Vector2f linearVelocity;
         DateTime detectionTime;
 
-        core::Pose2D estimateAt(DateTime& time) const;
+        core::Pose2D estimateAt(const DateTime& time) const;
     };
 
     struct HumanGroup
-- 
GitLab


From 87e3ad4e552b6aeb6bb6b7d432be2ff2b83c3a7c Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 15 Aug 2022 23:57:10 +0200
Subject: [PATCH 092/324] Implement human tracking.

TODO: Integrate new definitions of keypoints
---
 .../dynamic_scene_provider/CMakeLists.txt     |   2 +
 .../dynamic_scene_provider/HumanTracker.cpp   | 185 ++++++++++++------
 .../dynamic_scene_provider/HumanTracker.h     |  29 ++-
 3 files changed, 152 insertions(+), 64 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index c53238db..d9dce5d0 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -35,6 +35,8 @@ armarx_add_component(dynamic_scene_provider
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
+    DEPENDENCIES_PRIVATE
+        range-v3::range-v3
     # DEPENDENCIES_LEGACY
         ## Add libraries that do not provide any targets but ${FOO_*} variables.
         # FOO
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 6bae4e5d..279d579d 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -3,97 +3,172 @@
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
+#include <range/v3/range/conversion.hpp>
+#include <range/v3/view/transform.hpp>
+
 namespace armarx::navigation::components::dynamic_scene_provider
 {
 
-    void
-    HumanTracker::update(const Measurements& measurements)
-    {
-        trackedHumans.clear();
 
-        auto positions = getMeasurementPositions(measurements);
+    HumanTracker::DetectedHuman
+    convertHumanPoseToPosition(const armem::human::HumanPose& humanPose)
+    {
+        const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
+        ARMARX_CHECK_NOT_EMPTY(keypoints);
 
-        for (const armem::human::HumanPose& humanPose : measurements.humanPoses)
+        auto centerPos = core::Position::Zero();
+        for (const auto& [_, v] : keypoints)
         {
-            auto centerPos = positions.find(humanPose);
-
-            core::Pose2D pose = core::Pose2D::Identity();
-            pose.translation() = Eigen::Vector2f{centerPos.x(), centerPos.y()};
-            pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
+            centerPos += v.positionGlobal;
+        }
+        centerPos /= static_cast<float>(keypoints.size());
 
-            const human::Human newHuman = {
-                .pose = pose,
-                .linearVelocity = Eigen::Vector2f::Zero(), //TODO more sophisticated guess
-                .detectionTime = measurements.detectionTime};
+        core::Pose2D pose = core::Pose2D::Identity();
+        pose.translation() = centerPos;
+        pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
 
-            trackedHumans.push_back(newHuman);
-        }
+        return pose;
     }
 
-    const std::vector<human::Human>&
-    HumanTracker::getTrackedHumans() const
+    void
+    HumanTracker::update(const Measurements& measurements)
     {
-        return trackedHumans;
-    }
+        //TODO: proper time to live
+        Duration maxAge = Duration::MilliSeconds(500);
 
+        for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
+        {
+            auto& human = *it;
+            if ((measurements.detectionTime - human.human.detectionTime) >= maxAge)
+            {
+                it = trackedHumans.erase(it);
+            }
+            else
+            {
+                human.associated = false;
+                human.human.pose = human.human.estimateAt(measurements.detectionTime);
+                it++;
+            }
+        }
 
-    std::map<const armem::human::HumanPose&, armarx::navigation::core::Position>
-    HumanTracker::getMeasurementPositions(const Measurements& measurements) const
-    {
-        std::map<armem::human::HumanPose&, armarx::navigation::core::Position> map;
+        std::vector<DetectedHuman> newPoses = measurements.humanPoses |
+                                              ranges::views::transform(convertHumanPoseToPosition) |
+                                              ranges::to_vector;
 
-        for (const armem::human::HumanPose& humanPose : measurements.humanPoses)
-        {
+        associateHumans(newPoses);
+    }
 
-            const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
-            ARMARX_CHECK_NOT_EMPTY(keypoints);
+    struct PosDistance
+    {
+        HumanTracker::TrackedHuman& oldHuman;
+        HumanTracker::DetectedHuman& newHuman;
+        const float distance;
+    };
+
+    std::vector<PosDistance>
+    getSortedDistances(const std::vector<HumanTracker::TrackedHuman>& oldHumans,
+                       const std::vector<HumanTracker::DetectedHuman>& newHumans)
+    {
+        std::vector<PosDistance> posDistances;
 
-            auto centerPos = armarx::navigation::core::Position::Zero();
-            for (const auto& [_, v] : keypoints)
+        for (const auto& oldHuman : oldHumans)
+        {
+            if (oldHuman.associated)
             {
-                centerPos += v.positionGlobal;
+                continue;
+            }
+            for (const auto& newHuman : newHumans)
+            {
+                if (newHuman.associated)
+                {
+                    continue;
+                }
+                posDistances.emplace_back(
+                    oldHuman,
+                    newHuman,
+                    (newHuman.pose.translation() - oldHuman.human.pose.translation()).norm());
             }
-            centerPos /= static_cast<float>(keypoints.size());
-
-            map.insert(
-                std::pair<const armem::human::HumanPose&, armarx::navigation::core::Position>(
-                    humanPose, centerPos));
         }
-    }
 
+        std::sort(posDistances.begin(),
+                  posDistances.end(),
+                  [](const PosDistance& a, const PosDistance& b) -> bool
+                  { return a.distance < b.distance; });
 
-    std::map<armem::human::HumanPose&, human::Human&>
-    HumanTracker::getAssociatedHumans(const Measurements& measurements) const
-    {
+        return posDistances;
     }
 
-    std::vector<human::Human>
-    HumanTracker::getMostRecentTrackedHumans() const
+    void
+    HumanTracker::associateHumans(std::vector<DetectedHuman>& detectedHumans)
     {
-        if (trackedHumans.empty())
+        // associate humans by their tracking id
+        for (auto& oldHuman : trackedHumans)
         {
-            return {};
+            if (oldHuman.associated || !oldHuman.trackingId)
+            {
+                continue;
+            }
+            for (auto& newHuman : detectedHumans)
+            {
+                if (newHuman.associated)
+                {
+                    continue;
+                }
+                if (oldHuman.trackingId.value() == newHuman.trackingId)
+                {
+                    associate(oldHuman, newHuman);
+                }
+            }
         }
 
-        std::sort(trackedHumans.begin(),
-                  trackedHumans.end(),
-                  [](human::Human a, human::Human b) -> bool
-                  { return a.detectionTime.operator<=(b.detectionTime); });
-        DateTime mostRecentTime = trackedHumans.back().detectionTime;
 
-        std::vector<human::Human> mostRecentHumans;
+        // associate leftover humans by their distances
+        const auto sortedDistances = getSortedDistances(trackedHumans, detectedHumans);
 
-        for (human::Human trackedHuman : trackedHumans)
+        for (auto& posDistance : sortedDistances)
         {
-            if (trackedHuman.detectionTime == mostRecentTime)
+            if (!posDistance.oldHuman.associated || !posDistance.newHuman.associated)
             {
-                mostRecentHumans.push_back(trackedHuman);
+                continue;
             }
+            associate(posDistance.oldHuman, posDistance.newHuman);
         }
+    }
 
-        return mostRecentHumans;
+    void
+    HumanTracker::associate(TrackedHuman& trackedHuman, DetectedHuman& detectedHuman)
+    {
+        ARMARX_CHECK(!trackedHuman.associated);
+        ARMARX_CHECK(!detectedHuman.associated);
+
+        trackedHuman.associated = true;
+        detectedHuman.associated = true;
+
+        // TODO alpha parameter
+        float a = 0.7;
+
+        float dt =
+            (detectedHuman.detectionTime - trackedHuman.human.detectionTime).toSecondsDouble();
+        Eigen::Vector2f ds =
+            (detectedHuman.pose.translation() - trackedHuman.human.pose.translation());
+        Eigen::Vector2f linVelocity = ds / dt;
+
+        Eigen::Vector2f velocity = a * linVelocity + (1 - a) * trackedHuman.human.linearVelocity;
+
+        trackedHuman.human = {detectedHuman.pose, velocity, detectedHuman.detectionTime};
+        trackedHuman.trackingId = detectedHuman.trackingId;
     }
 
+    std::vector<human::Human>
+    HumanTracker::getTrackedHumans() const
+    {
+        return trackedHumans |
+               ranges::views::transform([](const TrackedHuman& h) -> human::Human
+                                        { return h.human; }) |
+               ranges::to_vector;
+    }
+
+
     void
     HumanTracker::reset()
     {
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 76c6ce50..132464db 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -22,21 +22,32 @@ namespace armarx::navigation::components::dynamic_scene_provider
             std::vector<armem::human::HumanPose> humanPoses;
         };
 
+        struct DetectedHuman
+        {
+            core::Pose2D pose;
+            std::string trackingId;
+            DateTime detectionTime;
+            bool associated;
+        };
+
+        struct TrackedHuman
+        {
+            human::Human human;
+            std::optional<std::string> trackingId = std::nullopt;
+            bool associated;
+        };
+
         void update(const Measurements& measurements);
 
-        const std::vector<human::Human>& getTrackedHumans() const;
+        std::vector<human::Human> getTrackedHumans() const;
 
         void reset();
 
     private:
-        std::vector<human::Human> trackedHumans;
-
-        std::map<const armem::human::HumanPose&, armarx::navigation::core::Position>
-        getMeasurementPositions(const Measurements& measurements) const;
+        void associateHumans(std::vector<DetectedHuman>& detectedHumans);
+        void associate(TrackedHuman& tracked, DetectedHuman& detected);
 
-        std::map<armem::human::HumanPose&, human::Human&>
-        getAssociatedHumans(const Measurements& measurements) const;
-
-        std::vector<human::Human> getMostRecentTrackedHumans() const;
+    private:
+        std::vector<TrackedHuman> trackedHumans;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From b43ce686014462297db376d6bac4e846b54acde9 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Tue, 16 Aug 2022 00:22:49 +0200
Subject: [PATCH 093/324] Use new HumanPose definition with TrackingID

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 40 +++++++++++++------
 .../dynamic_scene_provider/HumanTracker.h     |  6 +--
 2 files changed, 31 insertions(+), 15 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 279d579d..61eaaa69 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -11,23 +11,29 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
 
     HumanTracker::DetectedHuman
-    convertHumanPoseToPosition(const armem::human::HumanPose& humanPose)
+    convertHumanPoseToPosition(const DateTime& time, const armem::human::HumanPose& humanPose)
     {
-        const armem::human::Keypoint3DIdMap& keypoints = humanPose.keypoint3dMap;
+        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
         ARMARX_CHECK_NOT_EMPTY(keypoints);
 
         auto centerPos = core::Position::Zero();
+        int size = 0;
         for (const auto& [_, v] : keypoints)
         {
-            centerPos += v.positionGlobal;
+            if (v.positionGlobal.has_value())
+            {
+                centerPos += v.positionGlobal.value().toEigen();
+                size++;
+            }
         }
-        centerPos /= static_cast<float>(keypoints.size());
+        centerPos /= size;
 
         core::Pose2D pose = core::Pose2D::Identity();
         pose.translation() = centerPos;
-        pose.linear() = Eigen::Rotation2Df(0 /*angle*/).toRotationMatrix();
+        //TODO: angle
+        pose.linear() = Eigen::Rotation2Df(0).toRotationMatrix();
 
-        return pose;
+        return {pose, humanPose.humanTrackingId, time, false};
     }
 
     void
@@ -51,9 +57,12 @@ namespace armarx::navigation::components::dynamic_scene_provider
             }
         }
 
-        std::vector<DetectedHuman> newPoses = measurements.humanPoses |
-                                              ranges::views::transform(convertHumanPoseToPosition) |
-                                              ranges::to_vector;
+        std::vector<DetectedHuman> newPoses =
+            measurements.humanPoses |
+            ranges::views::transform(
+                [measurements](const armem::human::HumanPose& humanPose) -> DetectedHuman
+                { return convertHumanPoseToPosition(measurements.detectionTime, humanPose); }) |
+            ranges::to_vector;
 
         associateHumans(newPoses);
     }
@@ -110,11 +119,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
             }
             for (auto& newHuman : detectedHumans)
             {
-                if (newHuman.associated)
+                if (newHuman.associated || !newHuman.trackingId)
                 {
                     continue;
                 }
-                if (oldHuman.trackingId.value() == newHuman.trackingId)
+                if (oldHuman.trackingId.value() == newHuman.trackingId.value())
                 {
                     associate(oldHuman, newHuman);
                 }
@@ -125,9 +134,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // associate leftover humans by their distances
         const auto sortedDistances = getSortedDistances(trackedHumans, detectedHumans);
 
+        //TODO max distance parameter
+        float maxDistance = 600;
+
         for (auto& posDistance : sortedDistances)
         {
-            if (!posDistance.oldHuman.associated || !posDistance.newHuman.associated)
+            if (posDistance.distance > maxDistance)
+            {
+                break;
+            }
+            if (posDistance.oldHuman.associated || posDistance.newHuman.associated)
             {
                 continue;
             }
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 132464db..f13a6653 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -24,9 +24,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         struct DetectedHuman
         {
-            core::Pose2D pose;
-            std::string trackingId;
-            DateTime detectionTime;
+            const core::Pose2D pose;
+            const std::optional<std::string> trackingId;
+            const DateTime detectionTime;
             bool associated;
         };
 
-- 
GitLab


From 7c38b6f4ebdbf6fca408ca47c53e5fbf397d884b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Tue, 16 Aug 2022 00:38:07 +0200
Subject: [PATCH 094/324] Change human library CMake target due to naming
 conflict

---
 source/armarx/navigation/human/CMakeLists.txt | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 670c1869..fd5fb36c 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -1,9 +1,9 @@
-armarx_add_aron_library(human_aron
+armarx_add_aron_library(teb_human_aron
     ARON_FILES
         aron/Human.xml
 )
 
-armarx_add_library(human
+armarx_add_library(teb_human
     DEPENDENCIES_PUBLIC
         ArmarXCore
         armarx_navigation::core
-- 
GitLab


From e27109b4d39e1a63b943d242e1c33fdf0fa88280 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Tue, 16 Aug 2022 00:42:21 +0200
Subject: [PATCH 095/324] New library name

---
 .../navigation/components/dynamic_scene_provider/CMakeLists.txt | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index d9dce5d0..39d89c1a 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -31,7 +31,7 @@ armarx_add_component(dynamic_scene_provider
         armarx_navigation::util
         armarx_navigation::memory
         armarx_navigation::dynamic_scene
-        armarx_navigation::human
+        armarx_navigation::teb_human
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
-- 
GitLab


From b7dcb8b4c0ea349a5aca664152535ff5bbe9e0ae Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Tue, 16 Aug 2022 01:24:25 +0200
Subject: [PATCH 096/324] Fix eigen errors

---
 .../dynamic_scene_provider/Component.cpp      |  8 +--
 .../dynamic_scene_provider/HumanTracker.cpp   | 50 +++++++++----------
 .../dynamic_scene_provider/HumanTracker.h     |  8 +--
 3 files changed, 31 insertions(+), 35 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index a4d10991..e8abd88f 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -318,13 +318,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         }
 
         // here ends: data fetching
-        
-        humanTracker.update(HumanTracker::Measurements{
-            .humanPoses = humanPoseResult.humanPoses
-        });
-
-
 
+        humanTracker.update(HumanTracker::Measurements{.detectionTime = timestamp,
+                                                       .humanPoses = humanPoseResult.humanPoses});
     }
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 61eaaa69..a63f8a30 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -16,7 +16,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
         ARMARX_CHECK_NOT_EMPTY(keypoints);
 
-        auto centerPos = core::Position::Zero();
+        Eigen::Vector3f centerPos;
         int size = 0;
         for (const auto& [_, v] : keypoints)
         {
@@ -29,7 +29,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         centerPos /= size;
 
         core::Pose2D pose = core::Pose2D::Identity();
-        pose.translation() = centerPos;
+        pose.translation() = centerPos.head(2);
         //TODO: angle
         pose.linear() = Eigen::Rotation2Df(0).toRotationMatrix();
 
@@ -69,33 +69,33 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     struct PosDistance
     {
-        HumanTracker::TrackedHuman& oldHuman;
-        HumanTracker::DetectedHuman& newHuman;
-        const float distance;
+        HumanTracker::TrackedHuman* oldHuman;
+        HumanTracker::DetectedHuman* newHuman;
+        float distance;
     };
 
     std::vector<PosDistance>
-    getSortedDistances(const std::vector<HumanTracker::TrackedHuman>& oldHumans,
-                       const std::vector<HumanTracker::DetectedHuman>& newHumans)
+    getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
+                       std::vector<HumanTracker::DetectedHuman>& newHumans)
     {
         std::vector<PosDistance> posDistances;
 
-        for (const auto& oldHuman : oldHumans)
+        for (auto& oldHuman : oldHumans)
         {
             if (oldHuman.associated)
             {
                 continue;
             }
-            for (const auto& newHuman : newHumans)
+            for (auto& newHuman : newHumans)
             {
                 if (newHuman.associated)
                 {
                     continue;
                 }
-                posDistances.emplace_back(
-                    oldHuman,
-                    newHuman,
-                    (newHuman.pose.translation() - oldHuman.human.pose.translation()).norm());
+                posDistances.push_back(
+                    {&oldHuman,
+                     &newHuman,
+                     (newHuman.pose.translation() - oldHuman.human.pose.translation()).norm()});
             }
         }
 
@@ -125,7 +125,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 }
                 if (oldHuman.trackingId.value() == newHuman.trackingId.value())
                 {
-                    associate(oldHuman, newHuman);
+                    associate(&oldHuman, &newHuman);
                 }
             }
         }
@@ -143,7 +143,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             {
                 break;
             }
-            if (posDistance.oldHuman.associated || posDistance.newHuman.associated)
+            if (posDistance.oldHuman->associated || posDistance.newHuman->associated)
             {
                 continue;
             }
@@ -152,27 +152,27 @@ namespace armarx::navigation::components::dynamic_scene_provider
     }
 
     void
-    HumanTracker::associate(TrackedHuman& trackedHuman, DetectedHuman& detectedHuman)
+    HumanTracker::associate(TrackedHuman* trackedHuman, DetectedHuman* detectedHuman)
     {
-        ARMARX_CHECK(!trackedHuman.associated);
-        ARMARX_CHECK(!detectedHuman.associated);
+        ARMARX_CHECK(!trackedHuman->associated);
+        ARMARX_CHECK(!detectedHuman->associated);
 
-        trackedHuman.associated = true;
-        detectedHuman.associated = true;
+        trackedHuman->associated = true;
+        detectedHuman->associated = true;
 
         // TODO alpha parameter
         float a = 0.7;
 
         float dt =
-            (detectedHuman.detectionTime - trackedHuman.human.detectionTime).toSecondsDouble();
+            (detectedHuman->detectionTime - trackedHuman->human.detectionTime).toSecondsDouble();
         Eigen::Vector2f ds =
-            (detectedHuman.pose.translation() - trackedHuman.human.pose.translation());
+            (detectedHuman->pose.translation() - trackedHuman->human.pose.translation());
         Eigen::Vector2f linVelocity = ds / dt;
 
-        Eigen::Vector2f velocity = a * linVelocity + (1 - a) * trackedHuman.human.linearVelocity;
+        Eigen::Vector2f velocity = a * linVelocity + (1 - a) * trackedHuman->human.linearVelocity;
 
-        trackedHuman.human = {detectedHuman.pose, velocity, detectedHuman.detectionTime};
-        trackedHuman.trackingId = detectedHuman.trackingId;
+        trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
+        trackedHuman->trackingId = detectedHuman->trackingId;
     }
 
     std::vector<human::Human>
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index f13a6653..e5197d82 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -24,9 +24,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         struct DetectedHuman
         {
-            const core::Pose2D pose;
-            const std::optional<std::string> trackingId;
-            const DateTime detectionTime;
+            core::Pose2D pose;
+            std::optional<std::string> trackingId;
+            DateTime detectionTime;
             bool associated;
         };
 
@@ -45,7 +45,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     private:
         void associateHumans(std::vector<DetectedHuman>& detectedHumans);
-        void associate(TrackedHuman& tracked, DetectedHuman& detected);
+        void associate(TrackedHuman* tracked, DetectedHuman* detected);
 
     private:
         std::vector<TrackedHuman> trackedHumans;
-- 
GitLab


From 8c3e1e57edd7c1c5a3fff6b8b9835a46c74d5bc1 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Tue, 16 Aug 2022 03:07:21 +0200
Subject: [PATCH 097/324] Use eigen conversions

---
 .../components/dynamic_scene_provider/HumanTracker.cpp         | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index a63f8a30..4adc1106 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -3,6 +3,7 @@
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
+#include <armarx/navigation/conversions/eigen.h>
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
 
@@ -29,7 +30,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         centerPos /= size;
 
         core::Pose2D pose = core::Pose2D::Identity();
-        pose.translation() = centerPos.head(2);
+        pose.translation() = conv::to2D(centerPos);
         //TODO: angle
         pose.linear() = Eigen::Rotation2Df(0).toRotationMatrix();
 
-- 
GitLab


From 54466920c92ee945f68301f74a1a2bec8a30ea21 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 16 Aug 2022 21:36:22 +0200
Subject: [PATCH 098/324] distance to obstacle costmap as separate component

---
 .../navigation/components/CMakeLists.txt      |   3 +-
 .../NavigationMemory/CMakeLists.txt           |   1 +
 .../NavigationMemory/NavigationMemory.cpp     |  13 +-
 .../NavigationMemory/NavigationMemory.h       |   2 +
 .../components/NavigationMemory/Visu.cpp      |  93 +++++-
 .../components/NavigationMemory/Visu.h        |   7 +-
 .../components/Navigator/Navigator.cpp        |  43 +--
 .../components/Navigator/Navigator.h          |   5 +-
 .../CMakeLists.txt                            |  34 +++
 .../Component.cpp                             | 268 ++++++++++++++++++
 .../Component.h                               | 152 ++++++++++
 .../ComponentInterface.ice                    |  35 +++
 .../Component.cpp                             |   8 +
 .../Component.h                               |   2 +-
 source/armarx/navigation/core/StaticScene.h   |   3 +-
 .../navigation/global_planning/AStar.cpp      |   2 +-
 .../navigation/global_planning/SPFA.cpp       |   7 +-
 .../memory/client/costmap/Reader.cpp          |   4 +-
 .../server/scene_provider/SceneProvider.cpp   |  35 +--
 19 files changed, 635 insertions(+), 82 deletions(-)
 create mode 100644 source/armarx/navigation/components/distance_to_obstacle_costmap_provider/CMakeLists.txt
 create mode 100644 source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
 create mode 100644 source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
 create mode 100644 source/armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.ice

diff --git a/source/armarx/navigation/components/CMakeLists.txt b/source/armarx/navigation/components/CMakeLists.txt
index 3f13b407..24217c76 100644
--- a/source/armarx/navigation/components/CMakeLists.txt
+++ b/source/armarx/navigation/components/CMakeLists.txt
@@ -4,4 +4,5 @@ add_subdirectory(Navigator)
 
 add_subdirectory(dynamic_distance_to_obstacle_costmap_provider)
 
-add_subdirectory(dynamic_scene_provider)
\ No newline at end of file
+add_subdirectory(dynamic_scene_provider)
+add_subdirectory(distance_to_obstacle_costmap_provider)
\ No newline at end of file
diff --git a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
index 06bd4080..3f8da95e 100644
--- a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
+++ b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
@@ -17,6 +17,7 @@ armarx_add_component(navigation_memory
         ## NavigationMemoryInterfaces  # If you defined a component ice interface above.
         armarx_navigation::graph
         armarx_navigation::location
+        armarx_navigation::algorithms
 
     SOURCES
         NavigationMemory.cpp
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
index 0189ad50..a18764b0 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
@@ -27,6 +27,8 @@
 #include <fstream>
 #include <iostream>
 
+#include "ArmarXCore/core/time/Metronome.h"
+#include "ArmarXCore/core/time/forward_declarations.h"
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/time/CycleUtil.h>
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
@@ -429,7 +431,9 @@ namespace armarx::navigation
     {
         memory::Visu visu{arviz,
                           workingMemory().getCoreSegment(navigation::location::coreSegmentID),
-                          workingMemory().getCoreSegment(navigation::graph::coreSegmentID)};
+                          workingMemory().getCoreSegment(navigation::graph::coreSegmentID),
+                          workingMemory().getCoreSegment(memory::constants::CostmapCoreSegmentName)};
+
 
         Properties::LocationGraph p;
         {
@@ -437,7 +441,7 @@ namespace armarx::navigation
             p = properties.locationGraph;
         }
 
-        CycleUtil cycle(static_cast<int>(1000 / p.visuFrequency));
+        Metronome metronome(Frequency::HertzDouble(p.visuFrequency));
         while (tasks.visuTask and not tasks.visuTask->isStopped())
         {
             ARMARX_TRACE;
@@ -455,9 +459,12 @@ namespace armarx::navigation
             // Graph Edges
             visu.drawGraphs(layers, p.visuGraphEdges);
 
+            // Costmaps
+            visu.drawCostmaps(layers, p.visuCostmaps);
+
             arviz.commit(layers);
 
-            cycle.waitForCycleDuration();
+            metronome.waitForNextTick();
         }
     }
 
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
index 0b4b95a5..c67da7fc 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
@@ -96,6 +96,8 @@ namespace armarx::navigation
             {
                 bool visuLocations = true;
                 bool visuGraphEdges = true;
+                bool visuCostmaps = true;
+                
                 float visuFrequency = 2;
             };
             LocationGraph locationGraph;
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.cpp b/source/armarx/navigation/components/NavigationMemory/Visu.cpp
index 07f364bc..73df72de 100644
--- a/source/armarx/navigation/components/NavigationMemory/Visu.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/Visu.cpp
@@ -22,8 +22,14 @@
 
 #include "Visu.h"
 
+#include <SimoxUtility/color/cmaps/colormaps.h>
+
+#include "RobotAPI/components/ArViz/Client/Layer.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
+#include "armarx/navigation/conversions/eigen.h"
+#include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
+#include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/core/Graph.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
@@ -35,10 +41,12 @@ namespace armarx::navigation::memory
 
     Visu::Visu(viz::Client arviz,
                const armem::server::wm::CoreSegment& locSegment,
-               const armem::server::wm::CoreSegment& graphSegment) :
+               const armem::server::wm::CoreSegment& graphSegment,
+               const armem::server::wm::CoreSegment& costmapSegment) :
         arviz(arviz),
         locSegment(locSegment),
         graphSegment(graphSegment),
+        costmapSegment(costmapSegment),
         visu(std::make_unique<graph::GraphVisu>())
     {
     }
@@ -117,4 +125,87 @@ namespace armarx::navigation::memory
         }
     }
 
+    namespace
+    {
+
+        void
+        visualize(const algorithms::Costmap& costmap, viz::Layer& layer, const std::string& name)
+        {
+            const auto cmap = simox::color::cmaps::viridis();
+            const float vmax = costmap.getGrid().array().maxCoeff();
+
+            const auto asColor = [&cmap, &vmax](const float distance) -> viz::data::Color
+            {
+                const auto color = cmap.at(distance, 0.F, vmax);
+                return {color.a, color.r, color.g, color.b};
+            };
+
+            const std::int64_t cols = costmap.getGrid().cols();
+            const std::int64_t rows = costmap.getGrid().rows();
+
+            auto mesh = viz::Mesh(name);
+
+            std::vector<std::vector<Eigen::Vector3f>> vertices;
+            std::vector<std::vector<viz::data::Color>> colors;
+
+            for (int r = 0; r < rows; r++)
+            {
+                auto& verticesRow = vertices.emplace_back(cols);
+                auto& colorsRow = colors.emplace_back(cols);
+
+                for (int c = 0; c < cols; c++)
+                {
+                    verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
+                    colorsRow.at(c) = asColor(costmap.getGrid()(r, c));
+                }
+            }
+
+            mesh.grid2D(vertices, colors);
+
+            layer.add(mesh);
+        }
+
+    } // namespace
+
+    void
+    Visu::drawCostmaps(std::vector<viz::Layer>& layers, bool enabled)
+    {
+        if (not enabled)
+        {
+            return;
+        }
+
+        std::map<std::string, std::vector<std::pair<std::string, algorithms::Costmap>>>
+            namedProviderCostmaps;
+
+        costmapSegment.doLocked(
+            [&]()
+            {
+                using namespace armem::server;
+
+                costmapSegment.forEachEntity(
+                    [&](const wm::Entity& entity)
+                    {
+                        if (const wm::EntityInstance* instance = entity.findLatestInstance())
+                        {
+                            navigation::algorithms::Costmap costmap =
+                                algorithms::fromAron(*instance);
+
+                            namedProviderCostmaps[instance->id().providerSegmentName].emplace_back(
+                                instance->id().entityName, std::move(costmap));
+                        }
+                    });
+            });
+
+        for (const auto& [providerName, namedCostmaps] : namedProviderCostmaps)
+        {
+            viz::Layer& layer = layers.emplace_back(arviz.layer("costmaps_" + providerName));
+            for (const auto& [name, costmap] : namedCostmaps)
+            {
+                visualize(costmap, layer, name);
+            }
+        }
+    }
+
+
 } // namespace armarx::navigation::memory
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.h b/source/armarx/navigation/components/NavigationMemory/Visu.h
index f28fa6d8..cfd732ad 100644
--- a/source/armarx/navigation/components/NavigationMemory/Visu.h
+++ b/source/armarx/navigation/components/NavigationMemory/Visu.h
@@ -25,8 +25,10 @@
 #include <memory>
 #include <vector>
 
+#include "RobotAPI/libraries/armem/server/wm/memory_definitions.h"
 #include <RobotAPI/components/ArViz/Client/Client.h>
 #include <RobotAPI/libraries/armem/core/forward_declarations.h>
+#include "armarx/navigation/algorithms/Costmap.h"
 
 
 namespace armarx::navigation::graph
@@ -42,12 +44,14 @@ namespace armarx::navigation::memory
     public:
         Visu(viz::Client arviz,
              const armem::server::wm::CoreSegment& locSegment,
-             const armem::server::wm::CoreSegment& graphSegment);
+             const armem::server::wm::CoreSegment& graphSegment,
+             const armem::server::wm::CoreSegment& costmapSegment);
         ~Visu();
 
 
         void drawLocations(std::vector<viz::Layer>& layers, bool enabled);
         void drawGraphs(std::vector<viz::Layer>& layers, bool enabled);
+        void drawCostmaps(std::vector<viz::Layer>& layers, bool enabled);
 
 
     public:
@@ -55,6 +59,7 @@ namespace armarx::navigation::memory
 
         const armem::server::wm::CoreSegment& locSegment;
         const armem::server::wm::CoreSegment& graphSegment;
+        const armem::server::wm::CoreSegment& costmapSegment;
 
         std::unique_ptr<navigation::graph::GraphVisu> visu;
     };
diff --git a/source/armarx/navigation/components/Navigator/Navigator.cpp b/source/armarx/navigation/components/Navigator/Navigator.cpp
index 8b56fd6d..e10c47a8 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.cpp
+++ b/source/armarx/navigation/components/Navigator/Navigator.cpp
@@ -123,7 +123,6 @@ namespace armarx::navigation::components
         addPlugin(resultsWriterPlugin);
         addPlugin(graphReaderPlugin);
         addPlugin(costmapReaderPlugin);
-        addPlugin(costmapWriterPlugin);
 
         addPlugin(virtualRobotReaderPlugin);
 
@@ -174,7 +173,7 @@ namespace armarx::navigation::components
                                               ->getRobotName();
 
             const server::scene_provider::SceneProvider::Config cfg{.robotName = robotName};
-            sceneProvider = server::scene_provider::SceneProvider(srv, cfg);
+            sceneProvider.emplace(srv, cfg);
         }
 
         initializeScene();
@@ -449,46 +448,6 @@ namespace armarx::navigation::components
         return def;
     }
 
-    void
-    visualize(const algorithms::Costmap& costmap, viz::Client& arviz, const std::string& name)
-    {
-        const auto cmap = simox::color::cmaps::viridis();
-        const float vmax = costmap.getGrid().array().maxCoeff();
-
-        const auto asColor = [&cmap, &vmax](const float distance) -> viz::data::Color
-        {
-            const auto color = cmap.at(distance, 0.F, vmax);
-            return {color.a, color.r, color.g, color.b};
-        };
-
-        auto layer = arviz.layer("costmap_" + name);
-
-        const std::int64_t cols = costmap.getGrid().cols();
-        const std::int64_t rows = costmap.getGrid().rows();
-
-        auto mesh = viz::Mesh("");
-
-        std::vector<std::vector<Eigen::Vector3f>> vertices;
-        std::vector<std::vector<viz::data::Color>> colors;
-
-        for (int r = 0; r < rows; r++)
-        {
-            auto& verticesRow = vertices.emplace_back(cols);
-            auto& colorsRow = colors.emplace_back(cols);
-
-            for (int c = 0; c < cols; c++)
-            {
-                verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
-                colorsRow.at(c) = asColor(costmap.getGrid()(r, c));
-            }
-        }
-
-        mesh.grid2D(vertices, colors);
-
-        layer.add(mesh);
-
-        arviz.commit(layer);
-    }
 
     server::Navigator*
     components::Navigator::activeNavigator()
diff --git a/source/armarx/navigation/components/Navigator/Navigator.h b/source/armarx/navigation/components/Navigator/Navigator.h
index d20a2101..4c25c56b 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.h
+++ b/source/armarx/navigation/components/Navigator/Navigator.h
@@ -42,7 +42,6 @@
 
 #include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
-#include <RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h>
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/RobotUnitComponentPlugin.h>
 #include <RobotAPI/libraries/armem/client/plugins.h>
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
@@ -54,7 +53,6 @@
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/components/Navigator/RemoteGui.h>
 #include <armarx/navigation/core/types.h>
-#include <armarx/navigation/memory/client/costmap/Writer.h>
 #include <armarx/navigation/memory/client/graph/Reader.h>
 #include <armarx/navigation/memory/client/parameterization/Reader.h>
 #include <armarx/navigation/memory/client/stack_result/Writer.h>
@@ -195,8 +193,7 @@ namespace armarx::navigation::components
             graphReaderPlugin = nullptr;
         armem::client::plugins::ReaderWriterPlugin<memory::client::costmap::Reader>*
             costmapReaderPlugin = nullptr;
-        armem::client::plugins::ReaderWriterPlugin<memory::client::costmap::Writer>*
-            costmapWriterPlugin = nullptr;
+
         // armem::vision::occupancy_grid::client::Reader occupancyGridReader;
 
         // `robot_state` memory reader and writer
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/CMakeLists.txt b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/CMakeLists.txt
new file mode 100644
index 00000000..a637fdcb
--- /dev/null
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/CMakeLists.txt
@@ -0,0 +1,34 @@
+armarx_add_component(distance_to_obstacle_costmap_provider
+    ICE_FILES
+        ComponentInterface.ice
+    ICE_DEPENDENCIES
+        ArmarXCoreInterfaces
+        # RobotAPIInterfaces
+    # ARON_FILES
+        # aron/my_type.xml
+    SOURCES
+        Component.cpp
+    HEADERS
+        Component.h
+    DEPENDENCIES
+        # ArmarXCore
+        ArmarXCore
+        ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
+        # ArmarXGui
+        ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
+        # RobotAPI
+        armem_vision
+        armem_robot_state
+        armem_robot
+        ## RobotAPICore
+        ## RobotAPIInterfaces
+        RobotAPIComponentPlugins  # For ArViz and other plugins.
+        armarx_navigation::memory
+        armarx_navigation::algorithms
+        armarx_navigation::util
+    # DEPENDENCIES_LEGACY
+        ## Add libraries that do not provide any targets but ${FOO_*} variables.
+        # FOO
+    # If you need a separate shared component library you can enable it with the following flag.
+    # SHARED_COMPONENT_LIBRARY
+)
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
new file mode 100644
index 00000000..6c52b133
--- /dev/null
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
@@ -0,0 +1,268 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::distance_to_obstacle_costmap_provider
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#include "Component.h"
+
+#include <VirtualRobot/SceneObjectSet.h>
+
+#include "ArmarXCore/core/Component.h"
+#include "ArmarXCore/core/services/tasks/RunningTask.h"
+#include "ArmarXCore/core/time/Clock.h"
+#include "ArmarXCore/core/time/DateTime.h"
+#include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
+
+#include "RobotAPI/libraries/ArmarXObjects/forward_declarations.h"
+
+#include "armarx/navigation/algorithms/CostmapBuilder.h"
+#include "armarx/navigation/util/util.h"
+
+
+namespace armarx::navigation::components::distance_to_obstacle_costmap_provider
+{
+    Component::Component()
+    {
+        addPlugin(virtualRobotReaderPlugin);
+        addPlugin(costmapWriterPlugin);
+    }
+
+
+    const std::string Component::defaultName = "distance_to_obstacle_costmap_provider";
+
+
+    armarx::PropertyDefinitionsPtr
+    Component::createPropertyDefinitions()
+    {
+        armarx::PropertyDefinitionsPtr def =
+            new armarx::ComponentPropertyDefinitions(getConfigIdentifier());
+
+        def->optional(properties.robotName, "p.robotName", "Robot name.");
+
+        return def;
+    }
+
+
+    void
+    Component::onInitComponent()
+    {
+        // Topics and properties defined above are automagically registered.
+
+        // Keep debug observer data until calling `sendDebugObserverBatch()`.
+        // (Requies the armarx::DebugObserverComponentPluginUser.)
+        // setDebugObserverBatchModeEnabled(true);
+    }
+
+
+    void
+    Component::onConnectComponent()
+    {
+        // Do things after connecting to topics and components.
+
+        /* (Requies the armarx::DebugObserverComponentPluginUser.)
+        // Use the debug observer to log data over time.
+        // The data can be viewed in the ObserverView and the LivePlotter.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        {
+            setDebugObserverDatafield("numBoxes", properties.numBoxes);
+            setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+            sendDebugObserverBatch();
+        }
+        */
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        // Draw boxes in ArViz.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        drawBoxes(properties, arviz);
+        */
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        // Setup the remote GUI.
+        {
+            createRemoteGuiTab();
+            RemoteGui_startRunningTask();
+        }
+        */
+
+        runningTask = new RunningTask<Component>(this, &Component::run, "createAndStoreCostmap");
+        runningTask->start();
+    }
+
+
+    void
+    Component::run()
+    {
+        // FIXME: whenever the static scene changes, update the costmap
+
+        createAndStoreCostmap();
+    }
+
+    bool
+    Component::createAndStoreCostmap()
+    {
+        auto robot = virtualRobotReaderPlugin->get().getRobot(
+            properties.robotName,
+            armarx::DateTime::Invalid(),
+            VirtualRobot::RobotIO::RobotDescription::eCollisionModel);
+
+        const auto objectPoseClient = ObjectPoseClientPluginUser::getClient();
+
+        const objpose::ObjectPoseSeq objectPoses = objectPoseClient.fetchObjectPoses();
+
+        // remove those objects that belong to an object dataset. the manipulation object / distance computation is broken
+        const auto objectPosesStatic =
+            armarx::navigation::util::filterObjects(objectPoses, {"KIT", "HOPE", "MDB", "YCB"});
+
+        const auto objects = armarx::navigation::util::asSceneObjects(objectPosesStatic);
+
+        ARMARX_CHECK_NOT_NULL(objects);
+        ARMARX_INFO << objects->getSize() << " objects in the scene";
+
+        ARMARX_INFO << "Creating costmap";
+        ARMARX_CHECK_NOT_NULL(robot);
+
+        // FIXME: move costmap creation out of this component
+        // FIXME create costmap writer enum: type of costmaps
+        algorithms::CostmapBuilder costmapBuilder(
+            robot,
+            objects,
+            algorithms::Costmap::Parameters{.binaryGrid = false, .cellSize = 100},
+            "Platform-navigation-colmodel");
+
+        const auto costmap = costmapBuilder.create();
+
+        ARMARX_INFO << "Storing costmap in the memory.";
+        return costmapWriterPlugin->get().store(
+            costmap, "distance_to_obstacles", getName(), armarx::Clock::Now());
+    }
+
+
+    void
+    Component::onDisconnectComponent()
+    {
+        runningTask->stop();
+    }
+
+
+    void
+    Component::onExitComponent()
+    {
+    }
+
+
+    std::string
+    Component::getDefaultName() const
+    {
+        return Component::defaultName;
+    }
+
+
+    std::string
+    Component::GetDefaultName()
+    {
+        return Component::defaultName;
+    }
+
+
+    /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+    void
+    Component::createRemoteGuiTab()
+    {
+        using namespace armarx::RemoteGui::Client;
+
+        // Setup the widgets.
+
+        tab.boxLayerName.setValue(properties.boxLayerName);
+
+        tab.numBoxes.setValue(properties.numBoxes);
+        tab.numBoxes.setRange(0, 100);
+
+        tab.drawBoxes.setLabel("Draw Boxes");
+
+        // Setup the layout.
+
+        GridLayout grid;
+        int row = 0;
+        {
+            grid.add(Label("Box Layer"), {row, 0}).add(tab.boxLayerName, {row, 1});
+            ++row;
+
+            grid.add(Label("Num Boxes"), {row, 0}).add(tab.numBoxes, {row, 1});
+            ++row;
+
+            grid.add(tab.drawBoxes, {row, 0}, {2, 1});
+            ++row;
+        }
+
+        VBoxLayout root = {grid, VSpacer()};
+        RemoteGui_createTab(getName(), root, &tab);
+    }
+
+
+    void
+    Component::RemoteGui_update()
+    {
+        if (tab.boxLayerName.hasValueChanged() || tab.numBoxes.hasValueChanged())
+        {
+            std::scoped_lock lock(propertiesMutex);
+            properties.boxLayerName = tab.boxLayerName.getValue();
+            properties.numBoxes = tab.numBoxes.getValue();
+
+            {
+                setDebugObserverDatafield("numBoxes", properties.numBoxes);
+                setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+                sendDebugObserverBatch();
+            }
+        }
+        if (tab.drawBoxes.wasClicked())
+        {
+            // Lock shared variables in methods running in seperate threads
+            // and pass them to functions. This way, the called functions do
+            // not need to think about locking.
+            std::scoped_lock lock(propertiesMutex, arvizMutex);
+            drawBoxes(properties, arviz);
+        }
+    }
+    */
+
+
+    /* (Requires the armarx::ArVizComponentPluginUser.)
+    void
+    Component::drawBoxes(const Component::Properties& p, viz::Client& arviz)
+    {
+        // Draw something in ArViz (requires the armarx::ArVizComponentPluginUser.
+        // See the ArVizExample in RobotAPI for more examples.
+
+        viz::Layer layer = arviz.layer(p.boxLayerName);
+        for (int i = 0; i < p.numBoxes; ++i)
+        {
+            layer.add(viz::Box("box_" + std::to_string(i))
+                      .position(Eigen::Vector3f(i * 100, 0, 0))
+                      .size(20).color(simox::Color::blue()));
+        }
+        arviz.commit(layer);
+    }
+    */
+
+
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
+
+} // namespace armarx::navigation::components::distance_to_obstacle_costmap_provider
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
new file mode 100644
index 00000000..bd6a9bee
--- /dev/null
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
@@ -0,0 +1,152 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::distance_to_obstacle_costmap_provider
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#pragma once
+
+
+#include "ArmarXCore/core/services/tasks/RunningTask.h"
+#include <ArmarXCore/core/Component.h>
+
+#include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
+#include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
+#include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h>
+
+#include "armarx/navigation/memory/client/costmap/Writer.h"
+#include <armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.h>
+
+
+namespace armarx::navigation::components::distance_to_obstacle_costmap_provider
+{
+
+    class Component :
+        virtual public armarx::Component,
+        virtual public ObjectPoseClientPluginUser,
+        virtual public armarx::navigation::components::distance_to_obstacle_costmap_provider::
+            ComponentInterface
+    // , virtual public armarx::DebugObserverComponentPluginUser
+    // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
+    // , virtual public armarx::ArVizComponentPluginUser
+    {
+    public:
+        Component();
+
+        /// @see armarx::ManagedIceObject::getDefaultName()
+        std::string getDefaultName() const override;
+
+        /// Get the component's default name.
+        static std::string GetDefaultName();
+
+
+    protected:
+        /// @see PropertyUser::createPropertyDefinitions()
+        armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
+
+        /// @see armarx::ManagedIceObject::onInitComponent()
+        void onInitComponent() override;
+
+        /// @see armarx::ManagedIceObject::onConnectComponent()
+        void onConnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onDisconnectComponent()
+        void onDisconnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onExitComponent()
+        void onExitComponent() override;
+
+
+        /* (Requires armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// This function should be called once in onConnect() or when you
+        /// need to re-create the Remote GUI tab.
+        void createRemoteGuiTab();
+
+        /// After calling `RemoteGui_startRunningTask`, this function is
+        /// called periodically in a separate thread. If you update variables,
+        /// make sure to synchronize access to them.
+        void RemoteGui_update() override;
+        */
+
+        bool createAndStoreCostmap();
+
+        void run();
+
+    private:
+        // Private methods go here.
+
+        // Forward declare `Properties` if you used it before its defined.
+        // struct Properties;
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        /// Draw some boxes in ArViz.
+        void drawBoxes(const Properties& p, viz::Client& arviz);
+        */
+
+
+        static const std::string defaultName;
+
+
+        // Private member variables go here.
+
+
+        /// Properties shown in the Scenario GUI.
+        struct Properties
+        {
+            std::string robotName = "Armar6";
+        };
+        Properties properties;
+        /* Use a mutex if you access variables from different threads
+         * (e.g. ice functions and RemoteGui_update()).
+        std::mutex propertiesMutex;
+        */
+
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// Tab shown in the Remote GUI.
+        struct RemoteGuiTab : armarx::RemoteGui::Client::Tab
+        {
+            armarx::RemoteGui::Client::LineEdit boxLayerName;
+            armarx::RemoteGui::Client::IntSpinBox numBoxes;
+
+            armarx::RemoteGui::Client::Button drawBoxes;
+        };
+        RemoteGuiTab tab;
+        */
+
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+         * When used from different threads, an ArViz client needs to be synchronized.
+        /// Protects the arviz client inherited from the ArViz plugin.
+        std::mutex arvizMutex;
+        */
+        std::optional<armem::robot::RobotDescription> robotDescription;
+        armem::client::plugins::ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>*
+            virtualRobotReaderPlugin = nullptr;
+
+
+        armem::client::plugins::ReaderWriterPlugin<memory::client::costmap::Writer>*
+            costmapWriterPlugin = nullptr;
+
+
+        RunningTask<Component>::pointer_type runningTask;
+    };
+
+} // namespace armarx::navigation::components::distance_to_obstacle_costmap_provider
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.ice b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.ice
new file mode 100644
index 00000000..469a4290
--- /dev/null
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.ice
@@ -0,0 +1,35 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * package    navigation::distance_to_obstacle_costmap_provider
+ * author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * date       2022
+ * copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *            GNU General Public License
+ */
+
+
+#pragma once
+
+
+module armarx {  module navigation {  module components {  module distance_to_obstacle_costmap_provider 
+{
+
+    interface ComponentInterface
+    {
+	// Define your interface here.
+    };
+
+};};};};
diff --git a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
index fa926fb7..6b89eb56 100644
--- a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
@@ -84,6 +84,14 @@ namespace armarx::navigation::components::dynamic_distance_to_obstacle_costmap_p
         // def->optional(
         //     properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
         def->optional(properties.updatePeriodMs, "p.updatePeriodMs", "");
+        def->optional(properties.staticCostmap.name, "p.staticCostmap.name", "");
+        def->required(properties.staticCostmap.providerName, "p.staticCostmap.providerName", "");
+
+        def->optional(properties.laserScannerFeatures.name, "p.laserScannerFeatures.name", "");
+        def->optional(properties.laserScannerFeatures.providerName, "p.laserScannerFeatures.providerName", "");
+
+        def->optional(properties.robot.name, "p.robot.name", "");
+
 
         costmapReader.registerPropertyDefinitions(def);
         costmapWriter.registerPropertyDefinitions(def);
diff --git a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.h b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.h
index 6094a09e..1837d8ac 100644
--- a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.h
@@ -124,7 +124,7 @@ namespace armarx::navigation::components::dynamic_distance_to_obstacle_costmap_p
             // std::string boxLayerName = "boxes";
             struct
             {
-                std::string providerName = "navigator";
+                std::string providerName;
                 std::string name = "distance_to_obstacles";
             } staticCostmap;
 
diff --git a/source/armarx/navigation/core/StaticScene.h b/source/armarx/navigation/core/StaticScene.h
index de0f008d..534b4345 100644
--- a/source/armarx/navigation/core/StaticScene.h
+++ b/source/armarx/navigation/core/StaticScene.h
@@ -35,8 +35,7 @@ namespace armarx::navigation::core
     {
         VirtualRobot::SceneObjectSetPtr objects;
 
-        // TODO(fabian.reister): rename, why unique_ptr
-        std::unique_ptr<algorithms::Costmap> costmap;
+        std::optional<algorithms::Costmap> distanceToObstaclesCostmap;
 
     };
 
diff --git a/source/armarx/navigation/global_planning/AStar.cpp b/source/armarx/navigation/global_planning/AStar.cpp
index eafc77da..67db7790 100644
--- a/source/armarx/navigation/global_planning/AStar.cpp
+++ b/source/armarx/navigation/global_planning/AStar.cpp
@@ -159,7 +159,7 @@ namespace armarx::navigation::global_planning
         ARMARX_TRACE;
 
         // FIXME check if costmap is available
-        algorithm::astar::AStarPlanner planner(*scene.staticScene->costmap);
+        algorithm::astar::AStarPlanner planner(*scene.staticScene->distanceToObstaclesCostmap);
 
         const Eigen::Vector2f goalPos = conv::to2D(goal.translation());
 
diff --git a/source/armarx/navigation/global_planning/SPFA.cpp b/source/armarx/navigation/global_planning/SPFA.cpp
index ed53c513..9491705a 100644
--- a/source/armarx/navigation/global_planning/SPFA.cpp
+++ b/source/armarx/navigation/global_planning/SPFA.cpp
@@ -91,7 +91,7 @@ namespace armarx::navigation::global_planning
         // FIXME check if costmap is available
 
         algorithms::spfa::ShortestPathFasterAlgorithm::Parameters spfaParams;
-        algorithms::spfa::ShortestPathFasterAlgorithm planner(*scene.staticScene->costmap,
+        algorithms::spfa::ShortestPathFasterAlgorithm planner(*scene.staticScene->distanceToObstaclesCostmap,
                                                               spfaParams);
 
         const Eigen::Vector2f goalPos = conv::to2D(goal.translation());
@@ -211,14 +211,15 @@ namespace armarx::navigation::global_planning
         // auto smoothTrajectory = smoothing.smooth(result.trajectory.value());
         // smoothTrajectory.setMaxVelocity(params.linearVelocity);
 
-        const auto costmap = scene.staticScene->costmap.get();
+        ARMARX_CHECK(scene.staticScene->distanceToObstaclesCostmap.has_value());
+        const auto& costmap = scene.staticScene->distanceToObstaclesCostmap.value();
 
 
         for (auto& point : result.trajectory->mutablePoints())
         {
             const float distance = std::min<float>(
                 spfaParams.obstacleMaxDistance,
-                costmap->value(Eigen::Vector2f{point.waypoint.pose.translation().head<2>()})
+                costmap.value(Eigen::Vector2f{point.waypoint.pose.translation().head<2>()})
                     .value_or(0.F));
 
             if (spfaParams.obstacleDistanceCosts)
diff --git a/source/armarx/navigation/memory/client/costmap/Reader.cpp b/source/armarx/navigation/memory/client/costmap/Reader.cpp
index 436fd2b9..ef078b77 100644
--- a/source/armarx/navigation/memory/client/costmap/Reader.cpp
+++ b/source/armarx/navigation/memory/client/costmap/Reader.cpp
@@ -96,7 +96,7 @@ namespace armarx::navigation::memory::client::costmap
 
         if (not coreSegment.hasProviderSegment(query.providerName))
         {
-            ARMARX_WARNING << "Provider segment `" << query.providerName
+            ARMARX_VERBOSE << "Provider segment `" << query.providerName
                            << "` does not exist (yet).";
             return {.costmap = std::nullopt, .status = Result::Status::NoData};
         }
@@ -106,7 +106,7 @@ namespace armarx::navigation::memory::client::costmap
 
         if (providerSegment.empty())
         {
-            ARMARX_WARNING << "No entities.";
+            ARMARX_VERBOSE << "No entities.";
             return {.costmap = std::nullopt,
                     .status = Result::Status::NoData,
                     .errorMessage = "No entities"};
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index b51208e2..308cb088 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -3,10 +3,12 @@
 #include <VirtualRobot/SceneObjectSet.h>
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+#include "ArmarXCore/core/time/Clock.h"
 
 #include "RobotAPI/libraries/armem_robot/types.h"
 
 #include "armarx/navigation/core/types.h"
+#include "armarx/navigation/memory/client/costmap/Reader.h"
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
 #include <armarx/navigation/util/util.h>
 
@@ -33,8 +35,8 @@ namespace armarx::navigation::server::scene_provider
             config.robotName, timestamp, VirtualRobot::RobotIO::RobotDescription::eCollisionModel);
         ARMARX_CHECK_NOT_NULL(scn.robot);
 
-        scn.staticScene = getStaticScene(timestamp);
-        scn.dynamicScene = getDynamicScene(timestamp);
+        scn.staticScene.emplace(getStaticScene(timestamp));
+        scn.dynamicScene.emplace(getDynamicScene(timestamp));
         scn.graph = getSceneGraph(timestamp);
 
         return true; // TODO(fabian.reister): return false if sync fails
@@ -77,28 +79,19 @@ namespace armarx::navigation::server::scene_provider
         ARMARX_CHECK_NOT_NULL(objects);
         ARMARX_INFO << objects->getSize() << " objects in the scene";
 
-        ARMARX_INFO << "Creating costmap";
-        ARMARX_CHECK_NOT_NULL(scn.robot);
-
-        // FIXME: move costmap creation out of this component
-        // FIXME create costmap writer enum: type of costmaps
-        algorithms::CostmapBuilder costmapBuilder(
-            scn.robot,
-            objects,
-            algorithms::Costmap::Parameters{.binaryGrid = false, .cellSize = 100},
-            "Platform-navigation-colmodel");
-
-        const auto costmap = costmapBuilder.create();
-
-        // ARMARX_INFO << "Storing costmap in memory";
-        // costmapWriterPlugin->get().store(
-        //     costmap, "distance_to_obstacles", getName(), armarx::Clock::Now());
-
-        ARMARX_INFO << "Done";
+        ARMARX_INFO << "Retrieving costmap in memory";
+        const memory::client::costmap::Reader::Query query
+        {
+            .providerName = "",
+            .name = "distance_to_obstacles",
+            .timestamp = armarx::Clock::Now()
+        };
 
         ARMARX_TRACE;
+        const auto costmap = srv.costmapReader->query(query);
+        ARMARX_INFO << "Done";
 
-        return {.objects = objects, .costmap = std::make_unique<algorithms::Costmap>(costmap)};
+        return {.objects = objects, .distanceToObstaclesCostmap = costmap.costmap};
     }
 
     core::DynamicScene
-- 
GitLab


From a76fc3cbeef88bc757feecde2de4fea450c21d2d Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 16 Aug 2022 21:36:54 +0200
Subject: [PATCH 099/324] removing mutex

---
 .../navigation/server/introspection/ArvizIntrospector.cpp | 8 --------
 .../navigation/server/introspection/ArvizIntrospector.h   | 2 --
 2 files changed, 10 deletions(-)

diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 694ff174..0fed2680 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -42,8 +42,6 @@ namespace armarx::navigation::server
     void
     ArvizIntrospector::onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result)
     {
-        std::lock_guard g{mtx};
-
         ARMARX_DEBUG << "ArvizIntrospector::onGlobalPlannerResult";
 
         drawGlobalTrajectory(result.trajectory);
@@ -56,8 +54,6 @@ namespace armarx::navigation::server
     void
     ArvizIntrospector::onLocalPlannerResult(const local_planning::LocalPlannerResult& result)
     {
-        std::lock_guard g{mtx};
-
         drawLocalTrajectory(result.trajectory);
         arviz.commit(layers);
     }
@@ -82,8 +78,6 @@ namespace armarx::navigation::server
     void
     ArvizIntrospector::onGoal(const core::Pose& goal)
     {
-        std::lock_guard g{mtx};
-
         auto layer = arviz.layer("goal");
         layer.add(viz::Pose("goal").pose(goal).scale(3));
         arviz.commit(layer);
@@ -94,8 +88,6 @@ namespace armarx::navigation::server
     void
     ArvizIntrospector::onGlobalShortestPath(const std::vector<core::Pose>& path)
     {
-        std::lock_guard g{mtx};
-
         auto layer = arviz.layer("graph_shortest_path");
 
         const auto toPosition = [](const core::Pose& pose) -> core::Position
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index 4681016c..c784e0de 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -80,8 +80,6 @@ namespace armarx::navigation::server
 
         std::vector<viz::Layer> layers;
 
-        std::mutex mtx;
-
         util::Visualization visualization;
     };
 
-- 
GitLab


From ce590cda230b27c64385a8b5cb06489cf1db07f0 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 16 Aug 2022 21:37:08 +0200
Subject: [PATCH 100/324] updating scenario

---
 .../config/RobotStateMemory.cfg               | 109 +-----
 .../config/SimulatorApp.cfg                   |   2 +-
 .../PlatformNavigation/PlatformNavigation.scx |   4 +-
 .../config/ObjectMemory.cfg                   | 115 +------
 .../config/VisionMemory.cfg                   | 113 +------
 .../config/control_memory.cfg                 | 268 +++++++++++++++
 .../distance_to_obstacle_costmap_provider.cfg | 262 +++++++++++++++
 ..._distance_to_obstacle_costmap_provider.cfg | 309 ++++++++++++++++++
 .../config/example_client.cfg                 |  52 ++-
 .../config/navigation_memory.cfg              |  26 +-
 .../PlatformNavigation/config/navigator.cfg   |  52 +--
 11 files changed, 927 insertions(+), 385 deletions(-)
 create mode 100644 scenarios/PlatformNavigation/config/distance_to_obstacle_costmap_provider.cfg
 create mode 100644 scenarios/PlatformNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg

diff --git a/scenarios/NavigationSimulation/config/RobotStateMemory.cfg b/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
index 71c1ac65..8ed364db 100644
--- a/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
+++ b/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
@@ -240,21 +240,12 @@ ArmarX.RobotStateMemory.RobotUnitName = Armar6Unit
 # ArmarX.RobotStateMemory.mem.loc.seg.CoreSegmentName = Localization
 
 
-# ArmarX.RobotStateMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.RobotStateMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            10
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.RobotStateMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.depthImageExtractor.Enabled = true
+# ArmarX.RobotStateMemory.mem.ltm.configuration = {}
 
 
 # ArmarX.RobotStateMemory.mem.ltm.enabled:  
@@ -266,100 +257,6 @@ ArmarX.RobotStateMemory.RobotUnitName = Armar6Unit
 # ArmarX.RobotStateMemory.mem.ltm.enabled = false
 
 
-# ArmarX.RobotStateMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.RobotStateMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.imageExtractor.Enabled = true
-
-
-# ArmarX.RobotStateMemory.mem.ltm.memFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.RobotStateMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.RobotStateMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.pngConverter.Enabled = true
-
-
-# ArmarX.RobotStateMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.RobotStateMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.RobotStateMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.RobotStateMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RobotStateMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.RobotStateMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
-# ArmarX.RobotStateMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateMemory.mem.ltm.storagepath = Default value not mapped.
-
-
 # ArmarX.RobotStateMemory.mem.prop.seg.CoreMaxHistorySize:  Maximal size of the Proprioception entity histories (-1 for infinite).
 #  Attributes:
 #  - Default:            1024
diff --git a/scenarios/NavigationSimulation/config/SimulatorApp.cfg b/scenarios/NavigationSimulation/config/SimulatorApp.cfg
index 8401b4d0..788c12bd 100644
--- a/scenarios/NavigationSimulation/config/SimulatorApp.cfg
+++ b/scenarios/NavigationSimulation/config/SimulatorApp.cfg
@@ -900,7 +900,7 @@ ArmarX.Simulator.SimulationType = kinematics
 #  - Default:            25
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Simulator.StepTimeMS = 10
+ArmarX.Simulator.StepTimeMS = 1
 
 
 # ArmarX.Simulator.WorkingMemoryName:  Name of WorkingMemory
diff --git a/scenarios/PlatformNavigation/PlatformNavigation.scx b/scenarios/PlatformNavigation/PlatformNavigation.scx
index a50c5adc..cc0fcea7 100644
--- a/scenarios/PlatformNavigation/PlatformNavigation.scx
+++ b/scenarios/PlatformNavigation/PlatformNavigation.scx
@@ -6,8 +6,10 @@
 	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
 
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index 5e0858b9..2af60bde 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -513,74 +513,21 @@
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.ObjectMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.ObjectMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm..enabled = false
 
 
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -591,40 +538,6 @@
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -641,15 +554,7 @@
 # ArmarX.ObjectMemory.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  
+# ArmarX.ObjectMemory.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -657,14 +562,6 @@
 # ArmarX.ObjectMemory.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.ObjectMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
diff --git a/scenarios/PlatformNavigation/config/VisionMemory.cfg b/scenarios/PlatformNavigation/config/VisionMemory.cfg
index 9c59a9f6..4c7327ed 100644
--- a/scenarios/PlatformNavigation/config/VisionMemory.cfg
+++ b/scenarios/PlatformNavigation/config/VisionMemory.cfg
@@ -210,74 +210,21 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.VisionMemory.mem.ltm..configuration:  
 #  Attributes:
-#  - Default:            10
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..configuration = ""
 
 
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
+# ArmarX.VisionMemory.mem.ltm..enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
+# ArmarX.VisionMemory.mem.ltm..enabled = false
 
 
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -288,40 +235,6 @@
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
 # ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -364,19 +277,3 @@
 # ArmarX.VisionMemory.pointCloudMaxHistorySize = 20
 
 
-# ArmarX.VisionMemory.tpc.pub.MemoryListener:  Name of the `MemoryListener` topic to publish data to.
-#  Attributes:
-#  - Default:            MemoryUpdates
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.tpc.pub.MemoryListener = MemoryUpdates
-
-
-# ArmarX.VisionMemory.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
-#  Attributes:
-#  - Default:            MemoryUpdates
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.tpc.sub.MemoryListener = MemoryUpdates
-
-
diff --git a/scenarios/PlatformNavigation/config/control_memory.cfg b/scenarios/PlatformNavigation/config/control_memory.cfg
index dd21987d..53efd6fe 100644
--- a/scenarios/PlatformNavigation/config/control_memory.cfg
+++ b/scenarios/PlatformNavigation/config/control_memory.cfg
@@ -2,3 +2,271 @@
 # control_memory properties
 # ==================================================================
 
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.EnableProfiling = false
+
+
+# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ObjectName = ""
+
+
+# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Control
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.MemoryName = Control
+
+
+# ArmarX.ControlMemory.mem.ltm.configuration:  
+#  Attributes:
+#  - Default:            {}
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.configuration = {}
+
+
+# ArmarX.ControlMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.enabled = false
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
+
+
+# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.snapshotToLoad = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/PlatformNavigation/config/distance_to_obstacle_costmap_provider.cfg b/scenarios/PlatformNavigation/config/distance_to_obstacle_costmap_provider.cfg
new file mode 100644
index 00000000..6059c7a8
--- /dev/null
+++ b/scenarios/PlatformNavigation/config/distance_to_obstacle_costmap_provider.cfg
@@ -0,0 +1,262 @@
+# ==================================================================
+# distance_to_obstacle_costmap_provider properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.distance_to_obstacle_costmap_provider.EnableProfiling = false
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.distance_to_obstacle_costmap_provider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectMemoryName = ObjectMemory
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectName = ""
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider = ""
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.p.robotName:  Robot name.
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.p.robotName = Armar6
+
+
diff --git a/scenarios/PlatformNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg b/scenarios/PlatformNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
new file mode 100644
index 00000000..81d7cebf
--- /dev/null
+++ b/scenarios/PlatformNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
@@ -0,0 +1,309 @@
+# ==================================================================
+# dynamic_distance_to_obstacle_costmap_provider properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.EnableProfiling = false
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.ObjectName = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.CoreSegment:  Name of the mapping memory core segment to use.
+#  Attributes:
+#  - Default:            LaserScannerFeatures
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.CoreSegment = LaserScannerFeatures
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.MemoryName:  
+#  Attributes:
+#  - Default:            Vision
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mem.vision.laser_scanner_features.MemoryName = Vision
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.name:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.name = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.providerName:  
+#  Attributes:
+#  - Default:            LaserScannerFeatureExtraction
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.providerName = LaserScannerFeatureExtraction
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.robot.name:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.robot.name = Armar6
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.name:  
+#  Attributes:
+#  - Default:            distance_to_obstacles
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.name = distance_to_obstacles
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName:  
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName = distance_to_obstacle_costmap_provider
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs:  
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs = 100
+
+
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index fa27dee3..eef85301 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -102,14 +102,64 @@
 # ArmarX.ExampleClient.ObjectName = ""
 
 
+# ArmarX.ExampleClient.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
+
+
 # ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
-#  - Default:            Navigator
+#  - Default:            navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
+# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.relativeMovement = 200
+
+
+# ArmarX.ExampleClient.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.robotName = Armar6
+
+
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index d66f1082..f808f777 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -150,37 +150,21 @@
 # ArmarX.NavigationMemory.mem.MemoryName = Navigation
 
 
-# ArmarX.NavigationMemory.mem.ltm..configuration:  
+# ArmarX.NavigationMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm..configuration = ""
+# ArmarX.NavigationMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.NavigationMemory.mem.ltm..enabled:  
+# ArmarX.NavigationMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm..enabled = false
-
-
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.NavigationMemory.mem.ltm.enabled = false
 
 
 # ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 0501ba1e..098e6c14 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -142,18 +142,17 @@
 ArmarX.Navigator.ObjectName = navigator
 
 
-# ArmarX.Navigator.RobotUnitName:  No Description
+# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
 #  Attributes:
-#  - Default:            Armar6Unit
-#  - Case sensitivity:   no
-#  - Required:           no
+#  - Case sensitivity:   yes
+#  - Required:           yes
 ArmarX.Navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Navigator.cmp.PlatformUnit:  Ice object name of the `PlatformUnit` component.
+# ArmarX.Navigator.cmp.PlatformUnit:  No Description
 #  Attributes:
-#  - Default:            PlatformUnit
-#  - Case sensitivity:   yes
+#  - Default:            Armar6PlatformUnit
+#  - Case sensitivity:   no
 #  - Required:           no
 ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 
@@ -182,14 +181,6 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.costmap.Provider:  Name of this provider
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Provider = ""
-
-
 # ArmarX.Navigator.mem.nav.events.CoreSegment:  
 #  Attributes:
 #  - Default:            Events
@@ -286,15 +277,7 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.Navigator.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  
+# ArmarX.Navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -302,14 +285,6 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
@@ -328,20 +303,21 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
+# ArmarX.Navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
 #  Attributes:
-#  - Default:            0.550000012
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.Navigator.p.disableExecutor = false
 
 
-# ArmarX.Navigator.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
+# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
 #  Attributes:
-#  - Default:            MemoryUpdates
+#  - Default:            0.550000012
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.tpc.sub.MemoryListener = MemoryUpdates
+ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
-- 
GitLab


From 1978d4b4810fbd5c3e3a2045f9179bdcb376441d Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 16 Aug 2022 22:10:02 +0200
Subject: [PATCH 101/324] SceneProvider: waiting for distance to obstacle
 costmap to become available in the memory

---
 .../server/scene_provider/SceneProvider.cpp   | 34 ++++++++++++++-----
 .../server/scene_provider/SceneProvider.h     |  3 ++
 2 files changed, 28 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index 308cb088..6ab93b8f 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -3,6 +3,7 @@
 #include <VirtualRobot/SceneObjectSet.h>
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+#include "ArmarXCore/core/logging/Logging.h"
 #include "ArmarXCore/core/time/Clock.h"
 
 #include "RobotAPI/libraries/armem_robot/types.h"
@@ -80,18 +81,33 @@ namespace armarx::navigation::server::scene_provider
         ARMARX_INFO << objects->getSize() << " objects in the scene";
 
         ARMARX_INFO << "Retrieving costmap in memory";
-        const memory::client::costmap::Reader::Query query
-        {
-            .providerName = "",
-            .name = "distance_to_obstacles",
-            .timestamp = armarx::Clock::Now()
-        };
+        const memory::client::costmap::Reader::Query query{.providerName =
+                                                               config.staticCostmapProviderName,
+                                                           .name = config.staticCostmapName,
+                                                           .timestamp = armarx::Clock::Now()};
 
         ARMARX_TRACE;
-        const auto costmap = srv.costmapReader->query(query);
-        ARMARX_INFO << "Done";
 
-        return {.objects = objects, .distanceToObstaclesCostmap = costmap.costmap};
+        const algorithms::Costmap costmap = [&]()
+        {
+            // waiting for static costmap to become available
+            while (true)
+            {
+                if (const memory::client::costmap::Reader::Result costmap =
+                        srv.costmapReader->query(query))
+                {
+                    ARMARX_CHECK(costmap.costmap.has_value());
+                    return costmap.costmap.value();
+                }
+
+                ARMARX_INFO << deactivateSpam(5) << "Static costmap `" << query.name
+                            << "` from provider " << query.providerName << " not available yet.";
+            }
+        }();
+
+        ARMARX_INFO << "Retrieved static costmap";
+
+        return {.objects = objects, .distanceToObstaclesCostmap = costmap};
     }
 
     core::DynamicScene
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.h b/source/armarx/navigation/server/scene_provider/SceneProvider.h
index cd93e072..a71a958f 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.h
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.h
@@ -60,6 +60,9 @@ namespace armarx::navigation::server::scene_provider
         struct Config
         {
             std::string robotName;
+
+            std::string staticCostmapProviderName = "distance_to_obstacle_costmap_provider";
+            std::string staticCostmapName = "distance_to_obstacles";
         };
 
         SceneProvider(const InjectedServices& srv, const Config& config);
-- 
GitLab


From f73113a36c1d33eb98f8b4a31bc1f2dca29f2c62 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Tue, 16 Aug 2022 23:43:35 +0000
Subject: [PATCH 102/324] Create parameter struct in header file for human
 tracking parameters

Not quite sure if it builds though as I edited this in the online editor, should be checked at some time
---
 .../dynamic_scene_provider/HumanTracker.cpp       | 15 +++------------
 .../dynamic_scene_provider/HumanTracker.h         | 11 +++++++++++
 2 files changed, 14 insertions(+), 12 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 4adc1106..a86c684c 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -40,13 +40,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
     void
     HumanTracker::update(const Measurements& measurements)
     {
-        //TODO: proper time to live
-        Duration maxAge = Duration::MilliSeconds(500);
-
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
-            if ((measurements.detectionTime - human.human.detectionTime) >= maxAge)
+            if ((measurements.detectionTime - human.human.detectionTime) >= parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
             }
@@ -135,12 +132,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // associate leftover humans by their distances
         const auto sortedDistances = getSortedDistances(trackedHumans, detectedHumans);
 
-        //TODO max distance parameter
-        float maxDistance = 600;
-
         for (auto& posDistance : sortedDistances)
         {
-            if (posDistance.distance > maxDistance)
+            if (posDistance.distance > parameters.maxAssociationDistance)
             {
                 break;
             }
@@ -161,16 +155,13 @@ namespace armarx::navigation::components::dynamic_scene_provider
         trackedHuman->associated = true;
         detectedHuman->associated = true;
 
-        // TODO alpha parameter
-        float a = 0.7;
-
         float dt =
             (detectedHuman->detectionTime - trackedHuman->human.detectionTime).toSecondsDouble();
         Eigen::Vector2f ds =
             (detectedHuman->pose.translation() - trackedHuman->human.pose.translation());
         Eigen::Vector2f linVelocity = ds / dt;
 
-        Eigen::Vector2f velocity = a * linVelocity + (1 - a) * trackedHuman->human.linearVelocity;
+        Eigen::Vector2f velocity = parameters.velocityAlpha * linVelocity + (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
         trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index e5197d82..b29011b4 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -37,6 +37,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
             bool associated;
         };
 
+        struct Parameters
+        {
+            // the duration after which tracked humans will be erased if no new measurement for this human is found
+            Duration maxTrackingAge = Duration::MilliSeconds(500);
+            // the maximum distance in millimeters of two human measurements to be associated with each other
+            float maxAssociationDistance = 600;
+            // alpha value from interval [0,1] to determine how much the new (and respectively the old) velocity should be weighted
+            float velocityAlpha = 0.7;
+        };
+
         void update(const Measurements& measurements);
 
         std::vector<human::Human> getTrackedHumans() const;
@@ -49,5 +59,6 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     private:
         std::vector<TrackedHuman> trackedHumans;
+        Parameter parameters;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From c668ada987838a18990ccfebd33df4c15a539e15 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 17 Aug 2022 02:15:32 +0200
Subject: [PATCH 103/324] Fix spelling mistake, apply formatting

---
 .../components/dynamic_scene_provider/HumanTracker.cpp     | 7 +++++--
 .../components/dynamic_scene_provider/HumanTracker.h       | 2 +-
 2 files changed, 6 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index a86c684c..59158f28 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -43,7 +43,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
-            if ((measurements.detectionTime - human.human.detectionTime) >= parameters.maxTrackingAge)
+            if ((measurements.detectionTime - human.human.detectionTime) >=
+                parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
             }
@@ -161,7 +162,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
             (detectedHuman->pose.translation() - trackedHuman->human.pose.translation());
         Eigen::Vector2f linVelocity = ds / dt;
 
-        Eigen::Vector2f velocity = parameters.velocityAlpha * linVelocity + (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
+        Eigen::Vector2f velocity =
+            parameters.velocityAlpha * linVelocity +
+            (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
         trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index b29011b4..9146a798 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -59,6 +59,6 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     private:
         std::vector<TrackedHuman> trackedHumans;
-        Parameter parameters;
+        Parameters parameters;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 54043b951ef90ae62283b734ae6346b99ace27ca Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 17 Aug 2022 02:29:27 +0200
Subject: [PATCH 104/324] Add aron conversion functions to type structs

---
 source/armarx/navigation/human/types.cpp | 44 ++++++++++++++++++++++++
 source/armarx/navigation/human/types.h   |  8 +++++
 2 files changed, 52 insertions(+)

diff --git a/source/armarx/navigation/human/types.cpp b/source/armarx/navigation/human/types.cpp
index 6296ba6e..854b0d15 100644
--- a/source/armarx/navigation/human/types.cpp
+++ b/source/armarx/navigation/human/types.cpp
@@ -1,5 +1,8 @@
 #include "types.h"
 
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
+#include <armarx/navigation/human/aron_conversions.h>
+
 namespace armarx::navigation::human
 {
     core::Pose2D
@@ -11,4 +14,45 @@ namespace armarx::navigation::human
         return estimation;
     }
 
+    aron::data::DictPtr
+    Human::toAron() const
+    {
+        arondto::Human dto;
+        human::toAron(dto, *this);
+        return dto.toAron();
+    }
+
+    Human
+    Human::FromAron(const aron::data::DictPtr& dict)
+    {
+        ARMARX_CHECK_NOT_NULL(dict);
+        arondto::Human dto;
+        dto.fromAron(dict);
+
+        Human bo;
+        fromAron(dto, bo);
+        return bo;
+    }
+
+
+    aron::data::DictPtr
+    HumanGroup::toAron() const
+    {
+        arondto::HumanGroup dto;
+        human::toAron(dto, *this);
+        return dto.toAron();
+    }
+
+    HumanGroup
+    HumanGroup::FromAron(const aron::data::DictPtr& dict)
+    {
+        ARMARX_CHECK_NOT_NULL(dict);
+        arondto::HumanGroup dto;
+        dto.fromAron(dict);
+
+        HumanGroup bo;
+        fromAron(dto, bo);
+        return bo;
+    }
+
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 625fa764..e80df033 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -23,6 +23,8 @@
 
 #include <ArmarXCore/core/time.h>
 
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/human/shapes.h>
 
@@ -35,6 +37,9 @@ namespace armarx::navigation::human
         DateTime detectionTime;
 
         core::Pose2D estimateAt(const DateTime& time) const;
+
+        aron::data::DictPtr toAron() const;
+        static Human FromAron(const aron::data::DictPtr& dict);
     };
 
     struct HumanGroup
@@ -42,6 +47,9 @@ namespace armarx::navigation::human
         shapes::Polygon shape;
         std::vector<Human> humans;
         DateTime detectionTime;
+
+        aron::data::DictPtr toAron() const;
+        static HumanGroup FromAron(const aron::data::DictPtr& dict);
     };
 
     struct ProxemicZone
-- 
GitLab


From 80d2baa4b8c98015e348e91b3743ffe20f28e1b7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:24:05 +0200
Subject: [PATCH 105/324] scenario HumanAwareNavigation update

---
 .../HumanAwareNavigation.scx                  |   2 +
 .../config/HumanMemoryApp.cfg                 | 368 ++++++++++++++++++
 .../config/control_memory.cfg                 |  26 +-
 .../distance_to_obstacle_costmap_provider.cfg | 262 +++++++++++++
 ..._distance_to_obstacle_costmap_provider.cfg |  39 ++
 .../config/dynamic_scene_provider.cfg         |  34 +-
 .../config/navigation_memory.cfg              |  20 +-
 .../HumanAwareNavigation/config/navigator.cfg |   8 -
 8 files changed, 711 insertions(+), 48 deletions(-)
 create mode 100644 scenarios/HumanAwareNavigation/config/HumanMemoryApp.cfg
 create mode 100644 scenarios/HumanAwareNavigation/config/distance_to_obstacle_costmap_provider.cfg

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
index 3c4d6c5a..570cffa4 100644
--- a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -11,5 +11,7 @@
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="dynamic_scene_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="HumanMemoryApp" instance="" package="VisionX" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
 
diff --git a/scenarios/HumanAwareNavigation/config/HumanMemoryApp.cfg b/scenarios/HumanAwareNavigation/config/HumanMemoryApp.cfg
new file mode 100644
index 00000000..28099ebc
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/HumanMemoryApp.cfg
@@ -0,0 +1,368 @@
+# ==================================================================
+# HumanMemoryApp properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.HumanMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.HumanMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.HumanMemory.DebugObserverTopicName:  Name of the topic the DebugObserver listens on
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.DebugObserverTopicName = DebugObserver
+
+
+# ArmarX.HumanMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.EnableProfiling = false
+
+
+# ArmarX.HumanMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.HumanMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.HumanMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ObjectName = ""
+
+
+# ArmarX.HumanMemory.face.seg.CoreMaxHistorySize:  Maximal size of the FaceRecognition entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            64
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.face.seg.CoreMaxHistorySize = 64
+
+
+# ArmarX.HumanMemory.face.seg.CoreSegmentName:  Name of the FaceRecognition core segment.
+#  Attributes:
+#  - Default:            FaceRecognition
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.face.seg.CoreSegmentName = FaceRecognition
+
+
+# ArmarX.HumanMemory.ident.seg.CoreMaxHistorySize:  Maximal size of the Identification entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ident.seg.CoreMaxHistorySize = -1
+
+
+# ArmarX.HumanMemory.ident.seg.CoreSegmentName:  Name of the Identification core segment.
+#  Attributes:
+#  - Default:            Identification
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ident.seg.CoreSegmentName = Identification
+
+
+# ArmarX.HumanMemory.instanceseg.CoreMaxHistorySize:  Maximal size of the PersonInstance entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            32
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.instanceseg.CoreMaxHistorySize = 32
+
+
+# ArmarX.HumanMemory.instanceseg.CoreSegmentName:  Name of the PersonInstance core segment.
+#  Attributes:
+#  - Default:            PersonInstance
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.instanceseg.CoreSegmentName = PersonInstance
+
+
+# ArmarX.HumanMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.MemoryName = Human
+
+
+# ArmarX.HumanMemory.mem.ltm.configuration:  
+#  Attributes:
+#  - Default:            {}
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.ltm.configuration = {}
+
+
+# ArmarX.HumanMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.mem.ltm.enabled = false
+
+
+# ArmarX.HumanMemory.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.HumanMemory.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.HumanMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.HumanMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.HumanMemory.pose.seg.CoreMaxHistorySize:  Maximal size of the Pose entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            256
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.pose.seg.CoreMaxHistorySize = 256
+
+
+# ArmarX.HumanMemory.pose.seg.CoreSegmentName:  Name of the Pose core segment.
+#  Attributes:
+#  - Default:            Pose
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.pose.seg.CoreSegmentName = Pose
+
+
+# ArmarX.HumanMemory.profile.pk.load:  Load profiles from prior knowledge on startup.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.profile.pk.load = true
+
+
+# ArmarX.HumanMemory.profile.pk.packageName:  ArmarX package to load human profiles from.
+#  Attributes:
+#  - Default:            PriorKnowledgeData
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.pk.packageName = PriorKnowledgeData
+
+
+# ArmarX.HumanMemory.profile.seg.CoreMaxHistorySize:  Maximal size of the Profile entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            64
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.seg.CoreMaxHistorySize = 64
+
+
+# ArmarX.HumanMemory.profile.seg.CoreSegmentName:  Name of the Profile core segment.
+#  Attributes:
+#  - Default:            Profile
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.seg.CoreSegmentName = Profile
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/HumanAwareNavigation/config/control_memory.cfg b/scenarios/HumanAwareNavigation/config/control_memory.cfg
index 4aad1c46..53efd6fe 100644
--- a/scenarios/HumanAwareNavigation/config/control_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/control_memory.cfg
@@ -92,37 +92,21 @@
 # ArmarX.ControlMemory.mem.MemoryName = Control
 
 
-# ArmarX.ControlMemory.mem.ltm..configuration:  
+# ArmarX.ControlMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ControlMemory.mem.ltm..configuration = ""
+# ArmarX.ControlMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.ControlMemory.mem.ltm..enabled:  
+# ArmarX.ControlMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ControlMemory.mem.ltm..enabled = false
-
-
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ControlMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ControlMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.ControlMemory.mem.ltm.enabled = false
 
 
 # ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
diff --git a/scenarios/HumanAwareNavigation/config/distance_to_obstacle_costmap_provider.cfg b/scenarios/HumanAwareNavigation/config/distance_to_obstacle_costmap_provider.cfg
new file mode 100644
index 00000000..6059c7a8
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/distance_to_obstacle_costmap_provider.cfg
@@ -0,0 +1,262 @@
+# ==================================================================
+# distance_to_obstacle_costmap_provider properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.distance_to_obstacle_costmap_provider.EnableProfiling = false
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.distance_to_obstacle_costmap_provider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectMemoryName = ObjectMemory
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.ObjectName = ""
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.nav.costmap.Provider = ""
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.distance_to_obstacle_costmap_provider.p.robotName:  Robot name.
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.distance_to_obstacle_costmap_provider.p.robotName = Armar6
+
+
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
index 27479d20..565bb501 100644
--- a/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
+++ b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
@@ -260,6 +260,45 @@
 # ArmarX.dynamic_distance_to_obstacle_costmap_provider.mns.MemoryNameSystemName = MemoryNameSystem
 
 
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.name:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.name = ""
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.providerName:  
+#  Attributes:
+#  - Default:            LaserScannerFeatureExtraction
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.laserScannerFeatures.providerName = LaserScannerFeatureExtraction
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.robot.name:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.robot.name = Armar6
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.name:  
+#  Attributes:
+#  - Default:            distance_to_obstacles
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.name = distance_to_obstacles
+
+
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName:  
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName = ::_NOT_SET_::
+
+
 # ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs:  
 #  Attributes:
 #  - Default:            100
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
index 98cd68b7..c632df10 100644
--- a/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
+++ b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
@@ -191,7 +191,7 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Undefined
+ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Verbose
 
 
 # ArmarX.dynamic_scene_provider.ObjectMemoryName:  Name of the object memory.
@@ -242,6 +242,30 @@
 # ArmarX.dynamic_scene_provider.mem.nav.costmap.Memory = Navigation
 
 
+# ArmarX.dynamic_scene_provider.mem.nav.human.CoreSegment:  
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.nav.human.CoreSegment = Human
+
+
+# ArmarX.dynamic_scene_provider.mem.nav.human.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.nav.human.Memory = Navigation
+
+
+# ArmarX.dynamic_scene_provider.mem.nav.human.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.mem.nav.human.Provider = ""
+
+
 # ArmarX.dynamic_scene_provider.mem.robot_state.Memory:  
 #  Attributes:
 #  - Default:            RobotState
@@ -308,6 +332,14 @@
 # ArmarX.dynamic_scene_provider.mns.MemoryNameSystemName = MemoryNameSystem
 
 
+# ArmarX.dynamic_scene_provider.p.humanPoseProvider:  
+#  Attributes:
+#  - Default:            OpenNIPointCloudProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.dynamic_scene_provider.p.humanPoseProvider = OpenNIPointCloudProvider
+
+
 # ArmarX.dynamic_scene_provider.p.laserScannerFeatures.name:  
 #  Attributes:
 #  - Default:            ""
diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index c024b256..38cf4a09 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -152,10 +152,10 @@ ArmarX.NavigationMemory.MinimumLoggingLevel = Verbose
 
 # ArmarX.NavigationMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.configuration = ""
+# ArmarX.NavigationMemory.mem.ltm.configuration = {}
 
 
 # ArmarX.NavigationMemory.mem.ltm.enabled:  
@@ -167,22 +167,6 @@ ArmarX.NavigationMemory.MinimumLoggingLevel = Verbose
 # ArmarX.NavigationMemory.mem.ltm.enabled = false
 
 
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.storagepath = Default value not mapped.
-
-
 # ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index 0484c3f0..5d038290 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -181,14 +181,6 @@ ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.costmap.Provider:  Name of this provider
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Provider = ""
-
-
 # ArmarX.Navigator.mem.nav.events.CoreSegment:  
 #  Attributes:
 #  - Default:            Events
-- 
GitLab


From 2be9abaf22bce090e709ecef8bc166b1b76e7e24 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:25:15 +0200
Subject: [PATCH 106/324] memory: humans and groups client reader and writer

---
 source/armarx/navigation/human/types.h        |   8 +-
 .../armarx/navigation/memory/CMakeLists.txt   |   5 +
 .../navigation/memory/client/human/Reader.cpp | 236 ++++++++++++++++++
 .../navigation/memory/client/human/Reader.h   |  97 +++++++
 .../navigation/memory/client/human/Writer.cpp | 133 ++++++++++
 .../navigation/memory/client/human/Writer.h   |  69 +++++
 source/armarx/navigation/memory/constants.h   |   1 +
 7 files changed, 548 insertions(+), 1 deletion(-)
 create mode 100644 source/armarx/navigation/memory/client/human/Reader.cpp
 create mode 100644 source/armarx/navigation/memory/client/human/Reader.h
 create mode 100644 source/armarx/navigation/memory/client/human/Writer.cpp
 create mode 100644 source/armarx/navigation/memory/client/human/Writer.h

diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 625fa764..b447df92 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -37,13 +37,19 @@ namespace armarx::navigation::human
         core::Pose2D estimateAt(const DateTime& time) const;
     };
 
+    using Humans = std::vector<Human>;
+
+
     struct HumanGroup
     {
         shapes::Polygon shape;
-        std::vector<Human> humans;
+        Humans humans;
         DateTime detectionTime;
     };
 
+    using HumanGroups = std::vector<HumanGroup>;
+
+
     struct ProxemicZone
     {
         core::Pose2D pose;
diff --git a/source/armarx/navigation/memory/CMakeLists.txt b/source/armarx/navigation/memory/CMakeLists.txt
index 8f4483b1..eba21c61 100644
--- a/source/armarx/navigation/memory/CMakeLists.txt
+++ b/source/armarx/navigation/memory/CMakeLists.txt
@@ -8,6 +8,8 @@ armarx_add_library(memory
         client/events/Writer.cpp
         client/costmap/Writer.cpp
         client/costmap/Reader.cpp
+        client/human/Reader.cpp
+        client/human/Writer.cpp
         # ./client/events/Reader.cpp
     HEADERS
         memory.h
@@ -18,6 +20,8 @@ armarx_add_library(memory
         client/events/Writer.h
         client/costmap/Writer.h
         client/costmap/Reader.h
+        client/human/Reader.h
+        client/human/Writer.h
         # ./client/events/Reader.h
     DEPENDENCIES
         ArmarXCoreInterfaces
@@ -27,6 +31,7 @@ armarx_add_library(memory
         armarx_navigation::algorithms
         armarx_navigation::graph
         armarx_navigation::location
+        armarx_navigation::teb_human
 )
 
 armarx_add_test(memory_test
diff --git a/source/armarx/navigation/memory/client/human/Reader.cpp b/source/armarx/navigation/memory/client/human/Reader.cpp
new file mode 100644
index 00000000..e3bee9f2
--- /dev/null
+++ b/source/armarx/navigation/memory/client/human/Reader.cpp
@@ -0,0 +1,236 @@
+#include "Reader.h"
+
+#include <ArmarXCore/core/exceptions/LocalException.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
+#include <RobotAPI/interface/armem/server/ReadingMemoryInterface.h>
+#include <RobotAPI/libraries/armem/client/Query.h>
+#include <RobotAPI/libraries/armem/client/Reader.h>
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/client/query/selectors.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/util/util.h>
+#include <RobotAPI/libraries/aron/core/Exception.h>
+#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
+
+#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/algorithms/aron_conversions.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
+#include <armarx/navigation/human/aron_conversions.h>
+#include <armarx/navigation/memory/constants.h>
+
+namespace armarx::navigation::memory::client::human
+{
+    Reader::~Reader() = default;
+
+    armarx::armem::client::query::Builder
+    Reader::buildHumansQuery(const Query& query) const
+    {
+        armarx::armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties().coreSegmentName)
+        .providerSegments().withName(query.providerName)
+        .entities().withName("humans")
+        .snapshots().beforeOrAtTime(query.timestamp);
+        // clang-format on
+
+        return qb;
+    }
+
+    armarx::armem::client::query::Builder
+    Reader::buildHumanGroupsQuery(const Query& query) const
+    {
+        armarx::armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties().coreSegmentName)
+        .providerSegments().withName(query.providerName)
+        .entities().withName("groups")
+        .snapshots().beforeOrAtTime(query.timestamp);
+        // clang-format on
+
+        return qb;
+    }
+
+
+    std::string
+    Reader::propertyPrefix() const
+    {
+        return "mem.nav.human.";
+    }
+
+    armarx::armem::client::util::SimpleReaderBase::Properties
+    Reader::defaultProperties() const
+    {
+        return {.memoryName = memory::constants::NavigationMemoryName,
+                .coreSegmentName = memory::constants::HumanCoreSegmentName};
+    }
+
+    navigation::human::Humans
+    asHumans(const armem::wm::ProviderSegment& providerSegment)
+    {
+        navigation::human::Humans humans;
+
+        ARMARX_CHECK(not providerSegment.empty()) << "No entities";
+        ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
+
+        providerSegment.forEachEntity(
+            [&humans](const armem::wm::Entity& entity)
+            {
+                const auto& entitySnapshot = entity.getLatestSnapshot();
+                ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
+
+                entitySnapshot.forEachInstance(
+                    [&humans](const armem::wm::EntityInstance& entityInstance)
+                    {
+                        const auto dto =
+                            navigation::human::arondto::Human::FromAron(entityInstance.data());
+
+                        navigation::human::Human human;
+                        fromAron(dto, human);
+                        humans.push_back(human);
+                    });
+            });
+
+        return humans;
+    }
+
+    navigation::human::HumanGroups
+    asGroups(const armem::wm::ProviderSegment& providerSegment)
+    {
+        navigation::human::HumanGroups humans;
+
+        ARMARX_CHECK(not providerSegment.empty()) << "No entities";
+        ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
+
+        providerSegment.forEachEntity(
+            [&humans](const armem::wm::Entity& entity)
+            {
+                const auto& entitySnapshot = entity.getLatestSnapshot();
+                ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
+
+                entitySnapshot.forEachInstance(
+                    [&humans](const armem::wm::EntityInstance& entityInstance)
+                    {
+                        const auto dto =
+                            navigation::human::arondto::HumanGroup::FromAron(entityInstance.data());
+
+                        navigation::human::HumanGroup human;
+                        fromAron(dto, human);
+                        humans.push_back(human);
+                    });
+            });
+
+        return humans;
+    }
+
+    Reader::HumanGroupResult
+    Reader::queryHumanGroups(const Query& query) const
+    {
+        const auto qb = buildHumansQuery(query);
+
+        ARMARX_DEBUG << "[MappingDataReader] query ... ";
+
+        const armem::client::QueryResult qResult = memoryReader().query(qb.buildQueryInput());
+
+        ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
+
+        if (not qResult.success)
+        {
+            ARMARX_WARNING << "Failed to query data from memory: " << qResult.errorMessage;
+            return {.groups = {},
+                    .status = HumanGroupResult::Status::Error,
+                    .errorMessage = qResult.errorMessage};
+        }
+
+        const auto coreSegment = qResult.memory.getCoreSegment(properties().coreSegmentName);
+
+        if (not coreSegment.hasProviderSegment(query.providerName))
+        {
+            ARMARX_VERBOSE << "Provider segment `" << query.providerName
+                           << "` does not exist (yet).";
+            return {.groups = {}, .status = HumanGroupResult::Status::NoData};
+        }
+
+        const armem::wm::ProviderSegment& providerSegment =
+            coreSegment.getProviderSegment(query.providerName);
+
+        if (providerSegment.empty())
+        {
+            ARMARX_VERBOSE << "No entities.";
+            return {.groups = {},
+                    .status = HumanGroupResult::Status::NoData,
+                    .errorMessage = "No entities"};
+        }
+
+        try
+        {
+            return HumanGroupResult{.groups = asGroups(providerSegment),
+                                    .status = HumanGroupResult::Status::Success};
+        }
+        catch (...)
+        {
+            return HumanGroupResult{.groups = {},
+                                    .status = HumanGroupResult::Status::Error,
+                                    .errorMessage = GetHandledExceptionString()};
+        }
+    }
+
+
+    Reader::HumanResult
+    Reader::queryHumans(const Query& query) const
+    {
+        const auto qb = buildHumansQuery(query);
+
+        ARMARX_DEBUG << "[MappingDataReader] query ... ";
+
+        const armem::client::QueryResult qResult = memoryReader().query(qb.buildQueryInput());
+
+        ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
+
+        if (not qResult.success)
+        {
+            ARMARX_WARNING << "Failed to query data from memory: " << qResult.errorMessage;
+            return {.humans = {},
+                    .status = HumanResult::Status::Error,
+                    .errorMessage = qResult.errorMessage};
+        }
+
+        const auto coreSegment = qResult.memory.getCoreSegment(properties().coreSegmentName);
+
+        if (not coreSegment.hasProviderSegment(query.providerName))
+        {
+            ARMARX_VERBOSE << "Provider segment `" << query.providerName
+                           << "` does not exist (yet).";
+            return {.humans = {}, .status = HumanResult::Status::NoData};
+        }
+
+        const armem::wm::ProviderSegment& providerSegment =
+            coreSegment.getProviderSegment(query.providerName);
+
+        if (providerSegment.empty())
+        {
+            ARMARX_VERBOSE << "No entities.";
+            return {
+                .humans = {}, .status = HumanResult::Status::NoData, .errorMessage = "No entities"};
+        }
+
+        try
+        {
+            return HumanResult{.humans = asHumans(providerSegment),
+                               .status = HumanResult::Status::Success};
+        }
+        catch (...)
+        {
+            return HumanResult{.humans = {},
+                               .status = HumanResult::Status::Error,
+                               .errorMessage = GetHandledExceptionString()};
+        }
+    }
+
+} // namespace armarx::navigation::memory::client::human
diff --git a/source/armarx/navigation/memory/client/human/Reader.h b/source/armarx/navigation/memory/client/human/Reader.h
new file mode 100644
index 00000000..2e693237
--- /dev/null
+++ b/source/armarx/navigation/memory/client/human/Reader.h
@@ -0,0 +1,97 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <mutex>
+
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/client/util/SimpleReaderBase.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
+
+#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+
+namespace armarx::navigation::memory::client::human
+{
+
+    class Reader : virtual public armarx::armem::client::util::SimpleReaderBase
+    {
+    public:
+        using armarx::armem::client::util::SimpleReaderBase::SimpleReaderBase;
+        ~Reader() override;
+
+        struct Query
+        {
+            std::string providerName;
+            armem::Time timestamp;
+        };
+
+        struct HumanResult
+        {
+            armarx::navigation::human::Humans humans;
+
+            enum Status
+            {
+                Success,
+                NoData,
+                Error
+            } status;
+
+            std::string errorMessage = "";
+
+            operator bool() const noexcept
+            {
+                return status == Status::Success;
+            }
+        };
+
+        struct HumanGroupResult
+        {
+            armarx::navigation::human::HumanGroups groups;
+
+            enum Status
+            {
+                Success,
+                NoData,
+                Error
+            } status;
+
+            std::string errorMessage = "";
+
+            operator bool() const noexcept
+            {
+                return status == Status::Success;
+            }
+        };
+
+        HumanResult queryHumans(const Query& query) const;
+        HumanGroupResult queryHumanGroups(const Query& query) const;
+
+    protected:
+        ::armarx::armem::client::query::Builder buildHumansQuery(const Query& query) const;
+        ::armarx::armem::client::query::Builder buildHumanGroupsQuery(const Query& query) const;
+
+        std::string propertyPrefix() const override;
+        Properties defaultProperties() const override;
+    };
+
+} // namespace armarx::navigation::memory::client::human
diff --git a/source/armarx/navigation/memory/client/human/Writer.cpp b/source/armarx/navigation/memory/client/human/Writer.cpp
new file mode 100644
index 00000000..c38c2ac7
--- /dev/null
+++ b/source/armarx/navigation/memory/client/human/Writer.cpp
@@ -0,0 +1,133 @@
+#include "Writer.h"
+
+#include <iterator>
+
+#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
+#include <armarx/navigation/algorithms/aron_conversions.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
+#include <armarx/navigation/memory/constants.h>
+#include <armarx/navigation/human/aron_conversions.h>
+
+
+namespace armarx::navigation::memory::client::human
+{
+    Writer::~Writer() = default;
+
+    bool
+    Writer::store(const armarx::navigation::human::Humans& humans,
+                  //   const std::string& name,
+                  const std::string& providerName,
+                  const armem::Time& timestamp)
+    {
+        std::lock_guard g{memoryWriterMutex()};
+
+        const auto result =
+            memoryWriter().addSegment(memory::constants::HumanCoreSegmentName, providerName);
+
+        if (not result.success)
+        {
+            ARMARX_ERROR << result.errorMessage;
+
+            // TODO(fabian.reister): message
+            return false;
+        }
+
+        const auto providerId = armem::MemoryID(result.segmentID);
+        const auto entityID = providerId.withEntityName("humans").withTimestamp(timestamp);
+
+        armem::EntityUpdate update;
+        update.entityID = entityID;
+
+        std::transform(humans.begin(),
+                       humans.end(),
+                       std::back_inserter(update.instancesData),
+                       [](const navigation::human::Human& human) -> armarx::aron::data::DictPtr {
+                            navigation::human::arondto::Human dto;
+                            toAron(dto, human);
+
+                            return dto.toAron();
+                       });
+
+
+        update.timeCreated = timestamp;
+
+        ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
+        armem::EntityUpdateResult updateResult = memoryWriter().commit(update);
+
+        ARMARX_DEBUG << updateResult;
+
+        if (not updateResult.success)
+        {
+            ARMARX_ERROR << updateResult.errorMessage;
+        }
+
+        return updateResult.success;
+    }
+
+    bool
+    Writer::store(const armarx::navigation::human::HumanGroups& groups,
+                  //   const std::string& name,
+                  const std::string& providerName,
+                  const armem::Time& timestamp)
+    {
+        std::lock_guard g{memoryWriterMutex()};
+
+        const auto result =
+            memoryWriter().addSegment(memory::constants::HumanCoreSegmentName, providerName);
+
+        if (not result.success)
+        {
+            ARMARX_ERROR << result.errorMessage;
+
+            // TODO(fabian.reister): message
+            return false;
+        }
+
+        const auto providerId = armem::MemoryID(result.segmentID);
+        const auto entityID = providerId.withEntityName("groups").withTimestamp(timestamp);
+
+        armem::EntityUpdate update;
+        update.entityID = entityID;
+
+        std::transform(groups.begin(),
+                       groups.end(),
+                       std::back_inserter(update.instancesData),
+                       [](const navigation::human::HumanGroup& group) -> armarx::aron::data::DictPtr {
+                            navigation::human::arondto::HumanGroup dto;
+                            toAron(dto, group);
+
+                            return dto.toAron();
+                       });
+
+
+        update.timeCreated = timestamp;
+
+        ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
+        armem::EntityUpdateResult updateResult = memoryWriter().commit(update);
+
+        ARMARX_DEBUG << updateResult;
+
+        if (not updateResult.success)
+        {
+            ARMARX_ERROR << updateResult.errorMessage;
+        }
+
+        return updateResult.success;
+    }
+
+    std::string
+    Writer::propertyPrefix() const
+    {
+        return "mem.nav.human.";
+    }
+
+    armarx::armem::client::util::SimpleWriterBase::SimpleWriterBase::Properties
+    Writer::defaultProperties() const
+    {
+        return SimpleWriterBase::Properties{.memoryName = memory::constants::NavigationMemoryName,
+                                            .coreSegmentName =
+                                                memory::constants::HumanCoreSegmentName};
+    }
+
+} // namespace armarx::navigation::memory::client::human
diff --git a/source/armarx/navigation/memory/client/human/Writer.h b/source/armarx/navigation/memory/client/human/Writer.h
new file mode 100644
index 00000000..b224149c
--- /dev/null
+++ b/source/armarx/navigation/memory/client/human/Writer.h
@@ -0,0 +1,69 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI::ArmarXObjects::
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <mutex>
+
+#include <RobotAPI/libraries/armem/client/util/SimpleWriterBase.h>
+#include <RobotAPI/libraries/armem_vision/types.h>
+
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/human/types.h>
+
+namespace armarx::navigation::memory::client::human
+{
+
+    /**
+    * @defgroup Component-ExampleClient ExampleClient
+    * @ingroup RobotAPI-Components
+    * A description of the component ExampleClient.
+    *
+    * @class ExampleClient
+    * @ingroup Component-ExampleClient
+    * @brief Brief description of class ExampleClient.
+    *
+    * Detailed description of class ExampleClient.
+    */
+    class Writer : virtual public armarx::armem::client::util::SimpleWriterBase
+    {
+    public:
+        using armarx::armem::client::util::SimpleWriterBase::SimpleWriterBase;
+        ~Writer() override;
+
+        bool store(const armarx::navigation::human::Humans& humans,
+                //    const std::string& name,
+                   const std::string& providerName,
+                   const armem::Time& timestamp);
+
+        bool store(const armarx::navigation::human::HumanGroups& groups,
+                //    const std::string& name,
+                   const std::string& providerName,
+                   const armem::Time& timestamp);
+
+    protected:
+        std::string propertyPrefix() const override;
+        Properties defaultProperties() const override;
+    };
+
+
+} // namespace armarx::navigation::memory::client::human
diff --git a/source/armarx/navigation/memory/constants.h b/source/armarx/navigation/memory/constants.h
index fe57b76c..2b3364a8 100644
--- a/source/armarx/navigation/memory/constants.h
+++ b/source/armarx/navigation/memory/constants.h
@@ -32,5 +32,6 @@ namespace armarx::navigation::memory::constants
     inline const std::string GraphCoreSegmentName = "Graph";
     inline const std::string LocationCoreSegmentName = "Location";
     inline const std::string CostmapCoreSegmentName = "Costmap";
+    inline const std::string HumanCoreSegmentName = "Human";
 
 } // namespace armarx::navigation::memory::constants
-- 
GitLab


From 3742c7965a3419125c03cc0f9ad5fc5530e583df Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:26:23 +0200
Subject: [PATCH 107/324] cmake: adding comment to rename teb_human once the
 CMake migration is complete

---
 source/armarx/navigation/human/CMakeLists.txt | 3 +++
 1 file changed, 3 insertions(+)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index fd5fb36c..76a44730 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -1,3 +1,6 @@
+# TODO remove teb_ once the ArmarX CMake migration is complete.
+# Note: "human" is a library defined in VisionX
+
 armarx_add_aron_library(teb_human_aron
     ARON_FILES
         aron/Human.xml
-- 
GitLab


From e9de6c98d04b2d090b0127f8923fc7723989d69e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:26:57 +0200
Subject: [PATCH 108/324] dummy implementation of HumanTracker

---
 .../dynamic_scene_provider/HumanTracker.cpp    | 18 ++++++++++++++++++
 1 file changed, 18 insertions(+)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 4adc1106..7dd61dc6 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -3,6 +3,7 @@
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
+#include "armarx/navigation/human/types.h"
 #include <armarx/navigation/conversions/eigen.h>
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
@@ -40,6 +41,23 @@ namespace armarx::navigation::components::dynamic_scene_provider
     void
     HumanTracker::update(const Measurements& measurements)
     {
+
+        trackedHumans.clear();
+
+        for (const armem::human::HumanPose& measurement : measurements.humanPoses)
+        {
+            human::Human human{
+                .pose = conv::to2D(
+                    core::Pose(Eigen::Translation3f(measurement.keypoints.begin()->second.positionGlobal->toEigen()))),
+                .linearVelocity = Eigen::Vector2f::Zero(),
+                .detectionTime = 0};
+
+            trackedHumans.push_back(TrackedHuman{
+                .human = human, .trackingId = std::to_string(trackedHumans.size()), .associated = true});
+        }
+
+        return; // FIXME remove section above
+
         //TODO: proper time to live
         Duration maxAge = Duration::MilliSeconds(500);
 
-- 
GitLab


From 872c4c50c2ef3100cd85f61f1b7a076c2f40f163 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:27:21 +0200
Subject: [PATCH 109/324] navigation memory: new core segments + visu

---
 .../NavigationMemory/CMakeLists.txt           |  1 +
 .../NavigationMemory/NavigationMemory.cpp     | 12 +++-
 .../NavigationMemory/NavigationMemory.h       |  1 +
 .../components/NavigationMemory/Visu.cpp      | 68 ++++++++++++++++++-
 .../components/NavigationMemory/Visu.h        |  6 +-
 5 files changed, 85 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
index 3f8da95e..5f88e9cf 100644
--- a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
+++ b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
@@ -18,6 +18,7 @@ armarx_add_component(navigation_memory
         armarx_navigation::graph
         armarx_navigation::location
         armarx_navigation::algorithms
+        armarx_navigation::teb_human
 
     SOURCES
         NavigationMemory.cpp
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
index a18764b0..97d8fa36 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
@@ -48,6 +48,7 @@
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
 #include <armarx/navigation/core/aron/Trajectory.aron.generated.h>
 #include <armarx/navigation/core/aron/Twist.aron.generated.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
 #include <armarx/navigation/graph/constants.h>
 #include <armarx/navigation/location/constants.h>
 
@@ -127,6 +128,11 @@ namespace armarx::navigation
         workingMemory().addCoreSegment(navigation::graph::coreSegmentID.coreSegmentName,
                                        navigation::core::arondto::Graph::ToAronType());
 
+        workingMemory().addCoreSegment(memory::constants::HumanCoreSegmentName,
+                                       navigation::human::arondto::Human::ToAronType());
+
+        // workingMemory().addCoreSegment(memory::constants::HumanGroupCoreSegmentName,
+        //                                navigation::human::arondto::Human::ToAronType());
 
         if (not properties.snapshotToLoad.empty())
         {
@@ -432,7 +438,8 @@ namespace armarx::navigation
         memory::Visu visu{arviz,
                           workingMemory().getCoreSegment(navigation::location::coreSegmentID),
                           workingMemory().getCoreSegment(navigation::graph::coreSegmentID),
-                          workingMemory().getCoreSegment(memory::constants::CostmapCoreSegmentName)};
+                          workingMemory().getCoreSegment(memory::constants::CostmapCoreSegmentName),
+                          workingMemory().getCoreSegment(memory::constants::HumanCoreSegmentName)};
 
 
         Properties::LocationGraph p;
@@ -462,6 +469,9 @@ namespace armarx::navigation
             // Costmaps
             visu.drawCostmaps(layers, p.visuCostmaps);
 
+            // Humans
+            visu.drawHumans(layers, p.visuHumans);
+
             arviz.commit(layers);
 
             metronome.waitForNextTick();
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
index c67da7fc..e34aa21e 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
+++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
@@ -97,6 +97,7 @@ namespace armarx::navigation
                 bool visuLocations = true;
                 bool visuGraphEdges = true;
                 bool visuCostmaps = true;
+                bool visuHumans = true;
                 
                 float visuFrequency = 2;
             };
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.cpp b/source/armarx/navigation/components/NavigationMemory/Visu.cpp
index 73df72de..f3ae9cbc 100644
--- a/source/armarx/navigation/components/NavigationMemory/Visu.cpp
+++ b/source/armarx/navigation/components/NavigationMemory/Visu.cpp
@@ -22,18 +22,24 @@
 
 #include "Visu.h"
 
+#include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/cmaps/colormaps.h>
 
+#include "RobotAPI/components/ArViz/Client/Elements.h"
 #include "RobotAPI/components/ArViz/Client/Layer.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 #include "armarx/navigation/conversions/eigen.h"
+#include "armarx/navigation/human/aron/Human.aron.generated.h"
+#include "armarx/navigation/human/aron_conversions.h"
+#include "armarx/navigation/human/types.h"
 #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
 #include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/core/Graph.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
 #include <armarx/navigation/graph/Visu.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
 
 
 namespace armarx::navigation::memory
@@ -42,11 +48,13 @@ namespace armarx::navigation::memory
     Visu::Visu(viz::Client arviz,
                const armem::server::wm::CoreSegment& locSegment,
                const armem::server::wm::CoreSegment& graphSegment,
-               const armem::server::wm::CoreSegment& costmapSegment) :
+               const armem::server::wm::CoreSegment& costmapSegment,
+               const armem::server::wm::CoreSegment& humanSegment) :
         arviz(arviz),
         locSegment(locSegment),
         graphSegment(graphSegment),
         costmapSegment(costmapSegment),
+        humanSegment(humanSegment),
         visu(std::make_unique<graph::GraphVisu>())
     {
     }
@@ -165,6 +173,24 @@ namespace armarx::navigation::memory
             layer.add(mesh);
         }
 
+        void
+        visualize(const human::Humans& humans, viz::Layer& layer)
+        {
+            ARMARX_INFO << "Visualizing " << humans.size() << " humans";
+            for (const auto& human : humans)
+            {
+                viz::Cylinder cylinder(std::to_string(layer.size()));
+                cylinder.fromTo(conv::to3D(human.pose.translation()),
+                                conv::to3D(human.pose.translation()) + Eigen::Vector3f{0, 0, 10});
+
+
+                cylinder.color(simox::Color::orange());
+                cylinder.radius(300);
+
+                layer.add(cylinder);
+            }
+        }
+
     } // namespace
 
     void
@@ -207,5 +233,45 @@ namespace armarx::navigation::memory
         }
     }
 
+    void
+    Visu::drawHumans(std::vector<viz::Layer>& layers, bool enabled)
+    {
+        if (not enabled)
+        {
+            return;
+        }
+
+        std::map<std::string, navigation::human::Humans> namedProviderHumans;
+
+        humanSegment.doLocked(
+            [&]()
+            {
+                using namespace armem::server;
+
+                humanSegment.forEachEntity(
+                    [&](const wm::Entity& entity)
+                    {
+                        entity.getLatestSnapshot().forEachInstance(
+                            [&namedProviderHumans](const armarx::armem::wm::EntityInstance& instance)
+                            {
+                                const auto dto =
+                                    navigation::human::arondto::Human::FromAron(instance.data());
+
+                                navigation::human::Human human;
+                                fromAron(dto, human);
+
+                                namedProviderHumans[instance.id().providerSegmentName]
+                                    .emplace_back(std::move(human));
+                            });
+                    });
+            });
+
+        for (const auto& [providerName, humans] : namedProviderHumans)
+        {
+            viz::Layer& layer = layers.emplace_back(arviz.layer("humans_" + providerName));
+            visualize(humans, layer);
+        }
+    }
+
 
 } // namespace armarx::navigation::memory
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.h b/source/armarx/navigation/components/NavigationMemory/Visu.h
index cfd732ad..123a865d 100644
--- a/source/armarx/navigation/components/NavigationMemory/Visu.h
+++ b/source/armarx/navigation/components/NavigationMemory/Visu.h
@@ -28,6 +28,7 @@
 #include "RobotAPI/libraries/armem/server/wm/memory_definitions.h"
 #include <RobotAPI/components/ArViz/Client/Client.h>
 #include <RobotAPI/libraries/armem/core/forward_declarations.h>
+
 #include "armarx/navigation/algorithms/Costmap.h"
 
 
@@ -45,13 +46,15 @@ namespace armarx::navigation::memory
         Visu(viz::Client arviz,
              const armem::server::wm::CoreSegment& locSegment,
              const armem::server::wm::CoreSegment& graphSegment,
-             const armem::server::wm::CoreSegment& costmapSegment);
+             const armem::server::wm::CoreSegment& costmapSegment,
+             const armem::server::wm::CoreSegment& humanSegment);
         ~Visu();
 
 
         void drawLocations(std::vector<viz::Layer>& layers, bool enabled);
         void drawGraphs(std::vector<viz::Layer>& layers, bool enabled);
         void drawCostmaps(std::vector<viz::Layer>& layers, bool enabled);
+        void drawHumans(std::vector<viz::Layer>& layers, bool enabled);
 
 
     public:
@@ -60,6 +63,7 @@ namespace armarx::navigation::memory
         const armem::server::wm::CoreSegment& locSegment;
         const armem::server::wm::CoreSegment& graphSegment;
         const armem::server::wm::CoreSegment& costmapSegment;
+        const armem::server::wm::CoreSegment& humanSegment;
 
         std::unique_ptr<navigation::graph::GraphVisu> visu;
     };
-- 
GitLab


From f3159e8c60629ed451c89fdde36ddde019393870 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:28:07 +0200
Subject: [PATCH 110/324] dynamic_scene_provider component: tested on ARMAR-6;
 minor fixes

---
 .../dynamic_scene_provider/CMakeLists.txt     |  2 +-
 .../dynamic_scene_provider/Component.cpp      | 24 ++++++++++++++++---
 .../dynamic_scene_provider/Component.h        |  5 ++++
 3 files changed, 27 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 39d89c1a..e061ea23 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -35,7 +35,7 @@ armarx_add_component(dynamic_scene_provider
         ## RobotAPICore
         ## RobotAPIInterfaces
         ## RobotAPIComponentPlugins  # For ArViz and other plugins.
-    DEPENDENCIES_PRIVATE
+    # DEPENDENCIES_PRIVATE
         range-v3::range-v3
     # DEPENDENCIES_LEGACY
         ## Add libraries that do not provide any targets but ${FOO_*} variables.
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index e8abd88f..4a1cd5e8 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -53,6 +53,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         addPlugin(virtualRobotReaderPlugin);
         addPlugin(costmapReaderPlugin);
         addPlugin(occupancyGridReaderPlugin);
+        addPlugin(humanWriterPlugin);
     }
 
     armarx::PropertyDefinitionsPtr
@@ -86,6 +87,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         def->optional(properties.occupancyGrid.name, "p.occupancyGrid.name", "");
         def->optional(properties.occupancyGrid.freespaceThreshold, "p.occupancyGrid.freespaceThreshold", "");
         def->optional(properties.occupancyGrid.occupiedThreshold, "p.occupancyGrid.occupiedThreshold", "");
+        
+        def->optional(properties.humanPoseProvider, "p.humanPoseProvider", "");
 
         return def;
     }
@@ -141,12 +144,14 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         task = new PeriodicTask<Component>(
             this, &Component::runPeriodically, properties.taskPeriodMs, false, "runningTask");
+        task->start();
     }
 
 
     void
     Component::onDisconnectComponent()
     {
+        task->stop();
     }
 
 
@@ -189,12 +194,14 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // Human
         //
 
-        const armem::human::client::Reader::Query humanPoseQuery{.providerName = "", // all
+        ARMARX_INFO << "Querying humans";
+
+        const armem::human::client::Reader::Query humanPoseQuery{.providerName = properties.humanPoseProvider,
                                                                  .timestamp = timestamp};
 
         const armem::human::client::Reader::Result humanPoseResult =
             humanPoseReaderPlugin->get().query(humanPoseQuery);
-        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success);
+        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success) << humanPoseResult.errorMessage;
 
         ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
 
@@ -202,6 +209,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // Laser scanner features
         //
 
+        ARMARX_INFO << "Querying laser scanner features";
+
         const armem::vision::laser_scanner_features::client::Reader::Query laserFeaturesQuery{
             .providerName = properties.laserScannerFeatures.providerName,
             .name = properties.laserScannerFeatures.name,
@@ -219,6 +228,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         //  Objects in the scene (both static and dynamic)
         //
 
+        ARMARX_INFO << "Querying object poses";
+
         const objpose::ObjectPoseSeq objectPoses = ObjectPoseClientPluginUser::getObjectPoses();
 
         // remove those objects that belong to an object dataset. the manipulation object / distance computation is broken
@@ -243,8 +254,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
         //  Costmaps
         //
 
+        ARMARX_INFO << "Querying costmap";
+
         const memory::client::costmap::Reader::Query costmapQuery{.providerName =
-                                                                      "navigator", // TODO check
+                                                                      "distance_to_obstacle_costmap_provider", // TODO check
                                                                   .name = "distance_to_obstacles",
                                                                   .timestamp = timestamp};
 
@@ -319,8 +332,13 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         // here ends: data fetching
 
+        ARMARX_INFO << "Running human tracker";
+
         humanTracker.update(HumanTracker::Measurements{.detectionTime = timestamp,
                                                        .humanPoses = humanPoseResult.humanPoses});
+
+
+        humanWriterPlugin->get().store(humanTracker.getTrackedHumans(),getName(), timestamp);
     }
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index 171b8638..bcc3ad7d 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -49,6 +49,7 @@
 #include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
 #include "armarx/navigation/components/dynamic_scene_provider/HumanTracker.h"
 #include "armarx/navigation/memory/client/costmap/Reader.h"
+#include "armarx/navigation/memory/client/human/Writer.h"
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
 
 
@@ -151,6 +152,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 float freespaceThreshold = 0.45F;
                 float occupiedThreshold = 0.55;
             } occupancyGrid;
+
+            std::string humanPoseProvider = "OpenNIPointCloudProvider";
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
@@ -199,6 +202,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ReaderWriterPlugin<armem::vision::occupancy_grid::client::Reader>*
             occupancyGridReaderPlugin = nullptr;
 
+        ReaderWriterPlugin<memory::client::human::Writer>* humanWriterPlugin = nullptr;
+
 
         HumanTracker humanTracker;
     };
-- 
GitLab


From f854d1f4e51904d160eb677e3cc12af8465847fe Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:28:43 +0200
Subject: [PATCH 111/324] cmake: moved human lib up as other libs depend on it

---
 source/armarx/navigation/CMakeLists.txt | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/CMakeLists.txt b/source/armarx/navigation/CMakeLists.txt
index ca819773..60936986 100644
--- a/source/armarx/navigation/CMakeLists.txt
+++ b/source/armarx/navigation/CMakeLists.txt
@@ -3,6 +3,7 @@ add_subdirectory(core)
 add_subdirectory(util)
 add_subdirectory(conversions)
 add_subdirectory(algorithms)
+add_subdirectory(human)
 add_subdirectory(dynamic_scene)
 add_subdirectory(global_planning)
 add_subdirectory(local_planning)
@@ -15,7 +16,6 @@ add_subdirectory(location)
 add_subdirectory(memory)
 add_subdirectory(server)
 add_subdirectory(platform_controller)
-add_subdirectory(human)
 
 # Components.
 add_subdirectory(components)
-- 
GitLab


From 16ccec9a3bb7ecd47294ac7b77c88c0c7bd594b8 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 09:32:42 +0200
Subject: [PATCH 112/324] merge with origin/feature/human-tracker

---
 .../dynamic_scene_provider/HumanTracker.cpp       | 15 ++++++---------
 .../dynamic_scene_provider/HumanTracker.h         | 11 +++++++++++
 2 files changed, 17 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 7dd61dc6..e7771cb3 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -64,7 +64,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
-            if ((measurements.detectionTime - human.human.detectionTime) >= maxAge)
+            if ((measurements.detectionTime - human.human.detectionTime) >=
+                parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
             }
@@ -153,12 +154,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // associate leftover humans by their distances
         const auto sortedDistances = getSortedDistances(trackedHumans, detectedHumans);
 
-        //TODO max distance parameter
-        float maxDistance = 600;
-
         for (auto& posDistance : sortedDistances)
         {
-            if (posDistance.distance > maxDistance)
+            if (posDistance.distance > parameters.maxAssociationDistance)
             {
                 break;
             }
@@ -179,16 +177,15 @@ namespace armarx::navigation::components::dynamic_scene_provider
         trackedHuman->associated = true;
         detectedHuman->associated = true;
 
-        // TODO alpha parameter
-        float a = 0.7;
-
         float dt =
             (detectedHuman->detectionTime - trackedHuman->human.detectionTime).toSecondsDouble();
         Eigen::Vector2f ds =
             (detectedHuman->pose.translation() - trackedHuman->human.pose.translation());
         Eigen::Vector2f linVelocity = ds / dt;
 
-        Eigen::Vector2f velocity = a * linVelocity + (1 - a) * trackedHuman->human.linearVelocity;
+        Eigen::Vector2f velocity =
+            parameters.velocityAlpha * linVelocity +
+            (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
         trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index e5197d82..9146a798 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -37,6 +37,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
             bool associated;
         };
 
+        struct Parameters
+        {
+            // the duration after which tracked humans will be erased if no new measurement for this human is found
+            Duration maxTrackingAge = Duration::MilliSeconds(500);
+            // the maximum distance in millimeters of two human measurements to be associated with each other
+            float maxAssociationDistance = 600;
+            // alpha value from interval [0,1] to determine how much the new (and respectively the old) velocity should be weighted
+            float velocityAlpha = 0.7;
+        };
+
         void update(const Measurements& measurements);
 
         std::vector<human::Human> getTrackedHumans() const;
@@ -49,5 +59,6 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     private:
         std::vector<TrackedHuman> trackedHumans;
+        Parameters parameters;
     };
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 3b4d3cc6fe3f2953696751412f130d092b8b9c7f Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 17 Aug 2022 17:55:42 +0200
Subject: [PATCH 113/324] moving components

---
 .../navigation/components/CMakeLists.txt      | 19 +++-
 .../GraphImportExport/test/CMakeLists.txt     |  5 --
 .../test/GraphImportExportTest.cpp            | 38 --------
 .../CMakeLists.txt                            |  4 +-
 .../Component.cpp}                            | 56 ++++++------
 .../Component.h}                              |  9 +-
 .../CMakeLists.txt                            |  4 +-
 .../Component.cpp}                            | 41 +++++----
 .../Component.h}                              | 12 +--
 .../Visu.cpp                                  |  0
 .../Visu.h                                    |  0
 .../{Navigator => navigator}/CMakeLists.txt   |  4 +-
 .../Navigator.cpp => navigator/Component.cpp} | 87 ++++++++++---------
 .../Navigator.h => navigator/Component.h}     | 19 ++--
 .../{Navigator => navigator}/RemoteGui.cpp    | 33 ++++---
 .../{Navigator => navigator}/RemoteGui.h      | 20 ++---
 16 files changed, 170 insertions(+), 181 deletions(-)
 delete mode 100644 source/armarx/navigation/components/GraphImportExport/test/CMakeLists.txt
 delete mode 100644 source/armarx/navigation/components/GraphImportExport/test/GraphImportExportTest.cpp
 rename source/armarx/navigation/components/{GraphImportExport => graph_import_export}/CMakeLists.txt (93%)
 rename source/armarx/navigation/components/{GraphImportExport/GraphImportExport.cpp => graph_import_export/Component.cpp} (90%)
 rename source/armarx/navigation/components/{GraphImportExport/GraphImportExport.h => graph_import_export/Component.h} (96%)
 rename source/armarx/navigation/components/{NavigationMemory => navigation_memory}/CMakeLists.txt (93%)
 rename source/armarx/navigation/components/{NavigationMemory/NavigationMemory.cpp => navigation_memory/Component.cpp} (95%)
 rename source/armarx/navigation/components/{NavigationMemory/NavigationMemory.h => navigation_memory/Component.h} (93%)
 rename source/armarx/navigation/components/{NavigationMemory => navigation_memory}/Visu.cpp (100%)
 rename source/armarx/navigation/components/{NavigationMemory => navigation_memory}/Visu.h (100%)
 rename source/armarx/navigation/components/{Navigator => navigator}/CMakeLists.txt (95%)
 rename source/armarx/navigation/components/{Navigator/Navigator.cpp => navigator/Component.cpp} (85%)
 rename source/armarx/navigation/components/{Navigator/Navigator.h => navigator/Component.h} (95%)
 rename source/armarx/navigation/components/{Navigator => navigator}/RemoteGui.cpp (93%)
 rename source/armarx/navigation/components/{Navigator => navigator}/RemoteGui.h (86%)

diff --git a/source/armarx/navigation/components/CMakeLists.txt b/source/armarx/navigation/components/CMakeLists.txt
index 24217c76..317b56b4 100644
--- a/source/armarx/navigation/components/CMakeLists.txt
+++ b/source/armarx/navigation/components/CMakeLists.txt
@@ -1,8 +1,19 @@
-add_subdirectory(GraphImportExport)
-add_subdirectory(NavigationMemory)
-add_subdirectory(Navigator)
+# Memory
+# ===================================
+
+add_subdirectory(graph_import_export)
+add_subdirectory(navigation_memory)
+
+# Navigator
+# ===================================
+add_subdirectory(navigator)
+
+# Costmap provider
+# ===================================
 
 add_subdirectory(dynamic_distance_to_obstacle_costmap_provider)
+add_subdirectory(distance_to_obstacle_costmap_provider)
 
+# others
+# ===================================
 add_subdirectory(dynamic_scene_provider)
-add_subdirectory(distance_to_obstacle_costmap_provider)
\ No newline at end of file
diff --git a/source/armarx/navigation/components/GraphImportExport/test/CMakeLists.txt b/source/armarx/navigation/components/GraphImportExport/test/CMakeLists.txt
deleted file mode 100644
index c22cdacd..00000000
--- a/source/armarx/navigation/components/GraphImportExport/test/CMakeLists.txt
+++ /dev/null
@@ -1,5 +0,0 @@
-
-# Libs required for the tests
-SET(LIBS ${LIBS} ArmarXCore GraphImportExport)
-
-armarx_add_test(GraphImportExportTest GraphImportExportTest.cpp "${LIBS}")
diff --git a/source/armarx/navigation/components/GraphImportExport/test/GraphImportExportTest.cpp b/source/armarx/navigation/components/GraphImportExport/test/GraphImportExportTest.cpp
deleted file mode 100644
index 6be2d498..00000000
--- a/source/armarx/navigation/components/GraphImportExport/test/GraphImportExportTest.cpp
+++ /dev/null
@@ -1,38 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * ArmarX is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License version 2 as
- * published by the Free Software Foundation.
- *
- * ArmarX is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * @package    MemoryX::ArmarXObjects::GraphImportExport
- * @author     Rainer Kartmann ( rainer dot kartmann at kit dot edu )
- * @date       2021
- * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
- *             GNU General Public License
- */
-
-#define BOOST_TEST_MODULE MemoryX::ArmarXObjects::GraphImportExport
-
-#define ARMARX_BOOST_TEST
-
-#include "../GraphImportExport.h"
-
-#include <iostream>
-
-#include <MemoryX/Test.h>
-
-BOOST_AUTO_TEST_CASE(testExample)
-{
-    armarx::GraphImportExport instance;
-
-    BOOST_CHECK_EQUAL(true, true);
-}
diff --git a/source/armarx/navigation/components/GraphImportExport/CMakeLists.txt b/source/armarx/navigation/components/graph_import_export/CMakeLists.txt
similarity index 93%
rename from source/armarx/navigation/components/GraphImportExport/CMakeLists.txt
rename to source/armarx/navigation/components/graph_import_export/CMakeLists.txt
index 123769e2..40de77dd 100644
--- a/source/armarx/navigation/components/GraphImportExport/CMakeLists.txt
+++ b/source/armarx/navigation/components/graph_import_export/CMakeLists.txt
@@ -24,8 +24,8 @@ armarx_add_component(GraphImportExport
         ## GraphImportExportInterfaces  # If you defined a component ice interface above.
 
     SOURCES
-        GraphImportExport.cpp
+        Component.cpp
 
     HEADERS
-        GraphImportExport.h
+        Component.h
 )
diff --git a/source/armarx/navigation/components/GraphImportExport/GraphImportExport.cpp b/source/armarx/navigation/components/graph_import_export/Component.cpp
similarity index 90%
rename from source/armarx/navigation/components/GraphImportExport/GraphImportExport.cpp
rename to source/armarx/navigation/components/graph_import_export/Component.cpp
index c1976d58..b4e8cbba 100644
--- a/source/armarx/navigation/components/GraphImportExport/GraphImportExport.cpp
+++ b/source/armarx/navigation/components/graph_import_export/Component.cpp
@@ -20,7 +20,7 @@
  *             GNU General Public License
  */
 
-#include "GraphImportExport.h"
+#include "Component.h"
 
 #include <iomanip>
 
@@ -42,11 +42,10 @@
 #include <armarx/navigation/graph/constants.h>
 #include <armarx/navigation/location/constants.h>
 
-
-namespace armarx::navigation
+namespace armarx::navigation::components::graph_import_export
 {
 
-    GraphImportExport::GraphImportExport()
+    Component::Component()
     {
         properties.locationCoreSegmentID = location::coreSegmentID;
         properties.graphCoreSegmentID = graph::coreSegmentID;
@@ -54,7 +53,7 @@ namespace armarx::navigation
 
 
     armarx::PropertyDefinitionsPtr
-    GraphImportExport::createPropertyDefinitions()
+    Component::createPropertyDefinitions()
     {
         armarx::PropertyDefinitionsPtr def =
             new ComponentPropertyDefinitions(getConfigIdentifier());
@@ -67,7 +66,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::onInitComponent()
+    Component::onInitComponent()
     {
         // Topics and properties defined above are automagically registered.
 
@@ -77,7 +76,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::onConnectComponent()
+    Component::onConnectComponent()
     {
         // Get proxies.
         if (proxies.priorKnowledge->hasGraphSegment())
@@ -95,26 +94,32 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::onDisconnectComponent()
+    Component::onDisconnectComponent()
     {
     }
 
 
     void
-    GraphImportExport::onExitComponent()
+    Component::onExitComponent()
     {
     }
 
 
     std::string
-    GraphImportExport::getDefaultName() const
+    Component::getDefaultName() const
+    {
+        return GetDefaultName();
+    }
+
+    std::string
+    Component::GetDefaultName()
     {
-        return "GraphImportExport";
+        return "graph_import_export";
     }
 
 
     void
-    GraphImportExport::createRemoteGuiTab(const std::vector<std::string>& sceneNames)
+    Component::createRemoteGuiTab(const std::vector<std::string>& sceneNames)
     {
         using namespace armarx::RemoteGui::Client;
 
@@ -169,7 +174,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::RemoteGui_update()
+    Component::RemoteGui_update()
     {
         if (tab.sceneRefreshButton.wasClicked())
         {
@@ -205,7 +210,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::refreshScenes()
+    Component::refreshScenes()
     {
         const ::Ice::StringSeq sceneNames = proxies.graphSegment->getScenes();
         createRemoteGuiTab(sceneNames);
@@ -213,7 +218,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::locationsMemoryxToArmem(const std::string& sceneName)
+    Component::locationsMemoryxToArmem(const std::string& sceneName)
     {
         const armem::Time time = armem::Time::Now();
         armem::Commit commit;
@@ -276,7 +281,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::locationsArmemToMemoryx(const std::string& sceneName)
+    Component::locationsArmemToMemoryx(const std::string& sceneName)
     {
         ARMARX_IMPORTANT << "locationsArmemToMemoryx() is WIP!";
         (void)sceneName;
@@ -284,7 +289,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::graphMemoryxToArmem(const std::string& sceneName)
+    Component::graphMemoryxToArmem(const std::string& sceneName)
     {
         memoryx::GraphNodeBaseList graphNodes = proxies.graphSegment->getNodesByScene(sceneName);
         navigation::core::Graph graph = toArmemGraph(graphNodes);
@@ -331,7 +336,7 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::graphArmemToMemoryx(const std::string& sceneName)
+    Component::graphArmemToMemoryx(const std::string& sceneName)
     {
         ARMARX_IMPORTANT << "graphArmemToMemoryx() is WIP!";
         (void)sceneName;
@@ -339,8 +344,8 @@ namespace armarx::navigation
 
 
     void
-    GraphImportExport::clearArMemProviderSegment(armem::client::Writer& writer,
-                                                 const armem::MemoryID& providerSegmentID)
+    Component::clearArMemProviderSegment(armem::client::Writer& writer,
+                                         const armem::MemoryID& providerSegmentID)
     {
         const bool clearWhenExists = true;
         auto result = writer.addSegment(providerSegmentID, clearWhenExists);
@@ -356,7 +361,7 @@ namespace armarx::navigation
 
 
     armem::MemoryID
-    GraphImportExport::getLocationProviderSegmentID()
+    Component::getLocationProviderSegmentID()
     {
         return properties.locationCoreSegmentID.withProviderSegmentName(
             tab.providerSegmentLine.getValue());
@@ -364,7 +369,7 @@ namespace armarx::navigation
 
 
     armem::MemoryID
-    GraphImportExport::getGraphProviderSegmentID()
+    Component::getGraphProviderSegmentID()
     {
         return properties.graphCoreSegmentID.withProviderSegmentName(
             tab.providerSegmentLine.getValue());
@@ -372,7 +377,7 @@ namespace armarx::navigation
 
 
     navigation::core::Graph
-    GraphImportExport::toArmemGraph(const memoryx::GraphNodeBaseList& graphNodes)
+    Component::toArmemGraph(const memoryx::GraphNodeBaseList& graphNodes)
     {
         navigation::core::Graph graph;
         std::map<std::string, navigation::core::Graph::Vertex> vertexMap;
@@ -439,6 +444,7 @@ namespace armarx::navigation
     }
 
 
-    ARMARX_DECOUPLED_REGISTER_COMPONENT(GraphImportExport);
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
+
 
-} // namespace armarx::navigation
+} // namespace armarx::navigation::components::graph_import_export
diff --git a/source/armarx/navigation/components/GraphImportExport/GraphImportExport.h b/source/armarx/navigation/components/graph_import_export/Component.h
similarity index 96%
rename from source/armarx/navigation/components/GraphImportExport/GraphImportExport.h
rename to source/armarx/navigation/components/graph_import_export/Component.h
index c877740c..45e704ad 100644
--- a/source/armarx/navigation/components/GraphImportExport/GraphImportExport.h
+++ b/source/armarx/navigation/components/graph_import_export/Component.h
@@ -38,7 +38,7 @@
 #include <armarx/navigation/core/forward_declarations.h>
 
 
-namespace armarx::navigation
+namespace armarx::navigation::components::graph_import_export
 {
 
     /**
@@ -52,7 +52,7 @@ namespace armarx::navigation
      *
      * Detailed description of class GraphImportExport.
      */
-    class GraphImportExport :
+    class Component :
         virtual public armarx::Component,
         virtual public armarx::DebugObserverComponentPluginUser,
         virtual public armarx::LightweightRemoteGuiComponentPluginUser,
@@ -60,11 +60,12 @@ namespace armarx::navigation
         virtual public armarx::armem::ClientPluginUser
     {
     public:
-        GraphImportExport();
+        Component();
 
 
         /// @see armarx::ManagedIceObject::getDefaultName()
         std::string getDefaultName() const override;
+        static std::string GetDefaultName();
 
 
     protected:
@@ -154,4 +155,4 @@ namespace armarx::navigation
         };
         RemoteGuiTab tab;
     };
-} // namespace armarx::navigation
+}  // namespace armarx::navigation::components::graph_import_export
diff --git a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
similarity index 93%
rename from source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
rename to source/armarx/navigation/components/navigation_memory/CMakeLists.txt
index 5f88e9cf..eb1d9add 100644
--- a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt
+++ b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
@@ -21,10 +21,10 @@ armarx_add_component(navigation_memory
         armarx_navigation::teb_human
 
     SOURCES
-        NavigationMemory.cpp
+        Component.cpp
         Visu.cpp
 
     HEADERS
-        NavigationMemory.h
+        Component.h
         Visu.h
 )
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/navigation_memory/Component.cpp
similarity index 95%
rename from source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
rename to source/armarx/navigation/components/navigation_memory/Component.cpp
index 97d8fa36..13f1fe8c 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Component.cpp
@@ -20,13 +20,13 @@
  *             GNU General Public License
  */
 
-#include "NavigationMemory.h"
+#include "Component.h"
 
-// STD / STL
 #include <filesystem>
 #include <fstream>
 #include <iostream>
 
+#include "ArmarXCore/core/Component.h"
 #include "ArmarXCore/core/time/Metronome.h"
 #include "ArmarXCore/core/time/forward_declarations.h"
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
@@ -53,14 +53,13 @@
 #include <armarx/navigation/location/constants.h>
 
 
-namespace armarx::navigation
+namespace armarx::navigation::components::navigation_memory
 {
 
-    ARMARX_DECOUPLED_REGISTER_COMPONENT(NavigationMemory);
-
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
 
     armarx::PropertyDefinitionsPtr
-    NavigationMemory::createPropertyDefinitions()
+    Component::createPropertyDefinitions()
     {
         armarx::PropertyDefinitionsPtr def =
             new ComponentPropertyDefinitions(getConfigIdentifier());
@@ -96,7 +95,7 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::onInitComponent()
+    Component::onInitComponent()
     {
         // Topics and properties defined above are automagically registered.
 
@@ -331,7 +330,7 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::onConnectComponent()
+    Component::onConnectComponent()
     {
         // Do things after connecting to topics and components.
 
@@ -359,26 +358,32 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::onDisconnectComponent()
+    Component::onDisconnectComponent()
     {
     }
 
 
     void
-    NavigationMemory::onExitComponent()
+    Component::onExitComponent()
     {
     }
 
 
     std::string
-    NavigationMemory::getDefaultName() const
+    Component::getDefaultName() const
+    {
+        return GetDefaultName();
+    }
+
+    std::string
+    Component::GetDefaultName()
     {
-        return "NavigationMemory";
+        return "navigation_memory";
     }
 
 
     void
-    NavigationMemory::createRemoteGuiTab()
+    Component::createRemoteGuiTab()
     {
         using namespace armarx::RemoteGui::Client;
 
@@ -393,14 +398,14 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::RemoteGui_update()
+    Component::RemoteGui_update()
     {
         tab.locationGraph.update(*this);
     }
 
 
     void
-    NavigationMemory::RemoteGuiTab::LocationGraph::setup(NavigationMemory& owner)
+    Component::RemoteGuiTab::LocationGraph::setup(Component& owner)
     {
         using namespace armarx::RemoteGui::Client;
         GridLayout grid;
@@ -421,7 +426,7 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::RemoteGuiTab::LocationGraph::update(NavigationMemory& owner)
+    Component::RemoteGuiTab::LocationGraph::update(Component& owner)
     {
         if (visuLocations.hasValueChanged() or visuGraphEdges.hasValueChanged())
         {
@@ -433,7 +438,7 @@ namespace armarx::navigation
 
 
     void
-    NavigationMemory::visuRun()
+    Component::visuRun()
     {
         memory::Visu visu{arviz,
                           workingMemory().getCoreSegment(navigation::location::coreSegmentID),
@@ -479,4 +484,4 @@ namespace armarx::navigation
     }
 
 
-} // namespace armarx::navigation
+}  // namespace armarx::navigation::components::navigation_memory
diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h b/source/armarx/navigation/components/navigation_memory/Component.h
similarity index 93%
rename from source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
rename to source/armarx/navigation/components/navigation_memory/Component.h
index e34aa21e..fcbcb08d 100644
--- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -35,7 +35,7 @@
 #include <mutex>
 
 
-namespace armarx::navigation
+namespace armarx::navigation::components::navigation_memory
 {
 
     /**
@@ -49,7 +49,7 @@ namespace armarx::navigation
      *
      * Detailed description of class NavigationMemory.
      */
-    class NavigationMemory :
+    class Component :
         virtual public armarx::Component,
         // , virtual public armarx::DebugObserverComponentPluginUser
         virtual public armarx::LightweightRemoteGuiComponentPluginUser,
@@ -60,6 +60,8 @@ namespace armarx::navigation
         /// @see armarx::ManagedIceObject::getDefaultName()
         std::string getDefaultName() const override;
 
+        static std::string GetDefaultName();
+
 
     protected:
         /// @see PropertyUser::createPropertyDefinitions()
@@ -117,8 +119,8 @@ namespace armarx::navigation
                 armarx::RemoteGui::Client::CheckBox visuLocations;
                 armarx::RemoteGui::Client::CheckBox visuGraphEdges;
 
-                void setup(NavigationMemory& owner);
-                void update(NavigationMemory& owner);
+                void setup(Component& owner);
+                void update(Component& owner);
             };
             LocationGraph locationGraph;
         };
@@ -132,4 +134,4 @@ namespace armarx::navigation
         Tasks tasks;
     };
 
-} // namespace armarx::navigation
+}  // namespace armarx::navigation::components::navigation_memory
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
similarity index 100%
rename from source/armarx/navigation/components/NavigationMemory/Visu.cpp
rename to source/armarx/navigation/components/navigation_memory/Visu.cpp
diff --git a/source/armarx/navigation/components/NavigationMemory/Visu.h b/source/armarx/navigation/components/navigation_memory/Visu.h
similarity index 100%
rename from source/armarx/navigation/components/NavigationMemory/Visu.h
rename to source/armarx/navigation/components/navigation_memory/Visu.h
diff --git a/source/armarx/navigation/components/Navigator/CMakeLists.txt b/source/armarx/navigation/components/navigator/CMakeLists.txt
similarity index 95%
rename from source/armarx/navigation/components/Navigator/CMakeLists.txt
rename to source/armarx/navigation/components/navigator/CMakeLists.txt
index 57f641b3..a8d6245e 100644
--- a/source/armarx/navigation/components/Navigator/CMakeLists.txt
+++ b/source/armarx/navigation/components/navigator/CMakeLists.txt
@@ -1,9 +1,9 @@
 armarx_add_component(navigator
     SOURCES
-        Navigator.cpp
+        Component.cpp
         RemoteGui.cpp
     HEADERS
-        Navigator.h
+        Component.h
         RemoteGui.h
     DEPENDENCIES
         # ArmarXCore
diff --git a/source/armarx/navigation/components/Navigator/Navigator.cpp b/source/armarx/navigation/components/navigator/Component.cpp
similarity index 85%
rename from source/armarx/navigation/components/Navigator/Navigator.cpp
rename to source/armarx/navigation/components/navigator/Component.cpp
index e10c47a8..40f41ce2 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -21,7 +21,7 @@
  *             GNU General Public License
  */
 
-#include "Navigator.h"
+#include "Component.h"
 
 #include <algorithm>
 #include <cmath>
@@ -78,7 +78,7 @@
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/client/ice_conversions.h>
-#include <armarx/navigation/components/Navigator/RemoteGui.h>
+#include <armarx/navigation/components/navigator/RemoteGui.h>
 #include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/factories/NavigationStackFactory.h>
@@ -87,9 +87,9 @@
 #include <armarx/navigation/server/introspection/MemoryIntrospector.h>
 #include <armarx/navigation/util/util.h>
 
-namespace armarx::navigation::components
+namespace armarx::navigation::components::navigator
 {
-    ARMARX_DECOUPLED_REGISTER_COMPONENT(Navigator);
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
 }
 
 namespace armarx::navigation
@@ -109,10 +109,10 @@ namespace armarx::navigation
 
 } // namespace armarx::navigation
 
-namespace armarx::navigation::components
+namespace armarx::navigation::components::navigator
 {
 
-    components::Navigator::Navigator() : parameterizationService(nullptr, nullptr)
+    Component::Component() : parameterizationService(nullptr, nullptr)
     // publisher(&resultsWriter, &eventsWriter)
     {
         // scene().timeServer = &timeServer;
@@ -131,15 +131,15 @@ namespace armarx::navigation::components
     }
 
 
-    components::Navigator::~Navigator() = default;
+    Component::~Component() = default;
 
     void
-    components::Navigator::onInitComponent()
+    Component::onInitComponent()
     {
     }
 
     void
-    components::Navigator::onConnectComponent()
+    Component::onConnectComponent()
     {
         ARMARX_TRACE;
 
@@ -180,7 +180,7 @@ namespace armarx::navigation::components
 
         ARMARX_TRACE;
 
-        if(not params.disableExecutor)
+        if (not params.disableExecutor)
         {
             executor.emplace(server::PlatformControllerExecutor(getControlComponentPlugin()));
         }
@@ -190,7 +190,7 @@ namespace armarx::navigation::components
         // memoryIntrospector = server::MemoryIntrospector(resultsWriterPlugin->get(), );
 
 
-        navRemoteGui = std::make_unique<NavigatorRemoteGui>(remoteGui, *this);
+        navRemoteGui = std::make_unique<navigator::RemoteGui>(remoteGui, *this);
         navRemoteGui->enable();
 
         initialized = true;
@@ -199,14 +199,14 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::onReconnectComponent()
+    Component::onReconnectComponent()
     {
         ARMARX_TRACE;
         navRemoteGui->enable();
     }
 
     void
-    components::Navigator::onDisconnectComponent()
+    Component::onDisconnectComponent()
     {
         ARMARX_TRACE;
 
@@ -215,27 +215,34 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::onExitComponent()
+    Component::onExitComponent()
     {
     }
 
     void
-    components::Navigator::initializeScene()
+    Component::initializeScene()
     {
         ARMARX_TRACE;
         sceneProvider->initialize(armarx::Clock::Now());
     }
 
     std::string
-    components::Navigator::getDefaultName() const
+    Component::getDefaultName() const
     {
-        return "Navigator";
+        return GetDefaultName();
     }
 
+    std::string
+    Component::GetDefaultName()
+    {
+        return "navigator";
+    }
+
+
     void
-    components::Navigator::createConfig(const aron::data::dto::DictPtr& stackConfig,
-                                        const std::string& callerId,
-                                        const Ice::Current&)
+    Component::createConfig(const aron::data::dto::DictPtr& stackConfig,
+                            const std::string& callerId,
+                            const Ice::Current&)
     {
         // TODO: Not thread-safe.
         ARMARX_TRACE;
@@ -256,7 +263,7 @@ namespace armarx::navigation::components
                 &resultsWriterPlugin->get(), &eventsWriterPlugin->get(), callerId));
 
         server::ExecutorInterface* executorPtr = nullptr;
-        if(executor.has_value())
+        if (executor.has_value())
         {
             executorPtr = &executor.value();
         }
@@ -275,10 +282,10 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::moveTo(const std::vector<Eigen::Matrix4f>& waypoints,
-                                  const std::string& navigationMode,
-                                  const std::string& callerId,
-                                  const Ice::Current&)
+    Component::moveTo(const std::vector<Eigen::Matrix4f>& waypoints,
+                      const std::string& navigationMode,
+                      const std::string& callerId,
+                      const Ice::Current&)
     {
         ARMARX_TRACE;
 
@@ -305,7 +312,7 @@ namespace armarx::navigation::components
 
 
     void
-    Navigator::moveTo2(const client::detail::Waypoints& waypoints,
+    Component::moveTo2(const client::detail::Waypoints& waypoints,
                        const std::string& navigationMode,
                        const std::string& callerId,
                        const Ice::Current& c)
@@ -323,10 +330,10 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::moveTowards(const Eigen::Vector3f& direction,
-                                       const std::string& navigationMode,
-                                       const std::string& callerId,
-                                       const Ice::Current&)
+    Component::moveTowards(const Eigen::Vector3f& direction,
+                           const std::string& navigationMode,
+                           const std::string& callerId,
+                           const Ice::Current&)
     {
         // TODO: Error handling.
         ARMARX_TRACE;
@@ -340,7 +347,7 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::pause(const std::string& configId, const Ice::Current&)
+    Component::pause(const std::string& configId, const Ice::Current&)
     {
         ARMARX_CHECK(navigators.count(configId) > 0)
             << "Navigator config for caller `" << configId << "` not registered!";
@@ -348,7 +355,7 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::resume(const std::string& configId, const Ice::Current&)
+    Component::resume(const std::string& configId, const Ice::Current&)
     {
         ARMARX_TRACE;
         ARMARX_CHECK(navigators.count(configId) > 0)
@@ -357,7 +364,7 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::stop(const std::string& configId, const Ice::Current&)
+    Component::stop(const std::string& configId, const Ice::Current&)
     {
         // FIXME make sure that event is emitted
         ARMARX_TRACE;
@@ -372,7 +379,7 @@ namespace armarx::navigation::components
     }
 
     void
-    components::Navigator::stopAll(const Ice::Current&)
+    Component::stopAll(const Ice::Current&)
     {
         ARMARX_IMPORTANT << "stopAll()";
 
@@ -392,7 +399,7 @@ namespace armarx::navigation::components
     }
 
     bool
-    components::Navigator::isPaused(const std::string& configId, const Ice::Current&)
+    Component::isPaused(const std::string& configId, const Ice::Current&)
     {
         ARMARX_TRACE;
         ARMARX_CHECK(navigators.count(configId) > 0)
@@ -401,14 +408,14 @@ namespace armarx::navigation::components
     }
 
     const core::Scene&
-    Navigator::scene() const
+    Component::scene() const
     {
         ARMARX_CHECK_NOT_NULL(sceneProvider);
         return sceneProvider->scene();
     }
 
     bool
-    components::Navigator::isStopped(const std::string& configId, const Ice::Current&)
+    Component::isStopped(const std::string& configId, const Ice::Current&)
     {
         ARMARX_TRACE;
         ARMARX_CHECK(navigators.count(configId) > 0)
@@ -417,7 +424,7 @@ namespace armarx::navigation::components
     }
 
     armarx::PropertyDefinitionsPtr
-    components::Navigator::createPropertyDefinitions()
+    Component::createPropertyDefinitions()
     {
         ARMARX_TRACE;
 
@@ -450,7 +457,7 @@ namespace armarx::navigation::components
 
 
     server::Navigator*
-    components::Navigator::activeNavigator()
+    Component::activeNavigator()
     {
         ARMARX_TRACE;
         // We define the active navigator to be the one whose movement is enabled.
@@ -471,4 +478,4 @@ namespace armarx::navigation::components
         return &it->second;
     }
 
-} // namespace armarx::navigation::components
+} // namespace armarx::navigation::components::navigator
diff --git a/source/armarx/navigation/components/Navigator/Navigator.h b/source/armarx/navigation/components/navigator/Component.h
similarity index 95%
rename from source/armarx/navigation/components/Navigator/Navigator.h
rename to source/armarx/navigation/components/navigator/Component.h
index 4c25c56b..8b2b3467 100644
--- a/source/armarx/navigation/components/Navigator/Navigator.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -50,8 +50,7 @@
 #include <RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h>
 
 #include <armarx/control/client/ComponentPlugin.h>
-#include <armarx/navigation/client/ice/NavigatorInterface.h>
-#include <armarx/navigation/components/Navigator/RemoteGui.h>
+#include <armarx/navigation/components/navigator/RemoteGui.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/memory/client/graph/Reader.h>
 #include <armarx/navigation/memory/client/parameterization/Reader.h>
@@ -65,7 +64,7 @@
 #include <armarx/navigation/server/scene_provider/SceneProvider.h>
 
 
-namespace armarx::navigation::components
+namespace armarx::navigation::components::navigator
 {
 
     /**
@@ -79,8 +78,8 @@ namespace armarx::navigation::components
      *
      * Detailed description of class Navigator.
      */
-    class Navigator :
-        virtual public Component,
+    class Component :
+        virtual public armarx::Component,
         virtual public client::NavigatorInterface,
         virtual public ObjectPoseClientPluginUser,
         virtual public ArVizComponentPluginUser,
@@ -89,12 +88,14 @@ namespace armarx::navigation::components
     {
 
     public:
-        Navigator();
-        ~Navigator() override;
+        Component();
+        ~Component() override;
 
         /// @see armarx::ManagedIceObject::getDefaultName()
         std::string getDefaultName() const override;
 
+        static std::string GetDefaultName();
+
         void createConfig(const aron::data::dto::DictPtr& stackConfig,
                           const std::string& callerId,
                           const Ice::Current& c = Ice::emptyCurrent) override;
@@ -174,7 +175,7 @@ namespace armarx::navigation::components
         std::mutex propertiesMutex;
 
         // TODO maybe as optional, but requires some effort
-        std::unique_ptr<NavigatorRemoteGui> navRemoteGui;
+        std::unique_ptr<armarx::navigation::components::navigator::RemoteGui> navRemoteGui;
 
 
         // unique_ptr to avoid dangling refs
@@ -216,4 +217,4 @@ namespace armarx::navigation::components
 
         Parameters params;
     };
-} // namespace armarx::navigation::components
+}  // namespace armarx::navigation::components::navigator
diff --git a/source/armarx/navigation/components/Navigator/RemoteGui.cpp b/source/armarx/navigation/components/navigator/RemoteGui.cpp
similarity index 93%
rename from source/armarx/navigation/components/Navigator/RemoteGui.cpp
rename to source/armarx/navigation/components/navigator/RemoteGui.cpp
index cc082cef..c63a52c4 100644
--- a/source/armarx/navigation/components/Navigator/RemoteGui.cpp
+++ b/source/armarx/navigation/components/navigator/RemoteGui.cpp
@@ -15,26 +15,25 @@
 #include <ArmarXGui/interface/RemoteGuiInterface.h>
 #include <ArmarXGui/libraries/RemoteGui/WidgetProxy.h>
 
-#include "Navigator.h"
+#include "Component.h"
 #include "armarx/navigation/local_planning/TimedElasticBands.h"
-#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/factories/NavigationStackFactory.h>
 #include <armarx/navigation/global_planning/AStar.h>
 #include <armarx/navigation/global_planning/Point2Point.h>
+#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/server/Navigator.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 #include <armarx/navigation/util/util.h>
 
-namespace armarx::navigation::components
+namespace armarx::navigation::components::navigator
 {
     namespace gui = RemoteGui;
 
-    NavigatorRemoteGui::NavigatorRemoteGui(const RemoteGuiInterfacePrx& remoteGui,
-                                           Navigator& navigator) :
+    RemoteGui::RemoteGui(const RemoteGuiInterfacePrx& remoteGui, Component& navigator) :
         remoteGui(remoteGui),
-        runningTask(new RunningTask<NavigatorRemoteGui>(this, &NavigatorRemoteGui::run)),
+        runningTask(new RunningTask<RemoteGui>(this, &RemoteGui::run)),
         navigator(navigator)
     {
         createRemoteGuiTab();
@@ -44,13 +43,13 @@ namespace armarx::navigation::components
         runningTask->start();
     }
 
-    NavigatorRemoteGui::~NavigatorRemoteGui()
+    RemoteGui::~RemoteGui()
     {
         shutdown();
     }
 
     void
-    NavigatorRemoteGui::createRemoteGuiTab()
+    RemoteGui::createRemoteGuiTab()
     {
         ARMARX_TRACE;
 
@@ -193,7 +192,7 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::run()
+    RemoteGui::run()
     {
         constexpr int kCycleDurationMs = 100;
 
@@ -227,11 +226,11 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::handleEvents(RemoteGui::TabProxy& tab3)
+    RemoteGui::handleEvents(::armarx::RemoteGui::TabProxy& tab3)
     {
         ARMARX_TRACE;
 
-        const std::string configId = "NavigatorRemoteGui";
+        const std::string configId = "RemoteGui";
 
         if (tab.controlGroup.moveToButton.wasClicked())
         {
@@ -262,7 +261,7 @@ namespace armarx::navigation::components
 
             ARMARX_TRACE;
 
-            navigator.createConfig(stackConfig, "NavigatorRemoteGui");
+            navigator.createConfig(stackConfig, "RemoteGui");
 
             const Eigen::Vector3f targetPos{tab.targetPoseGroup.targetPoseX.getValue(),
                                             tab.targetPoseGroup.targetPoseY.getValue(),
@@ -321,7 +320,7 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::shutdown()
+    RemoteGui::shutdown()
     {
         // std::lock_guard g{mtx};
 
@@ -335,7 +334,7 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::enable()
+    RemoteGui::enable()
     {
         ARMARX_TRACE;
 
@@ -348,7 +347,7 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::disable()
+    RemoteGui::disable()
     {
         ARMARX_TRACE;
 
@@ -366,7 +365,7 @@ namespace armarx::navigation::components
     }
 
     void
-    NavigatorRemoteGui::reset()
+    RemoteGui::reset()
     {
         ARMARX_TRACE;
 
@@ -383,4 +382,4 @@ namespace armarx::navigation::components
         tab.sendUpdates();
     }
 
-} // namespace armarx::navigation::components
+} // namespace armarx::navigation::components::navigator
diff --git a/source/armarx/navigation/components/Navigator/RemoteGui.h b/source/armarx/navigation/components/navigator/RemoteGui.h
similarity index 86%
rename from source/armarx/navigation/components/Navigator/RemoteGui.h
rename to source/armarx/navigation/components/navigator/RemoteGui.h
index ee8b78b6..2cdc30c5 100644
--- a/source/armarx/navigation/components/Navigator/RemoteGui.h
+++ b/source/armarx/navigation/components/navigator/RemoteGui.h
@@ -33,16 +33,16 @@
 #include <ArmarXGui/libraries/RemoteGui/Client/Tab.h>
 #include <ArmarXGui/libraries/RemoteGui/WidgetProxy.h>
 
-namespace armarx::navigation::components
+namespace armarx::navigation::components::navigator
 {
-    class Navigator;
+    class Component;
 
-    class NavigatorRemoteGui
+    class RemoteGui
     {
     public:
-        NavigatorRemoteGui(const RemoteGuiInterfacePrx& remoteGui, Navigator& navigator);
+        RemoteGui(const RemoteGuiInterfacePrx& remoteGui, Component& navigator);
 
-        ~NavigatorRemoteGui();
+        ~RemoteGui();
 
         void shutdown();
 
@@ -57,18 +57,18 @@ namespace armarx::navigation::components
         std::mutex handleEventsMtx;
         RemoteGuiInterfacePrx remoteGui;
 
-        RunningTask<NavigatorRemoteGui>::pointer_type runningTask;
+        RunningTask<RemoteGui>::pointer_type runningTask;
 
-        Navigator& navigator;
+        Component& navigator;
 
-        RemoteGui::TabProxy tabPrx;
+        armarx::RemoteGui::TabProxy tabPrx;
 
         void createRemoteGuiTab();
 
         // thread function
         void run();
 
-        void handleEvents(RemoteGui::TabProxy& tab);
+        void handleEvents(armarx::RemoteGui::TabProxy& tab);
 
         const std::string REMOTE_GUI_TAB_MAME = "Navigator";
 
@@ -105,4 +105,4 @@ namespace armarx::navigation::components
         RemoteGuiTab tab;
     };
 
-} // namespace armarx::navigation::components
+}  // namespace armarx::navigation::components::navigator
-- 
GitLab


From 14a19d2ececc76641d2e99728c37be2c2e289846 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 18:50:55 +0200
Subject: [PATCH 114/324] fixing PlatformNavigation scenario

---
 .../PlatformNavigation/config/navigator.cfg   | 228 +++++++++---------
 1 file changed, 114 insertions(+), 114 deletions(-)

diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 098e6c14..482582bb 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -92,299 +92,299 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.Navigator.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            ArVizStorage
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ArVizStorageName = ArVizStorage
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.Navigator.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            ArVizTopic
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ArVizTopicName = ArVizTopic
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.Navigator.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            false
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.EnableProfiling = false
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.Navigator.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Navigator.MinimumLoggingLevel = Undefined
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.Navigator.ObjectMemoryName:  Name of the object memory.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            ObjectMemory
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ObjectMemoryName = ObjectMemory
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.Navigator.ObjectName:  Name of IceGrid well-known object
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.ObjectName = navigator
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
+#  - Default:            false
 #  - Case sensitivity:   yes
-#  - Required:           yes
-ArmarX.Navigator.RobotUnitName = Armar6Unit
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
+#  - Default:            Info
+#  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Verbose
 
 
-# ArmarX.Navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
+# ArmarX.navigator.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.cmp.RemoteGui = RemoteGuiProvider
+# ArmarX.navigator.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment:  
+# ArmarX.navigator.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            Costmap
+#  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment = Costmap
+# ArmarX.navigator.ArVizTopicName = ArVizTopic
 
 
-# ArmarX.Navigator.mem.nav.costmap.Memory:  
+# ArmarX.navigator.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigator.EnableProfiling = false
 
 
-# ArmarX.Navigator.mem.nav.events.CoreSegment:  
+# ArmarX.navigator.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            Events
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.CoreSegment = Events
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.navigator.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.Navigator.mem.nav.events.Memory:  
+# ArmarX.navigator.ObjectMemoryName:  Name of the object memory.
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            ObjectMemory
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Memory = Navigation
+# ArmarX.navigator.ObjectMemoryName = ObjectMemory
 
 
-# ArmarX.Navigator.mem.nav.events.Provider:  Name of this provider
+# ArmarX.navigator.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Provider = ""
+ArmarX.navigator.ObjectName = navigator
 
 
-# ArmarX.Navigator.mem.nav.graph.CoreSegment:  
+# ArmarX.navigator.RobotUnitName:  Name of the RobotUnit
 #  Attributes:
-#  - Default:            Location
 #  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.CoreSegment = Location
+#  - Required:           yes
+ArmarX.navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Navigator.mem.nav.graph.Memory:  
+# ArmarX.navigator.cmp.PlatformUnit:  No Description
 #  Attributes:
-#  - Default:            Navigation
-#  - Case sensitivity:   yes
+#  - Default:            Armar6PlatformUnit
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.Memory = Navigation
+ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 
 
-# ArmarX.Navigator.mem.nav.param.CoreSegment:  
+# ArmarX.navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
 #  Attributes:
-#  - Default:            Parameterization
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.CoreSegment = Parameterization
+# ArmarX.navigator.cmp.RemoteGui = RemoteGuiProvider
 
 
-# ArmarX.Navigator.mem.nav.param.Memory:  
+# ArmarX.navigator.mem.nav.costmap.CoreSegment:  
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            Costmap
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Memory = Navigation
+# ArmarX.navigator.mem.nav.costmap.CoreSegment = Costmap
 
 
-# ArmarX.Navigator.mem.nav.param.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.costmap.Memory:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Provider = ""
+# ArmarX.navigator.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment:  
+# ArmarX.navigator.mem.nav.events.CoreSegment:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Events
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment = ""
+# ArmarX.navigator.mem.nav.events.CoreSegment = Events
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Memory:  
+# ArmarX.navigator.mem.nav.events.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Memory = Navigation
+# ArmarX.navigator.mem.nav.events.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.events.Provider:  Name of this provider
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
+# ArmarX.navigator.mem.nav.events.Provider = ""
 
 
-# ArmarX.Navigator.mem.robot_state.Memory:  
+# ArmarX.navigator.mem.nav.graph.CoreSegment:  
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            Location
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.Memory = RobotState
+# ArmarX.navigator.mem.nav.graph.CoreSegment = Location
 
 
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.navigator.mem.nav.graph.Memory:  
 #  Attributes:
-#  - Default:            Localization
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
+# ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.navigator.mem.nav.param.CoreSegment:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            Parameterization
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled = true
+# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigator.mem.nav.param.Memory:  
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.navigator.mem.nav.param.Memory = Navigation
 
 
-# ArmarX.Navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
+# ArmarX.navigator.mem.nav.param.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            false
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.p.disableExecutor = false
+# ArmarX.navigator.mem.nav.param.Provider = ""
 
 
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment:  
 #  Attributes:
-#  - Default:            0.550000012
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment = ""
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigator.mem.nav.stack_result.Memory:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigator.mem.nav.stack_result.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            3000
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.navigator.mem.nav.stack_result.Provider = ""
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigator.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            0
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
-#  - Default:            false
+#  - Default:            Localization
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigator.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            1
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigator.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.navigator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.navigator.p.disableExecutor = false
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
 #  Attributes:
-#  - Default:            Info
+#  - Default:            0.550000012
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
-- 
GitLab


From 97fe7bdc1315ebc081d602e61237418a4a2d7b17 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 18:54:51 +0200
Subject: [PATCH 115/324] fixing HumanAwareNavigation scenario

---
 .../config/navigation_memory.cfg              | 163 +++++------
 .../HumanAwareNavigation/config/navigator.cfg | 260 ++++++++++--------
 2 files changed, 229 insertions(+), 194 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index 38cf4a09..4fd3110f 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -92,199 +92,202 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.NavigationMemory.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            ArVizStorage
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ArVizStorageName = ArVizStorage
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.NavigationMemory.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            ArVizTopic
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ArVizTopicName = ArVizTopic
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.NavigationMemory.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            false
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.EnableProfiling = false
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.NavigationMemory.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.NavigationMemory.MinimumLoggingLevel = Verbose
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ObjectName = ""
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.NavigationMemory.RemoteGuiName:  Name of the remote gui provider
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.RemoteGuiName = RemoteGuiProvider
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.NavigationMemory.mem.MemoryName:  Name of this memory server.
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.MemoryName = Navigation
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.NavigationMemory.mem.ltm.configuration:  
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            {}
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.configuration = {}
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Verbose
 
 
-# ArmarX.NavigationMemory.mem.ltm.enabled:  
+# ArmarX.navigation_memory.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            false
+#  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.enabled = false
+# ArmarX.navigation_memory.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.navigation_memory.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            true
+#  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled = true
+# ArmarX.navigation_memory.ArVizTopicName = ArVizTopic
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigation_memory.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName = MemoryNameSystem
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.EnableProfiling = false
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+# ArmarX.navigation_memory.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            2
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency = 2
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.navigation_memory.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+# ArmarX.navigation_memory.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
-#  - Default:            true
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges = true
+# ArmarX.navigation_memory.ObjectName = ""
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation:  Enable visualization of locations.
+# ArmarX.navigation_memory.RemoteGuiName:  Name of the remote gui provider
 #  Attributes:
-#  - Default:            true
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation = true
+# ArmarX.navigation_memory.RemoteGuiName = RemoteGuiProvider
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+# ArmarX.navigation_memory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.p.snapshotToLoad = ""
+# ArmarX.navigation_memory.mem.MemoryName = Navigation
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigation_memory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigation_memory.mem.ltm.configuration = {}
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigation_memory.mem.ltm.enabled:  
 #  Attributes:
-#  - Default:            3000
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.mem.ltm.enabled = false
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            0
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigation_memory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            false
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigation_memory.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            1
+#  - Default:            2
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 2
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges = true
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.navigation_memory.p.locationGraph.visuLocation:  Enable visualization of locations.
 #  Attributes:
-#  - Default:            false
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.navigation_memory.p.locationGraph.visuLocation = true
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.navigation_memory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
 #  Attributes:
-#  - Default:            Info
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+# ArmarX.navigation_memory.p.snapshotToLoad = ""
 
 
+# ArmarX.navigation_memory.MinimumLoggingLevel:  
+#  Attributes:
+ArmarX.navigation_memory.MinimumLoggingLevel = Verbose
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index 5d038290..7b44af1c 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -92,299 +92,331 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.Navigator.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.Navigator.ObjectName:  No Description
 #  Attributes:
-#  - Default:            ArVizStorage
-#  - Case sensitivity:   yes
+#  - Default:            navigator
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.Navigator.ArVizStorageName = ArVizStorage
+ArmarX.Navigator.ObjectName = navigator
 
 
-# ArmarX.Navigator.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.Navigator.RobotUnitName:  No Description
 #  Attributes:
-#  - Default:            ArVizTopic
-#  - Case sensitivity:   yes
+#  - Default:            Armar6Unit
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.Navigator.ArVizTopicName = ArVizTopic
+ArmarX.Navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Navigator.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+#  Attributes:
+#  - Default:            Armar6PlatformUnit
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
+
+
+# ArmarX.Navigator.p.disableExecutor:  No Description
 #  Attributes:
 #  - Default:            false
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.p.disableExecutor = false
+
+
+# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  No Description
+#  Attributes:
+#  - Default:            0.8
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.EnableProfiling = false
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.Navigator.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Navigator.MinimumLoggingLevel = Undefined
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.Navigator.ObjectMemoryName:  Name of the object memory.
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            ObjectMemory
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ObjectMemoryName = ObjectMemory
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.Navigator.ObjectName:  Name of IceGrid well-known object
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.ObjectName = navigator
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
+#  - Default:            1
 #  - Case sensitivity:   yes
-#  - Required:           yes
-ArmarX.Navigator.RobotUnitName = Armar6Unit
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
+#  - Default:            ""
+#  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.Navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.cmp.RemoteGui = RemoteGuiProvider
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment:  
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            Costmap
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment = Costmap
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Verbose
 
 
-# ArmarX.Navigator.mem.nav.costmap.Memory:  
+# ArmarX.navigator.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
+# ArmarX.navigator.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.Navigator.mem.nav.events.CoreSegment:  
+# ArmarX.navigator.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            Events
+#  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.CoreSegment = Events
+# ArmarX.navigator.ArVizTopicName = ArVizTopic
 
 
-# ArmarX.Navigator.mem.nav.events.Memory:  
+# ArmarX.navigator.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Memory = Navigation
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigator.EnableProfiling = false
 
 
-# ArmarX.Navigator.mem.nav.events.Provider:  Name of this provider
+# ArmarX.navigator.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Provider = ""
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.navigator.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.Navigator.mem.nav.graph.CoreSegment:  
+# ArmarX.navigator.ObjectMemoryName:  Name of the object memory.
 #  Attributes:
-#  - Default:            Location
+#  - Default:            ObjectMemory
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.CoreSegment = Location
+# ArmarX.navigator.ObjectMemoryName = ObjectMemory
 
 
-# ArmarX.Navigator.mem.nav.graph.Memory:  
+# ArmarX.navigator.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.Memory = Navigation
+# ArmarX.navigator.ObjectName = ""
 
 
-# ArmarX.Navigator.mem.nav.param.CoreSegment:  
+# ArmarX.navigator.RobotUnitName:  Name of the RobotUnit
 #  Attributes:
-#  - Default:            Parameterization
+#  - Case sensitivity:   yes
+#  - Required:           yes
+# ArmarX.navigator.RobotUnitName = ::_NOT_SET_::
+
+
+# ArmarX.navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
+#  Attributes:
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.CoreSegment = Parameterization
+# ArmarX.navigator.cmp.RemoteGui = RemoteGuiProvider
 
 
-# ArmarX.Navigator.mem.nav.param.Memory:  
+# ArmarX.navigator.mem.nav.costmap.CoreSegment:  
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            Costmap
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Memory = Navigation
+# ArmarX.navigator.mem.nav.costmap.CoreSegment = Costmap
 
 
-# ArmarX.Navigator.mem.nav.param.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.costmap.Memory:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Provider = ""
+# ArmarX.navigator.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment:  
+# ArmarX.navigator.mem.nav.events.CoreSegment:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Events
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment = ""
+# ArmarX.navigator.mem.nav.events.CoreSegment = Events
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Memory:  
+# ArmarX.navigator.mem.nav.events.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Memory = Navigation
+# ArmarX.navigator.mem.nav.events.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.events.Provider:  Name of this provider
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
+# ArmarX.navigator.mem.nav.events.Provider = ""
 
 
-# ArmarX.Navigator.mem.robot_state.Memory:  
+# ArmarX.navigator.mem.nav.graph.CoreSegment:  
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            Location
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.Memory = RobotState
+# ArmarX.navigator.mem.nav.graph.CoreSegment = Location
 
 
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.navigator.mem.nav.graph.Memory:  
 #  Attributes:
-#  - Default:            Localization
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
+# ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.navigator.mem.nav.param.CoreSegment:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            Parameterization
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled = true
+# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigator.mem.nav.param.Memory:  
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.navigator.mem.nav.param.Memory = Navigation
 
 
-# ArmarX.Navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
+# ArmarX.navigator.mem.nav.param.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            false
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-ArmarX.Navigator.p.disableExecutor = false
+# ArmarX.navigator.mem.nav.param.Provider = ""
 
 
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment:  
 #  Attributes:
-#  - Default:            0.550000012
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment = ""
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigator.mem.nav.stack_result.Memory:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigator.mem.nav.stack_result.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            3000
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.navigator.mem.nav.stack_result.Provider = ""
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigator.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            0
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
-#  - Default:            false
+#  - Default:            Localization
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigator.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            1
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigator.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.navigator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.navigator.p.disableExecutor = false
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
 #  Attributes:
-#  - Default:            Info
+#  - Default:            0.550000012
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+# ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.550000012
 
 
-- 
GitLab


From 2502c7ee2c34b0609e3e12544e11344317583535 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 19:17:05 +0200
Subject: [PATCH 116/324] Setup proxemic zone creator

---
 source/armarx/navigation/human/CMakeLists.txt                | 2 ++
 source/armarx/navigation/local_planning/CMakeLists.txt       | 1 +
 source/armarx/navigation/local_planning/TebObstacleManager.h | 4 ++++
 3 files changed, 7 insertions(+)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 76a44730..c0a1b74e 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -16,8 +16,10 @@ armarx_add_library(teb_human
     SOURCES
         types.cpp
         aron_conversions.cpp
+        ProxemicZoneCreator.cpp
     HEADERS
         types.h
         aron_conversions.h
         shapes.h
+        ProxemicZoneCreator.h
 )
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 9d0cd30a..91544733 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -10,6 +10,7 @@ armarx_add_library(local_planning
         armarx_navigation::core
         armarx_navigation::conversions
         armarx_navigation::local_planning_aron
+        armarx_navigation::teb_human
         # teb_extension::obstacles
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
index 185778f7..2ef318dc 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.h
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -24,6 +24,8 @@
 
 #include <RobotAPI/components/ArViz/Client/Layer.h>
 
+#include <armarx/navigation/human/ProxemicZoneCreator.h>
+#include <armarx/navigation/human/types.h>
 #include <teb_local_planner/obstacles.h>
 
 namespace armarx::navigation::local_planning
@@ -42,9 +44,11 @@ namespace armarx::navigation::local_planning
         size_t size();
 
         void addBoxObstacle(const VirtualRobot::BoundingBox& bbox, viz::Layer* visLayer = nullptr);
+        void addHumanObstacle(const human::Human& human, viz::Layer* visLayer = nullptr);
 
     private:
         teb_local_planner::ObstContainer& container;
+        human::ProxemicZoneCreator proxemics;
     };
 
 
-- 
GitLab


From 313373b82518e02e2b03d7c91032ebe53fb9331a Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 20:06:16 +0200
Subject: [PATCH 117/324] Implement TebObstacleManager for humans

---
 source/armarx/navigation/human/types.h        | 11 +++++
 .../navigation/local_planning/CMakeLists.txt  |  2 +-
 .../local_planning/TebObstacleManager.cpp     | 48 +++++++++++++++++++
 3 files changed, 60 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 5f65e1ba..76b726df 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -57,11 +57,22 @@ namespace armarx::navigation::human
 
     using HumanGroups = std::vector<HumanGroup>;
 
+    struct ExponentialPenaltyModel
+    {
+        float minDistance;
+        float epsilon;
+        float exponent;
+    };
 
     struct ProxemicZone
     {
         core::Pose2D pose;
         shapes::Ellipse shape;
+        ExponentialPenaltyModel penalty;
+        float weight;
+        bool homotopicRelevance = true;
     };
 
+    using ProxemicZones = std::vector<ProxemicZone>;
+
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 91544733..deba22fc 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -11,7 +11,7 @@ armarx_add_library(local_planning
         armarx_navigation::conversions
         armarx_navigation::local_planning_aron
         armarx_navigation::teb_human
-        # teb_extension::obstacles
+        teb_extension::obstacles
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
     DEPENDENCIES_LEGACY
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 72c3714f..cccd87f2 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -2,7 +2,10 @@
 
 #include <ArmarXCore/core/logging/Logging.h>
 
+#include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
+#include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
+#include <teb_local_planner/obstacles.h>
 
 namespace armarx::navigation::local_planning
 {
@@ -40,6 +43,7 @@ namespace armarx::navigation::local_planning
             const Eigen::Vector3f min = conv::fromRos(min);
             const Eigen::Vector3f max = conv::fromRos(max);
 
+            // TODO unique name
             visLayer->add(viz::Polygon("pol")
                               .addPoint(min)
                               .addPoint(Eigen::Vector3f(min.x(), max.y()))
@@ -49,4 +53,48 @@ namespace armarx::navigation::local_planning
         }
     }
 
+    void
+    TebObstacleManager::addHumanObstacle(const human::Human& human, viz::Layer* visLayer)
+    {
+        auto proxemicZones = proxemics.createProxemicZones(human);
+
+        for (auto& proxemicZone : proxemicZones)
+        {
+            auto& pose = proxemicZone.pose;
+            float angle = Eigen::Rotation2Df(pose.linear()).angle();
+            auto& shape = proxemicZone.shape;
+
+            auto obst = boost::make_shared<teb_local_planner::extension::EllipseObstacle>(
+                pose.translation(), angle, shape.a, shape.b);
+
+            auto& penalty = proxemicZone.penalty;
+
+            obst->setPenaltyModel(boost::make_shared<teb_local_planner::ExponentialPenaltyModel>(
+                teb_local_planner::LinearPenaltyModel(penalty.minDistance, penalty.epsilon),
+                penalty.exponent));
+
+            obst->setWeight(proxemicZone.weight);
+            obst->setHomotopicRelevance(proxemicZone.homotopicRelevance);
+
+            if (human.linearVelocity != Eigen::Vector2f::Zero())
+            {
+                obst->setCentroidVelocity(human.linearVelocity.cast<double>());
+            }
+
+            container.push_back(obst);
+
+            if (visLayer)
+            {
+                const Eigen::Vector3f axisLength(shape.a, shape.b, 0);
+                const core::Pose pose3d = conv::to3D(pose);
+
+                // TODO unique name
+                visLayer->add(viz::Ellipsoid("ell")
+                                  .pose(pose3d)
+                                  .axisLengths(axisLength)
+                                  .color(simox::Color::blue()));
+            }
+        }
+    }
+
 } // namespace armarx::navigation::local_planning
-- 
GitLab


From 94b185bc8ea1fbdead060b2f1d7186546b02f2b2 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 20:09:46 +0200
Subject: [PATCH 118/324] Create unique visualization ids

---
 .../armarx/navigation/local_planning/TebObstacleManager.cpp | 6 ++----
 .../armarx/navigation/local_planning/TebObstacleManager.h   | 1 +
 2 files changed, 3 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index cccd87f2..7b186e84 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -43,8 +43,7 @@ namespace armarx::navigation::local_planning
             const Eigen::Vector3f min = conv::fromRos(min);
             const Eigen::Vector3f max = conv::fromRos(max);
 
-            // TODO unique name
-            visLayer->add(viz::Polygon("pol")
+            visLayer->add(viz::Polygon("polygon_" + std::to_string(viualisationIndex++))
                               .addPoint(min)
                               .addPoint(Eigen::Vector3f(min.x(), max.y()))
                               .addPoint(max)
@@ -88,8 +87,7 @@ namespace armarx::navigation::local_planning
                 const Eigen::Vector3f axisLength(shape.a, shape.b, 0);
                 const core::Pose pose3d = conv::to3D(pose);
 
-                // TODO unique name
-                visLayer->add(viz::Ellipsoid("ell")
+                visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(viualisationIndex++))
                                   .pose(pose3d)
                                   .axisLengths(axisLength)
                                   .color(simox::Color::blue()));
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
index 2ef318dc..96e0582c 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.h
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -49,6 +49,7 @@ namespace armarx::navigation::local_planning
     private:
         teb_local_planner::ObstContainer& container;
         human::ProxemicZoneCreator proxemics;
+        int viualisationIndex;
     };
 
 
-- 
GitLab


From b0d7d3b5d3827026569bf11068574563ca9392be Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 20:12:13 +0200
Subject: [PATCH 119/324] Setup ProxemicZoneCreator

---
 .../navigation/human/ProxemicZoneCreator.cpp  | 13 +++++
 .../navigation/human/ProxemicZoneCreator.h    | 48 +++++++++++++++++++
 2 files changed, 61 insertions(+)
 create mode 100644 source/armarx/navigation/human/ProxemicZoneCreator.cpp
 create mode 100644 source/armarx/navigation/human/ProxemicZoneCreator.h

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.cpp b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
new file mode 100644
index 00000000..af8dde63
--- /dev/null
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
@@ -0,0 +1,13 @@
+#include "ProxemicZoneCreator.h"
+
+namespace armarx::navigation::human
+{
+
+    ProxemicZones
+    ProxemicZoneCreator::createProxemicZones(const Human& human)
+    {
+        return ProxemicZones();
+    }
+
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.h b/source/armarx/navigation/human/ProxemicZoneCreator.h
new file mode 100644
index 00000000..645cefa0
--- /dev/null
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.h
@@ -0,0 +1,48 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+#pragma once
+
+#include <armarx/navigation/human/types.h>
+
+namespace armarx::navigation::human
+{
+
+    class ProxemicZoneCreator
+    {
+
+    public:
+        struct ProxemicParameters
+        {
+        };
+
+        ProxemicZoneCreator() = default;
+        ProxemicZoneCreator(ProxemicParameters& params) : params(params)
+        {
+        }
+
+
+        ProxemicZones createProxemicZones(const Human& human);
+
+    private:
+        ProxemicParameters params;
+    };
+
+} // namespace armarx::navigation::human
-- 
GitLab


From 3880850f3b346d96558302c30cbcae7064d0b2a2 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 20:52:20 +0200
Subject: [PATCH 120/324] Proper armarx -> ros conversion

---
 .../navigation/local_planning/TebObstacleManager.cpp     | 9 ++++-----
 .../armarx/navigation/local_planning/ros_conversions.cpp | 5 +++++
 .../armarx/navigation/local_planning/ros_conversions.h   | 2 ++
 3 files changed, 11 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 7b186e84..56a78be7 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -59,12 +59,11 @@ namespace armarx::navigation::local_planning
 
         for (auto& proxemicZone : proxemicZones)
         {
-            auto& pose = proxemicZone.pose;
-            float angle = Eigen::Rotation2Df(pose.linear()).angle();
+            auto pose = conv::toRos(proxemicZone.pose);
             auto& shape = proxemicZone.shape;
 
             auto obst = boost::make_shared<teb_local_planner::extension::EllipseObstacle>(
-                pose.translation(), angle, shape.a, shape.b);
+                pose.position(), pose.theta(), shape.a / 1000, shape.b / 1000); // [mm] to [m]
 
             auto& penalty = proxemicZone.penalty;
 
@@ -77,7 +76,7 @@ namespace armarx::navigation::local_planning
 
             if (human.linearVelocity != Eigen::Vector2f::Zero())
             {
-                obst->setCentroidVelocity(human.linearVelocity.cast<double>());
+                obst->setCentroidVelocity(conv::toRos(human.linearVelocity));
             }
 
             container.push_back(obst);
@@ -85,7 +84,7 @@ namespace armarx::navigation::local_planning
             if (visLayer)
             {
                 const Eigen::Vector3f axisLength(shape.a, shape.b, 0);
-                const core::Pose pose3d = conv::to3D(pose);
+                const core::Pose pose3d = conv::to3D(human.pose);
 
                 visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(viualisationIndex++))
                                   .pose(pose3d)
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 8e88aa18..297a352d 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -14,6 +14,11 @@
 
 namespace armarx::navigation::conv
 {
+    Eigen::Vector2d
+    toRos(const Eigen::Vector2f& vec)
+    {
+        return vec.cast<double>() / 1000; // [mm] to [m]
+    }
 
     Eigen::Vector2d
     toRos(const Eigen::Vector3f& vec)
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 1f4dcaa4..65f9e6fd 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -30,6 +30,8 @@
 namespace armarx::navigation::conv
 {
 
+    Eigen::Vector2d toRos(const Eigen::Vector2f& vec);
+
     Eigen::Vector2d toRos(const Eigen::Vector3f& vec);
     Eigen::Vector3f fromRos(const Eigen::Vector2d& vec);
 
-- 
GitLab


From 78ea20c2b26164c33a55b5da3c8a47b0aa6683ea Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 21:43:26 +0200
Subject: [PATCH 121/324] More ros conversions

---
 source/armarx/navigation/human/types.h                   | 4 ++--
 .../navigation/local_planning/TebObstacleManager.cpp     | 7 ++++---
 .../armarx/navigation/local_planning/ros_conversions.cpp | 9 +++++++++
 .../armarx/navigation/local_planning/ros_conversions.h   | 2 ++
 4 files changed, 17 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index 76b726df..fe5490d5 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -59,8 +59,8 @@ namespace armarx::navigation::human
 
     struct ExponentialPenaltyModel
     {
-        float minDistance;
-        float epsilon;
+        float minDistance; // [m]
+        float epsilon; // [m]
         float exponent;
     };
 
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 56a78be7..235c5153 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -60,10 +60,11 @@ namespace armarx::navigation::local_planning
         for (auto& proxemicZone : proxemicZones)
         {
             auto pose = conv::toRos(proxemicZone.pose);
-            auto& shape = proxemicZone.shape;
+            auto shape = conv::toRos(proxemicZone.shape);
 
+            //swap a and b params, because ArmarX has y pointing forwards,
             auto obst = boost::make_shared<teb_local_planner::extension::EllipseObstacle>(
-                pose.position(), pose.theta(), shape.a / 1000, shape.b / 1000); // [mm] to [m]
+                pose.position(), pose.theta(), shape.a, shape.b);
 
             auto& penalty = proxemicZone.penalty;
 
@@ -83,7 +84,7 @@ namespace armarx::navigation::local_planning
 
             if (visLayer)
             {
-                const Eigen::Vector3f axisLength(shape.a, shape.b, 0);
+                const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
                 const core::Pose pose3d = conv::to3D(human.pose);
 
                 visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(viualisationIndex++))
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 297a352d..60fa5cbc 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -153,4 +153,13 @@ namespace armarx::navigation::conv
         return {trajectory};
     }
 
+    human::shapes::Ellipse
+    toRos(const human::shapes::Ellipse& ellipse)
+    {
+        // a,b parameter are along the x and y axis respectively
+        // ROS and ArmarX have the x axis pointing in a different direction
+        // ROS: x pointing forward, ArmarX: y pointing forward
+        return {.a = ellipse.b / 1000, .b = ellipse.a / 1000}; // [mm] to [m]
+    }
+
 } // namespace armarx::navigation::conv
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 65f9e6fd..20f8e1e3 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -23,6 +23,7 @@
 
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/types.h>
+#include <armarx/navigation/human/shapes.h>
 #include <geometry_msgs/Twist.h>
 #include <teb_local_planner/pose_se2.h>
 #include <teb_local_planner/timed_elastic_band.h>
@@ -46,5 +47,6 @@ namespace armarx::navigation::conv
 
     core::LocalTrajectory fromRos(const teb_local_planner::TimedElasticBand& teb);
 
+    human::shapes::Ellipse toRos(const human::shapes::Ellipse& ellipse);
 
 } // namespace armarx::navigation::conv
-- 
GitLab


From 6ad7e946b800c0748794e71ee7ab3052d0086e40 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 21:43:44 +0200
Subject: [PATCH 122/324] Implement ProxemicZoneCreator

---
 .../navigation/human/ProxemicZoneCreator.cpp  | 35 ++++++++++++++++++-
 .../navigation/human/ProxemicZoneCreator.h    | 24 +++++++++++--
 2 files changed, 56 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.cpp b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
index af8dde63..e6495840 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.cpp
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
@@ -1,12 +1,45 @@
 #include "ProxemicZoneCreator.h"
 
+#include <cmath>
+
 namespace armarx::navigation::human
 {
 
     ProxemicZones
     ProxemicZoneCreator::createProxemicZones(const Human& human)
     {
-        return ProxemicZones();
+        // intimate zone
+        ProxemicZone intimate{.pose = human.pose,
+                              .shape = {.a = params.intimateRadius, .b = params.intimateRadius},
+                              .penalty = intimatePenalty,
+                              .weight = params.intimateWeight};
+
+        // personal zone
+        auto& global_T_human = human.pose;
+        auto& global_V_offset = global_T_human * params.offset;
+
+        core::Pose2D pose = human.pose;
+        pose.translation() += global_V_offset;
+
+        float velocityNorm = human.linearVelocity.norm();
+        float movementStretch = 1 + velocityNorm * params.movementInfluence;
+        if (velocityNorm != 0)
+        {
+            // y pointing forward
+            float movementDirection =
+                std::atan2(human.linearVelocity.y(), human.linearVelocity.x()) - M_PI_2;
+            pose.linear() = Eigen::Rotation2Df(movementDirection).toRotationMatrix();
+            pose.translation() +=
+                human.linearVelocity / velocityNorm * params.personalRadius * (movementStretch - 1);
+        }
+
+        ProxemicZone personal{
+            .pose = pose,
+            .shape = {.a = params.personalRadius, .b = movementStretch * params.personalRadius},
+            .penalty = personalPenalty,
+            .weight = params.personalWeight};
+
+        return {intimate, personal};
     }
 
 
diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.h b/source/armarx/navigation/human/ProxemicZoneCreator.h
index 645cefa0..fa59e388 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.h
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.h
@@ -31,10 +31,28 @@ namespace armarx::navigation::human
     public:
         struct ProxemicParameters
         {
+            float intimateWeight = 2.0;
+            float personalWeight = 1.0;
+
+            float intimateRadius = 400;
+            float personalRadius = 1000;
+
+            float minDist = 450;
+            float movementInfluence = 1;
+            // in the coordinate system of the human
+            Eigen::Vector2f offset{100, 150};
         };
 
-        ProxemicZoneCreator() = default;
-        ProxemicZoneCreator(ProxemicParameters& params) : params(params)
+
+        ProxemicZoneCreator()
+        {
+            intimatePenalty = {.minDistance = 0.1, .epsilon = 0, .exponent = 1.2};
+            personalPenalty = {.minDistance = 0.1, .epsilon = 0, .exponent = 1.2};
+        }
+        ProxemicZoneCreator(ProxemicParameters& params,
+                            ExponentialPenaltyModel& intimatePenalty,
+                            ExponentialPenaltyModel& personalPenalty) :
+            params(params), intimatePenalty(intimatePenalty), personalPenalty(personalPenalty)
         {
         }
 
@@ -43,6 +61,8 @@ namespace armarx::navigation::human
 
     private:
         ProxemicParameters params;
+        ExponentialPenaltyModel intimatePenalty;
+        ExponentialPenaltyModel personalPenalty;
     };
 
 } // namespace armarx::navigation::human
-- 
GitLab


From ce1dd4afc9ef5833de3affdae5c36e5aad03c74a Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 22:06:32 +0200
Subject: [PATCH 123/324] Some fixes

---
 .../navigation/local_planning/CMakeLists.txt  |  1 +
 .../local_planning/TebObstacleManager.cpp     | 21 ++++++++++---------
 .../local_planning/TebObstacleManager.h       |  2 +-
 .../local_planning/TimedElasticBands.cpp      |  8 +++++++
 .../local_planning/ros_conversions.cpp        |  2 +-
 .../local_planning/ros_conversions.h          |  2 +-
 6 files changed, 23 insertions(+), 13 deletions(-)

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index deba22fc..ae184519 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -7,6 +7,7 @@ armarx_add_library(local_planning
     DEPENDENCIES_PUBLIC
         ArmarXCoreInterfaces
         ArmarXCore
+        ArViz
         armarx_navigation::core
         armarx_navigation::conversions
         armarx_navigation::local_planning_aron
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 235c5153..6adb5614 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -14,6 +14,7 @@ namespace armarx::navigation::local_planning
     TebObstacleManager::clear()
     {
         container.clear();
+        visualizationIndex = 0;
     }
 
     size_t
@@ -40,14 +41,14 @@ namespace armarx::navigation::local_planning
 
         if (visLayer)
         {
-            const Eigen::Vector3f min = conv::fromRos(min);
-            const Eigen::Vector3f max = conv::fromRos(max);
-
-            visLayer->add(viz::Polygon("polygon_" + std::to_string(viualisationIndex++))
-                              .addPoint(min)
-                              .addPoint(Eigen::Vector3f(min.x(), max.y()))
-                              .addPoint(max)
-                              .addPoint(Eigen::Vector3f(max.x(), min.y()))
+            const Eigen::Vector3f min3d = conv::fromRos(min);
+            const Eigen::Vector3f max3d = conv::fromRos(max);
+
+            visLayer->add(viz::Polygon("polygon_" + std::to_string(visualizationIndex++))
+                              .addPoint(min3d)
+                              .addPoint(Eigen::Vector3f(min3d.x(), max3d.y(), 0))
+                              .addPoint(max3d)
+                              .addPoint(Eigen::Vector3f(max3d.x(), min3d.y(), 0))
                               .color(simox::Color::gray()));
         }
     }
@@ -77,7 +78,7 @@ namespace armarx::navigation::local_planning
 
             if (human.linearVelocity != Eigen::Vector2f::Zero())
             {
-                obst->setCentroidVelocity(conv::toRos(human.linearVelocity));
+                obst->setCentroidVelocity(conv::toRos2D(human.linearVelocity));
             }
 
             container.push_back(obst);
@@ -87,7 +88,7 @@ namespace armarx::navigation::local_planning
                 const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
                 const core::Pose pose3d = conv::to3D(human.pose);
 
-                visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(viualisationIndex++))
+                visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(visualizationIndex++))
                                   .pose(pose3d)
                                   .axisLengths(axisLength)
                                   .color(simox::Color::blue()));
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
index 96e0582c..b336b65b 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.h
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -49,7 +49,7 @@ namespace armarx::navigation::local_planning
     private:
         teb_local_planner::ObstContainer& container;
         human::ProxemicZoneCreator proxemics;
-        int viualisationIndex;
+        int visualizationIndex;
     };
 
 
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index a926bd71..54c9700c 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -159,6 +159,14 @@ namespace armarx::navigation::local_planning
                 obstManager.addBoxObstacle(obst->getGlobalBoundingBox(), visPtr);
             }
         }
+        if (scene.dynamicScene)
+        {
+            //TODO include humans in dynamic scene
+            //for (const auto& obst : scene.dynamicScene.value().humans)
+            //{
+            //   obstManager.addHumanObstacle(obst, visPtr);
+            //}
+        }
 
         if (arviz)
         {
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 60fa5cbc..4bb21ef4 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -15,7 +15,7 @@
 namespace armarx::navigation::conv
 {
     Eigen::Vector2d
-    toRos(const Eigen::Vector2f& vec)
+    toRos2D(const Eigen::Vector2f& vec)
     {
         return vec.cast<double>() / 1000; // [mm] to [m]
     }
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 20f8e1e3..548dce73 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -31,7 +31,7 @@
 namespace armarx::navigation::conv
 {
 
-    Eigen::Vector2d toRos(const Eigen::Vector2f& vec);
+    Eigen::Vector2d toRos2D(const Eigen::Vector2f& vec);
 
     Eigen::Vector2d toRos(const Eigen::Vector3f& vec);
     Eigen::Vector3f fromRos(const Eigen::Vector2d& vec);
-- 
GitLab


From dac86032990494a57d1323920a89bdf6ca552b95 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 22:21:43 +0200
Subject: [PATCH 124/324] Remove unnecessary parameter

---
 source/armarx/navigation/human/ProxemicZoneCreator.h | 1 -
 1 file changed, 1 deletion(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.h b/source/armarx/navigation/human/ProxemicZoneCreator.h
index fa59e388..d1696db4 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.h
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.h
@@ -37,7 +37,6 @@ namespace armarx::navigation::human
             float intimateRadius = 400;
             float personalRadius = 1000;
 
-            float minDist = 450;
             float movementInfluence = 1;
             // in the coordinate system of the human
             Eigen::Vector2f offset{100, 150};
-- 
GitLab


From f9001ab0911fbe94eb4686e24bbd5a53e5f387b9 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 18 Aug 2022 22:47:16 +0200
Subject: [PATCH 125/324] Remove leftover comment

---
 source/armarx/navigation/local_planning/TebObstacleManager.cpp | 1 -
 1 file changed, 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 6adb5614..e5a903ce 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -63,7 +63,6 @@ namespace armarx::navigation::local_planning
             auto pose = conv::toRos(proxemicZone.pose);
             auto shape = conv::toRos(proxemicZone.shape);
 
-            //swap a and b params, because ArmarX has y pointing forwards,
             auto obst = boost::make_shared<teb_local_planner::extension::EllipseObstacle>(
                 pose.position(), pose.theta(), shape.a, shape.b);
 
-- 
GitLab


From c8017d983d9056ab5563bee1fe5c064208e931e7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 22:56:22 +0200
Subject: [PATCH 126/324] human reader plugin

---
 source/armarx/navigation/components/navigator/Component.cpp | 1 +
 source/armarx/navigation/components/navigator/Component.h   | 6 +++++-
 2 files changed, 6 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 40f41ce2..e8612e91 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -123,6 +123,7 @@ namespace armarx::navigation::components::navigator
         addPlugin(resultsWriterPlugin);
         addPlugin(graphReaderPlugin);
         addPlugin(costmapReaderPlugin);
+        addPlugin(humanReaderPlugin);
 
         addPlugin(virtualRobotReaderPlugin);
 
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index 8b2b3467..7462c3d7 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -50,6 +50,8 @@
 #include <RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h>
 
 #include <armarx/control/client/ComponentPlugin.h>
+
+#include <armarx/navigation/memory/client/human/Reader.h>
 #include <armarx/navigation/components/navigator/RemoteGui.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/memory/client/graph/Reader.h>
@@ -194,6 +196,8 @@ namespace armarx::navigation::components::navigator
             graphReaderPlugin = nullptr;
         armem::client::plugins::ReaderWriterPlugin<memory::client::costmap::Reader>*
             costmapReaderPlugin = nullptr;
+        armem::client::plugins::ReaderWriterPlugin<memory::client::human::Reader>*
+            humanReaderPlugin = nullptr;
 
         // armem::vision::occupancy_grid::client::Reader occupancyGridReader;
 
@@ -217,4 +221,4 @@ namespace armarx::navigation::components::navigator
 
         Parameters params;
     };
-}  // namespace armarx::navigation::components::navigator
+} // namespace armarx::navigation::components::navigator
-- 
GitLab


From 7961d63d548e201b21c71e6f869ba857738d8d6c Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 22:56:46 +0200
Subject: [PATCH 127/324] navigator: remotegui as optional

---
 source/armarx/navigation/components/navigator/Component.cpp | 2 +-
 source/armarx/navigation/components/navigator/Component.h   | 4 +---
 2 files changed, 2 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index e8612e91..b5dff818 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -191,7 +191,7 @@ namespace armarx::navigation::components::navigator
         // memoryIntrospector = server::MemoryIntrospector(resultsWriterPlugin->get(), );
 
 
-        navRemoteGui = std::make_unique<navigator::RemoteGui>(remoteGui, *this);
+        navRemoteGui.emplace(remoteGui, *this);
         navRemoteGui->enable();
 
         initialized = true;
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index 7462c3d7..316e4da5 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -176,9 +176,7 @@ namespace armarx::navigation::components::navigator
 
         std::mutex propertiesMutex;
 
-        // TODO maybe as optional, but requires some effort
-        std::unique_ptr<armarx::navigation::components::navigator::RemoteGui> navRemoteGui;
-
+        std::optional<armarx::navigation::components::navigator::RemoteGui> navRemoteGui;
 
         // unique_ptr to avoid dangling refs
         std::vector<std::unique_ptr<server::MemoryIntrospector>> memoryIntrospectors;
-- 
GitLab


From 6f5e92d3c30d35cb4722d7996eb0b92de33cfc71 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 23:15:53 +0200
Subject: [PATCH 128/324] scene provider: adding human reader

---
 .../server/scene_provider/SceneProvider.cpp   | 20 ++++++++++------
 .../server/scene_provider/SceneProvider.h     | 24 +++++++++++++++++--
 2 files changed, 35 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index 6ab93b8f..26d9cd41 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -2,17 +2,20 @@
 
 #include <VirtualRobot/SceneObjectSet.h>
 
-#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
-#include "ArmarXCore/core/logging/Logging.h"
-#include "ArmarXCore/core/time/Clock.h"
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/Clock.h>
 
-#include "RobotAPI/libraries/armem_robot/types.h"
+#include <RobotAPI/libraries/armem_robot/types.h>
 
-#include "armarx/navigation/core/types.h"
-#include "armarx/navigation/memory/client/costmap/Reader.h"
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
+#include <armarx/navigation/core/types.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/graph/Reader.h>
+#include <armarx/navigation/memory/client/human/Reader.h>
 #include <armarx/navigation/util/util.h>
 
+
 namespace armarx::navigation::server::scene_provider
 {
 
@@ -113,7 +116,10 @@ namespace armarx::navigation::server::scene_provider
     core::DynamicScene
     SceneProvider::getDynamicScene(const DateTime& timestamp) const
     {
-        return {}; // FIXME implement
+        const memory::client::human::Reader::Query query{.providerName = config.humanProviderName,
+                                                         .timestamp = timestamp};
+
+        return {.humans = srv.humanReader->queryHumans(query).humans};
     }
 
     core::SceneGraph
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.h b/source/armarx/navigation/server/scene_provider/SceneProvider.h
index a71a958f..1f21e85e 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.h
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.h
@@ -31,12 +31,28 @@
 
 #include <armarx/navigation/core/DynamicScene.h>
 #include <armarx/navigation/core/StaticScene.h>
-#include <armarx/navigation/memory/client/costmap/Reader.h>
-#include <armarx/navigation/memory/client/graph/Reader.h>
 #include <armarx/navigation/core/types.h>
+#include <armarx/navigation/memory/client/human/Reader.h>
 #include <armarx/navigation/server/scene_provider/SceneProviderInterface.h>
 
 
+namespace armarx::navigation::memory::client
+{
+    namespace graph
+    {
+        class Reader;
+    }
+    namespace costmap
+    {
+        class Reader;
+    }
+    namespace human
+    {
+        class Reader;
+    }
+} // namespace armarx::navigation::memory::client
+
+
 namespace armarx::navigation::server::scene_provider
 {
 
@@ -54,6 +70,8 @@ namespace armarx::navigation::server::scene_provider
             // `robot_state` memory reader and writer
             armem::robot_state::VirtualRobotReader* virtualRobotReader;
 
+            memory::client::human::Reader* humanReader;
+
             objpose::ObjectPoseClient objectPoseClient;
         };
 
@@ -63,6 +81,8 @@ namespace armarx::navigation::server::scene_provider
 
             std::string staticCostmapProviderName = "distance_to_obstacle_costmap_provider";
             std::string staticCostmapName = "distance_to_obstacles";
+
+            std::string humanProviderName = "dynamic_scene_provider";
         };
 
         SceneProvider(const InjectedServices& srv, const Config& config);
-- 
GitLab


From c126f89b65f8d6055880e0601ebfa0aafa133c78 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 23:16:03 +0200
Subject: [PATCH 129/324] dynamic scene: adding humans

---
 source/armarx/navigation/core/DynamicScene.h | 9 +++------
 1 file changed, 3 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/core/DynamicScene.h b/source/armarx/navigation/core/DynamicScene.h
index 05f211a9..172957d0 100644
--- a/source/armarx/navigation/core/DynamicScene.h
+++ b/source/armarx/navigation/core/DynamicScene.h
@@ -23,17 +23,14 @@
 #pragma once
 
 
+#include <armarx/navigation/human/types.h>
+
 namespace armarx::navigation::core
 {
 
     struct DynamicScene
     {
-
-            // TODO(SALt): Implement
-
-    public:
-    protected:
-    private:
+        human::Humans humans;
     };
 
 } // namespace armarx::navigation::core
-- 
GitLab


From 9ba0352267389370bf3d08b92bb9f17dc78be2ef Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 23:16:37 +0200
Subject: [PATCH 130/324] navigator: human readerwriter plugin

---
 source/armarx/navigation/components/navigator/Component.cpp | 6 ++++--
 1 file changed, 4 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index b5dff818..25dbba4c 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -66,8 +66,9 @@
 #include <RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
-#include "armarx/navigation/server/execution/ExecutorInterface.h"
-#include "armarx/navigation/server/scene_provider/SceneProvider.h"
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/server/execution/ExecutorInterface.h>
+#include <armarx/navigation/server/scene_provider/SceneProvider.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
 #include <armarx/navigation/algorithms/astar/util.h>
@@ -165,6 +166,7 @@ namespace armarx::navigation::components::navigator
                 .graphReader = &graphReaderPlugin->get(),
                 .costmapReader = &costmapReaderPlugin->get(),
                 .virtualRobotReader = &virtualRobotReaderPlugin->get(),
+                .humanReader = &humanReaderPlugin->get(),
                 .objectPoseClient = ObjectPoseClientPluginUser::getClient()};
 
             const std::string robotName = getControlComponentPlugin()
-- 
GitLab


From cbd3b908e5f27595793ce9c6c1c2aacca0594734 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 23:17:29 +0200
Subject: [PATCH 131/324] timedelasticbands: activated 
 obstManager.addHumanObstacle

---
 .../local_planning/TimedElasticBands.cpp          | 15 ++++++++-------
 1 file changed, 8 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 54c9700c..b9a9d0b3 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -145,7 +145,7 @@ namespace armarx::navigation::local_planning
 
         viz::Layer* visPtr = nullptr;
         viz::Layer visLayer;
-        if (arviz)
+        if (arviz != nullptr)
         {
             visLayer = arviz->layer("local_planner_obstacles");
             visPtr = &visLayer;
@@ -154,6 +154,7 @@ namespace armarx::navigation::local_planning
 
         if (scene.staticScene)
         {
+            ARMARX_CHECK(scene.staticScene.has_value());
             for (const auto& obst : scene.staticScene.value().objects->getCollisionModels())
             {
                 obstManager.addBoxObstacle(obst->getGlobalBoundingBox(), visPtr);
@@ -161,14 +162,14 @@ namespace armarx::navigation::local_planning
         }
         if (scene.dynamicScene)
         {
-            //TODO include humans in dynamic scene
-            //for (const auto& obst : scene.dynamicScene.value().humans)
-            //{
-            //   obstManager.addHumanObstacle(obst, visPtr);
-            //}
+            ARMARX_CHECK(scene.dynamicScene.has_value());
+            for (const auto& obst : scene.dynamicScene.value().humans)
+            {
+              obstManager.addHumanObstacle(obst, visPtr);
+            }
         }
 
-        if (arviz)
+        if (arviz != nullptr)
         {
             arviz->commit(visLayer);
         }
-- 
GitLab


From 6f52f9814edab484754bb4a67da0cb007a03aa03 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 18 Aug 2022 23:17:38 +0200
Subject: [PATCH 132/324] navigator: minor

---
 .../armarx/navigation/components/navigator/Component.cpp  | 2 +-
 .../navigation/local_planning/TebObstacleManager.cpp      | 8 ++++----
 2 files changed, 5 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 25dbba4c..4cf28549 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -56,7 +56,7 @@
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
-#include "ArmarXGui/libraries/RemoteGui/Client/Widgets.h"
+#include <ArmarXGui/libraries/RemoteGui/Client/Widgets.h>
 
 #include <RobotAPI/components/ArViz/Client/Client.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 6adb5614..1e395628 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -39,7 +39,7 @@ namespace armarx::navigation::local_planning
         obst->finalizePolygon();
         container.push_back(obst);
 
-        if (visLayer)
+        if (visLayer != nullptr)
         {
             const Eigen::Vector3f min3d = conv::fromRos(min);
             const Eigen::Vector3f max3d = conv::fromRos(max);
@@ -58,7 +58,7 @@ namespace armarx::navigation::local_planning
     {
         auto proxemicZones = proxemics.createProxemicZones(human);
 
-        for (auto& proxemicZone : proxemicZones)
+        for (const auto& proxemicZone : proxemicZones)
         {
             auto pose = conv::toRos(proxemicZone.pose);
             auto shape = conv::toRos(proxemicZone.shape);
@@ -67,7 +67,7 @@ namespace armarx::navigation::local_planning
             auto obst = boost::make_shared<teb_local_planner::extension::EllipseObstacle>(
                 pose.position(), pose.theta(), shape.a, shape.b);
 
-            auto& penalty = proxemicZone.penalty;
+            const auto& penalty = proxemicZone.penalty;
 
             obst->setPenaltyModel(boost::make_shared<teb_local_planner::ExponentialPenaltyModel>(
                 teb_local_planner::LinearPenaltyModel(penalty.minDistance, penalty.epsilon),
@@ -83,7 +83,7 @@ namespace armarx::navigation::local_planning
 
             container.push_back(obst);
 
-            if (visLayer)
+            if (visLayer != nullptr)
             {
                 const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
                 const core::Pose pose3d = conv::to3D(human.pose);
-- 
GitLab


From 15826b17cabb1551c14899023636c9df0334d134 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 19:31:49 +0200
Subject: [PATCH 133/324] first draft: update navigator

---
 .../components/example_client/Component.cpp   |  90 +++++++++-
 .../components/example_client/Component.h     |  14 ++
 ...ulatedObjectLocalizerDynamicSimulation.cfg |   8 -
 .../HandUnitDynamicSimulationApp.LeftHand.cfg |  17 ++
 ...HandUnitDynamicSimulationApp.RightHand.cfg |  17 ++
 .../config/ObjectMemory.cfg                   |  26 +--
 .../config/RobotUnitSimulationApp.cfg         |   2 +-
 .../SelfLocalizationDynamicSimulationApp.cfg  |  39 +++--
 .../config/SimulatorViewerApp.cfg             |  74 ++-------
 .../config/VisionMemory.cfg                   |  26 +--
 .../config/ObjectMemory.cfg                   |  97 ++++++++++-
 .../config/VisionMemory.cfg                   |  97 ++++++++++-
 .../config/example_client.cfg                 |  36 ----
 .../config/navigation_memory.cfg              |  22 ++-
 .../PlatformNavigation/config/navigator.cfg   |  51 ++++--
 .../navigation/client/ComponentPlugin.cpp     | 150 ++++++++---------
 source/armarx/navigation/client/Navigator.cpp |   7 +
 source/armarx/navigation/client/Navigator.h   |   2 +
 .../client/ice/NavigatorInterface.ice         |   2 +
 .../client/services/IceNavigator.cpp          |  12 ++
 .../navigation/client/services/IceNavigator.h |   5 +
 .../components/navigator/CMakeLists.txt       |  11 +-
 .../components/navigator/Component.cpp        |  84 +++++++++-
 .../components/navigator/Component.h          |  11 +-
 .../navigation/core/NavigatorInterface.h      |   6 +
 source/armarx/navigation/server/Navigator.cpp | 155 ++++++++++++++++--
 source/armarx/navigation/server/Navigator.h   |  13 ++
 27 files changed, 773 insertions(+), 301 deletions(-)

diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index afbf7503..7b48c323 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -36,10 +36,11 @@
 #include <ArmarXCore/core/time/forward_declarations.h>
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
-#include <armarx/navigation/client/types.h>
-#include <armarx/navigation/global_planning/Point2Point.h>
+#include "armarx/navigation/core/types.h"
 #include <armarx/navigation/client/PathBuilder.h>
+#include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
+#include <armarx/navigation/global_planning/Point2Point.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
@@ -68,7 +69,7 @@ namespace armarx::navigation::components::example_client
     void
     Component::onConnectComponent()
     {
-        task = new armarx::RunningTask<Component>(this, &Component::exampleNavigationPointToPoint);
+        task = new armarx::RunningTask<Component>(this, &Component::run);
         task->start();
     }
 
@@ -94,6 +95,74 @@ namespace armarx::navigation::components::example_client
         return "ExampleClient";
     }
 
+    void
+    Component::run()
+    {
+        switch (properties.mode)
+        {
+
+            case Mode::Standard:
+                ARMARX_IMPORTANT << "Running `Mode::Standard`";
+                exampleNavigation();
+                break;
+            case Mode::Complex:
+                ARMARX_IMPORTANT << "Running `Mode::Complex`";
+                exampleNavigationComplex();
+                break;
+            case Mode::PointToPoint:
+                ARMARX_IMPORTANT << "Running `Mode::PointToPoint`";
+                exampleNavigationPointToPoint();
+                break;
+            case Mode::UpdateNavigator:
+                ARMARX_IMPORTANT << "Running `Mode::UpdateNavigator`";
+                exampleNavigationUpdateNavigator();
+                break;
+        }
+    }
+
+    void
+    Component::exampleNavigationUpdateNavigator()
+    {
+        // Import relevant namespaces.
+        using namespace armarx::navigation;
+
+        ARMARX_INFO << "Configuring navigator";
+
+        // Create an example configuration valid for the following move* calls.
+        configureNavigator(
+            client::NavigationStackConfig()
+                .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
+                .globalPlanner(global_planning::AStarParams())
+                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));
+
+        // Example of registering a lambda as callback.
+        getNavigator().onGoalReached([&]() { ARMARX_IMPORTANT << "Goal reached!"; });
+
+        // Start moving to goal position using above config.
+
+        ARMARX_INFO << "Moving to goal pose";
+        core::Pose goal = core::Pose::Identity();
+        goal.translation() << 2000, 1000, 0;
+        getNavigator().moveTo({goal}, core::NavigationFrame::Absolute);
+        Clock::WaitFor(Duration::Seconds(1.0));
+
+
+        // after short period of time (before goal is reached), change goal
+        const std::vector<core::Pose> goals{
+            core::Pose(Eigen::Translation3f{1000, 2000, 0}),
+            core::Pose(Eigen::Translation3f{3000, 0, 0}),
+            core::Pose(Eigen::Translation3f{5000, 1000, 0}),
+        };
+
+        while (true)
+        {
+            for (const auto& nextGoal : goals)
+            {
+                Clock::WaitFor(Duration::Seconds(1.0));
+                getNavigator().update({nextGoal}, core::NavigationFrame::Absolute);
+            }
+        }
+    }
 
     void
     Component::exampleNavigation()
@@ -108,7 +177,8 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::AStarParams())
-                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));  // FIXME
+                .trajectoryController(
+                    traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
         // Example of registering a lambda as callback.
         getNavigator().onGoalReached([&]() { ARMARX_IMPORTANT << "Goal reached! (lambda-style)"; });
@@ -207,7 +277,8 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::AStarParams())
-                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));  // FIXME
+                .trajectoryController(
+                    traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
         // Example of registering a lambda as callback.
         getNavigator().onGoalReached([&]() { ARMARX_IMPORTANT << "Goal reached! (lambda-style)"; });
@@ -283,7 +354,8 @@ namespace armarx::navigation::components::example_client
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
                 .globalPlanner(global_planning::Point2PointParams())
-                .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
+                .trajectoryController(
+                    traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
         Clock::WaitFor(Duration::Seconds(1));
 
@@ -366,6 +438,12 @@ namespace armarx::navigation::components::example_client
                       "relativeMovement",
                       "The distance between two target poses [mm]");
 
+        def->optional(properties.mode, "mode", "Which example to run")
+            .map({{"standard", Mode::Standard},
+                  {"complex", Mode::Complex},
+                  {"point_to_point", Mode::PointToPoint},
+                  {"update_navigator", Mode::UpdateNavigator}});
+
         return def;
     }
 
diff --git a/examples/components/example_client/Component.h b/examples/components/example_client/Component.h
index 295d1964..2e622a35 100644
--- a/examples/components/example_client/Component.h
+++ b/examples/components/example_client/Component.h
@@ -35,6 +35,14 @@
 namespace armarx::navigation::components::example_client
 {
 
+    enum class Mode
+    {
+        Standard,
+        Complex,
+        PointToPoint,
+        UpdateNavigator
+    };
+
     /**
      * @defgroup Component-ExampleClient ExampleClient
      * @ingroup armarx_navigation-Components
@@ -75,6 +83,8 @@ namespace armarx::navigation::components::example_client
 
         std::string getDefaultName() const override;
 
+        void run();
+
         void exampleNavigation();
         void exampleNavigationComplex();
 
@@ -91,12 +101,16 @@ namespace armarx::navigation::components::example_client
          */
         void exampleNavigationPointToPoint();
 
+        void exampleNavigationUpdateNavigator();
+
     private:
         void goalReached();
 
         struct{
             std::string robotName = "Armar6";
             float relativeMovement = 200; // [mm]
+
+            Mode mode = Mode::Standard;
         } properties;
 
         armarx::RunningTask<Component>::pointer_type task;
diff --git a/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg b/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
index a64fd58d..7c4574e0 100644
--- a/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
+++ b/scenarios/NavigationSimulation/config/ArticulatedObjectLocalizerDynamicSimulation.cfg
@@ -133,14 +133,6 @@ ArmarX.ArticulatedObjectLocalizerDynamicSimulation.mem.obj.articulated.ProviderN
 # ArmarX.ArticulatedObjectLocalizerDynamicSimulation.objects = Default value not mapped.
 
 
-# ArmarX.ArticulatedObjectLocalizerDynamicSimulation.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
-#  Attributes:
-#  - Default:            MemoryUpdates
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ArticulatedObjectLocalizerDynamicSimulation.tpc.sub.MemoryListener = MemoryUpdates
-
-
 # ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
 #  Attributes:
 #  - Default:            mongo/.cache
diff --git a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
index 18e2d2db..aa21b8fd 100644
--- a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
+++ b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.LeftHand.cfg
@@ -139,6 +139,23 @@ ArmarX.HandUnitDynamicSimulation.ObjectName = LeftHandUnit
 # ArmarX.HandUnitDynamicSimulation.SimulatorProxyName = Simulator
 
 
+# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory:  Require the legacy MemoryX working memory to be available before starting.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory = false
+
+
+# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName:  Name of the object pose storage (only used if necessary).
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName = ObjectMemory
+
+
 # ArmarX.HandUnitDynamicSimulation.inheritFrom:  No Description
 #  Attributes:
 #  - Default:            RobotConfig
diff --git a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
index 85cc4345..b92bb000 100644
--- a/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
+++ b/scenarios/NavigationSimulation/config/HandUnitDynamicSimulationApp.RightHand.cfg
@@ -139,6 +139,23 @@ ArmarX.HandUnitDynamicSimulation.ObjectName = RightHandUnit
 # ArmarX.HandUnitDynamicSimulation.SimulatorProxyName = Simulator
 
 
+# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory:  Require the legacy MemoryX working memory to be available before starting.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HandUnitDynamicSimulation.UseLegacyWorkingMemory = false
+
+
+# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName:  Name of the object pose storage (only used if necessary).
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HandUnitDynamicSimulation.cmp.ObjectPoseStorageName = ObjectMemory
+
+
 # ArmarX.HandUnitDynamicSimulation.inheritFrom:  No Description
 #  Attributes:
 #  - Default:            RobotConfig
diff --git a/scenarios/NavigationSimulation/config/ObjectMemory.cfg b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
index ed320714..a1b9d81c 100644
--- a/scenarios/NavigationSimulation/config/ObjectMemory.cfg
+++ b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
@@ -513,37 +513,21 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..configuration:  
+# ArmarX.ObjectMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..configuration = ""
+# ArmarX.ObjectMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.ObjectMemory.mem.ltm..enabled:  
+# ArmarX.ObjectMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm..enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.ObjectMemory.mem.ltm.enabled = false
 
 
 # ArmarX.ObjectMemory.mem.robot_state.Memory:  
diff --git a/scenarios/NavigationSimulation/config/RobotUnitSimulationApp.cfg b/scenarios/NavigationSimulation/config/RobotUnitSimulationApp.cfg
index 47323755..10974951 100644
--- a/scenarios/NavigationSimulation/config/RobotUnitSimulationApp.cfg
+++ b/scenarios/NavigationSimulation/config/RobotUnitSimulationApp.cfg
@@ -474,7 +474,7 @@ ArmarX.RobotUnitSimulation.PlatformUnitName = Armar6PlatformUnit
 # ArmarX.RobotUnitSimulation.RTLogging_DefaultLog = ""
 
 
-# ArmarX.RobotUnitSimulation.RTLogging_KeepIterationsForMs:  All logging data (SensorValues, ControlTargets, Messages) is keept for this duration and can be dunped in case of an error.
+# ArmarX.RobotUnitSimulation.RTLogging_KeepIterationsForMs:  All logging data (SensorValues, ControlTargets, Messages) is kept for this duration and can be dumped in case of an error.
 #  Attributes:
 #  - Default:            60000
 #  - Case sensitivity:   yes
diff --git a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
index 1dab8f00..b8200627 100644
--- a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
+++ b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
@@ -175,23 +175,32 @@ ArmarX.SelfLocalizationDynamicSimulation.RobotName = Armar6
 # ArmarX.SelfLocalizationDynamicSimulation.cmp.Simulator = Simulator
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.cmp.WorkingMemory:  Ice object name of the `WorkingMemory` component.
+# ArmarX.SelfLocalizationDynamicSimulation.cycleTime:  
 #  Attributes:
-#  - Default:            WorkingMemory
+#  - Default:            30
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SelfLocalizationDynamicSimulation.cmp.WorkingMemory = WorkingMemory
+# ArmarX.SelfLocalizationDynamicSimulation.cycleTime = 30
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.cycleTime:  
+# ArmarX.SelfLocalizationDynamicSimulation.localizationUnit.proxyName:  If enabled, connects to the localization unit
 #  Attributes:
-#  - Default:            30
+#  - Default:            LocalizationUnit
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SelfLocalizationDynamicSimulation.cycleTime = 30
+# ArmarX.SelfLocalizationDynamicSimulation.localizationUnit.proxyName = LocalizationUnit
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.longterm_memory:  Ice object name of the `LongtermMemory` component.
+# ArmarX.SelfLocalizationDynamicSimulation.localizationUnit.use:  If enabled, connects to the localization unit
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SelfLocalizationDynamicSimulation.localizationUnit.use = true
+
+
+# ArmarX.SelfLocalizationDynamicSimulation.longterm_memory:  Which legacy long-term memory to use if longterm_memory.updateor longterm_memory.retrieve_initial_pose are set
 #  Attributes:
 #  - Default:            LongtermMemory
 #  - Case sensitivity:   yes
@@ -291,6 +300,14 @@ ArmarX.SelfLocalizationDynamicSimulation.mem.robot_state.Memory = RobotState
 # ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.GlobalRobotPoseLocalization = GlobalRobotPoseLocalization
 
 
+# ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.GlobalRobotPoseLocalizationCorrection:  Name of the `GlobalRobotPoseLocalizationCorrection` topic to publish data to.
+#  Attributes:
+#  - Default:            GlobalRobotPoseLocalizationCorrection
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.GlobalRobotPoseLocalizationCorrection = GlobalRobotPoseLocalizationCorrection
+
+
 # ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.LaserScannerSelfLocalisation:  Name of the `LaserScannerSelfLocalisation` topic to publish data to.
 #  Attributes:
 #  - Default:            LaserScannerSelfLocalisation
@@ -307,14 +324,6 @@ ArmarX.SelfLocalizationDynamicSimulation.mem.robot_state.Memory = RobotState
 # ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.PlatformUnit = PlatformUnit
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
-#  Attributes:
-#  - Default:            MemoryUpdates
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SelfLocalizationDynamicSimulation.tpc.sub.MemoryListener = MemoryUpdates
-
-
 # ArmarX.SelfLocalizationDynamicSimulation.working_memory.update:  If enabled, updates the global pose in the working memory
 #  Attributes:
 #  - Default:            true
diff --git a/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg b/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
index d514a485..74604be7 100644
--- a/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
+++ b/scenarios/NavigationSimulation/config/SimulatorViewerApp.cfg
@@ -117,73 +117,14 @@
 # ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.SimulatorViewer_EntityDrawer.CommonStorageName:  Name of the the CommonStorage memory component
+# ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel:  No Description
 #  Attributes:
-#  - Default:            CommonStorage
-#  - Case sensitivity:   yes
+#  - Default:            Verbose
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.SimulatorViewer_EntityDrawer.CommonStorageName = CommonStorage
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerSelectionTopic:  Name of the DebugDrawerSelectionTopic
-#  Attributes:
-#  - Default:            DebugDrawerSelections
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerSelectionTopic = DebugDrawerSelections
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerTopic:  Name of the DebugDrawerTopic
-#  Attributes:
-#  - Default:            DebugDrawerUpdates
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SimulatorViewer_EntityDrawer.DebugDrawerTopic = DebugDrawerUpdates
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.SimulatorViewer_EntityDrawer.EnableProfiling = false
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 ArmarX.SimulatorViewer_EntityDrawer.MinimumLoggingLevel = Verbose
 
 
-# ArmarX.SimulatorViewer_EntityDrawer.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SimulatorViewer_EntityDrawer.ObjectName = ""
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.PriorKnowledgeName:  Name of the the PriorKnowledge memory component
-#  Attributes:
-#  - Default:            PriorKnowledge
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SimulatorViewer_EntityDrawer.PriorKnowledgeName = PriorKnowledge
-
-
-# ArmarX.SimulatorViewer_EntityDrawer.ShowDebugDrawing:  The simulator implements the DebugDrawerInterface. The debug visualizations (e.g. coordinate systems) can enabled/disbaled with this flag.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.SimulatorViewer_EntityDrawer.ShowDebugDrawing = true
-
-
 # ArmarX.SimulatorViewer_PhysicsWorldVisualization.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
@@ -383,6 +324,15 @@ ArmarX.SimulatorViewer_SimulationWindow.Camera.z = 6000
 # ArmarX.UpdateRate = 30
 
 
+# ArmarX.UseDebugDrawer:  Whether to create the debug drawer component for the viewer.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseDebugDrawer = false
+
+
 # ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
 #  - Default:            false
diff --git a/scenarios/NavigationSimulation/config/VisionMemory.cfg b/scenarios/NavigationSimulation/config/VisionMemory.cfg
index 4c7327ed..1b95447f 100644
--- a/scenarios/NavigationSimulation/config/VisionMemory.cfg
+++ b/scenarios/NavigationSimulation/config/VisionMemory.cfg
@@ -210,37 +210,21 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..configuration:  
+# ArmarX.VisionMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..configuration = ""
+# ArmarX.VisionMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.VisionMemory.mem.ltm..enabled:  
+# ArmarX.VisionMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm..enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.VisionMemory.mem.ltm.enabled = false
 
 
 # ArmarX.VisionMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index 2af60bde..b2764c9b 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -513,21 +513,74 @@
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..configuration:  
+# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..configuration = ""
+# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
 
 
-# ArmarX.ObjectMemory.mem.ltm..enabled:  
+# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm..enabled = false
+# ArmarX.ObjectMemory.mem.ltm.enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
 
 
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -538,6 +591,40 @@
 # ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
 # ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -678,5 +765,3 @@
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
-
-
diff --git a/scenarios/PlatformNavigation/config/VisionMemory.cfg b/scenarios/PlatformNavigation/config/VisionMemory.cfg
index 4c7327ed..0dfef493 100644
--- a/scenarios/PlatformNavigation/config/VisionMemory.cfg
+++ b/scenarios/PlatformNavigation/config/VisionMemory.cfg
@@ -210,21 +210,74 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..configuration:  
+# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..configuration = ""
+# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
 
 
-# ArmarX.VisionMemory.mem.ltm..enabled:  
+# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm..enabled = false
+# ArmarX.VisionMemory.mem.ltm.enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
+
+
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
+
+
+# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
 
 
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
@@ -235,6 +288,40 @@
 # ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
 
 
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
+
+
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
+
+
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
+
+
 # ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
 #  Attributes:
 #  - Default:            Default value not mapped.
@@ -275,5 +362,3 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 # ArmarX.VisionMemory.pointCloudMaxHistorySize = 20
-
-
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index eef85301..6a9bccd3 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -102,40 +102,6 @@
 # ArmarX.ExampleClient.ObjectName = ""
 
 
-# ArmarX.ExampleClient.mem.robot_state.Memory:  
-#  Attributes:
-#  - Default:            RobotState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
-
-
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
-#  Attributes:
-#  - Default:            Localization
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
-
-
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
-
-
 # ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
 #  - Default:            navigator
@@ -242,5 +208,3 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
-
-
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index f808f777..8253a316 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -155,7 +155,7 @@
 #  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.configuration = {}
+# ArmarX.NavigationMemory.mem.ltm..configuration = ""
 
 
 # ArmarX.NavigationMemory.mem.ltm.enabled:  
@@ -164,7 +164,23 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.enabled = false
+# ArmarX.NavigationMemory.mem.ltm..enabled = false
+
+
+# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+#  Attributes:
+#  - Default:            1024
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+
+
+# ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.mem.ltm.storagepath = Default value not mapped.
 
 
 # ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
@@ -286,5 +302,3 @@ ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graph
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
-
-
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 482582bb..233f17f4 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -139,12 +139,20 @@
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+ArmarX.Navigator.ObjectName = navigator
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
 #  Attributes:
-#  - Default:            false
+#  - Default:            Armar6Unit
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.RobotUnitName = Armar6Unit
+
+
+# ArmarX.Navigator.cmp.PlatformUnit:  Ice object name of the `PlatformUnit` component.
+#  Attributes:
+#  - Default:            PlatformUnit
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
@@ -270,18 +278,26 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.mem.nav.events.Provider = ""
+# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
 
 
-# ArmarX.navigator.mem.nav.graph.CoreSegment:  
+# ArmarX.Navigator.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            Location
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.mem.nav.graph.CoreSegment = Location
+# ArmarX.Navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.navigator.mem.nav.graph.Memory:  
+# ArmarX.Navigator.mem.robot_state.descriptionSegment:  
+#  Attributes:
+#  - Default:            Description
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Navigator.mem.robot_state.descriptionSegment = Description
+
+
+# ArmarX.Navigator.mem.robot_state.localizationSegment:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
@@ -289,15 +305,16 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
-# ArmarX.navigator.mem.nav.param.CoreSegment:  
+# ArmarX.Navigator.mem.robot_state.proprioceptionSegment:  
 #  Attributes:
-#  - Default:            Parameterization
+#  - Default:            Proprioception
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization
+# ArmarX.Navigator.mem.robot_state.proprioceptionSegment = Proprioception
 
 
-# ArmarX.navigator.mem.nav.param.Memory:  
+# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
@@ -321,15 +338,15 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.navigator.mem.nav.stack_result.CoreSegment = ""
 
 
-# ArmarX.navigator.mem.nav.stack_result.Memory:  
+# ArmarX.Navigator.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            MemoryUpdates
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation
+# ArmarX.Navigator.tpc.sub.MemoryListener = MemoryUpdates
 
 
-# ArmarX.navigator.mem.nav.stack_result.Provider:  Name of this provider
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
@@ -386,5 +403,3 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 #  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
-
-
diff --git a/source/armarx/navigation/client/ComponentPlugin.cpp b/source/armarx/navigation/client/ComponentPlugin.cpp
index b047700c..173e3dd4 100644
--- a/source/armarx/navigation/client/ComponentPlugin.cpp
+++ b/source/armarx/navigation/client/ComponentPlugin.cpp
@@ -17,93 +17,97 @@
 
 // ComponentPlugin
 
-armarx::navigation::client::ComponentPlugin::~ComponentPlugin() = default;
-
-void
-armarx::navigation::client::ComponentPlugin::postCreatePropertyDefinitions(
-    armarx::PropertyDefinitionsPtr& properties)
+namespace armarx::navigation::client
 {
-    if (not properties->hasDefinition(PROPERTY_NAME))
-    {
-        properties->defineOptionalProperty<std::string>(
-            PROPERTY_NAME, "navigator", "Name of the Navigator");
-    }
-}
 
-void
-armarx::navigation::client::ComponentPlugin::preOnInitComponent()
-{
-    ARMARX_TRACE;
-    parent<armarx::Component>().usingProxyFromProperty(PROPERTY_NAME);
-}
+    ComponentPlugin::~ComponentPlugin() = default;
 
-void
-armarx::navigation::client::ComponentPlugin::preOnConnectComponent()
-{
-    ARMARX_TRACE;
-    parent<armarx::Component>().getProxyFromProperty(navigatorPrx, PROPERTY_NAME);
+    void
+    ComponentPlugin::postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties)
+    {
+        if (not properties->hasDefinition(PROPERTY_NAME))
+        {
+            properties->defineOptionalProperty<std::string>(
+                PROPERTY_NAME, "navigator", "Name of the Navigator");
+        }
+    }
 
-    ARMARX_TRACE;
-    const std::string componentName = parent().getName();
+    void
+    ComponentPlugin::preOnInitComponent()
+    {
+        ARMARX_TRACE;
+        parent<armarx::Component>().usingProxyFromProperty(PROPERTY_NAME);
+    }
 
-    ARMARX_CHECK_NOT_NULL(navigatorPrx) << "Navigator proxy is null!";
-    iceNavigator.setNavigatorComponent(navigatorPrx);
-}
+    void
+    ComponentPlugin::preOnConnectComponent()
+    {
+        ARMARX_TRACE;
+        parent<armarx::Component>().getProxyFromProperty(navigatorPrx, PROPERTY_NAME);
 
-void
-armarx::navigation::client::ComponentPlugin::configureNavigator(
-    const client::NavigationStackConfig& stackConfig,
-    const std::string& configId)
-{
-    ARMARX_TRACE;
+        ARMARX_TRACE;
+        const std::string componentName = parent().getName();
 
-    // ARMARX_CHECK_NULL(eventHandler) << "`configureNavigator()` can only be called once!";
+        ARMARX_CHECK_NOT_NULL(navigatorPrx) << "Navigator proxy is null!";
+        iceNavigator.setNavigatorComponent(navigatorPrx);
+    }
 
-    eventHandler = [&]() -> std::unique_ptr<SimpleEventHandler>
+    void
+    ComponentPlugin::configureNavigator(const client::NavigationStackConfig& stackConfig,
+                                        const std::string& configId)
     {
-        if (parentDerives<armarx::armem::client::plugins::ListeningPluginUser>())
-        {
-            ARMARX_INFO << "Using memory event callbacks.";
-            // must(!!) use a reference here: otherwise the mns events won't work
-            auto& memoryNameSystem =
-                parent<armarx::armem::client::plugins::ListeningPluginUser>().memoryNameSystem();
-            return std::make_unique<MemorySubscriber>(configId, memoryNameSystem);
-        }
+        ARMARX_TRACE;
 
-        ARMARX_INFO << "Cannot use memory event callbacks as this component is not derived from "
-                       "`armarx::armem::client::plugins::ListeningPluginUser`";
+        // ARMARX_CHECK_NULL(eventHandler) << "`configureNavigator()` can only be called once!";
 
-        return std::make_unique<SimpleEventHandler>();
-    }();
-
-    iceNavigator.createConfig(stackConfig, configId);
+        eventHandler = [&]() -> std::unique_ptr<SimpleEventHandler>
+        {
+            if (parentDerives<armarx::armem::client::plugins::ListeningPluginUser>())
+            {
+                ARMARX_INFO << "Using memory event callbacks.";
+                // must(!!) use a reference here: otherwise the mns events won't work
+                auto& memoryNameSystem =
+                    parent<armarx::armem::client::plugins::ListeningPluginUser>()
+                        .memoryNameSystem();
+                return std::make_unique<MemorySubscriber>(configId, memoryNameSystem);
+            }
+
+            ARMARX_INFO
+                << "Cannot use memory event callbacks as this component is not derived from "
+                   "`armarx::armem::client::plugins::ListeningPluginUser`";
+
+            return std::make_unique<SimpleEventHandler>();
+        }();
+
+        iceNavigator.createConfig(stackConfig, configId);
+
+        navigator = std::make_unique<Navigator>(Navigator::InjectedServices{
+            .navigator = &iceNavigator, .subscriber = eventHandler.get()});
+    }
 
-    navigator = std::make_unique<Navigator>(
-        Navigator::InjectedServices{.navigator = &iceNavigator, .subscriber = eventHandler.get()});
-}
+    // ComponentPluginUser
 
-// ComponentPluginUser
+    ComponentPluginUser::ComponentPluginUser()
+    {
+        ARMARX_TRACE;
+        addPlugin(plugin);
+    }
 
-armarx::navigation::client::ComponentPluginUser::ComponentPluginUser()
-{
-    ARMARX_TRACE;
-    addPlugin(plugin);
-}
+    void
+    ComponentPluginUser::configureNavigator(const client::NavigationStackConfig& stackConfig)
+    {
+        ARMARX_TRACE;
+        plugin->configureNavigator(stackConfig, getName());
+    }
 
-void
-armarx::navigation::client::ComponentPluginUser::configureNavigator(
-    const client::NavigationStackConfig& stackConfig)
-{
-    ARMARX_TRACE;
-    plugin->configureNavigator(stackConfig, getName());
-}
+    Navigator&
+    ComponentPluginUser::getNavigator()
+    {
+        ARMARX_CHECK_NOT_NULL(plugin->navigator)
+            << "You need to call `configureNavigator()` before you can access the navigator!";
+        return *plugin->navigator;
+    }
 
-armarx::navigation::client::Navigator&
-armarx::navigation::client::ComponentPluginUser::getNavigator()
-{
-    ARMARX_CHECK_NOT_NULL(plugin->navigator)
-        << "You need to call `configureNavigator()` before you can access the navigator!";
-    return *plugin->navigator;
-}
+    ComponentPluginUser::~ComponentPluginUser() = default;
 
-armarx::navigation::client::ComponentPluginUser::~ComponentPluginUser() = default;
+} // namespace armarx::navigation::client
diff --git a/source/armarx/navigation/client/Navigator.cpp b/source/armarx/navigation/client/Navigator.cpp
index 15fb4bc1..e2f47c4d 100644
--- a/source/armarx/navigation/client/Navigator.cpp
+++ b/source/armarx/navigation/client/Navigator.cpp
@@ -60,6 +60,13 @@ namespace armarx::navigation::client
 
         srv.navigator->moveTo(path, frame);
     }
+    
+    void Navigator::update(const std::vector<core::Pose>& waypoints, core::NavigationFrame frame)
+    {
+        ARMARX_TRACE;;
+        ARMARX_CHECK_NOT_NULL(srv.navigator) << "Navigator service must not be null!";
+        srv.navigator->update(waypoints, frame);
+    }
 
 
     void
diff --git a/source/armarx/navigation/client/Navigator.h b/source/armarx/navigation/client/Navigator.h
index d116a1de..32af0bb9 100644
--- a/source/armarx/navigation/client/Navigator.h
+++ b/source/armarx/navigation/client/Navigator.h
@@ -132,6 +132,8 @@ namespace armarx::navigation::client
 
         void moveTowards(const core::Direction& direction, core::NavigationFrame frame);
 
+        void update(const std::vector<core::Pose>& waypoints, core::NavigationFrame frame);
+
         void pause();
 
         void resume();
diff --git a/source/armarx/navigation/client/ice/NavigatorInterface.ice b/source/armarx/navigation/client/ice/NavigatorInterface.ice
index 678379d0..806aa2d9 100644
--- a/source/armarx/navigation/client/ice/NavigatorInterface.ice
+++ b/source/armarx/navigation/client/ice/NavigatorInterface.ice
@@ -67,6 +67,8 @@ module armarx
 
                 void moveTo2(detail::Waypoints waypoints, string navigationFrame, string callerId);
 
+                void updateMoveTo(Eigen::Matrix4fSeq waypoints, string navigationFrame, string callerId);
+
                 void
                 moveTowards(Eigen::Vector3f direction, string navigationFrame, string callerId);
 
diff --git a/source/armarx/navigation/client/services/IceNavigator.cpp b/source/armarx/navigation/client/services/IceNavigator.cpp
index 965a59ee..cc1c51b4 100644
--- a/source/armarx/navigation/client/services/IceNavigator.cpp
+++ b/source/armarx/navigation/client/services/IceNavigator.cpp
@@ -2,6 +2,8 @@
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
+#include "armarx/navigation/core/types.h"
+
 
 namespace armarx::navigation::client
 {
@@ -79,6 +81,16 @@ namespace armarx::navigation::client
             direction, core::NavigationFrameNames.to_name(navigationFrame), configId);
     }
 
+    void
+    IceNavigator::update(const std::vector<core::Pose>& waypoints,
+                         core::NavigationFrame navigationFrame)
+    {
+        ARMARX_TRACE;
+
+        navigator->updateMoveTo(
+            convert(waypoints), core::NavigationFrameNames.to_name(navigationFrame), configId);
+    }
+
     void
     IceNavigator::pause()
     {
diff --git a/source/armarx/navigation/client/services/IceNavigator.h b/source/armarx/navigation/client/services/IceNavigator.h
index 60750002..142bebb4 100644
--- a/source/armarx/navigation/client/services/IceNavigator.h
+++ b/source/armarx/navigation/client/services/IceNavigator.h
@@ -3,6 +3,8 @@
 
 #include <string>
 
+#include "armarx/navigation/core/basic_types.h"
+#include "armarx/navigation/core/types.h"
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/client/ice_conversions.h>
@@ -35,6 +37,9 @@ namespace armarx::navigation::client
         void moveTowards(const core::Direction& direction,
                          core::NavigationFrame navigationFrame) override;
 
+        void update(const std::vector<core::Pose>& waypoints,
+                    core::NavigationFrame navigationFrame) override;
+
         void pause() override;
 
         void resume() override;
diff --git a/source/armarx/navigation/components/navigator/CMakeLists.txt b/source/armarx/navigation/components/navigator/CMakeLists.txt
index a8d6245e..a686acda 100644
--- a/source/armarx/navigation/components/navigator/CMakeLists.txt
+++ b/source/armarx/navigation/components/navigator/CMakeLists.txt
@@ -8,7 +8,8 @@ armarx_add_component(navigator
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
-        # ArmarXCoreComponentPlugins  # For DebugObserver plugin. ArmarXGui
+        ArmarXCoreComponentPlugins  # For DebugObserver plugin. 
+        # ArmarXGui
         ArmarXGuiComponentPlugins # For RemoteGui plugin.
         # RobotAPI
         RobotAPICore
@@ -18,15 +19,13 @@ armarx_add_component(navigator
         armem_robot
         armem_robot_state
         armem_vision
-        # This project ${PROJECT_NAME}Interfaces  # For ice interfaces from this
-        # package. This component
+        # navigation
         armarx_navigation::server
         armarx_navigation::client
         armarx_navigation::util
         armarx_navigation::factories
+        # Simox
         Simox::SimoxUtility
+        # others
         Eigen3::Eigen
-    ICE_DEPENDENCIES
-        ArmarXCoreInterfaces
-        RobotAPIInterfaces
 )
diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 4cf28549..32cc481f 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -281,6 +281,7 @@ namespace armarx::navigation::components::navigator
                                                     .publisher =
                                                         memoryPublishers.at(callerId).get(),
                                                     .introspector = &(introspector.value()),
+                                                    .debugObserverHelper = &getDebugObserverComponentPlugin(),
                                                     .sceneProvider = &sceneProvider.value()}));
     }
 
@@ -313,6 +314,37 @@ namespace armarx::navigation::components::navigator
         }
     }
 
+    void
+    Navigator::updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
+                            const std::string& navigationMode,
+                            const std::string& callerId,
+                            const Ice::Current&  /*c*/)
+    {
+        ARMARX_TRACE;
+
+        ARMARX_INFO << "updateMoveTo() requested by caller '" << callerId << "'";
+        ARMARX_CHECK(navigators.count(callerId) > 0)
+            << "Navigator config for caller `" << callerId << "` not registered!";
+
+        const auto checkIsActiveNavigator = [&](const std::string& callerId)
+        {
+            const std::optional<std::string> activeNavigatorCallerId = activeNavigator();
+            if (not activeNavigatorCallerId.has_value())
+            {
+                ARMARX_VERBOSE << "No navigator is active.";
+                return false;
+            }
+
+            return activeNavigatorCallerId == callerId;
+        };
+
+        ARMARX_CHECK(checkIsActiveNavigator(callerId))
+            << "The navigator with id `" << callerId << "` is not active!";
+
+        navigators.at(callerId).update(convert(waypoints),
+                                       core::NavigationFrameNames.from_name(navigationMode));
+    }
+
 
     void
     Component::moveTo2(const client::detail::Waypoints& waypoints,
@@ -458,27 +490,67 @@ namespace armarx::navigation::components::navigator
         return def;
     }
 
+    void
+    visualize(const algorithms::Costmap& costmap, viz::Client& arviz, const std::string& name)
+    {
+        const auto cmap = simox::color::cmaps::viridis();
+        const float vmax = costmap.getGrid().array().maxCoeff();
+
+        const auto asColor = [&cmap, &vmax](const float distance) -> viz::data::Color
+        {
+            const auto color = cmap.at(distance, 0.F, vmax);
+            return {color.a, color.r, color.g, color.b};
+        };
+
+        auto layer = arviz.layer("costmap_" + name);
+
+        const std::int64_t cols = costmap.getGrid().cols();
+        const std::int64_t rows = costmap.getGrid().rows();
+
+        auto mesh = viz::Mesh("");
+
+        std::vector<std::vector<Eigen::Vector3f>> vertices;
+        std::vector<std::vector<viz::data::Color>> colors;
+
+        for (int r = 0; r < rows; r++)
+        {
+            auto& verticesRow = vertices.emplace_back(cols);
+            auto& colorsRow = colors.emplace_back(cols);
+
+            for (int c = 0; c < cols; c++)
+            {
+                verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
+                colorsRow.at(c) = asColor(costmap.getGrid()(r, c));
+            }
+        }
+
+        mesh.grid2D(vertices, colors);
+
+        layer.add(mesh);
+
+        arviz.commit(layer);
+    }
 
     server::Navigator*
-    Component::activeNavigator()
+    components::Navigator::activeNavigator()
     {
         ARMARX_TRACE;
         // We define the active navigator to be the one whose movement is enabled.
-        const auto isActive = [](auto& nameNavPair) -> bool
+        const auto isActive = [](const auto& nameNavPair) -> bool
         {
-            server::Navigator& navigator = nameNavPair.second;
+            const auto& [name, navigator] = nameNavPair;
             return not navigator.isPaused();
         };
 
-        auto it = std::find_if(navigators.begin(), navigators.end(), isActive);
+        const auto it = std::find_if(navigators.begin(), navigators.end(), isActive);
 
         // no navigator active?
         if (it == navigators.end())
         {
-            return nullptr;
+            return std::nullopt;
         }
 
-        return &it->second;
+        return it->first;
     }
 
 } // namespace armarx::navigation::components::navigator
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index 316e4da5..d5f41ea9 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -33,6 +33,7 @@
 
 #include <Ice/Object.h>
 
+#include "ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h"
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 #include <ArmarXCore/util/CPPUtility/TripleBuffer.h>
@@ -85,7 +86,8 @@ namespace armarx::navigation::components::navigator
         virtual public client::NavigatorInterface,
         virtual public ObjectPoseClientPluginUser,
         virtual public ArVizComponentPluginUser,
-        virtual public armarx::control::client::ComponentPluginUser
+        virtual public armarx::control::client::ComponentPluginUser,
+        virtual public armarx::DebugObserverComponentPluginUser
     // virtual public armem::ListeningClientPluginUser
     {
 
@@ -112,6 +114,11 @@ namespace armarx::navigation::components::navigator
                      const std::string& callerId,
                      const Ice::Current& c = Ice::emptyCurrent) override;
 
+        void updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
+                    const std::string& navigationMode,
+                    const std::string& callerId,
+                    const Ice::Current& c = Ice::emptyCurrent) override;
+
         void moveTowards(const Eigen::Vector3f& direction,
                          const std::string& navigationMode,
                          const std::string& callerId,
@@ -158,7 +165,7 @@ namespace armarx::navigation::components::navigator
         // [[nodiscard]] VirtualRobot::RobotPtr getRobot();
         // void updateRobot();
 
-        server::Navigator* activeNavigator();
+        std::optional<std::string> activeNavigator() const;
 
     private:
         void visualizeSPFA();
diff --git a/source/armarx/navigation/core/NavigatorInterface.h b/source/armarx/navigation/core/NavigatorInterface.h
index 05df688d..18e50335 100644
--- a/source/armarx/navigation/core/NavigatorInterface.h
+++ b/source/armarx/navigation/core/NavigatorInterface.h
@@ -6,6 +6,10 @@
 namespace armarx::navigation::core
 {
 
+    /**
+     * @brief Navigator interface for PointGoal navigation (with waypoints) and relative movement
+     * 
+     */
     class NavigatorInterface
     {
 
@@ -19,6 +23,8 @@ namespace armarx::navigation::core
         virtual void moveTo(const std::vector<client::WaypointTarget>& targets,
                             core::NavigationFrame navigationFrame) = 0;
 
+        virtual void update(const std::vector<core::Pose>& waypoints,
+                            core::NavigationFrame navigationFrame) = 0;
 
         virtual void pause() = 0;
 
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index af121508..22913fa5 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -5,9 +5,6 @@
 #include <optional>
 #include <thread>
 
-#include <range/v3/view.hpp>
-#include <range/v3/view/reverse.hpp>
-
 #include <boost/graph/dijkstra_shortest_paths.hpp>
 #include <boost/graph/named_function_params.hpp>
 #include <boost/graph/properties.hpp>
@@ -42,6 +39,8 @@
 #include <armarx/navigation/server/StackResult.h>
 #include <armarx/navigation/server/monitoring/GoalReachedMonitor.h>
 #include <armarx/navigation/server/scene_provider/SceneProviderInterface.h>
+#include <range/v3/view.hpp>
+#include <range/v3/view/reverse.hpp>
 
 
 namespace armarx::navigation::server
@@ -164,6 +163,33 @@ namespace armarx::navigation::server
         moveToAbsolute(globalWaypoints);
     }
 
+    void
+    Navigator::update(const std::vector<core::Pose>& waypoints,
+                      core::NavigationFrame navigationFrame)
+    {
+        ARMARX_INFO << "Received update() request.";
+
+        std::vector<core::Pose> globalWaypoints;
+        switch (navigationFrame)
+        {
+            case core::NavigationFrame::Absolute:
+                globalWaypoints = waypoints;
+                break;
+            case core::NavigationFrame::Relative:
+                globalWaypoints.reserve(waypoints.size());
+                std::transform(
+                    std::begin(waypoints),
+                    std::end(waypoints),
+                    std::back_inserter(globalWaypoints),
+                    [&](const core::Pose& p)
+                    { return core::Pose(srv.sceneProvider->scene().robot->getGlobalPose()) * p; });
+                break;
+        }
+
+        ARMARX_TRACE;
+        updateAbsolute(globalWaypoints);
+    }
+
     using GraphPath = std::vector<semrel::ShapeID>;
 
 
@@ -626,6 +652,8 @@ namespace armarx::navigation::server
         ARMARX_TRACE;
 
         ARMARX_INFO << "Planning local trajectory enabled";
+
+        // FIXME instead of PeriodicTask, use RunningTask.
         runningTask = new PeriodicTask<Navigator>(this,
                                                   &Navigator::run,
                                                   config.general.tasks.replanningUpdatePeriod,
@@ -644,13 +672,14 @@ namespace armarx::navigation::server
     Navigator::moveToAbsolute(const std::vector<core::Pose>& waypoints)
     {
         ARMARX_TRACE;
+
         // if this navigator is in use, stop the movement ...
         pause();
         // ... and all threads
         stopAllThreads();
 
         // FIXME remove
-        std::this_thread::sleep_for(std::chrono::seconds(1));
+        //std::this_thread::sleep_for(std::chrono::seconds(1));
 
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_EMPTY(waypoints);
@@ -710,6 +739,48 @@ namespace armarx::navigation::server
         ARMARX_INFO << "Movement started.";
     }
 
+
+    void
+    Navigator::updateAbsolute(const std::vector<core::Pose>& waypoints)
+    {
+        ARMARX_TRACE;
+        ARMARX_CHECK_NOT_EMPTY(waypoints);
+
+
+        // global planner
+        ARMARX_INFO << "Planning global trajectory";
+        ARMARX_CHECK_NOT_NULL(config.stack.globalPlanner);
+        // TODO plan on multiple waypoints, ignoring waypoints for now
+        // idea: compute multiple global trajectories, one for each segment between waypoints.
+
+        srv.introspector->onGoal(waypoints.back());
+        globalPlan = config.stack.globalPlanner->plan(waypoints.back());
+
+        ARMARX_TRACE;
+
+        if (not globalPlan.has_value())
+        {
+            ARMARX_WARNING << "No global trajectory. Cannot move.";
+            srv.publisher->globalPlanningFailed(
+                core::GlobalPlanningFailedEvent{{.timestamp = armarx::Clock::Now()}, {""}});
+
+            srv.introspector->failure();
+            return;
+        }
+
+        ARMARX_TRACE;
+        srv.publisher->globalTrajectoryUpdated(globalPlan.value());
+        srv.introspector->onGlobalPlannerResult(globalPlan.value());
+        // srv.executor->execute(globalPlan->trajectory);
+
+        ARMARX_INFO << "Global planning completed. Will now start all required threads";
+        ARMARX_TRACE;
+
+        startStack();
+
+        ARMARX_INFO << "Movement started.";
+    }
+
     void
     Navigator::moveTowards(const core::Direction& direction, core::NavigationFrame navigationFrame)
     {
@@ -733,8 +804,67 @@ namespace armarx::navigation::server
             const Duration duration =
                 armarx::core::time::StopWatch::measure([&]() { updateScene(); });
 
-            ARMARX_VERBOSE << deactivateSpam(0.2) << "Scene update: " << duration.toMilliSecondsDouble()
-                           << "ms.";
+            ARMARX_VERBOSE << deactivateSpam(0.2)
+                           << "Scene update: " << duration.toMilliSecondsDouble() << "ms.";
+
+            srv.debugObserverHelper->setDebugObserverDatafield("scene update [ms]", duration.toMilliSecondsDouble());
+        }
+
+        // global planner update if goal has changed
+        {
+            std::lock_guard g{globalPlanningRequestMtx};
+
+            if (globalPlanningRequest.has_value())
+            {
+                const auto& waypoints = globalPlanningRequest.value();
+
+                // recreate goal monitor
+                {
+                    // first we check if we are already at the goal position
+                    goalReachedMonitor = std::nullopt;
+                    goalReachedMonitor = GoalReachedMonitor(
+                        waypoints.back(), srv.sceneProvider->scene(), GoalReachedMonitorConfig());
+
+                    if (goalReachedMonitor->goalReached())
+                    {
+                        ARMARX_INFO << "Already at goal position. Robot won't move.";
+
+                        srv.publisher->goalReached(core::GoalReachedEvent{
+                            {armarx::Clock::Now()},
+                            core::Pose(srv.sceneProvider->scene().robot->getGlobalPose())});
+
+                        return;
+                    }
+                }
+
+                // global planning
+                {
+                    // global planner
+                    ARMARX_INFO << "Update/Planning global trajectory";
+                    ARMARX_CHECK_NOT_NULL(config.stack.globalPlanner);
+                    // TODO plan on multiple waypoints, ignoring waypoints for now
+                    // idea: compute multiple global trajectories, one for each segment between waypoints.
+
+                    srv.introspector->onGoal(waypoints.back());
+                    globalPlan = config.stack.globalPlanner->plan(waypoints.back());
+
+                    ARMARX_TRACE;
+
+                    if (not globalPlan.has_value())
+                    {
+                        ARMARX_WARNING << "No global trajectory. Cannot move.";
+                        srv.publisher->globalPlanningFailed(core::GlobalPlanningFailedEvent{
+                            {.timestamp = armarx::Clock::Now()}, {""}});
+
+                        srv.introspector->failure();
+                        return;
+                    }
+
+                    ARMARX_TRACE;
+                    srv.publisher->globalTrajectoryUpdated(globalPlan.value());
+                    srv.introspector->onGlobalPlannerResult(globalPlan.value());
+                }
+            }
         }
 
         // local planner update
@@ -753,6 +883,8 @@ namespace armarx::navigation::server
                 });
             ARMARX_VERBOSE << deactivateSpam(0.2)
                            << "Local planner update: " << duration.toMilliSecondsDouble() << "ms.";
+
+            srv.debugObserverHelper->setDebugObserverDatafield("local planner update [ms]", duration.toMilliSecondsDouble());
         }
 
         // monitor update
@@ -764,6 +896,8 @@ namespace armarx::navigation::server
 
             ARMARX_VERBOSE << deactivateSpam(0.2)
                            << "Monitor update: " << duration.toMilliSecondsDouble() << "ms.";
+
+            srv.debugObserverHelper->setDebugObserverDatafield("monitor update [ms]", duration.toMilliSecondsDouble());
         }
     }
 
@@ -796,7 +930,7 @@ namespace armarx::navigation::server
     void
     Navigator::updateExecutor(const std::optional<local_planning::LocalPlannerResult>& localPlan)
     {
-        if(srv.executor == nullptr)
+        if (srv.executor == nullptr)
         {
             return;
         }
@@ -835,7 +969,8 @@ namespace armarx::navigation::server
     }
 
     void
-    Navigator::updateIntrospector(const std::optional<local_planning::LocalPlannerResult>& localPlan)
+    Navigator::updateIntrospector(
+        const std::optional<local_planning::LocalPlannerResult>& localPlan)
     {
         ARMARX_CHECK_NOT_NULL(srv.introspector);
 
@@ -930,7 +1065,7 @@ namespace armarx::navigation::server
 
         executorEnabled.store(false);
 
-        if(srv.executor != nullptr)
+        if (srv.executor != nullptr)
         {
             srv.executor->stop();
         }
@@ -943,7 +1078,7 @@ namespace armarx::navigation::server
 
         executorEnabled.store(true);
 
-        if(srv.executor != nullptr)
+        if (srv.executor != nullptr)
         {
             srv.executor->start();
         }
diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index 5c236f3a..f4c0fb10 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -30,6 +30,7 @@
 #include <Eigen/Core>
 
 // ArmarX
+#include "ArmarXCore/libraries/DebugObserverHelper/DebugObserverHelper.h"
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
@@ -81,6 +82,8 @@ namespace armarx::navigation::server
             EventPublishingInterface* publisher;
             IntrospectorInterface* introspector = nullptr;
 
+            armarx::DebugObserverHelper* debugObserverHelper;
+
             scene_provider::SceneProviderInterface* sceneProvider;
         };
 
@@ -89,6 +92,9 @@ namespace armarx::navigation::server
         void moveTo(const std::vector<core::Pose>& waypoints,
                     core::NavigationFrame navigationFrame) override;
 
+        void update(const std::vector<core::Pose>& waypoints,
+                    core::NavigationFrame navigationFrame) override;
+
 
         void moveTo(const std::vector<client::WaypointTarget>& targets,
                     core::NavigationFrame navigationFrame) override;
@@ -116,6 +122,8 @@ namespace armarx::navigation::server
         void moveToAbsolute(const std::vector<core::Pose>& waypoints);
         void moveTowardsAbsolute(const core::Direction& direction);
 
+        void updateAbsolute(const std::vector<core::Pose>& waypoints);
+
         void run();
 
         void updateScene();
@@ -155,6 +163,11 @@ namespace armarx::navigation::server
 
         std::optional<global_planning::GlobalPlannerResult> globalPlan;
         std::optional<local_planning::LocalPlannerResult> localPlan;
+
+        using Waypoints = std::vector<core::Pose>;
+
+        std::mutex globalPlanningRequestMtx;
+        std::optional<Waypoints> globalPlanningRequest;
     };
 
 } // namespace armarx::navigation::server
-- 
GitLab


From 0bf689dda741a622cedcf1d8f28cd5660327993a Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 19:40:59 +0200
Subject: [PATCH 134/324] minor cleanup

---
 .../components/navigator/Component.cpp           | 16 +++++++++++++++-
 .../navigation/components/navigator/Component.h  |  3 ++-
 2 files changed, 17 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 32cc481f..d4938415 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -29,6 +29,7 @@
 #include <cstdint>
 #include <iterator>
 #include <memory>
+#include <optional>
 #include <utility>
 
 #include <Eigen/Geometry>
@@ -532,7 +533,20 @@ namespace armarx::navigation::components::navigator
     }
 
     server::Navigator*
-    components::Navigator::activeNavigator()
+    Component::activeNavigator()
+    {
+        
+        const auto navigatorId = activeNavigatorId();
+        if(not navigatorId.has_value())
+        {
+            return nullptr;
+        }
+
+        return &navigators.at(navigatorId.value());
+    }
+
+    std::optional<std::string>
+    Component::activeNavigatorId() const
     {
         ARMARX_TRACE;
         // We define the active navigator to be the one whose movement is enabled.
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index d5f41ea9..5e552d7f 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -165,7 +165,8 @@ namespace armarx::navigation::components::navigator
         // [[nodiscard]] VirtualRobot::RobotPtr getRobot();
         // void updateRobot();
 
-        std::optional<std::string> activeNavigator() const;
+        server::Navigator* activeNavigator();
+        std::optional<std::string> activeNavigatorId() const;
 
     private:
         void visualizeSPFA();
-- 
GitLab


From 5801fb3c6e0bb280d307631cdfb413c257d4cf90 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 19:43:01 +0200
Subject: [PATCH 135/324] fix: build

---
 source/armarx/navigation/components/navigator/Component.cpp | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index d4938415..402c90e4 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -316,7 +316,7 @@ namespace armarx::navigation::components::navigator
     }
 
     void
-    Navigator::updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
+    Component::updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
                             const std::string& navigationMode,
                             const std::string& callerId,
                             const Ice::Current&  /*c*/)
@@ -329,7 +329,7 @@ namespace armarx::navigation::components::navigator
 
         const auto checkIsActiveNavigator = [&](const std::string& callerId)
         {
-            const std::optional<std::string> activeNavigatorCallerId = activeNavigator();
+            const std::optional<std::string> activeNavigatorCallerId = activeNavigatorId();
             if (not activeNavigatorCallerId.has_value())
             {
                 ARMARX_VERBOSE << "No navigator is active.";
-- 
GitLab


From 244b5edbead131343d3de4b4b6dea967f2cf5374 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 19:47:53 +0200
Subject: [PATCH 136/324] scenario update: removing memoryx

---
 .../NavigationSimulation.scx                  | 11 --------
 .../config/ObjectMemory.cfg                   | 25 +++++++++++++------
 .../SelfLocalizationDynamicSimulationApp.cfg  |  4 +--
 3 files changed, 19 insertions(+), 21 deletions(-)

diff --git a/scenarios/NavigationSimulation/NavigationSimulation.scx b/scenarios/NavigationSimulation/NavigationSimulation.scx
index 66b83347..5115bad6 100644
--- a/scenarios/NavigationSimulation/NavigationSimulation.scx
+++ b/scenarios/NavigationSimulation/NavigationSimulation.scx
@@ -3,12 +3,7 @@
 	<application name="DebugObserver" instance="" package="ArmarXCore" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ConditionHandler" instance="" package="ArmarXCore" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="SystemObserver" instance="" package="ArmarXCore" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="CommonStorage" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="PriorKnowledge" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="LongtermMemory" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="WorkingMemory" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="RobotStateComponent" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="ViewSelectionApp" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="ObjectLocalizationSaliencyApp" instance="" package="RobotComponents" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="SimulatorApp" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="SimulatorViewerApp" instance="" package="ArmarXSimulation" nodeName="" enabled="false" iceAutoRestart="false"/>
@@ -19,25 +14,19 @@
 	<application name="DepthImageProviderDynamicSimulationApp" instance="" package="ArmarXSimulation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="ObjectLocalizationDynamicSimulationApp" instance="TexturedRecognition" package="ArmarXSimulation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="ObjectLocalizationDynamicSimulationApp" instance="SegmentableRecognition" package="ArmarXSimulation" nodeName="" enabled="false" iceAutoRestart="false"/>
-	<application name="ObjectMemoryObserver" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="HandUnitDynamicSimulationApp" instance="LeftHand" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="HandUnitDynamicSimulationApp" instance="RightHand" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ForceTorqueObserver" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="SelfLocalizationDynamicSimulationApp" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="RobotHandLocalizationDynamicSimulationApp" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="HeadIKUnit" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="TCPControlUnit" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="ProfilerObserverApp" instance="" package="ArmarXCore" nodeName="" enabled="false" iceAutoRestart="false"/>
-	<application name="GraphNodePoseResolverApp" instance="" package="MemoryX" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ImageSourceSelectionApp" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="RobotUnitSimulationApp" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="LaserScannerUnitObserverApp" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ImageProviderDynamicSimulationApp" instance="Roboception" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ArmarXFileLoggerApp" instance="" package="ArmarXCore" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ArVizStorage" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="RobotToArVizApp" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
-	<application name="WorkingMemoryToArVizApp" instance="" package="MemoryX" nodeName="" enabled="false" iceAutoRestart="false"/>
-	<application name="ObstacleAvoidingPlatformUnit" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="RemoteGuiProviderApp" instance="" package="ArmarXGui" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="DebugDrawerToArVizApp" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="ArticulatedObjectLocalizerDynamicSimulation" instance="" package="ArmarXSimulation" nodeName="" enabled="false" iceAutoRestart="false"/>
diff --git a/scenarios/NavigationSimulation/config/ObjectMemory.cfg b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
index a1b9d81c..9d742ccc 100644
--- a/scenarios/NavigationSimulation/config/ObjectMemory.cfg
+++ b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
@@ -259,6 +259,15 @@ ArmarX.ObjectMemory.MinimumLoggingLevel = Debug
 # ArmarX.ObjectMemory.mem.inst.calibration.offset = 0
 
 
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName:  Name of robot whose note can be calibrated.
+# If not given, the 'fallbackName' is used.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.calibration.robotNode:  Robot node which can be calibrated.
 #  Attributes:
 #  - Default:            Neck_2_Pitch
@@ -341,6 +350,14 @@ ArmarX.ObjectMemory.MinimumLoggingLevel = Debug
 # ArmarX.ObjectMemory.mem.inst.head.maxJointVelocity = 0.0500000007
 
 
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName:  Robot name to use as fallback if the robot name is not specified in a provided object pose.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.scene.10_Package:  ArmarX package containing the scene snapshots.
 # Scene snapshots are expected to be located in Package/data/Package/Scenes/*.json.
 #  Attributes:
@@ -572,14 +589,6 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.prediction.TimeWindow = 2
 
 
-# ArmarX.ObjectMemory.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.robotName = Armar6
-
-
 # ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
 #  Attributes:
 #  - Default:            DebugObserver
diff --git a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
index b8200627..aa388636 100644
--- a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
+++ b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
@@ -223,7 +223,7 @@ ArmarX.SelfLocalizationDynamicSimulation.longterm_memory.retrieve_initial_pose =
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.SelfLocalizationDynamicSimulation.longterm_memory.update = true
+ArmarX.SelfLocalizationDynamicSimulation.longterm_memory.update = false
 
 
 # ArmarX.SelfLocalizationDynamicSimulation.longterm_memory.update_frequency:  
@@ -330,7 +330,7 @@ ArmarX.SelfLocalizationDynamicSimulation.mem.robot_state.Memory = RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.SelfLocalizationDynamicSimulation.working_memory.update = true
+ArmarX.SelfLocalizationDynamicSimulation.working_memory.update = false
 
 
 # ArmarX.SelfLocalizationDynamicSimulation.working_memory.update_frequency:  
-- 
GitLab


From 236e4b3b9e82dcbe6689473fcf67a99f4c585abe Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 20:25:25 +0200
Subject: [PATCH 137/324] scenario updates: fixes after renaming components

---
 .../config/ObjectMemory.cfg                   |  51 +++---
 .../config/VisionMemory.cfg                   |  26 +--
 ..._distance_to_obstacle_costmap_provider.cfg |   2 +-
 .../config/example_client.cfg                 | 149 +++++++++-------
 .../config/navigation_memory.cfg              |   5 +-
 .../HumanAwareNavigation/config/navigator.cfg |  68 +++----
 .../PlatformNavigation/PlatformNavigation.scx |   2 +-
 .../config/ObjectMemory.cfg                   | 111 +-----------
 .../config/VisionMemory.cfg                   | 111 +-----------
 .../config/example_client.cfg                 | 150 ++++++++++------
 .../config/navigation_memory.cfg              | 167 +++++++++---------
 .../PlatformNavigation/config/navigator.cfg   |  77 +++++---
 12 files changed, 376 insertions(+), 543 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
index 2af60bde..773e4812 100644
--- a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
+++ b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
@@ -259,6 +259,15 @@
 # ArmarX.ObjectMemory.mem.inst.calibration.offset = 0
 
 
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName:  Name of robot whose note can be calibrated.
+# If not given, the 'fallbackName' is used.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.calibration.robotNode:  Robot node which can be calibrated.
 #  Attributes:
 #  - Default:            Neck_2_Pitch
@@ -341,6 +350,14 @@
 # ArmarX.ObjectMemory.mem.inst.head.maxJointVelocity = 0.0500000007
 
 
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName:  Robot name to use as fallback if the robot name is not specified in a provided object pose.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.scene.10_Package:  ArmarX package containing the scene snapshots.
 # Scene snapshots are expected to be located in Package/data/Package/Scenes/*.json.
 #  Attributes:
@@ -513,37 +530,21 @@
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..configuration:  
+# ArmarX.ObjectMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..configuration = ""
+# ArmarX.ObjectMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.ObjectMemory.mem.ltm..enabled:  
+# ArmarX.ObjectMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm..enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.ObjectMemory.mem.ltm.enabled = false
 
 
 # ArmarX.ObjectMemory.mem.robot_state.Memory:  
@@ -588,14 +589,6 @@
 # ArmarX.ObjectMemory.prediction.TimeWindow = 2
 
 
-# ArmarX.ObjectMemory.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.robotName = Armar6
-
-
 # ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
 #  Attributes:
 #  - Default:            DebugObserver
diff --git a/scenarios/HumanAwareNavigation/config/VisionMemory.cfg b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
index 4c7327ed..1b95447f 100644
--- a/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
+++ b/scenarios/HumanAwareNavigation/config/VisionMemory.cfg
@@ -210,37 +210,21 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..configuration:  
+# ArmarX.VisionMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..configuration = ""
+# ArmarX.VisionMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.VisionMemory.mem.ltm..enabled:  
+# ArmarX.VisionMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm..enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.storagepath = Default value not mapped.
+# ArmarX.VisionMemory.mem.ltm.enabled = false
 
 
 # ArmarX.VisionMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
index 565bb501..81d7cebf 100644
--- a/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
+++ b/scenarios/HumanAwareNavigation/config/dynamic_distance_to_obstacle_costmap_provider.cfg
@@ -296,7 +296,7 @@
 #  Attributes:
 #  - Case sensitivity:   yes
 #  - Required:           yes
-# ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName = ::_NOT_SET_::
+ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.staticCostmap.providerName = distance_to_obstacle_costmap_provider
 
 
 # ArmarX.dynamic_distance_to_obstacle_costmap_provider.p.updatePeriodMs:  
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
index eef85301..c21733bd 100644
--- a/scenarios/HumanAwareNavigation/config/example_client.cfg
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -76,171 +76,188 @@
 # ArmarX.EnableProfiling = false
 
 
-# ArmarX.ExampleClient.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.ExampleClient.nav.NavigatorName:  No Description
 #  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
+#  - Default:            navigator
+#  - Case sensitivity:   no
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.EnableProfiling = false
+ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
-# ArmarX.ExampleClient.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.ExampleClient.MinimumLoggingLevel = Undefined
+# ArmarX.LoadLibraries = ""
 
 
-# ArmarX.ExampleClient.ObjectName:  Name of IceGrid well-known object
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.ObjectName = ""
+# ArmarX.LoggingGroup = ""
 
 
-# ArmarX.ExampleClient.mem.robot_state.Memory:  
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            Localization
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            true
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            navigator
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.ExampleClient.nav.NavigatorName = navigator
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            200
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.relativeMovement = 200
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.ExampleClient.robotName:  
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            Armar6
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.example_client.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.robotName = Armar6
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.example_client.EnableProfiling = false
 
 
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+# ArmarX.example_client.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.LoadLibraries = ""
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.example_client.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+# ArmarX.example_client.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.LoggingGroup = ""
+# ArmarX.example_client.ObjectName = ""
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.example_client.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.example_client.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.example_client.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
-#  - Default:            3000
+#  - Default:            Localization
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.example_client.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.example_client.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            0
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.example_client.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.example_client.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            false
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.example_client.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.example_client.mode:  Which example to run
 #  Attributes:
-#  - Default:            1
+#  - Default:            standard
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+#  - Possible values: {complex, point_to_point, standard, update_navigator}
+# ArmarX.example_client.mode = standard
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
-#  - Default:            ""
+#  - Default:            navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.example_client.nav.NavigatorName = navigator
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.example_client.relativeMovement:  The distance between two target poses [mm]
 #  Attributes:
-#  - Default:            false
+#  - Default:            200
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.example_client.relativeMovement = 200
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.example_client.robotName:  
 #  Attributes:
-#  - Default:            Info
+#  - Default:            Armar6
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+# ArmarX.example_client.robotName = Armar6
 
 
diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index 4fd3110f..a3e73f4f 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -191,7 +191,7 @@ ArmarX.Verbosity = Verbose
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.navigation_memory.MinimumLoggingLevel = Undefined
+ArmarX.navigation_memory.MinimumLoggingLevel = Verbose
 
 
 # ArmarX.navigation_memory.ObjectName:  Name of IceGrid well-known object
@@ -288,6 +288,3 @@ ArmarX.Verbosity = Verbose
 # ArmarX.navigation_memory.p.snapshotToLoad = ""
 
 
-# ArmarX.navigation_memory.MinimumLoggingLevel:  
-#  Attributes:
-ArmarX.navigation_memory.MinimumLoggingLevel = Verbose
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index 7b44af1c..e55d723f 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -92,46 +92,6 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.Navigator.ObjectName:  No Description
-#  Attributes:
-#  - Default:            navigator
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.ObjectName = navigator
-
-
-# ArmarX.Navigator.RobotUnitName:  No Description
-#  Attributes:
-#  - Default:            Armar6Unit
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.RobotUnitName = Armar6Unit
-
-
-# ArmarX.Navigator.cmp.PlatformUnit:  No Description
-#  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
-
-
-# ArmarX.Navigator.p.disableExecutor:  No Description
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.p.disableExecutor = false
-
-
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  No Description
-#  Attributes:
-#  - Default:            0.8
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
-
-
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -216,6 +176,14 @@ ArmarX.Verbosity = Verbose
 # ArmarX.navigator.ArVizTopicName = ArVizTopic
 
 
+# ArmarX.navigator.DebugObserverTopicName:  Name of the topic the DebugObserver listens on
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.DebugObserverTopicName = DebugObserver
+
+
 # ArmarX.navigator.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
@@ -254,7 +222,7 @@ ArmarX.Verbosity = Verbose
 #  Attributes:
 #  - Case sensitivity:   yes
 #  - Required:           yes
-# ArmarX.navigator.RobotUnitName = ::_NOT_SET_::
+ArmarX.navigator.RobotUnitName = Armar6Unit
 
 
 # ArmarX.navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
@@ -321,6 +289,22 @@ ArmarX.Verbosity = Verbose
 # ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
+# ArmarX.navigator.mem.nav.human.CoreSegment:  
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.mem.nav.human.CoreSegment = Human
+
+
+# ArmarX.navigator.mem.nav.human.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.mem.nav.human.Memory = Navigation
+
+
 # ArmarX.navigator.mem.nav.param.CoreSegment:  
 #  Attributes:
 #  - Default:            Parameterization
@@ -417,6 +401,6 @@ ArmarX.Verbosity = Verbose
 #  - Default:            0.550000012
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.550000012
+ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
diff --git a/scenarios/PlatformNavigation/PlatformNavigation.scx b/scenarios/PlatformNavigation/PlatformNavigation.scx
index cc0fcea7..a290831f 100644
--- a/scenarios/PlatformNavigation/PlatformNavigation.scx
+++ b/scenarios/PlatformNavigation/PlatformNavigation.scx
@@ -6,7 +6,7 @@
 	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index b2764c9b..be7ed818 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -513,21 +513,12 @@
 # ArmarX.ObjectMemory.mem.inst.visu.useArticulatedModels = true
 
 
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.ObjectMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.depthImageExtractor.Enabled = true
+# ArmarX.ObjectMemory.mem.ltm.configuration = {}
 
 
 # ArmarX.ObjectMemory.mem.ltm.enabled:  
@@ -539,100 +530,6 @@
 # ArmarX.ObjectMemory.mem.ltm.enabled = false
 
 
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.imageExtractor.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.pngConverter.Enabled = true
-
-
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
-# ArmarX.ObjectMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.mem.ltm.storagepath = Default value not mapped.
-
-
 # ArmarX.ObjectMemory.mem.robot_state.Memory:  
 #  Attributes:
 #  - Default:            RobotState
@@ -765,3 +662,5 @@
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/PlatformNavigation/config/VisionMemory.cfg b/scenarios/PlatformNavigation/config/VisionMemory.cfg
index 0dfef493..1b95447f 100644
--- a/scenarios/PlatformNavigation/config/VisionMemory.cfg
+++ b/scenarios/PlatformNavigation/config/VisionMemory.cfg
@@ -210,21 +210,12 @@
 # ArmarX.VisionMemory.mem.MemoryName = Vision
 
 
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq:  Frequency to store the buffer to the LTM in Hz.
+# ArmarX.VisionMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10
-
-
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true
+# ArmarX.VisionMemory.mem.ltm.configuration = {}
 
 
 # ArmarX.VisionMemory.mem.ltm.enabled:  
@@ -236,100 +227,6 @@
 # ArmarX.VisionMemory.mem.ltm.enabled = false
 
 
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime:  Waiting time in MS after each LTM update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled:  
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true
-
-
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
-#  Attributes:
-#  - Default:            1024
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
-
-
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime:  Max Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled:  
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false
-
-
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime:  Waiting time in MS after each Entity update.
-#  Attributes:
-#  - Default:            -1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1
-
-
-# ArmarX.VisionMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.VisionMemory.mem.ltm.storagepath = Default value not mapped.
-
-
 # ArmarX.VisionMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
@@ -362,3 +259,5 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 # ArmarX.VisionMemory.pointCloudMaxHistorySize = 20
+
+
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index 6a9bccd3..f459b030 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -76,56 +76,6 @@
 # ArmarX.EnableProfiling = false
 
 
-# ArmarX.ExampleClient.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.EnableProfiling = false
-
-
-# ArmarX.ExampleClient.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.ExampleClient.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.ExampleClient.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.ObjectName = ""
-
-
-# ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
-#  Attributes:
-#  - Default:            navigator
-#  - Case sensitivity:   yes
-#  - Required:           no
-ArmarX.ExampleClient.nav.NavigatorName = navigator
-
-
-# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
-#  Attributes:
-#  - Default:            200
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.relativeMovement = 200
-
-
-# ArmarX.ExampleClient.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.robotName = Armar6
-
-
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
@@ -208,3 +158,103 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
 # ArmarX.Verbosity = Info
+
+
+# ArmarX.example_client.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.example_client.EnableProfiling = false
+
+
+# ArmarX.example_client.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.example_client.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.example_client.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.ObjectName = ""
+
+
+# ArmarX.example_client.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.example_client.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.example_client.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.example_client.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.example_client.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.example_client.mode:  Which example to run
+#  Attributes:
+#  - Default:            standard
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {complex, point_to_point, standard, update_navigator}
+ArmarX.example_client.mode = standard
+
+
+# ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
+#  Attributes:
+#  - Default:            navigator
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.nav.NavigatorName = navigator
+
+
+# ArmarX.example_client.relativeMovement:  The distance between two target poses [mm]
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.relativeMovement = 200
+
+
+# ArmarX.example_client.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.robotName = Armar6
+
+
+# ArmarX.ExampleClient.nav.NavigatorName:  
+#  Attributes:
+ArmarX.ExampleClient.nav.NavigatorName = navigator
+
+
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index 8253a316..74b205e7 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,213 +92,204 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.NavigationMemory.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            ArVizStorage
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ArVizStorageName = ArVizStorage
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.NavigationMemory.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            ArVizTopic
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ArVizTopicName = ArVizTopic
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.NavigationMemory.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            false
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.EnableProfiling = false
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.NavigationMemory.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.NavigationMemory.MinimumLoggingLevel = Undefined
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ObjectName = ""
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.NavigationMemory.RemoteGuiName:  Name of the remote gui provider
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.RemoteGuiName = RemoteGuiProvider
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.NavigationMemory.mem.MemoryName:  Name of this memory server.
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.MemoryName = Navigation
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.NavigationMemory.mem.ltm.configuration:  
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            {}
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm..configuration = ""
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
 
 
-# ArmarX.NavigationMemory.mem.ltm.enabled:  
+# ArmarX.navigation_memory.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            false
+#  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm..enabled = false
+# ArmarX.navigation_memory.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes:  The size in MB to compress away the current export. Exports are numbered (lower number means newer).
+# ArmarX.navigation_memory.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            1024
+#  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024
+# ArmarX.navigation_memory.ArVizTopicName = ArVizTopic
 
 
-# ArmarX.NavigationMemory.mem.ltm.storagepath:  The path to the memory storage (the memory will be stored in a seperate subfolder).
+# ArmarX.navigation_memory.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            Default value not mapped.
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.storagepath = Default value not mapped.
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.EnableProfiling = false
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.navigation_memory.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            true
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled = true
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.navigation_memory.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigation_memory.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.navigation_memory.ObjectName = ""
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+# ArmarX.navigation_memory.RemoteGuiName:  Name of the remote gui provider
 #  Attributes:
-#  - Default:            2
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency = 2
+# ArmarX.navigation_memory.RemoteGuiName = RemoteGuiProvider
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+# ArmarX.navigation_memory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
-#  - Default:            true
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges = true
+# ArmarX.navigation_memory.mem.MemoryName = Navigation
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation:  Enable visualization of locations.
+# ArmarX.navigation_memory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation = true
+# ArmarX.navigation_memory.mem.ltm.configuration = {}
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+# ArmarX.navigation_memory.mem.ltm.enabled:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.mem.ltm.enabled = false
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
 #  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigation_memory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            3000
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.navigation_memory.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            0
+#  - Default:            2
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 2
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
 #  Attributes:
-#  - Default:            false
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges = true
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigation_memory.p.locationGraph.visuLocation:  Enable visualization of locations.
 #  Attributes:
-#  - Default:            1
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.p.locationGraph.visuLocation = true
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.navigation_memory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.navigation_memory.p.snapshotToLoad = ""
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.NavigationMemory.p.snapshotToLoad:  
 #  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
-#  Attributes:
-#  - Default:            Info
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 233f17f4..5bf206ad 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -139,20 +139,12 @@
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.ObjectName = navigator
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            Armar6Unit
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.Navigator.RobotUnitName = Armar6Unit
-
-
-# ArmarX.Navigator.cmp.PlatformUnit:  Ice object name of the `PlatformUnit` component.
-#  Attributes:
-#  - Default:            PlatformUnit
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
@@ -184,6 +176,14 @@ ArmarX.Verbosity = Verbose
 # ArmarX.navigator.ArVizTopicName = ArVizTopic
 
 
+# ArmarX.navigator.DebugObserverTopicName:  Name of the topic the DebugObserver listens on
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.DebugObserverTopicName = DebugObserver
+
+
 # ArmarX.navigator.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
@@ -278,43 +278,50 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
+# ArmarX.navigator.mem.nav.events.Provider = ""
 
 
-# ArmarX.Navigator.mem.robot_state.Memory:  
+# ArmarX.navigator.mem.nav.graph.CoreSegment:  
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            Location
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.Memory = RobotState
+# ArmarX.navigator.mem.nav.graph.CoreSegment = Location
 
 
-# ArmarX.Navigator.mem.robot_state.descriptionSegment:  
+# ArmarX.navigator.mem.nav.graph.Memory:  
 #  Attributes:
-#  - Default:            Description
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.descriptionSegment = Description
+# ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  
+# ArmarX.navigator.mem.nav.human.CoreSegment:  
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.mem.nav.human.CoreSegment = Human
+
+
+# ArmarX.navigator.mem.nav.human.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigator.mem.nav.graph.Memory = Navigation
+# ArmarX.navigator.mem.nav.human.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment:  
+# ArmarX.navigator.mem.nav.param.CoreSegment:  
 #  Attributes:
-#  - Default:            Proprioception
+#  - Default:            Parameterization
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.proprioceptionSegment = Proprioception
+# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.navigator.mem.nav.param.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
@@ -338,15 +345,15 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 # ArmarX.navigator.mem.nav.stack_result.CoreSegment = ""
 
 
-# ArmarX.Navigator.tpc.sub.MemoryListener:  Name of the `MemoryListener` topic to subscribe to.
+# ArmarX.navigator.mem.nav.stack_result.Memory:  
 #  Attributes:
-#  - Default:            MemoryUpdates
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.tpc.sub.MemoryListener = MemoryUpdates
+# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigator.mem.nav.stack_result.Provider:  Name of this provider
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
@@ -403,3 +410,15 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 #  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
+# ArmarX.Navigator.ObjectName:  
+#  Attributes:
+ArmarX.Navigator.ObjectName = navigator
+
+
+# ArmarX.Navigator.RobotUnitName:  
+#  Attributes:
+ArmarX.Navigator.RobotUnitName = Armar6Unit
+
+
-- 
GitLab


From 8ea35a42f6ba63301a644b414adca77ffa86f5cb Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 20:25:49 +0200
Subject: [PATCH 138/324] reming private eigen includes

---
 examples/components/example_client/Component.cpp | 3 ---
 1 file changed, 3 deletions(-)

diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index 7b48c323..c950667e 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -27,9 +27,6 @@
 #include <cmath>
 #include <thread>
 
-#include <Eigen/src/Geometry/AngleAxis.h>
-#include <Eigen/src/Geometry/Translation.h>
-
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/time/Clock.h>
 #include <ArmarXCore/core/time/ClockType.h>
-- 
GitLab


From 1c3ee0eb9377af1b80ccef7ad6438c4fed1e7469 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 19 Aug 2022 20:26:10 +0200
Subject: [PATCH 139/324] reduced verbosity; fixed example component

---
 .../components/example_client/Component.cpp   | 22 ++++++++++++++-----
 .../components/example_client/Component.h     |  2 ++
 .../navigation/client/ComponentPlugin.cpp     |  2 ++
 .../navigation/global_planning/AStar.cpp      | 11 +++++-----
 .../navigation/memory/client/human/Reader.cpp |  5 ++---
 source/armarx/navigation/server/Navigator.cpp |  6 ++---
 6 files changed, 31 insertions(+), 17 deletions(-)

diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index c950667e..4bb1c1f7 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -34,6 +34,8 @@
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
 #include "armarx/navigation/core/types.h"
+#include "armarx/navigation/global_planning/SPFA.h"
+#include "armarx/navigation/local_planning/TimedElasticBands.h"
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
@@ -89,9 +91,17 @@ namespace armarx::navigation::components::example_client
     std::string
     Component::getDefaultName() const
     {
-        return "ExampleClient";
+        return GetDefaultName();
     }
 
+
+    std::string
+    Component::GetDefaultName()
+    {
+        return "example_client";
+    }
+
+
     void
     Component::run()
     {
@@ -129,7 +139,8 @@ namespace armarx::navigation::components::example_client
         configureNavigator(
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
-                .globalPlanner(global_planning::AStarParams())
+                .globalPlanner(global_planning::SPFAParams())
+                .localPlanner(local_planning::TimedElasticBandsParams())
                 .trajectoryController(traj_ctrl::local::TrajectoryFollowingControllerParams()));
 
         // Example of registering a lambda as callback.
@@ -173,7 +184,7 @@ namespace armarx::navigation::components::example_client
         configureNavigator(
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
-                .globalPlanner(global_planning::AStarParams())
+                .globalPlanner(global_planning::SPFAParams())
                 .trajectoryController(
                     traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
@@ -273,7 +284,7 @@ namespace armarx::navigation::components::example_client
         configureNavigator(
             client::NavigationStackConfig()
                 .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
-                .globalPlanner(global_planning::AStarParams())
+                .globalPlanner(global_planning::SPFAParams())
                 .trajectoryController(
                     traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
 
@@ -444,7 +455,6 @@ namespace armarx::navigation::components::example_client
         return def;
     }
 
-
-    ARMARX_DECOUPLED_REGISTER_COMPONENT(Component);
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
 
 } // namespace armarx::navigation::components::example_client
diff --git a/examples/components/example_client/Component.h b/examples/components/example_client/Component.h
index 2e622a35..3c6748d3 100644
--- a/examples/components/example_client/Component.h
+++ b/examples/components/example_client/Component.h
@@ -65,6 +65,8 @@ namespace armarx::navigation::components::example_client
 
         ~Component() override;
 
+        static std::string GetDefaultName();
+
     protected:
         /// @see PropertyUser::createPropertyDefinitions()
         armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
diff --git a/source/armarx/navigation/client/ComponentPlugin.cpp b/source/armarx/navigation/client/ComponentPlugin.cpp
index 173e3dd4..2ecd8fce 100644
--- a/source/armarx/navigation/client/ComponentPlugin.cpp
+++ b/source/armarx/navigation/client/ComponentPlugin.cpp
@@ -62,8 +62,10 @@ namespace armarx::navigation::client
 
         eventHandler = [&]() -> std::unique_ptr<SimpleEventHandler>
         {
+            ARMARX_TRACE;
             if (parentDerives<armarx::armem::client::plugins::ListeningPluginUser>())
             {
+                ARMARX_TRACE;
                 ARMARX_INFO << "Using memory event callbacks.";
                 // must(!!) use a reference here: otherwise the mns events won't work
                 auto& memoryNameSystem =
diff --git a/source/armarx/navigation/global_planning/AStar.cpp b/source/armarx/navigation/global_planning/AStar.cpp
index 67db7790..6765a908 100644
--- a/source/armarx/navigation/global_planning/AStar.cpp
+++ b/source/armarx/navigation/global_planning/AStar.cpp
@@ -283,15 +283,16 @@ namespace armarx::navigation::global_planning
 
         if (not result)
         {
-            ARMARX_ERROR << "Optimizer failure";
+            ARMARX_WARNING << "Optimizer failure";
             return std::nullopt;
         }
 
-        // TODO circular path smoothing should be done now
+        ARMARX_TRACE;
 
-        algorithm::CircularPathSmoothing smoothing;
-        auto smoothTrajectory = smoothing.smooth(result.trajectory.value());
-        smoothTrajectory.setMaxVelocity(params.linearVelocity);
+        // TODO circular path smoothing should be done now
+        // algorithm::CircularPathSmoothing smoothing;
+        // auto smoothTrajectory = smoothing.smooth(result.trajectory.value());
+        // smoothTrajectory.setMaxVelocity(params.linearVelocity);
 
         ARMARX_TRACE;
         return GlobalPlannerResult{.trajectory = result.trajectory.value()};
diff --git a/source/armarx/navigation/memory/client/human/Reader.cpp b/source/armarx/navigation/memory/client/human/Reader.cpp
index e3bee9f2..de91ae99 100644
--- a/source/armarx/navigation/memory/client/human/Reader.cpp
+++ b/source/armarx/navigation/memory/client/human/Reader.cpp
@@ -152,8 +152,7 @@ namespace armarx::navigation::memory::client::human
 
         if (not coreSegment.hasProviderSegment(query.providerName))
         {
-            ARMARX_VERBOSE << "Provider segment `" << query.providerName
-                           << "` does not exist (yet).";
+            ARMARX_DEBUG << "Provider segment `" << query.providerName << "` does not exist (yet).";
             return {.groups = {}, .status = HumanGroupResult::Status::NoData};
         }
 
@@ -162,7 +161,7 @@ namespace armarx::navigation::memory::client::human
 
         if (providerSegment.empty())
         {
-            ARMARX_VERBOSE << "No entities.";
+            ARMARX_DEBUG << "No entities.";
             return {.groups = {},
                     .status = HumanGroupResult::Status::NoData,
                     .errorMessage = "No entities"};
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 22913fa5..6c4c51b9 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -804,7 +804,7 @@ namespace armarx::navigation::server
             const Duration duration =
                 armarx::core::time::StopWatch::measure([&]() { updateScene(); });
 
-            ARMARX_VERBOSE << deactivateSpam(0.2)
+            ARMARX_DEBUG << deactivateSpam(0.2)
                            << "Scene update: " << duration.toMilliSecondsDouble() << "ms.";
 
             srv.debugObserverHelper->setDebugObserverDatafield("scene update [ms]", duration.toMilliSecondsDouble());
@@ -881,7 +881,7 @@ namespace armarx::navigation::server
                         updateIntrospector(localPlannerResult);
                     }
                 });
-            ARMARX_VERBOSE << deactivateSpam(0.2)
+            ARMARX_DEBUG << deactivateSpam(0.2)
                            << "Local planner update: " << duration.toMilliSecondsDouble() << "ms.";
 
             srv.debugObserverHelper->setDebugObserverDatafield("local planner update [ms]", duration.toMilliSecondsDouble());
@@ -894,7 +894,7 @@ namespace armarx::navigation::server
             const Duration duration =
                 armarx::core::time::StopWatch::measure([&]() { updateMonitor(); });
 
-            ARMARX_VERBOSE << deactivateSpam(0.2)
+            ARMARX_DEBUG << deactivateSpam(0.2)
                            << "Monitor update: " << duration.toMilliSecondsDouble() << "ms.";
 
             srv.debugObserverHelper->setDebugObserverDatafield("monitor update [ms]", duration.toMilliSecondsDouble());
-- 
GitLab


From 7e8ee33076517a72f416a4c2c77b5c52f7d0a272 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 22 Aug 2022 14:11:42 +0200
Subject: [PATCH 140/324] Visualize path alternatives inside TimedElasticBands

---
 .../local_planning/TimedElasticBands.cpp      | 29 ++++++++++++++++++-
 1 file changed, 28 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index b9a9d0b3..ce1fbbd8 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,5 +1,6 @@
 #include "TimedElasticBands.h"
 
+#include <SimoxUtility/algorithm/apply.hpp>
 #include <SimoxUtility/json/json.hpp>
 #include <VirtualRobot/MathTools.h>
 #include <VirtualRobot/Robot.h>
@@ -128,6 +129,32 @@ namespace armarx::navigation::local_planning
 
         core::LocalTrajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
 
+        // visualize path alternatives
+        if (arviz != nullptr)
+        {
+            auto layer = arviz->layer("local_planner_path_alternatives");
+
+            int i = 0;
+            int bestTebIdx = hcp_->bestTebIdx();
+            for (const auto& teb : hcp_->getTrajectoryContainer())
+            {
+                if (i == bestTebIdx)
+                {
+                    continue;
+                }
+                const core::LocalTrajectory trajectory = conv::fromRos(teb->teb());
+                const std::vector<Eigen::Vector3f> points =
+                    simox::alg::apply(trajectory.points(),
+                                      [](const core::LocalTrajectoryPoint& pt) -> Eigen::Vector3f
+                                      { return pt.pose.translation(); });
+                layer.add(viz::Path("path_alternative_" + std::to_string(i))
+                              .points(points)
+                              .color(simox::Color::gray()));
+                i++;
+            }
+            arviz->commit(layer);
+        }
+
         return {{.trajectory = best}};
     }
 
@@ -165,7 +192,7 @@ namespace armarx::navigation::local_planning
             ARMARX_CHECK(scene.dynamicScene.has_value());
             for (const auto& obst : scene.dynamicScene.value().humans)
             {
-              obstManager.addHumanObstacle(obst, visPtr);
+                obstManager.addHumanObstacle(obst, visPtr);
             }
         }
 
-- 
GitLab


From 763f18ff43d84ad417771cf985a3ecaa87b7385e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 22 Aug 2022 17:32:50 +0200
Subject: [PATCH 141/324] Move visualization member to LocalPlanner

viz::ScopedClient was changed to viz::Client
---
 source/armarx/navigation/local_planning/LocalPlanner.cpp | 6 ++++++
 source/armarx/navigation/local_planning/LocalPlanner.h   | 7 ++++++-
 .../navigation/local_planning/TimedElasticBands.cpp      | 9 +--------
 .../armarx/navigation/local_planning/TimedElasticBands.h | 5 -----
 4 files changed, 13 insertions(+), 14 deletions(-)

diff --git a/source/armarx/navigation/local_planning/LocalPlanner.cpp b/source/armarx/navigation/local_planning/LocalPlanner.cpp
index b98a0a53..4b7ea7ed 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.cpp
+++ b/source/armarx/navigation/local_planning/LocalPlanner.cpp
@@ -5,4 +5,10 @@ namespace armarx::navigation::local_planning
     LocalPlanner::LocalPlanner(const core::Scene& context) : context(context)
     {
     }
+
+    void
+    LocalPlanner::setVisualization(viz::Client* vis)
+    {
+        arviz = vis;
+    }
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h
index 8c2554d6..f2f6641b 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.h
+++ b/source/armarx/navigation/local_planning/LocalPlanner.h
@@ -26,13 +26,14 @@
 
 #include <VirtualRobot/VirtualRobot.h>
 
+#include <RobotAPI/components/ArViz/Client/ScopedClient.h>
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
-#include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/core/DynamicScene.h>
 #include <armarx/navigation/core/StaticScene.h>
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
+#include <armarx/navigation/local_planning/core.h>
 
 namespace armarx::navigation::local_planning
 {
@@ -57,7 +58,11 @@ namespace armarx::navigation::local_planning
 
         virtual std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) = 0;
 
+        void setVisualization(viz::Client* vis);
+
     protected:
+        viz::Client* arviz;
+
     private:
         const core::Scene& context;
     };
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index b9a9d0b3..0a580d18 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -131,13 +131,6 @@ namespace armarx::navigation::local_planning
         return {{.trajectory = best}};
     }
 
-    void
-    TimedElasticBands::setVisualization(viz::ScopedClient* vis)
-    {
-        arviz = vis;
-    }
-
-
     void
     TimedElasticBands::fillObstacles()
     {
@@ -165,7 +158,7 @@ namespace armarx::navigation::local_planning
             ARMARX_CHECK(scene.dynamicScene.has_value());
             for (const auto& obst : scene.dynamicScene.value().humans)
             {
-              obstManager.addHumanObstacle(obst, visPtr);
+                obstManager.addHumanObstacle(obst, visPtr);
             }
         }
 
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 2bf54057..9eba4d52 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -22,7 +22,6 @@
 
 #pragma once
 
-#include <RobotAPI/components/ArViz/Client/ScopedClient.h>
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
 #include "armarx/navigation/core/basic_types.h"
@@ -59,8 +58,6 @@ namespace armarx::navigation::local_planning
 
         std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
 
-        void setVisualization(viz::ScopedClient* vis);
-
     private:
         void readDefaultConfig(arondto::TimedElasticBandsParams& target);
         void fillObstacles();
@@ -76,7 +73,5 @@ namespace armarx::navigation::local_planning
         TebObstacleManager obstManager;
         teb_local_planner::PoseSequence teb_globalPath;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
-
-        viz::ScopedClient* arviz;
     };
 } // namespace armarx::navigation::local_planning
-- 
GitLab


From 9c99adbbc5bc794be1a559cd28aaefd3c55e4702 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 22 Aug 2022 17:33:51 +0200
Subject: [PATCH 142/324] Set visualization of LocalPlanner in createConfig

---
 .../components/navigator/Component.cpp        | 27 ++++++++++---------
 1 file changed, 15 insertions(+), 12 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 402c90e4..34d27ae7 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -67,9 +67,6 @@
 #include <RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
-#include <armarx/navigation/memory/client/costmap/Reader.h>
-#include <armarx/navigation/server/execution/ExecutorInterface.h>
-#include <armarx/navigation/server/scene_provider/SceneProvider.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
 #include <armarx/navigation/algorithms/astar/util.h>
@@ -84,9 +81,12 @@
 #include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/factories/NavigationStackFactory.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
 #include <armarx/navigation/server/Navigator.h>
 #include <armarx/navigation/server/event_publishing/MemoryPublisher.h>
+#include <armarx/navigation/server/execution/ExecutorInterface.h>
 #include <armarx/navigation/server/introspection/MemoryIntrospector.h>
+#include <armarx/navigation/server/scene_provider/SceneProvider.h>
 #include <armarx/navigation/util/util.h>
 
 namespace armarx::navigation::components::navigator
@@ -257,6 +257,9 @@ namespace armarx::navigation::components::navigator
         server::NavigationStack stack =
             fac::NavigationStackFactory::create(stackConfig, sceneProvider->scene());
 
+        // set visualization of LocalPlanner
+        stack.localPlanner->setVisualization(&getArvizClient());
+
         memoryIntrospectors.emplace_back(
             std::make_unique<server::MemoryIntrospector>(resultsWriterPlugin->get(), callerId));
 
@@ -278,12 +281,12 @@ namespace armarx::navigation::components::navigator
             std::forward_as_tuple(
                 server::Navigator::Config{.stack = std::move(stack),
                                           .general = server::Navigator::Config::General{}},
-                server::Navigator::InjectedServices{.executor = executorPtr,
-                                                    .publisher =
-                                                        memoryPublishers.at(callerId).get(),
-                                                    .introspector = &(introspector.value()),
-                                                    .debugObserverHelper = &getDebugObserverComponentPlugin(),
-                                                    .sceneProvider = &sceneProvider.value()}));
+                server::Navigator::InjectedServices{
+                    .executor = executorPtr,
+                    .publisher = memoryPublishers.at(callerId).get(),
+                    .introspector = &(introspector.value()),
+                    .debugObserverHelper = &getDebugObserverComponentPlugin(),
+                    .sceneProvider = &sceneProvider.value()}));
     }
 
     void
@@ -319,7 +322,7 @@ namespace armarx::navigation::components::navigator
     Component::updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
                             const std::string& navigationMode,
                             const std::string& callerId,
-                            const Ice::Current&  /*c*/)
+                            const Ice::Current& /*c*/)
     {
         ARMARX_TRACE;
 
@@ -535,9 +538,9 @@ namespace armarx::navigation::components::navigator
     server::Navigator*
     Component::activeNavigator()
     {
-        
+
         const auto navigatorId = activeNavigatorId();
-        if(not navigatorId.has_value())
+        if (not navigatorId.has_value())
         {
             return nullptr;
         }
-- 
GitLab


From 2e5ebf35a5e60f498fdd6e8e5ce56bd93c4b40ac Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 24 Aug 2022 14:30:55 +0200
Subject: [PATCH 143/324] Fix human tracking and association

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 30 +++++++++----------
 1 file changed, 14 insertions(+), 16 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 4bdc8c4b..2196ad99 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -41,22 +41,6 @@ namespace armarx::navigation::components::dynamic_scene_provider
     void
     HumanTracker::update(const Measurements& measurements)
     {
-        trackedHumans.clear();
-
-        for (const armem::human::HumanPose& measurement : measurements.humanPoses)
-        {
-            human::Human human{
-                .pose = conv::to2D(
-                    core::Pose(Eigen::Translation3f(measurement.keypoints.begin()->second.positionGlobal->toEigen()))),
-                .linearVelocity = Eigen::Vector2f::Zero(),
-                .detectionTime = 0};
-
-            trackedHumans.push_back(TrackedHuman{
-                .human = human, .trackingId = std::to_string(trackedHumans.size()), .associated = true});
-        }
-
-        return; // FIXME remove section above
-
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
@@ -81,6 +65,20 @@ namespace armarx::navigation::components::dynamic_scene_provider
             ranges::to_vector;
 
         associateHumans(newPoses);
+
+        // add all not associated humans as new tracked humans
+        for (const auto& detectedHuman : newPoses)
+        {
+            if (!detectedHuman.associated)
+            {
+                human::Human human{.pose = detectedHuman.pose,
+                                   .linearVelocity = Eigen::Vector2f::Zero(),
+                                   .detectionTime = detectedHuman.detectionTime};
+
+                trackedHumans.push_back(
+                    {.human = human, .trackingId = detectedHuman.trackingId, .associated = true});
+            }
+        }
     }
 
     struct PosDistance
-- 
GitLab


From 54dedfeea3c80c3e9efc21fba01ef9b8966c2b39 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Wed, 24 Aug 2022 18:04:24 +0200
Subject: [PATCH 144/324] Add new teb_config paramters from new global path
 edge

Teb now uses the orientation of the global path for optimization which
added a new weight paramter.
---
 .../local_planner_config/TimedElasticBands/default.json     | 3 ++-
 .../navigation/local_planning/aron/TimedElasticBands.xml    | 6 +++++-
 .../armarx/navigation/local_planning/aron_conversions.cpp   | 3 ++-
 3 files changed, 9 insertions(+), 3 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 0dcf777b..8ba4936e 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -6,7 +6,8 @@
     "pse": {
       "pse_costum_obstacle_penalties": true,
       "pse_costum_obstacle_penalties_dynamic": true,
-      "weight_global_path": 0.3,
+      "weight_global_path_position": 0.3,
+      "weight_global_path_orientation": 0.3,
       "lrk_use_alternative_approach": false,
       "lrk_enable_collision_check": true,
       "hybrid_homotopy_calculation": true,
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 4c3c9249..352c9213 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -14,7 +14,11 @@
                 <bool />
             </ObjectChild>
 
-            <ObjectChild key='weight_global_path'>
+            <ObjectChild key='weight_global_path_position'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='weight_global_path_orientation'>
                 <float />
             </ObjectChild>
 
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 220a02b3..0601914b 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -29,7 +29,8 @@ namespace armarx::navigation::local_planning
         bo.pse.pse_costum_obstacle_penalties = dto.teb_config.pse.pse_costum_obstacle_penalties;
         bo.pse.pse_costum_obstacle_penalties_dynamic =
             dto.teb_config.pse.pse_costum_obstacle_penalties_dynamic;
-        bo.pse.weight_global_path = dto.teb_config.pse.weight_global_path;
+        bo.pse.weight_global_path_position = dto.teb_config.pse.weight_global_path_position;
+        bo.pse.weight_global_path_orientation = dto.teb_config.pse.weight_global_path_orientation;
         bo.pse.lrk_use_alternative_approach = dto.teb_config.pse.lrk_use_alternative_approach;
         bo.pse.lrk_enable_collision_check = dto.teb_config.pse.lrk_enable_collision_check;
         bo.pse.hybrid_homotopy_calculation = dto.teb_config.pse.hybrid_homotopy_calculation;
-- 
GitLab


From 267bb959bca0761fedfbcde7751b1e9ca81933ec Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 24 Aug 2022 20:53:55 +0200
Subject: [PATCH 145/324] deleting use file as it is no longer needed

---
 etc/cmake/Usearmarx_navigation.cmake | 1 -
 1 file changed, 1 deletion(-)
 delete mode 100644 etc/cmake/Usearmarx_navigation.cmake

diff --git a/etc/cmake/Usearmarx_navigation.cmake b/etc/cmake/Usearmarx_navigation.cmake
deleted file mode 100644
index 4c5c677a..00000000
--- a/etc/cmake/Usearmarx_navigation.cmake
+++ /dev/null
@@ -1 +0,0 @@
-# This file contains macros for projects depending on Navigation
-- 
GitLab


From 740a34772bf3edeee434bb1d2b3744e0a1feaa33 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 24 Aug 2022 20:54:14 +0200
Subject: [PATCH 146/324] GraphImportExport: component name is now
 graph_import_export

---
 .../navigation/components/graph_import_export/CMakeLists.txt    | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/graph_import_export/CMakeLists.txt b/source/armarx/navigation/components/graph_import_export/CMakeLists.txt
index 40de77dd..44a43ae8 100644
--- a/source/armarx/navigation/components/graph_import_export/CMakeLists.txt
+++ b/source/armarx/navigation/components/graph_import_export/CMakeLists.txt
@@ -1,4 +1,4 @@
-armarx_add_component(GraphImportExport
+armarx_add_component(graph_import_export
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
-- 
GitLab


From 7da5feb5615e60f91d68acbde01ddabfeee81b81 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 24 Aug 2022 20:55:34 +0200
Subject: [PATCH 147/324] formatting files

---
 source/armarx/navigation/core/aron/Graph.xml     |  2 +-
 .../armarx/navigation/server/test/serverTest.cpp | 16 +++++++++-------
 2 files changed, 10 insertions(+), 8 deletions(-)

diff --git a/source/armarx/navigation/core/aron/Graph.xml b/source/armarx/navigation/core/aron/Graph.xml
index 8c717719..e4d07bc0 100644
--- a/source/armarx/navigation/core/aron/Graph.xml
+++ b/source/armarx/navigation/core/aron/Graph.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0" encoding="UTF-8" ?>
 <AronTypeDefinition>
     <AronIncludes>
-      <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" autoinclude="true" />
+        <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" autoinclude="true" />
     </AronIncludes>
 
     <GenerateTypes>
diff --git a/source/armarx/navigation/server/test/serverTest.cpp b/source/armarx/navigation/server/test/serverTest.cpp
index b7c81dfa..701b55ae 100644
--- a/source/armarx/navigation/server/test/serverTest.cpp
+++ b/source/armarx/navigation/server/test/serverTest.cpp
@@ -56,17 +56,17 @@ namespace armarx::navigation::server::scene_provider
         const core::Scene&
         scene() const override
         {
-            return dummyScene; 
+            return dummyScene;
         };
 
         bool
-        initialize(const armarx::DateTime&  /*timestamp*/) override
+        initialize(const armarx::DateTime& /*timestamp*/) override
         {
             return true;
         };
 
         bool
-        synchronize(const armarx::DateTime&  /*timestamp*/) override
+        synchronize(const armarx::DateTime& /*timestamp*/) override
         {
             return true;
         };
@@ -75,7 +75,7 @@ namespace armarx::navigation::server::scene_provider
         // non-api
         ~DummySceneProvider() override = default;
 
-        private:
+    private:
         core::Scene dummyScene; // FIXME implement
     };
 
@@ -99,15 +99,17 @@ BOOST_AUTO_TEST_CASE(testNavigator)
     //           traj_ctrl::TrajectoryFollowingControllerParams(), scene)};
 
     // Executor.
-    server::DummyExecutor executor{scene.robot, server::DummyExecutor::Params()};
+    server::DummyExecutor executor;
     client::SimpleEventHandler eventHandler;
 
     server::scene_provider::DummySceneProvider sceneProvider;
 
     server::Navigator navigator(
         server::Navigator::Config{.stack = stack, .general = server::Navigator::Config::General{}},
-        server::Navigator::InjectedServices{
-            .executor = &executor, .publisher = &eventHandler, .sceneProvider = &sceneProvider});
+        server::Navigator::InjectedServices{.executor = &executor,
+                                            .publisher = &eventHandler,
+                                            .debugObserverHelper = nullptr,
+                                            .sceneProvider = &sceneProvider});
     navigator.moveTo(std::vector{goal}, core::NavigationFrame::Absolute);
 
     BOOST_CHECK_EQUAL(true, true);
-- 
GitLab


From 90183c5eab3ac760636bcc2e3206719f65bbb9ab Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 14:24:14 +0200
Subject: [PATCH 148/324] Make visualization inside LocalPlanner ScopedClient

---
 .../navigation/components/navigator/Component.cpp |  2 +-
 .../navigation/local_planning/LocalPlanner.cpp    |  4 ++--
 .../navigation/local_planning/LocalPlanner.h      |  4 ++--
 .../local_planning/TimedElasticBands.cpp          | 15 ++++++++-------
 4 files changed, 13 insertions(+), 12 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 34d27ae7..3509d2f3 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -258,7 +258,7 @@ namespace armarx::navigation::components::navigator
             fac::NavigationStackFactory::create(stackConfig, sceneProvider->scene());
 
         // set visualization of LocalPlanner
-        stack.localPlanner->setVisualization(&getArvizClient());
+        stack.localPlanner->setVisualization(getArvizClient());
 
         memoryIntrospectors.emplace_back(
             std::make_unique<server::MemoryIntrospector>(resultsWriterPlugin->get(), callerId));
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.cpp b/source/armarx/navigation/local_planning/LocalPlanner.cpp
index 4b7ea7ed..ab0fbd22 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.cpp
+++ b/source/armarx/navigation/local_planning/LocalPlanner.cpp
@@ -7,8 +7,8 @@ namespace armarx::navigation::local_planning
     }
 
     void
-    LocalPlanner::setVisualization(viz::Client* vis)
+    LocalPlanner::setVisualization(viz::Client& vis)
     {
-        arviz = vis;
+        arviz.emplace(vis);
     }
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h
index f2f6641b..03131881 100644
--- a/source/armarx/navigation/local_planning/LocalPlanner.h
+++ b/source/armarx/navigation/local_planning/LocalPlanner.h
@@ -58,10 +58,10 @@ namespace armarx::navigation::local_planning
 
         virtual std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) = 0;
 
-        void setVisualization(viz::Client* vis);
+        void setVisualization(viz::Client& vis);
 
     protected:
-        viz::Client* arviz;
+        std::optional<viz::ScopedClient> arviz;
 
     private:
         const core::Scene& context;
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 2633583d..daedf66c 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -130,9 +130,9 @@ namespace armarx::navigation::local_planning
         core::LocalTrajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
 
         // visualize path alternatives
-        if (arviz != nullptr)
+        if (arviz)
         {
-            auto layer = arviz->layer("local_planner_path_alternatives");
+            auto layer = arviz.value().layer("local_planner_path_alternatives");
 
             int i = 0;
             int bestTebIdx = hcp_->bestTebIdx();
@@ -152,7 +152,8 @@ namespace armarx::navigation::local_planning
                               .color(simox::Color::gray()));
                 i++;
             }
-            arviz->commit(layer);
+
+            arviz.value().commit(layer);
         }
 
         return {{.trajectory = best}};
@@ -165,9 +166,9 @@ namespace armarx::navigation::local_planning
 
         viz::Layer* visPtr = nullptr;
         viz::Layer visLayer;
-        if (arviz != nullptr)
+        if (arviz)
         {
-            visLayer = arviz->layer("local_planner_obstacles");
+            visLayer = arviz.value().layer("local_planner_obstacles");
             visPtr = &visLayer;
         }
 
@@ -189,9 +190,9 @@ namespace armarx::navigation::local_planning
             }
         }
 
-        if (arviz != nullptr)
+        if (arviz)
         {
-            arviz->commit(visLayer);
+            arviz.value().commit(visLayer);
         }
 
         ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";
-- 
GitLab


From ee0795dabf509edd05f37326b1786217bcc6cf38 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 14:24:33 +0200
Subject: [PATCH 149/324] Fix bounding box coordinates

---
 source/armarx/navigation/local_planning/TebObstacleManager.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 5e46a901..c7288854 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -29,7 +29,7 @@ namespace armarx::navigation::local_planning
         auto obst = boost::make_shared<teb_local_planner::PolygonObstacle>();
 
         const Eigen::Vector2d min = conv::toRos(bbox.getMin());
-        const Eigen::Vector2d max = conv::toRos(bbox.getMin());
+        const Eigen::Vector2d max = conv::toRos(bbox.getMax());
 
         obst->pushBackVertex(min);
         obst->pushBackVertex(min.x(), max.y());
-- 
GitLab


From b34891b1a71436e03a036822d02650e93c48e296 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 15:06:58 +0200
Subject: [PATCH 150/324] Update config

---
 .../local_planner_config/TimedElasticBands/default.json         | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 8ba4936e..53f1c25e 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -70,7 +70,7 @@
       "weight_acc_lim_x": 1,
       "weight_acc_lim_y": 1,
       "weight_acc_lim_theta": 1,
-      "weight_kinematics_nh": 1000,
+      "weight_kinematics_nh": 1,
       "weight_kinematics_forward_drive": 1,
       "weight_kinematics_turning_radius": 1,
       "weight_optimaltime": 1,
-- 
GitLab


From 05569ad63d0ca019a46b1ed945b94177ecb1003f Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 17:20:18 +0200
Subject: [PATCH 151/324] Fix offset paramter

Only apply rotation to offset, not translation.
---
 source/armarx/navigation/human/ProxemicZoneCreator.cpp | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.cpp b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
index e6495840..3e946a31 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.cpp
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
@@ -15,8 +15,8 @@ namespace armarx::navigation::human
                               .weight = params.intimateWeight};
 
         // personal zone
-        auto& global_T_human = human.pose;
-        auto& global_V_offset = global_T_human * params.offset;
+        auto& global_R_human = human.pose.linear();
+        auto& global_V_offset = global_R_human * params.offset;
 
         core::Pose2D pose = human.pose;
         pose.translation() += global_V_offset;
-- 
GitLab


From a59775fe2903e2f114d4f1eaf4a4f69ff9652195 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 17:22:26 +0200
Subject: [PATCH 152/324] Use velocity in m/s for stretching

---
 source/armarx/navigation/human/ProxemicZoneCreator.cpp | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.cpp b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
index 3e946a31..8a6aac53 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.cpp
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
@@ -22,7 +22,8 @@ namespace armarx::navigation::human
         pose.translation() += global_V_offset;
 
         float velocityNorm = human.linearVelocity.norm();
-        float movementStretch = 1 + velocityNorm * params.movementInfluence;
+        // stretch with velocity in m/s as factor
+        float movementStretch = 1 + velocityNorm * params.movementInfluence / 1000; // [mm] to [m]
         if (velocityNorm != 0)
         {
             // y pointing forward
-- 
GitLab


From 1fd9cb56180d6231deb60b0c32c1862ac6149189 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 17:39:53 +0200
Subject: [PATCH 153/324] Fix proxemic zone visualization, draw them in
 different colors

Use the proper pose to draw the proxemic zone ellipse.
Use different colors for the intimate and personal zones.
---
 .../armarx/navigation/local_planning/TebObstacleManager.cpp | 6 ++++--
 .../armarx/navigation/local_planning/TebObstacleManager.h   | 3 +++
 2 files changed, 7 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index c7288854..d532e6d9 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -58,6 +58,7 @@ namespace armarx::navigation::local_planning
     {
         auto proxemicZones = proxemics.createProxemicZones(human);
 
+        int i = 0;
         for (const auto& proxemicZone : proxemicZones)
         {
             auto pose = conv::toRos(proxemicZone.pose);
@@ -85,13 +86,14 @@ namespace armarx::navigation::local_planning
             if (visLayer != nullptr)
             {
                 const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
-                const core::Pose pose3d = conv::to3D(human.pose);
+                const core::Pose pose3d = conv::to3D(proxemicZone.pose);
 
                 visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(visualizationIndex++))
                                   .pose(pose3d)
                                   .axisLengths(axisLength)
-                                  .color(simox::Color::blue()));
+                                  .color(PROXEMIC_ZONE_COLOR[i % PROXEMIC_ZONE_COLOR.size()]));
             }
+            i++;
         }
     }
 
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.h b/source/armarx/navigation/local_planning/TebObstacleManager.h
index b336b65b..b8859c4b 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.h
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.h
@@ -50,6 +50,9 @@ namespace armarx::navigation::local_planning
         teb_local_planner::ObstContainer& container;
         human::ProxemicZoneCreator proxemics;
         int visualizationIndex;
+
+        const std::array<simox::Color, 2> PROXEMIC_ZONE_COLOR = {simox::Color::red(),
+                                                                 simox::Color::blue()};
     };
 
 
-- 
GitLab


From 0e2a263a86f90004dd99fa6183c24767af000e07 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 18:20:57 +0200
Subject: [PATCH 154/324] Normalize angle in ros conversions

---
 source/armarx/navigation/local_planning/ros_conversions.cpp | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 4bb21ef4..86fd6a2c 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -49,6 +49,8 @@ namespace armarx::navigation::conv
         // we change it such that x is pointing forward.
         // ROS: x pointing forward, ArmarX: y pointing forward
         theta += M_PI_2;
+        // normalize angle
+        theta = g2o::normalize_theta(theta);
 
         return {pos / 1000., theta}; // [mm] to [m]
     }
-- 
GitLab


From 9286eebd79692745637d249723cc162356ae02c6 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 18:21:25 +0200
Subject: [PATCH 155/324] Add some comments

---
 source/armarx/navigation/human/ProxemicZoneCreator.h          | 4 +++-
 .../armarx/navigation/local_planning/TebObstacleManager.cpp   | 2 ++
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 2 +-
 3 files changed, 6 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.h b/source/armarx/navigation/human/ProxemicZoneCreator.h
index d1696db4..fed4c18c 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.h
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.h
@@ -38,7 +38,9 @@ namespace armarx::navigation::human
             float personalRadius = 1000;
 
             float movementInfluence = 1;
-            // in the coordinate system of the human
+            // an offset applied to the personal zone in the coordinate system of the human
+            // a positive x-value means an offset to the right
+            // a positive y-value means an offset to the front
             Eigen::Vector2f offset{100, 150};
         };
 
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index d532e6d9..35d3afb4 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -39,6 +39,7 @@ namespace armarx::navigation::local_planning
         obst->finalizePolygon();
         container.push_back(obst);
 
+        // visualize bounding box if layer is available
         if (visLayer != nullptr)
         {
             const Eigen::Vector3f min3d = conv::fromRos(min);
@@ -83,6 +84,7 @@ namespace armarx::navigation::local_planning
 
             container.push_back(obst);
 
+            // visualize proxemic zone if layer is available
             if (visLayer != nullptr)
             {
                 const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index daedf66c..91483e74 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -112,7 +112,7 @@ namespace armarx::navigation::local_planning
 
         geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity);
 
-        //TODO (SALt): fill obstacles
+
         fillObstacles();
 
         try
-- 
GitLab


From 8fe4e2c01016cc24d907b83ba7b3ccf14706b51e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 25 Aug 2022 18:37:27 +0200
Subject: [PATCH 156/324] Add new weight parameter to config.

---
 .../local_planner_config/TimedElasticBands/default.json       | 1 +
 .../navigation/local_planning/aron/TimedElasticBands.xml      | 4 ++++
 source/armarx/navigation/local_planning/aron_conversions.cpp  | 1 +
 3 files changed, 6 insertions(+)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 53f1c25e..34d3506a 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -6,6 +6,7 @@
     "pse": {
       "pse_costum_obstacle_penalties": true,
       "pse_costum_obstacle_penalties_dynamic": true,
+      "weight_costmap": 0.5,
       "weight_global_path_position": 0.3,
       "weight_global_path_orientation": 0.3,
       "lrk_use_alternative_approach": false,
diff --git a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
index 352c9213..9d0873c3 100644
--- a/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
+++ b/source/armarx/navigation/local_planning/aron/TimedElasticBands.xml
@@ -14,6 +14,10 @@
                 <bool />
             </ObjectChild>
 
+            <ObjectChild key='weight_costmap'>
+                <float />
+            </ObjectChild>
+
             <ObjectChild key='weight_global_path_position'>
                 <float />
             </ObjectChild>
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 0601914b..928c543e 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -29,6 +29,7 @@ namespace armarx::navigation::local_planning
         bo.pse.pse_costum_obstacle_penalties = dto.teb_config.pse.pse_costum_obstacle_penalties;
         bo.pse.pse_costum_obstacle_penalties_dynamic =
             dto.teb_config.pse.pse_costum_obstacle_penalties_dynamic;
+        bo.pse.weight_costmap = dto.teb_config.pse.weight_costmap;
         bo.pse.weight_global_path_position = dto.teb_config.pse.weight_global_path_position;
         bo.pse.weight_global_path_orientation = dto.teb_config.pse.weight_global_path_orientation;
         bo.pse.lrk_use_alternative_approach = dto.teb_config.pse.lrk_use_alternative_approach;
-- 
GitLab


From 9aad8ce26074bc8e2c27819d974088c5bf2565ba Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Fri, 26 Aug 2022 15:38:39 +0200
Subject: [PATCH 157/324] Add dependency from dynamic scene provider to
 RobotAPI to use ukfm

---
 .../navigation/components/dynamic_scene_provider/CMakeLists.txt | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index e061ea23..70f871f1 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -20,7 +20,7 @@ armarx_add_component(dynamic_scene_provider
         ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
         # ArmarXGui
         ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
-        # RobotAPI
+        RobotAPI
         armem
         armem_robot
         armem_robot_state
-- 
GitLab


From 686e36019cb434f529002cb34c67ef239a6dd371 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Fri, 26 Aug 2022 18:05:11 +0200
Subject: [PATCH 158/324] Correct dependency from RobotAPI to ukfm

---
 .../components/dynamic_scene_provider/CMakeLists.txt           | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 70f871f1..f3cedc48 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -20,7 +20,8 @@ armarx_add_component(dynamic_scene_provider
         ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
         # ArmarXGui
         ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
-        RobotAPI
+        # RobotAPI
+        ukfm
         armem
         armem_robot
         armem_robot_state
-- 
GitLab


From ef08c59792fb860f9b4e535ddd5ef85695750d42 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Fri, 26 Aug 2022 18:05:48 +0200
Subject: [PATCH 159/324] Initialize new ukfm for every tracked human

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 39 ++++++++++++++++++-
 .../dynamic_scene_provider/HumanTracker.h     |  6 +++
 2 files changed, 43 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 2196ad99..b405d696 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -11,6 +11,12 @@
 namespace armarx::navigation::components::dynamic_scene_provider
 {
 
+    //TODO which values are here good?
+    constexpr T acc_noise_std = 0.01;
+    constexpr T om_noise_std = 0.01;
+    constexpr T obs_noise_std = 0.01;
+    constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
+    const Vector initial_offset_pos = 0.5 * Vector(1, 0.7);
 
     HumanTracker::DetectedHuman
     convertHumanPoseToPosition(const DateTime& time, const armem::human::HumanPose& humanPose)
@@ -71,12 +77,41 @@ namespace armarx::navigation::components::dynamic_scene_provider
         {
             if (!detectedHuman.associated)
             {
+                //initialize new human for detected human
                 human::Human human{.pose = detectedHuman.pose,
                                    .linearVelocity = Eigen::Vector2f::Zero(),
                                    .detectionTime = detectedHuman.detectionTime};
 
-                trackedHumans.push_back(
-                    {.human = human, .trackingId = detectedHuman.trackingId, .associated = true});
+
+                //initialize new kalman filter for new detected human
+                UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+                    UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+                Q.block<2, 2>(0, 0) *= acc_noise_std * acc_noise_std;
+                Q.block<1, 1>(2, 2) *= om_noise_std * om_noise_std;
+
+                UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+                    UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std *
+                    obs_noise_std;
+
+                UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+                    UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+                P0.block<1, 1>(2, 2) *= initial_offset_angle * initial_offset_angle;
+                P0.block<2, 2>(0, 0) *= initial_offset_pos.norm() * initial_offset_pos.norm();
+
+                UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
+                    UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
+
+                SystemModelT::StateT state0;
+                state0.position = initial_offset_pos;
+                state0.orientation = manif::SO2<T>{initial_offset_angle};
+
+                UnscentedKalmanFilter<SystemModelT> ukf{Q, R, alpha, state0, P0};
+
+                //add new tracked human to list of tracked humans
+                trackedHumans.push_back(TrackedHuman{.human = human,
+                                                     .ukf = ukf,
+                                                     .trackingId = detectedHuman.trackingId,
+                                                     .associated = true});
             }
         }
     }
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 9146a798..cb14edaa 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -3,6 +3,8 @@
 
 #include <ArmarXCore/core/time.h>
 
+#include "RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h"
+
 #include "VisionX/libraries/armem_human/types.h"
 
 #include "armarx/navigation/core/basic_types.h"
@@ -10,6 +12,9 @@
 
 namespace armarx::navigation::components::dynamic_scene_provider
 {
+    using T = double; //TODO double or float?
+    using Vector = Eigen::Matrix<T, 2, 1>;
+    using SystemModelT = SystemModelSO2xR2<T>;
 
     class HumanTracker
     {
@@ -33,6 +38,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         struct TrackedHuman
         {
             human::Human human;
+            UnscentedKalmanFilter<SystemModelT> ukf;
             std::optional<std::string> trackingId = std::nullopt;
             bool associated;
         };
-- 
GitLab


From 08d7c37779314796ee94ad4a588309bd64b83fef Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 18:06:47 +0200
Subject: [PATCH 160/324] Move system models into dynamic scene provider

---
 .../dynamic_scene_provider/CMakeLists.txt     |  3 +
 .../HumanSystemModel.cpp                      | 60 ++++++++++++++
 .../dynamic_scene_provider/HumanSystemModel.h | 78 +++++++++++++++++++
 3 files changed, 141 insertions(+)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index e061ea23..308c3b01 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -10,10 +10,12 @@ armarx_add_component(dynamic_scene_provider
         Component.cpp
         ArVizDrawer.cpp
         HumanTracker.cpp
+        HumanSystemModel.cpp
     HEADERS
         Component.h
         ArVizDrawer.h
         HumanTracker.h
+        HumanSystemModel.h
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
@@ -21,6 +23,7 @@ armarx_add_component(dynamic_scene_provider
         # ArmarXGui
         ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
         # RobotAPI
+        ukfm
         armem
         armem_robot
         armem_robot_state
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp
new file mode 100644
index 00000000..684026bd
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp
@@ -0,0 +1,60 @@
+#include "HumanSystemModel.h"
+
+namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+{
+
+    // ------------------------------ SO2xR2 -----------------------------------------
+
+    template <typename floatT>
+    typename SystemModelSO2xR2<floatT>::ObsT
+    SystemModelSO2xR2<floatT>::observationFunction(const SystemModelSO2xR2::StateT& state)
+    {
+        ObsT observation;
+        observation.segment(0, 2) = state.position;
+        observation.segment(2, 1) = state.orientation.log().coeffs();
+        return observation;
+    }
+
+    template <typename floatT>
+    typename SystemModelSO2xR2<floatT>::StateT
+    SystemModelSO2xR2<floatT>::propagationFunction(const SystemModelSO2xR2::StateT& state,
+                                                   const SystemModelSO2xR2::ControlT& control,
+                                                   const SystemModelSO2xR2::ControlNoiseT& noise,
+                                                   FloatT dt)
+    {
+        StateT new_state;
+        new_state.orientation = state.orientation.template rplus(control.angular_velocity * dt);
+        new_state.position = state.position + control.euclidean_velocity * dt;
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSO2xR2<floatT>::StateT
+    SystemModelSO2xR2<floatT>::retraction(const SystemModelSO2xR2::StateT& state,
+                                          const SystemModelSO2xR2::SigmaPointsT& sigmaPoints)
+    {
+        StateT new_state;
+        manif::SO2Tangent<FloatT> tan;
+        tan.coeffs() << sigmaPoints.segment(2, 1);
+        new_state.orientation = state.orientation.lplus(tan);
+
+        new_state.position = state.position + sigmaPoints.segment(0, 2);
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSO2xR2<floatT>::SigmaPointsT
+    SystemModelSO2xR2<floatT>::inverseRetraction(const SystemModelSO2xR2::StateT& state1,
+                                                 const SystemModelSO2xR2::StateT& state2)
+    {
+        SigmaPointsT sigma;
+        // TODO: check if right order of substraction
+        sigma.segment(0, 2) = state1.position - state2.position;
+        sigma.segment(2, 1) = state2.orientation.lminus(state1.orientation).coeffs();
+        return sigma;
+    }
+
+    template struct SystemModelSO2xR2<float>;
+    template struct SystemModelSO2xR2<double>;
+
+} // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h
new file mode 100644
index 00000000..05ae031d
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h
@@ -0,0 +1,78 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @author     Corvin Navarro Ecker ( corvin dot ecker at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+#pragma once
+
+#include <RobotAPI/libraries/ukfm/SystemModel.h>
+
+#include <manif/SO2.h>
+
+namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+{
+    //----------- SO2xR2 -----------------
+
+    template <typename floatT>
+    struct StateSO2xR2
+    {
+        manif::SO2<floatT> orientation;
+        Eigen::Matrix<floatT, 2, 1> position;
+    };
+
+    template <typename floatT>
+    struct ControlSO2xR2
+    {
+        typename manif::SO2<floatT>::Tangent angular_velocity;
+        Eigen::Matrix<floatT, 2, 1> euclidean_velocity;
+    };
+
+    template <typename floatT>
+    struct SystemModelSO2xR2
+    {
+        static_assert(std::is_floating_point_v<floatT>);
+        struct dim
+        {
+            static constexpr long state = 3, control = 3, obs = 3;
+        };
+
+        using FloatT = floatT;
+        using StateT = StateSO2xR2<FloatT>;
+        using ControlT = ControlSO2xR2<FloatT>;
+        using ObsT = Eigen::Matrix<FloatT, dim::obs, 1>;
+        using ControlNoiseT = Eigen::
+            Matrix<FloatT, dim::control, 1>; // todo: correct name? Is it the same as ControlT?
+        using SigmaPointsT = Eigen::Matrix<FloatT, dim::state, 1>; // todo: rename
+
+        static ObsT observationFunction(const StateT& state);
+
+        static StateT propagationFunction(const StateT& state,
+                                          const ControlT& control,
+                                          const ControlNoiseT& noise,
+                                          FloatT dt);
+
+        static StateT retraction(const StateT& state, const SigmaPointsT& sigmaPoints);
+
+        static SigmaPointsT inverseRetraction(const StateT& state1, const StateT& state2);
+    };
+
+    extern template struct SystemModelSO2xR2<float>;
+    extern template struct SystemModelSO2xR2<double>;
+
+} // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
-- 
GitLab


From dce40c6bc3ec2222cc2c661fa1f5baccafec849d Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 18:07:21 +0200
Subject: [PATCH 161/324] Setup test for kalman filter

---
 .../dynamic_scene_provider/CMakeLists.txt     |  8 +++++
 .../test/kalmanFilterTest.cpp                 | 30 +++++++++++++++++++
 2 files changed, 38 insertions(+)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 308c3b01..b1f2efeb 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -46,3 +46,11 @@ armarx_add_component(dynamic_scene_provider
     # If you need a separate shared component library you can enable it with the following flag.
     # SHARED_COMPONENT_LIBRARY
 )
+
+armarx_add_test(kalman_test
+    TEST_FILES
+        test/kalmanFilterTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+)
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
new file mode 100644
index 00000000..8ec2e970
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
@@ -0,0 +1,30 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::dynamic_scene_provicer
+#define ARMARX_BOOST_TEST
+
+#include <armarx/navigation/Test.h>
+
+BOOST_AUTO_TEST_CASE(kalmanFilterTest)
+{
+    BOOST_CHECK_EQUAL(true, true);
+}
-- 
GitLab


From 7258d32982da069bf3756cc4452080363d7abe0b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 18:08:16 +0200
Subject: [PATCH 162/324] Add comment

---
 .../dynamic_scene_provider/HumanTracker.cpp   |  1 -
 .../dynamic_scene_provider/HumanTracker.h     | 23 ++++++++++++++++++-
 2 files changed, 22 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 2196ad99..197d76e0 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -1,4 +1,3 @@
-
 #include "HumanTracker.h"
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 9146a798..a6991aa2 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -1,5 +1,26 @@
-#pragma once
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @author     Corvin Navarro Ecker ( corvin dot ecker at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
 
+#pragma once
 
 #include <ArmarXCore/core/time.h>
 
-- 
GitLab


From 0fbc1a2dcc521f32372a2f307a578064fc805827 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 18:53:23 +0200
Subject: [PATCH 163/324] Fix SystemModels include includess

---
 .../components/dynamic_scene_provider/CMakeLists.txt     | 1 +
 .../components/dynamic_scene_provider/HumanTracker.h     | 3 ++-
 .../UnscentedKalmanFilter_impl.cpp                       | 9 +++++++++
 3 files changed, 12 insertions(+), 1 deletion(-)
 create mode 100644 source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index b1f2efeb..6897cc65 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -11,6 +11,7 @@ armarx_add_component(dynamic_scene_provider
         ArVizDrawer.cpp
         HumanTracker.cpp
         HumanSystemModel.cpp
+        UnscentedKalmanFilter_impl.cpp
     HEADERS
         Component.h
         ArVizDrawer.h
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index cb14edaa..30cb4dfe 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -9,12 +9,13 @@
 
 #include "armarx/navigation/core/basic_types.h"
 #include "armarx/navigation/human/types.h"
+#include <armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h>
 
 namespace armarx::navigation::components::dynamic_scene_provider
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
-    using SystemModelT = SystemModelSO2xR2<T>;
+    using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
 
     class HumanTracker
     {
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp
new file mode 100644
index 00000000..6242d973
--- /dev/null
+++ b/source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp
@@ -0,0 +1,9 @@
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.cpp>
+
+#include <armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h>
+
+
+template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
+                                         kalman_filter::SystemModelSO2xR2<float>>;
+template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
+                                         kalman_filter::SystemModelSO2xR2<double>>;
-- 
GitLab


From cb29d4b21c0e4470e35bc8b202de14985dd0cf59 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 18:55:12 +0200
Subject: [PATCH 164/324] Use angled-bracket includes

---
 .../components/dynamic_scene_provider/HumanTracker.h      | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 30cb4dfe..77a10ab3 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -3,13 +3,13 @@
 
 #include <ArmarXCore/core/time.h>
 
-#include "RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h"
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
 
-#include "VisionX/libraries/armem_human/types.h"
+#include <VisionX/libraries/armem_human/types.h>
 
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/human/types.h"
 #include <armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/types.h>
 
 namespace armarx::navigation::components::dynamic_scene_provider
 {
-- 
GitLab


From 90b010919b5e67d3fa4a5109f8c1d62a5a3751aa Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 21:15:33 +0200
Subject: [PATCH 165/324] Move HumanSystemModel to human library

---
 .../components/dynamic_scene_provider/CMakeLists.txt         | 5 +----
 source/armarx/navigation/human/CMakeLists.txt                | 4 ++++
 .../dynamic_scene_provider => human}/HumanSystemModel.cpp    | 4 ++--
 .../dynamic_scene_provider => human}/HumanSystemModel.h      | 2 --
 .../UnscentedKalmanFilter_impl.cpp                           | 0
 5 files changed, 7 insertions(+), 8 deletions(-)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/HumanSystemModel.cpp (95%)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/HumanSystemModel.h (98%)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/UnscentedKalmanFilter_impl.cpp (100%)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 6897cc65..ed763369 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -10,13 +10,10 @@ armarx_add_component(dynamic_scene_provider
         Component.cpp
         ArVizDrawer.cpp
         HumanTracker.cpp
-        HumanSystemModel.cpp
-        UnscentedKalmanFilter_impl.cpp
     HEADERS
         Component.h
         ArVizDrawer.h
         HumanTracker.h
-        HumanSystemModel.h
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
@@ -24,7 +21,6 @@ armarx_add_component(dynamic_scene_provider
         # ArmarXGui
         ## ArmarXGuiComponentPlugins  # For RemoteGui plugin.
         # RobotAPI
-        ukfm
         armem
         armem_robot
         armem_robot_state
@@ -54,4 +50,5 @@ armarx_add_test(kalman_test
     DEPENDENCIES
         PUBLIC
             ArmarXCore
+            armarx_navigation::teb_human
 )
diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index c0a1b74e..9e357d43 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -11,15 +11,19 @@ armarx_add_library(teb_human
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
+        ukfm
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
     SOURCES
         types.cpp
         aron_conversions.cpp
         ProxemicZoneCreator.cpp
+        HumanSystemModel.cpp
+        UnscentedKalmanFilter_impl.cpp
     HEADERS
         types.h
         aron_conversions.h
         shapes.h
         ProxemicZoneCreator.h
+        HumanSystemModel.h
 )
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
similarity index 95%
rename from source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp
rename to source/armarx/navigation/human/HumanSystemModel.cpp
index 684026bd..4d5e86c9 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -10,8 +10,8 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     SystemModelSO2xR2<floatT>::observationFunction(const SystemModelSO2xR2::StateT& state)
     {
         ObsT observation;
-        observation.segment(0, 2) = state.position;
-        observation.segment(2, 1) = state.orientation.log().coeffs();
+        observation.segment(0, 1) = state.orientation.log().coeffs();
+        observation.segment(1, 2) = state.position;
         return observation;
     }
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h b/source/armarx/navigation/human/HumanSystemModel.h
similarity index 98%
rename from source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h
rename to source/armarx/navigation/human/HumanSystemModel.h
index 05ae031d..fc0b8658 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h
+++ b/source/armarx/navigation/human/HumanSystemModel.h
@@ -21,8 +21,6 @@
  */
 #pragma once
 
-#include <RobotAPI/libraries/ukfm/SystemModel.h>
-
 #include <manif/SO2.h>
 
 namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
similarity index 100%
rename from source/armarx/navigation/components/dynamic_scene_provider/UnscentedKalmanFilter_impl.cpp
rename to source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
-- 
GitLab


From 1458fbfdd8dd6d0117d3fc33235c0d51108900dd Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 21:16:27 +0200
Subject: [PATCH 166/324] Implement basic kalman filter test

---
 .../test/kalmanFilterTest.cpp                 | 221 +++++++++++++++++-
 1 file changed, 218 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
index 8ec2e970..38909a91 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
@@ -22,9 +22,224 @@
 #define BOOST_TEST_MODULE Navigation::ArmarXLibraries::dynamic_scene_provicer
 #define ARMARX_BOOST_TEST
 
+#include <cstdlib> /* srand, rand */
+#include <ctime> /* time */
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/util/time.h>
+
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
+
 #include <armarx/navigation/Test.h>
+#include <armarx/navigation/components/dynamic_scene_provider/sciplot/sciplot.hpp>
+#include <armarx/navigation/human/HumanSystemModel.h>
+#include <manif/SO2.h>
+
 
-BOOST_AUTO_TEST_CASE(kalmanFilterTest)
+namespace armarx::navigation::components::dynamic_scene_provider
 {
-    BOOST_CHECK_EQUAL(true, true);
-}
+    using T = double; //TODO double or float?
+    using Vector = Eigen::Matrix<T, 2, 1>;
+    using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
+
+    constexpr long num_timesteps = 3000;
+    constexpr T max_time = 1;
+    constexpr T dt = max_time / num_timesteps;
+    constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
+
+    constexpr T rot_noise_std = 0.01;
+    constexpr T pos_noise_std = 0.01;
+    constexpr T obs_noise_std = 0.01;
+    constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
+    const Vector initial_offet_pos = 0.5 * Vector(1, 0.5);
+
+
+    void
+    simulate_trajectory(std::vector<SystemModelT::StateT>& states,
+                        std::vector<SystemModelT::ControlT>& omegas)
+    {
+        SystemModelT::StateT state;
+        state.position = Vector{1, 0};
+        state.orientation = manif::SO2<T>(0);
+        states.push_back(state);
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            const T t = dt * i;
+            const T angle = t * c;
+
+
+            const Vector last_pos = states.at(i - 1).position;
+            const Vector pos(std::cos(angle), std::sin(angle));
+
+            BOOST_TEST(((last_pos - pos).norm() < 0.1),
+                       "position differs too much from last step: " << (last_pos - pos).norm());
+
+            SystemModelT::ControlT control;
+            control.angular_velocity.coeffs() << angle / dt;
+            control.euclidean_velocity << (pos - last_pos) / dt;
+
+            const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
+                state, control, SystemModelT::ControlNoiseT::Zero(), dt);
+
+            T pos_diff1 = (propagated.position - pos).norm();
+            BOOST_TEST(pos_diff1 < 2e-5,
+                       "propagated position differs too much from real position: " << pos_diff1);
+
+            state.position = pos;
+            state.orientation = manif::SO2<T>(angle);
+            states.push_back(propagated);
+
+
+            // add noise
+            control.angular_velocity.coeffs() += rot_noise_std * Eigen::Matrix<T, 1, 1>::Random();
+            control.euclidean_velocity += pos_noise_std * Vector::Random();
+            omegas.push_back(control);
+        }
+    }
+
+    void
+    simulate_observation(const std::vector<SystemModelT::StateT>& states,
+                         std::vector<SystemModelT::ObsT>& observations)
+    {
+        for (const auto& state : states)
+        {
+            SystemModelT::ObsT obs = SystemModelT::observationFunction(state);
+            SystemModelT::ObsT true_obs;
+            true_obs.segment(0, 1) = state.orientation.log().coeffs();
+            true_obs.segment(1, 2) = state.position;
+
+            BOOST_TEST(
+                (obs - true_obs).norm() < std::numeric_limits<T>::epsilon(),
+                "observation differs too much from real observation: " << (obs - true_obs).norm());
+            observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
+        }
+    }
+
+
+    BOOST_AUTO_TEST_CASE(kalmanFilterTest)
+    {
+        srand(time(NULL));
+
+        std::vector<SystemModelT::StateT> states;
+        std::vector<SystemModelT::ControlT> omegas;
+        std::vector<SystemModelT::ObsT> observations;
+        simulate_trajectory(states, omegas);
+        simulate_observation(states, observations);
+
+        ARMARX_INFO << "Num States: " << states.size() << " Num Controls: " << omegas.size()
+                    << " Num Obs: " << observations.size();
+
+        UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+            UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+        Q.block<1, 1>(0, 0) *= rot_noise_std * rot_noise_std;
+        Q.block<2, 2>(1, 1) *= pos_noise_std * pos_noise_std;
+
+        UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std *
+            obs_noise_std;
+        UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+            UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+        P0.block<1, 1>(0, 0) *= initial_offset_angle * initial_offset_angle;
+        P0.block<2, 2>(1, 1) *= initial_offet_pos.norm() * initial_offet_pos.norm();
+
+        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
+            UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
+
+        SystemModelT::StateT state0;
+        state0.orientation = manif::SO2<T>(initial_offset_angle);
+        state0.position = states.at(0).position + initial_offet_pos;
+
+        UnscentedKalmanFilter<SystemModelT> ukf(Q, R, alpha, state0, P0);
+
+        std::vector<SystemModelT::StateT> ukf_states;
+        std::vector<UnscentedKalmanFilter<SystemModelT>::StateCovT> ukf_Ps;
+        ukf_states.push_back(state0);
+        ukf_Ps.push_back(P0);
+
+        std::vector<T> x_true, y_true, x_obs, y_obs, x_ukf, y_ukf;
+        std::vector<T> vx_true, vy_true, vx_ukf, vy_ukf;
+        std::vector<T> a_true, a_obs, a_ukf;
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            // propagate
+            TIMING_START(LOOP);
+            TIMING_START(PROPAGATION);
+            ukf.propagation(omegas.at(i - 1), dt);
+            TIMING_END(PROPAGATION);
+            if ((i - 1) % 100 == 0)
+            {
+                TIMING_START(UPDATE);
+                ukf.update(observations.at(i));
+                TIMING_END(UPDATE);
+                TIMING_START(REST);
+                const SystemModelT::StateT& current_state = ukf.getCurrentState();
+
+                BOOST_TEST_MESSAGE(
+                    "Position Diff: " << (states.at(i).position - current_state.position).norm());
+                BOOST_TEST_MESSAGE(
+                    "Orientation Diff: "
+                    << (states.at(i).orientation - current_state.orientation).coeffs().norm());
+
+                BOOST_TEST_MESSAGE("Max Cov "
+                                   << ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+                BOOST_TEST_MESSAGE("Diag: " << (ukf.getCurrentStateCovariance() -
+                                                Eigen::Matrix<T, 3, 3>::Identity())
+                                                   .norm());
+
+                x_true.push_back(states.at(i).position.x());
+                y_true.push_back(states.at(i).position.y());
+
+                x_obs.push_back(observations.at(i)(0));
+                y_obs.push_back(observations.at(i)(1));
+
+                x_ukf.push_back(ukf.getCurrentState().position.x());
+                y_ukf.push_back(ukf.getCurrentState().position.y());
+
+                a_true.push_back(states.at(i).orientation.log().coeffs()(0));
+                a_obs.push_back(observations.at(i)(0, 0));
+                a_ukf.push_back(ukf.getCurrentState().orientation.log().coeffs()(0));
+
+                TIMING_END(REST);
+            }
+
+            ukf_states.push_back(ukf.getCurrentState());
+            ukf_Ps.push_back(ukf.getCurrentStateCovariance());
+
+            TIMING_END(LOOP);
+        }
+
+        /*
+        sciplot::Plot3D position_plot;
+        sciplot::Plot pos_plot;
+
+        position_plot.drawCurve(x_true, y_true, z_true).label("True").lineWidth(1);
+        position_plot.drawCurve(x_obs, y_obs, z_obs).label("Obs").lineWidth(1);
+        position_plot.drawCurve(x_ukf, y_ukf, z_ukf).label("UKF").lineWidth(1);
+
+        pos_plot.drawCurve(x_true, y_true).label("True");
+        pos_plot.drawCurve(x_obs, y_obs).label("Obs");
+        pos_plot.drawCurve(x_ukf, y_ukf).label("UKF");
+
+        //    sciplot::Plot3D vel_plot;
+        //
+        //    vel_plot.drawCurve(vx_true, vy_true, vz_true).label("True").lineWidth(1);
+        //    vel_plot.drawCurve(vx_ukf, vy_ukf, vz_ukf).label("UKF").lineWidth(1);
+
+
+        sciplot::Plot3D orientation_plot;
+
+        orientation_plot.drawCurve(a_true, b_true, c_true).label("True").lineWidth(1);
+        orientation_plot.drawCurve(a_obs, b_obs, c_obs).label("Obs").lineWidth(1);
+        orientation_plot.drawCurve(a_ukf, b_ukf, c_ukf).label("UKF").lineWidth(1);
+
+        pos_plot.show();
+        position_plot.show();
+        //    vel_plot.show();
+        orientation_plot.show();
+       */
+    }
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 27901af5e61f492e9bdc3158b6b00ff7f882fd3b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 21:19:43 +0200
Subject: [PATCH 167/324] Fix includes

---
 .../navigation/components/dynamic_scene_provider/HumanTracker.h | 2 +-
 source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp   | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
index 77a10ab3..adb3bad7 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
@@ -7,8 +7,8 @@
 
 #include <VisionX/libraries/armem_human/types.h>
 
-#include <armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h>
 #include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/HumanSystemModel.h>
 #include <armarx/navigation/human/types.h>
 
 namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
index 6242d973..672e487f 100644
--- a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
+++ b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
@@ -1,6 +1,6 @@
 #include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.cpp>
 
-#include <armarx/navigation/components/dynamic_scene_provider/HumanSystemModel.h>
+#include <armarx/navigation/human/HumanSystemModel.h>
 
 
 template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
-- 
GitLab


From 05e740b7011945f3089fda17442ce3b766c042a7 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Fri, 26 Aug 2022 21:47:22 +0200
Subject: [PATCH 168/324] Cleanup initialization of ukf

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 32 ++++++++++++-------
 1 file changed, 20 insertions(+), 12 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index b405d696..3529987b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -11,12 +11,12 @@
 namespace armarx::navigation::components::dynamic_scene_provider
 {
 
-    //TODO which values are here good?
-    constexpr T acc_noise_std = 0.01;
-    constexpr T om_noise_std = 0.01;
+    //TODO which values are appropriate?
+    constexpr T pos_noise_std = 0.01;
+    constexpr T rot_noise_std = 0.01;
     constexpr T obs_noise_std = 0.01;
-    constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
-    const Vector initial_offset_pos = 0.5 * Vector(1, 0.7);
+    constexpr T initial_pos_state_cov = 0.01;
+    constexpr T initial_rot_state_cov = 0.01;
 
     HumanTracker::DetectedHuman
     convertHumanPoseToPosition(const DateTime& time, const armem::human::HumanPose& humanPose)
@@ -82,28 +82,34 @@ namespace armarx::navigation::components::dynamic_scene_provider
                                    .linearVelocity = Eigen::Vector2f::Zero(),
                                    .detectionTime = detectedHuman.detectionTime};
 
-
                 //initialize new kalman filter for new detected human
+
                 UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
                     UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
-                Q.block<2, 2>(0, 0) *= acc_noise_std * acc_noise_std;
-                Q.block<1, 1>(2, 2) *= om_noise_std * om_noise_std;
+                //rotation noise at (0,0)
+                Q.block<1, 1>(0, 0) *= rot_noise_std * rot_noise_std;
+                //position noise at (1,1) and (2,2)
+                Q.block<2, 2>(1, 1) *= pos_noise_std * pos_noise_std;
 
+                //observation noise at (0,0), (1,1) and (2,2)
                 UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
                     UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std *
                     obs_noise_std;
 
                 UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
                     UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
-                P0.block<1, 1>(2, 2) *= initial_offset_angle * initial_offset_angle;
-                P0.block<2, 2>(0, 0) *= initial_offset_pos.norm() * initial_offset_pos.norm();
+                P0.block<1, 1>(0, 0) *= initial_rot_state_cov * initial_rot_state_cov;
+                P0.block<2, 2>(1, 1) *= initial_pos_state_cov * initial_pos_state_cov;
 
                 UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
                     UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
 
+                //initial position and orientation according to detected human
                 SystemModelT::StateT state0;
-                state0.position = initial_offset_pos;
-                state0.orientation = manif::SO2<T>{initial_offset_angle};
+                //initialize with detected human pose position
+                state0.position = human.pose.translation();
+                //initialize with SO2 matrix according to detected human pose rotation
+                state0.orientation = manif::SO2<T>{Eigen::Rotation2Df(human.pose.linear()).angle()};
 
                 UnscentedKalmanFilter<SystemModelT> ukf{Q, R, alpha, state0, P0};
 
@@ -216,6 +222,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
             parameters.velocityAlpha * linVelocity +
             (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
+        //TODO extract new pose of tracked human from ukf after feeding the detected human
+
         trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
     }
-- 
GitLab


From 55ed9cb8b68f4919bafb9bd8f86c6ea5316debdf Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 21:53:16 +0200
Subject: [PATCH 169/324] Add sciplot to test

To use sciplot it has to be installed locally. For example install it locally
like described in https://sciplot.github.io/installation/ under Installation using CMake.
---
 .../dynamic_scene_provider/CMakeLists.txt     |  3 ++
 .../test/kalmanFilterTest.cpp                 | 43 ++++++++++---------
 2 files changed, 26 insertions(+), 20 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index ed763369..19def441 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -44,6 +44,8 @@ armarx_add_component(dynamic_scene_provider
     # SHARED_COMPONENT_LIBRARY
 )
 
+find_package(sciplot)
+
 armarx_add_test(kalman_test
     TEST_FILES
         test/kalmanFilterTest.cpp
@@ -51,4 +53,5 @@ armarx_add_test(kalman_test
         PUBLIC
             ArmarXCore
             armarx_navigation::teb_human
+            sciplot::sciplot
 )
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
index 38909a91..daad38bb 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
@@ -32,9 +32,9 @@
 #include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
 
 #include <armarx/navigation/Test.h>
-#include <armarx/navigation/components/dynamic_scene_provider/sciplot/sciplot.hpp>
 #include <armarx/navigation/human/HumanSystemModel.h>
 #include <manif/SO2.h>
+#include <sciplot/sciplot.hpp>
 
 
 namespace armarx::navigation::components::dynamic_scene_provider
@@ -211,35 +211,38 @@ namespace armarx::navigation::components::dynamic_scene_provider
             TIMING_END(LOOP);
         }
 
-        /*
-        sciplot::Plot3D position_plot;
-        sciplot::Plot pos_plot;
 
-        position_plot.drawCurve(x_true, y_true, z_true).label("True").lineWidth(1);
-        position_plot.drawCurve(x_obs, y_obs, z_obs).label("Obs").lineWidth(1);
-        position_plot.drawCurve(x_ukf, y_ukf, z_ukf).label("UKF").lineWidth(1);
+        sciplot::Plot2D pos_plot;
+        pos_plot.xlabel("x");
+        pos_plot.ylabel("y");
+        pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
 
         pos_plot.drawCurve(x_true, y_true).label("True");
         pos_plot.drawCurve(x_obs, y_obs).label("Obs");
         pos_plot.drawCurve(x_ukf, y_ukf).label("UKF");
 
-        //    sciplot::Plot3D vel_plot;
-        //
-        //    vel_plot.drawCurve(vx_true, vy_true, vz_true).label("True").lineWidth(1);
-        //    vel_plot.drawCurve(vx_ukf, vy_ukf, vz_ukf).label("UKF").lineWidth(1);
+        sciplot::Plot2D orientation_plot;
+        orientation_plot.xlabel("x");
+        orientation_plot.ylabel("y");
+        orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
 
+        sciplot::Vec x = sciplot::linspace(0.0, 1.0, a_true.size());
+        orientation_plot.drawCurve(x, a_true).label("True").lineWidth(1);
+        orientation_plot.drawCurve(x, a_obs).label("Obs").lineWidth(1);
+        orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
 
-        sciplot::Plot3D orientation_plot;
 
-        orientation_plot.drawCurve(a_true, b_true, c_true).label("True").lineWidth(1);
-        orientation_plot.drawCurve(a_obs, b_obs, c_obs).label("Obs").lineWidth(1);
-        orientation_plot.drawCurve(a_ukf, b_ukf, c_ukf).label("UKF").lineWidth(1);
+        // Create figure to hold plot
+        sciplot::Figure fig = {{pos_plot}, {orientation_plot}};
+        // Create canvas to hold figure
+        sciplot::Canvas canvas = {{fig}};
+        canvas.size(600, 600);
 
-        pos_plot.show();
-        position_plot.show();
-        //    vel_plot.show();
-        orientation_plot.show();
-       */
+        // Show the plot in a pop-up window
+        canvas.show();
+
+        // Save the plot to a PDF file
+        canvas.save("kalman_output.pdf");
     }
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From fee3eacb4c791bf7be27f62d8bbaf247bc13fdd2 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 21:58:28 +0200
Subject: [PATCH 170/324] Fix Eigen cast

---
 .../components/dynamic_scene_provider/HumanTracker.cpp          | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 3529987b..04db3537 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -107,7 +107,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 //initial position and orientation according to detected human
                 SystemModelT::StateT state0;
                 //initialize with detected human pose position
-                state0.position = human.pose.translation();
+                state0.position = human.pose.translation().cast<T>();
                 //initialize with SO2 matrix according to detected human pose rotation
                 state0.orientation = manif::SO2<T>{Eigen::Rotation2Df(human.pose.linear()).angle()};
 
-- 
GitLab


From 3429fd562e61af1497e990fd0bac8eed84b546a2 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Fri, 26 Aug 2022 23:21:52 +0200
Subject: [PATCH 171/324] Add skeleton for HumanTracker::update() step using
 ukf

---
 .../dynamic_scene_provider/HumanTracker.cpp           | 11 ++++++++++-
 1 file changed, 10 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index 04db3537..caf966bd 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -222,7 +222,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
             parameters.velocityAlpha * linVelocity +
             (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
-        //TODO extract new pose of tracked human from ukf after feeding the detected human
+        //TODO initialize with velocity (control variables) from tracked human
+        UnscentedKalmanFilter<SystemModelT>::ControlT omega;
+        trackedHuman->ukf.propagation(omega, dt);
+
+        //TODO initialize with detected human data
+        UnscentedKalmanFilter<SystemModelT>::ObsT observation;
+        trackedHuman->ukf.update(observation);
+
+        //TODO use state as new pose of tracked human
+        UnscentedKalmanFilter<SystemModelT>::StateT state = trackedHuman->ukf.getCurrentState();
 
         trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
-- 
GitLab


From 9b1b2100b8975126ae2713021d206ff83ad96b25 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 23:21:56 +0200
Subject: [PATCH 172/324] Fix kalman test

---
 .../test/kalmanFilterTest.cpp                 | 20 +++++++++----------
 .../navigation/human/HumanSystemModel.cpp     |  8 ++++----
 2 files changed, 14 insertions(+), 14 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
index daad38bb..a2bc7c82 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
@@ -50,9 +50,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     constexpr T rot_noise_std = 0.01;
     constexpr T pos_noise_std = 0.01;
-    constexpr T obs_noise_std = 0.01;
+    constexpr T obs_noise_std = 0.1;
     constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
-    const Vector initial_offet_pos = 0.5 * Vector(1, 0.5);
+    const Vector initial_offet_pos = 0.1 * Vector(1, 0.5);
 
 
     void
@@ -68,16 +68,17 @@ namespace armarx::navigation::components::dynamic_scene_provider
         {
             const T t = dt * i;
             const T angle = t * c;
-
+            const T last_angle = dt * (i - 1) * c;
 
             const Vector last_pos = states.at(i - 1).position;
+            //const Vector pos(angle, std::cos(angle));
             const Vector pos(std::cos(angle), std::sin(angle));
 
             BOOST_TEST(((last_pos - pos).norm() < 0.1),
                        "position differs too much from last step: " << (last_pos - pos).norm());
 
             SystemModelT::ControlT control;
-            control.angular_velocity.coeffs() << angle / dt;
+            control.angular_velocity.coeffs() << (last_angle - angle) / dt;
             control.euclidean_velocity << (pos - last_pos) / dt;
 
             const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
@@ -189,21 +190,20 @@ namespace armarx::navigation::components::dynamic_scene_provider
                                                 Eigen::Matrix<T, 3, 3>::Identity())
                                                    .norm());
 
-                x_true.push_back(states.at(i).position.x());
-                y_true.push_back(states.at(i).position.y());
-
-                x_obs.push_back(observations.at(i)(0));
-                y_obs.push_back(observations.at(i)(1));
+                x_obs.push_back(observations.at(i)(1));
+                y_obs.push_back(observations.at(i)(2));
 
                 x_ukf.push_back(ukf.getCurrentState().position.x());
                 y_ukf.push_back(ukf.getCurrentState().position.y());
 
                 a_true.push_back(states.at(i).orientation.log().coeffs()(0));
-                a_obs.push_back(observations.at(i)(0, 0));
+                a_obs.push_back(observations.at(i)(0));
                 a_ukf.push_back(ukf.getCurrentState().orientation.log().coeffs()(0));
 
                 TIMING_END(REST);
             }
+            x_true.push_back(states.at(i).position.x());
+            y_true.push_back(states.at(i).position.y());
 
             ukf_states.push_back(ukf.getCurrentState());
             ukf_Ps.push_back(ukf.getCurrentStateCovariance());
diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index 4d5e86c9..1bc17e64 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -35,10 +35,10 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     {
         StateT new_state;
         manif::SO2Tangent<FloatT> tan;
-        tan.coeffs() << sigmaPoints.segment(2, 1);
+        tan.coeffs() << sigmaPoints.segment(0, 1);
         new_state.orientation = state.orientation.lplus(tan);
 
-        new_state.position = state.position + sigmaPoints.segment(0, 2);
+        new_state.position = state.position + sigmaPoints.segment(1, 2);
         return new_state;
     }
 
@@ -49,8 +49,8 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     {
         SigmaPointsT sigma;
         // TODO: check if right order of substraction
-        sigma.segment(0, 2) = state1.position - state2.position;
-        sigma.segment(2, 1) = state2.orientation.lminus(state1.orientation).coeffs();
+        sigma.segment(0, 1) = state2.orientation.lminus(state1.orientation).coeffs();
+        sigma.segment(1, 2) = state1.position - state2.position;
         return sigma;
     }
 
-- 
GitLab


From 89cced53fbfb3fffe11070a09ad4b3d9448247fa Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Fri, 26 Aug 2022 23:23:23 +0200
Subject: [PATCH 173/324] Move kalman test to human library

---
 .../components/dynamic_scene_provider/CMakeLists.txt | 12 ------------
 source/armarx/navigation/human/CMakeLists.txt        | 12 ++++++++++++
 .../test/kalmanFilterTest.cpp                        |  2 +-
 3 files changed, 13 insertions(+), 13 deletions(-)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/test/kalmanFilterTest.cpp (99%)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index 19def441..e061ea23 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -43,15 +43,3 @@ armarx_add_component(dynamic_scene_provider
     # If you need a separate shared component library you can enable it with the following flag.
     # SHARED_COMPONENT_LIBRARY
 )
-
-find_package(sciplot)
-
-armarx_add_test(kalman_test
-    TEST_FILES
-        test/kalmanFilterTest.cpp
-    DEPENDENCIES
-        PUBLIC
-            ArmarXCore
-            armarx_navigation::teb_human
-            sciplot::sciplot
-)
diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 9e357d43..311fbcf3 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -27,3 +27,15 @@ armarx_add_library(teb_human
         ProxemicZoneCreator.h
         HumanSystemModel.h
 )
+
+find_package(sciplot)
+
+armarx_add_test(kalman_test
+    TEST_FILES
+        test/kalmanFilterTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::teb_human
+            sciplot::sciplot
+)
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
similarity index 99%
rename from source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
rename to source/armarx/navigation/human/test/kalmanFilterTest.cpp
index a2bc7c82..44971454 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -19,7 +19,7 @@
  *             GNU General Public License
  */
 
-#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::dynamic_scene_provicer
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
 #define ARMARX_BOOST_TEST
 
 #include <cstdlib> /* srand, rand */
-- 
GitLab


From 07cb3cda9e648c5610d6c14ab9460e74e1953554 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Sat, 27 Aug 2022 00:25:37 +0200
Subject: [PATCH 174/324] Implement usage of ukf in update step

---
 .../dynamic_scene_provider/HumanTracker.cpp   | 34 +++++++++++++++----
 1 file changed, 28 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
index caf966bd..d6332100 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
@@ -212,6 +212,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         trackedHuman->associated = true;
         detectedHuman->associated = true;
 
+        //estimate velocity via exponential smoothing
+
         float dt =
             (detectedHuman->detectionTime - trackedHuman->human.detectionTime).toSecondsDouble();
         Eigen::Vector2f ds =
@@ -222,18 +224,38 @@ namespace armarx::navigation::components::dynamic_scene_provider
             parameters.velocityAlpha * linVelocity +
             (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
 
-        //TODO initialize with velocity (control variables) from tracked human
-        UnscentedKalmanFilter<SystemModelT>::ControlT omega;
-        trackedHuman->ukf.propagation(omega, dt);
+        float angle_det = Eigen::Rotation2Df(detectedHuman->pose.linear()).angle();
+        float angle_track = Eigen::Rotation2Df(trackedHuman->human.pose.linear()).angle();
+        //TODO Check angular velocity! Calculation at turning point may be wrong (jump from +pi to -pi)
+        float angular_velocity = (angle_det - angle_track) / dt;
+
+
+        //estimate pose via ukf
 
-        //TODO initialize with detected human data
+        //initialize with estimated velocity (control variables) from tracked human
+        UnscentedKalmanFilter<SystemModelT>::ControlT control;
+        control.angular_velocity.coeffs() << static_cast<T>(angular_velocity);
+        control.euclidean_velocity << velocity.cast<T>();
+
+        //propagate control input for time diff
+        trackedHuman->ukf.propagation(control, dt);
+
+        //initialize observation with detected human data
         UnscentedKalmanFilter<SystemModelT>::ObsT observation;
+        observation.segment(0, 1) =
+            Eigen::Matrix<T, 1, 1>{Eigen::Rotation2Df(detectedHuman->pose.linear()).angle()};
+        observation.segment(1, 2) = detectedHuman->pose.translation().cast<T>();
+
+        //update with new observation
         trackedHuman->ukf.update(observation);
 
-        //TODO use state as new pose of tracked human
+        //use current state as new pose of tracked human
         UnscentedKalmanFilter<SystemModelT>::StateT state = trackedHuman->ukf.getCurrentState();
+        core::Pose2D filteredPose = core::Pose2D::Identity();
+        filteredPose.translation() = state.position.cast<float>();
+        filteredPose.linear() = Eigen::Rotation2Df(state.orientation.angle()).toRotationMatrix();
 
-        trackedHuman->human = {detectedHuman->pose, velocity, detectedHuman->detectionTime};
+        trackedHuman->human = {filteredPose, velocity, detectedHuman->detectionTime};
         trackedHuman->trackingId = detectedHuman->trackingId;
     }
 
-- 
GitLab


From f9dd944820437e59734ccb326046bc65d2b0fb7f Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 27 Aug 2022 00:25:14 +0200
Subject: [PATCH 175/324] Kalman test check angular velocity

---
 source/armarx/navigation/human/test/kalmanFilterTest.cpp | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
index 44971454..7f9b5f6c 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -78,7 +78,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
                        "position differs too much from last step: " << (last_pos - pos).norm());
 
             SystemModelT::ControlT control;
-            control.angular_velocity.coeffs() << (last_angle - angle) / dt;
+            //TODO (SALt): check angular velocity (>pi overflow)
+            control.angular_velocity.coeffs() << c; //(last_angle - angle) / dt;
             control.euclidean_velocity << (pos - last_pos) / dt;
 
             const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
-- 
GitLab


From c06dd826e5b2da5008b80ffb0de484c920a5c623 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 27 Aug 2022 00:25:32 +0200
Subject: [PATCH 176/324] Add UnscentedKalmanfilterTest.cpp from Christoph Pohl

Copied Test from RobotAPI/libraries/ukfm/test to human library
and fixed sciplot usage.
Does not work currently.
---
 source/armarx/navigation/human/CMakeLists.txt |  10 +
 .../human/test/UnscentedKalmanFilterTest.cpp  | 322 ++++++++++++++++++
 2 files changed, 332 insertions(+)
 create mode 100644 source/armarx/navigation/human/test/UnscentedKalmanFilterTest.cpp

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 311fbcf3..f3b7cc38 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -39,3 +39,13 @@ armarx_add_test(kalman_test
             armarx_navigation::teb_human
             sciplot::sciplot
 )
+
+armarx_add_test(se3_kalman_test
+    TEST_FILES
+        test/UnscentedKalmanFilterTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            ukfm
+            sciplot::sciplot
+)
diff --git a/source/armarx/navigation/human/test/UnscentedKalmanFilterTest.cpp b/source/armarx/navigation/human/test/UnscentedKalmanFilterTest.cpp
new file mode 100644
index 00000000..bc1ec384
--- /dev/null
+++ b/source/armarx/navigation/human/test/UnscentedKalmanFilterTest.cpp
@@ -0,0 +1,322 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    ROBDEKON
+ * @author     Christoph Pohl ( christoph dot pohl at kit dot edu )
+ * @date       18.03.21
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ *
+ * Code adapted to C++ from: https://github.com/CAOR-MINES-ParisTech/ukfm
+ * See also:
+ *      - https://arxiv.org/pdf/2002.00878.pdf
+ *      - https://ieeexplore.ieee.org/document/8206066/
+ */
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
+#define ARMARX_BOOST_TEST
+
+#include <cstdlib> /* srand, rand */
+#include <ctime> /* time */
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/util/time.h>
+
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
+
+#include <armarx/navigation/Test.h>
+#include <sciplot/sciplot.hpp>
+
+using T = double;
+using Vector = Eigen::Matrix<T, 3, 1>;
+using Matrix = Eigen::Matrix<T, 3, 3>;
+using SystemModelT = SystemModelSE3<T>;
+
+constexpr long num_timesteps = 3000;
+constexpr T max_time = 1;
+constexpr T dt = max_time / num_timesteps;
+constexpr T c = (1 / max_time) * 2 * M_PI;
+
+constexpr T acc_noise_std = 0.01;
+constexpr T om_noise_std = 0.01;
+constexpr T obs_noise_std = 0.01;
+constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
+const Vector initial_offet_pos = 0.5 * Vector(1, 0.5, 0.7);
+
+void
+test_retract()
+{
+    for (int i = 0; i < num_timesteps; i++)
+    {
+        SystemModelT::StateT state1, state2;
+        state1.pose = manif::SE3<T>::Random();
+        //        state1.velocity.setRandom();
+        state2.pose = manif::SE3<T>::Random();
+        //        state2.velocity.setRandom();
+        // sigma = state2 - state1
+        SystemModelT::SigmaPointsT sigma = SystemModelT::inverseRetraction(state1, state2);
+        // state3 = state1 + sigma --> state3 = state2
+        SystemModelT::StateT state3 = SystemModelT::retraction(state1, sigma);
+        //        ARMARX_CHECK((state2.velocity - state3.velocity).norm() < 10 * std::numeric_limits<T>::epsilon());
+        ARMARX_CHECK((state2.pose - state3.pose).coeffs().norm() <
+                     10000 * std::numeric_limits<T>::epsilon())
+            << (state2.pose - state3.pose).coeffs().norm();
+
+        SystemModelT::SigmaPointsT sigma2 = SystemModelT::inverseRetraction(state1, state3);
+        // TODO: fix bad accuracy
+        ARMARX_CHECK((sigma2 - sigma).norm() < 10000 * std::numeric_limits<T>::epsilon())
+            << (sigma2 - sigma).norm();
+    }
+}
+
+void
+test_se3()
+{
+    for (int i = 1; i < num_timesteps; i++)
+    {
+        const T t = dt * i;
+        const T angle = t * c;
+        const Eigen::Matrix<T, 3, 1> pos(std::sin(angle), std::cos(angle), 0);
+        manif::SO3<T> rot = manif::SO3<T>(0, 0, angle);
+        ARMARX_CHECK(std::abs(rot.log().coeffs()(2) - angle) < 1e-6);
+        manif::SE3<T> pose(pos, rot);
+
+        manif::SE3Tangent<T> tangent = pose.log();
+        ARMARX_CHECK((tangent.coeffs().segment(0, 3) - pos).norm() < 1e-6);
+        ARMARX_CHECK(std::abs(tangent.coeffs()(5) - angle) < 1e-6);
+    }
+}
+
+void
+simulate_trajectory(std::vector<SystemModelT::StateT>& states,
+                    std::vector<SystemModelT::ControlT>& omegas)
+{
+    SystemModelT::StateT state;
+    //    state.velocity = Vector(c, 0, 0);
+    state.pose = manif::SE3<T>(0, 1, 0, M_PI, M_PI, 0);
+    states.push_back(state);
+    for (int i = 1; i < num_timesteps; i++)
+    {
+        const T t = dt * i;
+        const T t_prev = dt * (i - 1);
+        const T angle = t * c;
+        // yaw goes from -pi to pi
+        const T yaw = 1 * M_PI * std::sin(angle);
+        const T roll = 0.1 * M_PI * std::sin(angle) + M_PI;
+        const T pitch = 0.1 * M_PI * std::sin(angle) + M_PI;
+        const Vector pos(std::sin(angle), std::cos(angle), 0);
+        manif::SE3Tangent<T> tangent(states.at(i - 1).pose.log());
+        ARMARX_CHECK((states.at(i - 1).pose.translation() - pos).norm() < 0.1);
+        //        ARMARX_CHECK((tangent.coeffs().segment(0, 3) - pos).norm() < 0.1);
+        const Vector vel(std::cos(angle) * c, -std::sin(angle) * c, 0);
+        const Vector acc(-std::sin(angle) * (c * c), -std::cos(angle) * (c * c), 0);
+        const Vector acc_prev(-std::sin(t_prev * c) * (c * c), -std::cos(t_prev * c) * (c * c), 0);
+        //        const Eigen::Vector3f vel((pos - state.position) / dt);
+        //        Eigen::Vector3f acc = (vel - state.velocity) / dt;
+        manif::SO3<T> rot = manif::SO3<T>(roll, pitch, yaw);
+        //        Eigen::Matrix<T, 3, 1> rot_tan = rot.log().coeffs();
+        //        ARMARX_CHECK(std::abs(rot_tan(2) - yaw) < 1e-6);
+        SystemModelT::ControlT control;
+        //        control.linear_accel = state.pose.rotation().inverse() * acc_prev;
+        Vector angular_velocity(0.1 * M_PI * std::cos(angle) * c,
+                                0.1 * M_PI * std::cos(angle) * c,
+                                M_PI * std::cos(angle) * c);
+        control.velocity.coeffs() << state.pose.asSO3().inverse().act(vel), angular_velocity;
+
+        const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
+            state, control, SystemModelT::ControlNoiseT::Zero(), dt);
+        manif::SE3Tangent<T> pro_tangent = propagated.pose.log();
+        T pos_diff1 = (propagated.pose.translation() - pos).norm();
+        //        ARMARX_CHECK(pos_diff1 < pos_diff2);
+        ARMARX_CHECK(pos_diff1 < 2e-5)
+            << "Position is not the same: " << pos << " vs " << propagated.pose.translation();
+        //        ARMARX_CHECK((propagated.velocity - vel).norm() < 1e-4) << "Velocity is not the same: " << vel << " vs " << propagated.velocity;
+        //        ARMARX_CHECK(propagated.pose.asSO3().lminus(rot).coeffs().norm() < 1e-2) << "Rotation is not the same: " << rot.rotation() << " vs " << propagated.pose.rotation();
+        //        state.velocity = vel;
+        state.pose = manif::SE3<T>(pos, rot);
+        states.push_back(propagated);
+
+        tangent = state.pose.log();
+        ARMARX_CHECK((state.pose.translation() - pos).norm() < 1e-6);
+        //        ARMARX_CHECK(std::abs(tangent.coeffs()(5) - yaw) < 1e-2);
+
+        // add noise
+        control.velocity.coeffs().segment(0, 3) += acc_noise_std * Vector::Random();
+        control.velocity.coeffs().segment(3, 3) += om_noise_std * Vector::Random();
+        omegas.push_back(control);
+    }
+}
+
+void
+simulate_observation(const std::vector<SystemModelT::StateT>& states,
+                     std::vector<SystemModelT::ObsT>& observations)
+{
+    for (const auto& state : states)
+    {
+        SystemModelT::ObsT obs = SystemModelT::observationFunction(state);
+        SystemModelT::ObsT true_obs;
+        true_obs = state.pose.log().coeffs();
+        //        true_obs.segment(0, 3) = state.pose.translation();
+        //        true_obs.segment(3, 3) = state.pose.asSO3().log().coeffs();
+        ARMARX_CHECK((obs - true_obs).norm() < std::numeric_limits<T>::epsilon());
+        observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
+    }
+}
+
+
+BOOST_AUTO_TEST_CASE(se3KalmanFilterTest)
+{
+    srand(time(NULL));
+
+    test_retract();
+    //    test_se3();
+
+    std::vector<SystemModelT::StateT> states;
+    std::vector<SystemModelT::ControlT> omegas;
+    std::vector<SystemModelT::ObsT> observations;
+    simulate_trajectory(states, omegas);
+    simulate_observation(states, observations);
+
+    ARMARX_INFO << "Num States: " << states.size() << " Num Controls: " << omegas.size()
+                << " Num Obs: " << observations.size();
+    UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+        UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+    Q.block<3, 3>(0, 0) *= acc_noise_std * acc_noise_std;
+    Q.block<3, 3>(3, 3) *= om_noise_std * om_noise_std;
+
+    UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+        UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std * obs_noise_std;
+    UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+        UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+    P0.block<3, 3>(3, 3) *= initial_offset_angle * initial_offset_angle;
+    P0.block<3, 3>(0, 0) *= initial_offet_pos.norm() * initial_offet_pos.norm();
+    //    P0.block<3, 3>(6, 6) *= 0.0;
+    UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
+        UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
+
+    SystemModelT::StateT state0;
+    manif::SO3<T> rot(0, 0, initial_offset_angle);
+    state0.pose = states.at(0).pose.lplus(manif::SE3<T>(initial_offet_pos, rot).log());
+    //    state0.velocity = states.at(0).velocity;
+    UnscentedKalmanFilter<SystemModelT> ukf(Q, R, alpha, state0, P0);
+
+    std::vector<SystemModelT::StateT> ukf_states;
+    std::vector<UnscentedKalmanFilter<SystemModelT>::StateCovT> ukf_Ps;
+    ukf_states.push_back(state0);
+    ukf_Ps.push_back(P0);
+
+    std::vector<T> x_true, y_true, z_true, x_obs, y_obs, z_obs, x_ukf, y_ukf, z_ukf;
+    std::vector<T> vx_true, vy_true, vz_true, vx_ukf, vy_ukf, vz_ukf;
+    std::vector<T> a_true, b_true, c_true, a_obs, b_obs, c_obs, a_ukf, b_ukf, c_ukf;
+
+    for (int i = 1; i < num_timesteps; i++)
+    {
+        // propagate
+        TIMING_START(LOOP);
+        TIMING_START(PROPAGATION);
+        ukf.propagation(omegas.at(i - 1), dt);
+        TIMING_END(PROPAGATION);
+        if ((i - 1) % 100 == 0)
+        {
+            TIMING_START(UPDATE);
+            ukf.update(observations.at(i));
+            TIMING_END(UPDATE);
+            TIMING_START(REST);
+            const SystemModelT::StateT& current_state = ukf.getCurrentState();
+            //            ARMARX_INFO << "Velocity Diff: " << (states.at(i).velocity - current_state.velocity).norm();
+            ARMARX_INFO << "Pose Diff: "
+                        << (states.at(i).pose - current_state.pose).coeffs().norm();
+            //            ARMARX_INFO << "Vel: " << current_state.velocity - states.at(i).velocity;
+            ARMARX_INFO << "Max Cov " << ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff();
+            ARMARX_INFO
+                << "Diag: "
+                << (ukf.getCurrentStateCovariance() - Eigen::Matrix<T, 6, 6>::Identity()).norm();
+            //            ARMARX_CHECK((states.at(i).position - current_state.position).norm() < 1);
+
+            x_true.push_back(states.at(i).pose.log().coeffs()(0));
+            y_true.push_back(states.at(i).pose.log().coeffs()(1));
+            z_true.push_back(states.at(i).pose.log().coeffs()(2));
+
+            x_obs.push_back(observations.at(i)(0));
+            y_obs.push_back(observations.at(i)(1));
+            z_obs.push_back(observations.at(i)(2));
+
+            x_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(0));
+            y_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(1));
+            z_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(2));
+
+            //            vx_true.push_back(states.at(i).velocity(0, 0));
+            //            vy_true.push_back(states.at(i).velocity(1, 0));
+            //            vz_true.push_back(states.at(i).velocity(2, 0));
+            //
+            //            vx_ukf.push_back(ukf.getCurrentState().velocity(0, 0));
+            //            vy_ukf.push_back(ukf.getCurrentState().velocity(1, 0));
+            //            vz_ukf.push_back(ukf.getCurrentState().velocity(2, 0));
+
+            a_true.push_back(states.at(i).pose.log().coeffs()(3));
+            b_true.push_back(states.at(i).pose.log().coeffs()(4));
+            c_true.push_back(states.at(i).pose.log().coeffs()(5));
+
+            a_obs.push_back(observations.at(i)(3, 0));
+            b_obs.push_back(observations.at(i)(4, 0));
+            c_obs.push_back(observations.at(i)(5, 0));
+
+            a_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(3));
+            b_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(4));
+            c_ukf.push_back(ukf.getCurrentState().pose.log().coeffs()(5));
+            TIMING_END(REST);
+        }
+
+        ukf_states.push_back(ukf.getCurrentState());
+        ukf_Ps.push_back(ukf.getCurrentStateCovariance());
+
+        TIMING_END(LOOP);
+    }
+
+    sciplot::Plot3D position_plot;
+    sciplot::Plot2D pos_plot;
+
+    position_plot.drawCurve(x_true, y_true, z_true).label("True").lineWidth(1);
+    position_plot.drawCurve(x_obs, y_obs, z_obs).label("Obs").lineWidth(1);
+    position_plot.drawCurve(x_ukf, y_ukf, z_ukf).label("UKF").lineWidth(1);
+
+    pos_plot.drawCurve(x_true, y_true).label("True");
+    pos_plot.drawCurve(x_obs, y_obs).label("Obs");
+    pos_plot.drawCurve(x_ukf, y_ukf).label("UKF");
+
+    //    sciplot::Plot3D vel_plot;
+    //
+    //    vel_plot.drawCurve(vx_true, vy_true, vz_true).label("True").lineWidth(1);
+    //    vel_plot.drawCurve(vx_ukf, vy_ukf, vz_ukf).label("UKF").lineWidth(1);
+
+
+    sciplot::Plot3D orientation_plot;
+
+    orientation_plot.drawCurve(a_true, b_true, c_true).label("True").lineWidth(1);
+    orientation_plot.drawCurve(a_obs, b_obs, c_obs).label("Obs").lineWidth(1);
+    orientation_plot.drawCurve(a_ukf, b_ukf, c_ukf).label("UKF").lineWidth(1);
+
+    // Create figure to hold plot
+    sciplot::Figure fig = {{pos_plot}, {position_plot}, {orientation_plot}};
+    // Create canvas to hold figure
+    sciplot::Canvas canvas = {{fig}};
+    canvas.size(600, 600);
+
+    // Show the plot in a pop-up window
+    canvas.show();
+
+    // Save the plot to a PDF file
+    canvas.save("kalman_output.pdf");
+}
-- 
GitLab


From b51cb7620736caf4b6892dd8053e66b40d47b686 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 28 Aug 2022 01:57:12 +0200
Subject: [PATCH 177/324] Use Robot local velocity

---
 source/armarx/navigation/human/HumanSystemModel.cpp      | 2 ++
 source/armarx/navigation/human/test/kalmanFilterTest.cpp | 1 +
 2 files changed, 3 insertions(+)

diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index 1bc17e64..f660f1fd 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -25,6 +25,8 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
         StateT new_state;
         new_state.orientation = state.orientation.template rplus(control.angular_velocity * dt);
         new_state.position = state.position + control.euclidean_velocity * dt;
+        //new_state.position =
+        //   state.position + state.orientation.rotation() * control.euclidean_velocity * dt;
         return new_state;
     }
 
diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
index 7f9b5f6c..7cfe6d5e 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -81,6 +81,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             //TODO (SALt): check angular velocity (>pi overflow)
             control.angular_velocity.coeffs() << c; //(last_angle - angle) / dt;
             control.euclidean_velocity << (pos - last_pos) / dt;
+            //control.euclidean_velocity = Eigen::Vector2d{0, c};
 
             const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
                 state, control, SystemModelT::ControlNoiseT::Zero(), dt);
-- 
GitLab


From d1e6eae0dc701a792682da837cba73a4fad6796b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 28 Aug 2022 02:09:06 +0200
Subject: [PATCH 178/324] Alternative system models

---
 source/armarx/navigation/human/HumanSystemModel.cpp | 10 ++++++++--
 1 file changed, 8 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index f660f1fd..7a613595 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -38,7 +38,8 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
         StateT new_state;
         manif::SO2Tangent<FloatT> tan;
         tan.coeffs() << sigmaPoints.segment(0, 1);
-        new_state.orientation = state.orientation.lplus(tan);
+        //new_state.orientation = state.orientation.lplus(tan);
+        new_state.orientation = state.orientation.rplus(tan);
 
         new_state.position = state.position + sigmaPoints.segment(1, 2);
         return new_state;
@@ -51,8 +52,13 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     {
         SigmaPointsT sigma;
         // TODO: check if right order of substraction
-        sigma.segment(0, 1) = state2.orientation.lminus(state1.orientation).coeffs();
+
+        //sigma.segment(0, 1) = state2.orientation.lminus(state1.orientation).coeffs();
+        sigma.segment(0, 1) = state1.orientation.lminus(state2.orientation).coeffs();
+
         sigma.segment(1, 2) = state1.position - state2.position;
+        //sigma.segment(1, 2) = state2.position - state1.position;
+
         return sigma;
     }
 
-- 
GitLab


From 6c48ca563dead87f3ba4174021270365ecc00fe3 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 28 Aug 2022 02:10:05 +0200
Subject: [PATCH 179/324] Fix kalman filter test

---
 .../human/test/kalmanFilterTest.cpp           | 60 +++++++++++++------
 1 file changed, 42 insertions(+), 18 deletions(-)

diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
index 7cfe6d5e..1ccc3114 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -50,8 +50,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
     constexpr T rot_noise_std = 0.01;
     constexpr T pos_noise_std = 0.01;
-    constexpr T obs_noise_std = 0.1;
-    constexpr T initial_offset_angle = 0.0 * 10 * M_PI / 180;
+    constexpr T obs_noise_std = 0.01;
+    constexpr T initial_offset_angle = 0.1 * 10 * M_PI / 180;
     const Vector initial_offet_pos = 0.1 * Vector(1, 0.5);
 
 
@@ -59,9 +59,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
     simulate_trajectory(std::vector<SystemModelT::StateT>& states,
                         std::vector<SystemModelT::ControlT>& omegas)
     {
+        constexpr T startAngle = 0;
+
         SystemModelT::StateT state;
         state.position = Vector{1, 0};
-        state.orientation = manif::SO2<T>(0);
+        state.orientation = manif::SO2<T>(startAngle);
         states.push_back(state);
 
         for (int i = 1; i < num_timesteps; i++)
@@ -86,12 +88,17 @@ namespace armarx::navigation::components::dynamic_scene_provider
             const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
                 state, control, SystemModelT::ControlNoiseT::Zero(), dt);
 
-            T pos_diff1 = (propagated.position - pos).norm();
-            BOOST_TEST(pos_diff1 < 2e-5,
-                       "propagated position differs too much from real position: " << pos_diff1);
-
             state.position = pos;
-            state.orientation = manif::SO2<T>(angle);
+            state.orientation = manif::SO2<T>(angle + startAngle);
+
+            T pos_diff = (propagated.position - state.position).norm();
+            BOOST_TEST(pos_diff < 2e-5,
+                       "propagated position differs too much from real position: " << pos_diff);
+
+            T rot_diff = propagated.orientation.angle() - state.orientation.angle();
+            BOOST_TEST(rot_diff < 2e-5,
+                       "propagated rotation differs too much from real orientation: " << rot_diff);
+
             states.push_back(propagated);
 
 
@@ -116,6 +123,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             BOOST_TEST(
                 (obs - true_obs).norm() < std::numeric_limits<T>::epsilon(),
                 "observation differs too much from real observation: " << (obs - true_obs).norm());
+
             observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
         }
     }
@@ -151,7 +159,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
 
         SystemModelT::StateT state0;
-        state0.orientation = manif::SO2<T>(initial_offset_angle);
+        state0.orientation = manif::SO2<T>(states.at(0).orientation.angle() + initial_offset_angle);
         state0.position = states.at(0).position + initial_offet_pos;
 
         UnscentedKalmanFilter<SystemModelT> ukf(Q, R, alpha, state0, P0);
@@ -162,8 +170,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ukf_Ps.push_back(P0);
 
         std::vector<T> x_true, y_true, x_obs, y_obs, x_ukf, y_ukf;
-        std::vector<T> vx_true, vy_true, vx_ukf, vy_ukf;
         std::vector<T> a_true, a_obs, a_ukf;
+        std::vector<T> x_ukf_full, y_ukf_full, a_ukf_full;
 
         for (int i = 1; i < num_timesteps; i++)
         {
@@ -172,8 +180,14 @@ namespace armarx::navigation::components::dynamic_scene_provider
             TIMING_START(PROPAGATION);
             ukf.propagation(omegas.at(i - 1), dt);
             TIMING_END(PROPAGATION);
-            if ((i - 1) % 100 == 0)
+            if ((i - 1) % 101 == 0)
             {
+                // dirty hack
+                //if (std::abs(M_PI - std::abs(observations.at(i)(0))) < 0.1)
+                //{
+                //   continue;
+                //}
+
                 TIMING_START(UPDATE);
                 ukf.update(observations.at(i));
                 TIMING_END(UPDATE);
@@ -194,18 +208,21 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
                 x_obs.push_back(observations.at(i)(1));
                 y_obs.push_back(observations.at(i)(2));
+                a_obs.push_back(observations.at(i)(0));
 
                 x_ukf.push_back(ukf.getCurrentState().position.x());
                 y_ukf.push_back(ukf.getCurrentState().position.y());
-
-                a_true.push_back(states.at(i).orientation.log().coeffs()(0));
-                a_obs.push_back(observations.at(i)(0));
                 a_ukf.push_back(ukf.getCurrentState().orientation.log().coeffs()(0));
 
                 TIMING_END(REST);
             }
             x_true.push_back(states.at(i).position.x());
             y_true.push_back(states.at(i).position.y());
+            a_true.push_back(states.at(i).orientation.log().coeffs()(0));
+
+            x_ukf_full.push_back(ukf.getCurrentState().position.x());
+            y_ukf_full.push_back(ukf.getCurrentState().position.y());
+            a_ukf_full.push_back(ukf.getCurrentState().orientation.log().coeffs()(0));
 
             ukf_states.push_back(ukf.getCurrentState());
             ukf_Ps.push_back(ukf.getCurrentStateCovariance());
@@ -218,27 +235,34 @@ namespace armarx::navigation::components::dynamic_scene_provider
         pos_plot.xlabel("x");
         pos_plot.ylabel("y");
         pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        pos_plot.xrange(-1.6, 1.6).yrange(-1.6, 1.6);
+        //pos_plot.xrange(-4, 4).yrange(-4, 4);
 
         pos_plot.drawCurve(x_true, y_true).label("True");
         pos_plot.drawCurve(x_obs, y_obs).label("Obs");
-        pos_plot.drawCurve(x_ukf, y_ukf).label("UKF");
+        pos_plot.drawCurveWithPoints(x_ukf, y_ukf).label("UKF");
+        pos_plot.drawCurve(x_ukf_full, y_ukf_full).label("Full UKF");
+
 
         sciplot::Plot2D orientation_plot;
         orientation_plot.xlabel("x");
         orientation_plot.ylabel("y");
         orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        orientation_plot.xrange(-0.1, 1.1).yrange(-4, 4);
 
-        sciplot::Vec x = sciplot::linspace(0.0, 1.0, a_true.size());
-        orientation_plot.drawCurve(x, a_true).label("True").lineWidth(1);
+        sciplot::Vec x = sciplot::linspace(0.0, 1.0, a_obs.size());
+        sciplot::Vec x_t = sciplot::linspace(0.0, 1.0, a_true.size());
+        orientation_plot.drawCurve(x_t, a_true).label("True").lineWidth(1);
         orientation_plot.drawCurve(x, a_obs).label("Obs").lineWidth(1);
         orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
+        orientation_plot.drawCurve(x_t, a_ukf_full).label("Full UKF").lineWidth(1);
 
 
         // Create figure to hold plot
         sciplot::Figure fig = {{pos_plot}, {orientation_plot}};
         // Create canvas to hold figure
         sciplot::Canvas canvas = {{fig}};
-        canvas.size(600, 600);
+        canvas.size(600, 1200);
 
         // Show the plot in a pop-up window
         canvas.show();
-- 
GitLab


From c2a93dddbc17920dd1a39c154457b1e3321a3e37 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sun, 28 Aug 2022 02:11:01 +0200
Subject: [PATCH 180/324] Document test findings

---
 .../navigation/human/test/findings/Notice.md  |  18 ++++++++++++++++++
 ...l-start_0-mod_100-low_error-dirty_hack.pdf | Bin 0 -> 67584 bytes
 ...native_model-start_0-mod_100-low_error.pdf | Bin 0 -> 60874 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 0 -> 67438 bytes
 ...ative_model-start_0-mod_101-high_error.pdf | Bin 0 -> 67428 bytes
 ...native_model-start_0-mod_101-low_error.pdf | Bin 0 -> 67336 bytes
 ...2-start_0-mod_100-low_error-dirty_hack.pdf | Bin 0 -> 67677 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 0 -> 67596 bytes
 ...tive_model2-start_0-mod_101-high_error.pdf | Bin 0 -> 67633 bytes
 ...ative_model2-start_0-mod_101-low_error.pdf | Bin 0 -> 67431 bytes
 .../start_0-mod_10-low_error-dirty_hack.pdf   | Bin 0 -> 79390 bytes
 .../findings/start_0-mod_10-low_error.pdf     | Bin 0 -> 76832 bytes
 .../start_0-mod_100-low_error-dirty_hack.pdf  | Bin 0 -> 67390 bytes
 .../findings/start_0-mod_100-low_error.pdf    | Bin 0 -> 60704 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 0 -> 67661 bytes
 .../findings/start_0-mod_101-high_error.pdf   | Bin 0 -> 67660 bytes
 .../findings/start_0-mod_101-low_error.pdf    | Bin 0 -> 67362 bytes
 .../findings/start_0-mod_11-low_error.pdf     | Bin 0 -> 75469 bytes
 .../findings/start_01-mod_10-low_error.pdf    | Bin 0 -> 76717 bytes
 .../findings/start_01-mod_100-low_error.pdf   | Bin 0 -> 67290 bytes
 .../findings/start_pi_2-mod_10-low_error.pdf  | Bin 0 -> 76444 bytes
 ...start_pi_2-mod_10-low_error_dirty-hack.pdf | Bin 0 -> 79465 bytes
 .../findings/start_pi_2-mod_100-low_error.pdf | Bin 0 -> 67483 bytes
 23 files changed, 18 insertions(+)
 create mode 100644 source/armarx/navigation/human/test/findings/Notice.md
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf
 create mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf

diff --git a/source/armarx/navigation/human/test/findings/Notice.md b/source/armarx/navigation/human/test/findings/Notice.md
new file mode 100644
index 00000000..61048442
--- /dev/null
+++ b/source/armarx/navigation/human/test/findings/Notice.md
@@ -0,0 +1,18 @@
+# Different configurations of the kalman filter test:
+
+- start_* is the start angle of the simulated trajectory
+- mod_* is the modulo value used to define how often the kalman filter is updated
+- error is the noise added to the measurements
+  - low: 0.01
+  - high: 0.1
+- offset is the initial position offset:
+  - blank: 0.1
+  - high: 0.5 (1 for the alternative models)
+- dirty hack: skip orientations close to pi
+
+Alternative models use different calculations for retract and inverseRetract
+
+- normal: lplus(tan), 2.lminus(1), 1-2
+- alternative_model: rplus(tan), 1.lminus(2), 2-1
+- alternative_model2: rplus(tan), 1.lminus(2), 1-2
+
diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..dcb8673c9ff6ed9fbb63c7d22740bb65ddfac5b2
GIT binary patch
literal 67584
zcmV)RK(oIkP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_TXj*B}x%7
zZNO;2fCt@uXNCtx8{I(T<e=<<?YH+9xz?g~-tU~On}tGEePSN%kSI!`__Jsq=j(s|
zX0QKa?L0sJ>(Ap~j`K$w=W~Dj`v3p)fBg9O|Ht|9-~aE!KK`HA|Nbwp|NS4w|MtJX
z{^0!hKMy-U{@0Ix`LOuO{J*cCbN_Ll_A$o!qrd+D&kyfE?$?iz@cHpyKK|43Ww+jc
z^w(d%y0ssVKO$teuSWWR{r8Xm@b}}+$=x5V{b+v9HeTK54{zhT?c?u1kAMH){&xOt
zef01D?f7?pvmfJs`uqPl{^!4c$AB*fYV*g~W*5!x=jPAzWBOg4Ncc^+yZyMfPoe#r
zPILUYN85UV@SARa2iL`Z68<^%KR@oPdw+d(*pKJ>g8hHaeDCdto%`%S_|5EW{IKWQ
zx`FV0x0m?6i!uqn>2@1M8QnnmO}FVOSh)b%{6p#Q^ZGHqkpA=EBK_U3cTpzcH*@Rf
zn<%6Gn@-l>MVW-}yR~Ohl(QQNzv*_r4!2>o03`fVOYoXkv&-(+SMUDg{OcX?asK%N
zwAtT9nS|fW&gZ)*lkl5vuO0m+$|U@zo3;In%;xu9>=_iSWIqZ2><$>W_m^ndYpc$$
z*#B?Y0e0PQqKx)$W;g9!lu7tax7YuF6J-*9)2-bUWpo4KH{HxAT37-Q{%{AF`H%M3
zhtS8r;SPBGU6RrMes0(GF2`tp-)Ww^6i4ef_e}rgp6~yPv$0Lc6ONr(;`C2T{cCq#
zUkLrbN$GjsrT6()$nK^Gl3?E*RId%Ocvam*c-`>->^U%A<Mi>mFFwZW8uhOfkw0R|
zYrl_em}q`Gx7ShDUks~GB7ED;Ugzfe=jvCK?>oNaVD0y<qbT2Z^pVPUbrj_fmcjg`
z1<u!L@O-}xf3ONR+b?2Pl<%i_J--NAQNHi^%(sPS``b?KrLw#)eNn#e_&P`5*S;u!
zuoCTcM)c>mJL1o7#`e+y-^Hyc-%oPBKM{X^6y^Jlcj%8>KN7z0_PmtU^KCUm`L<&>
ze_MOD|6nD$oj>N?$K&6v#2=}Mz1uIsR+R6j_j>HT3tLgX@A!ILzOQ^yzVG;Y61}f{
zQNHi^-0v$d!k?_g^ZHgQE8nigpIx1=H|D#r73JG0t~af}9l}NVzN0_UVZVAw`M%?v
z!Mv@bDBpLy``#&9f3ObzI)Ux?d*Y9j#^?D((2DZy)RtlAP0&R6zFY6Vta?$t@A&HQ
zzUoE!zT@ky|Gw%)`4iP?yl%t!+dc7Ty3<Qd{YB7<@*B~9*F)cR%+HTsfB0WB<(Tf@
z*2LF4C+FGj*G|jX|2pOWZ_Rf*#@mncZuh!SUn*dk8vot@E56t{?z_FdI$yfNxjz5e
zRxjTEwV=K>Pg|NuzQCe2!IEY9i?_i=TV7Ed51B=IiS-ereC&brqNK_J%Im*gl(&}Q
zRT-4^CV5d_GJE_&Y6FDz)VR+0@i#&ZcTJ<sC%S%q96QPNsik!-N?P!Wf){lVUjMWR
zHOUy)BGn{c!t<hB@r8FvO?#~N_TO`Tixc#Cc+nzKl(F%php{D3a8MTSUX&MGj-BEg
zV|u*sJO-4MHiA&B3IZ)#!6^$)^&ez{IqW?8bW&RJ$%0R9<I{^hN07v)SIde=(IS5g
zwxkme)}X{>Vm}=ut=YT|2y&$;<Vt>^jaxj(XWXKUp&yE69k;k(xnkpzd|NKTi((p4
zEWw!Tqx_-Z_>1HkQE>c4F^wqLIfi&+$-Xg?M<B(BT>P=%+oF(1XYRPs#iQH-iy|JK
z$+pqNqZ2%8;?W5nHEyUAEXq|lK#BpGB<BQ+OiWt_iPwQ9mYrbG`GY_E8u}3g(};sT
z&W*V!Oa8pJW&ZJ^n8v&Q>!s%3Td&~Gi-K-f3dN$J+x5WEctJ|9JiQm8Ke_c@q;+!O
zwUC71jZZEF9%o^%9Q@(ngip3!b97n@7a`d2qF_5ON_?2cvqgznJJ)0>Ag}Koi_|#U
z5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?E?GoFZ+4i;`2cSjr;^(ZoVtHzs*<
zNv<19i`9R%V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P(E3%K
zVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wppEeZu?
z=C130pqT^jTbCSo-@4?uwc%fs#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi9YG0J
z>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgpd<yzaWUFwm1U6kq-
z>}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8%*)I8
z04ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1w;a*A
zbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5oi9qm
z5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2i)3?}X+)5$P#3z_R;pQ+-!
zNN6P&`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpEUWELjbhdfptEmYcNy^XK)-68^
z59^B%4II7m!emb#@~Jn!ICehlkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT5z9cF&`
zl!`ZT{+<$wi39h%w2>#y*Hcn4^ITYz>K4*<QYu!+!{Y9lQgI|{vG<fzK$Bk-NX3hi
zljLvY1WPIgF3?jt;Y=Y~6tW*qowIAza4?=-Yp{%mt8I8<O~)ju(9e9$E&^A;qeW(R
zFjHs8>|8|y_j`Oq+T!f^hHeiyju(YI>CwV_X6AYJ`Wx+(JhDvTD~mFsO@^dA^P4R>
z7S33bqD4*^J|V3UULSid$(6+?LIMvEdU%ZWG?=LuEsH$aal(mQLUO{-JT<?Z_i{9I
zera$i*Yl#Z5d;cJ?wc27wZ@Zro;`XvjMznsfH{slUl#>)91ob(ImZF@bCK}F@z3Dn
zdQC-##<d$a*rZp*xH0yoGi%&n6#pPcuJdH%`Mf9`>xBh2jrGcBn?2Gr$A#fT)5H^P
zwK?7lxUgGVNIu$vLc7AqQ+<)Z+ZSbx<3-8V>%Sx^Bk%r2;mAh5;O&;E<csb_(P1$h
z-E@VF+>VRF&w7g1i-hJ{@_S$}4#$rU?!^JG`aLLsBX_&q@wo$}VE)Yq#mM*jix91b
z-_SWRu(@uX6Qglpdiv*^(O{EFLXJ+)i-A3L^LaV2rS8xH4v<1v@HkIO{BVha;fG5U
zPW*66!jYt0LyE$Q6+HRvQ|`6TutsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+wAT{=
zJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bi;}I^f9VP0kn>Bz
z;`pgWg0$c%YnKc~J~1{uNPQr>M0bskoSc<?&j-e)gT%ucwFo1d@!z=?3SeoH15a((
zpo=CY$0k#fJI1ElN0Be4S1uwQ?9%h)Mai+r$mAV-ldj_Z)zZ1*E#4H1GSD8;YHa3;
zo@j-5LRDK7$UStkBS|5iQwpu;XlzQM#hZFjD5WPtbZ)6xo|@<)QFd@uOsO+HuSqMb
zW6!H#)+@KKf0rQj8^J*#Nc}=<pp`?{#e#RR&90lUPmEnRMTgi--4s1{v<)4l9Wzez
zTmBHHJhY+kq_iQcYI{JL8zn|GA_Vpbg5ghc%^GGnCR(wAuVb438f!RoyS6KBdxn!d
zNiQA_r<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7w*gLy
zw{3uv+CF%2+K}Sb9BgaUI~uka27~M6b>8NE(>i#jS0Emri$Xs2c;qY!<gvZBQkeo9
z?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>D5(2h0thYz_1P0JsxVLsce42UiD
zD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNI86&91T+Fx&;h7(I<}t
z3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn&q2`ANm(>P1r>g?*)<qd;
z$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%Eh7DcT
zPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+kyh(`VtFL&=Y!Reu%DC+>8R%o_0dl>LoUiV
zdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)val#v
zs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe=^93+
zS9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV7&|qk
zMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixlvw}XtkUl
zE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5A^ZJ-
zU7*w6cq~%N`Kd1%mh2R#pp3~h{h~yRJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}t1Lns
z7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@ghMOTK+@`LgPMN?O;>mZPf7!HCe<L
zCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSRo0NpR
zgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SAo9o-B
zdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{5~9Nd
z4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk=r3jv
z<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4g@UHp
zPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8Y(8am{qx%{&K!l4G0s
zmN6Pg`ox88a>{hr#LaXn!T`P~9Nf^iFu0V6!;A*|MMAG=K^o-P>4;GY3PuNMu$xwu
z4!g4%^_fLsw}Cc0VQFbbHssD7K^j58_Mc6iumx!twi~VW_m{?M*nW0tuy}Nsj^D`F
zh&FyQJ>h1lHudqS2YlI!6la57l){0l!|228<5o9}m6lh#B$%|dn$GNzx}))tu?TVG
z8S*_AA&yBr9TuO)WGBpl7E&agt~UFC+apa;LBSNLI?!qMqC^9NftZ&?!I^{C^ox?M
z*MAMNe(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p@w-SV
zk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZA*IB*
zkNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vo^7KgP9mhi0Jc%I+O&
zA#IuVJ?rE^=lV&1R@PV-6S(ZU6CLNg=~i^(QPsr;!;0ymbeNtEw#@F_%$;J~xt--!
z>z&(Kw`u2g?$NrzUEQsSVhKvJqQj&dq#R6#|HI&|>m84MYh*=-es9wFJ6w^A1YY2k
zWXO(O?T~Joj(X=Iy;BCp$1|(*l%^-ScOKHZ*Lw%I_z3U4fm=;G2QlVB!YuH>Gv-+L
zd~2AT)ScEvP>v*lhw%p|q?3^@i<0cyDAB?iw1*N(=jI|MJBxBFLlLXeVC#9KEQ{Ns
z<T^oFH+j^18W-Q%$tWo=Z7Mes@uHmuMWe}LQ4HTEWhA4d@z8h(%8{gGRC;WCbFqqT
zG78JzxC?hmSbfZ-O0_0N6s6^0AR$o1-YMyTG$~+EY&MELoK$W?+R`=xb4G(vwCyO3
zG;&|gy$3BdMYy#_)D~cNsd1c_c!}YkQ>-fr$41Tn9O51r1K<C~&(k%)qJVihzD^CT
z2;?P}`s|t$DXj!A<>PD=Je*bV?QfDtW6B#vf|vX}tppEDKWoFK)StEAurbbaYc(2E
zw7C{VLPgTH--36GLQds2UKDVOgjCp$JPKBmhgY5+jmDFWGIe(4k<%i}4u{eK!uw&?
zp0OWhpztgUv04NkWj%eD4dxP^n++~|9Il}7I&e%0j$TrZAn`iLPqn%YFojmPf#(lX
z*`ed0JrD)mD(yLS`g0LZF_4RJih<zyo%+p@SKMmqp3K3}^r4%x(fDEXBDI_9YloSr
z-PnV?kr$!kA_uc>>aV=o+s$2>-pFGS`q=e>7iH5I+C8LYfKfDcQ15sVsFvioTs^>~
zd(&nxFlsZ7);xFRXi>tMA_b};Z=#f}2KPD@u^<?<E^@@kc^6AeYGHOdr4(|;r?f)O
z_>@+d=EFuKhV;=!8-|qDc0K9^LC7fM)Oy>6c->Nq+eKA}MwoUX_=D<oyQt_;0e?|G
zprGf-sQ9D~->#_+Sl?@Y)H7hEuki14H8VJMe@(3H6}|(oeizT=iB`+^3zqNV@=hHQ
z7uR@lCY_zIShP~;;nXg!@Wfo88P)5n(MZ7;T2R;t6Qb%mwK6BgVrpslGUW{FWs1d_
ze5LT&xhUBOPM$U&b;1m0y-Ww%e3xPZ^H!fYc8<uAVJ9rWywnW~F!@l)79J_L20Ia^
zq6hsVp$8d02YYd}RETbjcBl*P#FZt3J~$+&s}Bdu6Z+O*dv<!z=(MNcw3{$t(pG{j
znzE)ai>53tOrn8RCdX#jEVSK3HVq9v7@Vma2Zzf!Ohl1ela|s`yrh8}W~NB3$sQcu
zpn;plsznLqn<lN#NUdQv@DBd}vWzVXzXidBv;TmN4Wtgk92iJDg-mq~5dme+Yp_!s
zW%6q@Rmd*bXsVFykU2VKUPO-0`k|awN(AkbnVv(dCVm4FAv@<v&p{_H9^Cvgm<A;c
z$4z5t?8TwreFWR=k)-UUn{&Xjt$UJ@Rx$&(Vd^w8EF^MxU~uMYo$7{j1W7z)lx7l-
z4A)1HMwzyomuVZkpd|wa@|K1S8PJ;}CZw$FjZsofSBpcDleNAvBuW<jm9BHs3jo3O
zscr-9Ha5>eW6YDh3z5}x$^&tLL_Y>UUcL{0ynG-0c6mQWa>_SnNuzlKuf3$C??b1y
z)AylM+8aGq7a5MDL;jt{I3+oORua!OHb2oK<XT@09*jhvlddKv`N$WAB%ktDG0TVk
ztVr<*o1a`>i<I2g+1c^-lJ9IK@#F%~z1BKTW4Yj3hml){W52+Ddh!}v)r*q1A}uEE
zp+EXX+I)kN;}bqp`VSW+J(YAauEd^elpC_8Q~B6jm5Y@AcpYCI@i<7L3BuSsqK)R0
z^qS_-=sh=niN13kOP#)RJzU`br4RSW1RywZ`7H!T%MaYpKYhhPNa2t-c@Z#6Y49Dw
zA*Xa?1jTT4$n+C#YOX#W3cXZk_+isO-Wc5_|9PX)MNak?MK1W23Y4-hFMVqap`atb
zF~F<qplDDo6cNzU<Z^651Cbsy_P_#W2W8;FYDIj&)KC$=mB9-KNXdOhH#8hX6#>y`
zfay~Mh6_En_>q(pDJWGqkSiR6sX-O8v2uKJI0)-#jR%FoJ{qp4iVTU&pmUENVb)It
zoJ7)3Mqp^OHHJ?}?P!_gnSm{<mElc{d}%P__$fVJu~pI^6k8>2!EkdpTN%V-`qdk%
zyyAA6-CJBwgQA*oKdY4=(3>49GlGW>kPs@QAIYUx5Ymf)0HsLyiJ%|Yh#Ma&=Gqo`
z{#4Xc!xO3^qZWlBR}k8K^c@JXN{Rxo8eYH^qSf%Ut}w2KH#|bU4v_LQdMm*;p_s83
z0pVmVjX4!<){Mu3>j7hUY$|GP<@jXKlO7|qzbX1HGK1o#@Jo}U#6aXv=oyN$YlydE
zB;INxnvXBA6ZRs7^esv*j|BdNMyjYlW(y&5Fn<Wz2g3^&VV)I#xY`}jh8!IfR7Ei!
zD>EpfLYWL3$wON(BvOYeUXrOp6;m0hL$Qe!blFZugh~}Y84)VI_k<Cj@tqAO#>4Ql
ziU#Eb5u>9J(v>Nc5uvgc(damoXWSUhHDuRW;am!6MQ%~WytXt!Dk?Uzi*kOlgPbr^
zDZF-3GO*M&KWHzC(2bm<IMEfv%cP@<^o^t=zZDC-+R3;j?<=9`9t<QtKw<RpK%240
z$&<(`8hga@qGV_-1oco_kqLUhXq8la^vb)*&~mE&k#`fJ+0gS3CEg$!JN}5F<*x5D
zv^+<Q8Ai1C%6bWnw!*;|DUN%_i$@|%g_Ez;m$3z$M{-Pz>ZZqQk#gvo%+08BDuRoW
zBj=NOQ92^$VY*+W5JJIqFsG&h?jxrrV*XFGGTt9A*F{KqLOlOUmwE6PH)fnFoe}~T
zVQeV_M)P06kt|Y7@iGk`N4OFc7A2;rB!)$aoq8z+(|{O*bcmq9lEjP&Cg(7nVztMX
zZDF(=DkH-fAf>bo1I9|Fb{J4iD*eM0GNl|51I9-sk|2F&OExitQC$;_!7P;ngybDH
zAg1zEzKa2_qH<ykSQN;cIY7#l)yBG^O)CG!Xrok$PGtSW#}tQW7c+bKyfDUIDIv%J
zsZdEn{7K{#9Z8AbLDtb~XJ(ZI3%~`Hyu`s*g41CcpQRKiGC_$`1^|J|tujCcRQ^?P
zchAtWO#iPeE@Qk_<b4@UpiB!}g!p@9jx7ok&L9ko-BJo#NK*_1y22t1WU$$V<cG?7
zGlp>~Gj36GwzozOwN*)XmbvD~mZQf_hD5%kY>9qM0Ag}r?B(_0OdmWzik!+?8`#N|
zhiEXGR<5EU7d&$r<48G}>j(l;9W^W_YU&i9h$2>A<)U1pvMvot-j$fSC^>xIiOeOc
z1kXju;k(Y3$%M^;R%TW5_FI&(rJ2Tgoqx{_H5p;}z=r*zZ0W2<yRA}Q7loO#5F1)@
zD|gnAwq5D9M&qthaMz8Le3BeYIKiL0W{8+(FcOEq5`h<`jV)8yXcAU7u}v6tkaC=q
zNYbVjW=hgNwTMj8HZ5XopvZeZ(2jI}<wl#bv~@u!OPe}Y+}fv7u#cqVm$bE~BPCpW
zTY1_v+*#yl>pGZtZdc0qB4s+bi!+(2J@DU|rCp-JEbXBy5GHKusGm|*lmTyP)UF))
zMacQ#062ma*a_z)Rwfvg67m-zc`2o10!TuM{YOAqp9uvp@FzLLTQX)b!$<4~Zj%58
z79~&{h(WLj3EFUq`@mlkmVr$oMx5+KzzBtiT0{Xhx%^i<J}n>mq9j^H)2ad8h_2zK
z$^za<4qHR`V8T1BR(_fA4~sH3fC$T^?*j-DtGQS$_n{%uuuv$LMw;KG;nk1_4kU{M
zq=c%V^~46Sg9M2|)mEq(Hi#NA83G#$vELi|hQU1`gbqWxc!79W1~nGW#}UeR{LEdQ
zhRg-o&ap`Q99MFJIhu<Q*H<BvyhwsB`3#*u*dTZl%RtFOKrtkj1104EX~?FM?HGw%
z6i8bvK$b-arU<m<Snrdjpz8H{N#vQPE_sB>BVd`Pz9GoOlP9p*WZbtw*dE`yCGd=I
z-4f=-w_XYICbRo`g(dRLP&Ws&hPrtUac-SL3<`uN-gg^LkHODUSUy2HZNvMCcVi6j
z;-l2yj49xt_1??@mP7!{qLoAdyyt-_)ds<Po~=_t<vd%bgl6JpGH{d%9O;O+@$+m5
zN(R3VL6#O_!(d{nXW=vjB~EmKIq_NEWY#r=yA~+aqKpkTYPEx(y)&#VNHJbVD^R3-
z>yaQ*bv`tJNaeth-CqD$1|)z&$bu0f0kjOb00ppRh`0p^*8$QfpsqA^Jog6XMdOF?
zz6=O;1qpTp$#3F@;g53gH+$iD7y6hXy0_5DY@B31jh$h!SsxS5Sy22I5Sk$(xS-Mu
z&NaZP9U#TD0Jvs@KzVf*;F^%ZlGY?4yB$GFh&U;o<1Bc%Ws!;*2|>=Bn0Sm<S(HH5
zA`l%7TLo5U4lE+!*@ZDIzALo>fPO~-<1JFoak6#VhN}k?TS4zFLQYwM?dC+q)AIWc
z`WLpm_y!H#29INb2g2TWY!HKC6pSxDTen=rXX}=bh+1g}q$Cj!4PPxxMA{z<H8Ch-
zM^-dIMF4*B0BNy;HaVst7l@-_$_4beD2W)^8M&BUqyaeYPg&CpuGNB_G=z;ena(WW
z6ORqQ(g0FX7?(jgcN|QEixyy+q!3Q?03lf;-Oho*SH>|Ig#q3PN^s^Tj@Y8)MD-%v
zD368{+?uE4GfxyEj>Zp76u^-AXQPlm!1NQWDUI8V+Q1J56N!&n1gY{FX-|w*gUlBU
zD=5bX)k?#9p}7X-+!0@kGAKEDr5=SG8>9_emTlPqeF~43l0(YH`NhhWX>g+yqY{kv
z-WWy7#;C-ny^B#vcs51_K5cDG5pE4P?0kj)OFu<H1P5jDjv&H2q1X~mw?ZQ(Dbb1z
zsSkx_TokWK3KIEXQ;H8tSro3aD0i<<Duj@&fj~Tc?w%WWNZGithJ5Q4E{fnbH2M49
zB#D%bV~dCPvvCXrfSPeFo^xXe2%8wJ1$}H615juPqhvg`i9rzBHqj8Ur)_dT%Du~N
zM#S2?;6Am_Mzm^|jR><X!HHw*aeCvmqn>}*W6!q7Vq-r07K{D-jGb3W+V@$M%-OeD
z923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY&x6R|Hy{?uHPO=h+V9^=~VDyAESg
z>M#zG>SZ6niM=Aj>oi`A*-zU}<29QVb6%%$EZrj2ZMD9#qS@=VT0hy#*nyj<m%+o4
zF0)8=UEMLFv0YbpjA(4v)g2=m+jaHih~{?PpE07j-R>46y0+Urd30^J`!X9Z3R!f6
zA@_EfCqwS-GG9Ym`3YU>M;zpfG&P`Lh@G3p(yex5YBiDdpy35CHUkCpqi(i!3ucsw
zVvVHC6TnsJic^PHb_D67(rEGNy7A&1>59&#0@#)0MFnvcH<6N%=YB^7GZoFQ$YUy_
zU2()zSUaPDkB?MpgHl><&U(J9#@*@(dPYlnbaJehIU@DIuJBf>=!?Q<*NHjadPb$9
ze=HK;Q77ieE;&P)GV!433iafpqqj3{C;77IiqYiLr7QfB&zr8uO1^-46PhQVNsILM
zl<G|fF<x6;;f;KeElPAc^3AqVgQ`y~kzx?}^y^J)pD)AST+b*=%gG{DubhLcSHm3S
zs=za~BghZ$*q+vh{hb?0Q|gm5nCde!^J?tR>Ao2s;Ku8l^`T)AuB}@x!e)GkR@o5Z
z^hm?QK~nJhc{d{TH_Jmv%bVpPBnFm;vR8DO9$?bwZ-$510Gr_<nY$Su93sD2AM&Q`
zL<*r5rf;@~Jb3$NdsusS<p9E!4s%cMed}}OpH!C|U6~&o!}Bs3<{M>^*ll2VdWOP`
z)q9yI2gX-da~i~yHTfx{S!7nKTMTh---^}km!4Z=X1?aR8}E9r(;yC;Nc%i#@XN8>
zTc>dZq534Vo~=`i<k|Wpv-I2<S7fM?-+8xpFKLJ~Y!TEU2jY^3^;+w0TaU04F@ZKo
zYaHIHOEAPs6mVf~)(BjWUc!*fSQH94F2gcO;Ptl>g}IS%vw7)huuU%#_g^w`r6aT3
z15WU8$UDiYp&zi4N18JahbK5O)guJMrEtRz-~HNpr0Rf_>rYwqnU(!1tA8)k1v~@2
zOc&uh=z%p!UqXKT+4|(i<-dlPqWdq7j1JS#@d;-~P}nK&{yubFgvX>0dQalBLmI*a
zs#YIzUc)cLKWO-<G`w`}^fF-Jy^Li21Ei4kL3>p`pu1v*=x6FfvH@RI$H^3aB^;uP
z5u#VC56MP6ycaY9JwiA!5e_8B*&=YoJn#<67Z;LTCJ%V$0GjYA2OfYG4v=z&GGD<H
z*ehxX-oifUZ%j_=(1@q~5ft)%;6pk!@YwHz_egp+`_MIl=YJmxiKd6NPig$=MD3_N
zN-rz1E<WXj1t3Q3Aoyw*iHylJb5Xz;97ttEfm^uGCK2O{V9MhK2Xmhtt^AH`+B5!5
zqJpDl_L?9R?=q=`ADor0=_e0xlEEK|LuHnrAT+Q~Js#kZ?~}0*aN74dH9sh+Q^wA8
z{r4&Z#PEPVb;Tfr05C0|h-B&&frX%iKFb-3$b~+2iloV-Pog0*Bw|r87#Kkog|R40
z^HL}kf-Z<|^U27JM8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}pehm#z$y
zV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZm?V5D
z_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gKz%BjsI&Gn1CIJttBk0;e$_HV
z{{JDisb3X8gG*DfO=%)X@T)zFs^5A^Ak?bgx*!ma)o&>f_o)htpA6tS0-MVe(-rK#
zW#K_6SikwGM6?)Dz&;gUbp%w{Nm9tdt&<=k(^i{7XZh5)B^-!sTNK8rAp9**%rHLO
zSNA|Gr%W3V!t54-(QX|l#jPtO;`IV^jnQr)?6*z@1pM_|HX&FB0p_*`4ifS0Q_+Qs
zLf+w`xoIUrkYc~{R|m&NKRF^Ddzl0y7LrJHpA7XPnBAx1DFg8iZ>x;C3=+qWJEJ1B
zFt`55kAk4EMG^n80m_nyAkjr(xFqaB50zHLnl3^<L=leKWmrVW>cR`81jP+dfn4{K
z0E2r-?2#aZm^F^+G9qFk0dANRLg4L!NGwY5s6V<k5Goevj1MU}e%$~F1zsqRIYmSZ
z9}C#>B4u^*GOr=**iY>(geH518zE3?fpC)Lh;R<1P7FGYB!u&<DCvOwbW$cLld<>t
z$PAoNMQvv{B_tqfI{-)DBD=lfj2QmyvdSSwJWxy-*}dNCtKIb%*AVb&#NPL4BKSSe
z2|uro3S(b5s*V4g%;ZL5H2k8#CCykWmqm{u^{${KM&0{a`3D0$sQhAt?>jI@6yqNN
zvYg)l4<5}hE||caO?^I-37nxzNH*}W3NjfX0Be<=5G*j|@1D4L2z^^=4{pkB!`v2p
zF4r*U=CT|j$KnviZY5&4Dg7W+Qcp;ZNaXOs%|NP$TccPq8^jB|0tQYmU<#y_c%e*S
z+-@q3$NUrr8U#{UqJ5DNd{cs}wL~t)XHnR~3ts^_G+uZL7?T%P0+MkSk}^|XkQD9$
zIxx@Ly!enOhlZx-_{`Mw9G{srz1&+)`~cvX1rjuJb|73bYOdrZw@VYuWQRq;dLkui
zQNW@LlTqpovZ@w}HGc+4+=RMTZdUvee&@!Fl=_MEF0Vv+{Fj@q7v_>J61pMRY~gvM
z8}iY-64o1JA)~YMhcaZ)E2|t9PQr_SDnrgIg&e5n0ZNXu0I7Cf8RG$sp6KSeR*14%
zluX7;iE<@>9}Ol>R~Q$Q1-;U?kx;lOm8KY9ax`Lc-YS6-tJf-l63eHcF6Kjet1QY`
z>m!ilF(ce3O{X_9Ef=M2*_c7#a35mWGuboOsZuI&-L#2Tu90#okumC(L)|0j+F_+-
z(&=hr=txX;S#FWN8le5mlg&-uRN;v^uwFUS$dmQTnMN+HH*SQ^b-x&gz~HJ?Re*`I
z9aCf;CNg`Y5CJ~rm?bQL2Qq{g;bOvYuA&eokY(&!mh{L;DNnNl+ugUM=m~LFQuM@{
z2_2$eQFnoy%45Jg4T;RF_AN^~&jH`Eq+_n$h5G>8CQCdVpGx!gEloO~&`}x!-ST?#
zuKn1djdW;t47pkarqQoQ%W5-;9wO4?2awdhikU;k99fL6U^-;Sv*7us66n2>rjcat
zN}6_@3%#=8kgV^WPZcKgFA7ltI@n1M=K=*-t^85o>3bzn16IHVBF+db?*+<`dc1cf
z(K!?<??Mv-(1BNKbvo{y+12oadoN&ysV+?52IzwKUx67`6%c+LdPFZ^h8w*q6*WL0
z7Ga>pF8nrbg3iR$$h~B(kxvF`9Z`^kxFHk{rL4lu=Cbk=_F_@qurcz7h-6~wMr;g-
zh)x;6aJZZU#OgR)nE1f+SOfs8bac{fi(E-(s(1QqP>CgRLmX1YV+hU`uiWo+rFaj%
zz(cYMy+Gmza*|!S;XpxI1dd~>*FZZzqRd$&J$k2UnxHIEQU<>Q#h^cEWe=TMa1MBX
zv_Ln<CMX=(`CTEH#G3I=OD6GX7KICh>K$G==`g?tC1obTZ=#S6L<ZnEu24<@=o~=;
zSdXa}(Rxh1@-J{+R4zL#-9f>flZI`t>~@&3S^MXc&_Sy{5L(ee`pR?;jmQ!JCt``A
zPvRH3(-KRJBX_AZKtYO1MYyVA26ly>0$?d9knhA`ViBZIK{PFjWjGyioSY6KLOn$x
zCHyen6t2@2W=pS_R>Ddx5|NG`b<1rK;8d&00pqH0!B|`<GUKiTIgF`M6e^bqrc9QJ
z`V^R!yMQi$w-pp(kfr9gNHG>vLv=Z{i0tK+^bho}MM;-A0K&Xb001H8@`4d(%suqI
zgdt;btWTnp9ZAAxoIMCbhReZq?!%-R6nrN2t-}@XOPDox-3HecEntp8QSict!){MV
zf@Bl6yYB#TDSCPsr8RRAIDrRJmAA+7Dd;&@q%q;?TxDzsVHcE~6pV`w$KOFDJTLSE
zVCA{ul?kZl!b7;Zw0fD{z;t4{v`=C8xih{p@%^I48s>R(ZS|gmmG5x*9T^1ZP7FCf
z4Z7?8x`%4HeG013GcfJ|iCyw1CRR$f8z2(BKpOy~=nTU?gth2SD@s}wy>K0n#Obc5
z<;{((JMl)?^{QC+DP%}5D2O|Ev2M(pyI3z&z)iZB_6|%+ciyXjt@Of^Nc*6>E?QIq
zaaU9w0Wn=JTY_dfQ78bb>8?k?)3ab-jy7R957qGd6j-Mha0LK8-zgo#1?*;?(Fdyo
zehN+0T?Qv0j(S000G0Hea_2^72rltXT~23WqP|m-f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E&I5OpG@-G682@PI7?K9>0)oe0zKpw(Z`|`Mks9I^+2Z
zL)V2CLY&=q3OPl9TqmaxQ%*czcVY+<^Y@)X#sD#QiV=A|5MS7p#6S$<cgmF?zrnp*
z(;@}tY<HDipy}+5!lg_}TCmD*EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NcG0$UI_bJ2&D^BKxpXfL?m1kfB)L#Lzx=%G9(7t4-Btr@RRtZ7!>Qd=T?{lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3ja<SJm!v%f|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR4#ex=JNrL|3T|EVY2*vO($6KJv(-bwdDAtm;rI3oAdAO4GfR
zoaBrzlb^IAmX;{hiRC9sy<&-q(!e@ZqEgdP>Y`LRR>P3C$LKB8y#<9zBOXgEyis~&
zmgb<M$;ut2igp?^q^?E*kQ^JC@Te2E<T#~yf)Rsyk1AFTV6&Bqjd~?6WH6RADOH_i
zPo&K=WXoL+JqB&nivU4eLCH?N9v1jguZP8GSxv_EPT(Y5?*y#oh~egc;jdLEWB>rG
zUP-J!qlXj=)YMxG;aK$?W1X9z93Zd{2Y;~-R%B4W?OGA)x1CUZtjtqSOjhrycPK0T
z)LWHhfcTg_R4Aw(ycvL{H?ab+>fOu$ta@9cg3<B8C;6w!9M!Wu3nA6Jp0$$d?az8j
z9(GaIU`okTU4Yruivx7^;s9N}VD@7TC|NLABC4z$tRt015SE!LBMC}TrGW+lje1qE
zwt&KJ5Z?@_qREDZv0&6WKw=+^?PeDa?N%o;lV<IQ5Em%pRdy&=`YK};%Yl_a3t?Af
z^Fr9wZWv?bv9g|_I$0UmSimd|a4c{J16@`x%X6L?(4BS)+4)#Yjg~+ZTPsr`La;V-
zBI~u4$&p3f(j>{EZ)LG$VYoDE=D;8ailt_SIhsaUgRYFHtWziZ>XDV~$^gq^cV(qz
zLA<i$X34xV^`fZWZVyK3z0GKxL0M&1X8FD{J+s6g%+m)*X;#*aL^}qp+$<(ohHw@f
zq^bNsNkUi3J<ArBy`7~E%O;QNhh?@$fy9HxeULiL{rona960iCdN^F)ria7%P()G3
z%^R_bK9;wFMIp<h!LpI%^+0LKL!J?qpDe!#OH`I`g=H+u|AIo7n~w(7Fw2j_f|=#&
zVTe_^gR<;q`HK!#<t(ofOLwN%iKRWuE5(qi@>?OM>X2`XMMTT{g*v0<AY&=ga-y+X
zDLiclNV#Y_3?KU_Z`}%vN>=W5Q|YeD4gDC|uY>N%gJUbCifdylriyDrE=d-8J<4s#
zYOv+nWW`u{KT%Uw?om~pg$wlnsgKRg%JQ}4iCxug>8kxy^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9i73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<wt4xnALV{JOD~y8CWf5p`e5jgr5OTLV<Es>%vC3ap@CK@5Bf#TB
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g+=<PlIYk=_`#Nn4^f#%-$3eS@W)0hotQsEX2zgYDcSIUV3u2=@#M<2K<L
z$Rjl4Hlb_s+|8&`Zw%R-oZ(c|DrX3&f(l$+Bm}N<me&^f>RI9e(Xk*5#?KxgBoB0+
zGjL0RxN&Qq#%NtoZcvbO%?rB1e&ZG&duT9kdc+Se3UW;mV|;*=L9mSP4D}@##TTd3
zw8(g7D#Q$VPTf1Bsi!(k#Deoy<x`=;tK)$Y!PGFB<Rc|X+SGjy<X&&572&Q}Z|{ut
zW<dCQ?PXe$BF5uc8N=hNn(tGEo%2D<z;wFkGjja^WuAL<JD=bc0ncYU!sJ28aQ0J+
z=aIXtXnU9yDj?szGh#nm3fRY-9TDLb`A=g?<p$6wqx1n<a5BAsMxV?+I6#R+6J;pS
z1XWoK?n5egw3sWwfe#LBYV<?t5*$6GM>!X?6jove?2kt!Z_tdHxgCz&&dU8*_EjW@
zWD7iVU3st-R+0$~%aw*g8+N6t(0b0N)RCmI<-owtQE4*t!&EMfJ2P}lUwSw}o$p>L
zIuuf-=m5OZ7v2G~ejKTx$O}3^ieFIjkOSqa5{x|Ujmk=L#7;47$p@lL;t`$m0Y+S9
zIyrOtFTVaAIsD3)a)wt`T9pF?PkC3)?E8!FbZ5T3a<zOg`)t%SGyP1*>|pv?{-|SY
z5{=<GHfat6Nko-=wn&*bCh1^)yHePEFxyPG{upFd)4T_|>8M#L=S;72rjsiL&zU`b
z35L>v$W^&~ixMKmbUz;edYMv82a<1)Ab2Dx_ROr+M^c(H4V@|BQvv~rXLjNdq)h$P
ztqjv@<vBW1U1_LGN~Sr|+~Z?Uo%F$+OdTK0>{bfqqC^Vj;NT$amD=f(8JM)YFG?F*
zis&NbXwxpT+L=o!D~K~od+I`EmbTJW9R}P=XI+$JOh;?%*|5&6Y^BUPYSvd;txsgJ
zDHqo#5Vb2~*TV)}IlYcgFzeT06Rxyie~oC%8+PSeOMz3qHPVkA>DGF&Oys#Khxu?A
zkt@;Jm0~SjY~o%~`m_hvY0}SjZW?A`yArH*4k*D|w+5EClD!ut)K4aayK<~c5}0FM
zqJSi87awpNjZGFN^3_WgkTW+*7NFiR58h$ZrrYI6QgX0uy^?{_Oy>1L(ZG&YzP?XX
za;&U=N5Edk*r8Dg6TkuPR=5F<9oh+wvq*Pg4>)tM1y8Uj3HKm<14lupM}HB*7*Ie6
zp65qlB{)p&g{R>2+3*$|5rP0^I6%rT&+39N<5|iiZFw6VwI&1*aRe!0CLkBrxdBW#
zGqwdn;d!V6r~-s|zZaT?<0vk~3uj`tyjFe@>47o<55Q6A8V(%$Lf~*jFbbq&5t0kG
zbxJO%#D&9iAT*FgNIpnAy>QmZr{X}(>rNCJzW@RuToOlYWMP*$^T-8nvM4bgLZIXi
zB|gi&b&CNBN@Y=kKSEn^q@N3sW&IG+DT&z<lpK+64rZjw;vbafE_j&yp&ZfJx+P-F
z*t!Ky%h<k^h%q$0AAY$IZPp(^i5BXOU&Pyy%>jiy3Or{~QsL+l4Jg}!;8~O$UE6xa
z=vwv3!I|tq@$XV9F91<=2?fD+WFNQ)wsUTsQrKxuUX-zc7dbSo0ytWfYZL^M!`HLH
zBrQ?`LFqwq;aC;cl0(ZYJSInGK5V>4Qi7Q>={mH<0)KLpFCjS8YUhAuo^_`53*vfF
z5)5jnQ*c)}ReoI?j+I}4951jdhjXeBu@)tvxBAvC$KSVJDGWm2TBMu++#HLL;9G?7
zT9jaU+xq1A>GgF245-GcU-yP4=7{et#4(4XtWe1oC6G&^`s`{YHkuw3hzKs|GmnQu
z0;4&x3J9Eb1Syfx>KMqI!s-+t;+<X-7vb$_y-CP}V?%rMix79R*dP>HfN?>1o()rO
zQQ9Ev+yP3gkJSZH5O)-nz!w6(U9^S~0uPkbXsni<0C%<Qz_+VKC%&B)o%nXDZnsFW
zi-hdwH(-i{{O9mN7CK;1{N5o1JuBlB%-|yA(w<wd<iyF=8jPR}7iCF?vYdmkh9XGB
zMTw19Ha-GGoU}sRIf4yr(GloffQ(KQ34t~SC5EF-e;a`xbAq^7%Nz$kYe7gl;>QbS
za#0prPQk%Cu_=UC>3E?RrlrGQTez2=_!UCNJc1Czk*0^Ye_?Do$_f<@rvvsvP@RjA
z7)Jv11Ze~PbOgZ{FsQ@wuqXrV#1?&uUu}aLWs7_QYP{e|7bUSr>32x*jiX>sN!p-M
z9VU^2PxY*uQ~;|YsCe(9B>1du=^Lo`1amEdoM7;U0~9tFvH@3CI-Dqa<KGQfv*WF0
z8f=^rg<lKOhH>ja87UmxqFC`NUgU+ROHyI(I(+wq%ezy$hP%*cSr_h&BF+RDtuTUj
z%FvfWT<)82Tt&LJxrYP^wRor0L_?}rVCpD}w4=Lk$jRBFY4pE*{HJ5>^YitquPI(_
zyvVQ9?YwS(9j+h$`9FUA%ZGiOum8#a`(J+^HH!1&r%r`NO&>5%t$ZDbrmK2l&N|VF
zc?dW1Kv`SF`=Ah5lgk}SnVBjlKKUfHa__9<wD_S)eOF0cCShY6SN%l0vR3jP4T83<
z2?+Ca?GGo0jetfA+A3k-1RTf<_j+hgDv%CkPNe2m{`Qsamf>njZp)%l3gSJaMY^7f
z9dKXngqT_`0cM$F%^6$`+>Wp(;l{e;{Jd~u`Mur3abcxOm$KsHzMH>f#QU>=5zZgi
zY0tDTL<MC;aIL<J3!mRhd1>WP8+o`cD5Ot1+4pjnj9aLR$30=(jd-k`^_s13oTTt%
zCT1*|HDwkyl(MW0T%fVo7+lgbtIiP=jg>r%WksvX#n>nplpXXj*aq+`6qQ@);|v}+
zm575P-d=^pC!<f5!~Il*J^V_0fI1@(rzDKA8Mnd`=s|;%_w3ToB9FLVdJSe;WA}Rc
zT~fy$ohyGK4d*{d!+fKB*^y#2)e)4tecKW0I2R;4zRTa2L(M;H>PX7{ZO0XgDQW(h
zMuJVczvvWO;Jn!hTf)EXg!B)~V;FT^bJzTJ2X3s_o9gGb&H9%e5b(jR_fv;eZN@J;
zRxw?6B<1?9V}IJ)*8Uj+`o7t}=*Tm{)RC0y+l~piiKF8u16XyGe9<Y-n+zoRS?7;`
z*Qq^khtkimdAuJ}f89~1*{P1C%<nozVjT~?SGUIEyokK`q7zTb6P?(e-*g)HcAEao
z+8f*H`q!QE2u3)_PaVnq+fG~2`E`W-42+TYllzN~Jm4EUigJI~(GZ)q?tz~PbfsJ2
zufL>=qeTa{zFa4Raff%y&#ZR(cH4Z>@h;6OJL;PHmKjyE&Tzb`_@XYezwWrz6=X+H
zR3h)MJ0hp3PU1k{e!DEc7%K17rjDe1dlF|w9$dXY1?`QS_{(p_-!ybV^Zu^O{dS`#
zC*SY*FFBbu=Sv-_9Q5xOeQX*7g{27J$%-d@W_FY2(ZB2V+;7@Q?tpjw<jY;ah?%aP
zkbz(4w;h=)2yG{K_`Ck|<qmg*ccLRH-M;NOo;PjkXW~7)=~rKzU{J#lG4pd%%>3Jq
zPv5mQoXtDso70)uR_qAMu<tr{201|){2Au+clGd#+lN}@P)AVYCHvx%>~G5E&&=U?
zQ$N4x2rac=>PWry+nv#$@utlF%uwAo_4bR7)PgAhMY+D~=uE3c*7MJd_}VC6cBGbl
zsv{}$+m1drUHoUnZ|u7H7o8r!{GwB~@AG?2w(na0&v@Ctsr_Gc!{eZ<8wk(0-RO+L
z6XIu?Hh=S|(A&e<QIu=z_<DMr>*@M>u-aVajn{t+w^fz>U;A>cM+j{}cuPcO_iD*e
zm0?Z?QAk7ykP;fia+d_wN&PA)rr%i>rb}LiBG8tFyYwns7Afa8+OT(BXSI$1fuUhA
zm#odQE|XH$Wfb(B_cqD2(9OFhITFT3gUj~N(82~duZ;;wnMBQU6lN!=&O4>}5;jPM
zrXXgFa6QL6sW`LDIa9GoMJP^%6?OKqC8Gdo#hr-KHr|BEcDCY8w8)lFap|0+oo?E0
z6pRU)_yU{YJU46UT6yF?9z_|<os-RSJiC3=v(Vo!_R(=~X2V$6ac}m~A^fS$bX##I
zwD^u|vyMjG%!|b4ndJ@Njn88@K8Lw*$XG=i_7K9YOy6U(J_oDEW_^xU8R&z#qYTgB
zd>ehY&@b)|+MZD$dzAG#>#&ZpJ);)usOVj&>O?oABchGkoCe0(FYb)Sppip9k3}kf
zMsUV!gQD2B*9Jv-R<9_4JDcVEq18gZpP01&>iQunT~Z<dXF!<0sesURAo-p6c5+q4
zycre}F_F#Z)+1)^Dk((omQ2MrtGCMC`;XQ^jm~R^p_W&n)f${{4z6=A*UHiLZHnRF
zQ_<HNT-*AD-M4L>?AdF}((i}*vzVmH)6#X=l&MRHV^z6@PqMkp<<~>*pSyE&eMSkg
z=?<-uyN*1`D$7f!Y7_Vz%(+$E*O6~o6@cl`RgvHqVXGkwpYX928m8m8DH$}p&5KK_
zSL}F{W<BF{R-@SQ0YZ*_Y#nm!bUe4QRaB<Sylnv>cY0Z~D)Z6+g73<X^a~|iRoWTO
z{I&&upk8bG8R*TALs5B*2prfdO*6QlZ6P38dleBNN5&|`FP~ed<a339pgdtkfS{(K
zVn7r?(b}{13eHv(NLEjm>*-?k^gRS5BH9}B02u<(<cVOINEHodC`sEwKr)KssOsYp
zq!QzsTelqF+`5gda$dnOF~BVxAWr$JmL4HAo@LjoR}Qe^#q!@+n*9JNI9TywDMD4`
zooZ(lf=8TC){2J?aj}Ma+q%U`po;T;v4na>jIo5eRUi#iJ5{%jc&PZHbL*BPlDGMS
zcGN0l3`&hXTd(xGJzK9BkV!P4aM)b}1;?blMT{*D*<HP2IJO6j#fojAB7ppE6)S=}
z+$vtIMXRFVVmnr9TSjLu@NLCa;bN^kHpJisX1999<}=3MB@=w>k>`T>=H?1PF-I#t
ztGEJ$6bAaZI^<t4jsq%nv$l204_BxVDvVdq$h({C$QaM~nF=Yse|4RrEbyW*))F2K
z<Uqy`<w<rT&;Svst6hB@MmvV!qG0r?V__l$G`tWDWKDp3#oxw~RfGs)Yn$@B5P!Rn
z^|^=>=g+C7hx-1aL<{H2sYRX{JknJ1AR>r!Xwu;kW*ij-FxY_^DZ>EK$}CL~lqg+*
z>kzT&t#Y#_j)zkUVA!!&u>`JAicywR$aZ+1Tjg#|PfHiZjtAc<Egv!6i&8<~!L_rv
zhKJ3m>jA;zi$W(H_V*djIYgh^^N1m+y|_r^NbY5OlzD)tczYC8ob#{>M49=|iVrq?
zNb!P*u#cJ>Xy<S0UO*7N!Icm)YtiIfatpjDXoU^?DVfL(VNc0KoP~!yB@(HM+2e0{
z3PE5XLa16+d2I;Ax2IR$$Ai&V%E<$kP*WUF)F5FB#SMm3MhbG67l}C(HzrUSDd}f=
z6hela532wbq=g(&C*|C8M^-HrNF?%07KKSEIevvEAx*{ZElDYlWvg^Iq`O$9ydfuM
zQItdzBU`m#7T{Y@qD5{F{6;0D(6LboDY<bM1<XW=9jgpBWC~a%upu*OQ8*UI?<mx4
zU=5>$&%?Z>?53AOrV6|WXoMH-W@hrhCc0JaCGw@>Cv+qrsfv}1KACrAx3mMKW*MHp
z!6|H;n;{PQtF`)uU#->8%gpY|QVKT76!0D=G4g=1i%A7YSg=cP1eC2sttw`#g&<tI
z8PexLKT;C1jlGImy)Oz{5s_;bUks=aY*(c)rj*%LDU3NLmh?)>;^8%=d*k1km`6_+
zO+5hgvkPxYAdJ~1t&ydv?V<sZz;<>?K?sC8tF$zr&#`z~QerW$IwSB1wn|HbO_X)o
zk`kNc>S*QY7-#B?fVwJ&abR$j#5iJbmBN^A=1bWrKsB>VXi;=LED|T+7@H&qd8byn
zZNM5^lnw(N-p-chLeE<Z_4q!S{~83g4S&GV_f_Ulmcz`jW%0mIq~J!e!G|fh!TQQ@
zLng0HAsx~oV^hi}Qi7v4;vglaH!raunPHoK5kXcq^;YqWG&7YWB#M>EzK9eJn*bIf
zu9QvJU#OtvCvcdoEQCm?uu4zsD0;~{pPvHFK`mKOf)7JmDsd$vngYKQyL6QHobO1~
z<NXZ3L=2sYT5ye}A3Ji{*E~jr0o_}O-XJOV@zApy1v*dyIVg<t(Ee#iHM26j0bzjk
zmp>Dj02C7?qx8hQ1`XVXwoJzAqj+_;qly0x2AF1K;6S~{0ARvu-AQr$(T493v)1;(
zTa9smN0LGaE9VR0{5A^T0SbyM&&N`SXC?L{Nil85w#wHVLJ*^^!t$Sqim}EowAe+7
ztINs+2rv^9PHG@<JV`0kju^i%Mgd)Ne9&>9q!2@(dIoaInQa1hEbD^_dDAlsz+6B-
zp6|OLad<fP1c2!%$z)|qMA0Vml5b=N7;z{a)t^idla7c46NKc85-nn<bZE!|esrV?
zED9&x!98Ri0D#0~YczzVy6b^x*uer|TxcUEtVJM>nCszz8e1m+re_tdHMY1v3}LOV
zmk0oft&-Rb7qjamIUle#d4FQd%c<>nBAN<V6D!2LP<w9h)uc6KB7s$!+j&PT7XpyW
z<^}3=VfhNv2M4iL(i{Aq)_KDu$dFYM9BRBR3Ma@IuSbcacs5$kAB}U_DkJWM-dILZ
z2J|QjD57LT^!trwa9U7&L}s$C6B<}fR(4U~Jy};lO5#SDAn=GSWnHP1c=1_f%)Q=s
zt3|vm7>5^$fLjl~EiAj|!M8KE8gYW1xirMqvR>Gw400lD9iDe46Ke+qx)nxULXVh|
z?hZnaEK(tc#m_Pg?=OOPAFh~UzaPE{!kP<kGwXsgeYl7Mzk9fdz`g^DnswE+>ycq#
zofizD*GvZBfG-I~a+7t`o;1|8`aB5gW`%SINPLrxII!V7e}|lcMk1^6(UEmvg?ERn
z1Ct>+km{ZcYUIaohjd<8M_`zo`9lQO!#<a}xub}Hb-{n$*yo)XMF(L^tOM>7xe2R{
ziQTw2y3jpQTl7UiYsD~IV-ie9eD9(F*A36SMHy(vUTVVZyl1q8jfnf9@zx7q!!`E8
z!@E;L3jPk2UKb@0Fp?CkYeM;kqumr%)ZvGIQP2vmDK)ZZBF7OV&L>ok0>pzq(+Us|
zZboZFu|{6fA^_g1!`Ej`pquc7S({oi<SjG-PQ$%qZ3>VTo+4{IsAe))P|&DdY|0Pl
z2nDl*$~!>HZbH?(@(*GP@ReB8DFio&5jXEec&Yya&Fk=8tQc8-bfSmOCAb|-Kzbb>
zg~Md%?{FBHQb0SL0gFOtQOJW3lrL8&A&WYC2{<`3krx3#uN|Fq%%Cv$qU2w+Fea`x
z*#PSR@%TETI82GAz#(}N(8#}Ug*S`G3KLN~a@ws4Z}U3Ui+{l`IgW#|R@NGkc^~y5
zH1ES+(ZV$$2L{kbjxDcZ!ba5!)A&*^Vj5rg4lNlSs0v4ra)A)gWpadc#Ce!fWjhST
zD~gz~%W3R6BCuGQAKC5X5Qln!SwOZ}lz}$85E^s3I&pwqoye_Ua!dfrEM6P}Z{C^V
z*w@93u5R@y_ChWg(WI^M6+*=67X_{CQV7pHb_(DbE@@M$aaYa@Ib-USQ-YRRIadL0
z0=66=<e8`plJOL$@@JP-b+z%|@%Qpn0si|)QVx~YQPV9!W2gx!bwJSM;OYZ8+-5?6
zMs|TIGnzo>CSXXynJfz7$FqQi*@IU0(Cso9rmuP%0Ax2)=?s9jo83~WhDVd5?drn8
zc6AXLe75kBhKIAM<ODEFO!$<<r8iSK31-{LVb}9@dt|6Rz686UsXPRd*Nmu^i_kJW
zA6uP<JyW5*faDL(0B_o1Mlc#G2<&e{!c5@*Xy=DnFUL%Pv48+G)!glArn4&P0GqaD
zMF*TFCS7}xQlzS+1J_*_YCauJm4CZ)=_eodofbB^F1vH>0ZdC{nhEIIJz7=H0n1p`
z8@jrndIPM?Rs|fm(p9b@SNbKU6U|(&s@`C^U{$*TDuh+>2B;8L_dH^8%~ZYt1w>7L
z*G0)61`9ejHJ&9$AdKV^Ktbr-(#(-u6vKe42FR7a3(?3xlOsvVDm<u+(4`%5CMK+a
zjyRK`V7xP1kWv7Ho6t@PHe!}P>DUZXO@KABDBxxHRBZ)F&{3rJos!%YJUD>17e$GQ
z5j0^Y6{m*+DVKEzK=w|7%~L?E9S;IC;R|;Z^)(<Q{9_7aV3fpQ^o~NZlo2vvt)o>l
z5lUh#REh8wF!{?n?TT-dI3I$PGsy6iop6JBdKV%<C32H;k$_Qh>?9rx(7#$93)M1=
z7Bbg(Fvy|9N<?N-*%}XqqTpZ<a5~CNlM*$U@CV7L=3-P)$f*?ER>@c*q(}*k9q}da
z6vLW9wrP&sC?_veshC-4>YdQRZ)^ct{N5-zsjOAS11Qu~Gp#cJ`qaokIUg+!zIxvO
zFtYO&`!Rf)i{2>bI~&f)8>~n}BT9Ax^7W1IzDTEwy;NsT*DSEqXV)x>GIr@ebbu&F
zRz@p1i$7|bXHh6-IXvSUv5B)!(teuwK+35tjBSHraNE{e_9E-lLRe0&_9siu?UY-*
zjBU=sbvy|URky3Nfd%mDIEf;8+kq2h^zdoq;uAogvqpk@%`htVaXx1QWj{I^fNJ07
z=wg4B3-tFHxwy~qck&;YWl@@tGr|nIR)8~TT7jbE3Piop$9UVT;wXv-n6PTvbLzrD
zuK9E7!by+<Ak)T0fh_R*(e;v&2*`;=0HnZu>rNVIvkUGCB2Lux(rzBAs%?K?x`M#0
zd+G`zpus(L2Z38R57PWLl_?duzK8B|FyaP!dEMp#TY=lW<J-RJ2n|^brA9PF_=oC|
zBWqx96)kO2mLOFbhhADw16<3ZWPPD_mxe_y{GwsCyEH6F1C2DHq_qqfPTdboxOhsc
zg6Wmo73-H?RIXIN^tz?q_9_!g^%hHi-BNEc>FZKAOd2kEXuJnV?3NoPfniH;Zr7Aj
zj5*Rw6UukH2G>v(NiSZP)aV;cGz<`I7qw`C900NHsK>*L^ueb^ySVPEBzke(RV4Ik
zdexxb_SMvj(`o9(>HPYHY8O{tVNdNcW_)u-r+RUjPW6IhPQIA(I6aay@Rr1&C*Mp6
z!D{nXFN}HK>Vz2hHo1-YifxnIm@i#s+!!N3nQ&9j<D(&}uins$GCt~=9qBfB!Q;S~
zLwzvf*m?1w$AE|WfXSN?hT~<5I7jQUEZ}x-n-PW_?XukrwAl$#0T2~gJ&qu;6E^a%
z;2#W7lRZT^GBQUk%1B!n2TW54D~pdueIV1Ygk&~Aqb;NfLb5S<OqDd4Nw1>f<5nlI
za$unwV#y-gCOR>2q%q`66+KqM4LgCAW1<h%c>u@DR4JqZM>&j>_?dxDVAB||AgNq9
zgST4O-WiU(evZY}iDT*N#L;y0;ZQnGQo#c>Mr+A{yC?&OV2*}nG2Oibc|c_?ZVa80
zMY$zFcNv}Apfz51Bnk_LWtsyz*$XR0i;1k@&1s$|7!l&0n(7lUm4~Kw=JJ#wo_X)q
zSa2I&ds9^X(VPZ)Rnul<lRN`23S9@$n(6^A5CA?r4jBK87CuYQjH+2XJu@m+P5Vi!
zQq&IPyiR_nab5?%(;lnC-a9*GzFK4aQNbrUjq^Ikoo9hg?Tk5Uw?5q{^f$OoXU#2c
zQ#xq<YfiK2t%as|JTy8qnp&8d(HzpDgO<TW%I0XD((!PXoz5GYPg_rq9A?;wjzV*6
zL(w_w^u8mz=SasMx*-lu^{$xX6COfzyXb0+*4({}2T18=)NuzlwxK-NO6a-a_5?HG
z$d=dh2on6T@dqv+EH*4{G4ii6?Z<k<XF5Wax=t>5hRc=PPzB9;M=QOr!V=5sX4bnl
zVy90ZZ<S7uz78cCX5^V}G4pg=x2!>SY>w^L>F<|Pk2SHbqXvOnT_+7JEQfVz+DJ0D
zPK(xGz*hk&wgLr^B!pmsm?9+DSWB-l#7pJ&TBAHkgT?-07{k(Pa$A~e{WWZ5>-1GN
z8fQAquZ84tp%vB;C7ZRza1T|IZw2Xt;WBhU${Y$-AJ$c=y;Xn*IobvM!dZ3&pOB#d
z42<{_OrbHfgv*U9*i_uIHH7wPKQf@q<!xg2j|mi-**~VNz{Y?wM=K+8a<Il25QXhD
z+II>M%oy5}|IV-;sR+if9s!*q=cgiynDbLnM-94mMkTFQezogY;nFr0iEWA!(~BNY
zln9T)&mvAt_cm<L$09+b6cwh2tD?eafo*uOnyURaM1>uujM9duyQyF?vwuuwj~i?|
zruxYZCal9$mbobuOiwOrjCX@LTE^6oJFvj|RXnG7=%zF1qN?TH6#S)&O~GHWVn<Rk
z_zU-#osdikeHM~36{ydAA#*(!SoPkV&w~b3Src|cJ8?ibop<eI45;=%;+P#l0^}l8
z)&aF0IYdPANlFI2o*LejQJA=GvPzUGt9lU_smZYc4su9&rjZZ<`NyXcjZE<W4dw4_
z;5q>^?P}*KgSt>QI$CMN5=>9z9L3;i>}x=-tq9i!=tWaOgO+y1;WfofP8hlzPK38g
zzG+n)lJAp2t#ZXIQqGWv`Wuj8<P_nb+0H;!ZU=i%7stljNI4&>dMn!}=S)S(fH`Y}
z@7Blw3bU<%2Nr2WyW>w%ubWMOfRkADI*dlRsSpVR7_3cR-z!BXyU{pijJcYw0Wu2Q
z=_ZUkn)oALn+BxUMVX>73Oq#<nKTh84yBfvG!agYc6Pd=g?+>_EQ^rg^t{{bX0XMi
zOV+Y#lud5?7a`;2lP~wBfcle!<bi4zFH#1aYXNSo(qs_jN~%d7@S=-UoHHq86moIw
z5^&|slm;d%8j8u<g;)$@=+<Ru<qR()7nILHCLrAb^Jgl9gyV(<|7z6IjP}B-i4Ax>
zTzsY4%~S@73$2Kk97D#~uZu?H$oYxkd$uAg1S8L#dAUXooMO9N!*9w^;qakBUPEgL
ztK&7qdm50h5;s$}40&(NmdVjr{5P16Xrb$3sFMK>!GscI06Q=hk22tun+i-BqsuN?
z!H`^J7h@PKZI>)$WsEhu_>VbV!c`dY1MK33LKHH)s8sRSIid}pSCR%4{ljivAch40
z#f!g0YXxY&sb-kbK6*>#Cp%2l$bx0jt&1&J%3=IBv*w%(po8P)32n5W-dc35V{8vh
zkePEZ0uvGNSQHZSSExQS(P?dH!WfU-@E9lFO;Kv@V2aZ^RJa&0!`wPRmc3P|)rMsC
zILg37hBDlbn25t!0NHji6ZO>WnvxbF(Yd3KIFh;QxX7NSRmYM3G%`2ueqIPkNf+_c
z^?8dw;HPoEKaN&rs=9c<#8Rh)7Aa6cA|sets!IYDzw9BbFY`#LE*?BzBgr*?hK62M
zV>DC%d)=JTVj?LGBgmCHf`kc07Wry}leiA-LB2k-rxpQ6)65pH1loxoEh`YD4M_EI
zDMbsCretwOcv&TjpPJnjtz0RD_qCJOQ$vBVMd9QEsp2$x@fIOJ!+*}~ZR%++O0*!W
zN)y*9Uuoi<yckHM=KI|CoNzF7L@WQE8R5?G7z0XFQ@H{|kY76s{hLYQgVP5(1d5a%
zNy=>P5(mJAoh1&5>UCadWEOu(1MaFtqBL}-@uQWK(-xmSHFk^~Xj13REE*=FE!`h1
z1KfkE%rY@800%Jg#BgHe+C%EwBC!`yK~J$B=t^diJAf&ff&Edtt(g>nNpuID36ls9
zI>q%Nfp8aqyJ_b2rAOTc-)s2NnxwUD0xkc7D$oS_l41}H<>{K-*M>y)CKvLe1cyzv
z%@!#kHGJ!qpLcN!&`376k0qo=oH>i>XEe|O+3rn#MayjWhB&p=OgIhQAmN=jnxgEe
zmN)p^Y!J%-+PWkUZuKFOtZ>Kq0BDMrj7P%r$S46y{E%)E1c9~;3*`^RcobSnwADqa
zZZRS`b5>F$aaUlBHMmS@j7du3uGrQsp=zXUhF7Jb5cA?Va_bu-vlk(dYWmhCN7L&=
z(Zb&&Krw7m=n;BblkdTRmDc1}Sd>JB8C$1FYiKH5Z$MOQs&>C9$*Z|_%hAp1m3BBX
ze1K2VDe@87WSX}ux0zr;_|CxaZer3Iviw`Sw{FS0d+QdwE0Gu&9j>9V4uhs!2vBcL
z$tO%!ZAe%#MCCTwu!C~8GR1zP;zWamI^NpxqqcPkK6Yu2a91q~wreK09)g|@QW%xl
z1!sHL!7zaQ({(T;9&tlp;iqf`O{U;QN%$$>IuR-hwJ17~vZTNy#z9jC8Ix+8^3Dt;
zUYm-yE!##@aW@;SaK6|DP(jLhgMFlRHgfQKp28W|`psYiChoS*k0kG(txNKrao`63
zU6X+|C~?cXR1a8p8Z!_LLD9`kVvJ%uUI##K{G)lD00}|lZR?e|a&7CCz;bQtl)!R)
zBf&xySaWO-V9^c!Y{K5T<b_awPAkq|my*cQ=-B`t<nqd)MW-FwsV}%Rj6saMOY9^B
zpWY3FAa~c+3oO64Zi#z$SGQ>80yuH+WOjfnv?cPxLDEPxL+~;SVz!|j4&;cY+-q7Q
z8#s1+B2}7B+-!%G4JNV}ilsE>iPOT_R29?`Qt=29HUY}M4En7N(d|t}JsMBjaI^?Y
z$p@t;1|=8?+iR2gE)ut&#JU6@5is9qy)#D;Wm6qiOFlQ1YNeI84c+Ykb!H^MrxL=C
z3>HX2NYA*$+#86WrtxNbXtc>$l^A4Fd1DD%11?7!df~%ey(o`{+Y-dIrxVanb7qmI
zhMN?AIT$_ld_a-YMJetk)|U$V(qi5OuD}HM2pqxi0H`%}Wjo*|7=Q99V|<(1vZ%?^
zrcUdPa_eI&v7}9&)=6k{h&NC}%C-o{eVaP0HwvFh@D{YRE>=s-0dC>c9u`Ggcu_Kt
zs8}<ieQ~U@*kwB0D8;FS<Sm_zBw>pLW%2GhH@+mriZ3A|2)sIWQrq~jq(+s$Md;fk
zLuM}ek&YsbZ5AO)0FJ5lwJl1B)^%-*k{5p2lh{qDKSl9vfbsD%206kYs)841anFsZ
zLAZXr@#d~=O3F<~t~grO8&RH($7^BkXPakGV7ocCB~}HrqS!7tA5}-K+LD{WifuK;
z5I$9GlgO&7TTx`AO}Rf*8%`TRwd1sXo_$-c9ro<I5(FJt*r(67D@iEM#CCu7Z5gM;
zGk0E*RJ@AAMb-C09#oxA#}O;|)sdwte>&F$z^1cLl>&7(KF@ZzFGnDY4f2FlH9{W3
zRk4r<byYRwS&q_&Jl@Av9FccMR{_PM)IQCNMwJ*3-A4WF+ig{)8*!mkbw^x!TLnnm
zi-+n&*5%nxFLtg`Rc%Q_%XOpM*;t>FN{IQ*DwcKaSCLDo23sLast+udd6bG#6*Z}b
zsOqL6S*{9mQkhZl&h)(|r=CsgNNzow))8e%&P|J|8lq6Oj;+ur^)VD9U6fHJOgFvn
z%o3*1qJc49g-_wo?Si?aLRl46p>=LWS5q%VS=NJuu@`Txih3}_LHVunuYta^7J>GV
z)R4D=F2v{Qn@I%qN^O>&z16C<0dUYNXbXpP<ifnG=8IC@LLQV&36=kdN->Q}e{w-<
z4gIt;hF5Qi$j#APBC_49)-RtaSqqq+?XEm!K6Rp=u<x&--cm60y_5xs^~#DFDdv>#
zuHM@A$_jBtxF~)oYadsqn2<t0`3CHY>okODc9}a4;yLxr;L)RX@jV+-xY;^TdVDi=
zAb+QCwhq)DZ)N@JG2FRz3U0T#^$8(sSH0ajxJ?5XN|6fzV!iWwyEh9&j`o&0A+Gnx
zZ+o*R^!9A_gdFR$*%MIg`^{|8`?;GfVz7$gqxGZeiZ4pAw#&kbhsL5%Qy6IhkEFtf
zc9*u5IH#$mZ}yI4ePk~_d7=Z^QN`35KF~Ll$G`yl_N8EFryF%l>_8QFw}E=(o6RHZ
zk(bFMP3ToZJ`7~h=CuXv%9R?bKI^R5>>YW$_dd7JB=_K>KWNNb6!t=~@m^aWrNz5;
z{sms$Tc_{|c7>bK`nVEl)hl^bGI3!zGP|P^!_l3ENm+Z!ODJ%u`?>Xs@puUZ?q}bG
z0ynbT)-CwsZR-{T@)8SNr(S^>`3&q{mM~nE-nU-)7iGAPQ$yB}1D5OVE;Dq9jqld+
zkZTnV2<v#vfF3zy5iA0|3AmYjZk>`7Iwj`G5;xT;5_Y@GBswkf&&&T1^6J#-Cawp+
zs{=lKGwdrI67l7`dd2vwFesk7ee6D!tTLNiIOx{sV|S^99F20R#G)xAimsYI%BRx8
z0@+9TRB-yM?giaKedwNt=cp^@N%1*-(A+(H03*-^n3{bbQsCge>SZCpBfO81UNaop
zL%wqqB^qOMf#nRPssqfUv&P5~q$QR^+aF;<z2cehj_-pZI`I7Up^Kk!L%l2}s4COT
zW`anfK5!+#2MO2<Q1VNHVP&vUSIHJbj!hqrT&e-SQSQ|E$}ImYg7y29))yYuKIMOn
z4&^4p2{=uxyrM-_6xl+3%1MT^ZkCe_m6oRL;IKFl!6c;g!iVsTg9)OSbp^>xgkeca
ztWSk=O+0q{EMdu4gDU$NGN<}1alsKaOJ4GXnnDsZm@^jMOrtkHq)yPF1~8pI^(eSb
z;o5v=guq%#g5M-5nI%67EFuKaNlG$HHkb=fuP&HWLrJGT*~-CI01Xa-sfz*;RQ)RT
z0hqFc68dBamC%Ng65~@<DaK26;`@IJ;I>z|)fI|X1zTOvnJz3hkaU5rl!SHMTnuw0
z8gCaWZv;`r;FwCYqFrL%m$dr}?*4x1JjXxwOHTG{;-__mUl98(&Iy51{gPe>c&mOf
z9GqcM{VkR$=e372<(+fYQpEfDeyjGp*5NIbDL%#Gjf7$jxGx4>Es4Erp&+n#Efn5}
zxAroI&`}6!9j2&N({Ju)l;24RvuuX|+&cEN(oVmn;@`li@3-FWfG+E|tl}6~ub3&M
z(gp^bBG}?N*cnQNicVdjR5{FEwzC*!fWIleE+?%zQHBayiv%eFhFiZSBp7)B&nY}G
zN2jz{12i1*>plZAyx$7n%=?5Uy4$fJ6}pMU<^`h1;XB4w0i009D*y{IV!h0GoE#zi
zJ_UKcC>6n(yp!JysCtXS@yBKGu*&#qUr88f#x?pVb`z(6+5K*4wvVom8y33$R0JpX
zNd<NRAHJ745FF@&$43ZSqAOB}unnGy;>^w1%R+d=GV@3W$sGA3NMuDSlMfU2?Ku-K
zQqjF@DIbVo@T0Saz+o_i_9y=pvd*}#2dD8PB@=l53-}UjdysJ0Rqntrr~b&hia9L`
zL;*2uy)1()Qm{x2jn1nz;7378ZhHkvJ$bn-%B{bNWm`C=9Aq9Bekv&vhC)YdR0DYF
z!dGQ`BmgVY`py=Rtqh6(ha&c8Zg5xqkcLq&3UdiidTAldp8BJl;>}!wR6zrm7VVrL
z^QTYN<W!hb1c1fgJQ|;4I!ea_GOWwa#^NG=Dh#@vBXD++6OsrcRnK-2*4zlro0Q;#
zio75w><EZo&M}S3i-I|(qUwl@TJ0FWDNXoH-NQ4Y=>RDvplGQG6nm1wq={RA#hIuP
z<ELbx9Ly1@$Cb>H6Hxl@nL3pd!{dA~dZBNCg>JnD2LUS(41|w)!C9c}jSJ^!QLd3#
z&u6A@m<1X%^I!~oqHQRG$3_#X^rwQyyigkqDNkOg3@GK}1-f88;jHnYo}6OpD^Nq+
zWIJjA{BTnO8)oJOSpbL)S3p$*=9F9Z7;!v%!3-EB>edVgKCKK@Ov4K>fJhNu@BlzL
zbAbT>&%rD6KfxKi68&NG^i1qOK#H$d9zR0CyfN7a_y?{Stp>0IZvsqjmQ9W~btqRV
zJ>UXe0b30~0WRoC#DE=HwKsnUMowqUR!~9|E2$lc^xh=(4YB)9(9VX0cdra}gm`&V
z790M}D<QpkK-)9V842b@yH83^Q^}ry%Xiv8S@g`2M1CY`WKnB;7|YEB@is9KiG0Ia
zx1lLsshWBt%m`Aey-iK=!dR5;jl5}B#y3E^ys5xbgQe3OA481j^2Xb(3UdR?BlDYA
zGuPy3$Y^#MTC2~!{ciM9^0qqRCdicMBMTKICy?Omvd6Y=QSE^F(}p$D#Q^l>MPZH}
zOr<V^ErY{cu*M7y^DR*u7gvrle<*KxXN|u_h)H$<TqJU~Z>iciR{E)&a2zW#{5IqY
zd)JN9N3`&j)G8N&U%}hSyXiY=Kk=?BCXJ^qLouVpSdJnofl}m(mTM^59aSvAahxJb
z*Txajo4$l2q|1=FNbB1j{~fz=OV-8}q-u_=gy~%=c!48-1cev^ke99<ix@H&g!!T*
zD+S-=7Ohm98*uTx>(+9dFqOd#q(-k4ZfBkNf=@!0tp`T?YGoHeBV}Du?@C)m{_LU<
zC84KY;<AJ@q|Cd{0)&)#*I58Fsz)`>sJ$9Jrf#yZp}L|4QNcARg$$7kwgE$+4?l~b
z(naETp|WJYH!P@8<Q+4<u*^C)U_y1`LMDmb$n86Kj8K65Q7?Y^!7^VuRMUs*l_fqX
z9Mm%hWkcu9plsm0q5sfj>u-bNL1h#!J+D-A_~$%=AXh6p$QT$wY0-r@_2|(ktQ7XZ
zzv|D4mEu{M1|x9&Jx7ps7WXq+LxpZWGZ1b4HGK?6gQ?XOZ`sC-R{r|b-}CEJe~$rN
zS#1Y`KXQ3JGuu(*#ucjB23on8<K|y$75I8lEN2@}w20LLebft6=g~(9_;Y3pQZ-L>
zX=vr2OOb{xK1vkjC}z{R_>-;1MG&E`ZkQY@iZ2Qvnf&cnT^$f5*`})p0hva$3XF+e
z1jZEd;L>j<UmVWZ#x}WZ((_>;cGn?0Gm6DoAvxm9;<Wd!0blAx_^4aGI9}+3s(-?e
zviKp6@zEcFdC0nQ*GY_IEtjXL!JK(SMXOwfEB!I<I-p@P^@0+Bfz(|`HtLne4`GnY
z92$QDTr^zgF1R0*Ty<5CX<_nokMxXo;fbJnGYtuMF0WNX{wNB2B_UJ|m8>~hR>O4{
zj0bW99j>m`W*^RGvJ2;ev_xmMoJENXNA9t9abN14ba8JA-R`=hlo|CIlxg-tNq~LR
zRl28L*%G!LJ3xR~?AlfSXMyIW1WkY#;vg=Vg)~dLY6vyhM%@e8?&hjfcfGmjx{y$4
zJ}CHft~rf<N4vS|0yMh0>O#A_bJcZ^-CcdagBy<mR+mdsuDt9cH<w=T#~UjzSfm?4
z{;pE(i<IlAHzrJf?$oZ^%@bKy<eguQA0oCPce3!5Zti4(tK8hl`R}-A{TApE@<LgR
zFDc1&y=ak6@2p7Qkb}>PegQTLW0S(m8!U|OdIvwy%87V^S}m*;xK<BEI*Sw#pBN69
z^YBF0o8jRhOpo2MNE73M?4a(byYBU8kU65@p@#8JJXck|3#7M6O|grVOY9nGk8EKR
z(gx@Z(~e-m=Y86@xW{SV;@;elV!=RQraod{qCcbfY;mTar?>|^C;dV2sh?KN6h*uY
zK6P3K-zaIn5L!u3ER3Ci$CO%Q`|sok8GR7?w@8bU3}ARO@Pgk7$q>~JI4AG;B3;>f
z^3&W!Md2=b2usX8^59L;Pwo-=mI%)LPI=Vp1BlL;WQz-@qk6*j?Z%UHr(9znelvYL
zDMxQS7R3mF1in+qJ@6BTk)7$SbIczFh+QoT4%V}c_g2XbApP6;Rd4`qw+R<*A#W7O
z4NQm~$!(hyBfG5x9m#DQ;npt9Q{u>&ui8-z`PwPZFZ+-oU$s|zgKc>u^;7#0%t9fj
zonqRFc|i8g$4Gr2@BQujfH31>(ow}~Z*Rv>;>vf;oL}mgcwSt+_d36mpWQX_d_?r_
znm8n}yAB{yu>Vxsq7N|wV%OodcV!~=&g<?*i&q_?{IBg!iwXm{oADm$eY^ND{JQvn
zde3`LRiE;Gr#tq@nh0mxF5*s;1j;2wBo{7btfKQORIMlvr*CNm-A^eKV6K}KkUR<8
zq)LF3c!3<Hq;#4a{6g!2a>U{hycnxq1}{dXhqBa#E1|5r>yI#NANretHZ{VYv4h>G
z6g<vyO2xyRE-7>n2HFdJ>U^QWz_TC*w`kSB$Q@eMFJMQa65Jh+ZWk0-R5Zyprt?UP
z$M!^o)}mk;5upVY{QyaNd@fr;in^<81;T&pHPDBt6JP^+W~{}NA`8OcMT8j+uA?eW
z46Y+9PK?egOZ6m%f7H{b4_6P)hl|Q5R3G^gB5J;j1gh9KxXLOHIJn4+|LUXOoG>2u
zQIAfn(Wpl!#((|tdR&y)d!4zGebk$iQ>Zs5r*N|u7la#DkxC4|a#y*648QV#yX%uL
zQo5x3<cm}l11E|x#0x!nGx;J_`L1c|HqcJNq@OOzIiU}kKJ#rtLu;Q+oiNzRqx%16
z?QM20%aQG{`F@HV-aF_re}atQ)PN<x9vG6^Bf}F3x(1Bufn*4_-`<B2Yprv#)b(Xm
z_C*2RA0rPpe>OKG7+kS}rTcr{jU?PEz2o+g!K%Y8f~ieT=C><lf)L~FYMCI=fIp@>
zMw?YBp*Fu>rG(o2dK*gR=~Ggu4UQqXt&n`|!>z>xWhRVlCNN8nq7py>%a!ggyk}sy
zn5y~L!bPDPx<}8#l>H&k!jvUJ&jNjW%-!~O|4lj;;31rFE5L{NK*UOezhNEr26s&v
zSv{S11X5x?>070Oa$XWBS(Dq_Pl__Uq*!4Hh_mT5Ljkd}DWy@#*2`g=Fsn8`9J+*A
zT?x9e;c}NYaD2{k9ZwJ{+0^D=nd8#|jrRkf^A%z50DF_o?@|`R(~VCLU@e>PjD-is
z+;{#|Af@b`J~djF>ScfzEB){_g1`x9mXRIu;^#kh`StO!$8T=~h`@T^7+ic+UB<nW
zs|Ifal(8^)BakUj1GfR%Cu72`Kk4xx+{%Q&C)_HpNzk;Z8V1bE0MJ|hn&2tk;9#z!
zE(Em60fA)V+a<h;cRVwA*wr=A1asB<s%V0_>V2OygNs8s2#e(ILBjK21*o!jmQ=ur
z?42bwxHgnyFRBC=`vh>vCjJrc?42DICtqbpE#Oq$%b{2fHPI|zQQ%q*<D(Ztbj^vA
zsyjl|0a{@ky+!a}y)PRlq9$=835l<dOUr~r;nI?p!{PO`PD_A9y>Cb7vAR4(JFxDC
zEd7K0z$OCiD>}HA<(SHBe<w*r7^S^)q@D$P^qnU4Y}}yA(oJSa8!}?)3K_Zk9ITb0
zRN@nHmG;huT5*+EP%jBfWhn6)kW;2Gp=TBtD(}j%+JU$-5wJ``sD=`79U>ZNG(8h(
zbxh>*lMa=4hEc+-2B9)Wn3b6CpDS7gJ;;g4B+&pPRHrkMbUhfQ>YZ|fmy6{o)I+O>
z6e^-#tRYy_m>iUFF;fJXfmaLQisxIUy{^7?^&Wahc`6OjnWjt%Mif=K9v-CV&eq=v
z!ntJL3Buvj?%(AH&$8yJPWDP>VaOY0Vi_X(%=$s8U`e5ga-1g>r)R`Oz4L>I5I7y9
zCM2r<op31UIq8bN2mUY<`x_i&y%l<>9@%Sq$&4yiELw$6LPtTP^+qHiL3|;WYWN7{
zG%-LS5B-zaCsu<iM+tR^{xW6dVaj_`W*;j$<foun=&==a3;na|Kh1vwx0NY7lp&VW
z-g%o01kR>dQ3J`dF^Ly(T$X9b40(34&uDl9F{PE>Yn=>@5BrE<afU=SCN?nZTqm9T
zuyrn$g5VjVJxx4gTo7*@A3<7tTff%A^7R1-yh||wgP2%s8eIz?3;eDab`Iz(Yp{(C
zd|1}%3fSo9Q_wJxR#$?)A&YJ<UVP7kkWMZBQJ_w({Q-0)OV!!NjopNtYV>IkR&^!y
z28o<XT03rQ_v6JI9E59by0p1rTH6{Ajw+2eP272Nqga$|AXI?|CyL72(ukH|teEhE
zS2eBm%BsO_>uxk-XORPh!>RG`O9gcIM|@?-h;bzx0Ei#nm|LUQv1u_wW4^(=1_G_S
zqjQu|29aX&UrJv(;8$2ER5ZWJsF{c7D58W?VU@drhSC%#Bu!K5>5?p|@?X<l2XGpy
zlt%tFG~T}{G&C_d_i$0a;q5ffEc0;C505$t5U-hm2QCdJNfNX#=s8bnS5hl)g2!5*
zb{-vxdN;V_ZW*HlM(7Qk2ND9<`UjHr0lx>*;f>J0f&|kG#!o=Q8|we?O#O}r;5qzC
zu*l)adj}Tqv_He82LT^YbONCQF9AvnWvEH8N&CD?H9S#S(~B}guiEB2(!wZVpanZ`
z2xd^;RfD^5hN<_aI1s!vc&=s`JHHqQf>OpNh72aS-DXH<z<D=A_7PlwGloV0bQ2F+
zzsmbKLz)5?%rj&JAr5qgmK_OPW^^qXEa_-kGOm~&&X+5whmC>yV@A{421kb<wU*&S
zj%}X28Gbldh<9@#-Fc5QJ=8QJa9z7Pi75QN&MHO%jL1((atXWZO=aA!D5Q<N6z-ZW
z#2k@|+KN)5LbUL*z&G{|+OndDa4j~_IyhahMoxxG>1KdfO_wP`Y6aIGT}*E27C|G3
zg9Rw#j*!F%u3dXEB#y=hDGr<`VJptN=|jq4A(q2sT$92;wB<$`0WlyMi37Z8KPVCa
zZ}?}%^l^-ch!gjcF}8ne+gbQnHeFW6!2KN>BjWaVaEv?saab&iaiva&mBDR0x85^?
z>G%7kZp2-_U#ctak}C?huPa*kN%f5$aRU}?ia^U2Lr3jBO^6DuMYt3>ic)n|y9Kz*
zu7qzVz_B3)Fk1{8l_FjUHQGZ%MA)c|$OXce{XQQp#*IoPA&`AjBY^^KZfzCtDNhog
zJt?Y*BFTp_a(y?HD(YK{1FW-iNhNK@=_&JqF;IQMeQ69-U%XW`2C6S!!5M;spLfW!
zDa5=yi>45B9cC~|@8D_!S`Go&4@A`#u6(Y5vEG~;Xf6eNUkQV~0TnU4#<}VtrOgyj
zZVD(jO$}qpc}}-I8P_eH0=njRyt{$<?Hv<u0P9WU4Y72dPx4ciprX2EyuqJ7MOJ8g
zeT45Dyz9I^DoMqZiU#0{YDkSUhi}?sv+Pwg1`JKTf}&73yic%=ph4Za8-vPqgKU5a
zPF?L9KKiMDued$kj9yVTO~1|+RMXl&_>-;P@h2O;Xv1bR?Y$TrJPXnbpe3KWV>8?`
z+*?WN!|j+G)0mv(67O0?b&-3>4qbg_33h`Zk5)V9%qt;doVsp%3|s9KsM9vdH3orm
zhO3Mzi0YLTyGB<v>_MjEB?#naVbmXp$oIkJjo@H0rW(W9=X<|6q95T2V1q_V39#%&
zxbv#R0LJ7^cuA6#CEmY>war_JD_M2rt}4|LUN9H~;CX{!;Ooy@ee?{8R;Ln>8A8@4
zvz8gs08BacucT;M7Twy$$oXmSTKT5rn7@+hj(s#m4x5U;NXdQU@~N96a(Qa6z_rhu
zgG~)m?7Zt>vc^ZHm6#1xsmbaeb*gt-5V$&;85{CYlD*S<K!S!TC$urDpIHX2?43#f
z@{^LBzHvS(<?P9MY_OZ=h>xa<{|RfN9&|r8xq{8#j7nJNZdqbGWK`O!Ax@?Jt^!V_
z%~C#6YQl?8X?^^@xSv*a3f9%Ij|$mM?Fl3x7z_+CP!UX}Bz-LfSYXO*dL=crG8hZJ
zJKv62<bIiQy*kq3Boqr1xw8NLqfYg|zv~orRr{y{o-lb)U{YTZ)C*F|OeN|yq;j5e
zs~QaRE8&3<`AVkZ3$LUo(CVJka1%I13vaOaCnFu76cq!Sd_`nu=<f{y4uiMn6Dd|E
zGhNq%a$tRbRI7n$M}Yq5?;Qaase(tJ6rEz3<686Lw==CAP@ZIRcf;M~R5JQ2xfXYy
z9~H=L#}(k>w&UvrM+%d@Tit-pcetz}n@zT)N`bafDUyhf?;oTpN?>3PSnd_^{li-B
zGDsXp&ffLnpwSetYz{Ek>`gB&&!q~4&hl+t9!j!WG+Cr%z9^6615vU*zPA*zKFTFR
zGK|J&6u+a+D}MXcbSA|W@Wp9z_DT6DW5eH!kC@0(tIupYgMxCS$!+fBfYf2d$pLAa
zOHx4EFW8L90I6eWp5$knnp#pq%J6hjLPD85CCUy<n~)LmtxoEk(d4**3xQx;NQysG
z76v&&)R&sv_MTix@SA8v1wT~;pQ-FjI5V!KCKpMZh&TRT0`g1)KMH}%B}x8LojSl(
zQt;>R%b44M{Xq;hL??u^{$A46<0bI+XPK)MtSH2Qmt^N4wN1PwELri?zNbZ0wwjln
zLmnUVLJ1aKg*haTt{V2D+U1cG$-WXE|C{oATJ97k%3iZV33t>eJ(Adb^*AMOFDKkv
zBV-dug3t9nsECU3@u7qfm)UZo5jf(vgaa(g?inI*p=g9`vZ%4$I169j33x>M58wXX
z)4$#S{_Fqwtpi-Pxcf1EbGc&w>wo_CFV9_V?bWH@{{O4`|M=JERet^VmnhDk^=)1E
z@pwJ2fBWm-p8w%r{?h)^UTyvLU!MQ{pZ@yK-Ta^a>wo*t|NMXa^?!c;r@uaTMpwjm
zJ#+W7+kN=!z_Yi1`}hC$+kbi0yAQAb{ZD^;I*wy2xn=&Q1X~MSGk0izu(!!*{#9@P
z>3{u?|Mx%t_5Z3~1|BtitXKQ5FS~izReXQ1o0Yagy&Uko{6sH7f%io(|F{3;->8>%
zr_$~e&NKRc{o(C3tNrhGl2#3S$#dOjFaP^Wqt=BgftvE`N<gEmWHb8PH<fYG@F(Wu
z-m|o?*Vw=L=e7Rnzy12_w>vXhW{1nH@B8Lne=O_W_uriwgWBRKZG0}fuRHvApI2`D
z1^4djfo11Y@H_LyYB)^YepEMfy81Kg{bf;G+jm*so2b9PnEvwGD7BjY{P^;6`8_)1
zR{CmehKn~<GTp>|S*<cmzH0@v|Cg1(8u+fYxsQHX4SSBJ{~d?%XQuyUP58W^#q_rO
z?@a&CPrl)-{2rYS&tHxXl+o{M%Bl5LwFLcqE@cXSPz~f~?`mRc`?A_Le1~ul+n?U;
zwfe88{&%+0zqEg3^-tVuy~m~)!!O5H)D`bqq_X(35`ZJ`T0)Y1RqYyfSjtGjboR$m
z{@rS@Wc30l_;af4CGUO{ZeH7@{rxZCTl@JJFu<z$9-U}5zZ{+I@0T(KKd1(W(7T!t
zh+kH_N6?Q-ef)5bym>USuxk1#__JTYOaD$^#c=j})Blfr0myW#!720Ym!qpIqK{g;
z|AD34%ZvR{&Fl{><qq%LyPBYyUsgj}#`h~wp2na00{V4s{QXVn+drTKkhxWZQzqB1
z#s;^ID!KoGWqgw~zN_r^V?{rIqvz)z*c&T4@xATr_j3BvtN!|Pe`nGELq^Z}e)XO|
zuy#M}KnnU-8x^h@-_<1Gee0i?k$c;2>!mNgt(O|L-!nvhYD&`a_3kE$UykjR!}ncD
zf-kFexb5Ec-jc5?!fF3eQIfAK;<D|dq9i}@8v3O{+OOT<eElAN;w^OC41e@glCOsd
zU)o1SNxrU_==6_jD1TXLz%Bf)_Lh8I5itZG6(#wJH!%|U{lhQf=QJa834ZidlCKB3
zzds`W?b}=Ob;WXnebl4i>uTUu{ir9&mlZ23&AS@QKk+6qB~Q$C?5j8NQzl|w6n?kZ
z-jc6}hY0MCijsU?5ya~s6(#w)V)Wm<`M2cjiYLB*^Ah~bySP5mGFHBP7eA*u`})md
zdrQ6?q9G*z)00BU*A>AP@u_+#`MM%dTOSoA`MP4v&q`VPiT9BAFF*b!e#&SB4Em#&
zl6*O|RYb4vdJ=qH4P1jC^(6VaBC=+ERFvfFiU7fURFvdrOs9(}+dup!e$IBf&e87|
z+FSC2rTx7f`n`?$>$l%N_;)wDd=<UFw~zFxN$}^)o7YU0yQ^pRso!z9*w1X`?C7kU
zth<%x-H;?d8etLHe$*qg?bp@n`u3w5?{mMb*3SOEH3)uGjUG<Ch4$&;{PQoN#rnPD
z&tK+0@DdtOS0BUM=WBh6ir_@}sJKWo@pVPS_<vMX)c@BN0nYiTD7eno6%qUOeisS`
z`^lGafgr#0GR8mhGFrzWTO(}!t7A4Q9wZ@9JqmtM4M?GPHKi!|vfA!&RI}RdUpcB-
z4b(Aw3rAEkKlKvMr7QitOOT&`2M6G|_uzz<`*Lujad4<M+Q;aAw;EzP-_@Fb<;_C1
zI0a5qH41)EO>W?N1MxFn;LD6&W@Y><dx6<Y<Ry9!PKk=X9Nd~8Ro48`&y!#FT>*5n
zUsf6Wqe6o7zWg~H#hB|4Kk=WR=^Nnsujp+=5B>0B41=QJ>w$R`Li=4U$QATuHSfP^
z&HEo|4fy?cH39m+tOgb#&OggP`3C$lZvD<1_y=};pS(`v;O3XtX{?55-FG!5YyGks
zqSxQmlx+B`Y8woesz$*NssUWcH^A~wzJYzQO~13-`~wEi-t#wu+h1P9u^KW1zpJhG
zF}mNa_FI#8{~?Qa1A_amCQR;^)xf-{H_*;UV}Je)TsY?Md;|Z`IpD)HL&=v1CZOCt
zD!wH@aVosP-8!K6{;%w{>Z7n<A6@+r{lJ&|-PEA?Gmh#T$g^>4^`$51XEw3{1oTH&
zKSV$Dkp5-?e29L=5qx8-{?JH&YPlj2(C2!6i@tX3AuI7`)wk$poO_pavHy{g?w|21
zwT3&=w`1uo`hhQFf9G@f+qbvmXPjr3!|V@@Gk(f{R#?=}-o8aYaD~Nh7sH3>r*8G^
zmo<O93;m3_M+eepXWyb9c+Y>UNq)0w|N8B}d-@+4caHflcl7rjzQ!6cezAJlza94f
zcSrqk4ZnXmF`~~`?F-+RQu?R=SJU$qEcM=Y|3AO0R|3HCR4aEegu_n+40AXkZonD`
zLfE5zi_l`=cEjmU0i9YX?IuXv!-*b8BFS)4_(adpr%=2*ZW6*PG$jfm7S51@N-G&o
zsCf*GDTw%vfk6?+924DQge$lQ!Wp+xP~>phDuIa7aB@>c1(aUFs$$QHVoXyMmOLD;
zvjma`IQO0`@0=?JM1r_2ocwpOvVi6mrnZ8uku>ub5mtv2NjRAAKrJ6m;=5QiBw|jG
zV>09cA!9^1$sCYFGMw=ZAb7ii@<J6DJQQ*dzPBr2za0I5!?O6_!WmnK{F0%NeDJ}A
zlTajr{bEce@af@1)<@*zGJGNebBmCysKphoP~HfPEE_l&6;V8KYE+E1s3eprKm*_o
zNlDJkX?P(_)|^1$a3a`GLzftG1Ni<GAb|HY^oi6#r=wr33b#+2XpK{S2{8&BWPcB3
z5=QFE5XAu4>8=31t^%5?O*}F$@d49Rh<gC6b+Lhv0=>&Eqq#cvZyr`p0o{Wkw<*an
zMEza;=Q$1zo!E#red&eR3<LrxO>Cv-15hZ$VsH%oV>rTjdspzl>K_A#4zhoTcn^>R
z;0n-e0ZU^upaD>i*d(&d#Gz5q*iV)7J#PfAA(3coMme9Ih5WZ&9YXx-sgB1s@@XAM
ze+oRBp)#=<=6)Pak)7u_+T!PWz=jr^&?Qje1yXmPs29R$H}K+xP>6`>xdLpabwL}O
zpDP%KVwbn)983_SrO)}LevSv88eD8;k8Mywn{iB6QmrC9vgfFj>AFG9?8b?@qKO}&
zLbj@8>ToJw37?3$YU&0OZ^lxJ-3DE=j+!oIv#1U`Lbk4?KJ+U|K8jd}ZPiW|qHgGI
zzDl8HDt<TK8RbDU6~%4wK$NRvDSd2%23mnq_Dq@V;pw=N+8}!6On6en&KkUju9<=w
zT1<`H>Zu*$g&ta-DX78x7fX568}!iHY8IMkDf@aWRkXw)-Vv#nB1}PjaxV!=xvZA*
zKqq@(=mMrQlfxCUnbO{|=&b9_v&1GGV_6!VV>p#kxj}b{ed0>8=M4SqAXB>%wgLSG
z8t$h=H5OAt&|u3@x(}Ti8}!#=hV>#Sd{V-Op}|CP(ZO37YifX{$CmOdBYN{GZ}BbW
zcea$08MKD623tNDpVAK_Ic~gpF|KH(pf;vkuKqIsx+C~B7NX&MWyZY#vOrD0W%RYk
z4xbd&R&hnuJ!Py$y4(<*Mn~jpET*~cRRAkV2T5QoYz)Pqm}P7>9eQmkr+Xjheq-4C
z73FN(VKZgFTmg0hz}Z9DEPA&pVSrZi6=LJ)pj!-NYq;gRx|9o{gRn7_{h%Y-IZWh~
z9nlXV?0!d(bRbbd2U}!_!=r<RF_>cDNm2EmHt_3I_9`h~I^wkhc>r!XKMs-p_g-w#
zLDK);Q(+;kRR;lMDDhQ?+a#DRt0O5&m^jBeBG5xv=_{#OGfi!vYo-|pbj}z(-;200
z#DRYWHMz#t59Zc115j=T)_^BPx%|a&e<dr+*dxGj8ceg+!R{Dhq3@Ym_s-Nrsa^)n
z*$x_j5Py6h9eo>oXh+xHpCOXvh7FW%x0JRWiE~2~B^{|^LiF%`PzPF9!_a}IFSUpc
zt^m6VXlTRu&$ZZ;A@GW7fK5$9C0bL{GfUXZ1`cFNFW(0kM(>>!M^iRVhy$gA*&!vE
z<x+`aj=zH1{^n8N>#P&=pj3Bbp?07SNu1L2i7<JeTdd_dLtTeToS|l+5@)DYsKm)q
zem5e7zmk0aWM1h=jB^DX9Q5OKHC!L!6Uw)FMGMu~^2P{hHg{z84KccR@K`<}O7|<e
zACLIkJ8}!hT<SCQ9!Xp}IHqHYzOy6M?-lVUD@$w!if=NY>q_c9FSQJAyqKn@q4~%J
za|JafZ3xId9MgW`FE*-7uF_LuBn@Z>!%9pV*d3tVP{P@cOg>ivqV7I%Y!lsjuf)9}
zzV(hfuMppQN8a85-})`**Arq_?_gCA1<7^%Tg<MO1}3<xsgYCMWh$f1D_SVm49omR
z$AkHXJBV;%67}%(;+v1z)H1J?p=iNuA0n>l69=>*Yr0%(Pm1sr&)U>OZ0T2WP>l~N
zm&TQ#f2lvBmcau_PVkVCjf?@I#L*oobwiMvj+DAFl#H#<okg}>ILa$Q%Vn=#0pAJK
z<X{DiP<DAyBZU}rIua~j2_9N%I+TICBRTF%Qk}Y8kTs2MC6xHPW9td=q<3sjA)fSJ
zd)R|({a*W9D8YC~e%nwI@(w1cD`Cq}k7F^rRG(0fLsoX;3}VQ}M*fe$SP$N}sbSDj
z#E{jEv?C$9_A8mFhE2<$GKciCA%WHv)wW=%5_OZ<!Ot2ZV(-ZQ8cD?7k@q<&Ia-bn
zbgfr}XO=b;A5e$R4yCN`(CY!Z<*PP8FLp)vx{=*AMA+Vu$~8nI)REcdN{YOygT*XF
zEp#O-%WQmNjQYG`0fq27omSEn)u2}X&5l6F^`nkJ$90;+AaT6{?la(Zi+=dbLWLal
zqdcF{kLIAfqtTUeu9qztT}CxBONBV!JCaugxQjY6UfnWVdVMw_y7!LEo>#&VLI-x)
z*|5PwjPBj&h7`F`PrE%tZPdZ%dL`J_k+v=nSKh7ul`041uF+{R1K}NFLb{Tg*`=;Q
zb#+m3_Bxha3ERc7twYh`C=;Sj>NxIP$>2}2ThZw;?s;emF(2J>uB9%^d*NIs#-(0q
zv7$4<`W4gwWK|<kR`jU{_v*jCU7Q@RB%LW&1ohYHYtCDz9KzI~p#I3I)RW3Fx(x4y
zoX(N-^Bvre(T5s_?(0JXg7Om))0K?EH^Il9c;W0Wt@8zEra0<5vU<NHDAl@<dA{t)
zB3s3MLYHlhwBONXnkT_*h`+vrWH!3;qFhl8uzpZ_vdidRP?I8p>hPXi37@*)>lUSb
zhZp80$<j+jHW}s%DzZtX!>5xHsOJSG*^b)9X;O^$y+~=VfUV*-qE!ViWgkrny<ApT
zP@B@a-KeTik)pouNJAdYxs?`;YKVKPgGKgAumylcHUwF`l6*~V>%q7Ui?-Q~RDj~E
z>Y#bO5)Qs*FPiM_-LeG2whq47Xtb?&!*tQDd?nd^eDFI}U86y~VgFqTwg}L^UP=9=
z6j`Ht`3iDzG?~9(bd5IUeAwmmZ&QyQn6-(=LW{Mju|bP9<!S41K!>>WdpfA2$%NiG
z-8I<9yLOXX=3{Hexe~mt4Mo>vFoTXYM48o*ZT(8>%T3>WR6>>qg8ZtQOkHpwN0Uc-
zLzRhYt8b{XCi=cB$_bW1yrIe(ozj4PUI9D20aHA3K<rX)SH#vmOZeQtnd)Th>R?R0
z0zTFA!1)G0cHF{T2|lJ>7Ofvy$HkNCht$&@T&a&A8OR_@^+N+0T&aF!Amc*GQQ`iZ
zGrLB|Wz-e1)!GoQgv}ldP(EwicwI@QC%uvjffSk871RJPg?{%^hkoR?_ELvef`&<d
zdPQhC`A=^d?RvfLlr;XL1}8fkETw*y7J_$lSAJ>l)m<6QASJyLK4+lI3ng?;iZ|&-
z{m4Z2fzHW92D_*$#=hgy)sIPI;9}O3`K;Hitsg1oy4X!g?JPbq7<s0XBJ@cK8#eS^
zc6M=qrUV~6?xkHRBD%u~=;BN3b-8^7thLY`*~q@I0_kb?g;&ybNb#LTYylw1^drYJ
zF7dB~?d+Ufxt$%i4bDsy9Z&&3vZ}#h>7b1202kacTlN}G(?$;_Ne>#<;EnW<pV<SL
zWSPXpS>d6S-5u}>54oB_o9F=}xd;(mxhguy4n1Th7nk9aB2L3W_hcs*3t>vI8%4_!
z+66h_m6SOMo<9%yqN9}Cm7ry??|I15u7F?%AmN&WNY`*hIiRTbdCT}Zk>lZFwb9uq
zC^tI_&#5a5Mz2JEDZwWn1D%uMjD!<cQd?YwIr%$JMn{?o4_VGp>)e$&<4UUk`ha6%
z1aF`9O$wL-wq0u0nOx%vYK$_jqZFkFjq9i5AFl{san*Mv;poWUaV2cZYE-nO1GnW@
z!lo7mHBq|1mz9iJ^^gx6Q}2n`c_69I%1n-pz7CYKpR$ticCUmz-(01#lmkjrL`_#x
zt5mjfc$V0zW0hjs9m}ApUC+VEe~kt1VkqqR06av(*aOPYrJIq*&|N<2s1kbx_2)8r
z1N`nU5sJASg`c{TiZ!6sTU&>Fyqf??igJMW1O4anQCB*|D?r1i%oKNh{HLMwWimf0
z$!T?YrBBZi_I;36x^j$MNzSa0SN(uQ-IY?LW50J{sjg&YnO%WyQ<9M@DQ1`j=InlE
zme{e0uE0J%6CIK78S3gv*tJ;)7I!(HOYOPK^?b-cLreQW*9lg2B{dw-$ac_-UIE*-
zU+SrBnLIZ#y^*HT3B`JnQmK~LRJB#TlTt-;Cl|Qt(p*&c=!;G!jOw49(Fgj^VQeQi
zhPzDdvoZZr%m+EeT{%)Zc)H#(FC8f#-Q}DvgY62~vcsfwc&B0Zxu91ars0(g{-jo6
zSJSs|jjXmEJa6u@&aVxdWqiEI8F?jaCGZ9sP0F&Teaq}V(3nDCT}gI!%Xtm6{7U#>
z(Dq(YK6$j3h3flgP?(#x`2bt53yF0lxm35{Ay<^!fD*%8$z2Saw)qw0Vqm72(aOAW
znEJ0Zbw#-rcHjp!LRZTpOQ=84Ra)5tX(*qU2*vEeR-d34_g1H%7zMc+I2QWev`Gif
zjxP~P_n}LDf>PY{R1femUkMuq6Sr^L+yf-ezL#1yOzT3aX4KSBsl>!<Rlic@WvZI{
zclCmw?3Gk6U@DIysJ>-3h@=R<r)F?t3Go}gl3GGT58jx?!3UQ=;_*!{^nlaCmGEXD
zb*As3=2NK&nl&nU=1bBwKpX;h*K_L-xVs)3SR=Hj2Rt?oAH`FmTEb-t5BPm<`CVzF
z5_@wnee^>=11S`J(GfksSndn<@~FI<E`ZiRYDQn>h91nt>5Go&E2=O%I-&>iJ^G>}
zdi0)Qcx)DmZ3P`6SCm6qfp)rr`PfVy@>Zx79P(CZgdL~6MFV?)BkD?O-x=k1ObN$W
zMwcUl&nV~RlL9tAFd}}ueP#i>4l;!L+G-aHa_#pJp&{2+!#Mn{jfP7-E`8n|>XAu-
zMmMPYwbeHCqw)j|(Dh#l$D9gMd4p~_m&?+rdcaNXYq6<?F)g*UFaXnY7Y1PTGmlC+
za3$C~I+Um~4vh{ax{OUhVJ;cnBR&2uOxM7jfG^tI1NR2Lrdoo^TvIK<%js*fsZyEB
zV>FO~))UfoOSKe+8iu}HL&~B<W3Hi=10x!0Iq+5n8xD-IcKw_x94c2=tx}SLbzMRA
zj<)syhqEvKd#S@k+j@*vr5YYG2>YUo`buhL(nWnG^<JA)1}?W=B9wBfjc)3J?5R#b
z*FeT&SBj;P$vK{su;n^+xJo&T0(=cz0$vFQI}nPiScEa40?kzmD$tx=fx0tS!?i>l
z_f$`bsxP#p2W~!Hd6~wrS81yqC_LM2$8fe#;--Q7)GJ}rj4q}zekD1kt%l2De%uzH
zyfA{L2dAn86l@Hf@)V*xa8-RJ&^=?LD>S69gn`a{3gVpEGbl!*A^i*_qPZeY3N)ih
zQ6qItN*aH&vdoqp?jD<H8mB#Fk-CyvP*c+a<tf<LDA<4(H{=6Jy~Tm&!a1sBQv+0g
zPT<!S+-G$4^{{VU-G%D3{tK&A-}IeM=uLwWeFdW)3n#_^aKnv$?<=WQNWb@$RQG9F
zUr7x>e(y1>3R{Niw8oZkBs4m`uO#36JZib)BsPzlhIdB*urZ+pr!40=5MnONdCn}U
zYfyX2f^{X?n@J;iLg~#=_n`D9E2Ot``n!!<h11nDoCzm=*aILVS1zqVAkr0~W%y(S
z-nx<+kE4`RJ-1q3S)wMJ3uBQwo=|{O);17bK4m;l90v=wRS!yCHrGd`)Maz2XV7JH
zp_J=w%5<L8V}xjp8m3SBs|SE=KIyL>0K54#HJn@I6>y&iX6_}*64aOwTUSz}p%IRl
zMW0g*$1nK;r`pBYZ^|milJY659Lvt9tm#QjCdAgTmL*g%Tro`gs;{K_0$=sWM8wY3
zUV@rw+1vQ|TyU*{5A;gdE_B)KQakmb`)q0(XFGCt51>G=022eGr~}e9taF4i+ihft
z?ZR2gL}XWxZ*a&Qw^E3A6MIlTsKQ6qm4h;sT|xF#SgtF{t^yqRlqmZ;LM=fZ4jANS
z`8QjEG90qTjoMIHt}CkX$Qnn!V;{1{t+e5gF%F&f_<%Kz1jw!oX;+dffrzgw$b~Ru
zkf)~fv85@H6#0tS^3GB{0CyO|fRPdWN(O(D8`W6v2h_KtJZmKSbV0lZ%!@1GgON%0
zityyrmP2MXfapF<(*|`pWOxJ7?gjFy5kg-MS>9Iqa>($uzzd<_ZMX~>CKpDfA8{pm
z8?et@$gly>z7J_;gT_qU*H{J5_96RtK^YF&$4KAlO#3!qz+M4%ja9nvwGy(8{53t<
z17Qw6=*b?)gM1}ywdch0+kXbK9=}BS&jS<I^w3cgCR-ZzybJ3!Dj4K7IOU8R2pDmq
zxkkmE+%ony<U76+jtzGTz204&gj_JKfy0vb;4`7kdZ;JRW<c-XcZa0N-a{?dQ`stx
zbV6<o#P(b|7_<Yl@s+TlI?*Xj-4)buT+KiY3hp&<$bG!aI7X0@cNxdavxLtYQBqgJ
zhu|Wi4vY^()#0V7f|_HlyDP~4%6MK-azJy9h2z8(ux;o$rNUqaA6I_7k**2vvbh($
zo(1Q6Aj$>SVPYd>&6PlJR8*UHQ#&}}b(0qZd6QiLuTlP)E5P>;7mh3Q-hiLyN*2ns
z&vaST={|Cyxdsv^d#8JQAV}~^&=4{+dmlt54v@Dw2&zVf8QvnsxS<;f=Nd==eFbc~
z!^P6O+QxaX%QW9r;sD_;?Xb!bBI%5L`n9q@WY1(zSN>xcWNRStwRc(68``j3U-vWG
zFI6Yzo3Wwlgvc65x9#odsnB#v?>9EE+1}`<t~gb1a#bU(w>K%~T{^&p$-0u;|MvD&
z!%gdr7B)P&-lTW;zNPvLJWjHcH`JJLS_1*U-ee~uCio>m>GnWQXe3AX!e2cQRTpFz
z@A?5B7?{G1Qca&+&>L54SHwAnW)ebcRN%BXd7wc%`I4ZN%b@}=ABa{8YG0_kh*uef
zTn9pD4P@iJ68*lWN~SLI)w|LY4#yoplT#YGcfHB_t=zlyAZ#UhJ>yL-Y24sAQyLE3
z@mvAhhVE)Z(~ip`Z!)4QV&8?~8i@J#MiUvd09Sw*oZ&Nz91+fR!gyUty)PNao>vI1
zYd8on@+SKj7j52XA3HAAn^Y-M+g`~+IXmBo?;Xfwdqr#+YOpo6ZJ-#FQyaNzcOks$
zK`V>c6p)p6ANaJrPG<Yah^`#8DPhCVi&w;!Q{il(zy>Z@_mL4@>=paKhDOHMeS(OU
zfdsEx0I%WxD#<=}M_*+i<2HCB^W&)d;wJ^{zJrI226Ejw@8j=ADvgJ-0S#PK@AGz8
zgA-&QIjq4NvJdR$Bo*00bPceMY!coMhlhVF!Q}A!MER<5dB2t5W*|%GJ~E<_4s)Nk
zqOIhXDZ+-4c`9%DU8%Yv>le8oucYoI2XZOyBSjm%UYKlMfFQ1f4RyRk`JKVJvXA`E
zAYIu^Z#iOMcBOn{U{DjK8qd(~b)g_BV7mj|mkk}Ix3@4~BgnT08~904eGU4;!?MIG
zh6N@Ma~NI;|9z3b?}4BuR#q}lIa}DR0p!j;@;Vp1Cnb~baMfHlHM}s_4W*ptkf9x=
z9X8Qj$cp)-ge~tZvDGp)UlNq^vk>&_CgaT462f*MKj)Qjf=YL8G2~v!LM?0s;pka?
zR!@m?-h-BPQWDCj#?!8ZeXSOENHeonThOj6sv*cp9jO+#vWO0h?n=<`!63K%B2oL=
z4w>Rnd*78{6S=G{S!UDaPTT=I`x$t1TL7>D8kZfgv<u$1LpC%ZfIDPGA2?aIuw4U4
z!X0v518ukic6FwA-65;`l>Xdd+E`C%&>iwzpN;|OYd@txcgU_jquzd*)lW(4^~0_P
z-`5VguJMWPkfDtvwp&=QCv)Fs4`n5vi4M|Au6=2T>|bnMSHgJ!w(W{or`ncl`at^y
zUDKzYiERgn*d4-m48Uf0$S)0K?GD+|*q*llTLWA8uFS+aQya4>Pjsn)?Q%pzQ*4)Y
z4Rr7($m_{0B-tOAVm<YdY?obpN};*n8V3r^>56`C_T*gmPD>f-l($e?1IX)_1f}YW
ze9;GX_jWm>0rB20XLLSN2KK2l{uXHKN~-t%pjd3D@;jeXgV}21U@$bgC+wXKl-E<D
zTt7~mc>-d;1>2gSdf85+d4lO>!{&KPWT;ltGGQF<{LW|Dj@#*tzJlr=ENkT1ep14g
zq2AooGE|(?9X&G`;g;EKA*f!G2gMp7P4tO)hV7FL*9W$Js@+*jZqg}oCG}RP+JTl7
z&}-rpuzjd0!-T^ke=?1Emf3sgL7})Z^?9p0d@l5$cRd#{*X^BSC^hI^Lx36thKpI(
zx6>k@I412nYdjFuvg~U6r3t;M-Hnyd*zCqa;5R;bpxfSl;ZHW|u;DTw_da@VsY}7S
zCXSj{0*ApB<pB1<bL*ekPiR6RwldxQ?b;4Kl$vmddJ9dsgAdJBx<h@19^9e#14USX
ztp}o9rrXsx6ybI?UdR02&Oq@_{;P<W`lRg6e#&Zkd#e)ODT2RJgzo_%VkxR6^-Khk
zr3{O;mr<1>%vjHN_>$=D_WCPDp1bkv_45?56G-&kWR_jgtd0{6Fw?)10<JCiXnLdJ
zHQ~rf2_HT%99drz)G#T+k?zW}@5-8fCDnJCWjD2H^*w?OPINtjM$AO+u$1vftBP0x
z@Q$SjYXB~^6v3xB;b(ivTs<%jP|F}gGE0Ib*h@dBXg!eBQV~3VBD6C_?1N#o$cmfr
zGQLE*vX}@^O&M!0_LRq|S+TE~?t>lO?AFpJ*f%@2Fjt%1TI%U$w{SBtyH^QD%<PU;
zEM)$K4>(0^-}%~2Gv!#sX}~=t3D%p3KRT?3_JeQ1G~B>&=X;)lW1DI(I65BEZtipR
zYN(@!y%M%(mJ>fk?}}KTJa|pScBiO%IvUqvSHDJMzj$jgakG#jC~e$6qzEkzRDxS`
zj?QWCY_4<GwNK!h<BCwk*l>$dvKm`c<AVcf8r$HPrX67*18QSP%au*M8rSCzVt^E}
z=0vB2$iJeEihNLZO19mV)P#GepN4)4mVZUn&o?gr%IYl$n14lhI@>qw3C?1zLst~t
z#Kl|6YWu<ETuRvfs)Z=H{sh&-6``1i(^r{ivk4xW6yeFc`nT2L&Hin587`TWVZ*4a
z%_~}ZxU-Xs4|nuY2I25pRVib?9qZJWI^i4&??WaSI8wwu)PqbN2&_{Xh9kHnWEhU%
zl8|LMu&1XCn-T7&Q^Xz|jE2@9C{0p=4}V~VrYwInTNTjfNk#lN^(GauK>b&QPU_lY
zPAX!+`jNIf%joo^8h+b^lWN$9^v$Fm7Pg<M2~)&AlpYqi{|Yv%Ej}n%i(NpG%?}Qj
zC%`L0C*^3JlM0u3{VTbxzwNq7UAm7tL|vMO-BXfUl>+R~Nli+?{*??on_V(Y_YUoz
z?|f6T0t@_-6869_7UA|MxQ|jaFii`SOQe2^@<}rL=Hl?A@F(@}cBzL+-MU?mqH0ah
z{+w553bH@JPLm?e2oL}%!<2Y+N1yz3c4woAuJF#}iZIpd-8<?_A@}EmzT8XA2Zx}~
zeNtU+yvD$~5_o^kQ$=jZU;s-ITRQlRa2fWLtlpU67w9tGs}rcT6yec@Y%2-u4#3}1
zhCRcmTon#5jmlNw0Mn>k_pAqHjiJ`5SQ!d1jfz#F09S;?In;RPhNWnLE32UnHQu>6
z>p9f5TZciUF?&*m4h*hUogEU~m;yFGIMA-v2bIm1MPRdv*!gU7usSvvHTLGI(4dXC
z+_aNv)0<)orcoU$xL_L9v4RVxQ5)y&^#jo=0mnvdjQE1d^y^LW1=FaGE5M*0M1`yn
zgK1F63Nx5s)kzVCx3H<y-F-c3vzxO1t(3B22Ce|zl<{wy9i{Pa(6&ofy*bvc;sP=c
zLr&e=dN`Hs+V4(L+afez8Xm(rp{iXv8(450n_!-q3_F=;kIe_?66XLroJgGm40@K4
z0CTmZm@VJyT-2Zf^v^{NN<{x$(2a|p)mfaQPsuQctFv*L>BWDO5<a|h5+@(tspJLY
zzcNfB!3<Y~Ih0;!5nIi|U24kk?7<Z>^k^JeYj##C#zj+nQ7<mh#!Q4QbS#5q_fMjX
zCTMI^#EuvzuxTPpeUojzluA*y`GQVdyhXW^`d$;ef76C!a8qwW?`JBJoGd%)0d=Gu
z^`La5@cXlt(UY<)Z@fN}?Y?jtHJR><8q;LDgRJIBndw=MiX7R-I1~;r@nu~RiWr9T
zc4{JICuQ}`uhOkb9yk|us{#b(qJFIi0Y0fd6?3&u{c4V44OaI3qHaZyz>}i-;1wk>
z7uBu81g@x7jOie-@QZBwK8PyUbO^v6`4Z_6u&85A+I>^U7H;x^thz2^epAOPsNjmw
zb=vcrD%MPHm`xpvxPrM+1>4D{l2us2+|;rRD|k{?o3#Q9=H?mJXz_0-S%ntNO(k2Q
z1@}SpO)0ow7B^2y*n`2L=@_u7Rc-K^d2XIxO)gy~9BL-xeM4y~s9<jDOcQbB+*Fzf
zE4Tu@J(=sf^rOjG-_(z$`<l7wK2jjT+^dS5l*K8BCl{t(3MNjuo7$0~1anh6Dwbdt
z4}WipC79syPZ1`Z3Utco-#m&=nd%$bamrHP)Q)A5K9JRWVF1Cbd<H3CpB$4rWxemf
z+|Kt-0Kad_uorErNJSFNT^dq>1QUmg6yf}^c@~{A`Zx7x#uCg;EvjIGxuHeh0R?l@
zb3AGHZ~Bd=EPtmiRY<{1e|!q)eSy<HW$3pzc2Xa{H+E7tJ5G%|YiJI2t5AdKRJT*c
zzIVP98T(FkJ5Amfr@mFd!E_YaI!~h+ZZMrL<Eit2OCwJm2%IWeF$dG3k`;6?ohMjD
z9n2)(sYjuRfyw?y-jx*92IE#G_MfVHiY9tGb@d!5)@P)+gy~e%3{02~Ej@+0noc#X
z*o5hH0#DiXPE9>!);l%zJ3L`}scMBMOy_Zy@d?v;npJ?p^j$^3qbEF0DZ|d`RKi0h
zyHg1dnCxB(RuKo!l~n6PwzyNn4%*^Q{i>LQ>C~?kbnv7k*QX*6rc=c#^k6zw>>wax
z7M;gS;-ns(;QS~VX7^xr5o<7=3RS@dGcz@%fVvaOoKnW-4o4?LKd3y1EcBrEtoXfr
zSmaOSyALW$1r^MovK%nkqZ~s+275rsq-^jv!AjV&g10z|E0{r5slb8>a+wsd1A{XT
z1s_zNiY%Bx<;l>3E5V6$$ax?4M5@Sw89b2=of3j4(xJ~k5c2$z$+QoiHiy3D;APAh
zA2rcWIr9VY5-DTfsZSY;Fk@AT-KIJnETWHH$|k5x6^}53+Ef7vGoVdJSKEt=vQygx
zeZ)hbd{F0(jv`j6&J<B6Rz@y7DZvWR@ge9l9y&e*Z*+#v55XIq(dt1^z+DG}paSkX
z8Uz)vf*xj2|5nt)16lRFvsOM?$A_Tu?K(dMl`kV7o|M%<y3P+l4XoIQ8PLFrf4Gub
zBRvr!GkCMxT|J<VW<<mc-v1~fVxCgS-BG~T*L4m!RK}ft{sTqZW#1nvTE#oeql0ai
zjen?V74a|+6)i&^=0S=5LyURKFhPgPRzVN*@P1ZN4-?ElDPji(Pko)ofWyn5F1LOm
z9aB<2xr(&YZa>tceaap_)T4-4m<LL-%UOS@BfG5hLmk=QR{Eim?4;niqRE;Ig2j3q
zKJROaBZ7~@)XLyLS4%2P;Z@|M!Hho}-#PBm?*ctI&30M#hl;ezwm;O8UF!BwOZLX?
z;80C=8Rdu0pC+sP@S;U=3s+PfZEqyT3G}r=cOU3U1uk4kb(Db%6Nu-OP;DJ*P6aQ_
zL*3crus@|cn?B~l(`ln~-WpG*ieIpX!)c>^Z;gl3#t-$1>g^S}gwG28tcGKa_b&}t
zXluNEX|4u&`_eKkleN;YZL6`4SJjBovPKQ7$OvoHuq39rGOF0N***@V3XiZx1)K2^
zw^&P+0TNHjFxsUK3@p{Q)PY$=j-C1yX{Pc)Jkhp=pI||l#>!irW@?JpI?aeHw#Iv%
z#(O+#xY%j5|E*CeH`8FLlrs+Fu}1CNrkYzQ;_XoVD(u1<Rj}eN9&1#=ioCE!72GC@
zwb+NoO7+XY3u~L!hC(l_QT?`|4p0Rv_QD$Pf!a{}o7P6-c4Cd_h}Kn;=m<qvScB44
zjD<C)|5QO1)~IzEWnqm9wl#INlx*WBV=bt#6jx!5T2_G-hA;alu)+|!bk1RGVAnh6
zXs*g6IEbyVVy(_Ho6p)up%vDv7bo|k2a@~aqd*G7u6Yi9^i~<Ljv^%t#NG$n>Qkco
zN)AFL40PeQ%(m;joI_LIKp1os8SxlY#yMMUU9EBy7hzC52XPUG__=fFu(u8^dd^nc
z6JsKl$BK9TC_2Kx-+s=*b0-F{cy(*tvRHcy^zk{So*8<=qq~9V=O{43IxvZckr7s`
z_P5NQElloI*B0h>YEl+DJ9!~#NQ!k7D`9<Si7nS2co-*PFprMnB&-9Kc+ODM8>7^B
zTxQl$u!JEH^_;;6JKo`-4l{85oKugu-RSCOpkrNK4fL$@iNTK1PB)mS=kOWXsit0*
zYCVdaFl1`D66!Fdb2z7|<%6!%YPZY@aTGXVl{Vr^P)f__D00G(Q|ko%{f4AkCur4M
zCe=y-HV)7NJtt_>8`5Z<2tB8^tP}L^TPDsrik~nf&N`tyriRQ}FA+-BIeptWdL712
zSe?v{!Y6DXdB9QpgyE2P6hC1&37((>-*8+!0^Zq}uhOQIz{bRIHd`(y@`<gcXO3^H
z-HGvSsUn<bkAQoIp!^d{)eN1ZIc_<^rH-wduA@*1LsFO%#?IB#u7I5@jdu_zVVN5%
zi`*~9!fc!RwlUkLws%eURLgaVb1JX%RsYDJbA-7wq{cc3l(^-Z>!|^Hme?$=T22f#
z;}{Pw><mtx6VjjX1f8HoZs{yK<?(nRsGfB7Ezp;azSY07Uv;x`Lh5%=u_<uEkOAvN
zQ@c=Yikq+^?l=mYxPpuaI#G^zLr$zCyq$sm;{?3$2It#R7=<N)$nnD)fGf!LrL^LP
zL{i7~Ial_n<A;weH{$`5^?irso;=DOZg6290q+d-D@TDA26~qB4zw_2%{mOUuuPhD
zTn0UIW*ub^H)PE^3bn9F1*uRAL*A^TPz$THSx3<pSC9+SY2DA#G{;^0JUq!KVR;5$
z^HKPPP0JD+HH=SY{Y>K7!%XCctY}97Jww*5mn2K2JY8lvob>0NZQPJf>j-jZaQ7cY
zVHnbBo%+`2OK~a$!zS20kIP60DbZ2-aYHVxBcz>8XimjoSf$f?j-oIO>_aa}mK^V3
zs%fv`$y~?X$??fML7Q2uzv|l(+|H0)>oBsyDtFdVWQA4ktS3e66cnXGD-6lAjzTL8
zxw8%<D=crQj`w%BpeMa+LJsCw#<;aCVIx3F#lx_PE6ArEryKo>vj4KUkxT0+Zo<GV
zc9dJ(a98*o1Vva8lpV!I7!qNfO&_{}4(Kq2xD^}F*#ff|t}_p!A`D5ej=~}gcc4dM
z5r%uxgG;o#GvsCJQEqX=ed`f8&XCgcY?#(a`gzN2s1k}?2^%tuNZQw+7B`J;L$a*1
zWjPyc-9xmTCArVpGMjCockAOR`9bcb{zC2T^`0x}J){%2%9VA5lr!YYI-BOTLFw(K
zrg6eM+tfDn-Zr)ES;AHgIKdHe&VWNWn@OJxV1=_~fES$MY}wx+Ks?G;ZXf_UTS=d+
z7=X@}`E7wA$pp8+m}r6n%yE>W{He~#*hbc^vt?}~?bg{t?Lb@Zp>~kI=xmzg#T|K+
z$=r~2>m**zkaO#7qUQ}cw+_ieN>poCmU|}MI$L%-l5QO)LpK0%j(~EHA*0q&!gH&P
zT4&4TMn<hG!Ip%CS}zGocd;vvxh?3tC3_k$q$}Y=Yl_c0dg#PaY#kKu`&*$YfW9N5
z&5+Uh3b3;j`_L8OV%Crh>#RU2r%Z4+1H<c4nsO`X*AbG<7F5?+`=eGaoJCW4?JRI?
zINAxIW<al<B{m;RblX`=&)k@_rDtN!mWBuQq^#tx*9RRX2%8m6?^#Q2mr-#RO=l!}
zKT1VzD~AWWx#ssUgSY`yc!XUu01wZCxm(0Ow@6DH%syAdUK~u>)Vv<_OX?BHtj>~u
z+g>Z|EV{N0EAXuHY#Y|-S#)e0(p{ZJ6uNC{Euq@1AfIQ+jNUlOE!fClq&`b_awf$(
zi#Jt<6j*1;B;F%S*pL8)Jxlg5;Iaql#BJlc{|Mt|0N$QOd$_Q<x6GbH$JtS{&~kR(
za|Si11mlJzSw{dj%OqL1%%-8`3^wy)*j$etH4eRJp~j*4l&aivA5Q`H$BnS<W1+Tk
zAs(a2ycdQb6L~L;Kqhi3s$*||H*#wolRXTDcg)|<t^Uf{4ZV31!)B>eZ_i{71E_vX
zCNa?L$7B*Cuhy}xhIieC9%e7M?ODK%0+Rce1f^UDw$!TU*y!DU45r3Wx^n|q{|MP;
zK>Z(+5sZ9U$M{*l9#lnEf$}ohyU39BlAx5|j`EWmY_{hRg=Uo<>z1)~ARP8eu-79)
z)-n30ts*OqO?g2;L3A>Uxgndv5g_eKYAiIAksa%pJky?wN?vJLvBzXL!_qy%uNgv9
zjuMg^lVKg<&@4k-j`fd9wb0~xMy$*+8pbbk|Ij$jBIa3EF=&L2$tp&W_A$Ak5yyQc
zR1p>JbEdq|2nRotUTCDpI?7ybh#5K)wzb3kai+Y`_mq@nwhXT*6P24oDGI@62(&*l
z-kn?Mi*zX>w9b^J>>HhNJqU_0qdu;=o$0a8l<DkHgHxt6(qkPV&<yFZ&XnoQBk!5=
zQ`fQhOgXA?ay}D|Y8<VPQk5Hy-)C-a^Ejhl3ERF;kg;6>cqv&ZSMT-Zk_G5YTGHi~
zI8!z<@@E~T95=W!jzDJyj)*JaIU4!1&ZOr$S{Bezq|Z82W;3E1k5Z6ZWgL1^gk1y)
zw9b^>TnV(!l-V3O<4u~)0oUl9ay-DFbd<^5K+|yqK{KRoI?76JNTPKnOZQUbOc}Uv
zmz^mS7um566OJ34Y)7CmgA?v~iBP<wk!KoSyffvQ1|`awP3=PS6|r><(9n6A$zfOv
z4W*pNAxCt%E{_tH8}niv0n7|^GDoS#4YAFK*fFcbR%gh`jKo%Fyq(Metu+FrTsuQw
zDj0LF1P?81_X^k(fWFR<ml=WGXUNN(xvh?pjT_>_kI-R;bZ=*DUT_7DYC~S-sFT`|
zTRCu2QxbARKCA;k**)LEGk=EM%5dKwp~DQR@6M1h90${h(0~$E7v*d|xF8s`m@CEA
zQ4(>(4aEU0%y@}$2C?6Un~pQ&Y{qTK8FDtC+Y@=3ahY<)<XnLs;S8DH;7~XNrZ;F7
z&XA|MXc*2=ic|wx!x=KYkp=MxRc1(>btTvvK>l+j8)rrE|6I|+PijCiw$H2*W(kUL
z$k49bSx<`C4m9DA#~S${&ww>vnX``4kQ*{*9RbG-sk6?I&l;(-&X9qQ+*xPHNYC6^
zx4bLPz;JhXkj&hWOzQ|oW=N)W22Jz>T{&c<7pKr`j9o_h!PP{UMPB)~j(}x`d|Ri>
zBuBoj=XCn9^NRH-eYxQh_6RX%xTZZ_K5N|NUJ17@P~n|U1H8EMPM6afxwMXwnj4a7
z9iqja6y*Z%a#|yu*6DIugNNvJS?M4mI-LnuuVkVYo6lQ~gqT_7&N@tUZb+SVy3A{&
z&U($$wXauuX~9na^FmInBQV%PPOK}b&1C^EaFF%oDN((!g&)+c(g(djH*}P|d^OzC
z3l_Fot<Ec9(;YKrDAjCDJ+(?+jn>&OvyHE!%e)VxiM+t5dHP@l9P;{5d$<tjLqmms
z>?phV6$Pp_%$dDPUF|^8_0Dz-6Da5M0uJW%uBM^>lwy1p7wHi!Y&9J6iqhq^qOPPy
z&@_j6>{E{Mg;ZHbu(8!}q-#eV-uV97VUKYc(2kyq%K%`(R%P5i?R-2oKgXuH%Y{@~
zryWfcZrWR@ZKz1$z*c6;IxV=zTtN<@1)9cTuZ7x%&TOHng3fHArVB)NgcDmpnw{o&
zE_|8I^<21Zl$Cse0_Zf|7_FR<)3*8#720S=FTm`sWT9N$r5(KruJ@!UzuHv<!>7@V
zUf>`;ji&ShPw{E=TQ4NnI!%7-h3r}fxyo0s3bnT^<kmWEv03QPw$v_C`JQHK7%H@x
z8ZH&8gy#zo$U_X+OET~wwW(Urh5~b~*SCAxR268$Hq~Do3)_SqTgZxal)Ze_esF}_
zTF8ra+E6o4egMxsC8`%Y)E2Z~8=RX|eoAn@u$3K^%BRt~8eUmqqqvZ7T`k~7Uf`|;
zbnkg*GGCxPKf-9O%yxBJ`>0e4j^5^lY*#NymatYsdCOPnk`NMWfrcl}Q7dKGUJ2Vt
z+c%C7+E;RCHt^8;)<SvB7xG%gfhoR_*D6k^;Y<h;C)95F%CJ2k>s1KKwLqmGN;ken
z%My;+Ycw=U=ko&JP8>L&S6VA^XiqN~G;wH9KMOWbDBbviT@=D(E!a+Rh`(NGU%doN
zO@o*x&SKkjHjA^=dM%Mqit>fb1#xJXuTdrLtYhGH8J{}vwxmoe8&;gMw-*f8IHpI|
zHx$Rz`})q}Om%;vv-)NcY7vJ9_Nr75Pl~E3%fH!7X~Qeww3Rvx<s)CngcV20niftD
zafVv98qiR~hSfLF?!x+`Z~Iv|#)Pt(FC2B^=rhhpnK-n#7nphCbhV88^H3i1g@aZQ
z;I%40R-E=xse0GcUq}C1aR4l2#|ojh79xq_G(OgUsi(5Dr3)iyDL)GlN)bm*mx>GJ
zF<(ft5(03oN{<zB)HJSuA`aWGk2K<__56+_LUUDmJVM$Vfn5<Ip<l?56-s2jkRvOC
z-s)8;u_9;(FJ#0D5b8c9%EcHkgclqTA;{K(lj0@G(*5yP69~DFps#v?NGD>e*?WQt
z<u$+Mns03bv!m}j2M1S7#8Nw>hO*Skz))mkBYRc=;FW_b%@#^gz7Vb$!fUO{s}y1C
z%f$2>1HTvCSuaukz^X4Yn9CcMlG-@nFuMY_f~cn}!hVE+&xom(>#3afItN51Ctrvu
zjTl7AE#$(Apy`c-R}n+at{R+dab(L1<|}_vlpl-$UJK63h_2^s^i`Ji^enOG&SfCG
zdOAAX^;oFGpbL8;KUPHJ2ud4<yx0qV-3V!Fq{xbp@r@K&5%gmJhj0Jxxr?^FYQBEu
zW4)@jUt069`8xLe`+xiGzkKW8+Uvji-~aTt2Y9eRAmQJ>K_!JS4ZXj*x;Q7jyjG#8
z=w3;kUXvhSMF%}V$fEB67x|%?cXN>6=euBSqmBWO?{|X2Odr19sk)HBVTuZ$>1^N%
z8n_Vgcj$@8yN?)*T9G&_M5dFi?9JuGpx!s6VVal{-XZA>lAj7%3KDn?#=oAeunPh}
zdf|bIf5jO@6my0Pp0ni?)0J-dqoKV&JmaT4Lp)aEL>1bRu}cV_U2DbGYyI16jo3Wn
zb%KBOx%IRAkCw{%exc+*xlU@5Kh{aj4A#kOnIy^X=NgIMtP!3UKG#Ui1J;NGw)4E#
zi0JL#YvjB2@!jg^T60(&Po^5E)qvH(!0eC3@n#>x;!wD`*2dEP(RYhueZMr`ky!7w
zLBMn^4Z=7b_ZQ+7e6I~51h_O5K!MopGlg9^oi4uTb9wlOfyd=h3#OLG>*)4cAFox>
z_uWHYe=O_W_a9jv2ty91Re&JmATSjCkU?DNx46F+4;yyb(7a<44t=G_br6DkBC0rq
z_C!o^IPb&|Q5=GLBBD5i^h7*y2<chj#3`s_;!81w(_03;70$~rsI?Hv6Phms^bDXC
zLqN|`ptp=Bp^6Fo1U@>1`vinKF6{I91~&R|Zg7dg4$*Ui4K;)dMci>X&+bt_2LTPD
zjzfS@#2rVjw+bZ=fjtpO9Kw1AP&Of~C(!62s3+oxBaxmNK^%g42DC6?p3gS~6o<IB
z5l$TB+Wr=f7f+j_%(@Wsc7S~{5*rFMe>jiz1@{jELo+(~RjNO$H}uE_ZWM!H&oXgC
zI8Io>SAez;mKZGp#6pBO+BArl2!cIN%fD;1h_(p9JQ0o&&Qp6v1>Yi$bl5gy!v%M6
zwiF1oP8zX!Ku54iZ0hR+)`{5ENr>VN;5$#92#MVMhQtFQ<R%Vev7N}63bl#N+h_#i
z1c01~)Cu7@k@zG8<2*bZ3dVU}r$Zq)4-S62JYzV$hVYzqz71Iy4}yF{c+L!V3ZOEP
zctGmylxHk9H`TN8+vomW&&ClN?t&2Z5>Z~U%S_3zu-H5-BXBH=yyq!NHO8|tf^lQ>
zsEo8dvFo6G>Ik-ZR6e+Hh|Qxiaty@gNx2*;A+#mp;;vv-F~8A0h%3v;x?9Er4|>hh
zZ%43fY#wcUgAyPHvgfC>d9dwB6A+sR+YbL#?79T%sf|PU$c}*6*o;%|h=+~c)DIl1
z77euyN86RK<vLjb2KSUC*V{VmD|Y^M^x)Ulzd{ei-Y<}3Z+L;RWF3RfKUScWt-5O9
z47I3`I=q}$0=Hd9JnR*57O;aaXJ6~79g~P1d^t+Fv&Y(M7H6on)hrHCi%O|i&}yu$
zMr)^kLRia=0M(ZSrCc&=sh!;0*HSCk+}C;!4!gTxl`m5(OKie1mZj0*h_x0<rB0Wr
zmD<jQu<Q+|sby*dr>SLXr%qE(EK@`9FfK#sK9v5fj$4HwRI}sSA(p}sIzm~mhz-LD
zxuzN}1+u1^g$4mw^C?lSfWfv7M#M93M=)#XwA67;6GUS^DOxFjO^$qpv8djzqz2Jx
z)kB%QE&GmK<FV+E?iCaJaY{r??3G~P2#LKC_OGfxv8XCL;$#E8yMHw`JFpO%&Kp<<
zjr<%Pw{KU(W(P*t)GWN0$x_%63mbMc15`71)Gf;rCk<Xm3sr#^(t=$pT~nNb4<z}*
zjMqvXL>E`W2gAc?t_PQe76rn8N|MtkR>6+w*AS^-NAPPHRcU`6?ZR9wBeFF>7MPO!
z`b8DkE3h@Jlxgp&u}nujXe`s^PzSGm*iwz0W?Sk+VBVHG5}3Ee0FVx1l@J+VM{H}D
zTn8238b<Bf5#Jgh0_+vt`lNu3L%WF!up_!PNClXZ``9VR2V9Hy<eFmy%pgSY*9(ad
z1~66!4^9|e%~w)=8@z<<2xbi{P1_O58pivg4zxws;B!+Anp7<hb0IRo4p2vk46p<F
z5k_!F2RbB-psrp4u1{E3+c+Z`bv6%&A_we<Zw+f|9J;cY0c)~m7O_KskUz-z*MX`D
zQT}xVuZAf9`arIQm~s*n&C?Zd0MMY~0PF~Py%ID9{W(P=az)wSS?!dgf=xhs&QRxZ
z01|~@FWl3UA~p*RN&>-NA+RyY0(1qr6lRs+lYBD=b^xqCoF)S*RXER%_}7>~k9CB<
z#uWWPM+9sX&hz?W@^7wLXjFkbJ1}Ke!gihG+iDo6CV@QV;@MhW(6az}cF>|lfjl3G
zYKU8nL(9&s##7S@=h=}!KHx~{1Me}W_Lhp9O$i@chnti%{wBMteS|@>A?#;InCz7-
zl&ibiNDw6(1b+4ml8y3}KM>@~7WT6vY&L}b><F8UIn^=_X%lp!y+D;A<Yx!&GKl=_
zfM&*|^Q(iYKLq^j6I5X_wId<4Hm3Zw2(67tpJd0cV`_V0m~2cL0@aZaLbRi=A%tiL
zkTr-9?ZCRm?C<%SSgrMpm#!5)w1dJigb(fDcnsk~JDDJ3>XZNu|Crou@X}-QUi(Vw
z4Wt=>RT2dleIUA{6JoR@bT)=|8idZq;JtQ7<ZFx|8lWTeH3qMxdxgG+K%^ZXSqyCz
z_!48Vl;2Mb9TPw#8p4cru#JWwqrG;Pl(3=567JkPwx*W|rJUKJW5R?o9<&oCbg|&0
zeHM302tV2ZZGTBn%Fku+8oOh|k0FEJ;LxZ`*9W3%**>aO(>P=I3IGVfLOWsv0yn_-
z8$uvK2pHNCY7hd3UP<*(c0lsvUcdPL8!p7bj}A)u3fO(<$1zc=Nhd<2BNR4Dk3JAp
zFQoBdQlzBGU!G+)1BE$w>r#HGq0bS9ONa@uBQ`cf1lX<A=a5;B2$m-X|Gj#zFVI$&
z_(bT&(KPF&<wirHHi<5UjbPX4hwm-Dn$eG*P$$d~sb5FDPxK@E89_nOWt1auD7p-D
zd#SlDqa5L`(P@;EVmnCam!e!|qVwypt3zyly=?F3GTe<PMKbkuFyM!X`g-!;N7tu_
zkgVv^!d4|M_=Da`-y*g($mG`%+8SLSUxl`&B+;C`B3q;HcPsTxi0ZH7njl2<*Ad+s
z;`!?f30i_Ye?8;oZjm>9&~Y6q8L@XEj=zrByy!xjbg=G+DE@kp*+<t`j`L!4DQTQu
z130UvL^a(~uo;pVeSTD`?n%8O1~$O?*BS2`eQIV(opotb#JonAHbuIC=u)N&7lhH@
zx1Z2wU;ymP@^8)yeD|HEJ;Gw6iy)|HFldPS@0P3cGUOMuSJ#&fCrjV}e|JClVWR8v
zT{}yxva#l*H{scdPQAI1x;Mo5*DLJy<K7N|vC*U{5f>XxR(d(AqFfsfBssZFx)VOI
zmjtEke3M<iB1>!o0T)-qMxel&zGg(vhS>W$qGzM=+s*tR(L}%B;S!7{cN!vNUy@te
z?e&+wQUt|D<5$WACeienA}ltVbmWFIYx1O3RBVWwuOnH?6HOl~0%fD|tAwL9+EP=g
zx|)1x8}8Dk+ntW!*=RDA5i1`}suZ!XA&R|T!LV15;XEY?)Z%lX=$bSsywB0(HG_xx
zN(y(}(}Nvi-Rp31U&%tb`l~}XLSe6jEyMbbHq~@#x;E4@4vJ*l>)=6%rY{$1hOVRz
z{9wF~rq6fRGubZGp;-2=q{gR@_udgaDZrM2;Mr*Unh`u3tz*d0nWE+EML`kmZ8alW
zHk!`hh?b2e_d23wuY@f@X|{$_#`Y|5bkLcN-#_AIqv@2sOQ-qKhOps*y&^W8UzeYw
zcI#y5VCU;dh~-DN^sevRk2pp8K3T-qjR0CdI&mX_)(=nIb>Zcr=IeFg|D*`}1_EUL
z@W!{-#aT-5VDP8-p?f`v@cjs=-NA$JBJ1mjk-ZY)8G4r3ZpXZBKC^S$c>mPvPVpr`
zp{7jUba2po03;Ao`;z1*iG*-|?4!!cGJ8>~%t^S{ed0yP>s@s9w_j6FsgKjo)N^L_
zbZQbOdaL6qqGKOFa&;p-){ksw<lTEoP`VEtYS%E!N|Sj-k?&kbRRqxbA=;}Wg4U00
zY0tBqlb*OFGy6;E$;z3PF^$`EKQg9qz3$4b+kHP-WV0I!R32``+q#JQdIsG3;lI}C
zbPwDSZR>|V?uw&zG4OTZ5?ma79ngg<p%WGG1`j#45lZV!q}x5Rz>(BJ(8a;m9j<E^
z2VY0H?Ui6x0%FOPQ@0oWy(^<`2l@Tu%&6Oe_iz#S^+JSP0UNJf!Ie<ABc9g7b+>|m
zS`Rq63Qgx?*y}(Ic}Q6Ul;<Sb>w!Gh9`a#<oy`M2tYmKUkVOq{Hy6cT2j#to=tX+m
z2gsZT>d=)bw*#5zNQ&D5U378sb%ftu37Z)hj;v>d-@20Gb_CD5IQBZz)w(j-_R4bW
zA!`{7_AW}j4gz}zrCzV-Sr2iHbdUpHQEepX))law>bi%_XAI9lv-gx}rGPCjOs~H0
zSO9_1U`7gJ4|&6*LdIRxd>yD;4{2TCa$N~<JD|QUs=Xf0Mc?%9Jo_h=iXdAT)m}%U
zW(U(=M~JP5@EE;fY+b~99Wl1<Qlf~lb(anW)un@L?<rA!#SSeR_0L=~P>=*zb$q%m
zgjKKa`!zt<EjBg*7a3o#J;DXN>exoEB%h0&#$8d3y+GzpBEF7jTX&*8`srE1OT~`p
zf?4(2HJ=pW8Kn(f{$_;Ix}a1Yp|mb2RR=oXeZTt#tw=akPmupD5@uMd&s`p8L<+bd
zRZo9uC>NxvBW~7x@tIJO{su3WimZ($LnqwHv(<sabU~szkg=Yas9wan?$WQ|m3LvD
z`oSH#3-#11FvJCW>Ife3ggte{mbh?F9T?6lp@Ic-u)A)SGw{`2>J>JRd;M#j_1vX8
zPa)-;2&tYus18EUxV|s&$2*}<J;P63=%-G5(1m}xqCg!EJkTX+#RDzlL`C+BWqo{0
zDZ==4;-or)SzSP>jxZ+|RO(7{WpDYWMr&CFXc@s(PO`j#a8?(VY7}es6_~M3*{Pz-
z8?gOd5UYV;FBit@N~*ukrf{Y1+tpS_e@jh{R)4b<s3w7|26)AN%QrQ^K7LWRY#91V
z;Hy!mD&Mqz2M%7om4<5IaOO%<J8*(?<)|Gv<vBU`MjiuQ7_D2b^^gf_2O<Dn`Dq6@
z<9+jE9SEXzC8r%Y*Lo7{J&@Fh=#?HgAG_%C1|npAo8DV$FXDio6y$fk?c*`kLHkzt
z<y@A^Iy)*#)0K2~ki*}Vb9R8?-Ia27ART}!<LrP-!ZYFQK)9^$!TXGXz*A?+*@4(p
zSH{_q(W|a>vjg$1zUyD3jz6wEvIEW;7p2{3CreziP)Yj@;D%00f5!t!y^E%9986+U
zM-C>jX#x(qCM`RVr^1yRc9a{-l^J%x)8z|a{D3penHcs-QBExq!wy8fy7Iz~UKQ}c
zAne-7j5ipX?TZ?8fZP2_*tLP4=wt2!UE%3<bnMEm<gWu^uD<X!_nCjQW3?K5>1#%i
ztFQOh+@ZRZ8g?M=)s-1`RNSktt#)y|Lsr;lz#Z$#3_B3@>f+rSh<f#<k2k|!U0GpA
zQNlkds_`HOK#Y0=p{~xPu%mp^zD#Vrb98LYvp*c$wr%sowr!o*)`@Lfb7I?0PHfxG
ziS1vWFYbHSy6^l^GhJ0(Rl9r7UNfKSuFeTb)G1C!<Z8jM^a8!K*Em`M#%yDC{3}V=
z&Zwe+T<s_VyP}gl^<6Sw+6g@}$KGF}FGbT$6{v4tnvS=3cxQr^S8(+j`45mbq=xb;
z@Fk=H-~}5h@#9^oiVKr`8^|Dpb^0$AKdeEH-5&5<6zv{SK4jmB`}ks3HL)Np3+@Hh
z#VE>aT%|liXm`MZ0z+yyaHcz^%r;hx0fO%WXk7zCZg;?n7Nx?rAXi9KslDoVp`P#x
zNECxM{3e9WGTBB@4SR;ru7DZMn(J6dK*uZHg3t*!^Iv$TE-vavh!sP;A7$=SeOUWL
zIE$F=Wst%qo4Q@J_R(1tX5RH9KMM{=dO4AB&!tIu9azssdpRAP&ziS?S2*WlJwsd?
z=)w7bCe&4<)q_eM;Nf{GMBL(I<IjWYUfIbka<og79{1wcXO#*<Fk~8#yc2bpXHrn{
z9Yx@WN4d^k!yip|kTk>np>*m_D5ztw>i&*V;hO@{bM7`k_8aFc_<$<aG1zr0eN(G$
zU|D}sLN5l;?3-x2bKpyAOx$fjw92Fyd(+ne9n)jv^CR(|d%^U|C|`Rb*(JGlZ(%*0
ziF+kOXinxRI3SvhlYJaPy;kHsKK}^^$7lF_&W&UWrwJV~4xp93Y_wmXmXw>OApYMl
ziiDf&nQFqbo>D#v?iAnD=rku1-FcGT39$coO7ac!u{j&DvImJ9oKYjc2!7ZZnZ|ay
z|LbeAtwBH&zuCHih4gMOMEaH<Qw^}k?0&x|JlH&sqrOQs9TOT#q%u);fTC8Oy;_{2
z7G}6L5!uA?l1fE~&PNyrc&N3kN0Y9sFX#$AW~lYfwk}q6!lEw&JDj<B^OIoWl|4fj
zzJ<z8Cj=Mdw{a!3Ylh@yRwTXi$X>kg>IX}!4m(n?cbs%H%uDNd?OEXW_Q3M~65$4z
z1y}M#KP^zyl9@7HXOlfF?b2$xW1wPjutVOGBa|_X((2>LTU^viYapakVOMx-t$vSd
zrRPfC6QkDIC+cw`0s6c~SeVOGR2o7LMa*PtAl9>_PJ;nE$ik_<k5iR1Je_3Na`s-V
zGhwS30Gh9IaBOmD&fHNbZ<LVvDwD2u_?A5y&@yc0gJ7aF2SOe!I8Q8rO^d3ZSym7Z
z?#cde$Ouj^)tlkzr+zzD`;{~olP)IQCLQ9s)&Z!aUi?l)!2LPH^`d{^1F@M+YxEPb
ztuB-u=BpLZ;YCC@j-dbB%;}2qJUZhaP$7oD#A<qOu);s#<^57_*HP%KSNi&Klyg&G
zr5wtEDNHe!xBStMg4P;r+H{U|`?j2!PvKXB8A!Tl%cRn(MH~IoQrzIfD+@p`169mU
z!eJ9nY5Uw0#A~9|?9r4S@QKmMTPth)r|Bm_r#kEOwL@;UK?Cp+jMGa*AL?=a4D6L4
zHAFK!mPb<pCiEcw(wGCHmh5(1_VFo~!O`bjoy4M}-E;IcR+Z&P-qE|-=gdG!8UER6
z)CSi6L+ww-C5U7UK+R7&7`p$F@qJ#9DKRP1j&2%+wwK$0vJw)I-BfLI)_=6^DzCTl
z-q9VemgTp7@QKCc#H)1yA%CdRyJStb<*Ka5zCpX&W?2+@;>1eKGQq1*4uyBueZR5x
z*>PG2G}yXw0ilb`;MSqE6-m33jx}7pPv=80jZVCTkCT5c+TmD{1Li>r`d9bf9hBH(
zD@D|nNd78v=6Yzg;+(F-@%ik>xO!>cQ%gcrGE}aq7brApCt}k^9aTg+-bm+;Z|QEw
zpZfy!0_(vlPLAw%z!EN$jf+s>(9rDapJYy&m*6NWdm@1lchAQ7fjx4eGM@ED22M1Y
zG@6Z6@>qxxhQRXb{H<D5U5HqIDV=~2;4?_f2`i$fFxa2$G<@N(X6*4o2aaZH_}891
zN#zKwVqH@3{jO(K1h2}<gSwk(ko4p`izx@@R2$zENQ~2woVy<)<n?=R@qpYb+SI}K
zx)H7x=u-Bbgl-fLIJ8F2vP~DOj>KvNFih{HoX%Yi<V@?{^UFh3U!w9$>6p~Jt&nLP
z$<Tce3wW}Ln~5AAj)(l)!dThb{r;buPOkD2JMerfE?`?+#Z6-Ij}F=MEcRzq9PS!R
z3&1Sy_CG-O&jv$|aJFjOT|mThiKkUdTfXz#irNDOyUDZn()F9v?7Lig&_=H0O-mli
zf5eh#eNV45$WMSEDZ5~m*c~zsg;n)NZ8eY8^U}r3O@`40y$N;k-GP8q;lmznc$&TR
z0%48V<EO_mW?i@>pLI{lb{`m8Sd#Qd&zE&ZN`Q?Y=}+c?nBN)#d~sY6+fve9{GW|z
zSx<X?kN9~q_okc)kxk(gW&fgDZ8QvqT900VPF_4H{Ux2e2)|vGXkW({Nj`I{Ax=~^
z@%Zo{Z9Ao({u_ph&vaYtfy&SB(9#)_iu0?xi&{g!NS82crIdC=qb($+9q?EDm#yb=
zcZRRa4$CJ@t*)cdSE6ZIES*l9B;@l<3zR~2VX>}!!O0>3P6sKrbIbG>hhgkmzm%TT
zWVD^Tv7ud|Fk>z8c<3^e$Dlma0+5d}EEqeCQC*7hJxuu(i*;1PIYMnk>aN)xt(0;+
z{q-CW?Fh!NQ)v)2ix5z)dT_(`VD819Smj5#>Kx4z+#WzL{X<Hv84Am(7i6%x4pRv-
zuZ(8$h-VvW#<gJLxGGYyQhF{u*gVkRW9ixrVE8p4CO&c;HP~%zuDxa?S<oL&SwO|#
zy9{A_@8RO7FM3Nb9>AJ)q`#k4`RxzgD9x~AomHlVpwrv3;ymS$ye_!G@^*sx5TSMZ
zALPcBya$y1J~qHb)d&3Q@+1x)wn#O)tU!1HxTU4Q&#M>=Ry($r@vu<#K4H-(Dv=hj
zQ0%o%ZX?hxJVQW~NFFFH{)!s)<<Xm;F83Ng*`G1oM-D;dhwz<V{F@v#hUO^2+c0EB
za5P~X%Yb<{`jz2*Qg{zAcnr(e`!(Qa)a>%hAfV{oM<T_$_v!H#sQiy0;3~luv3(y_
zCf$06ozI@KKSDUk{zzHf<8Pq$qO_;fxcEPqk{X->osX(d%?04iX3ezGuAOvU`dX82
z+iz8aqEiwr_Fnb?XL&*RH|T)5?|Y;^uN6!QmmGkGP@pYxIqd5pR|x4qgRuh<ZS@Pn
z`$xAhDSr7`Ys@!j*{MD~Y1}*gWDdHZ@ms)%AnF4F&qOyyO(rTZ6;d4BK3;R3YMYjA
z&vV%#PDor{jH?;XE3rvaupM0mhxZg>SDZ!g5Nf(pn!GWs=R=83@pn4MF7fBSQDKii
zLO@n+f^+0Q;9NAcwi&gg6v@9QUZxgddk~tY4ib4nl1st&yCP1dk;yvZ0nn}PaPS}K
znK{rC-d3|*H^C{XX#s1(d1+{68nxtC)PgB<t6)dB5&O{uwQ&}Q3&C;hBFUumIpDdp
zuLZs{SZB<e%YL3qFY1DWTBCO^z+9{QsH>ycmsG4|7cZwzIl=FT6bA&jdEs5r2NCm$
zTA6upGN0(?0CGVZ1%R}+bRgvaI(D|uc{UB(D5DkJgz7dlQ=wbG()6k$%e9aVJJPs;
zUQ~7hvDw%+hr_cm#aeP>xk-ui$-*}>n2b5C0BlYdi~%W8IAj57b_VKhkBNRoF!!4Z
zv$FxQ+B&ro3s7pPl3c=zU>Gdbr>>&rqSUoz0r^fd8soKT1WuDIHZ5U48W<`L$@-o(
zfkT|e*AlDL>ES@^Qx^OR>`GhDw^#~~i$Rj1TgcynB!Z_((HDYXu<Y~idt%{8n~$t=
z0R4Hp=X5=RxlGSjw5|*|a320{rm93jcj2XiCbpK-TI3>obDo{MIeKGGL^&-U5`yIL
zJoK)lTlcoJry`v%9rH352Qv{EnTNzH$hD=}lM-M9>khg9*jNrB1%Mz}4X2DwmCL~^
zTsPxkqn(@pfycJoDc?e^NanE52iXjG?k6~Uz?ZWX9_CAT`Zw^fO5KiT8hVbmiyw*#
zRLRq;w2>AlCrP_z#zRn~k(xM0$uaEBN1Hpz=z=pew+)0di;8oTG>;p9+#cD&D)QnO
ztKVGZGuQiIcA6FUgRsi}Obh7z2+t>5S+`GE>1%=GX-dnUiFi!k6}m^pXUDDABuLh(
zuyM>avq4@cENS1}eV_+awC`f<hWF+edoDVN()AcK`<wl&awM8#W8KigQ_`Qsu4a!7
zr)k6s7lUDYwC^j4>8c3VN!4JbwtionRU$b5PA8HA))44fOV_})%Bigs2j1RE`<Fi?
ze6p>Q<Xz7KR#FcwLgbpkwa~GDF7eQajN8cIVCflU*eW5YW&G4h9uRKM2$=i`*X)Tk
zs+(+hUoea@%L`aK4A1X3^ffEE;O(Nvn(oD`+*EW7dPtIjkPg>bC^{}wZa->hW|`E5
z{ryl^EhynAI^$$yx)-sS!a_y<8|I!)0xbReKNE7@pkT!tYjI$e{6IN4?&cyx-z#@w
zsm_|Z4kc}d_^x<uPHWN%imGUH3NndfbX!R+xj6q2>WOOX$!OSZoSWMxnklXaYh3gh
z5@89`Iu3g>v{?)dOg;V6FNwi9TyxFOK(4nHHSzSEew%@coMiOR$`b!WRE>EkR^u}$
zU+jDy4=59<&P0-5%g#z3bgZpLc*xd5aQN*mY^0(5Lm9}TW;t5MrFf_C-J}wtnw)!Q
zNR_xoYIVo(6RQ$n4ovaPageLFhQV_Kzhs<(#|C~yIVHmxbs!gn$s14nEH3Lc4FP{J
zbZ8e7*`^?%tT-ho>|JF}j^W}Beh|+l_b$UWdW;aU7cT@qEW`fgUo;OAHHdVLo8TT^
zZ#&Ke2lf#jo=I{qWN3N~G}L=1MsV?4c`nEnS-CXBVJl+kpoc>O#`hvcMX~$l2+TMk
zFB3IfV!i}=@IJm}AIH5241aIX$a6FcH6jcHff6N(-ZhE|Rw4-n`p<32Hpsnl5loD4
z;YXSd1^3Rbf`{n|Hzmq=*;ckB+)uST(UlvfR9<3rgu5eAO|J=isYh+h5nkfvfhs#0
zdCoEOt(_-NQJaL=$IAkUQ*Oz`mVmsmau<TBbW{ai!)@piz1l1263+xbp};lEAztKW
z*vDOcZ_$M$sP%`>^;;1hUdR5jA4l-nOcD#kCmCQnJa8GL*6;9WdtG7NvugU^UY8k0
z1QG^n(3F4y)|h9!b;(orI*9`n=SW3qT^WCW$TaC|a!wvj!B=x>v_Nf=9b6L8wwe{k
zslmbJME91whd)=1@$XbckS|hohdiDK8^6xts;K5GIg6lZpDRtI8fkK*$dg_2SW2xe
zk{Ydo?QL0Dxd%F?)y+T;m6kh7ju@Uq445i+#exl}9)aMThii6|Mj$vYHO^i13)<>1
zFY(4}RX^wi@{GWoi2j@{($@)<zTR2nNzke+TSCn|G_cQ^`RmnV^-Vp|t?=V%oz%`n
zbv<`=oMsBcaSO=`xJlri_!V)70r3j@%Kl;nsLmf+7}s7DW+4K++e?6%Hqgfid*`on
z#BO&W){m<yTElRR5P}R-L?lD(sZSmj69ykjWqf*QO;7uTR4^nRLgd`<FHJX1YgYj2
zTX_Be&>qc37d)W)&UFLhFxrJ4HOSj^S(>?3A~mQxCR55z1j1<9@)i+LZM}=N@<DLr
zjVr3l<!~vE^CQ%W9_M!ffi|n4wX<lYwh5oC8tFm%M2OJDLxWv(Ov{!kd4HAlDAu*k
z50+HB$}$Z2&Knt}-J1GxZB|K;9y3b04L5q6AY6-O3KIuV`kxxO5m%pBFp-jb+FTF{
zExO*(vvqdiovu-em||4*z@?7>d*rgN6P*n>Zy^@+u(#Wk`h{$}Hx86`xvWT`0}lO5
zJEd6nc~)KA4ZJKj924X0kzv26DXs*KuhauB;54I1r|glMZ6`<vvIQeRcX12^2dcy%
z_)nyHx%D6+Sxo8*c$+w}zIJj&>k%xR4Z?XpKN+Xzv7l`TW_*Ts4jBrMUwjcKPCG49
zqG^yl_)}SwUhr7<u{(z%r8pN6&^~E3AF25`Ebo*z_*0K*a(0b!EeuH~@&L6gNu!i>
zQTMh3oy(1y<T@Xc&Qf(-lwCRNKVbb)wyrWvh@&l5Nl=W-KI5dJI&+0Vb=^Gj+2Qf7
zrs>K_Cv>4|SsU_EMy^rH^pj_&$}&T}WL8OLixkZ3E`K>AR@D=J5dM;XqXgE`t>B1Q
zzTIizW*G%Q@)lSSO!ax8ku@|OR`rOLXz!_SCT7cU0k6>xkoj}Uy^UTt=!{9(*kzWZ
zN^UIuMtvG_I%yf@b24FZ&75;mDuJ$M$r4Iwd>fX#LspUzZVlJ4r3e++sNjI!8~)m+
z0PdWHAE3C&y02)4+V;S3FQTKB*%s3QI~O<jhZdi9wNg@~xQ=;A=RfX|E6qdq?ujX#
zGv);Xs#C0x3r3f%V1elS)pfuuSegltUEHzNqoC-g)OAEHx>#zPl(ZG#Y><oY(qE;K
zt!(D}i8klh2QY}+Z$e_}1zoyDC1ap^V<^F+o@8JG&7+oO;5i{G%t_F@;T%(~EVV%}
z>RJ+7hQ8@3gQ4TT&lavOwG=-4CT3sjX|^A7wAiIplz%oS0j4QdSLQt}a+~EEBZ<?#
zZ7&JY@wmY+=>0u9uqbzBlCY*fxTWP4{@~ev@TXG%l~E%Gw#XLNM4q=){)BrR_(}*>
z;}`*&8`aHFgKFdbdq?dop5nHP^|d?oex{ni7>-(SwariyBmwN#CwRzcP&1e|*mJAT
zDOdh<C}C2d*1+Lapk;U-P1cv-H!1g381yQ1DKlE9OqP9<%nV#L$%iwj0u=!?$KlVG
z&E-d~*TQA(si`|T%4##6KyK=C*3WWVBm|e>E!}EDYIHy5Ef#mSTCBz(3>%!hAX?f@
zExVR)iL3%k76bFC>(ybmVAXQ=!LLHB=KHj+jZ4qS7(JL(*^^96Q5v|Qa*nM&E!b8d
zc}8H3E!7&wh;r52b+mvK@+6=!HqO-Xp1_~lnojoHrmMvAj)2)rMoQ>-8!W5|e_YV;
zfWYY!p#S}g9Q+2=8V`Au^o-R9l3y_lrIW~~*7$`OXy^I(CA2`#0|W)I>jM@fJ33Pf
z1SjUqBiE%Ko7HK2L+rQP{oICiY`JEbfi-NAB`ERU?bf<NZKi@0?<?@f%uPbydiN|)
zk(d?n2{Z5#hmY}xdcb}4*>l}Z0ATL9Vy|p_5$mVjC=*$6$tNo6o#Y>aYwFz>Zo?|I
zx~PW`>9$6C5c^=HNxSS&@f<$&j~DNajl!1Pk@dkcWJOAmli1WrPzu{HvqST7!C*o$
zZtP>|qj>bS2(j*jDC*LEW&Ca{^XO+H<n$nh34%M#?bG)k@Ved!fr=`oY(3)(!rY>|
z5eiE4G)r7V;gV5vp3V5}fV@Itp?QBQMM&Chbq(S{--&fC>_RUljjAV;fDk39)~f5V
zi|np+GRyiTd_{^k&q|{CEASc}S((V(OSJS|7eQEo46jkBfD$DZO7kfUjiaR)Cjb)h
zS86vD!4oe)Pi#hI{KnK;#_9M9${oFr_Sdw7hQwTg-3M6#uCboj_0Wz}CwEjj4X=AE
zvWVF+!<A%x460Hr*?2czD=M?1hp@_^;^~EIBCjW8e~7-kN6561s0KyQuk7)~t6-Ug
z?9}fnr3edKD2*zae+wYd5Z)1$$9cFmNOd#0aF$OLc06#~#OONB-!jK8EezzGI@_Xq
zr{0}{J0qD=*yV}zDtEANX?`=1=8SQ$k8+6+0m{f5Do8SU905V)-Mq7eYHK8R2BKn0
zsO4(D9%e9+3~X+*5|}tTeaUz~|6<f-hv1;0Ip?zhN`+z1Fdrf9)?0$jj$I<rX?ROE
zQfmb`qK9D6v;AzLLxn%t)GeqEj*Wqj@dFx+k&pQ}5r9E`YI5>HBma2wOT<TL4th*W
zEY?{Z^8&2@kc=3_o@m!$z}A!|Ucdj%GM@dehFWDjoBsr1P^sDP^mop9wq_VvjuxYj
zFUax_N+W6aFnwG6k9j-l4OT#~4YZ8>NCbJZy_+%}+WL%UP!Z1A@I^Ogn6X~l5B7bG
zUStm1R015Hy`P(aq%{He(|DjZa?Rh4l1SqZQg~#8DCI$_JE=sjUJB_5nfdfa7m#de
zZ9QW2&UFU?9IS=)U0{p0xvG0|xtqEzKxKFg!Un;mFx?T?s6I5Qy_l48I)G4ZD&>{+
zM?|m=`Wa0yy+Oz|5J5HA<`lse@HOf5EZ_=Z1tPrJQezZ3<Y<~_eFm`)s9Q*Ab!TRg
zt)Adqb`O^GPI0W3d#~_OzMItSpII3ovT~DzgK;n+i{GXE2365i1XRhG+i>0RGPV+v
z#zJ_}IM?r1*zfWBVz@Xw7cP!?Q~ZR$S8I0`B38BB1z@iEE)Tg9wn)yvMlv%gp-|Cb
zLNB1u(UXo1(vEN3W$lt$b|$J%>3H2^bOaXzj3TqT$cNt%!Kd7CDgRtThRcQi8qV;e
zVrf3^5|rg*bcsK+LG~w>axtF6{5}_To#KOX!ItaAMKld&wx0(e^9QU@`&U2+&|>k<
zf&&h&ibrHevZ9Oau&+!!?^2SLWeK-Fu=N`XF)bEWteP3<Vlfh?QmHU=Ym2ELhVvs&
zARe4g!9i<bB=v-tYB^F_Wl$Z>wVk&gl~$E8l%S9gx(HHattvB<OkXiNNy26#A9&a`
z3NxOGgU;XZJ1h~82+eq%{y-!Z3Z&+B)_l_w=AeByCm9^S1a@tjcC!!)L`*yvvjWYn
zSbue9u(WV-bde)^1`kqfBgXJpo_-!kx(FmUnJGmw;>vv|ZgIcN&O9;-{*!%Su-aIx
zLShh2fp<RU;5ax_oFEKlhB*_LCeRtHgC5Yb(25PP@?C`of7KugW@B~moaK#UDMRUi
zGRDF8vuG`JCkN-jN|?45Ze#V3&h;NA>LEVsc*JHk`Sw`@o5TleN2713PBzYpIHB)r
zc#UBRcD7m)hU=wc7>bIhECb3R9!B`TNc)I5TcEbcnV~YFWY8nwFYzrP5jg~e%8W<$
zE<$ps2Em9G!%>&qv2X32pT~nif_O<3!F^ZpgknUxZF1`pL~?CnuSba`I3&UkfhZ?Z
z0Id11${a-bfDmslmJljK{4IGQh?VnjWx~G_Nk6CtLC%Q~VIUx%E)~VyEFlWob)?B^
zW0_QmOE?4$%827QuKZ=V8oA&508v((yX+V)7S63HA@8d{^rnTkY!IFr^S|L5QS+@4
z=Sk#pnuFpaqFi|H@|RiKgQ6pRxN2fXc8Np4+jy9Y$%V<Rw9rq@X}9QVsJz$}HR2wQ
zD<IjICT@UM$i^BTaup!U29Qf=G}<fs+Q1E>9bz10FBK~<a+dBpYxYh7>o}4#$xI>A
zZJkRdS|GUlO(ld;TOiMz`FX}ZFl+MhiED)Gy6_t(h{M<v&W_H*^LccYL<qUPZfVBq
z&_s_f8cf>48A?zkz$)X1Gffhpxhr3w1JJulb%~B6o-TrLc@a}K<Y_eUnP5Y*H}NVA
zS|3L=&0B&ih(Pp0U~3gLD;xq?`?W)UEa3%Ifgo7(BbAdL)E<GxOVMa4kU_tca|5(P
zvKR4u4t4tHgG3lz$mn?J7ySjY2C{euDb5{U5WE^*dV^}|jaDH=^<<#>HACJv@v!in
zJe_CyB>K<6XEQLJRPLA+BDMS@Zxx+Ii(n`<<L+K54swoaW&2;I%hGFkVlqgLGI|FZ
zIT^y`O{^`kfJAv}Y=xSe+&V$m|Lk`hfe!ZVYGaCLqsf4KjfqVnTkc3Y9rUijX~aV)
zVC2WQWPG35rn|!jt7^@-EwzXSK6+zE7F&@q{o(wY%cY+aoIQc3pwfRDd5Jn@MjWa+
z%)1*Omr?SKk1;u?zqK3`0;Mo$pbZxjOCp`GXaqwUfBfa?Z$gmGuke{>$ZJkICUpLQ
zL%rNzb)7k#a8^Lan8Ts6nkJJFt%zsMFtNvQqHqRlgi#)Rjj%+&CGEfysuGShjZIhA
z3G|GE)G(??zaHTm#P;^=o`+Ey;@NTnr#8XA>gq4fgdd3<+2MDz#=8~0Lj};B7#?}}
zU_{<t<ikO=rg?T-!Oown49~aJRyzUP7GsCsg)-SCAnVg0b-YN=3Nmmk3a_q_1pOhF
zRY9_c7(ioQxYII9FDnD`6c_OUxt1MzhGRpIxv`F#a$%mFRFj9v2_DF1!dd0IhE7W8
zN(3R7MMXarC;q8!Ajmy0j_o35v_?g#H|r`&1<MInyxQh403@$r@WLqrJeLvvqnYYW
zG?WKKE#%Yz_MKEG(8<~Rdu!&oWW9Lp{LLqaZ0akBZYJDAh=?rerCoD!$1gc&jNLN8
zs5<1iG~3_bj@Pa8bWqD^a*UIB3UR+JDRXA40MHdTp`J2KM>kX4+QtuuP-f_ItoKMu
zqNprEa}=5J*o~aCrdy1IGO-jE;w}{y=>?t>xN>)>5`8*z&rz%{S-B-#u}Qz7v-&Pk
z<&OAr)9s<7reG^AjE9`FGbGN(AhK<Q&wp6NQS=TO`Ru4&qyQEY!efr#W=*?mxTxt6
z4S`lrFhCWyEm*dM9?|5WVyq)AL@hQ<MCZxTE_tfCfV=V2h-ZUmJdIG~h~Qs?4B;Fk
zzQdph!XDHv2;a(`&?)fWioI4Vh~J9MDzbnt+eoG^YzYdWLYrF`5<-JHy~rnmc?t8}
z@s;t9TN;?!#u5zgZY9TR51+x3yCb-%0#I`lkoK#w;m4Z=S6Hm&Lo%UuHWL6%3`O|a
zD#bESz5^LYek>`}R+iScfLcK5>mVu$goNAjIp7i->p-^5CZK)(tk7YfM8-dlEcc8>
z(gJSQ8Sb(QzgTj-!%3ldY0Hc$A3lgZUoXvkZrzJ1k3gj8q&FH}aa+pR63qSUsbrQ&
z%5NFZyo}t>Hkf%1<&2|t$4@a7sOgN4xktRD3n`%-&c2MSNLzm73$f518*aj^)MT|s
zny;>^brxQVelX|?wh+0N_XtwH^bw?QCyI`3$GBo03D+_}PCOX84*Qe|7`V8$gR0+k
zi^ml!N|_O|Lkoj%!PLE_B)kNlEz2o0)jf-PZzkPPS6u_ek0k^?TB8*!gGKHsft3pH
zYz`7;71duyra4a~O7X7IE`qbWrk(8`V5AVWTi^YGYTR=1M*${EJ?u?R^_^6^x%43*
z7hQ9^j~b_`bm8DJTw9gKEw<^qq^%5bwEHu$7_=J4#})vpke4eIP?=^^a#CL^qwktb
zt_I`?_vO1uVyLTS1#GBGZ08=_7b!g6p2wuAR2&%^r@>_55k{z)T-Fbq%$OJ~rZnru
z1rW<nfCR!AS6y8Zpy~I3#I|SprVUDH+yU-PxFJwByy-E*aLpecM`GCJoD8Sfa-H+1
zjG|iWN%dTVn(N4dv@m*7JmHBVE)Dnt7m<n6yv;lJXueIn;UU7o4fvhH0ku044$|sW
zAqbDhg1XnS)EJSlTS7$m|4<fuIM`o^5nd(*RMxx}<-f1%#KTN1lS7Sxyp5|ahPfYj
zzHjUeR7+b4k4i<X>tDhK;82#lOAV4G-LQa#rn82O0)UodRe}FDK0?<w)k%~o;IeL^
zdSImDR#If{;q5mEH~HlbHXTVqITQP=B_q_syJt?%y#0tOXdUs?462VowA1L@KNo4J
z6roEi-1K9o*|;pf^HS5e?E+ojmi8ISH0tLO2*pBnr%YczZ=e}H1nianJ$n1{8RUb;
zwSLC{gJvYbmeCJ7F~lpwF@tD=?h5SEMN_4Ol+1E7kVAT*a>B(>7zq0%6bZYq`S;ZP
z19f?rhajP*k%Dz2m#TYK{)d4(e{{VzE32Wm%UD4z8P#_D)T7AvGfNL6Mw?aoJ{Vwc
z_Xvp=(v^Oc1Uvf}z7xsZt>55VeUgoXzt@GN8Uxqwa)+K_W=CzL%H?MyG^@xV8xgW{
z4{<W@saI<9lFw!~p8x0`q=KZo|A^L#l;|e!*sLk?KhRm2R#+jyw`xqAE~F_NYW>=y
z*g5kUZWshzM&`ASm}=R7nMTR6AI2>pM`*n(n4eMmgCLuvYHb`j0yMItC6PGpG~j(q
z&a?fCqg>{|9{+7q$4R+OPZvgPi*;lSCG83WZ&3`cg`Cx|A3}!JFaoohlx7L!@cZfY
zyRy`qcM2FIV)vDsN)r%rj?Hr}S?YVxc8@}>E3uJ5{<;;r!X|Uy#rJ!eF5$`TM?wb%
z_b$)Y482mn>yJjAz2I}GoF)wSw@nsEc?%w4bNZVBSG*It*(W<Gb*s{R7j#WnG8Vqy
zpLC87Zoy;PfT(k*l%^4k<r_E0h;nzC*t*W%#r4UlZPm?uYmJVgoX$a<WyjX$RBPlR
z=nWKi`)QGO^0Td2=T7jk)>w%GnP^9iX^r190W-Y%sSJ)!ZoxC!G7w<G7W5G8SK;bS
zqVUVevsMw<)%$<`f-vh2|6XhIK$*F@ccXU_yLWbJ7lr+{-aZJk+(*=i*8Ba_lR6cK
z)QO$|%%zi2ze4#fA~hL4fpS1*!yZ3u*m`uaaX;9TUVqRvTe#*Aq|w*y>9WR0<Ja5p
z*SqRnX@~lCKQ2jMpU^{G&&Pd-^>nOL+TGn(Ps7*6@wxo=*N2gB`7q__=YpG+t#9?~
z=^bHp&&wv_VVD!<<BR)pkMGmV+u2=*z~^bp_Sf67U+d@PUDL5~&-(4>Nh$N#XM5b6
zz}>vS*GI`$_uWO!@z>`tVRd9hdS=1q*LB$*15{w;CMQj{k<k|Q`=-Fhkze=MyFuAW
ze~V4?uQbhHbY=`K-mtIaa=7nMMV8}HyKz+Q*a1V{VqXu0e&k}loTXQxjTWvOeiKeD
zwjY382m^;x>en(vs`eb(eMYzd1K;g8cfZ$<D*@XSc9_85`LUbjPlTISLfqYz&is<`
zV_UyiXtpYR{Az!_Zl6yJWG)F+wMKXAkmRLkY|4M3)7RPdTCP`JPWdq^8C*6I>gGJE
zne|jt8DC#8jGMD27Zw{#r!Otb@aM*KPpivU^qA7N`gvzn70SJt(y}>in~!HfKL{77
zTo3c?UKdX>x(9v)%2QpxdY9$C18pxO+OaTV^G+XanS=4I%7}*`_~s!`%`jp=Abt6Y
z+vw+Y&y3F_x()H$e@L4*8q8sP2t6qe2v7KG3;-F`-iBZWZ~q)HyH2uwZAlI-)lp~`
z3ir!`j}80_UM#QzJ<NPeTcP~nK?qjaR^qhx?xDloiQ!q_bgSG^^K)Q!JxR{o@v5Hw
zhq!Wc(Xy0%1F;9Nw;^?UpMi<XhUZx&t=#hMq1JVoPbVbCyJOzisL+$`VSAS;H-VMC
z-!I+TJU9%2&mwZ)P27FT0cgjU$Kzw$>@}RLPJyMlx5WK%laF~utaH?3-SUNnzU7Wc
zxp?6ptAjfq9P5<=w6;t3)bR3Q3eDZ!MQmV7W^b$?eFQ5;6Z^D$*Rbk75Usv6l=?X>
zDFeX!NmWy6YrgEb`pg2W_lmE2%>k&`X1F{6&n(*`W)N@xQ^d#Kh>6>j#Uo5CLC_o2
zyfOH<)UiI?_wQriWiGliFODg$o++Z-{lC6BfBzJIS#iWultPLEuImU^p0EuvKzl3*
zuWdBR%C6x0!OMdv_em}Nx{O-%rcxi|{wldQPJBs7R*)I^srn*!Rhi}pSmKZgD0b;l
z;+8;eFJBGE(V50D;}WPDh}v7Pj7UBwJ|O$%7xUiR`>4nXu<1IMz3}K0&aP(?V5oeJ
zhWq{_45MoOB_lTsX?50m;H~r|cHdl_OWbGREPWf`l{@URtvdaX;I+4Qptde?-<*rT
zRnMqpAWB$z%1?axn5Iz>m+p<98&NaH4|pPdnvOp(k9xck_*h-OQ|amcM4X-l4}>wZ
zGj(=xGBdLM=aap$6%0EO6VX5KL_|dF++3W@|K+p(hyUZpKO#mk4;Kj)7b6!lqJJ~~
z;TbV~H;5QTgov1l7)^}6DL?-|%KxT};`Vkf|4aKPJrg|>5y!V#<^L#s>-{GPmj7`^
z#Hi}&U`E8KXk>0iL{7x~FXxIzPG;Y>nE%_CQO?ZN(n#3egGlF_#q=FGHxV-n6BCi%
zztly(9e?XP6S4hI2MH&8SBL)<%)g!di~CQP?-!%Ww`(UOJ7<S~oSAt3mn}u);^b=f
z-<HU?mZ+JVrHPrcgz!Ji|6HrGnX|pClZlx#(Ldv+4D<h88s~TWpYi=?q-4$P%v~&q
zxc(<BaZ4K)GbbWOahvav6*V)lH~p8V|0psOak6o9{A24sQ|6I<q3P{`Ce~bYrn1Pl
z$;UU(mjO+dL57-03|$i(3<R8vESeid1dO^-D`YI13=4IOq@^!I<R5B2bB#kz6j;w(
zk3?{Oc8emS?hd^*j*f}0=t5erkH$%n;_U^((DCH_)wTW6z0R(tS5wVX^O~a~LPab}
z8U+>KTUdr#;`jW%B!FsMMJ$RVVEI@H<VnY$7GEkZTuPPkd9r}b_fvs*FwD08X_oRR
z#phB#EABx9nwe4Im#J~xF1}A_{K;`$&9UiUre@lrm0yJG)JY{%nQx{=%vkH3wR-P^
zjZ&!4+_Q1<ZjU%gCGy$4IVoeTwI3MGp!0b?rd|ezHJY|h%)~w{36c?|hUA?v-}UWn
zMn-=T-6AgZVM<4v;@MmLm7fS53LToDq8){y(2^pLW}6OfJ)#8&JNkZ2COPpG6sGGZ
zV@S(5!k+`Jk}ylBd+y2}%uke(87SAGEjx*6YlqM!DL@(Rzi=ljQXSv|8Bv717>5L_
zNdW#rCQ7<C7<n}DGJYY+BRnuz{Md>XHD&v`Sv!iwPtlVPx_Je`nFQlauJwa5-F6ot
z5CN5OMq;aIAhY7JHbcZJj4fwf<nIUnpfMpbhb`o&a>P*l<AjY4OM^x;<I6yUc}TD4
zx;A5-aUpH4EEIWz<{ujNeUpJmPMcJ0<#aj@by_v(i+5E}fmvDZKAYl!ir;sk8s2vV
z!rGHdEnb)#fc3^x@zspsngTcmgYH?2Uv86V!;{vjl$<0;=XRMnVm|tb3k4=t@*o^u
zNB1Y`8$#;*f$6CZY3~ejY+`KTHI#T+KR&C54ZNQ=m&JS1ho>))&o}HGFUET!?Lh<D
zFEb#UZMfs-kYAEVoC<rg4JdgmB@#uHoK{5or<!sXFVuQ?fxnNvejIs#*U97HTV}C@
z9A)8K)gl;AR&EG4OFTeuqpn)3ccuMow)+Su-#bDS2+vYI{4LtW71Wmd)8tI3VZgYU
z3Vr;K>?>W4L|*aqT79=nv<a*hvg5p3K|rL4GX35XogV4nMg7L0t)_g?3S(NqY3BT#
ztF3=Q1;y-(({q)KfK@wON%5E<p54)s+&T&yS{*5g@g_zEy?uvW)Z4RTg<ka}(pqSW
z^&!AvmLDz2uP8lM=S4loZ;=5Op3+5+VuQHCP}KSYZeEhZDY{_oV@=YelSe-bK+lPR
zeGVTd9uJkn>za0HC*hkoD!V0rccyP%NxPIIt!xpAW(b^nDX9{q9hti)%g)or(*~-}
zm?+|0D4RO!ZO!+PJGCWVO}m_9xhW#dMixReDExygEIHo9pGOkc2F?}UHLUUnOJ;29
zP(Kw%WL(lP%|0GtIii)xL){dJMu2y+ny^ga=$c9O@P^ou&#>;Yt~<6?8N+-U_jojm
zM#dYs>+kMat<!QBjZ?L$uIjE!t8>0{z@inOvLsAflv^>kh4BaVq`GBu<FA8I^Cbah
z5=LIBdp>bWMYekP+-f}K%wcg3dw)vFgN^$?&OC^&W%B_AZ>{9CEDiqDk5Q~NO0{GW
zXBblpbZWmJWtP#x0NMy)EP^UnW(c>u44dUr2&<ktIhUPbp&D6kMq+5R+Xb53fR#{=
z$)ESu6IM^C(jUXkRqMy>Lyek8^E_7Wb(d?JkNJr;DHaW<^ES;aGTy25v-*bXs}yEA
z&Eo4~21Y$Uc~kJUHSer@xir}MFnl&jhR#lB5+E1ly?ReXoC`3o3hq^%A7o9aHijX~
z2JYjP1czop%76$&ebMu~hswZTsZ27N(-_z|=HbWmwTo17udp#=)JZ{I^QA{={t%Ak
zp+^m$=HBhqa{1(T6X*U=n78DiwQ5_r<)}gzDKt`UOcxqgf~=A&4Prz}LSvyjNGysm
zW&TY(n1|$^4xg6A_&eB+?WdWtPUTAvIRc8XD_1zEnZ?7I9#SNU6$x`0H91W&j&e!G
zx>^&G&AU`{qUodScvE|-bvTXOv4^?NaTs)fkqv*H<j)b>bC^08&C7DNIGW7p@vUR#
ztT@h}yVX#{!?;r`7R`RD3y)M07;|=LyW?T7=5IC*QFf36C}D1^x3>i%z6gv_XGdWl
z1QnN)sW|G5HKr)X$P;T}=_zq<V#tiAxVJ&ly<&%l4AxEJabDIrp=Z};q~wro)8;`M
zcI#Un8*!Z41Z>eC^FH=34tG?v>$l?TM3E^6c$kTE36~YVM;S3Si%SSTA7w4u1y{2J
zbJeL4>n%N6<da{-?^dIQ=e6s_Mi6tgNS4=$Tr7Oa!al0>u9Z988dL%Yg%WFow+lQP
zZ~H!p1II)I<Z<5d0w9IM32z)sT{ijyE~Frr1^1sf^ZNrgSHlKz#~)IDYX)am=Y+!@
zRM@d_O;H>%vcKmGExRopt#;v(Ga0EtKD&G*oqIzKTwtX|lVNmLboVO-xDFQvlD7PG
zH;_s!yzWX=%TnB`OMe_BQbhaRsm2k!@wgUrm5Kj85xkkbk$ZcxZSc%o^@_;r8Njr;
zkB_nKCK}3tXXc-O1fO(&4b;&w$-p5drB)U`1D_S%?FW|@I|pA2n?k1@lyVfNE4h1y
zQlhO6pBAOZ7dElP!&fFJKv^GjyFsb~AeyXU&)yg%+o${$(|#{>r-DG>-aIRK>|VTF
zYn5Xj+{fP7qUJTeijs(|ueTF@zcpK^@x0YO3IGI)LGOYIa*JjEW(1hv+~k}zDUO!$
zH*&V#-nP3kuD2bw@z+cXh-m9fPxy6B7l<f}Zyx6@8>JFZ<x<5)UNPh6Xm;Y36_{$D
zlXHc5DUj!dy<*Fc7R5=)I+P{?Vx(kcvGPx$BPJxIEwS%XU&q!6>sJa4tD1P|h2~NB
z(QXB^2a32l@ga&<%>e~BELMbhIwa`Z`m8-&M{O~B)ip>{$&y+#1)+t?+E|%q%kS;m
ztMD;^sI5P%8W$B0i*Gy+K+yT_QuA~7@=DlSa0VqOjlqqB_kv!^(pF{a<!L-J@NqFS
ziDcIG2=Yw5;C4*J5XQs^?{xZdlag0?pHcTAr%`jug<<nGB`p$AnL@s{<_owvlBlKA
zw3OS}KBha+Q>U}23JjGvZQedws{^>Ngxj8X0z-t}fP;fU@(RLL+_ks&VLz(X>DMb6
znelO0csVCmuL7I#fP({0XD1kOL_&0z5*yw6i^X7$FQp)k^w<?MqioEJc)FbHnCe9u
zt-p@XO<M~JmqKiHn?Qm5bwXdMLgGH${2BLx#;V+buxR3&j_vER4aIibb=y}JsF<^#
z)!|X^x_2te)45#;6`6hv4B?0tl$pl!4mc(o)Crn*=ZcvFdn_7sT1SS=Q)E%j9KC(y
zK)2RvN6DiIg^{Pt#DK3C%BO)#2VS^MxfoCz`szFBWT|peZRvf>Sbb%MtpR4u_BceB
z=oEsKpEAzR%9h}a?l$opy!>fCETy_B`$XcqI2O|0lKVM_^3n=RNl(en$+E|MSj2Ev
zQApW{BFI@2glb3Er&DURkph%yw1-pDD>U|M2)*{ns1Cv}?$3g4Fb1_1?=mkGKGR<m
z?$p@<?cxcuWGNI%v@iD^a~xyZdqnC!%ZVQh0?W!2la|<XK2l!a`@OTO73Jx$4+|6T
z<0ZC6NOF(ZAxmI*aEqIy2Kh6P8%rI}N4&_QV_FmEnYzu|*~*Jv^>_vG>r1{@gB`7F
zP7EYL6b=a0O97zv1co+=2M&n&BQbAI-+9u?s&)@rtgX$iwsCAHsKmX>;|U_LOdY9m
zaSV}wOn`v(pq*i&)Xo;d4cwSY#ygohwTJWj!-G-e*AsDG3(_K~uAM;3uiZ39<bS`)
zuO|po=D3iENCJCCPY}~apvdti#Wu3u7m}WSOufZ8HU{&H<%OCp)cSJD1=_e+k2Wt)
z0BcFA9)vp|%eTnx^c~44ZfAGt1Y6G5h10bVZB2^)l@qa_i+Kh#Dzn$IA)!BF8@YD<
zMTA_UtVz*$b1Rg1`wit`@{SK$OxPJwo^6*G*0W8u(2Udq91`1VL<$SCe>kE>l4#>D
zB4Xv(KR6f>utz2iLt2vgF^~eFzwU5t8L3N1+U*Pbv~~}F`m+dKQhd<G`Y@>y=61<j
z>$o0!Jly$mFfk9Fr*!O$B>SWL=(l}fpUGwe&6r=4<8t;X>v4(81|igY-BCstM;?0V
zZ=;ctJR8`ep}`>`Zvlu<GN<wh%qn>Cm5$VeT2Wa!KxR)4v{UC~KI8Py+k$mnVV%z9
z=OrCvKb*GXO^bKtgMEWps~+q=Ih-+^@u3^XvH8E2{JeIa(fv?SMs;+tZ{`WBw<>k4
z`#)dO;^)%I>tyy)pWTx-9Wlxo!^Jb_lkVHIJ{z#mGG<s#FOHBsB1Utc8`5O_9NjMG
z;a@b$+-F3X_l9!$ypLv@e2eXHcuI_Wds#Odsy{!Ec}s?)dPLu~xzE~2_DobHe^HT3
zQ;3%(1^+&*74Ry-c1v~DJU761aZ~(YhF1C|DIE<9cp<e<BjpGA-O^LRd{9N|+NfV1
z=A}M-ZrW+NL?#(>@?^)$N7e=3P2TG3Y7>Q-SPv*FM_+HL>6KkX&XVYKUfOIqx>2CQ
zToyp5-^0Nd+ZVS9?fzcvax;>EX~07_Ss`~y)s1W*ph?yJIc~l;J_3%=<qFmkP$}H4
zF7_-<fo*C?wL;J)oiYHeH;~%|U7_M`+U#EJa{H$IZijB4;?d+n`NwQce&%tFL!`x)
zeXc&>9f2aSIY~;0(j-d2xOx;{dFDcNGuIy`QN3!l&3Q6YkN3|MxwX`J9%E!v)ba%q
zr~MWhXGLhGUc2eXE4j?FG$l<MW6g$cd#96b{?A$5tDdhRK&D_=(&2H9KA*v_MEUF{
z(^0yKLik<(m9H@_=p^wyUf`M&L0wZ~%OaB#QJ%EV#Ofq@X-p7&(2M~70F5M`#^$xJ
zw0I_8e~jJdK%IRhuH3i%X9WSYr&dAQQ;c?am1lLHh*SJmgxK+~J(=Fb-yveCgyKbT
zCS1a6Ur}8@1ePjw?DvNW(78X#hS8~WzGg68CG<$`=pH0D1Ki`k{62?8oF(b|8ltxB
z5LboWjVi!8%ncPZ%ZbNFR92j$mxw1^{&edd@Nh@5rX}&L3_#(F*Vm=R-|3QYS`e(p
zSsy4fPX5v1Fd|+3^$1j9me=4l7d2`6P#Hd1xO$C3IP7jT6@r=w>FZ8XR)je!>x9+q
zZ^JcqX~y7$d}f5$7TCe0+Y_6dM8iU8c{68eTEJ%D1>`M%<E0#7i4(j0J0(}_3}L?L
z0MC;koh{hr_i=m;&n><djOUy%SeQ*2*r`B>_2T|hiYW!@JKkb=JdX*Xa-26G9`$|!
ztpKLf@=fw2rDvhE_)|66K11`M+pI~WlD<O!0o^;^&)zT>Y?+@Ot4PXQ6u?v@hplc!
zA2GVZ$HZ4|nf5gdlSX1Lh%bTY)QJ0Qls2&r(;su7BTCTRk)E+OBnrN#EL0-W7qcG9
zHE<@_&wSPSbb{5;84%p2FiS^CzJ;MKAu!6Zv|`UG-Zxj*<Me+~58AT%X?-QmcJ&kG
zrB~RK*$HIVK?zh%rvw3oGQE|lfg({ABERoIuh7U`FK!hk{ma10M@y|t^z)mWTvhqK
zssgPpYeMsXXM!gQyp;7Rw7X&R(+DVTvYc$`R3Ol_W4;X?m@L{EaXuopbF%!j*PaY|
z#?@BEPiNz<ozu<OFfV$M%&R5~^q&h}lY_?m!?^L$O&$>&4xh&-aC>y|G>Mog(F(Hw
zJIH@yYal9ZRvs?Vi^M5lfpbCAy7=`(2|?c|+AbRD$$J~o80iy!Wt*O6l2iNpfMLRS
zwP=X~OB}%&adjAH6wVVYW3=ml>0Gw>22l!LKTV-Q+DUti+<w31QCo*e!;oRP^K41~
z$v8Lm#e@vbvT;@wXEqfZKqhf97H)aVN(Q1O4O*`p{NfGP=rb{rg*qLKdOigYmGV2j
zW-GXrIji_1&pWsSYlJjs)KpXg&Ts^_nJrx*a)`4c1tUb;4{7Egqz8QWjjmM-c)M*!
z2bdG=T?47xvCn{Z#|x=j-xKjmySEAExf}#1Yll(py2zjLwRaKty3K#OerN2E`CS@Z
zcPJulxVK1w^|^@RnGKX5`MS<OO6%I3(MJ^+6U^r%;7b?iIIh<Z>KUlSuNG*E9q#BD
zLvX;5>#c<AmwIpB-cB6I7Up%XzW`KejX$d^^n0{_JD3M2tUN4N+r%E_hXV;tEG!qr
z&J)NM#&xRyHnfLIuRS;(x`Sx15iCLq#0xQS6J*@AHZUY2+HH`;&JKy&4yVwse5M5$
zNa4SnLMx0rF)*db*X{mRz&#kXHCX!2eHGq8?~BGO9m4}p5Jqv3`a%E$%fL+#eT-U}
zUU@`S=#`tqsH>5{G~H`s=3qzZR*+`cmFC6K7U-3;VEQbR=TzerUCY}^W<|?>Seze>
zhAJU_oY19AhNQn5>p(av-EZJ6Yq!A9GYu~?NqwsP*$+c}CXqE8!czn=4-P{V35=(~
zceQ{kG+g&9z$?!nXcHz=o&;B6a?(7FLJ-F5Ogx#B0fo{*wG)8`(3<Uodotj3b%u5R
zVjvhWP)(mseITDQz_1v-tbdpUriYIqcP)YMz$RS#@F*vicBp|HG7W#C{#XTL%`|NH
zw*>i=>qV8iZuO^L0^&D=`$1uN3*v!>OAbPStVm~==pP0y`xjJ9j;Rki1cU&ENncQ?
zdk8j@$RG&vx5;ym7L$Ch=7#5Appm;iEUR1Qi(O#GXabBs60lfB10NvbpA!e9;O`T`
z$RMHnBM!g=p_x9KXmBx{&x)v_SWKF|zUWM)AeZP&if3bx9DV+z4$}@$&?k&LmmNRe
z?HD%}rzfv&1$(+7t}v}!MGQb+p+?YWI?~df>;m=q<hI6P`J7$0=7aI@y~qTcfweYW
zbIJ2N5HhfNrrC%@!tC_awkCtCX<SAFr*Z;2ota&vpRVPFB%cJet>Q~ILCb_ruogTe
zIKf;ck>ly|gK!h$r^yh(B8lsuQQ|{_jl(&6<52El!>t2XfRTb?uz)Y33h<@NbNnsd
zsdylKKsrGHU>**E68<5b+MvC<K$pf2&`jC08%R5Yt5X&;;1(36Ab4Dp#DX`0x^Qri
z*xLSxwU}Ulp3$OeK{+B23wnC}N4kr5zg^<5b+Gqw%FiC)<hV?(|BGw?1G4@X*Jfj4
z`7hGU{eR(D=6@jMe__&$|9^Pw|At@n636X=n2^MtJ|ne?qr$^LrO1O-i*PY~OB)G+
z9^*;SO|a{Cu6Xw&l*?e#2cEYo62cBPesJ395_=*xSUQFnxp3^T7z7EO+_3PZ92!bA
zY<2Ig%jRf6XRO<5Ia+NnRg?!F1R<oc+thm3JI5iy0425<GDly6bksQ0Rz045Aj+Sp
zORDJw{R!C9=lNQbgOXyq!j(DRZ@(CQEP3AeAxzN2iak1kfw_$hm(!77KGzs(g=G~o
z^~pPqXnYEJw+XIxm|AElEvCj3B^&Ze<$Lgp_#==TU0#bco0X7|RE3xyIxjp*#FS=X
zx+srT<|u(xW;gMLNwiqlcQ#F_My!Tg<z8&z32>G1&F>QL3^h;1W}D6@mvD|v^_hIp
z?#%4cJ}T+Q^yr}Omfm{tl{mrysiOSEa%AjGnBD!@zG*Pm@c9LtO;(Kff9LF9Gx48E
z`#vY+zjMa?5AgqA4E^88{Xe+{Q8Q-~Crbwxd#8VZ_<yAv<c(~<a|d#=+G<*2w4!EK
zM(VCA-;n<Q$i<CpEp0rBsQxV?`bS3nZ=sEm`8RgY@;{ow|IRMZGc*0ay3VerZ5Rr}
z_x%;VK@?3C+ez$%yRLvhn*@RluDvu(EkRN_sWk1^?>%<Y#<awW6u&wCI3Lc<Q>l`(
z%T!4wbdi8EByvX?9(wa`%Xw43SB(2{^R6UJQOMkPX@AtelyHT1xG<ah%GPU;3{2yt
zm%jRVWqBA+o%^9f9-<s8$%r6~i2@;%<7kBGwtsq$Pkw<}P^7&2-E@_QF<(W-x~^ZW
zjT-{+)9m^}1^^R>oB4!<6LZ@DTG*y$S8ukNH=P{>zw(=1;-`Y3G>ITDPPaty-FuZN
z_SFq^gtw<>AT`rOvO-hY@T~L0x(el`6RM@tO(n#Ou#Ol;2Ro?`b8wcz`3yBd`ytjt
z^a%=X51#;$+TV>OlEdg*Gfv!b8589S)%n9NDNY2!p7$7QOVDe?lEj#kJ-K$dEkTc_
zrLnGMVkWW~T%4}^esg^VAP2Q}X0x_sH)~ye5lVdl`q$gGxgnT0y}6cLN}kJ{i!4ox
zZ(N>pelcG3KmrFiw=k&vw)QFZF6_|UfqMOQ)oQ|-NGE)MF{CBQ*op;BsUn9zbg^d8
zI4_XoNCVuXBt{xKl%z<5ox)ZlO{pwJ)MJe&M`Kl%Q%%QqSxyBJYf7e{_o9^4D1+Ee
z^J6<L@E4bRyWSa`Zs)n+i~Uzotmq^0+_p$M#XKCahh~M``nm`t(74`5S7|Bq<m~MB
H@ow@TfvY3y

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..8727bb0cf9a7c758407d3542771e16dd6ff4ca7c
GIT binary patch
literal 60874
zcmV)aK&rnbP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58fy-km8yRsG7pT8oT_cd-Z?XW#P
zyGVdUsZ;_^wGfReiih-+yYU`Ez`w8Mh%rWZ<vn}lK6!W`xZC5Tr$1LX9F7=K-p<GW
z{cCyrf2E%1+kgIX{Nr)H*M8pf?eqWs`+xKHFaDqN?Z5uFqrCl($N&4ckN@`%$AA1!
zk3Try{=cJ~Z~y1pKfV?JWc>e+&slpPXMOAae7Cc_{dlwbesz^U-u}bezx!#6|MXwq
z{^f7Sj84wCa=(wun$1Ubd$-!JS>As8ar}$F|LghJ)#h)1fBfaI?eBj3hvQ%U_G%bE
z?WK+P8NIakao+->n?J2qje|oq0AEx)?==-!E6T4cwR=3qk(E&XqSCBr$^RF{Z_a(2
z{r$Rrf9~!3bKl1OJg_K#F|gkKkFyqlFRHcrUY@D}_@Y{!pIQU(MYYn|T1-F6-<|(5
z-|J8Ie*F{kf0j>!1MqrqHs^b3GpiB!qT2QN-=}H-zNj|Jr`7;`QLSBU%~ycsZ?1qn
zgxC1VFQ9yX1?=&^<?+8cH~?P^uActCSq;D!)z0fvYXDwXtG7M3M&OHT^KnS@l>aRM
zp%r+H>nvB9kAF>jKYxD(-p=o@Kpo?~_f3!!_+oI6)98Gv2H=Zoc7JLOz!%l(_|zJJ
zFRGRLo<~5GzB~I50oH$C0=@l-{r@D9zm~@3aSm<gMHIiNa%~%T6~6fMKHpp0I|bm2
zYOTHBE#*DS-<<985LWk3_WGZY_r=Pm!2$SUaOL9QPz}Hr)z0>*H2|-x-RJwfH*t^h
z>q^)4Zg&cM6u&w94>{F-veo~DvNP;?Tqu8~FLGSe7q@}^{KR~peV6i4{z@{v+g=If
zFV>0;`K;etGk<)`*Z2989sg&v`@Dk?sGIWei@mhR;riI~<uU)`v4wx427ITRZTc){
zHwBbe%IT<nY-cqAFRNYMZ#G#?z{_egj;O3A;AORP#*HZJCGw3$xbJuSdJ(?!16|_m
zd>UXPuSfXU7~946QIEjuYLCO=sTRtwD?QGk`c#X+>uT4&O``OT$uDC*eyCs0{&&u%
zb%;MtB7xTfd+djGm~8cgysTJ@`G3xeiM+1((7EoX787}0v7I5jv!al1tVMmu^Xu!i
z_>NXqd-L;U>#2~}LmY7f+$surU2zsa2DgerURS)k-{-c9LS9z1^Zqo(M80)4Jao`$
z{cf*T<9j!h#~J)A<`a26M4b3rMIo;%_Ve?xDdcs<$Izb-vP522yyhp_o5*)o<7)5K
zzFduO-B|AO>GVwG<q+H2Ax}e0<aNbze>y-Dd0o+LujHlI720@~!2-Uq2FtK^f4v6Z
zIV;*YpH5DeUk`5WiKkiwURRsDjEK_93LVC?tdz*>ijTYX^HG+_H|D>WN2_1Y|93Q{
zUhhw5XCkkMxc0>J5QV(1*vBU^pUCTq*ZE1zC-S=DY@d#@M82~ckK3euy&8Ywj-yN1
z^Ofi0?ej=}rQhD?zpmatc2SAW)>+@%@LSsFe*dr4?d>dl=tJ{yfIkGzLyG4m`Y-=e
z!z*W>v%akx)jiJDd>fDdbN&7ZaTe6;rUgO>&AAW6OJPNe(ts7)E;m#h4)G7dc2U>e
z$FHjkSqjHOvKo<sMy~bO>q9+@k5a>Z+>x^ca+W8=wuY7+?(!S<@r;CFWC4ErzHIwU
zAa(o98u~(3Z;mHq`_8)6KalM^Ku*m>_o)np3m+mB23|+JoF9&|sWZ)|lRqjTYpQ6u
zG1y}kqWL2*G{NRGdcOBh<&u+SKB4C}0!PLTd(=W6qJ05V!v^3D#Tbj*d2hAEauu*<
z^8pl1LLhT%=kebThq9&O2IaYp$@l65$<0SZ`^HPPA6tpd#`U6(OU)+2%`jrCj!T=@
zk;5T28`|GO*lav<I&zjz2=~0}01w^%%F?oqXUnvgXUjq~0^gVq#P`HAlr7T|pDp_~
z978Kjq{rX@Ie;z2Vm9p?bM$xqci(c4vS|Po6V<hMN9?)>k`2ceYud~kq5)K&sHT-4
z*i%i7vz(2`mTKH}1KX#?&e|c{)<5=-W!qlT3V4aj-XZ-S5ZAq9yBM48*cztE7s8T{
zwuS%<$ag~J%&W|)@7M<^jye{d;^=V52Uj)uiJTfhta{PpcVFd_O^2*`AVb}cbuRDy
zQ<+oWvB)LoAXc>G)b|h@r)Ium1y9X<B0~d+H9fuC2OuBQxvfAf;i>%}4RQJ#e&T1A
z9s}&Res{4G7lKJ>v0x8?3lLj#AzXmwYxDq&tJv^vb!+}(`!0m@&&RHmdo5O^yVyHE
zK|@36Uhevg{}g*ly*M{(*sy#%#4lqZIT33K`n3(*C%mVq3kAm!jXdOXzqX<Kg!dG6
z%}X41{JIvxVH;+6#N-3=?hP%!VUCA}Z868GYVc_=M9%@J#iz0N3{#xK&wTb$Ju%Fl
zB%MKS^%Qo7+3Om0C=d%VeW%8UbKvV=$AWU?F`-Qh9u|j%<iKM-o0h@6^cZ!_RmJqB
za#S&UsT@_zUemDSk+R2X9f9y=b?Q4Yd&a4#dW{|WOzcK`=U?>0i`kdhdXj(@b7wkt
zE9TBn@_E|?V8uqP*^QXC6oD0!lp?TtiHlMAyH4>}Fl|-+D44dQ)hIDZMT-$P%ws`A
z--$^o+J^<Rlv-TDEEO$C{5Stlb|_}5XnPb))wy*jrs~{!gk6=oUBUF6TaRK_rC2PO
zuoR2Yh<}KC<ir%E26)C4wOe~6dg6#a6m!&W^(gwbkggB;9JO0LTAHYr^%?&iK9EOu
z4nRIb?cVz1^U>zkpS6A3+`8ktr-i&c0D0qc>yA%HOObg-DLyh{ybHnHj2kzUHrW|y
z!L?oN%u<8B?TfvEVqE1Ovk?C!FR1H7-OHxW#8g~ce|%@OYwM4p@e_h!+!*=T`r|vJ
zjjca16(jrOC3a=vhtr07GqDGxQ9>zS2zxUzaA}mGrmqimZsrAf+g-hxK5$(O$Hc(<
z)}I)7mxengM&7sn#K0wcVI6lQe(VDm+tzgGjOj(30|S@RCb^4SfFmdWX32*JwKFaS
zhXbas#2Be};+C+0qL0KN8%nXqO`10@4GX&XjToQAFm4eG;a|k)D2I;+6h%xC?lDbz
zC~g`H;gZD_1eT)!u!dDDhRZ~&nkBy&w5k=u#h^(v4`}_ZN;?`OezlU$0~&mjbRN*o
z8%r_3qV=No-Keb&Xx2^2>VS6LpseEhvdWwnsKBjA>Wq#7NG{_}v!0bWGf-*UxpgN7
zaLW2Hpq#c-`v=Nt!!3M38GV$wf1qr(lbRduK?~u^LA7irOK^SSuio`TlYkx#TD;v_
zG^m4ekFvNZEr6>Ab<pmuZ)-fqg0Q)p|97q!^g6p)@+KszM<{ScQGG1LrK3r=#qDY#
z?3n9oHr21#;tOHFe3u^%aXT40Kex{LVi=q8g|HOevFjay<~^WRS<3EEqAVphG$xZe
zjBDCLR`-s8q7o(z8j@Y=8x$hDP>P<W(5@ll7sLfD=&o!51KNxYbtSYJ8=9#2VH^uW
zU!bU1O7c)t7Q)>RJ;hRxLo2Z^ooy6Mc*=4=->u`{@rjhSCpKW?kN0#V%>p>tvEdiO
z*~Y1Dbab+QV;UrYJI`sO1dfZ`Dr1NpXR<X8vEP^mSpsmiTL_2PaRwX3a=+szLvPIm
zM2{hranoC6oTZ(|t4T6<9Is~Fybt7x?_z)8>i0lUiq2M@7;vI<NMDW4N>0aJ&;fll
zdK-R=#{y1#nB9dj*JS3zb#Wo=ZJdcF!QC&M8pdLDS4IZh9UakEqqowsd)O7tRqF#t
zbQiL`U;c0Q6z7{svg0bb5cYK7xVECc;y5!_S#3(n<6^lGY}*dwlslqCw}zLvA8`bk
z1UfE=waUQI!}d`npL>t9XF(i(`~g=ACW#7@DlUtw%;DomsCS4$KxZ_}@%y<@C9iu^
z*Z4b#L!i<gaTqR;3u5<i->;KD16=T{gm}l@y-J98*yJ4|;JuRq?l(#=pRD4OUnSJz
zO6dUigt2!hMbBi<?GWl!Mve}dUN82(vS*U=xMnVd-FFGT$|yz8q_Fq6!`3TjA6M2Y
zJ4mnU9pz9_?>PSj6PK0|Ts#-VArv_+a|0Fco(_kOdt}Aoa5z-sZ#w=Wx~IdUN3-0u
zxCvGs6mbDP9N~aY^^6-TE}#ztCI6Y%t{*;xe$8{E<F;05ed)NX)vo0@qZDnl8w&`#
zbG!YQxXM@zTtgk{tkb<*StZs_&ri68I)bg$Aj?%H7EgwoHnDg*(r^V`NDQS-ZY^CY
z8m>T9SBeJFU2&&?hvF(XwG>m-q&~NaNs__GyV|%k4N|)5($PXnR~>ncQo8EQYyS3B
zWe&oH)RB{wYWxXCh-*hRS*LLMbcp3M{)Fp;7Yez+8m^xUfzsP>iKsdhar>-Qr((mE
zq3QyI+h?s+@(Z`m1#wik6I7j*xPLAL!@{MYR_;MwKOI8z6zuh#l?uMXg@gWIWtM{5
zx+4%2xPUH*BW>yqw<krpEcXp2-^$PW&Zt$EtOo79>b`^vs3RCR1-DM!25rY7w9SYJ
znY$WAHxA+k18SA|tHE4aOYT@xe@v~jKOA^fe>iYT>wG!D#q$BN<R8(QjceyZIB*ys
zt88d-?K~X9ibLnFGO9HSXI<WK^;`&Ng4V$*1)vpmh}*rWL)-;L9fEX$@?7&V7MD+l
z(4kWu;tv3(xO$@G6I1k9+fG=TimrwYGPy|kXt1aiK6f-o<RWFHh1z{M6rI6kb0L@u
zTsIv-*?;9l7fReU7h=#`4U)LX3K&<*1yp{f;4|1I7Jb94#O*T1h~I`m#umM*n46i3
zE~2<PIuc7_p&XY<wGJ1@g<uv8x^R)2W010Ca*G(83Cff_v`f9=JV5;|Qhf{tpQ0<R
z!QxY<1cgD?mdUAsq%BgAaAR}?U4*PHQ)Yh~F&X&JG5^w-;%2x2&J`X~i&QAy`W6&h
z#^Qyt=;6p<XDQOD3`UirrzC^?ELYAIL}<}%+F&p#Qnd^sv|O4iXu~D7FI*xQgt@{a
zT9G<tO+)8gH4eQ%X~LDU7Aa^3qedB;Fv!Ouqbu%%j&ytoBC<$j!~Jg|m_rE2A}!9K
z&K8<#4>LUd6y5r9<68)Sh%iYMsCowRS7gw&8dvQibq|*}N6<frzbAx4$DC676{&;<
zb3&0h0XH;9(Bq<!b5cXzuMb7h!{Io;&_s*0$Or;(0KLcC0+GX^m~fezaU)v@CY*9k
z77K%Up>$1nz12D<yi(4|L|rNAc7$y;=phwyO<F3hVUENwaO-j;`dp{lN+eXuLS+_r
ztf~lT!<EXBScE#+IM$%z>R(ddtrTV*rP$TdcX1hdMq-ZTy21O8Ll_ip?M3gK^?E8%
zh*4>-VT3MCW>nl_00Cjk5HA(lVUb>qd&)v6UJ%p?$dRtrJIZJr@~3vSt(9~aiK55X
zN;xJIRPAay5w^^QY&^GUrm7TU8!#|+T-k=Ev&^Pxyv7~CAxs4Hz72uiS9BSGhW|iN
zimQQ&-Gex|?zosgAvOMl8v(jq$wv+7<PKp{D7tjLs1#j061&cC97iB*9UG>yaqf<)
z#)%ZQtsiz#<J>~HXcw9DYEk2fu<_VI{vkBaJyq0v^zT&TEXNN`PKov8k9vpLG`HEQ
zrV~NS++`<AKI7$9L)dgs>7Eg`6PvEwYNm$sW4YN3c3rujN>i;s+CXJ`Mxco5@>Zt4
zDxhHPu_?=?FDHT%$52FHQK}Jzja^x;rxKpKiY|h2WFDWO_@bOaA4k$&>iH2&V9y#*
zK0-7vBsM67;S&%OB-?D^Z<NUKfTD;QG=4Jy)xZQ+{fU6^)hT+LE2ny!NX^)FJ3~{>
zlA-66p(hneec>GMPtBfPf04*j-_I5%n<qqdVn$9_88-y4OPa>h-Z{+&%J#fCXH}I%
z5UP(AJ!@9NbIl3&liU_($?pico;KTA-anV)N*<f@#B~lO>NMKfCsmjo*?u2~1BE{;
z%q#U3{?O`u>%)m$`>*#{$PTQs;b-O|U;%7M0NV+%QE%P4cIeur(E>h~*-i+sg|H!9
z2p7brLK4>d(vUU;qPwHaQ-kGxY!Z0^Y&ntgB<mM)KFRue!v>p2#Dbm=jfJr7f$1FY
z{ZpBZ$39&M8^1aMo|c%*o`<Cn9hR|A8IPC8?n3&fGTXi}cb#H40SJlaMc%GhqDpdN
z;x?TG)6}FFLX}*QL95~}#MP>4(``x#kW@<I;91Coc7uIrQcAh$OpSAwnc5EISWw+H
zwgpfp<(9IiQdPqpWt`7V8>p(`M5L2qW@_rBn1+gn9;vbq=&4lHGPXvcLdtzmq>$pg
zS&;N_OhQr1+zCZ$As4<#CB;)iy>-<>iMJ{)b%><B%xezU83wGpjVy?ls#wK&f4b%@
z<oTMjka(!p?Px*!{b`kX%fYhEyis9IX5Of9ek};s94^zOy24xELU^UZy3D*%g&OJz
z`izyCd8fiM%;%CWSX`8O;T+^;cOftxphT+yetz@PT^?&NFPRN+1y~U623UhRWH!JW
z3|S30<3m=1g&YC(w=@#0GOzMngCVm)e74JIz!i|KXlTB>3?`iKE~^3OyKCeZzwF&g
z3(A5DddwN_8aQXTY2cjU_<0^_(^=4F_VF?eQ`pwC$u7kirTn@OTC(VqWS2q*E$ve1
zAO+Z^8KeNa=-##<8m2gjv=v>NLz7{Ob7*gAe_Ih{IG-<0V3kFVvsK@BL*FWM*qke9
zl-O2P7Ew+duT@hMMfo)~QM^^TzJCPLVaMb|l{AQ=ZzT<)H@{q9$aFv2fM^iqL{WfE
zP1GriC@1QaMbz&S0nzr0zc74-Q+3ih%(*(%8_d;3w-ec+7j%Uw8?$rWSOeO!7qS_<
zS231AulNh1H6Al@QOwb>UN4HdFukwx#AkeB4u|+SfO)tm<Y?w!2;T-Seuqy3aM)T9
zyMw7<z@VNTDkA{>S)wvbPtO+hqSvI}HW*)s2M{3f_IPq`U?bNvN=4Mzk#8-P@n3q6
zsf^#!qfKQXmL7I0LZ*&<{b4+#9*8Q#oAiiO8K<O&rplP3xbYu=qC-&y=B8RS7krE?
znhI!jdKRk}POp4Bs|>oSMUw%CL_NYWxRTFwm4Pu~)rj6T^@rnb>JN8CQ-3&cXngUs
z$PckU+yo8%sVGHXs(u{wBB>fUY(@DJS{VaUs|F5-K|QH1gm1MRIO8|)GRt7ke7mg|
zUn8pqZt4#foR5*Z*jENs=q<T2ghCI_mGKdJlxEN<9<KQzy=C95#<%Rs=Ho$9_os^w
zlE!G4$^ZtuwbzTjBD&~Y<$ZgvXIyE%=r6?I0`%%%89N}qfCsWU4lwLAeG3qF3ipEp
z$bd%z7mltW($wkPFGq(;=l*bohzQq$&kQw1KMd?o#HPyYg0ZRTm~m9P<;#1+k?=A>
ziJmGL68-JvA`;=N;b)>sbX38JMtlOYXiUsgII67j6<#RtXk#R6y1FouRo*ZRWQE5J
z5xA;MYy-N#yW35rqr2R47~h(%JB)9YdruuuMdblh>Bue*A&+-`qX!XVUFBosNR=DX
z0fb&g*lzSwmp9XjL1pK-HWbi`Y+wv*`c5$hHvOw=_@P&+U-UYsm)7A>O+PLM#HODY
z17gz`3<0rk@)xV&QXc+d970#`ID}5`Hk9PHhH~_5>IXAAUEA1uN^faE^c{x>U8V21
zoa_#U%%&$^rK>od^(wu^<<A!}wCVEaF|;?l5%H6UZ@4@MJ&3l2Ln3FN^8D5a4Dm(s
zQmk|dhaY2wL%19rJ<=9Fi~M=pyL=@N00v)34ggj@`CL}IX-f-0q-?lt##Vr~E7#72
z)ZP2jBWJ_m6r~extegbKn90Mm$_HB~HGQy)=Ah8y6m#GbI{jR$+^uy4%iUT>u)MA5
zQ;XPI_}o59$L5jiLACeXoOT&zn~uE<vrXq;N8B_72jL2jZk?j?>aOZ3B)I&LJ@6Kv
z#Y>Pw-c^gz=IQKVxcA(gp&jv0%F@_xy79`Ah|pX*Ua#`*nC)@7`0T|$FnpCd3<7o2
z2i%dfZhqnqWb-5UAYFL1hZJShZn~p;)b4$6F6)lqtB^X~Ev0gNXB=<%#vep_-Tdb(
zy}6@Zx>(C#As1_%8{uMoY;OFF*iBb|M(t)efFlS-z!)z^6hzPHcdcVWe%Cq}I;6Lv
z7Z}uw5C?uJdVHZ21J<oPB6<}?!GK=ISpbRsdSzd>U=5G?z2_Fs;fVK@@p=_x=Lifr
z2zg7a!T=Ta48{sYpD-vmLsY8!d`E-|yVez<lHEguN_Oupqh%_+!0GY?$Q!y*x*~*!
zJ%jGfcpXF$zhz91BM}+IenFL2WDui@GkU0Y#R_HD;wq*fBnBEskW!_OxPq7%b*w<A
zN~iINg*pHs(CM9j62X+Zx^-y(?Ns03YQxB^3{KAQEl0eqqMeT$K`UDaBg77}Jc5a1
z6p-B=CyxTo9KnY#{>i|1`9rJ<szWhGAZZ=W<_e9gbT@Ch^K{%F!q@QtRQE8vN(XcW
z>M`&+gZXN&TeP1?J^R70h(L$@kMy3@<2-9AjdAB_DU1tDY>m<w79WK#GE!O*j+Gwk
zP1g{FPS@5B6k~mK>!1sJlk_c$@Z>xd#cI~@Xg{`SPKUfvT_*a;_)absPDSxeR}l6c
z8CuG?>kL1wbbVKdDkHHG$4bOanhJJZP~GEU8Je9Dvz6}gt#2KQVGpUx4R<2N=Q4gf
zV|W?AopHXkg}n;S*he7ody}cQ;h<GOF+;pF=y)NFUOw|fG5Txk5W|<VLv@dW_CWAE
zzC$xsWAyU1btpzJ2~Nj+MP)NsT#?%m#2rg7(`Ae6nL@y8V@R_!a72`682Q0}@;}8N
z?cwN^{{4zruk`R&R682Q`1F~&hsU$089-kd1fU>$4seUaU$YRiAz9rR=PXgpXaR-&
zb2c|_0H5+T9U>6mA|%OxBWK-+2)K3|Tfu^YZ{ys06hsJ;&kgS!qDJ68+4vKDGkK57
z)}tUokP)mweGyrMc4aa;JfMy8fg3qlAsq4ENJKNJp;z7Dg3&Q4DEvp`-IHOe;m#@=
z3;x!~bP-|q@s+8s#B3Q#B-hBEkX<9BU>l)nh>@c*P6Cu2lnP1e;m8>ux%el+79szw
z2c$FoL*gg-MO;LA*JSc(Jy}U^{*7B1x>R3=UWn|(krv;X`c6!nWN@QJRLm+4y(Rey
z<!th^xGeS#N&+*2qo+v*0$XG-3jnLj)MsM$#y0YpJ*dbo(PR2jw)VFquHk8t+%|sV
z-19B@Z*T@3Z(zwG<ek&gRRisij3A61=_ytljN4-D;R%?uK7L5{`0~();=>$vG79mX
zu_dJtwjLD4o)QxrLvtH>?8QmGxE;!&#}v<P<T1tfHu9KaSRnjEZy;duKOpUpG}}hn
zA(<N*S%>)I(F_+j(Ln(MUlbIUq?4))j~OWzp`^y`_#m{pKT<A2Zxy-Kj!b>1Cq-81
zWkI<n69kklQEgR5-iVEBNAwpyL{WMz$jP`$&O$J6$+`gjFR8<JL=q4#X(Az`BAG;G
z4`d@UV+pNRvZ<x;t7KDqE@|?s$ki&p5sQ@`MJ;SWVr|<1&OB6fk-j<7rc78L#|BCN
zWatqY=BRro3Eht9FOIk5u_H%Da@{>4H~)sjdZ$JZSNW0Ru8LSM+YZvTuC{%V<@b;P
zj10JO(B!!zV{1B=eQawGt3LE*xj|fZ7|+C9_=Io>Z^?f6C^^HT|Fejck!>czomNEC
zNYPWo$;juf4Pu+{0v;*n5~1vg8xLqBk0%5Rk1NoaTjNBy>%bZ%_R3?2rbZE4YHp1O
zqC0)VWr}o~0FE~jZpQ6YjGS9JTZt`pZ><E$=$TiDA_mc-xgx@5e9K+u))0}abBMkP
zMOB(e*}l8>;gu3gKvVa^t4Oq|l@W7S**@$$^GXqwNbZub5M6cu_L|^JVhFd$t8QB&
z5X<k7Q})=3+*9!P7B6igsT#o`d!=f`>nVDHtEm`rcO)C~t$OvXp+H9N`MA+uW2@zW
ztYVBCyz)*3WWw&-g6x1kB>9mkpG>wqZTpizo(8>K7Z<cuTZ5W?pOyJEXds#wpUSBS
z@`T2|JTqlal=2tvi#f;h@*d$_weOQaa(4mA5BctzyXXk-zB#uat8de}i3$QK7}jo|
zbNes=nnwAXnY&mBWD^4Z)0_9!V<P!m^ts#x1CdXH;6Aqz2!R7}$dmirey<(Qft!4~
zcd<Yuf2;AbaF^}J>Vodx<${aHdlw8up5*SGk0%?XpYz(O_bw+K*u{iz)VuB@B($9`
zYc}s)a1cqE<eT;0L`i5g_by9(v);xd@7}bTa9@=o;2ZU}=R@?6*XwrD-n%kGB$X)N
zsCV0s^gG>kH>mEa!kxlNK(_1q?{0aTK?AvWRffo|5%`9?`=&(2_UhSo1lr&Ivleyt
zO>H8wX>301U3UpH>%A*4v46&<HpO-sTVuXGcGU&I$oYzuA6r|o^4D`|(~)A;Q^MF0
zMe5h#w%(uA=KI<%2eGQxb}fljz2s{oXl~a7U$@jtVE4Y~`_pyd-n5d0@*WbaHn;0Q
ztlGU@2f88$P>#L2U&vz7_6u1o+I}I671}Oj5%F_>zL0r5gzhgy^5U`n+7Wfx-6cG(
zLVaGV;;|RJ^hRukuAysm3wgeVu4oSZc;c?=kZ#WFUx)ztgz%pHSe8|cVIRCoGtead
zX7${3KX2Yuc}w~I+@n|2S)cF)Jzw(|lDF^Sovqt7f86omyy!0%=Y>3*9aelzQFmf`
zZ5#CT?%FnJfBug!odtCN&s^z_sg%JVh7~&-OWrXWm=2g?7Lo=g^N#HXrkKawz!dYi
z8<<?eEGR8Z@!==?k_RpobvNd6H!#Iqc0E_Yn6;p^FkL-DqV%1Zxy`;56Q|f^+ScrJ
zcb+yp#462wF>PbF?zM?9ER?+y;BE}aCvK#5FJ>tP*uX5MWocl?L5R^bxd2Z8z${%`
zUt*S0lnqQtin8I#<U%%s>lxp9Hn^_%v+Pbxlipa{#rU)s<Aooq9#~=eT?i-t!c?WM
zbz!n*s*@KsRVrH-rYrAY7p5!a-G%A8_a4Rc@LG0Za_+4^v4te<F3c8%-9bydl@ov9
z6I0HuD?TxW&!{l?d#E3Ni8J(u1$6*EGeys+cwAV>#XnhFrpP-6?;=*9lExc`l{7`g
z#4n`s6Wxp14WExv)C=FB3&?Kx_)E!dT=9|YMofT8KKPpQcw+dK-H0=40qn?);q!VE
zt7r;XJn$A}MVj1=(WjUUMcay@6oXF@36@_|6dj(<EF<FZN@EOMiw8K%5Hvj6SjLXw
z(Z-5x9f<+E*u)c#WqcMM3@szA;!Wpph!3S_j5nQBP7HW|ER6y0kEQO4Z)JZj?P&h_
zxpW1^@=f`~BJZ!IKJG3H5?*Gl?60LU@O&&SUdk8c69`{Q3x_G45N}780X29#vXTxj
z1v^^~FNMRD%*AVxG42H~-j*RPcw90Cu*ADLqLBHb9b>#$^6{m^OO4Xg<Gp1tNv|AV
zy1Ud^M%ne@C}0^G0%rmbuBH>fd(^qpl^{kZ=^HK!iqQt*<I{5~JRdAVHu#|!)0DeJ
zY}IsdF{~Qh6XA4WioH1KnX$soKlH3+8AAbw4-<zFokA=lB)U=7q*n`)_hv){98j#J
zTZ>@;>D6K}O%}loco4IUWWa-%DQ+QrWh}!M@IYn}qd+$vA5?}UI8`Hv0a!*u>2fpB
z(1d$y`2Q>d0<IhMw2Ur*4-r@k77!KEP00nRF=zk}YEF(IZ>QSDmhhn$Hp>73ys&|G
zVfUf3boYm&73doR@aa$2e)ww{{P>UM&SmMu-=PcD^l*VLRMW#HRG;+N?{HnSbkN7U
zoXPhd&vKT&_wZm_$g`K5Cz0&>PIOn7@qUR~<KvC4be696c(=3K+^&pAJ4?@c@S<8x
z;SEJ2J?r88XYixPhhhNfVtB>YNFPIJ5^|dd)vIl8^WcNEbejidEcr}6`1oh(Cl6Oe
zr$ssWCoT~zedFPe>9j3Ex|i8uoR&33>WwuRJPgO_{4#V>#zD9Fh@Y5V`V6`Qt8MPy
z@Nl)w-y5e>`g<3r%V8r0jYty06*o9`=)l{>%kv?RU)#L0<1k34?22iX`^N~1CfgjW
zA(iDj4Vk<-PuKWr`c6asK6y{Sk<;iSUeZ?2>||+;#H3sXv9_p^KJsDB>6GB%yR;YE
zoUcQDvCaG1A59m)8Nv13PTf)P)CO{=4?e3cZm4uZ_dT;YV7rjqysr@xZSt*d_^6~8
z9?=|;gTK$cQRfU-e9&FdIp4Rm$s@!c)fQ_O`-bbGNxUH@!02*)=v~b=59@*6(7_t=
zYjd#<`DKbz8kAo~-PGeAoCmD43j2})710+%$>pqNJQ89sEWNG~r(x-Jjn_9v(9jiq
zGszvizAcC=eZ9w@u=}_KnPg<7RB&Q7H8f*{l9PChvvkcykc*{jHiBR*-LnV0s!aab
zc%XCcx0AIxzLQ}){=2fahwXqsj$u0!U*V{tUBw^8k4ol+c&c*%ZQNYMJ^YAdcY(w-
z?cqnUhSHkxpyxb#{B`3lU=p;5mm>Y%hhnN0!Wc2=`quSpL~NF&LpkENoc!-(wSf;Y
z{xS4;IG7(FdiS&RFuzJr3dZ(EteGQdr^H-Q`@RaNN+w#5X(M&vhh7DP*ziM9aF!0}
zh?4^w;sGe8iV8Xc?#Q9|p_n}KEPm)EaUmLE#oFl{LIj|t>pG$YN$U8aNJ4`*`=M|{
zOLuleBszlTDWI>XxJFA4_e<hg2O8odNlp2o7)nd0cf?te(DEaLG0A%Qp@>ZjH+V#J
zTDrmGb<>f?zlmLxaZZRGbp}qf4Lvq}<q?Bw=_`*o)!^~;*`gSiZRhIh4+q}W9}c{$
zKNB9^$bjci=ZDxI4jhW9spKEYIBz)KlB+bJ=uJj?5A;U26hstT`r`B1mb9n=4Sa}U
z$mq)+&Wz7+Dk!^e1>#+o`g85k)Rr#%*QM@ow?nbCJ9j$_RBaFKCO>Q-zKhe%AK~F-
zl?}vqgURzBapu-Cv>V2xmXX~M)GZ^s5x{SZ4nWwuWpn@n;~hbFAe=K^00H*a$mq`~
zd}|rl?aFD>`y~STNy!_?5`C?p5GPoZsxr?gMK3@fK;GXEG7MPbwG12t77x7#p!f?i
zB0&B&`ALB6z!;tYIs|KSew}#hCQb2&h!x0X{2}rMQw#(68La7s2M&jWoX8&{da$M^
z43I&PN%=#B5f+gTAd~?2GC3xE8l*;nl)^F^!krSV@zw~R1Z#Q;nL!9f+UF0lVFZG%
znTVo4#HO*3j&e+ZXwOK>LB8n^F?W!U`a|p<)~K0*0L0*xc6^8>gv8b#ViK{YD=OGV
zNQeC)MiOg=l8;XpSa6z<Q9BUdj(S@L5ejLzKSY*tSmU)9ZWorZ9bjD{pZAA|SuCSH
zK;8lt@B>gxgozd=HiFbb5XF#6{6kbS#u$-9d^4sX5htXvCQT8XHDE0VGST4;@q;WQ
zOTdpq`tv|y#v4j8+tMvT!~+U-lI+BsOWmBI$TnTo;Td8IP?<BR+R=M>(mq2m-!jaC
zc*vUc(@8-nTkQlVtTEJOPBr{YghV3wk2jJfJtH;xPaO%)BqXH&fHR3Ts=9C`u_jd)
zR8C~IUseQomn1|=C~HYib#ehjPjzAuI!eCfr67Zx>KXCr-`S~R%O^Wk;g(N!D%{?m
zkXQqHB;1sKGH8H<3mE{&!G+ezLq_2zRs4=pa*V}~ZAap|(z<BJ*zhy!m^Hm8-cT){
z5H`$pyzPxS4nE{?@{H8zJV?hV?4;}8c+P)@*fN*Z)H0Wq(k>DFf|!@#gKj6!Kr}y4
ziZSa70jCq&0-oS>Vof&-IGtFAK*8zc8S$3m@&QV{*mb&(IHjI7UPs`A@&vGD?hfRo
zv!)x%J=FAu+|fO5kD;a$iKZ!6@1e%IXNFquD09?Nrl^x$Etn6FPY_#9GQ|F=%!bKi
zcd23RGQ31K`P$u6ttY}^W2;TIjQ|*TO<~rM_>1c^z;?LtZncw$M#-IbtEEKZ!`yc_
zTS_2Wx`JPnV(UUFh9YkGGZeJF9AZLw-p-SUQ9^|uC0Q=~MxK%QaO_DtA#5&QtLQg^
z{4B{~`ULQ+u}?vTn!rK2RBNKvhdakJf=c&%OIFq$Y1A>r;(ziNyCY~kde`5dOZ@Ym
zw6mSSThh>4Q#yfjs;h}a9gxhH$T0Ve*!}dCLY;I+>QmEr<2|0Cy7j-b{onc^hK>hR
zA%_@(w@ECWUrfNB*QWHW6i4kME8Z5kjI1K0W3z$ndFUGeuBUw!oXXqQ19RQBIm@Nt
zB*KrvW1bI(+rAGzxb4?cruvo$zWgSh=|jbP`=x@T`WY|^2~6Ova|FCOq{B|RLCWk6
zsplqp@T&I=gu#Upjm+Io09y$uNCxm{gmQb3$i3*yz;2B<yA;c0BY#HvChw0AJ=CSV
z=R+M239_SSxvFKdk>fSu31QRNptY*$M0jdo%aTj$8Dituq~MO%5sP=Zr!w2-KCSki
z2l)pX?6<R?&v4I(G=$SVulVqmx&|NKo)MfQDDAon9@vgg(1b#Xtyr5hQzEcuNtr?p
zfnDQbqJd{*)7zM=AT>MWGXQV^VcXnRLv3>x4JpNmP$}-2OhMWy%50o_WU%oB*mi7@
zV<m$~rI}B6&j=gl_PEq8w!@XWDVP6}Zkh;nQ!YQQ1{mN}%O?josh4u)c^B&_@gBy7
zro7607?b-w^I^<Sw;?71$x9S+h3J~abRxKi9e{LKLzy=*E?M5hHU!r>#M3k532%;k
z=*!C`-}UkW%6GlIq$2;yev`#B-ZQ|)W7#a4#rhbnP?^cXiY~)gBrCd)Vo8khuAxM`
z1D1r3czOHhBVL*anEd7$sk^0tIdl%$BKRUFd&L_w@uW?I*?Q9M!IVCZ8~_Ts%n7%&
zxuD0EHW&2IWbiR&JTi?P^J_A?aE{wsT7>vcmPVs^Cff~5d=(436LTn~U5YPYX}jX1
z7wlWi#Uzs#W|Pv6O#XP(N?RI}L($%LeCP?wGSj$q+5Y&MD{O<DOR7jpXlrA)3^KV@
zS`YE?B>N(tnbH6m&rC2;9soECoJn5GRDv0n^TunLQsSDfWy;rQm&~x7w@Y?d%o~kR
zO5lfAo+AyseAG!RFyC}&C*~VYT9T0t4aR2XLo<AZGd15gi#4BO(x$zTu!(ESO<sSL
zf7iSl@h>ceGWi+A;HgQXQinjY550qg^&WpS@EJ}C1));=83iF83gRt-&lLWdMnRZ~
z{my)(i0(8B!c6RU@+eYfKPrEG{$SF+d?Mk9^BIN7|BiTP;gs?rCXnz*$i#lIQf1cn
z#%IwR4;$PjmTBM{A4ZjGxba<7iTxTMM(=oh<4+-9srZA+r!4*k^SO(^WIc%;`nl)3
z8O`GPxJF?Uk8c!K`8Wshc5E+rl#_bqlXT6eKnm%6E<~QoV|!ENfq-X6oh$h;$+IaR
zFL|Wlfs+|N*&ptKrv7l?P5r?ygOM4={|=`JW$J5mZc$=B##HEGmkLlm{>o;VFT_;P
z@)?;HM?N%Dq0Faf>Y#Y8J^-;l*!%Qu(e07333?i*+E0mi1k~^{&ynKVs)u-9it@3Z
zS2Dimr|E~{dHoF^Ms;6eL;zd|a1T!30$jj%_k+0E%RzzGgmhs*s@?Q*U^ZTOLBwQ*
z;{*o?0W4Pv=KM`}3+4q*mkeYMKHlKC0f>GhT*@iGk*3DvH*&Mq%@6U{ddqKwqq^lc
z!aaM-Z-hVAo3qtX+}&Q7m^nRT3?A>MjLEovn;s!n_Gc4SBC|u&JBR6`(|?CKrqjm<
zd8ju(Am*t~Um@nQPJbdKynaicBj&_D(lN>4B8Aa_ku05?kaau#pO~2&9#RLO^rHGu
zdhc|!VhZqd#$ujuIcyzDCT`-=G$b4kw=V-9T)KrByv5}?X5kyY`IcGuhRgfRI)%7$
zJJAswE^O8*!K+jUI(dtIlxf@3T@I<;)1!{r->I%2A4m|-G?X7oAurE8qf57(`<RG6
z9RN)Z-0%@Z%KP*pTmZfOIFa--WZ&qZLYD!fTeV5Y=)1$Cb$X{roq!v)+$OC{FrQjw
z3T7z}oq}08fazH6E}Ry$MY!o5K*G;gdVxDpO9PM-wKRYZAq_{<RethBUBEyUuHKc-
ztkxk@<?gzWDv#I$NI0`Hm#sXOXMU4DvYd5#Bf~TIFnJ^ED5E#BPBJhL$pzRzJd|F-
z3vqt|c@i5~hG4)5AR5w9(nB|uzp{aN2p-Ko$Z@78bchQO=B977!6R8Rb>Pi_4%SCN
z_q};x8z_R(Rog)DD{pQa<t?4PZ4|ooOOVQKSvP&K45w$gfr&W1&leJ+G!x5@Licl&
z=sFJ(NndA4NpK{?P5uBBzUR6qgJ>un?iWJudHiAq^w6*m9)TD<@K1ebcmFqV4`qaa
z$&Wfy@6nN3LJo{X3`AJv=&vr412T@$3^t5YE*VE}>P*rOF6#`PuyCf%gzTU#Lj1)6
zC^`%Q2JdPGaTvX;8ROvqnqgO3#CUL)pvG2RwFcDK%$YtE$HJ~P*hDfz`hZ@W>Cgw`
zSlBn{xk`Nwf^tOA9DrhbpDeA>WDawBb!QH9dUa=h^1(osOi&K8q>Kt$NJK~Jl0r}K
z%r-tc<M>#NNH5(s=;+N5CL3LWP}!Ln!i3dlbOl0DG7JSmu`3YFnag`XFqbJc67J!d
zz8j?X8Qx_eVagCN3x{z9i5*6d@l3ltpkHT_?GeV@%%2UarVLnf<c@$eFJ5|I@)8C}
znM!|h#mqV4;|pc{Fwi??;GNOITsf!*Od^?ZdR&Ul<L<s-p3D@|V1UYKL4zB*0t#&~
z)K;qWxS;<jD$&Md*kY6vgUCr@T&+}Ox~XT{H5&}AO>xfXT4g*QjINb6cSLw?(<9=5
z?w?tQ>B^o7g9ig_Q+(q#5UG9#AK5ZX?_fYJEuSL_>;{8rk==ISsNC|<4#wBgG&vYe
zD^(TgHX@qV=ntP+Iv2Io@uqlOFZ)c_tsgPgs(!>sQ$#bEwjxl+5pT6_{XjtRDqWAO
zheD5yuJjB}UI1i_v`esMF~)h7Ys4>`K7uf6%mqE|izp=)gh*<X`dbEKuW~H&ncawy
zpIa}&l!1Wn1t5rg>jwkL)epvz7kveR<k2fQDkwJH=)BMHbq7{Y6ya`Q`C<(Gv4DuK
zm!$~2Ul~j9$UV1sdjl0%#^n2lBD#KV-HG^m8F?-!BVqtBh6acwz(3>^4Rh-d$p^AS
zBp<-9n9&2GEU>HYoCXFKvgAEjNKB4&Q^psFKVc!&xi|D;&xnIl>gokso2VKb@$Shy
za=F%XGEmMKl5k4aUeJTU8sX(OH(m(~LbRlwIE+CH&P!q7M-y>HAl?tYM_#s3Ul`*V
z&Q6D>1;q~1d*6kdp?EfoK@Z~MSO|DPcr#=mgcv;>@!m;-UM3<C&OfYzpbx=^`o=I~
z44x1R$wFe{8cW_?sk@hf-omzVlRl-h>|L{M&?HaELC5~GlnU)FIa!Rs7~*YNNX(_)
zP#B^i{uf7FFo+~(K|Yy!0AU!1sAe4T4zrz@$D%vt6<jna1@TaHQVM3-)Y+It-MTM6
zoS(XOU*x7aw^93^lv2u25mER!;##SAevHv0A_H0onSXNBL^x{rM<?^pf`Wxf0uNlk
zcM3dYbr8wXj_^Rdf>ZcTi3iqU@hLgd>&CfcO!)?0rsEkJ>U0n@!D4+mE3){XRyi1#
zWM;lPsn}AKfq_|MQwGk#B&1r1vtp$%6Ts^)Q`_As%s>czU)v-DVd<V5v6fxqAoW%h
zH)bwlZatBAEhH95w%84!&de-*q6%~5zBf9t9pTI(+uz-D856=83NG$DMHTqEMS->>
zT1HTOi%e}HJKb8AO&ty@t(Gl=ZmVrg$5J<ze9+SCHe_h7VwKZ2xj{MUzRog5CQ#J*
zSa-|P&VlDp59Yj!y(e*=7FtNQ>(V|s`3NO(pIz5m68l9-FRV-r31-0K31PEfi@zzj
zvdkR@hWR@M*9F!`aTz*v-)~8HxFcNRNS1b=YN?7;@c<IL>)curqW=1Z6M^H7(16ZN
znjnJQ%ckD>1|*wg0-L_&$={}))KnhooNq}HTkeRy8lq;-Z2-PWXNnpm6`0rdWg^*M
z*Kd=t6VOKMxe%u)9ou&RG|g2ol#01Hp}u{_H|vyAlR(i@f}}J{$6K<T8WW<<wskj<
z)Dq@Kry8XylMi#Of{-=K+#CPl?cW_sqdy=0cx<7o_Q!V~_m%USZC&mD{l9tp$G7r!
zKK^g~|Nr^NvAz<Vrg7%|NQo-GXKJmP`oPA@O0k)!k4U_B^AXkmoVF=L;#?_#g&Cst
z!#<fZ*k}OqwO?P!{M#3^)@9f}7!m6eq03p{kb;QBXOT=HIXkbQye2&v`Db^Q;}DBn
zy@NSZTysZ5G!iAj0r?v;X7p2B>D+w5=)}xW4cbHsy`0l&iY`!m^HUIRK9G@ZB`sY|
zL^f3J$?m2-9O8&wiT%_1oV7jnO|yHYAb;F2&vK9Q)9o|3eIEb&BTv?C`+$yBOF-jf
zZKs^jm<h^sfhCQ*tf_eK$du;G)p>0hy4sguC@vY6hF@}KN>^&zWNiSkWfETW_O|Dr
zQYw(-c-=_TALY`KdUH~+LlyLkN8Fntj6;kmMUJvGK^GeKltW;~ZLH;!L<?EaE?QRC
ziv7--^v`QD%M<d`idamXct759dF^#Yds_2V@&2?6eo~Q}#Z-~V{jwr#Slm-TbWzA%
z_LCNwsp?imZqNR*;y9o7><<|~wTpjN5t|*J6+gD^Z!atM^XVt?!ynzAe<VMth~HAZ
zRFS_fds)%${U`TB9v=D){(d$7Qo{lN$M)0hud3DS>G%9Y&(`@1|4BC~2uu};+%GE@
zlf3xh#{85XKdG<;%&7{)yY`|20+lF&elW%*Wzz4r6Tv(cp(sDz1dLbJJfL@zZ$CoY
ze3E!SsYt<StSIDuS@9}Q^7F@ArgpC{Cx(Kz+^X2LNnTY{eo;y@XTN!p*gvVr9I=-w
zQq;ecW|1&1jHExDzN^Z)?<W<SGEn}&@nJ73C<#r)4^*kybjbXqA_M?vB!6tDQ-4`8
z+$eEm{di+WBOYNtX$|LGWhIp7i%NwlEpZtBc${qI)A9I|ia14~>i^izReM$O9#4nu
zquyCR9lyU{kB4+YJptFtYPOx^UTHtrf7ZizNk*0NzWX%%{%j~xDMaaGRJDIn8GgSa
zH4Dh{ADgbxUsfdZ7Zi}SaQ7#b<R=xOxq!Lu$EM5JtBTkCq~QE`oBfl<^Sjlg7d2J`
zVCPote8117$v*VgGS&^~@sHk0xyCOmvebrf8H<bTl}`;suDq~$W}hoBq@D)w8rvWE
zmHHanUj(9?CDQ)VB=-zaqek+;OI~#wl5M%6AWXT(6J%R8&$43KI?AR&#*dO#=_8@K
zeZ_UQtLA42sC-6#mF>Gs!jgmXd*>z3hz+5^WP<rA|Lq?<@-}^yv@`^8ZgvrumDjl$
zFo;A8hpzV5x!Ev?=*xa`UAqm&k+Iug{4z4`Pqv70?>3D)Qt)I;L^dl&TZ!AoW|kSD
zAhUEvvY^d&0_2lbW~A%Y2BmqTlP&G3oc0ahsDmZ9@YZo{)-B(qW4mAamK=(r-H>c`
zwRdC^CmFcLwVAy9*vYpp0OPY|ZRBIurTa(P+K4=v^~TuEdO+w;`8$_c*pkPS;TVW4
znPEWTk$mhB{^TvQbgc`U@6?g+U5VsdKv<MU+f4MnFGoIjC6aFezUkW57680|)2u(z
zXbjW;u+NVHN{*&G=1Bi7SUWPw+K%MYLl>iDlw(&J3Fh^lF${kYrMf*s#3quk!Mn*w
z!!hz~kGj3TK$FRaW5?8O%44bPHsv0=oGI}1_%lj29t)cy3TYk3{?6q>#`E(XpOAd!
zij~`+xk9Au?_5{p0`%yfkG%7a{h2FPYJcVuqVL4og~<;eij_L?2R*VM>Jz>QJzuz(
z^)X+#aLi=#MLr@bJL4PP88d++-Xgaok9@B@G7}^pHI**%jSruhQgS_vX2waroCYr~
zADKf<p4%I)&v;kqEN_|XGTv~>nH%M>H}{lhNL12Op27UsukBgaXSSy}V^)-&0?iYr
zD90xsr85yIAFeZ5C?B^$T+BhngpX|^Vt(l=MN5qmm-6|2(JDvjWKva4#G5jq8W;-m
zy1@tkh43$8Ubi<gm;-vsx5%f{^NkESczQ}V<mu_#8yWKZ^tSm^#O&rPndeRKsRkjp
zkTTL9be_nxwREt^)V6TKAoq6wF_V@v5l=qKple`{WR6|>e`FTk2lA#Qz4RzS9$)&`
z#N-)EXCwwr_m(S+*>bk|WLgbfDbm#Q_YUh{Pg#d#Ts>u-r|;@1=#UjGVhq@~n6?yk
zNI<5%$`;C()933uF>Udu2cR>)Q}msfCw$|LME|RV#BP1_befS8H=og9^yum7<g=7A
z5V`F7=I9htk`AZP_Z|>SZ<!sN9$LuG0Kjc{_tpzPby^BQCT_p8Ss!{!rzYlY54$*1
zwks0}ozaj4<3s*xwaK4pAZ7b}a(ZKSjt{!U9Zcx)A=f!30Rghg_;(Ce!Vs=`wOv%O
zMy77xoB(fRYG=7k<w^OFn_wl;$g$iAGaWp=3~P{k3}$DSng=(<s;3fKfj7pC!Sw7<
z^WYGf8ScYpvWiGzFg5$wy5W+m2D<}vVkYVNko#s$4u-+J?CCj*yURwFFs3pQeYhiO
z3^qMSanDG4f`MyA(hm&2dM4w*z=a^G1K|By^To&+m}@>d!G#tnr4B;gdU}qAnw|0a
z@Ybyvj6a|<BPi0{@2|I-LG&P%t_qo#(L9|;;VRJRJUTeUbn=Irg5uf-d>=BB9Ujg#
zqSR?3jF@zKNyjp#)BlL^DX<C5+cksB;eXAXbw0lFRx?r@*MORl;qdcj>b^ky_n995
zoxex<mEx{YGl<)-3N<6R2UKOoYvcNW6p!>MuTiJ+Phy{@%RltjhK{|}wtM@#GcuEQ
z2E-SR^!LB|_T)j={n~bKe~;ErtLfjo_XTpo&U!O2f*<1CT7HO=3vH_D<~^V)Wmt6N
zfv#k^HQ2SPr8flMjX|jUDEq(J6KFIUwv5|HwTuV|e$kpS%An@28G`I#C)Fglk@qk|
zi*X%U2!tw>44YeDd`sHg`f{S3jK}fcm~9~eMQ=`=mCzhAPIy3dFe<pnP*52Yd^i+!
z_y+|wvgPPqy8q)S&$!*V(HstKflA&x$?-U_Ge~#D*}f2N7#z<wQeycTZL*~y)58N{
z$%m6-`-~Et7LX62np9aNm#7&giyKch-PJozPNTn91c6mcSAGPFEoiDz%nBp3dOQ=E
z)KuJUDg#yzMXfD}F?TqsO!60bHXaB{-j$3@1-oe7!c%cBZQ-dni1apSxCAYPad}sK
zSJ9j}bGBeqoH@!KV7L|4Efy6=3}R8Q(3ebhL<9|1lZeI@X(1V^7`@HlQ)E-Biarfz
zG-X&YT$&ugcX57f(Wp2-OgzNa;mK!g#wS-QGOkdL=&R9N3Gv>!`7`zu0MkG$zfY<P
zJ#{(1MV`Xqu|=N3z+r{19<i|{rhE6&#ZXqg5yy`yG6K~t5EZ9>HR{6%cl9T=rl8qp
ze+-1t`gc$s=m!nVox)h(wcq(}jm|L65;w|vE25LH$5O2kUtG8NR9poWpX#!<N`^Cv
z*`bpS)%Y9EG-PX)HjewyLfE?yq(`k1>j=cI8S4tcxy8D=+^iDxxDPF)Gu*qzU$DQB
zq*Zbrxy%;A{^BZx@Yo|D|D|pLvbgG0Nq!_>t5u@k?@3<9jTqtbwaVWvZc6kZ2p~Fm
zDds-9C)-DZ%hiI&l0bg~u|eGGT`~%=cO*&(o6=*-FBGG1$@>rzx9U8>b*d^<*Jp``
z$zjM4SZh)~g#4{!e1P<=N%;WbTa)o&az}~u0T+X+n*#_N98p6tO@1aJEn}@+YANnm
z4xu4D0#w>uaK&0ca#-{z!@dmq$6EVNVX=x_9EjGcgY0q1l7EKy5Nl1UhoR^Br0E#=
z1|5<hMl&iI*Q}#vSTa24YE8liI9Av6XoKX;Xk`$I_=l2^Wa2{{6>Qg4PSIeis~Nux
zViW%m1`Ex(%Kig}l$rs}U{R?N(2UDgt)@dB)NKpmI77^4jB}&EqK;Z;SgX}?XF~2~
z%yUqqIe=opH#ou;B{XXM(eY{&H?39XLc&T}bq+_K=8TVKZs(w3JOFt&bT-SWQ)lx^
zS6yj{V!CSuPzSHq5y(l0zJX69t57t;^{nbhk_x2*(!sCzTIuL!BJe8rR3;RcPYSuc
zYG$J&gVBPf8jD@1YZ)`OSK9lT6du9ZM?eGL;ogOLt;#M2VkWu7f<UWQ8p;mxJJk%~
zZbjYUUOv^GXCkSpsP2PoQ?*Kgz_sgvpcH-4Qv<GCH6y<p>|(Vl<giiTZzNl><ey2l
z9Eq6#5!X?xln-!9IfAm`GvpnEeAm?w)KHF)=`IE!)-m?viFK?hBO@uE7D8G(T6v0Y
zjzM@<Gsql7Of`edZF)(}YvHx594q8lsu_e1dNxO5Il$mn>6r`Hp-NZcLu^U4NTC5Y
zk|VJoxMI}|Tn7=7yx<P;9yx^mKxWI)i$q6s%>oi1LMb*w(JPG&FL9b+1Sxv5!JVoW
zJwltSxg|Z8aiwwy{eToMdet#VVdM@ai{L72rs!8DRmxzID6)ToIjCk_J(z+PqM5>L
zRfgJw7|0Ryuz88IWE?h15!g`lB<}a8TBLV@%%^5tK5k13!Iq*2<ds_r3UU#_iP7Iu
z+8ORg3*pp3D3%L^ZMY8AjPJ*Fs1_M$LB&%u;@{|)FO#joGf^5Gt~QRKe~@;`3SdPe
z=j4@$Laf0P0A3xI;Q3l)MX>a1<mAFckjZqNYA1m7oX2Ob&mQDSnHrNjq)Sy8*o$lr
zf9rT|XO#32*1&ixBtp82(ldX#)JG|%C>erbP=7)SA|R+O)~J#+vN27`1q}C7kpaW{
zy#sOeQ&@%J%2AW`09TGJVgvV!nmh=V5iU;<8t*7FfP>V(uC^ALz$*n`J{8tWO=Abj
zOE}4YDfmSGOSu=oA&#D!Bn+<Vdl_S-&`b8;!7!Bs!bd5I8!97LI!dwbEX8jyxq#vS
zP+Be^Zud#^5IXoX5X+ua!13R)f*=8WLf9~uw5j1lV!tI>aD(ejvPsmYmWjY{Tfnqd
zL%H0FvAyyc0bD&*S;U>I=Zwy9-A(Oqk?pBexwoXnhobomuxV_9s)hxy-9o}-sC>zV
z0S(a+%nM#+lO3ZLw(ag9A0*;&h#RA*^+aNGH<ZvaO7Y5G<YH4P@^%EC<0O*CMg9rF
zU-0Jx6KFDbK;dyDW)AAjGlG^76bbF6itfWzl~u%cf)?_Ouw`tpGP#O7goYRiHq}rf
z@fQ#(W$L?pM=Mi9iq54oJInkivn^csXqKV-=~`7TeU!-1JYip!fzM=_vp~HRM+Bfi
z-nJN}LXlx8g)~sf$C1}CNCiMZ;>WI=S#0=cAbws|47r%knq(>%rz7ZS&A$=Czv0Fx
zPY5YYRvG)?j5*rNh7m-Kvvck@q;N>l@Y(Q@Eb}Ai{t07bNs8$c_uQO_)AGYY&R+KU
zJgaJP($5;pjDKTWc&TVhWXu`&-X4Xv#Hu#ZS@gS2<Y_;iMY|>u?Q!Ov!B3~7$Zs-^
z@YH5ZL_f*UZJ5j^A<!7)Z<I6!&&dAcS6-cGh~4!yC1t@AKxyV{8teopA8(ljC}kHD
z1wA8@W_NV%N@;d02N9Y=9Oj(@A(0MY%*;nwT5TRF$(cWCN5-c!f;pI;k+}NmXo*}-
z&t<gCz|(ttI-tN=fMYF&M;(M2<-k~wha(vao{_#Cu?Le}<*5t?gJ+=R>He1aw4RZ8
zMT1H}{(`*>g#lC7qyTXTHnt0gck&mcvceo<&j<(2J!n#ct{#cJOllA|p{4ePd9i2h
z%P9=d_T*HBa>5N)r4n&7)lZ5aQ?!L*=wt<M6D^siu1e=lgvvfQP$<3JE4+wxMM&R;
z`Zo7Uk+zSWQFP1TJ}7D!?~Kl3fR+t&P^9g1E1bG%aN$oj&IsxIRO=mof!hE^cuL#n
z%AcR^8Au9<>q!iJ-f9{Pjr4-L)Gz~K-h+bX0A*z{MB@y_zNzkGVUY|mFJNRoh%1|7
zx3d_lu9S3OJ=mg+k+?Chir_)OP4WOzaF2~en^C}m%}aO74LP5ix!_N-wL_t%uU>38
zKf_BcmVFN0h4IcyCWQrI-9e>L!O!REI5B9f^Bfv9g1bSk@Rql1&-95=bDbl&l55;$
z0l*rQqDE|jOhcMB0Z&zm?s5sKTU;o?%0N$v6+%ht3TLy)y28n%OjGLa*<@V_)={T*
zfO&-z47sLU-m|531^qQyS31ft8z`CgG+9?TbtdZyr_N-^;q;lTE1W;m&^diD*~?z#
z2)@JVt31T`2Q;K{&(}1ho&0PKOCM*irWuWUp2AECz$awc)YKGN5V`Xx%)%IWc#2|t
zg_A`+N*Tc?MVT^!&r>!;P`xr`a@sFFR1qKIY@Hf9XY16^!H?pQ?53pDNK5NNXvD?j
zT$FB^Bm4%70h~tbb<2c{$+|+iWq$Bm23*Y5b<1##Thj_-ORF@)*kHN_a>Z9;!!Z0!
zwr}L)j;>)27<N{Y^MX&HCrkc(^*K3sO{&+*_$rz2nPFTO{>q>xamX_2j;{pBOU`Eu
zPQ%5{yz?`B!@&L^eUP3k4rW)+ca2H{B=O)@axdw5gh77!hH@~<FP>d0*`!3cTNxCj
zx0}kaAHDA&?fl^orh;#tMN`rB+{6umdu3Hta0JO5`6g8v@KTipoWU$&9%g`{-oG+v
zTYllcL#e^A6tNyx#+T^Pj)97`R^FW}<3&WMTp1ps7sAR|5RfoeMtbm-@rdZg9)H5k
zZt4%m1*xjn%*v39iYw-!C`deu;*X*~#uDCU$u2@)7Ny+2a6i@iEP^C!Reo(oHRy>q
z!X~R&uNgLpSK<Q@o{5K=W@k9YC}G`jbJcToy}*`IbtyuaWxRPum}S0*S4ITr)x6UE
zzv^mo(Thd*4!ZX1g}#Dg)Zg`4##g8=&|P2N01U=VkAZse6;rDGb*ejB!Bg-093xEm
z@?l`eX8Ji)_|uD@-GeXbfq|VF?(*`lV8kXJFc7YpE*dqw;g5iB)`_{H9y|DsDJ7L2
z?^QY}T;7lHC_zl;TY8)@q_b9KF9wmY99QZ{Hx-iHjPQPeXh2kFI?N!d(*b<+lFJO{
ze;@^4I_6ZmnOEs!gEIQk{8L6t-3q7ja3taoD5j-d1r;^jkt*1$t4RMN&a>8w500XZ
zVCsNMk8n9gRXTuIsYHV^I!c|t=Bb{Ab2oDsFzC}Ax$w~rXE1IRnEC3=u2B?Ec8!u)
z8p)swiu4aUXV)90_&H12KoDp;yw%a@B&To2jNIxg#p|7YqlBemKxgiHYuey)A|(Lq
z^wslGARzSEDV9b$3bJqMDahXa4KdT;yMUY$5e4c1zEjyWyGy@p9n}a6T?kBm9vJGa
z>u?^G?w;J0^u*>tEJtj`pjUZf>)e$iwvJsoVke0i{jPb&F0bow8D)oyTtaVsHe5oJ
z#){6_I&+!tp;~2+qXyTS^g=pZ5o%hks<V*9k^JQ#<lU|8Zn$Ar^_GM!IyMn{T8&0h
zXLX70>ZFvvHV;a7*QTwV(Wq4^a%wto)8bj>z%ARQ9JqN9b{E{HW3b=igyClBc!^aS
zAV#oOr3!MyzpIn3$A8Bu*ZKH?97POgttPuyhXKKKrgf;?N{v)EA8=YX<pj>p#>Um@
zMJI4sg%I*umDj0u1PY|1dzJgP4w`<!yPk6ZS*{dU6?`A?z&`-N1z!^ZGXs)qIh~GD
zZ&eXm>0C)~ZXGQ2=hh)2Uu`%gRC#LauH7NqSL{OcY<Pj6gn7Xv=n?OVAPOK?#BXrT
z8Mb2-_Q=FjmHCY%VpZAUs{FZiC+&<Yx4E?*vgB6lkoQW9=Yg=^LtYH&*DX$A2F5b3
z#mi?@VcUKLDEFU-#d_~_%L`ZV2yNkfhb2R)2^l$CmA=rC)e>_aibRjQ7QQk_t+;XQ
zefqDQwTur+W=B8Z6pQ3xw!Lg2Oc8inn}j$5Z!-YO5&te@@ez(&n=VhtOT|Ddgy(Ld
zSSvcWGX16p=iX1jT#VPvh%W@}RwV~@o+oca7b1AH9~oR$!>L`FOc~{y@o669>n-W7
z126Yhbw5McZ&iL)@_0t99D{%}maZa;n8NK47mSd+n}4%M?NxfkE3S`m!V3Lkm@uLP
z4?-)R5dUUOV$l~ElE_Ia3`yk9p&OBs6+3iBt?WsRFeNRFKrJQh$sy{lfaGr(eTg9C
z+ETW{38|%QJ-LiBo`<`AlOeq0>Y`xLO8<KWlsba8CHTW7zm2Uou~B99?TjxT*_|!)
zb;TVc#1GQAF_>6pSi0;p#ugFJ8HLM;=i07=MQ>C3dy7zF3TOE9XB=>C8DGr52=0h>
zZQZEx5%q$>#MzA)D@(D&Q)Z>cXktohh5<Ag85={4=R5xbk<{$QWGpH*bA}2u$!>-U
z#HMKzf#XGAh|%8^IEc&UECBI2ztxS}-!inkGOmEp=ZM>mVDs!o1ks;S(*F4HSz{1A
z_65TZdWz_FWfXnqA0du@=sS#~pZX31=_kx^4XQ+!7>;lS#rv;va59vwJLDD+;qLW`
zTmU<Yk|qF>3uJeK-a?YMT_m)q*`2rKLRcF+=0=L~M)*p~;3o=LvBG+fsRqXn2FC$_
zm@H$-dnPH{23|Bs2vHeMA-)K57fZoKTGZs6;Ex*zCc73hXIoc%=A_Uv0;9KW8e--e
zi5eX8wQbux#2#zep|_;ts0iAis`8QYD~UZE@|ly$%D|4!cgxmE4`TWZIa=`}!Zlkw
zBrad2*hLu}DkzaZh0{+zlrCWjDW3c(q)F_uj4)E9k8R8#tdYXX;1LnJ@Cczc?8sYk
z!tl@mZ_EKG_8f&|mN{Z5gk3_iC5a7e&<IND6aPJCQ7UbNjiBoxhCwSmg=8aNjow)z
zj-^k{0gSog?C}%&jt_GRk}{~A8X}>}0gy3>3r~Wel!eee`wgcgDhx?jR6&rv?v&i{
zO?*dL;*fFmTM#!o6w)C>11Jr6BL;FtBi!ux4X%rJ6rHcBXw6|38PYYOE!B}iE)m|i
zK@;q@1ogPf+7RWS(MlO-;?07C`wp4<ODe6-vX7{4qb73kPe`pbHH2W&vaM~BI&;1g
z$vKY$Y}hvEv1qonE`)O~`_n4n1#`4K^b^9Cs-i^Woa2>qq!3F4K|QsF!Y*pH4d9%^
z>tm!CgHAtswjCG7k%A1yeh|S?m9Im(;D%(={SAb39OO>kx|OGfNItw%LnHzoM~A$-
zW9uA|ra_VtZ)lLQCL<e<19qf_xN2PaFKq+dD@69UBgxJ`$t=hw@pduvyp5|?9kSdC
zVMDQ?n>Lsb76)knQqBqBw!oEU<V*1eWy7)PDd>pE5{sLoI2-{4J7hK%%btQRk*V40
zZ^<!<GI)og9Au)pSZ@d$4l2=eYlVn^H7>F)7Oqs_5-D1Npb{-xQ$#=?0V0xkX~Lg)
zxo+Pjm1usKNUnZ7oLn_O6YQe4e`igwSW0&!zq9`O5ZNh_dbQl3dWFmq7aCVa)FrFM
zl?n*#sh1vjgrxd_c<pQKf8%P%HCgmols|<K+HC$d-9RFRE*1r5z{&Lyz)34O^WiJ<
zgft!+h4#hSw(k&$pL>C-K<}Do1h2A%X3M!HO$dPM*FyT1nkCDs5PFExyA+y7l>(;F
zggUS7D@1bsLM$ucOd<Woq-IoTon_*h9q1b65*TwbR7(h(@r9d|13O}xI^PfT-aZ=p
zVeaeg+h|e{2vHKC0zGRX>TbkO-=`Y8m1>Cp=J#-Wz8Mml2$h$k(B!SGM?1pJfonQ)
zC+%f!RXPtN1rw1iOH%=*ijp{OK(_2V^{&*Hcc^I$zEhP^YDd(zZ`8Z;`kIh!t@}<@
zcB>sR&0ya$WE}}))4o-eX{+#QLfN<yX)HxfskXK2+w^W*yS^)x7HmgiOTnT0NILWz
zX;M%4#okDhdh#bNfWPSQ5_eDiI8SfnQ9Wt++JKk>WX#Llj~l>N{iM(2k$0SIky|ng
z9Q}DlI6;j3L?%`yt2~|{{F=`Afq2f#n04g#^E{a`>u{4_2u{F+cwH+<5}0W^ccio2
z!5-iA7coG-J1nTR`0&(c0^z&ELi(0?v>=Bel9L{Q##y%vraLm!<5*-^t_sp4da_jP
z^$04klb?tcymP{Z<fO+M-rF=_74L1*W91~l&OK!;OOP~(bU@D81CXy8^U^xd=9ap4
zAvH4Ma<Y+AmKkx69pPLf%WNr{Yh;-%l4&Qh%of_F{6mqxx2eazAj<e#5aHp7KI5~m
z%)yRCK3*2r)GO=o258Ja`K4;Ak(1W58y^7fNOzpG;8U;AnV83_89+u_g{v&2oJjV}
zDL|51#V|Q?NAhOQL5=yBd_(Tg!xR+aP_J7WX-B-n4W*dsra3^Sf`~yl0L9cc{LGM}
zR*?V&xlT<^{R_DwEjG*`3yI0>+qh#gyLLM=*UDMGAk%85`hI-Kwq)StMCw}kraRK6
z;=F*|x00R(QazFN(72JhRsqK4WO}io9goztaJ*jSn7u)p<bq=QhSnRYY2E$VOLt^}
z=a?;K>f)w@1;a|pIb^DpOL9S;TPrE)kg2w$plfj}G<g?)%7Ar;j5ZO@FpY<NtnQH6
zR+TFFj`Z_#szT6>$))N>I(j)!AyCKUKXqRR1ADy`KL>h7-68KytUpLnY9I=_eV(jp
z%8}O8$UKBtB9jZ$ja>E4W#myuCZ?nN!ibeF6@f|yucioOVj#7bW4xDIi{WaHueg<%
zyDNFSRA>=7Wpq?R@>dfD6@sl6fdB5BRHRln64cX23HfAA4oNq%)4M;CM|UxTedRwx
zUix~g`55V)&0kRi|2al_XX`Q4@Q!xij@G2Jcv!wG4n9(Gj@`&cPgXLd+yy-Vv>6{8
zsLgI9q8EkQ9lbO<6-Ck)J5ycqn~53qEpLvhGqovt4pCL2<B&8XP{JKleJl@{^UdfV
zBsIs%uEKbePYO*^*-2Ru-<{MI`2$H4kv|YL5tD1Jv<%VlNz1UhsW?{`YsIETr1uY$
z2GL(^I)mkz1HHg(JO6yk%HPM2<`}Ad)&s<Ns8e6Gh&tn~@i;%k_OYGj*77KhLAK9F
zvAlVB79U2A$AVAf(HFyMnim|ia^2A}8@@X{{$e=$p%i<uZ)b4~C(kA30O~X%>)aFp
zrp`?fWa^Z30!^KVHntNo#EXqQFJe^tF%=`vV=BfpG*dY2Z0O$1)6T|rYDRZ;RQ+wn
zL^yaa1g={pXacNBy@7+b$+@9`(#o24S~XE%c?k*;JR1s}xlNu8C49M!jtvE#+Scew
zU7WrPc{&dOzNh5MP~fO-tz|#Z*S7V=x0%1UtREnpwXI3}K^7#ij|C9j)z+)grpdG6
zC~(lWmI*15(Otd`#T~Rwo(-!UL+I)r)3vw$&bF^E61D(h06lvb1CV|MjR1si2cQ_j
zQ13d1puGt1Y?G_QLM9Nrgcj%l)`k|Qqy0;t9%w&z+CcLR?kb@lkYz6b->^+)raG_(
zq$a_g+UV49I5hBO?qMi7@@pt?s5bQ_b}Q|Hr7jJo>2?T@XoCwwsZcmX4_{oFutp<x
z0jHxS$$WwPtm)ajz+2YzYF^+P3mVM;e46lZegw4UNe|}*j<D8sLxCf#bsZt_gf-B9
zu6c^1&h(aEz`APwmR_tnk0>T2j=4bMi+JQXGI3eKBZnz3O2H#Xun0%lJEmMJ1ytpr
zEB1*R7YU7{6uWZJv!UQ+gH*{tR?kOKSKKAh^axnsN*`>?QC_1TI{op?LCWSpd>fAf
zb*O-Ep3KjIuy^b)RJKvoUsu!ek+6V1-;^n*M7BS&R|gQispu{=F})g=2y8e4LPJa?
zN6Q-mCKkZnxl-k6e+phfK-7Hz@_ythLu=BbV!6&J#rP5GVR~UK5e{;QMm(TcFewlS
zEHOPg7Ce?XXZg*)iEENlBo&0UEcSE!V6NgN%rvrIID*f{k7X!7Tft+B>8)}h(HY!+
zk;=pLc3F@k1jOu1wj+O<>Fu)M!Nn1L7rKX@GYe9nm@-Zsg&CuVuE-vkWJ*(2kfX(h
z4vBcAaX>AFeP~Euxh&Z2F#sqG%9gc|8sFdoKs^|W=Pn4>BHMl-1K;70aKes(QfwF9
zx-Y!@n;u0A5(^<UKmf6CrQqOwh$#kuxax=0Vg=D|%u*0YOw`aeLwfEZ%Oqm$kPjh7
z+0`8`9FE4J6D?9(nX;o51phHN!x2#Y35VIy9p3vRD;RS?1TgUtj&dAtkw?M{=!Q<a
zYp@#}ASJHeU9N#%KxAFG@#__LA?OB&OA#EUC4FTly$~kE<QoBbCv-X@;~aB%1QLJ2
zf#NhAQzoYi@;6S@ze&T5DCwqqJOZhk!j&eHC^hmP&rl(on2`~&-72SdhW^<^r#wSM
zwR$n;4_Q!~IGLxZBQfXG)Df2jGj?+m)ANL*L{rGqZ0bntC&aNgw;&+Qy@_5Lk?^hR
zVI9%(O%YLe7i=^%;8n0GAPOP*O_qn*LjpF%NFlO+0kOSiS4S}R5Drb|iP_bU*j_W_
zKvM|S9O?+hKGc!eZZo!Qa|^~qqJbtd@EQBHDZ~m~2u)@Vyi7J)Ip*d6hC>|~7n;JY
zf|H@i1_IKC1|vw&I(QL-j-O7GRb*b6Yg*c86foe4T}R9NoLKCet|TC+XbRoJ>t=IH
z%8bd)#HvAo;Q$6aLxeU3a?O~nMq|s2gTE=R3rrjiM6cp8t))3;#()=s{Sf18qOhMa
zq^3Zy`;0=EYw(oN6c&a@&?e4&e+O-f3A;~?6egWhBgL%*6eulhJO!iVO9CE6o8rYl
zw9-WEA6zVlBVh(A7$r5syI_>E3l)r#s^T35=d)g=*iSGUfo7)3YP48rq8L45np|p;
zH(~@DElYRkVoezh@CMpsX}V3r#5@^RQ@qM}18s)Ck1_HZar>RQ8J|7y_}LV;cDE>m
zWdKi~O?E51d^X0k;oY+-wF90#o9tS53o}DgK8U-iO*~aLj5{=1@E$dV!38r?GkO1l
zJgFJ=Tc=lQGK+zKDFN7t+VwK?IR9!g=X2PSyzFB!$kqfPTxaIcfGph+Uymuuv#wSI
zcq@@P2_Hlujte=BMD~?uAU-B?@qsQ1xcEgL85Wl$AOY~Jpk=)Bt55SsZ;Um4<!$}n
zfBLVF8=zlNI;bbeqzw{~fBG+Pe}61tbUwQE`F|g^|K)GT^ac3qbd~UYd}&FC`uJXX
z`|Zc^FaG|o=U>+<{r30AfBegDe^=V|mw)>2|K;!g({KOw_*cIjOV%LK^eFc@*T>s<
z{GaQ06HOO5lJ>b2ksrFsMVYy)f2p?-{P&`_fBC=u-~aY^zx_k>a^h2V)&6MjA<|b?
z?DZ7)d)=%!)7VWosehxFZZ~_`%m4fT_}A)XTT{7mbvL^g(bD;TosU^9zn`=lJY?+T
z;_F_&*u9s3Tgh#6s^Vwu7Zry8NkauM!H?z-%)?SM?$>+kU;kb2fBEkpA8%_$w7vdV
z9`o?j;P6`AciZd!{_f}Ech@^}!bj9^S0KqBn1Dq!b3Jy$V^ggFhu_}|e{I?df4r9n
z8C@H}<!)CD=__&DLB)~P#Le-t+UYZ$wN3=*ycF%XUz1b`<*(0!XsPlzxc=bg%eimM
z0q^?#xwr4neGA{#92k9FUk<E?7N4~`@BA;T!I?R$DT?xCwK_kwR_Cv@27WzFzxejP
zH~)`gss3c|*FQ1;;a;*0?kvABIKv%5)l43cFRQ_xk<~6fNW82DLupo%<@9AWSkSow
zvZ#M=1w0|rPksUA`zv6`%9evunzomN0~b|R6FJq(YH&@<YVuWkRgDgbs+Jy#FROvL
zj4QzMA5&Kzb;?y1z2Q<He}4tu&hM{4g}p5YCj;Ee!FA){j1ha==zdxaiA=JZ-M`Wr
z-kY*o9lz3=JAG;XOZ~&jV$S~ZU;2Fs^!6wA|C2=iS{j#S(%CA^{z3yom22C$tMJ92
z!^1qQblR6*R>LzX=ep?G^jouCR_yIh_WGZY_k3B)!HIL`<={Z=nAODf__EsBKDBnX
zUuX>`6V<wDU3pdM3X>?O|DuKTTeJU=Q|%{P{ZA-6cnH$C^f2^VU*x!`FKz?-`HAW3
z`*vXB;{RGQxpiU_OfZGKTq`!@vwm;Q{P8Vc-{((u{GZY8^A19wZpy>2-bU9g{n5?G
z{Ex>L{)rm!oo*tmKf5WQyi!g_Si-WJfS1*R7jmm6;AJ($nPfEqFRRgKC+j8hjYU}Q
zbYCyRcYdG+X&knW3VA)kaP8ab5qMqAJ#)5ND8H^0p;%ij0<WuG`!<QvHzwab1-_pB
z@0?8~g1fd(5_mnZJ6-^`dO}`StngXSiiy0g2tvZGqL9}W!9KKA6!ML=@C?{ruf=z?
zGBP`DJr(kLh<HxjDhhdBamJ&-R#C|7iZGXN6@|R4$S{=cXb|$Pv*DqGPV0AjwHn{M
zp@1WHH>BCG$a%U%ZWV>Rt_UKct)h_E6-WDYkR|fE;x#|X-bB8$8drO-_T_4P>&9}I
zPp4-hFNfI9{^|To<aI@mcW)Jiysl`rSMt*93c*9O)gkbWHCTqV`|CCM&RNmi?{4cR
z%C84^wda#l!0T#rml08VS)s#tmX#8DT@j%|TSXz?nE$>4%D$fe?`TRLw6I%Gg}feO
zxLfZPg}koV$0sqL$m@#N`AN(t^1322E^HNrd}lQlz5my%@h9#$x`aJnc|P7gkL0Uc
z{-^gE0pB#4KI;Foyx5fT`N>AeS0fA`{H-1d)?Ziq^k_riEAz*vXBz@vReOH8Vfnj@
zaQ^c=-INo~x!dr@{qm$|#n10ILcTO7)z2;d(i6@@VVa*?{G~^naw5(%*Fu4x-&~B9
z&g6gN-ANrqu+cWcv;4x_%KiBz=l-Raocr@j&izX-IX6hHvYJ?~URDELpv+8-zKq{m
zgnMbUKaom*!jgS|e#s&5#o#`_<lMjXl5?Ne^Me3^*VQJHo2eRsFRFcd$(eudC1?Kg
zyyVQ!FFEs<UUFu)t%}Ery!>;gNzMvjO@3LWj;(^HV0iiGPp>xf&%D~qf1X#H3vsj>
z6oD^{^zhKlYP0{sgTRH@gsgUzUuo_0OV0I6FF6+|6ZMqP+GeN!!z*yDmz<xhz@L!#
z7rZ-jaB}y2IXDE?XEjCIzpQq)PpzHp7g`(l`TP(;;EQVTzvl|D{LK{@O9B7icn4xH
z!6=x66UE@m!GX0otM&629$Lm{m3RD-#ydWHDUDz9QX1#Y)?x+Ddu!~EufTfS`N?nK
zPu&APKkht`*AE$S0o*Dk@{OzA3QY;iUn&2aO@9T6c($%?(3ckfy;>B%W%Gah$VWWR
zy&T{BcLZ4l?Z?*D4f?{^Y@av427Sk({<whLzckWsZPzn`7xw*{&=>aDxNq!L6Z(#Q
zbVVAMUm5B6j(HA*3|n_M=vOR|drcwVu|cj37{4^m`JHhhRqx*0gkD>hko9A$x<TKu
zFRffL_O%rHj=Dz!(%#vGUhmw$IY~YV?T@#=`TDPn+sFLZHTuQA6=R*VzPDKH&%^#-
zYt-9Y&3M0OoyFD*@7%mR{_;OHJ+B<|m$mtS{PbLz$jj-+%GwO`f}IGNLFc6ytWbpJ
zg`lnYTQIfF@NZlQ!lNSCX8{PQ3b&nkDF`jXcN{qJ7c1&(0cbH^)fRvN#exb5sPfpD
zc_|{VVoZ~C6v*Q`FGc+sy0wKcMz<8?=z%-)qOLNLZ+#)?Rzw@lE23aQB04Wd&VoX8
zUND`xL;WftN)@q%^XeIjIK5M(EScR43ivDdbA%Zh{+Ll@9YX*eGss9+8AIwZB>HzD
zKyb<eGLfZuUJSQJisX5bT?R3I^J27k#PqE)YFwCnQ@<`uJ`9!~)#pWY>%#KZjLD0B
z)r{jqzZhRMC+3zRODm4gi-;_om|KKRA&_rI95^BYV`K=)i%~J|E0SfeGTOT_23}Pn
zLhlHK5q2^CjM+ns-MkpphZwtgomu5Z71B%=bmWY}>cpUP(jAR20AW|bEinfJCU0==
zEd*`Gh!%i0qfi(k=X+`(JkEENxSoSq^l*gna$&7tRBG^w&cWL$!sX^*sGN5f_q5{;
z7MnT9=hgh*3S^7Eke39ZZ&Q)pclhAVhz>`%9L*>AVDyLFJ9k`wrwG39h##ASEGjps
zho)lU5$iU^CGN3qQ)J_Ks-I*dzvI_BN8h65d|APHe#b9<j*aNeP(xI3-fhy8VtjM(
zhY8-c30ef_Rhwd70E^m`TON4R9EiyJAWCyY{9@55OZGD_p^Fo1$AGjOWW-an_xFUQ
zia%RWmMs9$ls9^<sKFcCqefN>@QzI}^gGYk914ECF|Z_!#Bnvmz#D9#heKqqdK5(U
z3o6ZpJTqoZ5}|+{YYxTZk`Ze`V#M+l68|uWCudJyPaI4A7OhK=Mo#5&AeYtb$sJl@
zyt~;_2))_GqI}w8bjmA1#>J`J6Ld|R%1=SY!iDf7pk|tVqPRMi6o(DnNE*b3euyeD
zDuCavoH&kpFfHOV>PcvY)2JsCEzYB!Y_&a3dgUKkNOU}DZ{v44`#{NeOi#MW;UnqE
ztrh3<?8y!mXZY;NAcjM#CtcZv&b9ndoKrn1&u~yFKTH9M?d;;T0*&oN#<(M(=ySs#
ztdAx|C{C(Qa;+0bRZpr>1f4I44dcM-Ngo#{meTDMcm{=8xPYy8GJ9J<vF4<x0b}j#
zBDN`~m(XZAvE<^)34YqcAv9Y~AD?KHz*sxG*scqX!A^d^66aiGM>>E+-$g4_aMUTu
zQUUku?4r8`_w0<UWozn7lsFokb{#+bf&))xtcAp;J=HE^pcll3<Iqzkssg&%$!t{x
zY_n4dtrk+FPEdh>B6cdPRw*q?m{=T!%FMM8?<{$*O60$tP5dCBf1Qm=ZUOu2O!_Uv
za!o}PEhLr@$;lSby~H`edDq0IQgGrmu|=2hC=KzMl{juEvaXe&Z1plf8Yf;O?M(3#
zjkIb7NsMPwufe`DTW5_pv6Rqm0lsIFDy~Fy>|{cpfPB*=<y@JVHIg3|oLWlDw~&~$
zAU`?+^51mR@3{EU)kLCH;$WD}DOhTp9kYqZtFF^!jnaRib+t*Zv5Hfx>33CeYPE_|
z%&^$6YT=xTG%Iq}J3@*!oLWl$xYz-sSEB2x-iKo<hvY(HX8GS^R!=pJGfbH(3zEvu
zc53FUd6DdKxNfx*CB9GblX3e}-cDx*be%}4J)Oa?M=f?Vt}PD)rFiC=`YO&eBWFrk
zTgZ|*4riK@nUZyHA<4SuJy)94Qla=gAQZjpNpOcV%`S2R;@)MK8pa_P!~h4N7@bl*
zcp&z)owm<^n6^{<`SRKzHx@X1X0lO&KX01SPJn`ECZ}ca=}b#H!i%#n?o3eROcT=~
zPCiRAL>zoZwnRVrtc%tiWH!^1gAs?HB~K&nX(lc&(9z5wi#P)Dg-nu2oP9_}yvngL
zl+^<aG7DkTcd*_~r9m$CIR27F6_hVCnN|(=H!-~yaNtf$iq4=vnMoLn=dNj=IRYp6
zI11=TrdU9ZMFBWPB2vH}GA;QFah8e7q=4;XiVvlb&trl>rQn%X{3`_{wv&`C#SG&q
zYC2A`<cTSIPR6l{T+`D;J!rVNiK(aPc^N<O!=crgD%BV(K1CN)uq!6%hKk{?R;3-A
zC(N7TJSv9cOKvj@nW)5;hL_k%aDB}hjL?Dj<W{NE`1Q=n8ZjCXd&Mts0c`ZbJ(Cn!
z1-Y9SfFHEsPFAH3N8)7%FmE{I>Y&A-KzzmHJg7mY2*C?-E>CfW7vx-C2*-c3bJCCv
z2V51?oqG$+DsDW(<qV^VrJW&S4?w<|D$^yFh9j^_rH=H;3qZR#Ll!4Sl;Ss8b<Vcp
zrI0x|wPuxK>?xwAo(c<+Q_U(imV(S!4+y2`rMNed18i36#c?XHGJ9R)rnn%si&L>m
zH%7j+g+Rg}HQPcUE*>ZUtVJ3*NP8EAmT|MIqQ*q#yIGZ;0W`e}AuVYT^)7@h!&F(N
zD~GzX0JPMwv7{|iYg$nJN&G##j<d2z4F+@WLhwx-mE{&IGnjH`x%tg-6d^-cX*ev)
zt-j;5EVLjW1=&1jk@gJD(h*F*pO!`XGxCuxq@(P%kp-}A9G^vWdf>=i2#1a1Q(>f~
z!OFZKR>M*F|1<VBx!UABbLKo(Q7d?n`lYl2k8Ll()BXm%|4H8xuZTS51`MNs!V#Z4
zlaf+WP*jL4HjuB?zRGm%K)&Mmh}ix|l8X-MeAkx|fegS$l9Miz2Cpx#0x5QvaxXkr
zbO&Z}9PAGCm0{hRP6w#j>zuNZ><~%xh^l^*J??1UcU!fJBW#jJcYS#(NTYis+GLaM
zb`=K}CEe}%vS?g2j$q1G^GH;=nj6PeWNWi$Jpxq@*JWvxvLf}<L2uWuYG7ZfR-M@Q
zWhfzW?Q#+mGS@D)nl}*`@R(^(*!Zt6Ps-@G#1e@oVHI2G>1}vYL_e~ND-PXD=GY@q
zGN?gK-ak*JbGRs)UBQj=libn|2EVK|WR6{5RvVl$S3;250S>;~dcndkht5bW{L<`<
z44Jhu4bLE9@p_Hf<cVEQ<uky_FWb+}61%>9Km!NoyOfyhe!DO4P+mD)uZ(aQRqM48
zp2^IPAS?bT?bs19vq=-SOj%Smuk|`)DM`1E#7Vb~P4e0X$02wmU+S(qAYV^*9E<C9
ztky}Czav6<`X|?GtDJDpOF5?s(VdsGQWX-q9tn|@InaCMpDr^WklsQIZIj=?%}d#|
zic+^8iNYU)u`dSrObC5#S`%J*y*95W2>RM-eMDJR2P>XH=u52n+3w$}H~9H}F_Rlh
z!)p_r@W|`^0x^T2uTAus0Q!F6oU@wG5vAhJ0CPHt%)q){!#z=r*K4z#z``ptG(3oM
zPRZiVV}<qFfz83gdhNjGWMYvh>xQug5#PVzzH=1Hg?)qduGb!HLi5J92Rq|`KUXB>
zaZ4-!WGy|Cs>t0*s<g8@k9Htc5<>jeKenegF}GveoSq4OLDlc;W7|8Ov9q5mYW~gn
z$JjEbGhB9TThnu+_d2K}AuaZ_eVWm+uZZ@MM>O^q$M|5{DJv-OOVzQ+pDWt8Q!?su
zZj@qwahglE=8Nu}OZ$<0F|Dtubwr98opxkw8_zcub!?l?#G;Pf|2(sJMvhd@RO3sj
z$FXZ<&b>U7jV~o%9@}0?PVPL|eXc~B#hm>Djpy_6<p+#@OH!KZV>c&=h|XA&l^r7J
z+RTogpVUS+5u<~X%G>*c@9Jq6gU@O!n*h=AC0vZb=qU~&K4^jM>X^5ru*s7a*rtxj
z7qUk>h@cye`=OA}M-mDoecNO+J0@+y%8sBxuh$4j3P<$sFwaNw1&98<cG(z@bnqUD
zT9_WxBT>Za#LOc})#=iTWotYZ>}MO=k*>2?Hnbsf#ImUk*CQ6D_GOC1`T|*R>K0xk
zVpBPLs$)|*d#YD1T|sESQ$AyN$y5Cl$Sg-hN5N)^WlJ1BODqQzhtP5)3*cXc7T7$`
zOtV)qC^sHrX@Hh;h~avsUI#)fPjr|mNAf+D6_j1Q+OJ@XnUJAJBC{0gN-T%Ohr1HX
zPVLqBZryLCf4gI(uSN&k^5!3pgw-IQKLQq^tjCqq99FB-dp5P#eIoz5gMG<5UW1`x
zuQn8vpX8x<es6y@0jG~dEt{ybF}&iI^uow}{vk(YF+0o7Y7*tfva@;tV$0TaGE|O0
z-q>WI91*4a@x#XQ9qRF=EM_uX3B9s&FvO;GYhe~tAqI4WY~Gx?5$n$zZtul%wV3}$
zL~pQ0MA$vO0k!b_yGu=kX&D8kN`#DKm?{xAj-jd?3F{+Nl_Qb8oP?Dysj3j+IYOo|
zbd(6&!aGZPDg2x;i>hSG+bhvqFA|2WU;;fy*bLqvVGKF?3H2OKUtKmp2%qYdZ{=+T
z!(WMzCHxc!ED<(^x9)Y=Jq?yd$UOcbZJ1(Jc2^5AjiI@mvJ?Z2Vc+!DbrRdp$#jWm
zb{@fX2~)KSah;Du$_KTzHH@7S@j0x2hD?M_;SKPGZDDMm2uxuT8HSUZm&<2)QbK2g
za=!jjptMBTVZDL5u){jD3qDsg5R6-5HGugNA?uk8ff4psU#+hX?#SvFP6%H};}_;_
z6=*8qMDzusO2E8&QZ%mMd+1hW+FOkk9f}NEvAtu;TV3Bg0Sr^FDhB+K<Wf?x@{c4{
z)yy~-Qy%L|db#I_Pz8WZr&T9&T+Br&8x&StZhJyFQ(?G-a%NQaF=2vMg{u-y4N~8h
zr8g^z)Afk-2<UZllvHwhhO?SfwtC@YDD?%pGK0#4X!BU7BY`d_W;v2Got?|2a_{FS
zp_FFrbi#W$Fd-UNg#vQ~lTIABB&CDe_cJ0YTkJ3mtFm_wXY8pYZ;shqt;y%jDfy%*
zD^mZwC~HzxwYUXUE5FE*sA`d0fN)-;Bg)!pnpRvNNAeE+=8mjl#i5Z^q<Jy2inW7{
zvsgR$XqHyJtd~en!h;|`;j8y<+VJ|lo1v1Ham}0Sr>NSJ)**(>-dX^}f!TWmw{qrS
zRdOoFNUOJA!b%KNm@ABx7;-^Z7%MU4f<BU4{jsbWI80jBgXj#wv8<Y%-&m+lLnnq@
z&=p7Ek$^cBPvH?sd8Lu^L01wY#|Xa&1QdO%mQ2DMLso9Zff{4Fe!$z9|Iss98_#c?
zvPY6<W3}{KVwHin5@Wb(z}pzs3%reCy*(X@Va`^?X?!G7-Rbh776ET#So_Eh@4~W*
z2m6Smovq){#<~{pY&6$-Qo|-^K~2I+jOGf0XrsA;AlhiEAb_USZO;|u;A{Ngyi-o-
zQ_lXbt{ZqZs`aj0f~i;wdp2dMJA!PDZ0sY+)>KM)#k5!}Te?xKl?~h|ZX1v|WOg4(
zexUcyQ@7j0jH_C6i{?ubN04=q3%YXP^pjA!7gx7Co+GOexvEy6t#4}q+Pa+3m9wxT
zIf|bY<%^{^t&H#kw>9QtRj4vYf?l%AhBFP;q{<wD^s<}l%WCpdhG|-r^qNmN7C<Fn
zWjMQHy)pZvhx-j!GzqJcJTrR8rBX?j8GX7Dz+#_jM51D!Rt+k4Oz`K5vJo=DD<`<o
zr?mr(&RALRYljsNkY9-~D+kHpT$z=_=79B8NppS5(wqCo?)0z~E=@R(XC=4wch|XQ
z^2$(x(8_Uoh#2-<Q8uxoI_}?kC2-me<d9~r<kfG|*VAQOSMpQ^c~on%Xiibh!4uk>
zyAd$$PWxA((L|Sfx<aD~CxWe)NOQ{4%x<$+G=o7$Al>=OTq9~CX)pg#G3({&P6DJO
z$&8@&k~^ZyD_zMwbR<-QR725aM_1@EN0RS-Dm;?tc%^GHO`^*!U17&WlUusNj)}Id
zoNEqYepn?zPdFxZg*<a4sA418wsqZ&WV5fjLdgkJ#wyvEquG!q8*{X5^$-49Sf@63
zE!>shUlR~Rh6xk7D!iqigwpNDW>0k`hjO&(=7N1~T6JPyGgLRA5Aw>BqP%cF`N5sT
z&Bpgn9?ga~JeV+{t2Qnsgws4%$Y-G}(6s@2&J<ngi)c2S>98l7c+*ETc}%?m^xdS@
zwVfAuK0>}blB4yxlI-SYwZL9$Rtxkw=XOoD%n?9quh3<}l&;!<z9!onYD_fS-<KK_
zPOnrOgokjJrpn+AQ@SccKAc+WNU{yGwR>XY6OMI#M7PGatULJVyj!&ckj~XrNe~p7
z?dw65jgb9)7lUwqu?le}V0BekGvPF5wUYuXoC~c&oe3vUtGVWcv)0#+3$zN)Va`M~
zOQb@b3G%{Kh%@0ta+QSFQEj8MsD`rFJy&$wXm(h=OLI6wUS;tPXVt5$@KG_*lLh=-
zfixwCnhaLq&V+Lc)((U^5#f<s&p|kOVI^U8)Iim^f2)PLaSidsD)gGDVXS~)6LnfK
z7+P)RCjdvak)L^|ujG1gYX?D1J3ErBnJx4lx5QclE#^q{g!Y?N)_G6#t2VsJ_#CE#
zRcxZD-7g0G(kgin<wxv#@ddxy-TRBdV)H!{Jzq(#QolCl52P6Ht3s$%Y{{t2Z%v52
z9I<+tEm5oXJTP01gvAPG%TIDk32Ie-?1~{BW^ElwZh5LL>bwsTwfLoATFrlE*H`7r
zK9cOM*G?O9Q-^6>M>1|%igAS2Yj3kPiL(7t_K9L~)zMEO|H{v9+SQG)d(@TXA0KVS
z7V_w<gvB;8Td^q14F}$et!B1#Vcu2EUElKseW~mWj|AQ9?27Gbg0mfol!JLCbVORm
zyhSEAgqA3>nBlWTvB{i#mMGIN6)c*nRR^$GY%%9X{0P({V6oU}9)iUpqj`Xe#SlC|
zMW|YJ<Qt?GTr8i(JOIXGiy7ui6kE&#U^G*!CKu)i&Om=satC9<WX2bA%2EzcmhLu#
zltrfXQ?J)0%=W4fUyg*OX1=#H@^30{i+Scie!|qQnl7X$HjgKeSZp9qAd!Gn6-vt~
z%j<)$Dn#X~m*jGaQUf3sxv(oFmm}feu#$WHh@=`wEEwC#gbDMzDomItMT#q~$x^Hv
zKrF9ySK4Tc90y_)TjY6p^SL4xBJy{KqvBMEEMb~gO(ILYwxl7lJn?Q<8i0FcT;oQK
z*H}BpEwQZNhdmOlRrqR;NQ%I-*PiW}2y`UqNjK6FaFAI^fc+EQAAn}BJ=>Yv`UuoO
zc7Lyp^h`?qq=<gOUHaO>7TLwDtqR%Yoqrxmcj;?~H~E`?5=wWJy|%J(>xT(i71w{H
zd-*}Mcubn|2U3Fb^c|G4V{N79b@1nkLcdXXEU8VzbE1<fe$3k`WzBu!RK<09?abyf
ze3)%jN$4K0ec7aRKa#w@aU@r>?dbscUR%^;bUzY0fYYWB-|D%dtfKwd$(ea=VT&{K
z%EA_9=CwCl2VwCVt3{c4ZFEDMd2Mrx67$NO79-|;#g(jw67ynBbF_ELdgVpV*M>7E
zhI89;&J5~LieCNb4E?$7-6q(>+?dW83}S9u&X8f|-i8R+Fmv0z9fP1}p3U%MjzqfW
zElDpI5{_sfIA7|Nr8(!#k*L=u!Paa_=Rxt@W`-O|HqoXu8FJ>ftsFrEWGlz{XPdyW
zR5u&J9GD*o4^TJTz?{2J1-`9$FhBD)|AS=RirCo=^JQ*3y9tCcw@v8`mU1OJ&$<Me
zBarURx0f*u(O_=7y4U+FiE4e)lhHyW_<Cuf&2306a~pgiwM^5$j%3`js<sMMv737(
z+RZKFc@@5p5g97XPeSQflylq94Grc<RJTfR+s~b$gXgZ+n=8mOx7PsD<^Cj;vSaPp
zJ~`!YSy~#6DPQ{<t?_J!S91dX>9Ot*fGiSg+>)v>)cf{o6P@KJq4axT*~W$<G)2y;
zBy*q3%<4)y_qpuUUWsf+BE@%X9)Z;6@cl_B-DXbHw<?61BSCX+^^QPoi(8V?1jM<P
z?$1;hG}DBx%3pKY&d$8Wa~V!aygs33Jt-PI^}Q!+X9xCLR8Qvk%70c}H$A_M$@I=#
zw#DhexonHWwVBJtcz%gzE*s;pZRV0K4%cRy-&Nt-Oj5a3m^P;@tMXE9jsVRNYv!`;
z4Y6jL^Hq0l0O$Jr)g)J+3*$R^i*wm!4YhHa%vGU3&SjVNCd>F-wzc8b%!R#unKg6S
zV-2%rIxlsFSu@w?v4&bRonO1M63k_jJQs^2kmkmCsCXfu)*OM96ZcW{u_IVK!$NbC
zpa063)|<`dG+nH+9v%trNIYCNn^|>_L{$S0moG0@cr$aoeld8s<jCIh7F4mc|7O^W
zovfMXiliDqG;ORxr8yFoK~U^Sq?vp6M}+DmHy(l1Um%=e_=Y%rB&<P{@M!EseZ2*T
zDD#t0BAlt}1@<{zT}|uZNf8YM{KBqo?2w;?((UP(u2pu$k!YK+!M>0o-ro0?a>D;g
z^x~wHJt(JkyC&IlCE3djy38~etPyd1M)y;ooLF2fW4W9%j)R7EIzuk&h6VeRP`Z64
zuXV!)J`&#9)Md>z0n(zmeZX4CYu)bUhf|hXU@gq9ZZKqKRH^EWk!npn8&s{RGe*p=
zZZBA9YFB&DBSkMARJQn~gUaTVycvdm%WBASK7y=k`QAuR%UyjWS^3vJN6@q*LUlr)
zX<Q9v&5ZXy`axFxwQ8_0URk~kUd@cxx_{_5xAo@0oo0eHSTsj6C||@r0_nNC!s(O(
z4HC_fNJ|>L(@e0I8{9d~9%*cX=Ui?gfH@bs0mr$lX=jO#A#|K!HK5}RHz?7uyt{fl
zB|IJx#S_f(-M*;Wl6jM|{2mZ*u7t4w_2!BgVsLM+NYm)@Z>|LOI54h={wnG7{E0jy
zN>RPv?^Q(=*NMatW##>aOQG&2%Qpx$SCo9wmY$&$sq*z!)a>|%f9Z;(E)nmFG#5+a
z;!n1$Fah$4=)Vh)SD@}oguEi^ln{9(szS@=Ee`>FZ9h?1TjxV0yZ%8&rNSLER4E-N
zv?SDA3Bv_K%@uK6)1cH`*+7t=%O+PVlOl~ve7q?>xT)IU;ar)t&FpfST#fs(S2PeT
zJ#_mdUqsv3KQ%7mUWsZDG_AX_=^(nIkuM6hL(KYyYx^f^uG8Whh#S;!kY5q!7!6L%
zl~Jj!&(d6}t=_G!)mG=$@8fONR2!&<1OJMsMSZhK&FiZ!uN>+h5j`%8s&P>86Uoh~
z{M=UrIwno$N`UDG3FpePeUNajgsBaw<|lex%c^QQ{95A@eac?_tm{d=tg2ow#ak!#
z%1?^&JJ`ZHS?KaJ*u=Vt>2A%#QyoIi6=`v~l$<M({>E4gJ(DBRHdf<E>WT<+(KxtD
z8GYV!D8{n>&IgV~F+Xm|srj@z)DX@;j$~w6eKu6VaGi%L85FNA`73M7)gaVd5ig$9
zZ@R{lar&8ImCfdrsRC2Yn6AK7Q?&PLHBNC@KQ}n8j0yzf;j`EXT60CJK`<U-xB@JA
zSH?<2*pHv6`^lwx>M)~KimKywrEJdCty;;RtHM$<?vIE{<rb^egqSO^E)7#{vsx3J
znyKHK;56h)ZH+r(DSP#^kpgPaUNtVaT1UVq&{nIpl114?tuQI0T76M#y)ZPv=4Z@7
zZ%9$@4_iyzjMr5ZZhqEV6K=|UYXZ&iJ-F6{n!%>4HBd9O@oKO=Zbm0nllbayT5)>S
zT`cBy4H_RomR%E&n$h2yfOKv)PK}5{nL&yw^xNLgwu8}gMbaktolBd{2J_}8vvJl0
zq*I3%t<5a5cr^j(3@@Jqa=J45DRFd$>nI$ZL6I6xFEC9gI;V9DMxC9eHDJ_N02*|k
zD*|WW0JlI$zx!Mf>p&CO-irXO32A*3pxvZXz6Q{e;Pa$Rs+K;sXM7X%n%CdpdtH%U
zmf!D+)DS_h`Tea4dT00Rg}l?7z6MwI$WFN**mXjU)&;v$^n=y~yVKjgF4)c6=?^l-
zt#^JM-1YT=2L0!VZn0?4R-<4SGVAt0>q2H<A!wKWa|JXWzRwlm`D;C&$v@RB9j+V^
z&C;fz1Ie?v0fe8tGBrVvJZ<lHLGrY{-v!CKF>oaL4PQ4xh&*36L#RA$N_3&}^e#ax
zpDR-xKxJPpXz+Zlh$?hO$k?t!XMN{>LF)<2LzaFQD*Il*5oIO07|=S1I~>9Mh){03
zzE5fQg3*PzBm8n9?x7dtt0GG*{;+wjNc|ze9o`*u0q$^|$3_&%D^mr6&gBk4>x<bp
zrWGz)Hw`#_sde5WK-In}_Vl0-S9btfXKy;Xm-a3+9lCSZhR}4R|FjKZ>9AoxUe%y$
zZ6B}tS7f6$1g5?$a76U4JgqGsYTh6X!Ktqg91-2A?ZD9Hb$B~4*t`y3&TB)v*I~pT
zf?;19I3hlb4f`R41x$y))U^LbFxe|oH3g@>3ebk&^s=1vuB@l$^bnfz8e!=WdFhDw
z1h4MYwIMJa-X4qu)A3q;SJOP9hrsmSA;`=lw}yRN8ynf~jlj@GwtFKmw2$rEi|`Nv
z`{qC!lg9A<g|>b9-3hn4DDYfK*4lRk+7RaU<%S4yeSe@0L2jM|v;p4saMOghT^oTR
zxb+Q#HUzglzNQItea)Z^-XrCUaodApjt^fjXoI`RSB7@&kbTLZ4R*-gy9L5oUy*cg
zt-;+^LPo{D5{)FmwC@_UA(+-(gErqRY3nwH!QH!nDGc^af;NT0zDm%hAedD>McEb+
zC)yMQbDN+|fpGVBVhV$M_nJ3_!oGRXW}>h!9vlJRO?!-4^wqxgWojqfy)~FXuP+U>
zsm-wO4YVob?F3|RGdH>2X8#nVcANcEklKsiElBO<tCTjnTr+4BK<#!0PXTK824Xs6
z>bHT&3z<LB>naR&C))*L>tBIhp18|RgWuGdfGTMZ+Z3WU8~9U*s!IcH9;|H34fW=<
z8NFwqyNSqjL?Z=yv5>MYzgSySUoB`;;Mwf3or2Hi2|t0)<~_lLRCQ&%elbj%ZT^{W
z&Oft9+tkkmn$3YFTL?Apb%B<fu3yO(dI&OoXP|{3v*lX)q%6m9v*8}X%x1$qc#4@H
zg3LB3V*UH-K?^}>vt1v;&}O?nz);^lXxir<8D+kojrPbbYqQB70#x5GXdystpUECA
z%W6|oBW$mSFt#;{w4qve%M*nw%Q+w5t8W~%5Wf1-K?`B5FCDb#ZmFI7A&hO6;(fEN
z_z=G87D5YcUt1A7p@ksVHxpV2b(^jI0Ck(~f)MKF<%9<r<3pA`&Y&w%g9W<Hrab{6
zu1GF|NaXeXgBAi_-#};~;MEm`7Q)@SzZMF3xrA^8w=uqi&_c-TTL>)#z4i0|hp@NW
z{~v<hs$D^>EU~79ke7Q1PYZ!>wevr;{q^01M$V)wQV%ROH++5*f?r=yXrY~LwaFjy
zDf@mwTW=O+Y%d|J?-#TsWaWav5#*$-J`GraXf>JYi1M4)VP(S6>H~o#9QD<NwgjV<
zfOd`eF;_xYE#au{C$uFTtv(W1x7ZacqAmHHE5N>lv(?*%rJZWE^}n=J%?k$)vXK&&
zr6pXg?a!<DP}&kKL1_Ip0IREey<)7cdU^w}oIl*h0SgqZzC7Gup<Edn<yEfUI4ogp
zRgu;edl*(iZS_uqQ=Kc~#quiqdP7^<nAXqp&uLW3=+2OSd;XUY_g-RXE74YW7@jN1
z-YvHGi7a(R>Jh<hvEzRUZp-KRU*K)=4q$1wTJ%tkw_?x#l1G_@15e7by}lmN7C(`8
z`H#z@m>;ni`<J}Oy7h1*G{VOI2C0kf`Yog`w(a*Te|-tc)Y!)T7E0?fMB61xQY4Tr
z(-64jCoZ<^w}9HWA=(yD`#wb50CnDn(7SSc>Ow@@+Uxp8MB8#X7oP-dA$l<rtL=pJ
z;vK*ir2A$>gQ55nc?Yls;fhg^GMdP`u)$~Fb7))mTx`m3;qyJSeGpM~pBHSwGglzm
zPJk{xE!YC+(!7<}g6QJof-QtD-V<ygw699E4MOKp_JfGA!g;|S`c^(K*n<X}7qSJ}
zd6u4U5@!3#MBBpNVvBzZe0|-aZJ;(UH#~@_mCp>eu(q%X*aF((O~4k=mRHUSy+yi&
zw66~gwxHIxB-&*)UjdZ7wuQ7W_Q4j;`j$l7f>~XYXj{H$68JnRyRG%ri6hBszTS9j
zZE|0E8BTgqs%f@#f3=78^@sj~wXe<$`YWjQ1&IC%YTuxrdPXF@lI*G@p;|$aDoyJW
z%)+&KQkI{<H!1o{QOe~@e%X%nSFU8;qj;{2rcHj5qw*cr&YstoEBdPq?yIfG(_bOB
zFH`ha+t;_did}WmzTt?dlsRDi74*J359qI;_uiZ6FR=SIS5v6_wy%?fyRY^a{T1%M
z%{37AzRgun=vAbplrS(GMTTW{1%%Eo8;t%6o$1vlW%>Q9)oXYBRyS7uX5YE!1Va9a
z%opmfU|kn4j$~w64H0DfQpFKbb#E5>E6jd%GSFXPwk}`v7sP&Fccu{gbxgnh3buU-
zqrZaf_jM(N+P<36-~G?#TE^|Dv<r?1_35TQ0;x}6-`vXRFs!z(W%QS`$-T9g=y%Eb
z3D_c>@@d2NrHjtJuFai`Uh;4CRVh?VCkCAm;@g)gIy9=i!!Iq=Es_P(lR~w9-J-*w
z+B;m;{Q7%q@6bVpy|s0CI`FZ5F{2Y%efwTU&+zM4GAJ*ek@EK3qBJ+!sB?o3;_f~C
zNT+t#{{7<i-aa$v+;iN!yCR9GN5YB#W9mp)w;)U%Ngi|_N#iNiX3)PnFX&h<N1|>R
z*}+XDk&dCXb;qJ}vvm88MZeUjy{lh4X@aMD;Y9d|^ia^@Svo&2Zr?&@ar+iZi`%!Z
zQkn3b^a?)-rR=lURao?y?o#xEmv`^iig%9l*LpVtU3-9z8Ncs!ijJYbm!kyr-$r0B
z+4`NG!d^1<JKKqEHeV;M&|b3Hd&T3pmmxN{FWaQNBWOIO_hbhi36*6V^z0=serK=r
zlibqz%X1O})LvNh9rn{EF6kK$u%EUsSairw+czwF@}Kq!E3LFplk(|Mowlx1bcjyd
zS1S6YIc?vk=&+oQM2d)twaxD9wciqRzjj(Q+{R9mhV*u-?>ml1bnEYFTRZh1R+A{X
z*RZNVgSwYvHvM~b=^D31-7OrnD6RL7cVVw?&CsIu>Q<fW%l4Ivo~)?7nj1M88%>HQ
zjkKq}6W?L4>Zjt?P8NA5KE(D_iH?tEb5){~m*|vLm4#;6*&UM8Ud8XtLA_V;dzZdr
z;l=sS>I7hI8IK`6UCFE8oXR^F)DheXztSY{?WNm1xnUn|=M(R(+!8Z2eTB~z=@C#%
z7an@LCbu(&cifjdJageD9SQuJBdYn7-kaRW9ZT;8k3t^#Be}h%#Np2sWdm$sw{}a?
zoaWk&&|A}_+fFUsTkZh&CE@kU7uw1a-iZdZ&6(@)hxWbU(4h`(-*9+3Zu9Lc4jsSx
zj^Ta<h+??;0Fmi(_eHm3hgA<cHmf%2)b6GORMD+@=9YUqhj_p2qiwofhgr1mHHppv
z#SR<Dd5E#Y?z0Z3X#1W-=kR0uRzxS^-uAtS-WJtul<szUn?H9%cQ)#l#1V{Jlos&K
zmn1qzK|8AV01c1}Tg5Prw%Kz%&y#i(s|Mq^OYvMu4!&aTpk5Sf2l<?Iy!ZE(n4ul(
zcI%!*heUJ)yp<SU+iA%==W5$mC3?pF+Ia%>Ai4GR-H1+B$vtKEl6Z1E8+j)?<%UxC
z^qvK20r`AWqC+9tzA14eci7Hly=1Z5%1YjoX0*+&>l}k_E=qJ5Mtd%+1_<Yp52Zse
z+H+ZVqlLz5(tB<*^m^~qFTSn<+onw4o}uWD;Cm`7Xv3Fd=sl;p3S^tMe2I&<r&fx~
zEZWnSFU+DnhZPTY6?0g1{^Op*s)07rmG>kcZPV;J$M#2pZ-AryBa!ZzP3%@3G{`13
zu?shxyC+3i8Qa3pg|^vpJ=sD>z;Xgt=tyn_pDW5QC3~3=K-<a5vjMh^`=&0{Y6t+k
zXSJe>ZnL@{HvL<rCH+I&`N@wY8<b}00RE<!^G9-9BUgEc{<4+6yhD-MBFO!k2Q_F<
zqi8aNwn=RrUeKO$l6R;-KMAF4G>q+<fPTYfGeJhTvy*oiMMuI~k-<vyMN-{vNov`U
zjZNuJ=wT}xM$t}A$di)Wx?w9j`9yoz$c8Mm$D(v6f|+n#VTO)K??{X~61`;Hl4=cR
zI;HuMWL>|hOvdm%rZoYYLl*Q%$Q(AH2aq`&QM1Ds+Rkd;2e>(GLPI0k!)Ekl5$$0k
zdQ3G^Rx}i%J%*J7txk2`ArNh|=z3C!_Hc}#4q<4IZe5YBk_}B)Zzn_Vgd^Ti>Q4EN
zFWbk^8~3n*Ovd`HROcNQ&>nJsce36;M>G)J$~M;?;2h082XKyN)d1(0?7TDXw`p_z
zH!t?Ek<Gl>10$Q6wTFD(M{*k|m-i7&9%1%RKyuiKo`B@g?4G9%c5C+u1di7g0Rl-<
z-eKf!GvGRGpFLo~KRwAld%Ug)0NCZz?ofSp-)=t;=p^NRa$9Me64zOVcbDl6v3d7x
zUBA6wU)ICkudlC-Z2ruT>l3hZrt%J<XPeg6FB+Zlt;ur*x4XNY)_~fPP&u&8iOD;J
z^L+_yeR2nTcYCZS*w&{j2ex&)t7l?cx5Ikoa`0^BFYgnyGj;7qvPF~9o!#Be>Przi
zW!bpc6x%t^J9MDk?WiVL(C#+32^O@wkEc4+pWSV6V@@53UIhMiyR9+HeiBM&usgkZ
z=c2?G53O@0c6XcP+_>1?{%WpeJiFUUPZrVcHqs#x?VAL>!ynovvUS))`x<!<l5C&N
z^vEZqmF=Q)r*{nKZCYCos4TnNA}0~Wkz@-a_lwSqegs)n+uH$R_Rm2bKxVgpI@mCF
z+2p_d$nLhs*{^ITNAJ-zOl^?E6FL&91~t3g(#aCq%@#T&q34Luj3?Ad)H{KQHl(-?
zJ!m&u>6an2o5KZl_IkV7NWW@jjk9^&CdhR*n7d()la*z+^}Qh1D<@6w@O`d?-Ul+9
zJ=LMDW(!_?5wqD*4f$s`JF4OSY_sAz+@IY{Ywv8-ceA~od->gLu9F65H~iEj%Gu7L
z{`9<;w?(n*arc(wLhlfDwmESfZ^mx&Qm4D)_w~A~0rol3dB<<E&3EhYc#cFb=0fBV
z<(t=g|D7Iy!?T-R)azvs*et*PoZY@1`C`x5WO3sZ+RYy7ya>9RO>n|;Y;oOwi#nO0
zwo{uQNe&j3ZYSDHjpJ-Ld#M$PWGiWT&l|Seth1iiaF2vi_L<$(<hR=G{n`i4HM^--
zza?n}=b9~WSU5ikrCeaD4eoSE?rM7*r{%7mja+ozPG8=+3;k>{#rm4}-}M9lS8Xff
zs67(Z42-Le;nVT=?z$-5ntApSfM-|vr12r|YWsST(0o@L*wAuzwUK?9Iolb|JG`82
zj#-C;v+LCI4h3gdThvLwIRYtS2k5-$9SY8dV)mpc@+qlWG|CqB0vD?cYVP)L=Rtq^
zO^&zCB<rNl+tps_1rk<!rQzi4YI}N<yLDGt)Jf9WPKDk%|JabtItL`DjA~9%jznuQ
zM=eK$?tLDy$<0yCR>t%WJ!e;&+{w;)u1G(bJR`-0_SnMaNNHD3?wx2^eM`L)y6cFf
z3b?Eo*_>5vr%3O+Wr;4~RC`xDw&C9FYR5KND0j7En@p9v;@3`k&aTe7+M(xc(bGEQ
zoL%kOhMTkNYt^0hqyz0q(d0*ZO*Y8u1mu}rY-J~RW}AlAH-x8M?D2*<vy05`dmg%-
z-Mn*Rx{GaUPF0UY4sXt0k4WzY*@`^gJE!UqsNEnN3C^DsWgBdq@5HuZr#CVEc9AJg
z*uU)*=uf|=)cdl{dU9U2GMRT6FT2=&hVb%}P`VvkY%dSa<9CsZdvIvKO#~a9?C&BA
zdfWhvr;Kl9kXH96;-9k@<>5Y(>_nN|;|1x8rtWz2Ce$w7it&Y(PAO~O{MIZ*Dov2P
zsmaF+)pMJ-HQt88ss|F_N_7PQxKdpKK(5$NJ)oOx<tD$9te5QK@%})r6e|YgN|9oi
zFS``02KGv^YW$zhS3Z&hv(5P$a9f^TUcDLTW_kVMy8(1U^8u@8o7^?tc}rN{1Fq11
zx9blSzFS&A!gpH>KnRQL8JV^Fl&vM#ig&yAfZ@B{ZEW`5W!0pv+oo`hOL;lv+4Yk<
z^4>Iy2XvSHE~^F{Uwf$sWS9Le>rQlhwU-`nUG^K+yl7-7ob#aW+o{b5?c3&ijoT;t
zoqi3__sR@@1`N3)8vG<{EIW9>wA<o#4QMT|+}5K&|J|?r)<eXWS8nSgxnKX4+j<Za
zXuoMukCMNKNjyY;d583-Q|1VyxZL)2Yh?%MH0IBMxwuUX8)B%u%~b=%Ub(EtZzk`z
z`3a%eE2{Sq<-lyJ9FXOt<Re#yZPwNhujQ>?0!3_jt9AA4+-gmL)?1~i)3u=Nb4A&t
z$`7(R#hS-0sd4P)-eMgb;%~FLh6pT5QGO-a{hrXtV0qs^&*boWWu^|I`}{<=6#uNf
zU8}Szm(!CE_|D6`t5LY^ctp~gV0I+Zd%^4oSQd#fzj$lTw6&MmCIhO>5;beUlsN)v
zK9hRwWwq%cV|5S<W|^8bpt!6ZuGgj-GM`6%sfx_!Be^TX+VW5zQPu?y^|;2#+A^n4
zdESnbJw32!mSPm9DC;W+^}sY*ds_Lmp4J{#okL=!iF1Y)?3lHOwHMlHkcJ$yOxPMV
zOHy3*5xZJcX@L<q&CV;yU$m@RcU>D*bNK4PWsGGa)*wT~k+8^+LgGmBz5V{JdXnzv
zh*a6m7;M&@0J%)n8rb}6S1Z0Pd)BU2-1+zw#e+{@t$Z*Dt91{)eATU*LC%h~i<M8N
zP4SB+RmK<|cQ5uU6R_pElB~_^`UUlQsb5eVS-u0R%i6DAd*ctREid(e>ax~$<r1>i
z+U}WzwdJhkBlE62SH#-FR`*DxJSW~-Tgr209)Yyq$-9=bKMn3@E$22LB$HWYgdIuN
z&~OXo<w&$XwA<t(p@R4gj)V&0S2&WaAYpoz_*>5v-NCow{^0yte(OQHpS9$-9;5_X
zYg+5Ux0Nx09|YOq+BY9bR({@6V!~R(YHGG*SPQp@mXn$fSTk#RMsovlE!)hHVwPE0
zBO~xUYjxM9Q5X572R^Ewgwm~xjc8n4Yw1G8zzw!mvzkt~Hdn6GtIdk@tx`%f=XG<K
z512H|jI9BaW-XcH5NX!3J)S(8wW`={1M19j>hl40W|_t{a4)W9<2rMIU5Q^5x2UQE
zf+lGlN!GXcwLyJfw}7CPYsvg>iGj=3H=fwF4A*#T*RuWHfWhT}n*Z~k|Nfjo`~DvN
z{VeMEJ^KT#H&$=Iz0m*oZ~y$i|CE2;-+%f4|Mg$b(%eWx;J^MMRQj4u_)Xf2<&(C8
zpJzFVTIqDrs#=T7$honc$)ZI4Cmd$I<lKwpq#Ex{7ocPi|4*jhd^4G5c3mYe*q?lG
zgl~v?(<BhmC$#0Lf!XjUN<8e~X>wj;x1oreRabn%L0XzFXiwiB;spCf!r(GX==w*~
zZ9Z;2+NHvFHZO>9Hk!Ney+10|HH;nU?hm;`r$Mmm#&<wLLY>{_A0LstJ>SMD%{ecO
zBwSh>*K`h`K7O;J{{~KPyO#O;Bi^!S`9F@I$R7Il_{q`oXZ&0(43;}q?pI={Ja?=l
z&S<PKax_+)*M+g-fXE&y$5MFyjuZ!Q_elA&craSLGiJElR0cRQzv1GzFbtPznAC__
z-QgZRU`lm_F^?EC!Zl*1x%?V5QOwGEmB+Emu3*T7^F!p2S+o2ZF3!5-;WEEdJq?$S
z7te6HS824974tQ0t2DD2@;l^!`EBZcBjz_w$~;TW?~l<-iTQswU<gKe1a~wnpx6}E
z1rSF%30D3VXCl!pSE#>Ooma>`uo!I)$ISx2OkiE*PU;nM4y^RStVrJg@i|X1J0fFv
zo-#TsZCd(70NU~r0^Tk0Qj?~<Lfd<Y%qz6JPpb2CB_qps%?+J{LzrHou3kd*DdpHA
ze*KCePa-kyj|83L7SK1Su_he`#R|6YD{=N&p)Gv!$yaE^z&Kx_BQr?p%luR#*{*0Z
z`-pbC%s<Vke#%rM=v!^yvFlc_d%w*6=a#7!;CYFsBu7}GojkF6SBQH?INueXsq5|@
zLz8(edQy=c7Q4x~@7oLxZP?T3J!NnVyZA_G(xwG++Huulg)VCBm%f)pkf#50C4Oe{
zOxB8221k&<vDq@ln}t)W>F}&vG+82$ausEnKT6_`HMN40*<(%Z-S-&{Q#eHg>z^PC
zw?!t7?(~f=(MES#Yp2XLi+v5cBS2lQ;75RhG%c1XqGT~xW{4_t%9@;<?SB8Jx}6GY
zvEA$zr#AGP&7v44SCZA7dSO;l+xg8#acVce*(sVhx*>Xf1{FK)BS7uAtG71t|33sJ
zpUpbK8V^M>KdXZ?Zg!AUGZ)vwGKUoJ!<tOxoyUD^ifNAj;wLx-HkURyK&Ryhj$B4t
z$t8VKGHw}#>@6L-akG)UK^jRov>c{!uN<5{;NFWbt5skxMyECs=?}UBn!sl9Mq=FH
z!!pD4-u+vSxJb&T<%o-9by`!Ce6z9q0x*{MrQVg&t+f30N061qUte&)9YJb6k~DOt
zrv4FSL$s?XZ$5%${Q__f&sa!}wdRX0TF9TZ9E-8!P0!^>j7P9}NNPYe;xIlbs`->u
z0c?)KSa5bO1z{|>NS8^f&(Hq7#T@^I{A6ngp$qqC*Vxv>26Zg!Ar8+{<i;a8O)^il
zyg(*l8_S#Src;(`Fmu?0e?)iaj%D2!H_c`}<-6{UkYcv14(j-8A$v|UQ;+1<PI!I<
zSvvvxZ}UL?CiR`yBV)>G!Lz@H_9_MM|B>jm;H6El@{*DEhz5f56-_xUTr^*b+gM(_
zutP{*GHb%hSbo`2;3N#w!nw$D%*Mhc`epuT$&2>OaTcG#ZTutpp2`6PeE+rwcWXfV
z%FAfc#4UyRLTkv+UT(;NH3ZOws07~*gS?D?wygi!gxm%a@Zj%n5+jGab%ivMN22P1
zl7wwMlcoT5<Mm@;ox?4bJUd(ttXMc+T;i2JKM{B*Vrj{w1k3x&LQaBp11%Qv5iEyU
zJd#{p9A~j`=DEx%Ev4U*dJaq!!}JJlYx?%G$GPgFaUfz}R-2e;f@vY7$Lh;!1cHvX
zctrOT_3&f!mQ+tXrCs}&LP(RPY{x0es@V}ic$9T1rzJzDEE7%(;Z>I6CH}T4nAwh(
zSV%{^953-m?$~#@#3RY~N-cob=R+|YCrmFK=r2V{ES&kTKCCxUkhIcwNPv2MSWkBH
za@@p1wu9xciG^GTtK+bLj%3`jY7hGLZXXZu=U|9Ok`)%4rBqlnODxnQxiyx*ufV)m
zCZQflHbHLtQrX{i2T&;_RbE|g`%=r@O-nNv*sBz?$ukMHR5_q}y6g*tl)EQKaiW_T
zrlkUIU0#JkxTYh?HKMj#P^CaJlS_{z>!IlCN0KA*^-G0hL`y8`_E@Hu76?Pj^wI*M
zXm!v13Y4|&6&h;NYTL?jz&5*4NM*1fm=<ywED=n9gY5K)0xp*1VlB9$1+vz1D8&My
zYblbVe1XqTLNP04Jk5;hf1QOe)Q&_wi<7iXxy1@xw<F?nB}6sPQwVcMqQS;yuQ5-b
zE6RSeJCg`*%dWC=qr9!=xk@0o)ihTtbo$jiS;=a@+OTrquo-u2!eJX$o$K<iue#p6
z`5rp-F73Ugk$+Qpk<iM`FR%!Xf7;i8zUFD#z&_JQk0k4Apl)DaYbZ(z%_&O}(AVtG
zg$25rCuw7cXpZTTTzBhg2J}{MNs8GdHfAZ&5>Hu*0ng@q2!+6l%QV%Ju^Cr0Qd5N^
zkzT-(gPA8q*#eH*O8a49^VDr%Ve`~&fMH|iW)#ck3YZTKIBc)qnN{=5ZEO+ic4fiG
z>Wm15F>*xG%`UMTxi5M7l%<+|VrB9^h2Ws8ZY%#`YF$<grq<;)gQ?Zvttq(b@=Mqd
z)<x-5!$1uq{76(W(61_*Q6Zx0G8eVr!T(7potaXN(=0fvPS<O(jMiz*d4^c06@!Il
zrj{hm9|@)G)1kw{au>!UkQ$(|+V{-zy39%~9ZX|!J=3rQY9^GHo<E=-9R#a7T`OE{
zSoh$f+$g>25Pv9VHQM(+s=<`)iDo8+7M#zk3O1i3%8Cj%d!?G5ke%%tq|nma{hP_y
zA<rzIA`~u@9ElVIdDS~%41#5vXz83cnkHJXD;6}-g5|MlvGP1|ti`H1ajd@YQAh!>
z%o8oxN~;=PxxllkrfAw=3!CSDK5))F(L&7YRRGS;k(XJbM{);~SfWR8*3ja~*V)e%
zPr%N8&Q#JPxih0IYbMC?Dhg;^uz{C|qlM7o%f!)=;m21As{$R1vyT1VN}FtQ=RL8X
zWco31t#~Tt*5C-ZH(c009Fh8hO`RB}g&oKdsDkimE~B&zh=Z%>u)B~IU=`0r&bO91
zrsZDCTg7LHT-;klccaSy{fbRy_GPQ&Q4`2#ifPHqfy)fjGRRN7inqFK_g3+Q9spNq
zehlC$p0b0x@<+td!A5tL_UA>L$5dfX<t`(&<UV<o>LrW4^b#Spu-{&0q#jAuw^}h9
zL3XR>Gmd_X(hB;ON-3M?IX&0~ij7)ESL^KF$_uN@WYjW1x?*?M0O*RXYWx(>DmJT0
z1+c_VEo0t-x(paAwwJluyFNZ@;R5h7AGL5vc<FGs<SpVqhmN>&7If62yU5Ey1q)d^
zmSPGPGI^}m(|%llbUeXAevp;i(+AQ0=&z^vNCbQ}!?}IEUeEA!ge~(*pMtmSh%^S-
z`uT{r;B{LLHdye?tv96V-Zorjo*u!SRj*ft0R}qO;E`kt4A4{CLq{4sqT4916I`KR
zqN5(c{nF;69!b&$awk368amEkndO$G6(-K>HR49`Um~8KVxFA5UJ)ix`sNQ3NX;=V
zgdA9}r$0dn))#uP;8<RcJXi>Cux{YNGJiPgpo0Z3^)gAdOl}!2GgS+|?d6Drg#+s4
zfP-b`-tqNfF}Y>9ZoI)l*#BkXYRS0&OTh-qyoLOWN_mdYp-L71I`!E(%_+rtJ)=3s
zSg&U^Cmkz;1U`sz&}l~BNE^!`0t>M?mI<nbWLV1-)u+t3MJD}BR18J_JA!+jZw6|~
zbD%K)v`lyx;n;tLz$Ib!Xvs9NSCa4DI&N13b2*3|Ujq{XW6Nut=W5}|eudaAk&*rW
zDFpZrNA@d9jT@!|6oSHpIj7~OXbTfg3t8O4as7_u5(f6fi;>yju0Wbfw#b{}D746%
zVoob#`~0|Y#2MSZ=YO*_2*LA*<HM2ZmAv}Rc&?!671V!F%C0v&N2N8!XAXK}`}C>g
zS#WIK04W*0=twAK#XTXT-;&-4lQg!mJ33#>6DbDYOEZb2hOrI1M0a{(8+SQQk6qmZ
zFg%>`w-8GzcD`i({wg|vECiwo<@zlocnqidEu?`AXZkJViVW_X9TPY6Nrs~b7IIF8
z^Zb?w8l*`Id*KMAD)RGrmPYXTY;F^*E1dJU5Kcdw^0x%(<YH;=5=}pr=PnsKV*$o-
z@h_YJ_y}$TmM=#aNFT9$vIH+Aoc*^XcjQV?eH6r!0sa)2C$X6S<ctp|{w*Yy4=4UD
zB%hDvMPg;l<8Z9O0`(=9AiThJiN%@#)g?^1DG&)m7d}%|cu1-WO)_BLpmO2F!3E}2
zEKZ}IE6P@J90kiI99OU;%_W>SxWIFX<pZh(X(F68xR4b$oHqDKvQ->Vt#<!b3mc=u
zHauLJaJt|Ee>9vfxWF-u)vdSDo^CU1H9iymG$Q(k6AB+mR?V)lHEv17Gw7(Xe1NqE
zwbKC>#F%i_;F83cSYA6|#>DdNkped+oH4l2@!_PwN0Q%F=UVq$h4TeJ1p@L<#6M?i
ziWNt)=J=pNR~PF{SM2jq>k3gWgSdo+K$zj!ge7BThFPzLK_BY_d}hWK@qHE_!|MXn
znFxEvk~<SjxF;pIHfDnrR)~NOR&oi6@VdY<6Q+cf&9>l*azv4%Jj@C!tYBeUSh?)_
zFe|LUzdw>3sBmz?#IOPhClu7MK*9+JH7v=*i7%#MfoXF@dggw{u+0uugo79sZX!f@
z%I`#0Gs+6r8IFYS&y|NG;rnwfBFri)n+yFRURlX7xM5~lfp-((Wgv++SHi#pTqAsC
zw1B>0hFSTcb2uVmfu9p1oE7*vVZvG2IAA06gB%LB7LuP6CY%)rI^lSTg*g020yDp4
zXyPM5@t}b=?lE%W22Cvc2hk>|l}*y7Fh#9E$qC0tEO2td@evE8oVYZ#lJ|uozHL4x
zUYMv>FajgIWMC+UBP15A$@n59mTPc^<0BSK(uhhazlzt4tJG`8UTU4~jScXI&$l7p
zgaRLyOScJg(+Yf>2;VL%FmB?~(+YH(aD>AO+a^R%t4X*C6V&R<)x|JHtwOm8bJS|?
zIKoj5D-q5^Otd4oT{f43_#Dx=0=*XabO^%=GbU!ZHWk$lnp9t)aB3n~_GO{m!1cFn
z3nvDy?CZk83+u~1F&w_IvOf%G20oI>WALGgsUM0~Sl@)cC(J54qT8Ql#<SrKX92G4
znZuC=D`ES8l855$-EPGoovC0I+Dn)Vb|m=)a(X=}O4XeoWLGv<1e|kV!ip;*OcASZ
zJh!NC298}qScUQu4nkOy@)Bl<)#T)-MB{+Hp(6-ZE)<7IUKKx2nB-N7NFQ*#o)k5n
zQXhb8CVEwFMaR^?-`c&N4x62;GVs>I2GXpribE_+`>I^m4%5Es<<7+PJgkss!mO_f
zS0=>qs!(OZd3I}3WkRH{=SuDubY#K`S0+sSI+FX%O!KPTeGjp`o=TkhaQMM`Gogf8
zUA2H~WBI+{nn_(pa*xTwyslc<Hj39(lV1}KT3F%N#7G>jFl=Ik*ya^?Z#Y?Rg<%uU
z)mzIC)l3YlFl<603v0oN6lR817&ZYjtirJgC+)2S#1BU-tOUf5q>p9gKsNKoYDr)-
zeXQa-57Wmg&h>yj_EbFbF@{ymEYVABNJqC8&~9|AAtO;Z3vh*)6Y$AuQgdQ-HxaxW
zpl~g~-SEYS3N<I3|F=TT38(+9mzonMrBzNlf|!Q2a8vLTtot|1RbjI#e%cXa>zaFj
zz3P`3xRO*VOk_Kf+rH|0fSRVURql8Mw6*6-vNhGZE|8j%Rym;xQ_?EOSm8{<wX*Y6
z*ux{p3M;<Kkz{>+`>G~RnzL33(I3NMnQCP-Y93qVa4sAlv2uPFqOsL`z;}wd&OMbg
zz_>KF${Asp##RY86K1hhE>MM8Y_%qhFU(}Cuz8|;{UIM)biLyaYxCA>ZMWpcfxUfM
zNwOirS%d36d<~P>Dsg;58H1lI%JyWf*m0WWb|hy?IyrD9n_ZabRx6IJaBASnQFEB+
zR$=nQCA!u7%ITH?+sSf!QgR2eS#Fi%>@dsiNbZ<0%dI9GC`5C6uH+7i8&|OsmOo5$
ztDNA68Edu1EwMIM4mZPewF(<3L|3ax^a<0|Dny?!U9Cd&iQc{VLG%gp)ha}v5M8Za
zo==#qR^j;^iT?c_m4?Y`wdNb87SI+Ctr9ydoYc2A0Jl5+PQC1raJt?Kza-2%t8h?)
zT)j03Dq-eXO*YP{ndd8XoG|sQLdOYH&nkiW1Lj#JEPr&T?5s(%xgr_~6(`I+tCy@3
zZCf>)Mo49~Y0LOsw#&eDN5D6Pj&mdo4A?l~K!%lsuTM1F2PB0J#W$?2-vVC{%FdBU
zF?+_gwEwB(o{eUE0k%~*1Y#wue>52f4J^&ex_PBA!L)gv5<M^+@~}d%36s<+1e+jK
zVQqQ!BFsLk4cs&Ttirbm@y{v|6r&ln3CaHi5e<)E@QmsL?wNj8Nn#w$)3F`B=6qMW
zG2ow7Iy%fhtN9&{K<@<A9MJHoP-wzrvI>PJ6t1u`w!+M@BguX;fGV1Pm_1er+ZnLO
zYR2@8CWl#tnHjB05s1|sl%WzoG)x|=q{I%B$LgJk(L6z!s-Z}T&lTl}5y*Bxsu^UH
zq7%(?7K%=ob5^_jr%hMCDvX>k$E<eUWfi2dK7}b|^)6viosy?^kje25kK}#?6UvU{
zHo=s#+JUR2lsze_`DQf=xT>4d9d-_xSP70BW|SRC8eG-L+Q%(PD{xhp+6P)yUHz(%
zqJNUC6;M^fY7?reah6E?VWL_k(te1j_FPfTr&y+lG8`tVRRR&mC8||0Hq1+_Km2{d
z(Gn{F9S)aR0r4;?t%CGXr<JhE#O0~gB=bb|J{&SnC{$vF$`f^1G5A-V)92oJzLoWj
z=YA2;!4oT-{c!Naiun}8O}U)}>NynRk=*+AKTl=-48DWSsqT2!p~Fp6+A92>fYMek
zyC)p@u)^*M#}ufrdm>qH52F0e4ibQs8)CiHw1dN>w<E}}%sMiNM;vCp)eP|;=Dk%y
z{D*mOb%3T0k65w(pD<^wLhlKOHmtd^i0U<fy+>5zHiVudNjD38o-nDc!siK*+Un@H
zASD1}@d}X}t>=oQ_$>2b&Rb=(7I5Aw`?)aZt+MBf%X!P1fs<yv)x2dCCcRbIJYkC4
zk>n-!B~Dp|t`j9(J2s4FtJT~>NAZkimmTGs(QLy*p%81v+Yd)VJc8TZ=Dbw`@P|2X
zM{>6XM<nHdXR(iM<V(~w>>EXaJAyltinDB2d>U~%aFv^EVG3MLFG!dHS8<(08G7l~
zSG0i*Hz!PBtMk1js!449aCpRuGboDbEESJY6nVTWUZp6V(yf^tayX{K{I@z`WrhiG
z6>?6P|8^vI%A5aIFI^|heybCxJ(&ixn60zlZUVfbzg6;ogz0ZJDLo<f+jAv3;`HxX
zc`;uq0s2Giwj&s~_$OAx-MD<gB1oGOrm`JLR?S{J_&6aZTTMDnWT3?dNsdR1bbP7d
zNQ;$ww_(0p<!Wx=0=z98H|&Y@0;vv!GJ#Z+-Hzmba>#BqBm6&CAjKf211r|_Cx^o-
z9>J}>11naX&`%Iqu|njD*Y@{}Eb+B~Ovg~HT-lD-+|??w&l}c*NB6~B2iNDdG0wH{
z5Yeqpl5>WsZgqm1rn*&J{Ncchm9YQez>9U_H3$MPR)YSAnQoO+ig3il3L(fuwJJi;
z7dEkq6D0OpO}5W#$C}tauP1u|iRQ08RRkat*s2&nuY7An>5o@tdnFh_ymqZAN`IKg
zRx@8#n8sFv?V~~|9zk}Wy=8HCk8e(Ah&qagSUEBa=d`Vys|64LQ0>)ebqzu<hoc`>
zBIbt~YV}6U5A)MbIlD~%n%(u<R3?5!yf(o(a17JaYMx1k*=bcQo*Nsn#!#3cd$D5P
z5@Coga_Q|k*5>xC;#hZXd%-hI$TTOdauz%t)9^@6x6EyC6j|`*w%Ht^dU>ZC>xP?=
z=KSdtZLKCV=L)2GIYx~POQ<>1(GqKtbG|q>6>`pBN$&F}r<hNQ%B`@y<(%SAg-@*a
zlz%#WVuc4V9X_$fRvYatU+*oUcqzz^jA!C(O@~FS8Hwu%(yF=KhpC8%6>`LMg4zms
zW)ktRCPQO7;$dAxYMTzRQwdNu9r3Vc472Hghm|mAlYobHHTtaCVY3>2W}|pD`pi@A
z@K=6iZ?56NOu`w~g-3llp5YPId?qL6ItAQOgoc^UO<Uo>Oy{Ppm)kS9tz6hYb9?g(
zLuhUrzR-xK;~G8{uF-UU+9SCY^KLjJ>Rky{olFE<zl(TM)3FUJ)R-@5Q(bXOOiEZU
zQy~j0w3oTI&9~&e%w@|KYS(lY+X@qAI%HwZ@cEMv`3I?qpFfv3!2IJ}+5q$TTn0&0
z%#{!9f1bI#`CaK$I}&NlZQOJa#0rsSItXHgNONC=+MNyb<`*i>yfF|fjK1kOh!qyi
zREMW1qhr}lzBHQYoVJxAF>lnv3L$Yi>S0aN;&Vkb2WI13p0P=XoXcBVD3f#9Fy6U8
z`?YUS%(`|fs#I0;{LYW*D2WvY&0O6}9~7GDz=@S<HXS&zG7;wuoLG}SGo7inZW29B
zrK+vaXQl%uR_HU+ffFl1^QQwRRu-FQI(lLyZ2lLl>`1bWUJUM%HO)<{ENb)Prq#^N
zeMS0)okrT#290Kln^u!VGeu5&t|SL~<=?ZBK1<(&M*8Gx4@S8mf6wO@rFAk|<aL8-
zGnermWcW!a<uv~A9;WnM#(M(uPv^-!lG_*`n{V)!bS+PcvO(7bIREH8x)lgM5`8~_
zHS7{kD1WX<bq82OkDM_cUR|&lrW5T}h&MAn?g}aFXV_AJ>psJl0^$8<*is;l^G`x4
zF*Rf<G;E<G$wyi;YmOi>uO;9ACz*bzFhm19Z<kp!L%y&Evu1|i`bh5QiRt&|j&H`$
znMxyg&5WV<CIE*Ph$HAcl-+P7lV`a5-ttz&jA7-VYjnLAaE<O4UvP~C{&p?u(@{+i
zq|to@lYZ)ScH@z8|5oD$8td1%flm3t+l{h5qxzMgYgE0GJ`<j|mn7OVs@n#(IxlX^
zYdACHz-rKJj$}~2^D&&fqrGv9HUB*kG2Z{Em;*rbsIkkN@#=|1e>rL<0rThFt_5&7
z9boYV59f9dD6r?$oNI6XK$^kCxuqFMoZFhWF`sQ_dqKecA3c+cu3uY(fqHF8bkl~o
z6(Y4w6UrO0@@)hBB;^nMw;~8!dS_u#b3DOTis74H;@aIbo4l1G_|Da#6+vD=Fla@P
zryX!B6?E2Xg?R$`1}$cq2i^*C))K;72Fw2typ?7wR!utHHrxe*D(`-eC@VMA4+&L5
z^i$5d>0brK(#uiSbm-$&1XJCL!Kv=<7fcD#8xFW95xf<lQnR9&V2uuelHj`)p;8kC
ztlfC~A9^?9?SJ6iig2k>65>iJfu5#9AGZ>MT<H}`i4WR}K&o0XyTs+dW{uP`3Dm75
zzOsbFhncHL=`!L<tAK13s|Cm$E4d{f=ELa*A7(mKa)S@^Oa(@6c%G*tBR2x|f5?0!
zS$TQKT77Sc6M|M>V=-;2udz7wRDqk|x>dl<aZ*|px^3$zfUi!l8-D*8%c_d8H@Eh!
zCIWhOs6xPWm$fSV6XC5@;oq`mzTFW?b)`*4>?#EG0#Su-hV075a+*ipY6GFahlJ3o
zaWg_^jR}#P82%ut`4*OpDp(xWBUl{PM6eo;NuLyDWFQY;h2nR9$)-^Jy;90pO)@i&
z<lJxVvNDe#Lj%dmJdzB5<N-{SiPc{}r69#l9@%PS7$0gD4iBW7g~9_-%E%_$Nbevw
z9*Eo(c8bWR5d7^MnuN}PT=ArcFh0^u{EYSuO(I8$Nzpj6U1n4KhGzb|^lajxEVpnI
z55)tqkrTtDh}M)7!>ou#&>9aq1>0}76BTP;!G2mRiuChjk*YA_8o@K1@bO3#K}c0A
z4j_b&{D|Ujq@M;s#*uy+44Gx7MS~!-AX>Df$2@=H{Ip9)_`>`&I1H<G>rr?bIdWT4
zA#S9fhjQ<KL;bW2(eGG4SCEyJN2&2|3ib1(D64Dpvnfmz=I14Me35<{WSB3~Ps>_n
zI3T7k{FpD)PlF)yMfz#UkNJZAH25)(qWv5}2H^SPWDkcBs`^Qe1jooeA#9SXksZb5
zf0H#@Q^=`e#rJZt(^fWx_E*}<=Zf+h$&_swHPO_J2E}HXnbF|bEN7)`jdQ{;AW(y3
z<A6Y|tv}I#T3duCv9-(eS|53%F$b5)8;wc&MFVOIeq+nj!Ed&Vy+%YTlQ&w%`C4^T
z$j~n~M1Sj)B9><{QRd40lUv&qz53ay?G>^7utXja#lu7V6}>3K)VU(s2v_HdRD;CR
zD`I`=Y(=h2H8_xZ1=62G;fN@%tn_RBHH)}B8gP=bm!F(k9|@(bun*Z9yqqhF?DEUQ
zxdK(KQIpqeGen##Vrs+0`H7aX0WQv!<>HiFoGVZj6IHKB{gbeIMV#)oq*h)LQ@js4
z_6@x}m$NI;+ebFWj{hT}HD26d%=|>t&rMZ<<+?`}v<^d(`N_Nz!;-loDijPWAE6!5
z)N|MEd?ZVcsY0Q?^n%=%x^lS37k$~k4qs}CS84b$S2Pf;>?N<$oqxZ&PUE&3=am~$
z%}?Z|yDLG!>xCG~%oSCVOuYI`UWs8^|3qGjp<`bW6;IN3intBipmtx`ZH%5_YLB9d
zYcU>0_4bX^BjdB!YmoGr6iI(!#Cc7IKXXMx84;?Qr&V}Vjl$vv*Bphf)m4px*ZX#u
zH&@1T0$=}%)WW9rXmK87e%lVKctkO-gr#DT`pv1%+931W_G&!HS4t+$Cq<_zd&^UB
z={BdRh9&TBzw@+U?`6I0W{*gU6Lj~sCn4E3e{)KV!2sFc2O8PsSEetd>?FJVd3z3!
z?FE?N#8;$F#LB-iS~mG=`}=D1ezpC5waHi8UW1c~^Q27A1!H;NRd<{x*4NF8A^JIF
zpxIoJX3b)VF0Z+8ZH|cI9iHp!?8U0V(aZgUn-TOmZpO~;{+u^s)7{Hv^4N6kN?T)W
z`qd{kZN6Eg=i%sF5t^oemXoRTqAAe)oHJ9Pxnw%e1Vd+;Is&RQ<-2ZNXgjj|ll!L^
z<0&v)T8s&cekH8(lk`eg2KW$P{feX=6#cw7Q%JhJ8qcONrL&kL$}#2Rm^Kq!SGPKW
z>*u;jQVwro`JY0`&p|W0D%$)qKyrCOo?ye3>0LwpZ4d4gmO4q*5m9-$YUbU9UV*A0
zEL|+ebFhXjdvUp&c}1!Kbh0Z`4JM<~UYjXYw%cY3lzr2`Db>=I=|>EU;wnTIrC!ke
zxou{svA+I)WCO{oAJN*^>V@44_wfXii4gFlDBIx}0S!9N73t-IX-5fYQ$QV?9oFOr
zYL{U8^XE*#w8I26ZWjMUPE^;R_FS1NuygEuUY#j?ms=-<?y>CfOt1JARsE>xDQXZe
zr`t{u6y@Vbv?zFjw%s#ud*;UaO481BXrCiUmVqZcM*=f5O+1K_XJG4#!-dO|pq!iu
zdX(dd>D-YmNJl=mXL_{DlHglLgPMVP6%C4nt*bm&ncGR%k0fi~-9@;Cof@*i@|nA-
zV~6MsgnVqo9hgq~*oaFYmPCW%Gq)|IJb?OG5-qrVIsc?|n)I8|HzxgN?7fb&xjhka
zt<C+JMkWafW6cpV#EK(ih&4y({aPuKkj)}9e!jG2qWrv+d?+&X@0@7tKQBpFwUL=P
z8h=hom_*-6N$m7iJF@(dq<eQ$5(`3_<?OWq6ms?&k=OhDJxk$yc7A9q`p?q8`_v?r
z!2Ma_y&$RjKJr9kv75_oE*8j-E73T!POd~-L_(fU5!qI<B3S-OMfmX|8ZP?zAvbRP
zxu&~JB%;J^2t?n>iwHypZZU{H++JYq{9s!Qq7Su`LG)oZ@o_kLA=J)2d0{CN#mM-*
zx({BYxYIu4H~%K;#FL`P(-{_w)bWQu(J&iKpJ>TF`i@rC(10~;Lq7V_sx@dtQM{Rk
zv2t1Il#^uZ>>+K5U2eDg;%Zj0+nv}=QM9wZ!JVQwd&m(a#X0_?A7tgcspga~%9j^z
zK_s>pb>&Iw$763ylS@&jEXumxoByhJZd2BE%t$bu!V(XE>Xdl{%Z3^0EooR$bU(ap
zMdc`7=3#S1@y43<D2f<$jcvgtuHP~Qb;cJop(tH?i%INK41=|JlTC=UOIyc3n!KUQ
zQAckvk)6p7Q7DSQL$P*B^Dg*eL=<nq6>Fz>2TtI)D2gx9cDp5MA+&OQzBN)n9tn!S
z1clPmvikO;K?{oFbYl%(P<(DQXhBiDi34Dx2wrxF@9q}rGKk)gL)4qMt*anL76sNR
zc8~7C5cLjRk#&kT;BYXb_|OCzXE^3+yM|1pPwhc4VYhz|C9OAW66UR|ZXw<}lYO)I
zjL&lhpC?{J$L0#<yR0X~Wxu6lm&<Jn=_l+{gYy%gOYMe~jMp$i3df)1mf#v*@;Pna
zW|n6a`upBet^)n#c85J_op_mX9cd2|nCIE94pArUA?pxzNHU4!-a+oSQ1e#w{bn7q
zcJ$^t5$CZtO7{Y{#`+QDJ>;tS++QwS_+YO?y$K)e^;h@rD<!T`50&%2f)DnN$oHs+
zUYfB4<Uj5NY>i&5SV5(_ig~B|wWbUz<)gs<cHgU>^wzkQI~LT_aacy%{wBbW&iQ&W
zZ@&A{T>)@>gx50&&hzJjbXOD{-;eIEE)OrgSa*k)t41!<?~-)KdmBF4>-Q4HcSE{!
z7sL0VJ4BvP^5PWz>ppac$@ATZ?h1wD`_NsHa5%|(y29T0;O<BkKT*4ZAs^iJq6@^>
zIlU0`!UuPqMMpQJJIm5{L%OqceK({#%NsYOZ!1f=mz$**81g}0=VU^6raQEp@6L2D
zg)86PYKkvS(?Z3;@!4Ki92_6y_2Rq24OO}+-2CE}rR-}iReiUtJJ+tbW&I$^`d8~|
z|GH(}liu^)vhL7(e9O8Q!Z3tS?K<?H@0N9k-SgeD?icF6Th_hkTE4eIT~TgyOxG3T
z#<#4GB-`{_6E~YU%X?CkZSov0d12URc}I|~dfm?X?|auz$94*z=XGqWKe>3X^>xZ>
zC1ACe+c}9dL4e_o2^V`=H3+ts+MNKlmlbo3F*7SZh!lfZx&bgpA?{FpVu#zEFOlN)
z#UMuWatLCnz96=zTdWAm@=Eri0Liv2k0>j5HZHxse*y=07&>3z;0{A4HfCn8iU#1w
z!Cf(Iwtf)fPvGFL_%#k3+^gasJ8<w3)qF~d6$n`##UuGb37^uxLkag<pFgpLdsPtR
z=GG|)vRsXwq#ZYM@Ro#bmw&KltQp4*?us?zxWPyA#SQMYXWZbVD|IrBIBsw!8Oawn
zxO2z*iyPcYU*fpIzad`}{2Vv<2#6beONxrDE04V@Eb=SGgFCAZBYZ^TPZZ$}|K>=f
zW&CeZgga?oh!FfBQix!^D6a@RNbnK-2@-rI@vj)cPm2B>B=|`F6(slw2og*S*uxPc
zxL2+!enEme%$+YtaEH0`1qtp+-1%YzcMjv9SVCT+CdBd_hRUO;!5t>g7d5!o{WoH8
zhqrU%0iz~k9*gAFt3n=6D^bwn1nS-t&e*8j6wX+buFhim1q1F)0gesJ4I;jx0ryt^
zL<8<HeQxaE>@>JOUo_wj*N14p52DMD$Q0<!*-w|>dbttP%fE;|4xZOrhLrkprXI;9
zr_7hqrAv(Mx3(`2YKN{fHihdL`4XD;_GKsKfy_H<6HGjuq0L6e$RJnggXr>b9M-Nk
zqWCMU-4R?qiR0RJa+DnjY}DSAz%;C$1g7DBCyKuU*LCr1hK#wVC(&k1_n0!6PJhoY
z_o!+Ei)QHii$gQUpNAF?sWPOl8N;LR%TKDFSTM6jSB-CCH^-nm<*XjIS|k09gU}sG
z_OJcTT`ZbmW34&Osm49oZipz?#jF`}NI$*5w@7okvYgshV=J*7FRu45hv}evNBbH&
z9_sx|VVWq}$zW<TtbZ9yscZi-n92lX19g*{qMKCTqo6zg1|!*_Eyb7XonW)e0p^Y<
z$DFM)ay71@Gojv{6;*0;pZI)<Qai!7oE5bb`{qlFdL&8J+*U>Uo4&s`eu+?70eb(F
z7Pa>;5vp4GWkN->65e#%dfll{SrQ0q_9a8@{Y!=_RXM7kFF$JUbzKEmR88BKl$K6`
zr9rwDkdp3BC6`*d8ziI=q(iz9M3C+l>F)0CZul2{eZTjMf6ujtoqL{{IrBWv9Im}@
zm_z=pXRdxMdE9E>Nl6{@UE=G^<q)FFX|Bq?fBm&`;YFCU!)bojg-m)<Z0SO(fZ9hz
zngDaf8r9$xemw;aeoWkGv;#|C=7=q2vb_er=wo`K2>pw_tPXgCK_+Tn=V1PN*V;_)
zD&iD=UfbEu>1%Y}{`=V<cbXDepoGUX_fh$&3s;iv8e_Hh`HLXD5<Z>*<&zzWw;Cn<
zVUywB<(obWxw|HELDS_QFGFPgbQ;cDcBe1woHhCDIU>$)gR8@b+#z4}t!*AY;0kZ^
zVA5^uJXZCV(`18Z*Qd$OEbI9oTSPMHwo4A*?X7TrJW9}#9}t)+S>j(d9h<Pg$VsJ;
za+xqyokWh-<U28O=H_z-JKMP;Sb6;PmE`N#je?wzqamo-1?BNn=Cs75=@2yMYtkRc
zV^{pg?skNTQ@8UI$-(a_uWWf6lJ^;uQ@cuT&)+%F0cYuQUZW(36KzznqBeZ1P?oUm
z%;isdzgA`4{3=!HIxudDW?r6cJafyE=JSr3hvjDCP9lwlFcDU9`g{J=RMVze#N3<y
zm8Mkro!D~D(RaAvpI0a@N(*|93~QSXCog^uy3eNXV&(Na1HYt+CXcoW9gnroc3msK
zAiz1zCA=SflYf(Bn;xKh4z!Qoo3?J`@x1KEbCRCMBz8Ctk??MoOTvnac#~BA!yds3
zJh<bsc3`K6IpDV@pSI0|1m2W{Uq5Bd2Q!rLMr)I#$=9S%7=WbV2NjfycuT_fw`=8&
z4){x7u{B&ez>SRCgct`uTlT>Hy3NsL0_UGX5!C@t238nsX>Ym)zZm4M;qtJ&6c*lz
zLg|reB3h6haBMv!^V8oD+9#QHhpgtKid4iegCx!f{U7Z-rbs!2##?pmKNPfIw93-X
z8@Af*Mp{GmhGNe7^xXvA(RGm<YG@hZoOq*;WC2k)g$FZlY)-Y4Jxc#ZA}h|sdWU_S
z2M^fkcn;J#m?xj)y~Izm&`LeH?&BZk-(!#-=_9$o5lWgCX(Fd(_dp>|CRM6Z5$poG
z$4k^w(ZP`i%?k^;AM^8Nb_abA0y|<8I)WX?it_K@C>4ND*@UQr_>&gj6?_>~XQTQN
z1=$3cQNpQ`N0g6zoVeztGo?`3v`7LpFGn)}p0;#SzXPQ*vOyNY_m=`*h%NSA&7zcP
zjI(57t4KN3qul9@b0IByeN4R3A1oau{6nMIH}6UEqc4c;EIeP_h6C324lFc?#Rm>%
z8uWw*=n8v%MyxwAFPE#@Wdw;s2M(MWTZbVjufVtO3?uq(U={@WL}|s?8NibzBUFXj
zncF0%oj6e0Z1q!R(|T#4zZZaqP`%oA)+;vq33-%k-x6PexM#pwGm%89aNdB=34wcd
zEw^bw%OJA7d3pnxRB9D*qPX{RmYU6p)^}Dm56#AwSG_OFNbPv(E<OeB=WBJ@!7u2u
zr3SBkDXI)Q93@}R?&UYZmVd$-4N)wW^WCABk!3aI(dx@XqXT=F8o0ALT#Ue6o_?Ml
zLmVpYx7_(GZ=O6gh6fU^>Xu7wP}Rcg;B|?N@HrkNUT-Wr^HWKbA7tF<WIe8F@1D+k
z?KH(RYiID9A@!TK5?$T5Qzne~fu^;5G!bxe-kja0Re9!38+`*YZJu7l5|FHLReY`&
zyl9c8{2<oR$wl%^PbJmeKC9YHj`;Z&u(Y6kYuZAwr*ZdW0WE(Ax3oa7WEc3YU^QVr
zkJIUj&x5DQAZVzZm@-dfYue=X`CZ|xX#POZB6=!h+W{zjWESGFS&ofQFFcab#_b$!
z$}`jCv2*r4R#JzX`}q%ez*TR5rkYjuvmNl9LjH<n0OW41hjw`64#Zw<>b=*Jo=Tx^
zy%LJmn-C}6#PT2@)O=sX6zWnFmz=vMHM~)9hgd&){?3iOg836^>%Q(H_F;V}`F&{r
z80cb+pKM{QtZQl`XEW43t8LBgBoCc`w1&c=ACCL=W#Nlc(5-VqnabJztWF)p7|&u4
zudq&YR^X(`lwZA&s<Y>%rz$7|cnF{Q{tE^PWu()|$k10kxRQhuvI)NaF`VehDwxvg
z6L)mZA)M$-A|AJZHAY|pw>@8(R@h-+#KNA15eb1194lcO{mQH8e)yGDVhk~z&EYrb
zi9JSBT!?ed#nS`V2hL^F0|ZBn*rMTZH70JsC*{>vfekDb#3bJx3QXzw^fwoVon2c7
z=5xL!3e!pFOdz(q>J`BgONMK3(|a$t29yuDvFj?T4b&easjW8=mFVMK&M&oFmySR*
z@|!i^5!chhl#hPL<-}DsEI+H<c30Pbb_4C+qmP1ZQn|yQ{`q#|`Q;k0;=EO@uCa5n
z?T0Sb<Z~?R<Z6M$xY@b$)(J0myL9YayL=vj5sRbG&M-Se;91lI%AP7BsUG(Sd>6mo
za4p9RyKV7w5Z95nXWl$O?_$BkJ<MexYpg7}<AQhH@{=jaDx8AxZMaL1@;CJq1dFm;
zAMdm2Aee_?Fa?@&qF{O}m+rD*O@GER*N%VS=nF=anCnUm?vx28?y)bkK)D>#Sq><Y
z=NPut6boTQlrFb94h<h<;Bf|;_Wk;x$js;y`)SQEj<~+(qi#fX^$iWOvIpk@Ls=Af
zgOp(1Np!>#H;2{y-Q_$UlnVDywu`IShjgq=hP*V3W<hJ>WGaxoWj*S1wTGYo$olro
z4n}v_`DP@lFU#*NWfkp<*sRbBeAD4Rz>b2hWtMeCe8hjWXbSJ{`Ep71$`8~m!$Y;A
zhF+H1Tn^YA?7>#&uo|fTtt6~3#6X#`C_h|tzt<;I%hNKF>=^|6M4Z-dSZ7MVCGDGA
zT9{NPT~d&Ut|DnxA`(|XwxNvW&b_0jKgh7lw$1biIx?hu`<_>L?s0Nv{7l@seW>0$
zAflU0Yu7K@iE)T=h$Pf1KR+vh5eOH$HiZ50;a+-TH6}VNE+ii@QU~jlQh994FGos<
z&%+>)Td2<?^hR|$2U!}OHkO=kxU2&)7k?VjxvOjbr+!eFIZYa@+bY&+AEI(E7%46E
z;<KSVx<xEUM+$zJN~kZtp+}f6KTTIYvsQ4&0seWF60H-J$*Vfy!Z}1xO#oX^%2;9+
zcC8B_&s16o^2{bxg`^ragq2VvsFyQ0{_C(HF}e{}#$bBs;c^OX*=$2WT#<tc(vKJ}
z?utw~u&Vb6z^<<Q&exo^Ahps@)La2$Wce?eBlYc8YnIGkS?S-I2(*WOu+0&ULWHgS
zZkFxDi!%r;O+|9iUVD@pL8PrHLlnpY0<AR0eg>|$1)6^lNzVK{9XtJook(4f$kb$1
z35laTbGU~;JENm;U1L)6Yo1<l6mVo9Pe+1q27Q4R*ftbsQ==wR!sH#yC+#?dCynFd
z@m**9XSdT(vAJz~5?F(9?)%2Hs2@?C^6F96&q(3Im&~q(KY{y{!&7;CG=#GidX*@n
zg3Q6KvODPsgn6I&Cf~r)3h}|xP&M0k2s<igRqI9u(?YhrE*7p(fiWb<la`Z<*#hH<
zwo<D*#t_maYYxhx%O-DunPZ{TM>fpxM2V<KyOO>tsJ%z?QjWKwkCn@$T?DF)0IB#B
zID+_Hzb;a9n$Wp%wjj4f#7JmXavO!p>rOe$do_MHwEU)v5ocHIgdixLwt+5mrDPz+
zRj@44?Z7Bf<YK_jCB)}?VvdH9@2oAMTS%6mXPF<U-T4Xn%3+TV_nM(T1pn<<Lm$*J
zEi|aG8WKHAY()A&_uMbOrvX{_2JL4oad&LqNhbm9j{^5R$%M@|D19}uo+?~h`OK&H
zswS7wZ#}PV0=+$wP8=Q@d#h&{D^0Bn@xetuJR5lU<rn7`8C_%!_8bN8ogL~p1s3?;
z-`n5bZU=4GkE%9FmlXrK2xXCE%;tmcur|}1(;o+FM%?djJ6Da+<qZ2wP&`slwPgUR
z+e}8T^s#J4R~z|*k8^1cg<-{}y<+sWoegHpcIN|E<tgtdSt;^qn;raz850H*hxNSg
zB*otoDC)tF<SGk0U85)PRc$b&qm94q0!wXHymd!oc?T^#N~E&1`mL*fGAO9_d*9ng
zN8Ch3an45x&$QTOzQJ)^;doAxYw~ypKa&R+_jy`Oc6@HP6Ui}H%s}0AmoQPD%Z{RI
zHmDwJZ(R$QH0fDm=X50_O!`+}1G#fm<u85DRmYbZ<Vg)R<$&X@6+e5?t8$JSxX>3q
zs0qSXw)o?A#(t;54%v)bDpqWRj&P(QL2imz_sg$^8M)+xH!wc*(cbNRBWmOFCccLV
zM(Lzr`vYeN+N<ojW#?E>i4uIYfD<Mg>X@YPxdF!H+&dBc5kU^kvxKui^i+6ccOXfd
zVxdB1#^CcfMfq+JSdFdIDN^xMIb!EcipcVjw4C2`Zj3b^e72q+qj@D!t9k>u$W)Ju
zNgzv3kP_<F=`9*DfnnC$NtD6O+|$JmZal@lIM>cewq)AmDK%(i0iGy=O>s+B&s5il
zg-^z-psL(s+9PbPTX`maHr={Tir4*^N=x58#c|NlYs^;M*J+5-$Jk~j47+9tWTEV}
zVKEsbZHtU4YBg%i;hM{GywjTA6CtEsZy)^xU#xjdaZ(6e<`~}5<etJO3X|dpWKq>L
zWtre1YK49|>`%9hs#!FFJMJSuI@S_j?Fp`|U3rFWPHRk~ZJU4)gj9q|EkiTUw6`9`
zrR}(aI<Xx^!m?XOanFR}J2LhRCO^U~gPX~@2}WZcW+os2oBcI<o7E5$QAg9GzJ~CW
zI!!m&vn!$d(N2aP_u=NJxdb7S*-Ck4>nhZ7s4SBu;mh93<t||pCFd%`N(xk}xmSJy
z>CcF_eR6VNTh~dBh>YSi^?Nk|M--KVxbWOfDTpI0a&~YWLUNXUa!4{!i0g^XXz6s_
zccOA$Mml%|9Fg-(QrMH57i?BV1=>r$H!cfu&Vh->-7Tr9*2tvj<QLl09<-zg2OoS*
zUF*oYXK6NX1fHASybzT^XGAi#Hga&ZHwIZfeX=nyN8$vq0G@sV002&Qb{4KbIQw5X
zAKz0IvzV)+go-1`(HQU>c)~y|kOF{NL<qnNU^WCn&H@5Y#=p<Z;x^Wf|FAY;WMO0h
z03qEf|78TR`|Bdu{vHg#tm<ZK3}99SfsFxF0M=iFD}wBeA$_s_Y0E5UY-9!!ws8e$
zK_C_YCl3#Rm5qf3p!3UI1Trwh-T}bzcLND~8z<X;T+Hu5exXlIATMSW$k6s6YX{q>
z!3^F0z)}E5dne;RB@u{~sIjw|p|P@r@DupgT$PO-Y@F;3jU50_ep5#J*VMQm<tP6>
zc}mvU8te$!k@xS*5;wDSG`0sYi(5iGD{5?LWAtmJzYJLcTx>kRr@sCQnQO|vriUl?
zc%vZLYqM{!Z_m)AoakhVk|>($1qmV|BCM)9`np;eW~9EM-;ZG01pUZ-Z2xHVH!#pj
z?G|x9_zd9~WKianfMBxm_$5Y-cZEI%L{aWama_6U$*7t$x22B@gZG{XeQE5Q@4W^O
z4^yaO(X*nAVS~MIip-2jzs=w93WvQwh{}^s=bBU?3F)Pv%pxUIjg9B$vlz&5V@EtT
zNZoV0Dh<dL>uEuc*X!WvW+zEfUpbm{!o2m4u&QPM-dd{jR!TC*_k4|@e1j>mvh4wB
z;yI}Cs&slZAH#kw=saAL`7@`L5P=rmVCzk_=4Ar^gW@#HdWq&9ju=9^5T)`fb4|Ju
z5px_&tcvo(;5*{V<6KM%0*Tp~=a|{w8o%+gx5;wAgqRr6QKYV;&$=m%(GJ)&yKBo+
z#KsOej3}GI6@w0Fv?#?9*$2{46#By?&#2=iOLg#aahzzOm4y+$uI87n0Tkd?zrehN
zZDIZ3Q|!+jkgsY!8LUvnT0hFoTP(zkKe<F(<1Niz>e9@a^L;-)d;hJ;!kcKj%>DQa
z1{d9pnh+Iizf?sOudMG}sCm1TsbSOsYZz?lMby%i`!Y8}O_4G*L-qSEyws!0H?TUe
z^aa_$*aaLIW&M^m(VvZ|H+&c<U)lfI9;K-xS@In?9h&*vsO4{ZjDbx+rBydrZtoS4
z6J56SY$bf?)tEn$w`kWcLIIJHURN`jS!2UQJq6<ko=^+c{_ZN5=aQ7-I!CsHwg_d}
z3SxQIyP}t3$GTQr9_wUW;<o``@n*smn2DArMVm|&8AH<JS^D*&yCgBf^L1ay?9J0q
z(WIGx*EdjhMiVy9u%q33r3b90dKyRw0!tRj1ke*mxCP3W=HJ?o*euk#Jmy*PrlntP
ztgh1_3Fcma0g<+j^Q28ku%A%+3JV^l^K?#od+=y3r#CMjtB$+*anm`!WS4g3M_3}~
ziFW=FjvZVJOH3)p`1x@|T%xNyEh<tJMJ_9;Bmv4kr6Z%d#o*+DNLx6ux9XyLLD);t
zaR04F)G|rHF*Ei9oYfIQS95Mvk(4FG%?t(~uNtO$Oam}*`wcW1F8irY*JuoS3^#A$
zV?wvqS$ho=Zk=Q1OQ{Q)eSXHp$iOd(KdPaG%9_TVId5Ls-#A`WkTz-`$EYCVR?5|i
z@@F4J;A-sd?rx5ri-7sLOuYJoqiCL+=-iw~xWspaH2a_5v7QLxSgBI9X1KumCt|NC
z&{5{hU>cD|!WI%)trBX(bx}~Yk_GHb@XnT;PU3F7;F;Nk#)}Dsr%B?YiL@fm{O}2f
zc_?Th+mLs6=k4`Y-Y{|gZpb=ToT<h*txf6~xl}6x&l)w^t^4H+?f7Qs^K>p?&z5L+
z=4b7i8Efr<oJOiqTQIm*PDHw!JWnXvU8}ajq<7-m)ok54Z(*p#;(MB6rMS(H>UNka
z^!-0w(EHIs?3Kt~!G#7g<$T;4#T~2;?Y5+&r)H|7=2kA1DwNVrDzNacNy+<I^D=K<
zs3>AIb318%%*o1ML<2SJRQf7cMbMI)*jX;lcS^f2mnhz!qvE;N6t<&`Y`l)<I?1X;
zhZag^UmqX)VIW1e4t~|{w)<!AVftRSD0;SK;9EF}oQYl#cl1l1PpmWZGq9biPK7{~
zuZ|23mbNvVA4Iq2ig}$hn0Mk(OpbJuBrc~6Q&@|!qh({L1W!*nv<eA_qR)*yLMi4y
zADkrnNul*evAv}x&0627y&(I<2Tr3OZAgVRQ$!MugmY6wdnGiB;1uheU>N2QMsJE6
z>9NH>LfHkr_AKL*`fORR(5R4{qfmzT8d>MsgpM)J#597N)D9>4qZM)rvbLI0Wu3B~
zS&6+W&sS~cFUe<e7w^E|zRH)BAKD$*aV8!nZ}wTAl5yA`<nUVyq>Na`naB`PTYB2J
z8?GXkVRd|`ID@)ri6S^;DkRoXYN2+t_V1LO@(RklXA;%faWp!Tx6Wc`!AdlE&z+44
zrxN|edPTBdmDBvaqg*Lnp;<W{1xJ9A2}SeD$ays6L0w#9+hudJ-`UuUG_R>UdiWm}
zvZql*H+2Ow#=MKQ>fY-b%6<gtev5FXC;B31a7m|9p=?E>^J9a~p)!BkejlzXl|P^F
z>$g$oVT~!~DS6`{+!0SgmH{=n2q@;uLRNRevt=kwolD-p5kCCB=XAB^X=&T|FfJ!b
zJDU7kw3IPsnW_kvnN3JadNJd|{EMu!r9MnfmU%>R{1x(Mwhf2en_JFCnykXo%5)Ek
z4@IJU(z}Dfek)4^H+8OeD010mMK!zHld~04Vevm9yRV>q6DM|b$v_j3KvC+N%20_1
zM&;w9eu#jr?KiC-a)Y9BtmLPUd1sJ%B4a=yq#6`Hr5L!eL>ADBkVTE|N2vV4;EPbD
z?0j*dm=BAA*sIU)r=4nZci9AW7VVNQD;>Qe(eZn6v0{wi`OAvYRf43!G47hfM%owh
z)x#lCqoK(fvk_IP736(QcftD@n2cF4v<CTjcmo&jt_Y@)e^Q5SSFf*cY-B#y5Jx#`
z6{wy*G0~u)U(kA;ddgz5FV>gz;Z_X&1p)4vuXKylx^#Z6dUg=MoO6)*=@u3xQSGRO
zuZHg6!q$PrtQ;5N&!*{x>V_IO|Ib$L<lo)|2IRb?i5>|$uyQ}?mJ_rwC%m4)vT2rC
z%zvJ%qcd7%<6SQQ?oMZGd}Lcgzgn#QWe$jLWQnX4KPo09p%AA^ZSEFnz2DiLws3mh
zNN@M!xiqjOJS=9eSgDC6k_5Gr0$G;Xe|3M{wgoj0HG=*la>sjg7phM$Xxg`J&1zg+
z84mM}rr5^3W-Qr~2jWdUz@3F+4vOXrKWr&U_QaCzaqmpP7*q_>0gU^W71bn(Zg;KQ
zq<pW6LsvPzonjSoNbzcn19@|w=QX)`4rMfM-*2H84kNr)zFXdMxV^A0cYSpzFgQ4e
zjSQ^q&P&ro-|q=DEdh0W7)Um3J^#k4fEW{nKR~u#w3TIh!H}DE%RnrR7p%6D=qjN)
z65!cjiiy{epB3^ckCh|-Q!&=%M=OK+n)Hd`=g0E|6URcaHmQ3;?>vnpSqPK%nJRgD
z>L<prZ?!q>>JLN9daDw7Sud)=#yY4$Ey!Q=R;Skc?mLcqS456|?2#l)Y&1K^*qC$V
zg{ktFGU<t!n(p?>nY9XbKWCOO3P{z}D=>LknL3om4xdbe8546nWb#7VSF}7|D9}%b
zk14X%-}1ebXv~is{7}uk7p;<>h;E}oC6=5Ri7qHSx{8&UpgQzwqu@wgj5E22XUM2n
zE`0LLUo&8i$im?jP~lLiAYP%OQt!?F=DJQbf{5q)>8qQvTX<)l<~Q6bZEm1L@n~T)
zCEIv~(`|v<XB?qk?t-^0PKiKSQj^L19}&Y;YBJ-a6l{D13uj$pS7ZJh-tP?Tr32J6
zHKyoaS|evtNlh3L?=3x}scG>s4ffSMD&^*+qOfwEQ5cEOW0cWKz?H6##tlH{2y*xE
z9K-sIE`Zo0#gz`rKIG>Bzn-<(mV{WJudc>lV|O*2I_V{N-es8Ena8MiJCwGRw)uFL
zJo4W1YGG{b!-u6rQSc42n$`skRpaLv71zO<J0E(t(G#nZpO-%(#4B1kelTGT3Pu6D
z#}F6Sw7*8@&jHhc{x@Cw*1I)e%?t&Gp=RsIWzA0t)br`+O5sb;Vi;U*E)izHsy+Ub
z-A2ZhmotlEcAwG@JXd-OR5bMEHX}OT9+S!CcjKbc9C@*^d&1wcC7QF>_Ti|+^CX6`
z(|KZ6+9CSf3CHmmm!TFI)ENikdp}U!eNS#fYquRWg^~F<=uX)~IgU%0d!jn4PnYnb
zY@TYqTVjS<>V?c{&b4PiMX1IsP&(NvT}qcgwYaAg{hKW+2NjaCn;wr&w{b0>#()yr
ze)TFMNOcgg^#OogPH+b@7GN$f@#VZDsC`#ZHQA=__O*<3L2<#?CHB$(MV!nLPyLTa
z20cHU>%}!M$ReAhWlIXi!!oB%byb)Vf2+apBiN>{Y;iTezA)!nC!2Rr=FkOoZy2X1
zgeo&dH5%8kH(8T=<ZkX~!H3pBGk(lcKK3x&a3<on)dxl<+_5P>1v<vcUK%jPI?Upe
zE~r%#o<!vVTV`+ENdbdW*g`1;{1S708SP6#X@ei#2%6iB&CR&C_w%TyPph3R4kQxy
zsoLt0NdWYegmPI;>Ad*N??_W$Q^6X@a2m+S;crHF$Libr%f7^M#te-WY3fQ9@6sLj
zXtc3vS<pHc>y)?xu#y3NAi@Y<n^!2t8L38YMt(rWka_{mySK<TQE_!wKV1tDN;lz;
zGGfkZB4I%YC+?CjOlVBRq@BK2+2{p?6s~ebcwfd^Xs%|HsxTFMlGpt(PEs)Jv<U<~
z*K<D}%EZ%qP0MI0eL&HKskfj(*>u;NzcRQi!a;5_<>FH$)HLCLElo~fWW<6Vpq<;5
zdG$bcd2>}s$IF(z*S#%ZQ#P2p(oGU^S^Q&47CD$<tpdN!jud5*0bCan;<LWhy|p!g
zL*q#$yOSDLOloKN?1O)W$^1a-?!^8Koimf3LfxaQe3AFgH1WzzrNzp-`K@#Mc$=y3
zo*nMnsWUx2GyOPml`;3>y}FM}ev=8DHy)&41st|VKJOSh&dja%ZW@sDtHb}e(P)=X
z<bY~EhFwLri_XnSmd_d8g1%9?DRPv3y?eMic=qDFIcciCe)gu>*MF<A0<yod_F+WJ
zL&M>%_f=+1=i7HO)k9WSfyK?8NADAwKHi@+f8OrUCQD(-QEIc#Id|!7o~B>9jlR8^
zyng>N5dTUff<A@!p`hPE<t@#GH^+tT+m7t{N5RL{OrD&Oj6?F3u^2{2yb0-2H?%7M
z9PzSfK3_%&Q)J!sTf<o<`+$_TsJI-s9fC|lDPR?*eW1+RD@MSrZ8+afrkm?1nI-gW
z=Yg@@9{Yqee7XHZPv~2o{=kGQqb6h(k_L)e3_&bOEPjceZlSA}Wy>t}emvbgrUCBu
z7%re1FXRGhCnMI8mCW*PWwTO8=Bk&Q-*Rvlr>7P})!mT_cqKI=N7vl+M@-AY)5M$J
zb#WQNVN1$jye!LA&Uxf69uGaWkm8}Z;}{Q)yfGkBj_}~eA6U&06eRX4$w*+NhRcx`
z4_1q|#gj3p-@=$-vH_6UBYB}XEK$@&Q<ctJauggyJ;RPM*RG#PqDW9~Kn+~%nAjQd
zRF~cD-Yn8|L!b2OTtT>;qnZEsGA_D3aibUhgd?oj|5eV|PB_K49?f{)Q#&|gM0>d|
z%PunZ(u%}As_-1au}E`my1o*=L~lR#>hBRzo8~taXQ*ZYypn`;#tBLj@!4bO_HUwi
zU_zq3yt0Lm!syHp7T7x;tw9ElUXRM>M4`>TYh2v8H_3JNr}^JCb*Eb1qoRN3{QhR7
zQ*i9s?$K-YB>#%2PJG_({kT$xi~j5nI?W36sj&U*1BA=B$-tv$4?nTFuJQ+uN`UG#
zs5(}B92J6y6d7l4Mu|>$g$3>APdKHv?6y_F)Y|pOjTfLzS8%2~?pJl1eOCL}Nd}Cd
z@8rerr|crikKAts(`YM(l(+flmK)p5kn;#-No6dKu*W{CmbI^`%eGHlAE4pOpxJXx
z_s(>`bmODjB(aY?rz*de$iXOKq|s#LAzP2CwmXpEt|lB!+P$6gEkHrs2@1=AZjlz;
zm2&N;X+Wh*{eXxu0fZd|!9qys4+65c=smU#_ip|T)sc7%yr-;;ZvcJO4`0z7aNyu_
zm_Pe|p&`3z)R*#g%ayz<qc(f{{gxMsnB+?9SyTT93(li(tR`GrwHEK^OY}5%mGH%|
zOTFXOr_6BL#lFnu8I3RxBT(MBN7srq9MA$-M`pO%4J=W5MZU<~M{T0qk5cf0i%{uC
zEuGL0luO#Ucf&B=Uwq4<1?=0s8GYG<mM)<Mek_wR`Hot-9FNLm>@#tn*K2x7w;UQQ
zS3?V+A2s<bBA9;jjbS{#%khbKb!A4DN8qj+S?lyXlBax$V=LNH0@uK}#0b@ld6eg)
zhs4dW6zStf&7lG7TJDnv6XY7>19SWF%2&izpJ4V;+~<%P$+`Uj;6d^17PdhbCLCH9
zYY4D}2YnIWGMIX_llIKJ682)O{yOd1Sp6~%<xL#g6yuUHR6XpTqe!X`F*DEgCkEGU
zMCSN62toel`t?3mTKk^KkVl(OmGLCm(E0XP!Y{r=t%PsLXg!5a`)YTz2|LEEk0n2&
z3PZ%jef?8)YRMnWtAAf7;@RlqG%n^jPo`NNrY4BBG%lt{Y%~bFWCmq1iLzt?S48ma
zYgGSuwaECZR1G)%IJCGa#kbHnv<0Ehia3_R(CQ3a*GN#ka<0-XY)~?Au=U<`Mu?9E
zK2$PG-I$u%OY0wDzDu?ULm{WIETWxqxC*z-q0t`tbn@!UKaWLBWLy%2<%>s%KuR?G
zw8T!+MgeWY;2Tt`{A!5|iV8Xp*;TQnB2#e=>cv#1WXnBt9ujRz)^QtJVpi+>sNuUN
zhC~K^%mY3%SZr4iIp@_6+L}q2%dqgJON6e;WosxbFQX$wXfLA{SE$wR;1r)yLlglZ
z^v@qWSNJgEyh}__E)y+Z2x~-IBnt#dr=cj&TK880wE8tZv(`?hvwXI@j7(l%iL41W
zma1Xvby)hKMBvsC@!6)@gB)9ywEbROys`c?;DFjS3{vDX;ssb_43xv7jFGX6Y<@=T
z8UnrXj(fq9(TsFomSN-WbIIs?#=)iV;!P5fvI;ccxw9nVn{=On+ZsTINSO~MRHII0
zuqSn0s~$8WF?s~UkAycVFrKtR={{3v!30plnjyI8YS4{}%8jt1D>+@JM@UBq!RSjr
zp{${(Ps~3(GeoSBZlP-dMXaGgIlr`ufYtFa@p;t}*lr1p{i2Ji<$FvfoGX-;5MYN$
zd*{X2Gjbo`aCDr)XwxGe$w{+ZOY{4c2ecVaMVtR7lb@K)KV&i+ko^z6%k$qHDC-k%
z`-=!>{$C{MKRHjG=w54o78J3|Yb56Uj~FFTd6>e5c|^GHzf_Pu3(1tE67_w1bXmDN
zthxj389isA(-Fed?_ijZn&r~Gh0BFcZNXREJ8t1m(%D@|3CF&@Uxnn&?;<Z|WPRz>
zUR&CpRfv@J;<YwcbNg~P1HS<6v*3jWA;D=3G`$4%s+q42g525j0Cgu+_~+)ABej#(
z;=v!Tr|@5=SKUii33hBAppSf)r;OG`DJ~w};^oaMT&W2($2Sj{xZ{;!FFo^nIA|zT
z78&8r%PQQ%PJ}#UF@-h1jn08Q1wFsi)o=lCAhEZzMKyS^4ZNa#vpLrsn?`lX;IN!h
zgU*zwAfo@Og87Dgi%P3|+J1ObXz^ncn8_dc!u;5LAS{}Ir`(in!YDchNpEJ~`Rc}X
z;Iek>>m^6@5q=wkD^g6yt%u!5LyaphD7en-mj4dduOR#tF9`SlCtR#gMEf7k`ZrVl
z#N~?`I~dxV**e<TKM~)*=zV#R6@;socqc0(Do-zJYz|U)Qh`wDf7gqHtjsLk0JOiW
z08e#vzbh?4U<g;v_P3?*Z#JKim4%H3z{mk)1F&-OutQjVcDBD*eJMwfrJ13SHQ3S^
z!1Ak|kb~iqEWpFY{j2zNeNSaZHg?WmfC$J|(%1}a3Q-Oq-TZ=79F48i0o=daKNTeZ
z6rN@X$wXr|z!PKtPX_-<viNUr{O-=l!10${p$gFmo;>vn6$UvN{}Mm`KhK!iJ2;A%
zg6#h|Ko;~@nU(Fg;PLP72K)-h@5Lf!4G{^<tib?g4Kr&YYX`GGz^{=t%#0jO9U!U*
zJL}Ud{`bKSWcjNe$PNVj=Nlr?K+r$u|J?&bap8K>jeZ|M&Oe{Ixc@aO5RzP6>`$5W
zzYie$lR5(#hxJeE-*#+V|LTJUzyX;$CnO`DuIEWvdD40y2;}`s>VZf$Hfq*pPr3=<
z=_d2fu>E%uKWR$8b5q95=*de@vXk=PqLI^+#Pkp4hV`GSl%l<jk&_`rtD!Xnnc3R_
zSeaNknIKc7HFb2fea#G!zaS{s9%O53X6V3VV-KeLo#-MEt<BNQ##;1AI-?bR&BnsU
z#=_0U&BDsb#>qy{!bZcwLif)>|E0VAk-|hkkj%FM{|fN0Df}gb{YztVwKq0FVgayn
zAhG=Y0zksT&IvF9{KkMRY+R7}JiP$ce_@b%$m;q}jDrnw3IApXDLe(~-!O<)2oc@>
z1LNU-3etbradAQ-@$VQ9D+}Z|#eZT?$?_i<C;NYo!3nuH{JR~Hg`FLeH2>BX$il%1
zNw7bdqdf?+w(WnZa4Kf*#!tR_x``><*g%5*<n!OlOUl{=65FT1|4JnXN07baFYf|b
PI3e076_uERIMV+Cz3Z>_

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..934d6ddc327f7f50022048264af1854d8fdccbdd
GIT binary patch
literal 67438
zcmV)xK$E{EP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-%+#yN?|<uTOD?&Y-W05~Zq|
z8VC#o$iQ~bf(!x&Hel>K=wy)O+h>bhYf<~YchBqJYc#t1iT7xiL{SpOKa2KtzW?W+
z?EQbNo#)qo{dxS$asFuIeD1Gb|Nnpfk6-`(|2V(?`~Q8|*Z=eW-~Z+PzyIU--~RXa
zADmzR=V9m9|N8YWUlu=^|M&fK?mzC+zQ#Cz^!NY&`Q`n`{r)i$USI#^>pva8?biE`
z{{HKCxAx=lM}+M5yOI81|NZMf{PS_=<nFK5el$O48}IJ(hqrOv_Vv#{kAMH){^|Uu
z_0fO+Z^ys;C;Kt}r+@w*$N&7#-!b5~1GV{MY_p5z_jB{-`7!;jP9*$Ax4Zqgwojq`
z7oFz#agVn30^u*Z`5jyr`$_o6*#G>vukQW*)nPxL>o@HG`^@*=e%QIs4urp$osA#%
zJX<#qzVG%HzfVyn;V-(~Mo~sL5dNau^c1XIfNcIv>F@LUF@7Wc=f6ezyI-H8Ou}Ex
zt)CyFjP_r2vi>Q`Bz)hkJ(HrG-AMS0Zuk3e8&(TI!auYG?|C)5?0$ds?mx~y-vM9e
z-(P?>`==<A@E5c5`6<dI{6)9-j{Xp368@r_wf&6D=J#Ff85FE!KMDWn4j8xhw`kdW
ztIprC|KG9$?7BZh8STHA-Ly|pCgCr-z5oA*D3kCP-P%o2MmG@tqMI2-3rhgP-`oLa
z{-gc*A@uccxC0*llw`EOpWAhP$}!sCcbexe#nJkUd#3+#&-Z`D+1MuJ3CGSXar%d)
z{=GY|-w6G`N$Gh$rT6()$nK^Gl3?E*RPPP3cvam*c;E2<=s7Un<Mi>qFTTe68ui~P
zB7ch|@BKcuVWRo%+}=l7e>1E)iSTVVd!L)@pQ~R{zVG;!gSFqcj-q_u(MKxZ)lrnc
zu?*&KEpWb1gXjBo_#3NWv;87wMfrY;*Yk^@73KSm&-_?;w!iJv-YU!I(ii3Xj_-5y
zbM1@rH&&v(&xro~<&OA!H)DJ2fS=-4l<y}wKc9#{zl!pG$2;`Ltse>BcYEH->iMx6
zqI}!2n}4i5+kayvx}87f-N)nKt;F9_5qq~^gsmvwPw)NM`xLgKeBbf?xcprCqI}=+
z{UrKa`J#N^@wq=&UWC817SH=zsjPgv7Ju*Re7`Y2g{>&xPI0|y{o@cW%J&`pi4ObK
zOUm~h=M3g;9Yy)R<K6d8(fS+f;O`UI{(4XREv4~!ei5{yd^@#e*!d7N5x(!%`!B0r
zl<zyfJAAHsQNHi^e(Qg(dQtw4>NMWB;rz=z@%MD6x0?EkpcUmWMEg?@{nRmEU%&qF
zzh=rY-G5pWU+<ipXS?4!EocAhl>fgq-|ZN0KhC?|>q332fMsg@cmJ>WV&}N;_WtU8
z>k8-k{CiuydHd&r`rbTkX(IUoi`E27mgO(r1{ZC4MR7c27UeD0N09Qd2hy98DhDX<
z|9VqCT839;P}ZB|O?k`g@e8R95Y|)UI^)Mb2sPX_jW(a?`uaL{lIv4T>spkw;1vZg
z>L9%TX%T9YF|I|bNxp^WO}XL=pOl*RSnch<=lT{W=<)EPMWiTW<4X@?OP=7MEZ)5-
zZ?+se#W%+Ec;R^rC@F0Op;#3JTDF2y7M$uo$OLoPdGzU|wBnNmpW4Q!H+zmCiBIpA
z6_27t{updYCmyUpiOIx%I!Icxc^?quN>Rv_{6HJGc#zMyMHxds6w5kpalvxM#wGc-
zT!J^nG@@97G1o`=L&5Pk$u*+j_?u!HQLu9i@y3#UV<eA2iV?Z^W5KsYA&<`7aifbz
zxdRqOJUWwYqlrf+c+|wB6Fh3%P$yWFt8jo612Rd@2^N`{whR*Q15GSD!JzX8fA&4}
zBM7Du2YZ|wb5WN3d2P%5<3%xzcm3B}&A+!^!JRh+-L4dhMM1agfuZq&lwNsyFG7EE
z>%B?q<iKko3BenmTnIeQ!d^M}!@&ukY`y2`v=%Nxu;ER?c3zbDFpX!660>%$$x=Yx
z-#ZqmakL>4FnJ^;C*9TS#-uwt-Iz1ZVvvI6jVqZ3!$rVCz6m)++5{IRr)aU1M-ZZk
zg}iP|^5l|SH<lKw|8B<=&#jBC6R-7W>k~8TTK(&e7MJkK>2w~*i?BY@?^?oG-bLXO
zrbD3ht2)JGI&E%?5}UhY-H#x}8ueQERALr|3xDNS?vt&xKz&q?Bbxm4iO~<X;^$m~
zlAl@>3d+n~*Zn{<2i~_XIq<%9$#HALzbT9HJ@@;Ol-N?eZM~B5x_Ga=Y8HjUm3RH3
zEa5tW60Fw6dku{D+&Xob>FaMgEcq#a$07wE+e5J($;x(DuV_(X9manh*l)_Uwq3i_
zBl)^0)hpQ7uB}(Fug$Gjo>6UX-Ewqu>z2cl_H%i(*n_@_nAZVPOu^NoV|c#x%HioQ
zzB-tfm+=8oaIbIOa(I2~7K_=MJ_hBi<(@y1ln#~J_0Wi#ZQXK2I`l6nA}tSn{7?v7
zJGX8*qI2t(43kC%4X@dwE9SxtZ;!g+^0sH|79+9}4BX3h*VJ(5+D&o7m2215D_CSD
z9Jo8*l!hY?7p0YO;9j&T@x~=+lb^z!XVTQJb)g+WsZPNSs|(?Lw{#gy+)JjDVd54t
z*Tp_l#d(v^N-p%ROEN*K_R?!(^gUbQ2Ah!2dCN1#KhImiq_4dR`9<k$^Tt<G6FQQV
zpS7)9eik0qHz680dgq17o;>7JZ+>&^eApvxVvB%lVdB6(AKoT-VzyH{!Awo<SS0*R
z{4+bu{O~CiZ{qwtB@`0}?s;h=Pn@r(q+;f|uqf3nr0b+qtdNJr-7}@)NYY~ODXD-a
zzbKH3Hzg;@-^dA;R1938r*y)ZLbNDkKb$&e*Q()QJiFFl84p+6@Wh&qNm8Mo`I=n>
zu7F32%<N#M&W_o+iU#iY_=vQ{+3^kC9&j8l3VG6_h4;+N^X&aM+9`QtnZj2VWkj0{
zNqOcsTXHO%u_Q%{oG^SsS|hwZ_FR%Hi%*0E9w7Aa80%>;Q!iQ;d9ve#6S;)sgr9k8
zemU>uXy*LV;8L#VMQI}l6q4LGZ^~+oC-ppg^l%ulixvTM9C^Mj3g$Q-FsXBn1M24@
z;fLd&!N>KQiVlryH*T;=uZnSF>`iCZxWOp?L5^JK$;k70Q8?BM3v3$emCrVNq-l-|
z!-uAcC)#Rrycuv|x3rLav;~EBg^{QFB7wJW${NR;lCAfDNm54M{fokpjeNn|Em6rA
z-J7DrVmP|#3K_W_7loho6s<Q2&9&tBz+N1VA06C_177uePyk2ncDv(q2S~yEn-7YS
z@Ao$$S`ELUb7Ej~-8v^m<G}Rv&o`sNCX<95ot_s1d+O%%a$rl{p#vNsg|Ogpo|O3E
z5(UE#mnfY0;gp0UNx6m;g%c}y^4q7}Yp<|IX9xv@NERjJ!7e>I9J}Mv&Ek3M*d>M3
z<Fd5(697Bc*PXN4ykH%&FGs)QWomdgEJ|KQcIntaFq5U`e}ELMx+E{2`s|yMt@nTF
z3F46ROTyy#sYQac;3;dD3`IUMHa$pvAi6|%jgOq1m3_|##-@YB!y2^+Bb)KxxfTjw
zX_5m^ZP=iTCMCxvQ<6KzrrSr6FQ!*6A|33~^W{y+vB}8f9ek6n;{Dyyx#BI}6pJ#@
z9?@!S=8B$Zg?K_$TNKDWbh9H#A)ZqTt><WLN}<J@dQm8)Cqi^?sac+y=ps>ea8*pH
zGd-_KE30GAt6<hEx37PfAoUx;K_N)}LTjLvL)XQEcd*T_o3KxeT{lIC*i79NJ$JMX
z9i<&JPV-y-5T-n|q41=%A**V8K$#mQMl>P>_6UOEPjbx~W;iBVv4Zbon*SPWICQ(V
zD{Xs*lRQap9uB9Jw0JNq!r&i73p~&8nMI&-)$+}5gC<tT%W_d5tSwc5MFEpqssM{(
zuoJfdPKvi}fRoxjcyQW~;?^8&Yt%a$wipJ3>*amk=6%yTc&1k%9-oUsKJ|FyEDGeY
zy|+@C0vqm<A=R!ma6vBtyhJUngE>P(l$kWXhP%VH%^G&ln=;UjHTQ=Pxdu(kAFW|N
z+pG+TE%hqDHNG=i7@Ivf>s;>#%WZ8g5j9*3E)m5ubx{V|!F#`?6TL|}e3={#Qs}w`
z3_H;$j|2-L^wdw5q#N!4myyDt^Q2YMCiq4z!l2u@tQIy?L>CFd`+lM3hX<F{1~{jy
z0`JyE8ED5+d%ac7@hx2xhBMr?2M|hY3Q=2>Sdvb2lOYPw;{j_BDVOSD4WE$?Y7L*!
z<za>mUDi%BOewoSQFmP&hO^eCis1FSC_J$6e0`Hv>wIE)B<$yd)se8Dlnm*p=MDAI
zPc%a=$~byLF1nl>XIL~BfximPx94?prUY4+nB$GQDEy5$8W#cQ!#Sgs=jA!lu4-M^
z%9*mTC|IZy_jretpJ~8aZAi_D3%XBT&}W`?R`%5s3ToFA>Fm*hFrHX&Trx?)=q8#u
zvZ3i3My6MGyhc}>v&BWz%lCrkr*(;VK0y~DhuZN1U6g@#h)CzLe{?)S7b!=(D7k(f
zt<)GhHKj#}^F+qoMakD{?-*`>pdrfMyD0fH$?DZk=F|S$pNT1^I+K)~AvemRB=5OV
z-jryyoF6WqPGeBdfWb931D6&l=ZA}<Kb}+My|D;6MblSs4unlP$A;Ucn?BWJhNr#*
zwT&VB{efMe)82S2Qp)+MFBz8X6sMq!$u#|@M2kE*apt#2>_2l+X{cU=m~-Q6q2H-v
zHD;?ULL3&UdK@6dtQ%Fle%}g|9%u)r+6{qPl-Sx07trx0K^R*8L<mCTK3(l#Q{!#a
z@d`Cr#1|#s0*$YdMQZswIm3IX6K6QUx2Y+nzO*QsB5s8?HATF0+r$)Ioj660mSMCV
z=V6<agu8?NLtpOTKev2`U*Fo$hj~i0fiE|8;+HKKZRq1rQrpnCp;k2KW2I+^-=gr_
z(7~JQ+oyWPr!PD>8?7<NBC%8B-{eZuKGQEsN9Vl5{br4~XQwZ1k+9kqrGuV=MafQ(
z=8F=d!vqgcOJBkPQg#9#5CdY3N@s^(C@A<DC<!g&Czh<j#bd2$G!DVikpursP)`00
zdr{~wW)S4Op@}w~LixH30)7LAjYiW#Pq)SqBo3yr7sq1i#j%(^g#$eUP!<7KM~4%^
z+Np(trrA!7CohwBa-rs<PH@mI5_@5-=EGhPSv(l6;W@ep?2}@1EK+uge}{3+bllB6
z2ZEAgoB5V88c6!Yg>7=mblAkrbSlCCz9<~r(6=zSl!(KO2Kz-quV_IU<k;zmQ3(o0
z2WhaIR+SFBvl;c7MPavrHalTyX+}2W&K*G-LBRH(O`Wg>X&AN}t@Zbp#%kDpc4@G9
zbeN9c$k&KAelk7bW~nyy@u&xU*^3lsgI$!ufvdyl!|dZ$H;k2*SGy#bw6&Vf?2)>o
z@sY6zapW2DJr*I3Njx1EpT=Y-%z+kCB%Q7{`+(acO;JI?6sS7TY4)Z>1A>8=mqo#u
zgV*$%lCAfD4YGdlnlN1fv~=3wOqf2TI|0EjW_<lD%Ib6kDF~)coQkOv<Qzsy8=MIC
zzsd2tNGXp)%X31wqKiKeEV}=CJY-iJ3zOEyBS|?!ztt&cnC3<~3_G5wLCLQ=-jFL$
z`~V@P#JP|Cf{^fX>W=khKtgw}x8qT^D7oVFT6gD)>;A%na#66N9={s@<y=3;wRDGO
zpzO--9cv+Nnf5*F<Ur^8Nq<(>SQitx?79;j=e+4wbmLLg#RkKQ>7sO)o(;Cl?%d3s
zV%)i%<yPyR+gZ11=XUPVy1`xDt%za?O0uHEq#UFiOo#u&;H~Q&k9})oMTdTG()c@E
zk&6Ug;FV;^j$G}KZkmpI=OMjQ2FAxTtMinmC%JbX(z@4s2e<eL@4bOrO*;oM=0U<N
z@W3<XSoeHun4Hv|)<sZ`B!P$V2PdSHkuHmp?As{O!Wy)P5=!UhA|*SEaw|g-tI}ZW
z`JgO|+oI$;L0LC>)O#8iKibJCDKBj*Hxlupod!jt$zo9q-zH@wqoncBcnHdoq-0cj
zY<qLDifu9q%ip*QcS=}&%%n=SCPoyc<zOHoP{ckd>3}pTU{Gu}ianfEZbI79HUe`-
zgHg2YD2+67U(US;Ej2~BwMNtyV0Ni-oR@fs;h$5iD+<R(&Ho(Y9vB1P|HjYLHNc{P
zc{#pL4Xp^|C6@Z^niDCl1TW>|Y!p14Rq*X^l1F382StLH{5-7$4@^I6!===pwcoHY
z&U0%u8dJ2n7DYlu(zf4%cZ)(!<u+avaEgRf*p563R+EQUo*s?HlZ`TUcIA=NBFhek
z(gDKfVb-3pA7-HNEDNz(1RiBQeU}a95}lh3E_)oVpzu0yObL!&QjQ?;I>=A8x(zUe
zR=0uY4^!Ep<Dfkd1>Gv`Id%GT5l%6Xi*Sm8;Q5{U&5>8!YU-ZM!O--fo3qjQVe}%k
zo9b(anW){^gS?R!q2nS4vu^6IyxQB%U76m<V-fn;^?^5K(-+!3q-B6nG<8t#coV3W
z<hWctz@&TAW-u^nGmh3gcjahN!kHoksv&Qpl&l8#Iu)@X7_=^O#K?IUOH68Eb~>dL
za>l2$LeBV<R+#3)Mk9vw(MB7Fl-71V>IFf_DC5+6+l6@DQj6O~Rfk5Hb|LtK>UF!Q
z=uiQFQ@)^}=g6q|qz>P%sSa4*Ykt);V5P6{?{hUXICXzbtn3xO1F(J<&*X_#%l8YG
z@8a@K9T6ATcycD4ov>K6Qt08-F0SyzT%Z}%>#Na7!53Ok*a;J&>N>SDC&glFY4|eb
z4C-Zy#hHAi@Y%U2*#}OZHXn7u3}(Gd2ikm>VgmD4pE!1o$dO?uEWo_f4GS>&P{|e^
zDYphY5vHOC{UV_U89oPlakNy3Zj5%Q3+}{~C4)XVB&Vwn2g?)s)?j;fdeG>!r{J`k
zFk#YGf-IV{rZ9`9EG|r<fmJ5QX4ovW-9$DG4L%s0sT&7}%Q;L$kz13N(o?*ofg5I~
zNUg~p9NwUTo5rd|3FVt6tyiShup4*>|9@G=7KPt}V8Ypdz{UnrhhYv3q@6;hx`v2=
zGUqkeDULGvHJU197i=_D$acsaoiZ;XM`!&|PAesX_Q_1op;Z&V0f~^EbEW5?6BiF|
zei=-Il7{1^u{8GLQ1Cv2ZT3h~_R`HcVA<9^$w(`if!i>38W|Q6IXo~pbG1%&!#RQ^
zo-#@^iARR(BS@o6+s(_g4PMZa0RwqULxv3K%@Gq)R`$jysiv#Np~%Tv-xv}li~dU2
zx#<Of;QCazfp#04=b$m>N#2FX>N(|sI6$HwgC8&72R~lE4}QD6A0s*Co3o_Ryn)wV
zQquRKQ`_nL&?)VW9;=HC$I&7GPGg*soIopy=Ng-zXc2O)F9r`rqR&ZJ6O(-8i$ao5
zd8?S^Lw{DJ_=L?*F0VyO?(6LAczelrwvu>q0q9<99jCEeaIM40t;4ZjU_U*14X)}%
z$y<>YllIUb{U&X`!N~CmpDF!^i;|v7IvH1D&o#;o+0v<eY_7^hN`JhLua0;eB+&$6
zY#z}@^GSM5b7=IQ8^1)~xsIhy-?<(x@c+_>dt?F-oVffJf}`aJZs?!B;vl4O$eX+f
zn58uM4&jhfIx>P{I67qd2{$!Y9}k6Isx$ns=^t;5?vnq!(dZ&4`<o&c{7MB%*_W5T
zHHJ{ok>42L)pbxbC>M$dXlZgewxEGX4;p)50keZL@L;tfK45C72;a)!g#)DIKBF5N
z4x);HXf(j|sR6@<o?HA#N{SSeDjdiaj=|KR3fWjWJ~<qOb+pEVLSY{b*HcA?L}t*r
zM~^V;rvgqQ=_eyFwAmWNC!}_?O!CaYmetDeCPuzAm~s4+9<SIc=?{vnlD1&DIh?Hw
z;xYZ|4OL!oJI(GbuBSm!&A6Y{$`9zx4wV_fLkCC*71EF7(klq*O+bKBB>Y6s4{XGZ
z4;6E53p{@+>Z#!gRgqDP!jLNnZ9e)Agjgj-0ay($;0n=dcv@E&SHl|~p<V|_`5C>H
zV4G0P*qeZGvX;i2iZ*M;W5M-+F+4UEwYGA6GU!Q<5!&Ar{T7))aZ~uE$x&h;@+b5R
z#o0B)TQL%EwGqw77uX4VkwW?wC6`A6e?lWwR3Nj35ILAX1nq<2g^MuHia%WKj%Y)U
z4hpKG7>|`16j7l}hK=N*Ef^B1LlrN{)S-&0jMSmn#0t7>CnG|o3ZIM!mEL>8h|l=W
z1{339_*q4Ra)OA_Q3&bE6v~KDS&L|N9Lh6p4CflM>#T4t1+*f!sA67QnjjSw8`(uU
zKiNS}n5h(AyC@l0>Y5+47e(ks&QYA`3gTtbQAPSj(vjba1zzoB+>-Z|P;?Il5+9&2
z`gowt*yH3$WEG7)VtG+Av=)MTD6Pl@Jz%s-Dn5GU-DGGvRsYDliO_85`G*p35RDyw
z#L#lr_ZeEABgPCP+IwZaghpH8;ENQ;J>$hA5vIb)SL(~y0?s2jCPsDB<F!aRbWP@F
zR5=yFMahx#$-F2Xk@GO!FH#7h;5wL7QvvspQxh@&Ct4ZrkC*Erq&y*>f2GSj_=_7e
zPL)mx0gEuUlmVmpui!`)DW-UthL0m$2?~o6Q&bYeqQp+Ul!9qMj6pg?P+&=7#srgd
zm`<_UW6QQMS`L+wVGNK`+J*sRrBXW#s3w*EVG5a2j)(!{qY_DwzOyBp7{aKoiN;`-
z$^k<1jv5eCc`Dz<09R2tF$OFO<jou)<;rSf-OwhLe`B;!Dn%!<e&S<_!?TN-J$zmm
zW3QADWPnttq#^z!a*B?m#P1;MXtgu5N`eL8f=XWE;48uDu#C@A3KW^3#3=)SK;>2$
zAOkA@D!996Xj!KJR~DBsUMupxj3!W~g)Kt-y)wrZg$ZX62F7kF1udj01_E7S5e72Y
z>_YNGWxW~0xRe>UC^_3(BZu0mq&v%8^JB}=<0eBQUsAS2KPCV%IWYF}`f#QX9w0?d
zWvvbDWXeM{7)>iz(U1$Cxr}k79L#kD0jZ7}785mficdrlE3a}<u2ET+h9vJw%v_Wl
zKJP^45><ldqU7*hXUk;5=0Gd6DtY@Y%GlCO<Gjwl=Z2b$FnnOcep9w|R-@fkDX)vd
z%vp#HExDCDYe?I!^jf2FS1GvbMoK<O4kn!7&s{S_OfwjX!(WNOi_*rHDQq+eE1TFR
zj5<g;PD&(cQwuXCX`fm|CTW`%F*Z=-Js)UCy1#OxO<CHyAe5y|9V>3_Qz_U-Qu0gM
z+S8E|uDz{1Z5r+@^0ajwOgy(MWqgq`9o)s4%+wzE@66IJQDK($&=m+1Hg(jOR25~w
zTN<@1M}84<emDS*AO&{9d5M(?Mx})OMMz#s>6ieLP-6cPP}XNc0Sx>}&hVCuS<LVe
z`+?gefPqB`)COV@EJA`doZ>$4mxN_tlZX)~I}tEKA)*#hfK4v{)s9cghrTF@R?)O-
zKsTamc&W00H<H8F5I&gj4y%=4Cj7&qj13^dGU@vOg2ZYrR?B^8h%_t|ilvd}H)(h^
z<beap;s7b3Drh~i0qh__Vo<deYK9G>MofmlhC=N3hQ48N4+x>dkS<;z9+p9kh4XQQ
z@*O{OSEnI!LAG-&(muzPoM4XTBE<Do$Rux)pi5q%^9LIQZ(<oJSqLbG<Z_^-93TzZ
zRI(i-k&6Opiv`HC2*DJAwjAqy(iBv^UN4C})6^x8FnI(l)6_QvnRxO9Hk*w5HVE6}
zTek$B@vU3Jy!h5DLEdC`U$3x4o*C-qVAfDK&mqpOQ;0!<@WlIW!|5^jSqjT1D5q_B
zKk;si0bYER8k{i&9JJn>Ilz(#U|F=12!QuIFs0fcc+azSN~oM?>y*$;yi5j;Qh_5K
z@iu;*4MEA^_aVsAB5W8;O!X|Brl7=$E-)uP%bU!)hH%#cg<6!c!A7li@UwS@l?5rr
z>u3dvly5x}M5@k*1`w$nII{Z-0Ly>`PzYHtLL`8e0T-YEwhR%s0O2}78U@sqrjF;{
zz`SVu5Z;#op{^jojv)C>+%Wu64*q5@9PdIOGeq|mI+=}=%%`z4EH>+7!Z{0y-vUB2
zL<AR9n!&jSIJE<$m=*xnY!E1~&H`K$GFZ}@BxJWENC^=qrE{DG54S8*F(V<!nG+L_
z(JG4)$XW!VqhYJS>db*fBs{w?hQ)WKHUQA?C}6xr$~jK9PTO$xU}7uiy+z0=E3n<1
zsCZg_-$DPvmKWckq1)hbEbu_s`;HA_FpPrnrDyAwtN3i)5)x4>?SPad;-TTIg^5V}
zW1%JnW$eg`2B-+YFCHK*R?sHLG~@ztG)%dG9v3AMBReA(vx_tU$Ned5n!&YNu#<+c
z@g~!m1$^SM;a3_!DhlH=DCdrYX>id3ERz(%X&xXXYoyybF!;(i2BR>*J3$G~+{6)E
zl$@wugd642aDrR&lziriLd4Pdp@{+*GXHE8@&}lHf;FXan^7D1p<p8MQHvl|J|pdk
zv1*X{f?);a*q~ZzST8i!pqxA6Yf%OzC$H3_kYj_iVau{DJD^YD(Nc0qxj4UAxiSrI
zlwwqZ(cT-QNZA;b__TL1DhbcVsKBSKjVZ#d;f9^B@PFy2D2U*oEZz}BcqbHF!s%9M
z#3UtJu_5)L(2R@XHAz7tA8bnTK`D#ERTky$^+|;gvNaHhr_bGU;|?hsH`b7Ey~0Hi
z+=eE9-<u?nvT<zj@P0OqfdEi5uEle13;|&igSDWK?P3554Plgw$2KttLfa-90`{~`
z4oJCoxy^`J`xM-#_SuM5?XnSJwk0@mY&}kIymr*{hduUedn`8Qvv0B3&(GL-m85;2
zMai6fo5eBlT>IeyO2@02=go6%hf6Tx-k23q_1qh?NJ(bBnSMo}wdrmMA$gwdFkb(*
z!nf-%CZ!JJ5UF1F5uDg7GQ3XXwV3_1?KEDqSuy8z8pqNtQr%YTD=V74Zmac^y^I~W
ziFz449O*KPRM*uVBO2Rvb;pRtc3s^uqOo09PmXAA*ZmnIn%nJeF`{d`-IGVxcDpaL
z@uHALHyCnnmw7Ve-Y)Ysw3VOGrGCUgzDQF83WnIZX)N7pH>Oq-Sq~as@M1GiKtJkc
zTeo0FnJCss$~*yFm998-Xk|x`E-H-{pROA(&XKO@Y$||VNnTVCS8)?533={!L@-m)
z?20_5GTIeKOog>G3i$X+r8X#~<>svCr)u1-o}g#6q(>*mdYL0q59|tWrHZ~Ne0H6f
z<E>{@D*DGF@f~$yj_i^%lqnMrimp&kK010k({_?Ci>??=K3%%PFZsObimc=ds5hZ`
z@|m<qA5W>?bP(gU)fL{z7uljjrz78ND>bP4#1bh6kx#$gwD$Qj?9KIzvb3BmQuWF?
zxOz3rL9PlsQ#*qE@Q&?iec0c*ku;?~IfJP_BQvkY{+#Zc@d0kUzF8j{7U9~u<sxjx
zhiH`zAx@7pJRBqizn@PdLjSNlgtUBE9ztSZc_@2Dm+1i}js9VHhz+nA9+J76@xdYT
zoAn`Y%1)#ZT4DNTd&q;gZ?=cEcUKM|T<I|P^xn5VSN=(L$<dYh!7)59lVQG57Kz;k
zhNovJ%vimbd2(QUbv36!Oj(mJ8O<WIQr%*RbNg1TZol;08Z+}X&)s;}dz}Vx*hJdr
zNrPXG<=#4tBM8+ene}X)VkFPjCz++^&bT5&mHf`Ty?aSRoMDTg4ml8)G_2QJciVb|
zornpvNm}FZR$YQ2UZQ{tbF)U^dh`;8WX7UUz;PLtNdm9Gl_<=OgqzJvPlIiGk+}bo
zi7OqM-5zj)heO^;P7VEll|0g%c{n`5iK!kT7%qhycKGhs)+1F1q+Gvb(PvinOIH70
zrVDrmdYLZ5chCcClD>re__OuNkIR1zFGcrX92p&^q2mQ-M^M-)@BTh?U4+M^4|-4H
zvqKuf1gcgaa$dtP!#`;Fs5HEE?esEW;Ju7w{R5<s^+9`8KA^i|hUjPNL$U#1RL98_
zekB~DiV>n$s}IRWJiHe)0X;%EF%b?V$Jruq#XRs1$`==sTqX~A=Kz}Uk^>LG3I|9z
zLz%DO3G5X$1aDy<^fx9ab!f!X{s;<rKky-)8hGsY!Fwb<n|<gS!SlZlg+$Xs+NU)B
zbfR`t9;KI+SQjsOVF8E{I|#noMIvMJ%v=;O1_x3ZQQ#Ktvq{AGBAD`c!NJ^TM=QT0
zoA!)<lc?aRnY|_m#k))@;Rk1>Yx>CpoMiAv;!v3-C<qPgQ;!FD<ojeS1f2GLPR$QW
z>XflFUH`qx05LqEPhBwxAplIv3z1B{BCrsY&}TVA5xLN(PLVWu^hq>ChD0n11_L9=
zqA(U^X<iDYLeK@#ZC;GbNCce0=#4m}FNy-=IgUj_kO(xMOAC+s2K~~)N37Fob0ny}
zed)?TIR=6OB_)4F5Bms52|OW1u*A}`T-BkVmVU|jiNKeBF)${i{gUc{*qJ~;+GA^u
zgh|4ea?e~m1p-iMVJ~sU6C;uF3}HTtLJvDaf%>IKV+0E&4%AE0M4h#t8F19ET4hA#
z^{bW{^8bg}rhZlY3@%N@Hl>Lm!LRlxs($Mwfl#Y{>w-WyR==e{+@~rmz8JuD1U8o`
zrYqQe%ff?DuzvGViD)sRfV~u7bp%w{Nm9tdt&<=k(^i{7XZh5)B^-!sTNK8rAp9**
z%rHLOSNA|Gr%W3V!t54-(QX|l#jPtO;`IV^jnQr)?6*z@1pM_|HX&FB0p_*`4ifS0
zrRc&%A@6X}+_VxQNU`7ftAk^spB#~ny-b1;3rVE97el=WX7^G&Wgy<+ZIv;XLE`vv
zXH<k1=GGtiQ4kciDB?dhKv@zIB)TXJmxMj&q0)+2(?!UKD8f;@42uX^U3h_%ptu1l
zkn4UDU~mtKJraZvv&J!9Mnp^`zzuUk2)tboiA4z>^+(qRLd61|@gXJ0uNwfNzzgLu
zr-*3bV*y)Uq^wR}<~4*J`>DN!&}6T0BLqq<5Kgij5zc|si9x54gm9h}B^{8TPRayj
zGWI?nnSm3ksO{{ggakxw2jJ*OWVctG5yQV-Ryo9o2Z|{pyVqNNwY&b}8Uj9z*!vz$
z1i$Aw;pg>LVeAV>weg>mncPT>hF=u8q!~-)vgk3S-W8O@sCz#v|6qUzm0yhTeFx@<
zV*CR@mh&6n!J`?*1rwOFsn2IJfirXo$p#))K_(*vV6D;<f(54h-4hoNp>Heg!A-es
znA?KS<r?PPT$V%RSRBIGtwanrr5}V!>Iumai5y<I8A$bTYZOangLr{gz`*GROo6l#
zFO&(4+fAkMn4jW6gFp&Pv@a5ZZ%S~rmdM5UEDBqA;VU4A#tTmYWAegEKr+rkQfA5v
zlEPg;2j*Fu7a#KE(9rZ8pP8DT<1@3SmwU^J9{?P)K!Qfj4unfa&6T|5c4>l{?64?U
zPozXG3RrYuGD^KcR@FkW=FcFBn^4!v&5A$5@7$P?Qa_R2<&`Lp|8mpy!d$XNLO0}^
zEj({@Lq3{U!g_-&WOP>kP=*Y8WtGFiNqF&>GUU8c$bo7epyW6UkZR|ZF&@z9iEf^2
zg(#~<$z;5gC|C0L(O}|qg>f-i&?{{l35APNX^QbBM<XWZtr94)daV*Dv3v^ZVm_p|
z%A$<5J_1P|Gs1n+bb2Gxa#7lrjTr<E_aTNolRa~tDy0(FO`B-t8Y!m|8KYh~)IEZ(
z9adT<ovt>9j>J@#<rdki0ou<z+1%t!6`q&_>y<N&JXx=tY2?y+<3{LQ_lt1|46a&L
z1(+z?F-7KKBC|IN5#UpfS;7K%AVYW&E+!1;Dhgo&S;oF)NspYA@-#cJ-F-`no)Bjx
zMNh1m&>{L2br;B~JO;eekjT7h-?F6h9PlkmI_BzKxDT*xvc$vjQku7KY0~+Gj?xh5
zme-qi?Z*ynq(i%7$kie+jeb2^R+~xm5Ro1~fTZ?S%p5Z2$YOK_(;+*a1<zkfp!Z6e
zMv}cNY1(lv^vZ@qvc7jdRhZDfC`1Y9U?)AC3lw0r@<)NE@0COiSOFJ^I3uvU7brvO
z@!pk0=TNA;3rz?>2VSYw>9}`hSHlnPy?_~}x-fwopbOrA1!h=PK=^U!5xsyJZuF{D
z)Bu54gn<^j@Y}cvIulbP_mZ_nUJTMYq96%zLns_dS%sU;W#uRA#iD#*W8@DJ$;8x+
z*ccEIoic#oa5)Ev)p58m@qy>D2mn^;=%m{gxsuLQ@ATQA5=-KSIHZcl5S%Sux!>tZ
z@g97Ehh!Ccfy58wB)f9Mfr7FK9LH3zfp&gGnX^cG^iI<>L0O`t41NWQL4VN79y+t&
z9Ps{Vfo_gXP&lyjyFxIDHRGL@Oybcj3Ks~~JG^qzVSo=x%1naaL?IoB48U<*p_~BF
zIf4YR9#b!(^_Y6)U*No`Ty|KxgMvFJ4clJX?J#4r_RovZL90FxTG2uJ%5)Bm$Pxf2
zVu_&_@r&GPi6zF7yHpyWAVsAjT-7iGyFyO^uoM)?cVaNH2+~UsO^ad~PDdOkr-O)4
zPf<t-Ka4kp>$HX0(krHwuu_Xeq@zdOavKCV)oOCUxGG#Q78i=lxa&X;V`>zI%4LEn
zlVze_0@HFA&;{_ef<g?k)ch7H#)4|7E{7J8y}XkCf&R59=`sgEm=_8FAjDi=Fyf54
zhrX9EWGs&LB1+kjBz(r%gD_;c99-u<OqxN#XHwrfT=BkyS##HIa9z;?<`@(OFMK%c
z_JkxzHetK_4iJ~3r-xBmGZ%pqcpz1IdmJx8&$%Lv2~X!LV?zkLpyZ@rTy!}84kF=s
zp&tM%&lRssKs^^8!p)`C%j^cG6U(K&gx%-P_{zlhiyCW~=gqa%dk$8<!{v8m5TH9T
z<N!73uKVjAs^#_)RH0{J+yN51<WEejlx{abBzl2107lUnhJ6TY(VbS5v?_YxIv|PD
zT~EuK8(DYajj-!gvF;^gNG~XeJ9n{e%$vJdFI2!yx|jA2OiFj&tAMTa!jnk*pt~+w
zR045VR2=~^T`pUKW;#(Q0ITV)N5RvxU|)_lVK@)f@OufY(+ju)fS#X}j^P4!GtcOQ
z)d62Z6Lput35cU!5Ewuu{iNKvkr{$Zyi=FcnV6`bl;oduhQw8Mzl-V6>0N+(z-M)*
zTJhk)=R)8^DkdpM0>Qeg<OzUcKPeOA&5caJS(lR>ptQ#?q#NHJUxjVEw{t$9@VL%+
z{=(38p@k4<_me_S5g^yeDa4c$&)1z8g2ep&q>wQ{%$;IHUJt|<b|o<ogZPtj<;QPu
z@7A<PfjQe<Wfy2V`=D?sQ<4^}@<&Uf!{H8K=IuAysb#{an~9-CAwzG-Ljpx_a{`uh
zu?E0)9|SUw7~0N_xRb~}tQ4S^J}G1<);BS<kDW3#Ey8M3HQFg3!bh9SY9C+3{NAJ$
z0b@Hw8xB(6YQN>qI0!(#ZI<@yjsueUPU*G9kWff~^db>Jy-on4tk)?4AoiWm@N&{=
zLqK=OZ?s>IETY1HQU;H?<Ex<L>ntSPyepE1nDjb930u!Y_7Jpv9lMMNtHYY{V0EH1
z984$vA*6j?3WVa<O+vi>?Y1GNe_cqx{Xgo`VqJi`>R3CVu0s|Ws0))t2#&l_S)`yY
zVHPr|i<;FAbd@un%b9QTVnkP|1dQk^wSlD;P+T@BUD`(;S+s5lAc|ETN@Zc?hf-;}
zmy(m5@n!OpR>aa0r8=?vM5$LSQBfLLr%F_68cJQ1D#vOV()Jj=g}S$(P-(<tiG?>x
zkId2>R5V$+qg2sOV}{h#C;*aUBNHBV!j>GTG*2*MQ14O2ssU`aQn695#DxsTk|w39
zv+Rkqd4_Dc%b~}ht$Gn4Xe%h$sn^2-U+VR+7%i*GxZVkzgzKGv)f_S0{4e~q>Vymc
zVAU&$^=I^uVu6}^Yatw~o@1<Y6O;o4_Tk_!_Q8q_>bG4hLjATAs*ja<>WRtfJ@pP{
zg`aw>vJ4O(vxf==)q^(!u=FNY09L)58Gu!9Yg8~gzW5}6smxJ5+p`c-z3W*ksowsq
zr{rN5Weuj3Jk<r5UA;I!S1%6G)eB}n)_{@)gC(NM%E3BPX#`=JsWOtF6jd5%Ake5+
z1#1f^><018fGV17SQraNodYEH!Pstg;m~e%A~R{$eh6`aGG1keVx_M#R<Rsd8MF{~
zRW>h#UG0W3Rvs(s8LE?&fsF;s(g4Q-XE4xZ^|CzYnE~Btr;weGwbW<{M6tCp6(R&{
zGbgfMTbUeL)GbYtEc#X!OBRMpqh<~aa-djhR+yt{lr`wec*;6;vacRl$*v5rEOu8`
zS{B4BOKz6TD^o9u>h1Pml-}En#u=1VW@VP|E7LPe{J}hZfRtus-AJ@!(8|qXf@KJ2
z!9kkJ50oTyrQEY@VcFYR+OTZ$sD4;xdlX1KXxs;>!`#nr)5(D&|E7n-^=*1MoDW45
zb=<rWtLS5SD_9h=JQ^$;SzZs6mOSJcVfo4Oo3KP>`BqrQvivV7bh-IxPz|&EI4qc1
zt{#S1l{+ZQZkE63U{%iYDzS8DdYxF>v%FFasVct}VyX`Lwpc{8ykDp@S`IRnA}uEx
ztChmjc7T+Nro-^DukzNdz^G*9UN@EQy4=u@k^MU8o;*0VLaMknwqmNdHsq3Iq1U6_
zmaGO_u1!{qmG=`hW#t}K)mgYu50LuU+^j5LTb|fe-IlJ}m#W{&n~MUu$L8^672Wa*
zv(m0B3n**xmT#HWdf|W0u|XE(r0z({q#L_uVc>Fevu<#?!c|;2edVk^T)uSHCw4)Z
zql9t!<5A`KD4#t`A(va<foWB)|16(e!2v9=i~xe;tEw<plmW^#Z;=Qr<(#1kEc{%N
z3@8qLY~c=!Im=4(Us+{(Y!MQyLS11Lj4q2ni{nextb>rd)fr!<=!{kVx`H=Q9UB22
zUn-z|Y*8SrvR#oPEW=&VB&_CLK`1KsU6CrR30~1GuJ9+`^Q<#oVKFF1er&Nb4BJw8
zjb}Bh3cz7JRz>NcFghc7f?cS2q-Y-&Sa$&~u?TyG2(d^z!-x(Qa<4EW)_P}X605<x
z%Aqi%sv?|FR{q$+pjdgnBBfZJUV&6BU|+#j{KcapvK%#6Dr(D7P^BWf9K}*9{L4`a
z<*4|u;7i4iIZBu?z-%!)qm{a*39+aefsRV170l*Fv5;UZ5{kEw12EgGeBL7E(!`In
zvqJ7Xi+NN~9wMQ($USdBwyE&Gkmhp_0i?uNn4qJWM#U0hFCAOJp#!}t0}@xu5zvUy
zHN`w~cwO<1$BRcm#YB2z*d}d>-Wa#3I`<8hb_QS`I-x2`GY+<MkK}ZKTOr&tD2&^L
zXCRNzjN62+$#XZOO1&{;b8?1LQLCIGpb9E*b&(Lb%2{4p<f~_i2Smq$Fc?33fRH@U
zdCtHs1>(l7c^ad2LAgOe&NVOS3j2*)eC(mYyy+1?yeP;uMU3$QQU<{?zBAO9U=&}R
zPSYaenW+#n<T-WkjHaIIG!YBVTa{0R3a^d_Mg&vCWRj1RBxzIkJ&=37omPaqV!gdH
z)|&z0>$R6@Ns1VcXJrhJuWG(e6?V=CEd$f(qR+_n1C)90(d~SKR|Gtt?Ff?xCBxZI
zEuKg2vZC!_R;Yk{_s)p@Y$;$Lb9O|8SL8p9DU};Qqm0rAXu-+!0vdfX```d25>1q$
zKoeADF}M$@;L&2P1P4Aiu&L1xrAu)1kRIh+&{9~58L&SdmApYSX6AM{ayu*cW7$`c
z9Fi^Y%ys3#R#-_UG%Qyd3T@bxszU2IpHfGX#+CyEKS!m>&<|6&H15pMF@5Rb1a-c9
zrRY#dnW6*mN?&*f$og@lh9WQM04aV!$wLm5t4c8Pv^Od%$q_rnv?U*iGKoiY&IcHA
zmFeWn>A(2;cjWLZW6Bv`RcTcY5Ip5wIkWFCzSEug_R7`r!R)h9)6DcU9kYY!XZfR!
zu}L(B=h&n<3?va%^4TI~-k79=`Rz(!^TBL0-TGsYSxxgE=%%A)rJOUp&Y4cG6g+44
z_$3%h2O?MH@-0e;6x02D0O(~(F&#+0L4x3sq}VgFRv$@e$~1JQgii?sB%axcN02i0
zQ@1iqtCi>INOh&5E-9JjNOO;mJ$2Ftb24>&Ftb}Jn2QoAn1h3ZuvcoQPiA1!?!G8(
zY$>9PkfTkz$ZBUUrK}*%EbXZam08+KS9KV0E1h*wk}(~vv1h|Nv$B;k>!?{@X|+C)
z#im?bpFq^Ej9m{KaOLzmKEbSChfTQBg8e<BEpOPBZ!HB*`PN83cBEVD#WIoSrX1$O
zVMMM(XIF}~bg_whMd{NXT&GDt+qr3&h3!hP);XXAYuy@H-b(gflu$pJ5bnycE=gdH
zb%_F!tX+J-Z8SDnn8;TzSwPO*C|Q7d!#sG0O`C3)BT31@w)IK|N;8?)7exa*TKW1u
zQOU8g`W*p#9b<<^B}@PZxLe@{ICf|!IL;#7g+1WR!4^Ehq9ojd^bH&ZogV!~2xCA2
zA$Xo2g_YniwHKa(&u7D1a6||Kl;Hp=zdWl8zKmxnleFb+bkv#<K*SNGgqeU`T;~Qb
z;mp_;2!-dN3ZM!Q;{9G|7LKF15HFmG-SS%bMWhGH1Uvvop=&sB><fXz5y2>sjzvf=
z*w!hzpb{4j&w<cD79sf{?exM~BcF-`HLp8SX#4^Qgm6h5v5|#c;>;r#yvd@(cnE=#
zKa}_^_tq^2Bq)_d3H}Ie#gTq4M3(hKNT(!bOHgt|x;dDUE{lIqp1a^-@`rLnW9ycP
zF=Oi%I4xuQRwBmG@P7E^LbO?b03}+eH+~UsM>Yo(_9*b2MM;IDOEjQt3xa1+a&&F$
z6{Bm_CkJP;2gScjsk{J0(IpfF+mU_XBG}HkbxL8UIeAgW243XQv<l#8QLa%CNDg1m
z29vZ%2?V7F$%SK8SW6Bquke^0nfb8s9!Uvi%B1Vi77P5zQND!WP^+B-mU-5h(l3bX
zMM*HIp-#bF;Z*r`Z8%nb0dl;+t{l#(Ld05>gx=~~w;X@pdZjQ3eQS|&0&sIILV|A*
z!fR22<!$Se<EPix2{51<tA5=ZnwTTLw-Co1j<P}}Ta-X9iR!bfmDp%{P#_|>pwB!W
z4hf9r#3~?g+7YBgMyq2WZwjkZfQWZ`O<aVxqxB{s4~`A(%`ZaS$zp?0WC6wn;dwSp
zxkYJ%uyY3}u|8H8L_yq9R03ZJ_;%46MhHAmQlqh2b^_ehvIF0)7M=KZT6E&usk+@F
z#V!)EpWlEf67rwJ2U+NVLGgQs5cI5!Q!s;zkV|`Ry^<3rTWc_aGF+4;8Om}F!WxPo
z5f>#kUfK8v5OLB9apwp&uti6pcL6dwQ6vP~7?c=}HvMe`e#{BtVl8tV{Hz5b>4+aM
zn8`(1Y&iu7>%^uIUZvxOUYM2+e{JDjdg50I8S@B23`d$C-u{KL=_o5yIGhgH3qf@*
zLSh^V&=aH$^wSXpU%;Ra%fq4!v=dwODSovLYLqSV38?XcD_xYt9;M$Q!8eYAJtb*_
zMs=7(3O?1dZc+iPilE}Xi<028x}|TR-V@BV2y%kK7Y<O^T*wAoS?O@1=#76jV9kz?
zmT9nYN)&!ANE^nj17)OeaEoHat9X$Yo-Rp+x$E%V7cTEk=^E}rqh(#V4~jSwV6?&r
z-YG+03URq_!f_Sp+U6b-B-G-aQWFiSVu7inDAJDZz9A=Pi>A^4^7WsNwa?G@ufC^v
zwecpuPq*{B{e8H8{pbJq^)Fxcb-w>6|L=eO`ToLyXy%drGhbO})^MOH0#N5ltEUOo
zkR|g%)~(+}&HE}x{HhhqfGAW#Y8A+eg1xQNWzkusFySh$+?`ff4ye}=W!B?EEH_1z
z%LFV5+mAg}og|D_t-xhjL!t1|k;vD#3Pm};qZ`4LA6gf_05Ef!LJD44dnVi-N~~^=
zoQ2H&gq5t4Q`g0k(PW%cM_39Cco}LH&W52pEEf`h&I|&y-nt9~7I$qrRcextE^X8W
zYY!hODN8=?yZKv&ygv&#;rwx(_Ppo*r=kR?rG{cyKlNg&dI({zTNEn?M4p+3W9pS&
z-ZdJdJ!6^NLnOK)U|}DzrYOUf73VFO{;<NTg%AN=ajWbenyo1a%JLizJjaxUEb144
zKLn_PHLdOVxv?+ChT$D2_ANvz!K~t)av1RN`>67Nc>Uc<q7f2_N>oo}p;vMr!h03C
z14q7M!abvm8L<UVAfwjc$wOE``mV|iRi;Y^*4o2I)rm(SPhQLi1;mb&oj;L|@vC$|
z4`?c$_M48kE+>i=!KBY`JI?z<`hMnv??WDc^F@knQ%6$nZ#%O54W#?0EU+c-zv;+r
zajN5#uzlAN<+{0hex?s?-%r2mh;4U0?5K@6zU|0z&bc{%%4e?K`kQXt(;eMJc)sb@
z@A0woe`c`O$64^3jyy6tJBspr+Y#~EJXwB*5%}}0`AtV0NeFHExgApD+m7wz$@Mdy
z*gD33^XE9|M*Mj;+HcpZvC!=MB>c&YJ)Dbw-T~^7y)}lPQkE><uYcYF=)yc*e=1|V
z&fDK~<grYtFUq%4A9cNSdjHHCRoiL)n@)M;YmjI^-*vK##pAv3Gl0H6E{flD!*$~5
zMuI#Jf8GstI9xibAGRkczwOA|s;MI>_qQFlW2P;EGPqWB$^E8V9c$T5gy*|%tRj&Y
z=1-xF>jwQzH`ZRd(M=bxf7`8p+{Qnpz198v+hOLPO?3oC@eaQo=yu!xEZ}Wk|G(iT
zm4uVs3Y`6$ZgkW^llWO^w$d$r(~&BOt0O4${I(+kxT&f9RCV0aUH-hIR2)}FP@eO<
zj_vea6Z)weQmWB!x<P@;fUBRIMm4_c*87K=^)mo?J{7OubezIUVn=Fh{o9U{c{tp-
z?dl(t-*vpsLI6QWf_r>>R4f}yX^B6>{IqM0zv(oYRE1929_M$R`YrwQ=W_jQ+UTEm
zaAPP=bg&56_^tzrmP4ogsc;D?xxeW~Rd}!)v$X7+ZjMZ6Sd4#0xZelt*>Ad~o^21i
zQSlz%cI$0d#-X3>+WGGl!sliX`A;eJetx%B4i_&q{hyn2p1S{UI`WAy*pZaWzU@fI
z9bOVY<6Zjsw)jm)K0%r~l5&6Bk#=3YRMrb*eo%hfvCCM;j(qg=kN5I(t_Sn`nfyMR
zuX{b5huf+Z|F3;7lfwK_It&)2oDNCp<>JfAd5?TyXe)pUp-0O)MhiSC3W2z88Xy&F
z2X98Z>Dxxp_jW(q_>#hh5uGAOyLSgg*qH9kLlG@`C!*EpsY#QUiYD(QP6%cF?(#kr
zg+G%PxXt^Nrr&n&E~vES?H;JG|1oz*1O_|<=B3?bh1p14BUB5#6}f`Iu68SOr6_2n
zY4ldK0(@BQHt{ja3Et(9PTzmK%lC--f;aK&M7hfQh>C+(c^^@6@On00EeW~=Q?OCU
zhLE4@-WV0aa$Uu#5RFU5sS8B`T7|ITzuGm6Q^MnU$%#nJ9#CTVs>e*vBe8#yvR3UX
zH#5qWT@`KsT@-F@xJHBHSKnNtBcY2loaAN`r=UPzOm#Zob8VLbkS><yQ=Iw5N_-4N
zyjXSb+&Y0-XY~r0Co&2Ei$HY0b@VD24PN6ng{?CS4I-%-Zss;?XJ#<zQbWi&lun+t
zJ5djQDmXd(*=^3vpB-{I=jP82K23QJQCfM{hRu==ZH}!|uxXa(5M|{n@(ghGjge<q
z@-{1!8(#f3%XbK~&n(|zmSdjfJ9IFD8OaXWA(C1CO^8Run*Gtf2{BMn*yD?VBvm=q
zQF@@N%QE^z1!x(e(wypJT$sUA?^~~6YQ@K(3h+mGObD9tsB!NeTT$H=RufG0x*kvl
z7^Qg`iPMy&>?yg;E6DQttO3jjpQ;k<5bmlZjKH8OH+&>%eM)8;M~zFBEoQ_~RW@D`
zNvp+3Da7fiJTfDgs)Dj-Es83#><II0N`!UfEu&U51FCWc6Rp_$s`c!d`&{Lq8I+av
zqMd~_s-W~TQU>oU{)J}Cihs#au%`4-p8(sb;?|DT>?(iFAhRlw?WhG(WwbpryxSH4
zgYdPg$L*+Qs&d_q!=fsBGbWB@zmFsZJ1go1fvi<f-0}En3VVTnNM*^7jN*It+T{+|
zy{d1%V*XkyhX*Uw%ljS3eaBWv-Qm}%V(Sbyta9uTk@(zO&32zao{qZiAAyWj`<=m#
zO*x0CI@2n{5QpGVh2|r$^2t9^uQ(%G-+IM*s;GSgY>vjl_XkKhp0;&McIgC|tXI!C
zsL68m>E%9>l;g3jR}RRk*AUS3OM$Abom-bU;@eqWVl4J--l-UiDLM`@v9csFZnoK7
zLfYYwytiJ#9J{Mmh*CwxAY`{8D&}~}Hx_{23IvXW&lDRs;qNuY#!dK|k;-?x5Kp|o
z#;a4B!*nrZEvP^!*O!tPIb2qfw>lYcm6(!D5&pcO)3X&4YYL-)*;QccNs7-(HAQKx
zrXU%FWj9r}WaxH7Ze#?k|G{lHAoy0%{1AMT_JneA0T7SvoF(N5BA<UVF&+fsL(EOl
zny6>DC`?coc&iwN5dq1q()3`*59IvhIAWAr#^V4+b~%Ir0_2;Ecraxlm{n<b2w`3j
z|8SAT!=S0=K{$b8MyKv0lrIb;)XATTDXHc{_<7gbo^*z-ABwsLWH{uo66yxz@YDen
zMI2Z8gi0%ko2yj{9co1`N@IRXaIVth5HQV}4@nu(X7m#Rs9S~bpp0e|o505{TI9ir
z&nWaGOMD(EXOV=F<u07Q>|~PE5_q>4g*-T;^`1&(5<TEiWt8Do*9)H}rA1*%(u41u
zXoWvCYJ+^_A4LHX<R8WIF9LJ0@+7i{asePS%OIcwq&9+r2?93E9))WnUy3D9k`g|o
zN(}_2mQ@fC5VRJBsZZ%edYI+`!@E_gAmO3xQS26qT`!+U<&ot8p=~23+$sbJn(r#w
z!a&u`Sql<bK62uf1O^}C6KNiRYKr185A)<=Pc9NUzJ_2G6a*M8E0YEwmKLQl_C^f<
z)C&lR<W@02@DkWVs0XAEt{9R^IgH=Q$~Y-$dB9u61p#uX94^dwv|CCi)MvXZaU9|0
zQ4a_MI`K8Wo&1y!h*F&ju)#a}It0KI-rEOxo+&xE7PyC-tjr&s&LycKox*=p4}sOu
zD(0x)_+6=^0hMF7cK&Bb$H7i9V!fT9yrVKz5<>iLy_*r&ZU{3xUI5I=s#y5e1#W4B
z10Tn3Eiv$L456OLuZ?M4G;Klcw+j(|J-mY#p@vp_$?&DnOyb(uCDT{O_PB&WfXH|&
zGYO2FcIhri*qS5Doq;#0q1i>FSWh?Pb)hj-Q!U%EjMuCz<g|!drTxM0X{zJqh^Dv7
z`|BNJs|4%LK(7*_hOw0x<$k$JirSBCWAG4zHwDcco9+(4#4HL|-Y_=B4gwX%E@9a)
zvDzwq5HAv|>_LFQ*rkI5(P(y=Ualy+VV6#herCzQoM4uZcoWbVQH2nB?$|@u2>_1v
zV0wiGkWUvY(+z5g*whgN*cO`=P})*YwJG^Rm{-(vd`JlvOvx8Q^igjze<;rln>u1z
zzBa53Hi*HuDg88GB8$L0U5lA3TrNBs@hdtx0nZWjVe?BUj1$FcV}OUFdJb#ez63>4
zp@RWeu^2R@9~pMipx8$wO0a$qVk3u&lEbe*#*q=NqI$sUx^=nqo1D{?b&oOUyjX{x
zdx7s^qjrqp79H9#cotYC&EZ*KLpm2K7on2$0g~a5AV>(HXW8nP;5-mjlY|_9#w!K{
zNHV1WIXal2H$en9M(J)0FYHNHX?BKswH0AWR20@8e+fB-70Z*7Gf-%~Vbf)~^d#g2
zsK}dP0t)2Kp!+XYe1C=CEf(Qa_LiMLl0b>VjvfU(lTkU#MPI-(u?WoEI~<C?IqrZn
z)jM-V=%2XRDwXeyyH5zeerCRhDN-z8HR3y4;9W3E|C}Gug>X)ML`5)&qG3W<1!|88
zJk?P&%>+J9;2#6-=^=0+6ND*&GfZft#27N6jV20_2}U&iphr-M7}POEogRqfH!q;2
zjxX&%OL3H&pfDFHf2ePNls}}~;=}>2Dh7T63c_Uf><HaAr%t&j$-)K<DjeKSV^|Mf
zDH?KtR3-aNKMIw_jTl-uU<w2hl?e^H-$BGID||;_YMBxXiMwS5==eZiSE}Jb0Ix+N
zIM<98fw{Qa1zCpGR)|wiUH=FYgS4^S{Q+ALU0s-psoH0BG(HT?L8VaMlxPvn3qjpo
z@X8O=<-|io6peL-fj^mZWxayOQwv-a1hAsOq$!bc#g4=x7vA9m)JW^X1AfBzv<QeL
zhN9dB<9k1tj!=7V$VQ)Vqy0$)@{K!O>5v_jH?0e!ENccBw7?@Nxh8ywbyWSdjt6;1
zhJbD0g&C<PMB5wC4W=|oB7H0h=KvjYhato~e}N)Af&}h(H2A9>5&T`F#lDu|nLr*0
zv`l8DLMT%-krk~sai(F`!h1y;j`c>INBfaK!Vhu%3v`g{-_S}H2*;HbcNdA^mRx=9
z*o&*rT#}wSZAN={ht6-^G{cMHpgjz?ymjs2EB_tSgG+c(2HF{+-uX-+u!nW+Y3TS?
zFobYGTHz4VPiQQ1*3-*p1x$Dibz(3$j{U})t*1w95ukq(%fp(`>n~^yO(648xY`P-
z5c>L}z@O9MJhdi3_N$>2XW5X@Ary7^)vVwPQ#C(=gjpJT6<{i~|3<)62t+Hu)Kh(k
z)(I%uAmz`%?XzM~i4dFu(U`hJ)Z0Y?GzhaZO#TC)=Pm-|3VxHI;CC){0$vlqJr;!s
zyA!<xnu-J+D=fr`yFplpM~BzJkd52nPp~FXZm9Z3M@5HUz?87ti7a9IgY2P`2<CfJ
zR&Sttgaimg6_$7_{KN(Cv6>u6Qy223sS9LewrG(j#&PK=19C`(9CsMD7lp9Hr;?2z
zGWnRvABriCN1Y%u1Lp%nI2VCm0-J#G@unPTW)Ep2!1oAB&Tvo`q@RpSy`c3iQpkdU
zSjSW^j&7<KMmO1qK$?F{l>xGi30U$?iPpuRU<WMWfCtp%M0%4x28IXCHn5>@U|=<>
z01kKcAaFRPOUT@V(xnp}wsmU;m6j;%)&wjIzz~z`ig+Q5!tu7`5;J@cV!{UrOJwRr
z{BvV3W+Cy!F|=?-39EbXz|pM$oO^30vvhde=&Ep-8BLxvLh3IHW)PrRraW_k@>}Ec
zoH!wi!ov<=AtpRdRsgW38wOY*CWOw8s7*7$-*h|<f`qT-rDME=0RC^vbnigzH@f-~
z4umNa*~!(3l>=OzIMJ>?DOlc_>m^)p@7c;#LK@GaaE>@%1Si@72X9sdUI0&Lru#3$
zLyeH5ga%mzR!cb52ZmW-gP5sU3N5t;fN_AJuQt{e0Ouww(@q3)Q`Ub6*!ZHbh6xtj
zsz3?W+p0bZ%tD!9(xLL2>7qq7NwZ4P#KXc=Yh*BoMCCL3$Y!oIq8m*314Q>Qp{f$y
zBPeLk99WeVNi&3SS35#tP43!785nH}Lx(P5b;Ea4F9<!9zo1}zrfy^ubjwJTS*?6w
z3N9hwJYq^aCAlqVb)ZTHB?n9hXHzb1huUMN+9QpbL;_%MOyZGtk=jZA&;ViLTWkmS
zlmJLGph+P?(1Mu)Tmq~Ep9a%`4r&6fU6lOcWI4b(HbT!pOEZDN1FRz`m}3`filWS?
zj(lJ%sNO}AWMceHl35grCYRu|Ma7}SyBVd7gj4d8@{VH|@(v2cg*(6=$_rN!2(~-r
zuD{83#hwS{04W)xtwMw82ZgMN5z<^*?VKW39w5S>l!=c(7Saaz(dOtW8z+u<?MIrE
zs@Lfst*&zb-#uIH@*;u%G4!+cCfj5+CXcL7qwzM&tYKuy*9JWCopMW7kYxMZb&RD_
z(l8m8sk?M&kut@|%*&;nW+#MgOyb1E`cDd{h-~C%Xp$+&fy96W=8c2{|10b4;jl-m
z<4$4OJMOQWPW$$7yHwpfZkMWi*R~s_G1u~gk_xk_=v`fc$bo<A66~0t?m!Ukx&u4w
zHvW1Iw!5yu_|nbo!>cqf81k|``JFxO8vw9%&Nmu%bQioSAFW&KiR+^wlfEt;2Cmme
zK=67=K7-dO=0}ot!DcXf2{wb-H=&JS_Dy8(!D~n&32$ymAY$1!=|V93CQ5MC9*`cI
za7udaKZwfx2T{43q@d!~H!(om`o8L$s9+!^DlvFsuWoC4m0V!TSII?A8R$l#spYqU
zn{<@&){yZ~I$uMIfEin<zhc6OXE&2Yq+O*Nr|e&)8Dr8{DaM%MRf=%fwHj?N3VCa=
zy_kwQU!@0QhNT8`IvpVrilvLpvB6Z`cPsULe1dOm)p>@G)G|0P%FMRyL9v3>*@H9T
z6B|{ZFFvqU_4$HFrXDj5;k<h9wE3tPrZV}$7PtWoE_rUr+QN5NL$GT-%^I?l>iO0X
zlZrRq0TR36h(UB|y%igrr1hSR+R%RU6`DUZ^he-5&@@fCU=0|Y)|$qMo!Jx?(GU=6
zf+b_rdc3sJW+yNiLF+Od9E@5o^THyq7Y7J~YwOXn?4Ux>89JDT5Dpi9x28(a^JFg$
z_EettK$~4A%eNy6MOGNrE;m8CvA%g(b65i%CZ7YOlvkB{Mm2R~%xsgTLxr7X>2Pd5
zpr%?=p=Vh;Tmziy1PO&Vcu^3I|0j?l8cxk3&HqjHs)6BJcC9w}9+UB_rMKFIipN^?
zrfA^?6xV&sgPm@Oma_6ye0tF6tK!oGM&F^~;NWS4p{;GWdXcG}y*M1osLDu>u1>MW
zZy81WV%ag<ppdFaG@Qw%kn5Egp1p)a*}`>fZHhgnP8`pvPGrxCK3prl=Vat<GR#O>
z2sf}PXuKhNyzI$MW|=F4KN_quy0D$c5^raeGcL<^a~?{(e2?a^`$_9Ub<47$HwN@I
zX-huY34-l_05cXAYChD7AEynNrV(bTgd+eS&)57>&Vt6^J2@2Il&^9)G}>tBl4uOO
zYce4<r{Cz*r<=ST{51VWx|O`CSLz+<i!Db>b2<)ba*L#u@bKt<fuj{3o#c5)2z@?G
zS}CtkgBP_tM~#M?Zba#M%HISAGkmVo%-I+T*L5#svT}I3a*~L9JLn5*oz5d#iyNGv
z;ZZ{;`if|lZZz)nt{afn9h4PoS$EBpS<>K_G!-XXl;ng*3kOWN7171vorG|7dXRO1
zb$XCppXqW}^1OnzM?kU6WU)T<CHj?zz6C=bhJ6Gn9j@qN;L6Z^fK3u9JgrkURD-^s
zoS~}BGi0ozq<p7v=zM7u4%LEh6pl+bSc6}YRoff=iiH(Mx1wGEj1;4*{0I`g=ipR>
zn^~%PgWXS1!Ht1psA|~KmvsbzbHD?oOJ)8AB#UV;+YE4^^ox;)4L8R=1>7l$257ht
zD`J4@DiL)6Wg7~Q2_?BTF7|^t@GOwt+;A9BB|aKdJ#%ToC|G5F>UUx4L*g3JRZJB(
zn*kqi1#w^(LsvH<1~e%Ars|)~7(FCS67Q44lxWxRvNnQMGhfA2=Cm2(hnju|T1^&I
zJwOUxs19pGq?+ovwv1GB?0i7DR-{ccAe~h>PGqZ$jM?FjK!;Tn&!XfEv`wuuu7_!G
zk)v{EI1mm`s{o-qJdvVes$h&174xaLxP|9f)s>sU+N&bXD<OnYP~<Q}iY^BKHe*Z?
z<roE^OknB(Gr}0Ghm?%B;=E4<dVyOCF_T!IloDAiPKt@1swYFP^TVj`WUl-7#A8QT
z7?Es(C^Q1bWgHvt*7IV39EXMjVdx?S60D6=LxYk5?deET#wqd-7~q#|JE4XS$^40j
zks|&U1tFHY6Hmr%(nq-{8RDla@C5FXUOgFvmP+ISLQX&uf5N4pP)DYxFdDL<a+AU(
zk4R9-Aj|l70!d0g2Li1PU1lfV%|p8PiI}kn@Wd1u)+nX<WL%@Jrjv1vOo?tM9f(6$
zPu4WFApt+nXaS}0$tz{hhP0APk_Q(VWwd;b8?9sk?00`eKFmxLQ%wqc=xP|ZJ~I^h
z%RhqNhzc63J@FU(T`b158XDGPHnbw*xN&5;|B;d%?GaE#z*c-#Otpdv3{Vy}U0;OZ
zeln6Oa6!+c0Qix?UkRObfRxeMTm?g=C{tw>qb*WN@Wu$Ssqzbpl=0d;Rt#lQZSq(#
zU}Bgu@E0Zdbo1OZRFGPvfp%~Tiv7F2BFE#u^3<O~Ii=Zg3hZ-{LKG*Rw+5gq6V!mw
z7I~fG0aF>2Ov79gyG}6y%A%_AM7GJ36!HL)k$Le4NGqm3zvB_DpYwt-<Z2ozlNKZe
zj7Ynr<t|c=f^i-OtX&iQgVDmNibX`EGS(JIQp-#RuGacc4vjerh@P>VDGR*f?1tsZ
zuA$*GWnqfZFrr<&)a+);LJ8Z6gpY^g%2VOu)6@WcURfo^u(pfON&^f#vr~?j(pw^h
zC5Llm3rtF6`O1PZ*i{Jx_TsM{l}TejjZwBuj_OGYq!N%Rm9=AOe!W%3*8oaFmL(<A
zcqB?d2T=|YdB!xO<Hf9)4G+^2pMzL=NeJ=3n<ftNzdIqF4Zs+S#INJlx|t_w0GhCy
z51n6NWb=onlDD?6#Wbe)44?a*FOCo@ZtfSeagIzat53&oT>7*N0T2Soh(1-hTl*o8
zcGbeOEa72-__0eVb7(PLj_kxc?NK;B_iG%<_z`IHk7<f{+oL|<+WnQ@r|g`{05lq;
zl_tnDCDRC*uTyD;2D}wyBId~8+<kNqWF}9gH1f!+G)SiMFjX?7>Wn6a26zd37!hwk
zlQ7{n#R0sfXyS-Iwmi;A{)zF@C}oqGr_fY!<X3*EG4AlWv~y;qo?=Q<nWy}bOzV^!
zOzco4v>v>oD(Tf|K7Y8=iQjN)rxUH=)U`2*`Ev@c8+T^Ir}Gg_1?i=%q$U`DBNPKO
z29lItYMLbS&(9{_ApiWNk;DkIkZRunQhp5x-xJU^XBTruriJra#GI&h($0K@((&BX
zTVJ7tTtk{|5;85kq=p&jB{iP=x~W8}5g_3#Dd|cCr<8OgIZH}<WKt`rz)+m5sYZkm
z4dE;y0T{xm^MYUq=goH}l(BfUpcfE4&j;*7O@Q+e&ryHC=z2N~HQMq`6@Q`^*DDpo
zHCWThKLMd*I{7E!ft%UZErA1ch#)4kS=+khhpAIe02Yu>$WphiMLO~6u0=Y5Sm0V(
z;Myco1Aiz#?OV6}^w_#3U;>}XmIdbWDGt>r;gJ{kdNy|CiKL9grbtfx0i%4tCRz9u
zK{^2~os&cWYhxJIA|wQa&KY=QjwUZMp98|&U`Ah)gPxCwX7|=9+3-lah2vzA*bQKA
z@@?{Y(i&~UOcn&($N^GfxSU(J#Bi~#+uF=>_!)5VH}I1;DU3_(f#XWCuY7+s#m~n3
zEPkYKy;490*J6W!GJWfocsIUvOZ*n!dgTEschq_@CV<OOHz0q>Cu0EGP<bW;(8f`C
zHj%}+A>Qz{TBtZi=nXkRBCRn7coo}m9JZ1SBFsoKh%i%<k>_I}{V*9)Xh2514*3;~
zm>rF=sfM88##&p(vV+7T0_jY2BK1l;F!m5IJp_3al+$)xq(zEzK=~*}oDZe2q?w@*
zm@F$bd<muLkZq!{oE9a~t(>j+QR$Qm1w@8(8%TdnKq(_ANUtL#4`@MB8Bs#IG?CE?
z*9x~OTyc$AQnbVrK9*(3bRlSk`6dPq-&Wul6PF7o@W>WUUzmVem)=3}kxt}68<`0v
zM6k3a`MsfrMe^v_k;O8dl*nUI+2gr)a55G9@Hz;Hl~yMKvC>R(oF*DTrQwG*Ff|**
zNz=<=5Gk!wAOV!7x2SMWgzbh*R{7PEGUR&8cH+VDH)C~NX~#ye6t9H`Y?{}?;|h`i
zl@`KqCvt*k_$1K<>9UK0F7T5!0tOpFS7ZpyjM^h8SVO|F$n05|-dg!^x6%#!lD)GH
z#jpQK!HwuM+V<t_)3z^%EDV|u5~X|1K&4d{Wy$vFTd&~V=-YUMcf+^wrm{9%wP8Y9
zl;>?R6dlr@XI)eBIMasPP%UOlWSJ&|UnCO8P^9i5wK$>)PX12vMWKvga#qkpwv#jT
z_ZSdr7=7`Q;hGT|!7E(gtkQri<~FtU;NosH{B7-9pAKbvMU)gP64=qyDPbM8_0|NZ
z?qCPx+-$maV2N*2TTc{jJ)r5dslzsfwgIYa9mp{7w<$$U6e((`Yu=_*cL#VY>nI;Z
zk!1&t{Y9ZvUBt~iZEIg*CEREcs8j^SG9@K}HSdizv1n6Q>qg=21<asUcEOEOyb0LS
z^P?g8K}2N4c<IZr(wA*)iG{ngKS^jCSK<xbuC}oygh8;Y^wk75>qpzQvIKWM)Et^x
z?v%oeEy~o`i7Q(t-Nem$)fq*o**c>@5k9bfND#vHLjot(_shVuQ66;*R#ojFpM}U=
zUkjE$+-z*?63Z}<Kze@eozRL~&^n*CeLE?A<6+3q(>ER_r5-uBN7~~XTaz-jNrVWO
zv1FrMBhRWp*?s25<!p0~v5%g)u`?;x#?F{sE5nFGC4a7s6G@>~>M%V#GJk?{wCCP<
zvyP1C*;o_z-Scd$StIM``PteTwZ;%Q;~(qaPumzpO6{igZ~YV|0k_Ilp$t2$myJV|
zeLJoHT9obdY$GUjc=i~zix+v+EXt#Ac??m}VR?itLLDMA1~|8aV|o^v+z!~FaPJ*F
zbNhL1lV4o!=e?aA$;5k`d$R1VyFDvxZg*3R=J~vfqDtp>6|GO(x!uZ9venMIjAFu_
zaD%)%7oj=@Z*054G6s3o8r|;lGb@yCclncLP3tbdvaIRUB!Uy>R1ks<f`v4|)Ah17
zc-Ckw9WJ<FW7FX*>#L4Zq>>AB(}{A<b62HCmV+&&DB{SwT_0Lpw@WI~;z74-)9PaJ
ztu8QDcD+kFA52+h17~elJ`SCQT<dXoW){w_*&Zya@{;!3+qr4tYZJ6{)5BxV%{Dze
z7Mh7eFR11#uL%D=OnFByYWJC&B-MQ_XawHMx!#pv%r`_=gsjCc`u6bZ&sIYw-f#Km
zEKHXI)>}O&P%E6Fv3M4Cg}oB(r!zb>!F__IZER26IDr({X@IF@GFeiBi8M(aeB<^u
zw_Z7g3$3A)wwE5#OnZCrvAq_L-9sGOy>&^RNt=B?>3gfPd#Ebjo_gY<tT<y5X*%c%
zK%{wLQTRSeeszS29U!gWQDh*iJaxtaG7cb;5y9;&JI)s^+&8_`3^`a=yjPFhY=Yh}
z0Hbz=<`ISJ=)(A5ctKb29SlLNC;5`Cs4K3{#*7xdo`^2)ikYKTsw+y4maC4CING*W
z`=+S_Ma28Hb;`kA>J&q}w(lh4ZgshiXmT>R|27LkUSyjA0T<b3K!`gk%?Gp-#;R`i
zgDeK_=hi2fBuJhWKG6l@6K2d<LdAO_qN2N1j~t1Y7({7rZ(ElfNUO2s@$Y@>lOriX
zc%pU5z8gPLBJkw(<t_om!R=n1h7z)~9Sh@Q>k={@;aN09$J&%R0ru-&=7gEIYWKNW
zy+cl1VUV<zcVSu4qTUs3MXP&v{%o>9`+u$y&VtyYS-;E39}6Lk4Y<f%@ltRf1cgr|
z_!#;)w{G#-p$lU+<@`r0zsh*1j9fW_P#%={vVxy1U$B8duz678!)@yocB?+han%Fr
zpj<WiW%{ge;+DArX(N58E`k9xyDOAwQI@O?-+ILw3%hQ4q+*SS0&K%c72~DufY)>%
zB^i!MmSp@=_4EkRTBdPrf0JXTWl1Ae3<F18f`C}VUUm%)nXULr2?GxKQNqB{Zo+^=
zeo}b=M0%ek3%Pq1g-eS=9A=IqNx>T0IpA#U)3mSyUt%yEW0U&iF>%<O(c~)OG*<Nr
zMk)o=%0nM(eyH45F!A;2XvR`csgV=UjVYreytxF1dCBA3=KwGkox)vZJQiiG(NuT?
zoXdUc^$WPlMM>*PI;eY@Mo_$<PgTi<qr1<N7bwOROht=FpYo@BmayXDL#ds5@r7HS
zfIivI^(g-oy!!+OdPP7$vP$oYD^<x$Hwr3Sbkw}an1P%Du|o}2HTtDTAX4gB*zBc9
zs*dP~2q4LSTqG<@+FJrxX)y93Sgy)71VHUVR6QalV@>svs);{mJ+znNtQLh~CHXMv
zigSvxmDx=S!{q@?#b6Gc7!~7$1jk+m8Cr9CVBA_vhau#K$}s)XTOL`J{n9f6Ft&?A
zMFw?u7N8fW12yH+=0_QzuKGxfstR;5T*@e6v>?bTq$#@HwNQAls(=$iuNH;pN>=6y
z^fLui1vhW)?hE(*t=)Y+_?^B7ZiO5RgE?`FSDUlIb$!D)&EjV_b$}b@iGE8B0D@Xq
z1>i+lE1~M63|H$FymaHVTPSsmq{DrC>*<K#xJ6+k9WK{9miw~=He>ISGg@<mXDysP
zaF1o!ZYhX2Zo>Pfap~@u6#qRYRPm7>Er#qtQg3bS8_|HhjBtqVS`>!tLE%?1OM-6q
zM{mm;^{RS>KmoL`GX&~RRsG>R;+_jDG5;&%=8^O9o*b6;Jb1e(96QeVN1_Da@&4%b
zc>~{}m!%K+?Y&~8ZfL_5Bn7O)MXAtM%&(#)L*0FJd*q@l6iS3lJ~=BY5<pyEz?QF!
zNy`Z-+Tq5d|B=i3!K41EkZ3%>f!?rw2w`ab(Sd?`_g%>Q#F6i13q&y5qR>SRyo7}v
z3Q-69dqqh-I58g`D6pyqOeum1pA^bPs%|&_2+Q!~vFs{lU;vJATK^6r{4WZ49#&I7
z^;iI7T$LIa_2m_I^uUuv4A~^DnJ$=F#^~qm<ucJN%9^2{O7%HmC0QuA3}DYo%FjxH
z$gu|6?wOPxEr#f?VworYdp$l}#yXUs2nxgT^A*1+Q-3q?H;l#yn1(B&r~&uZ%{0(d
z)m&9Z8myWCEe0jD&4p~tq=UR;0{!?TWsS`Z$$MwKa#gUlomT-WzqZP>`u7_{qmhus
zMO>9t7A1$)mG^e070_ikWRRAtXiElZElB9fSh<Ekqcf=`o@tB3M4b~1b|&gT5KNhR
zs>!Q7Vlet}*&HM3CMKZ-2+J4OqA*vd1%5U&m?Gl9Z7N;f8a|}NyNulm3I~JwxdrM0
zj(9=YEK)K{;2W03T??gUabQ7+<G*9e6b?#SSC1euWrzZFYl0LYWz+!*+yzC}4B1UC
zP>IOXT21~gc5uN%Alb_c`T-eX-cGs-m^S7Dgkx%%6TbnoS#AFCI<UP};@h1nkQej<
zvf8|W7LfV2D9nV*4=V=<P;%ZBzKI;WDxJ$DJSXk}()3&aiA?2lVHzCB_w#}=Xf0Zm
zFc^|r*aPV6s;Z^hSuTSs(-U0~mP}#vLIgnOy;m-MLrLG~BM;ImZ63*z-l$A5ILig(
z*#HFUZKAb~zos)72&9X`#K{X|Rq{KE1b8LCHz-xExUSZ+RyDbHW2{?dY7SNTaER0L
zCIzh_Lwu1q`Uk_)Ht8pZr~3f5RTM=yKuTUJ6}9J&Fo)VOJZ&08YB@v2T8CtLWuzm&
z+AAv^U~#UjbR<u^!pRzvrw{K+or3{(QJ8cbIwT88ydpd+_G2ZX1BThV-VhPPwZ_x)
zH-_q0yfS=i%}_CE4H?Xf!bI)3FrqRBI%N&+PJ3emqP6#iR!mNC$tzGRIMNG$L{-X_
z8sGCEb*08L)!daEkJR2pP||fO>8=pEhHPK2<oFw-`^b&Q2$`7)Gp=vR@o{Bsx$%&(
zPQAAwwbv^-KFzpCkg#8ox$Bi3@3@bIWW6Z4LR6lbH<n3B$buY&6D_+TCD*%-6Yna%
z@=Dl)7_9OM9lz!Z@M9QQmUVft2B=rEJj#T+O!y7ix2O}7V;k9vmb->jTPLn~L-8h8
ztYAa*z@iMa*LhRf^FGyuU%s$F%F+!FunQNx!Ex)tPH*tJdL`7uS?Wxvhl|tu)R%G1
zls};%w#zHW-YE-oB)36X5NHPi=U5de07TB*zdGE8sTV<EC>%=v&5*N2AcRPR1`wF`
z4PH7|>|=uuPPOP8ylJd_l#~>x8~7oJGL3Rc$%x_VlrlG5eZYpnlO+c_vKkb`9Dbxl
z!6<mL2%&0Bl!kf<`^K|CzyT6|o+G$aZt5k79rqKh_~XjAA9u7M3$WZqO)Kybsw}hb
zNA~7IJo@{B56auj3qa~r9j#Y_5-q8yWPRX1yWBTz=D!Pu$<&3&My4(?s@dYd3BiPe
zz@_3OhV>C7j;cqCqry_VUJi&#W8tuu!qQM&i~v!|Pr(7qp@L+u3`s*5!c`6R0N@q^
z$lY}sBA;eaI6N$J;RnDR%=&0a31_M^wzZ|HmqpcH8J4zolAKiy$w;ilmK1cNgdy+A
z>C|edi?j%YJ3BSv!Wz4h6-2>;8P#1dScpt>h36tN?ft{iX!<TDok3~GK5OK%)ugYk
zUW7{P8ZKrHr2J!>Hj?jLfxwFbKBNpGdoX5=@#lleUDfqkWCFTEhZ`~#-F4}}>dAU|
zNr|g~)uoSy#7Qq;hb%SbavC;RI2VPJ!u!GXHoRc-aaFQz7q_$0<551r>3wW4UPj$N
zFfgAChpR?*L-jV7ld>T%)(dFj=7Q_p3CrW*szejOgy=>X!lrJ7A;jVBxCn19@zC9W
zbB$>=X-H0XAz0j8VcnK@uJF)<<>nIW`n<Ws6RnYj7?YbfS65Gfo9{&zM%K;cMa~b=
zCtXE-08r_LoN;q?RWq*LT;3_T&0HouEpD!@&<O7Qd%{ybd2YG<zYR7#6r_Ab<l>3J
z5)PGHTaX<Ow)T|N!(QhqZq!g8#{EJo*Fu`W)36wN<t$U(p<<ayNajjecsdq?4<Xv=
zT;QKDiXJZa^$LFs=E^YkKw<l!ByXj2JW%<a&|wemWtU0fnb9J)DQ;#j09&5fJ7O)4
z`ke$maRDx|iVJXyRYl1O5nkrG#VQ=6&m&e9g}mY#J&?oo@BK_ApjyczL6gJIxl?#8
z3()-JwS3d9-SH!apXJRgRCJmfHwyGH7Ub$@=f$>BZhSe{y`Q<2_x6nsr5LOrNW+IZ
z5tAn+Bax)fDZ#k$GgE>=$|b?LQ(^7rUCoGg>>q2<0V?xJxyH5>Jq>clFQi<r=wUpi
zv-M~Y`0K{Ab_3+LUq2hho6okyCI{bYLvePn#cV8S{wteW?H^!r*KPq}?qc8Dwp&Ee
zZplfuOH(Qe1VISh?II^hpo$|vYGCkvQgHnP#kxJ(Vr-KQ4*ovkLY^5tQ`$f{K+(C9
z?Chub0=cBI<by(1CD3c{t&X_fn>dC2(VIAhUDdldg^k#Iaf&1-W6*NkCXgUJUvaE|
zy%d4A9rV5P0))Kux&R>xo$3t>diA>ga;cBr>jK2ec3pr);01_<?c4pA%h;vf08_u$
z1&C$q&vvV>7_*Mia)Ijp!(*d+-GC@yQ5PUqz;yv)0le-%gwHVWj5V6$kM@zF0^K$`
z+Ba%+&Nr+yh3@SSgK57GrfULNdhb-bYA`Mp3hVDK4GN3vE)5Ec3*GLJQq_Gxg~B$b
z6~k#o?X+SDTdX@JV&vW0o${cnYYurBVg==4h!d2D!Em0Q_d{u*9Rb}eXq^=FidLz*
z<bs~B)PDP*stW}<0?wepLs|z<Uln{C(sa{o)M22I0^bK;H?%Z$WX0(n&<Ec(PP=tS
zfUhf_FoVqMeGx%sc&1=Zqn<WA)Cb=-SlCf-8!Y6gw+*KRi<RC?oq2KfvO;~MdVH}0
zlHO;1aIxtvLmeges!%t$+8wQ2vtJ7~)l;&|Ora`Ch&8IGH-pUTdCnlSdcOCtRj5kR
zJoS7>p+VUyRON2wFM|8iWO@Mi|9{rrrsujH*B0u}U$L9#Hck=e%T5=GdnITf;Lt*J
zKwKnLr@=)C`1h>XV~n|~IQ!XEZ=o$!J@LCT?PMm?jx%g;ZfjLZ+PxeRCFr-a0#EGf
z0Xa9fv??UQU-7Vt`JaU)o6LDQfV6x4Dg)rU*Y`3i4+h*bHNu5nP4X`EVojt9t4pU3
zp1aj&p$+w;YM6Vo5B4vhWAiPM3Fz4CoEmUojPptd_5K#kqz8lkuK@?fTSJrn3nYZi
zGHyqmDBoc($mdPHARnC^gBKkSuwvKQhqvwYRlZgE=&O9I@)<i}XZh=^toifTTZxzJ
zoqg)v`s=L3T=`(12TeLeYk*Eqr7HCC5=8cu(^JU`eY{0gR5_t%UxG~dD`n%CoakRa
zcIIvvPWPsy*k6v_fqYD_1Y1AnL~P!)&_Z%oA5I1CR)>rm`bLy2l?5T6sVuPrX}0ED
zdX&DAA+=q_C(~DsWpdPsM;>6iW~Q(ml?;r<=l`rim{U0bMgXZXq%;e)RnC5J4pTR<
z21aWtQh>m<nb`+!t1c>Ny#?(3K~08CZ1by7=|CTH#Ys!~gP%b^ic$;%w8k3te@^&W
z?E<M2<f5BH$|DN8&Z_o*PV^Zsf$Gi1RwumKptJj}UFvm@1nVuh7~aCATns2IOh1b5
ztS%U>udhq3X9QOQ|DCsI9N*FH8OL{Yea7(}pjzI_r9eaJsxIr{W)ojy<VehWNp#`&
zr2UDtd`%agcxT6W;YmKc2-AlYNx68HnstxId(}FKfqILQqKNQ&V|ytD6JTYxQ-!8y
ze`^r~+oQ|jabQ?5$@xHP%BfT%m$K>#8q4%7-BW|n)-^RJ3Lu`h0_iFJ!XTw5!DG3c
zy3T!vFbsW74pA67T^*t@@|bi2L)3TU;GR^`Q-jVIrMxHpY`&F5&w=B*%P6ljT~m=-
zi9Z7XA*YJyv#G2xv+*i^ak3^r3?==fOGdbd*?1SP>h_hT>kB_ITYo_o3xs+DZ{=^e
zTouDM8}v<QZTmJ0+_6v-9mp@$;hczFovL)1#mrBkNXm|z^wPX#HZO_5l3L%hDqT(G
z0GgFq>xHXaLcJv;IB*ikCEUx!yxDw_F}IzMH9h5E1#vr~1pV^`%E>zQt*||OOZfh)
zSPKzyQ{`P|rq-G!!)7AC)(az=$a*|cnTA-nscJS8xsxZW;uM6g5KP>GlQ6B&b9*7D
z@KhqSXh=+>??9=f<`+bZ4-p=VvJ@W6^%P>VHocUIKLZ#H3s0CVZk;Ji7Ea$2iLi+~
zd;Xk%8i8qGUYIPZ&uPH)@djZElBJzOwAqW3n<(rgC><x@McYl3S9&3N1eiT9Y>!ht
zZD{_!fq#5~L<bh7Fp&f2jEPD@AIfc^P|$sK7%|HJOa(7b)bvTD<07R@CF5abBGJ}V
z7<4WEY1$OPY$=u7L>l**!PO5aCBLCnv(_XVVSw5Z_y$}GWz!;~j!GEV{ZTuT4H~D>
zl%L4Nbtx1N0Pv}tcbAl)TN>rFFK+HX*S9nAwb%fisNJ9oh=8w4!dDcZ?fi%|QVN0V
zdI9@I;9|uC(RE3D0XX9*Umze`N#T&7f|@d`Px>$g3MLxsQfe6WcSoaU0H5>G_&I*6
znR~a<WpD{K1@s5djG-bZO3g{V?z<1ii;{+Ffdx1lZ4+9S3Ae^?meAh!g*-H!lY$u-
z#KG?`N<q8n_u}zM`1MDJu7tSP<l?AyDfklL0GgotNy_?y<$n&xk4&gP^EiD8m@OQ_
z$04$dhy8Jg51W;d>SIYBHZ$Vl-~>%q#yALIgYzS;Ml4!5UPc^V0n%TS<|kxFFkR?#
zU(TZuM5vSl>b7e<5Byjercv(*-mej^DL_C^&~)NuEbZ%}q^GPxMCdjgOoB`I;~Ql{
zFXm9175Z`!uJVAykQT`Ab$WngjQ&}Y9$7D9>UB6J(|4Q6DPnTIgYh<KDP9MX1tc5q
z>{ob1ybI^lkqQ%!6b;H-Jdu83#JiRbqNw6sO^9A&j^w$T!jjm|7s{}dSqTn89-9e&
z<RxLwn6n`Cy+!i05&GONhN&s=dLl4(I4q8ZxHTC36GgarEWVVE5H2mZ0$M$Fzy|NG
z&@b{Hc_gog4h4^O5*U1@5n?YW=k{dI0pH?MF>RPurV~)i+gywka(pqFJiuiWFjIiD
zP{6#20Tf#|nFhd>V`nY~y6I!O80bd3_=fK*tZy<_-?ebo=8S3OEJnRCYGE#{dnI$4
z2+XC&sVIoilPX5wyf+LP8Ckq($e|d_mr}v1%2+&+Ni-ul!K(Jc*4JPm?a9uM0i)hG
zeJgVzoibd5AXQ8$#YdF;eqR|QJMqRU+;?nwG$tzCjZFu}WU%^{g;r(pDz5f6at4%h
zY;Ih=(xqCY3PUCEXl8)$V5x%%_}Lo+JQ<8$al$2A{|Y3YNR~D>9Rw4O-?8Bhn2bH&
z#LCU`1V3^+7pW$?X?%l`&S)W^8Z(ce<FS-$V=8c)2lx2~ZexIqG!G3BDLb%WuDWIH
zw$uhHC=S)Tn0PO6@fRT(@se@!We%m(o2Umd*47YLaoT7U7paJiEw_|!aU#5VEZXu|
zXJg3{*cG(5WVd5!Dop=LQpKK+Kk+G*3_$ytf!fLiFd3-5I{F|r+nZD1k}4!$W_YHQ
zdovT<cCN6c#ew+M)!xM)U&#;V#!g=E!hlwrvMCt0txOBEBCVgg3R`?ornq2_N-Lq`
z<AzBkWX0Ujd{ecIFR4;mIH$i-TDT_vD5nHx{}kK(_NaxSJJacJMhkRuX0*^Z11a%_
z?h<Ey{BU*ofKa^WSEu9+dl^~ihah?r*u^2l<1-ogjfzbZ`R#}9wI=f44*@$bg$YIQ
zp1ty^j@iF@RW=Q+4X+k^Agu+jc`l(>auhBMTptYKbSFa3$82w>%Jp(yE=ZGeWZ*+b
z4T6&=!_9TyF_9E-=rZF{D)me-z;gnC$t(Q&5tGln-70U7zr0EwI`N-b<q(p@Ua)_M
zPWr%cUJAb5&O}0lJU)~0?PGp*t1LWkr<xyGgjEH2$Xz`hVT*)cT+$LeBU{LZBgYj3
z<yCHQI`asr+R7!>Y}r@0nl1b4R<qT<nALPCt=&Z3iZ_GO^qoi+cEP!;YwK6(jSm5h
z3O!cf&qT3~H`CJucC|7=P1t8|s;G&Y%t$BokaU=BYPx@AqME27G892I8SbAUR}*(V
zz!yCvo%l+NHPf;jSVahyex04DZ8B8RbvlYMy$QM|G8v36Gr_CHE;v5Cu1sV)7+;P{
zTrph|gb8IU<EG0H>~31mIMjA~yCBt8`|49uD)$O=5-9unbmpAXvAePqJV|0V<liuP
zPRi0B3W%IcWI%5riqs5?_iM_Ga{QL!%Z?m#)0t6DK9DL!^X93Wj;oS4ncZZ51SPzi
z%#iRp^#Z}=w!VIIF;qhyJe0J_Y<%ieBhXe4Bs@|HfyqP*_Ik5%wi@M+1J*fH2Tne=
zQsT*C4`f9$A^|3kY{N|5Dr+ITAne^_0HV6iFn!6R+!4l*jfpz$<8_-czeCfTMoFIW
z`pEKhIZ(~+exsQJf^IS7$rz3Ix)Vt4@%q3}WN9=xZUS{-F3BWtzR5<#9ymododj?i
zz7)Qb^5j3`b$A8zUXw4N%0FdF%*p5E$Fyl{135n0&{>kXEZWeNLOC`a$(Y<iwMr)H
zQ4L;|6zMMGCKDgmtCzwlgIDMEhrxSLXxo~2B$z+%`x})K_I-WGN`Kzhhk_v|WRC>0
z*&n{ZfjqA9CCw7R80}@kAQxpbPpe7bI~D!t^}U24d3TQBeSLYH=tp%jChn0FSH1dQ
zQrKFRzIIF6IF-G2NZx#j{pdR#D8F*vms$Hd(c=&g^##uRGFivv$m+tSc0cdid?}0V
zbA)v-O1>vv&3+MvSl5e_1|}t>g;Aag==`+1UJ`$BC*pPKeNi|yb@F16fGCeb35v8B
zYw$Mr*F5ENKvApjHox_OA~_**`-?KgIM>JPp%Z251d1YaJ?7WM6h)`-LKS=n-wpec
zHkEb{`+BXpqM~U4l?__AZlw7Bnv+~*&Tz>8?zjKuvES~0|LK4I&0y~@YIoEpuu{|i
z>3{j{KR$OOx6dQ~`u{)O|MP!&KJCwc|6Fz5Z2h+Gm4E*{&wl%te|`S5|M<`CpWBDm
zzx>DNfB2_=`FA$`pZ?ST`M><T|M6e`%jduNm*;A{712M>+;(=m5C0rE_x9iZ+yC&}
z|NiNBA720aKmY5)Otb5{ZGZb$WrwPE4ef7~_C~+WpQQb#|N4LWKmOgn{BI>?;8DZ-
z`tbiO_U17^D)!$L^M+b~Rv@Kh%;7IcIm#vbgOvaMfA#Mr<-Ail?-Y)63-)}rZTrls
z{hLD4Orn&d;^F>6%KvXC1m>#~Za;qRgrMw|`|)3YQyWRd|Bm^n(B>c4*uVdGYyH#z
z`R70Xc4tP*>~NXczHjdH$C_rJ)55<sH50KF9Odla%kF1^|IO#swq0;sd>&X|{v}Vw
zzd3L0h6CA^qr}h&?eAIdA5&tseV66Mdi~pr>7PGe8m*?ke|&jK{f^G|@2?3WuaU!C
zou-nS|Jbc8lebsEZ~0><<TZSIsR-+j-SExP^po)SP5;OC@o`audB@<tGyT6l`4hQ*
z-_a@g?~kJcUf}H}0Kre)E+ptLmNE%{&<%$B+b!&CDgSP_J+Tkr+Ma*+*Iujtdh~zi
zQ~J;CA6fkaQ9SS16xQ?O*b?{l)oZjrUdjU*mEK-TvGh~7j=GNO)>Y{7$8IR3suw`Q
z->1qxbaRVH3#k3uJK(qW>o1_AqToBaJ^qHJ+;M69c2g|MkKHP>_gA-m{)VMo73AMe
z$kFvv7eipCrk{krcL#j*?}aXBJ?`I|{(oc#pjxj6hxQ+g4i`voFWo5p*bP_uZ#PA_
z{MZcu%eR{lmp^th<I=(_F#B3sfA<cs3oiS&KSIC#13CZ)Nexa1%b&&u@1i=n{|(DH
zYb~kEZhx%k$6x9B@i%-M`^I|0XJ^05>F-|k7clfYi~b)ndd^?2-t#xC-7h<k1pDbj
zg}d0dn+Qa`{T(xMum0w`UcPlNGk?zz`K2jIU+*g>nm>*W-jcVI2tRf+E5F9u@1^|Q
z5jniRI*RghN5m0+brj_nUV~jk)&6`9&d=}R7v6#)QTLamqWnBWII_Pwit=;E%=!7%
z4ecL0_3}M`b$cm4cO31n-u+AYg*VX?b^V7s;@31I3mJaND$37;+<$pQ{MX-J%Fi7u
zWAax&5`ON6)U;pyMESAfNLcjSjqP7}6L|*^W1acaoA@OYF|Qi`VzIrHpNEI64PPBa
z`MD#a48J;x@^eRc0KYnl@^i-%fBEJ`_?35Yoxo+R{P-?@O?3jt{-p>-`EiI7C2YPu
zDWv?|5pmGps+W|XJMOwd{^}^o&mCiYcgof;yobEP{Np|GOGYE^W4@#m<;S6|3O;!I
ziSTo`N@V!mPn4fKB8A>pM^S$62=v}pM^S#obh?nU{fB$v*KDVS+n6s|MfroJ{g-y=
zU)q>|{_U?H{JS5zd=+Nz=OcY;BK&>k&1a^{-DO#O>vtS3^H)CQ6cm{m@25O3Rz&%u
z5mp_uuYN3S_H(yNY4g>soga?3?AFfyOKu?iQ8#)x@fO;*hx6}$3GK$B{*Glc{(+a!
zfQ<VZ-abF;Q*>N)?funp@gn@^j=+(9briDf=Z*mRe03D;=jV=A(Z}z*u=NWD|JTd7
z*plCQ8T}u58Awj`HNs{;9kbE#L~wxBkAy$y1_asLO*rx&yKRG`n%%bj<fvvh<VWFK
zI7*20OE2MESn2Owg8ceBILJZt4o;QvejFT1LcZNpBl5>?C}8?_Q$^FCx&@NTsT&D@
z&`oaOdIRw*Uf|ETTA7vc|FajEQUcKY4sP$iWpHbJby?$&exB)S-ww!L`(u~Bzd9t?
z@5i6RQH;6%@)Q64GyVBq{mzxgFBy)I&<`)hFepFqlM9yJ0Hk=k30d)DHx!$CyQ%ur
zkKKUpf4d3r|6?~KxaRz`{flqFZz`wXc?18z7vBf3(>S>C<8>OlA?o+-ra0&yyS4dO
z+}ivbxb4$mnxY#Cf6&b<f`D&;?O%KY`=TO$=WFv17(jcEzZ%^B@gk1hka6qnw%XU|
zez)6So4osPvUoR8y>B<ce1GiL4!PAEK>JtUzzyyGojvdmoddo+Go<`@U;;k&tK&=g
zg;U|hht~n!?Eh!4mGugx`x5nw^asA&znB^{f5lOK!^}2rt$y?b{mO@|16BPc>KEw`
zJ*0oN0KQ1S;t2j6K+fMZ(qCGxm0061*6U09*|E3kyz$-jCH;zX?`8qDzh$KRSNuxI
zqx&W97wHdt8T&7M4*&YwOZgS&+0AVBH;prX$$wUG+iz)K(jU0O;;$FO7wMO7_2!?}
z_~Wn8ub6vuAbkt_lK#MZ{@0r1uRhv;{_X$s^uJ}?Ip%-9qrdm?HP*PW_j=iXJ?#JI
zj{55we*fu24;!D}w^*l?(m(y*nx3CvsrR<~|N33M5(w-_wQ?6jIQ&G2sR-5nL;yt~
z8a?W_2*^NS#HG{>BMc&($@viT5YE&Hh;RsJaq_6xyHM~tZW6)^LXRMXP$YW=9E6IR
zBDx@4fsY6!2qz93(EV^Gm;x+6oCy2E%7@cd2^13u1-k<zeF>|YmJ`JoDZs_U;W|qo
zX`sIAlkJ^z#Z*%ON{52uV`T&E7N)kMu2F3?Tsfz3BDs`~U)01B@m+;7!-+XTVz-b7
zgjw=0rB0twP^)mJAPL9hGb*QW>)||%hhy@G<Z?_t9G2lF2D8VZRB1SawooNARED=o
zmp(}W*TCE|cp!^rhBKrOp!{&ectv1p6$c)HktKtJQ4z&cH8yV>{0_#zqe=w|JVnWw
zIStd#_%D>y3}?kFq>;M>bvft)sSw5Rp;Y4vp>oNmn8#+2!YPb>Y^H}h2v>~FL_7$b
zh|TO&ryBLKM!NqGp&GfOHiK6V%6h~GB<gf{D;QOJ>YTrMIz=Ub$U@R*KwM|CFL-QX
zBmDUD;Sc31I1{okAPqpE*mMt}YHDmHzCN$}1P?5E7)NmG0DK7$ux>Li0bEggE>vb4
zSdQ2Xo5@6Yp~Bq2vBgF{IHbjkt*RHNHgq6A0@CEgW{eFgv&JT9wSstJBRuY4e4(1+
z$e9<wkRJb2{Tu>1Bw}JK#1bW;a)=;(UMRo92?$kT(wR^%TM#ku?g&OaC_EQRzHkDb
zDsEc@J%viHp985Gj)y?0OUR%OluM1xOe{CHDw|+>Fff9G4Y~JXtAKQC6b!MMmLq4X
z4MWsdC{=?Y8D9VZcH6bA8oyYE?0lg@_RZ=IshTkgw8ml(zcr|(b(p5$lJ2Z7mCbI@
zOiQJcQD@;&z^OiZp(GI2#%FXZ#HT{lE`>vcGF!YExRhM?EA)_Ay6{6n^9tq?V?qp-
ziAOX+Fh#`2w#Y{9&Bq$l(enC7h`@x5hV+23RJ*!CA1#$3Zk1~^mMWZAso0`maJ4TZ
zlT6%Ju9&sNXXi*1(q>5E6>Eu2>F`TId0$lHjWzWchj8<KQ0b|~9440#=*8ziQ>`g+
z1LD@#>?u+Jl0a?0$vp9c`_LiA&{PX~X)d9p9pa0e*_TAdP*`h-acL}Nz%Z1zD7Ua7
z=rmU6xAT(fop*9Rc;!rZW7e_-rq=MvRZrUx)gChcEi)*_VkG@-*Z3GBX2?hviv_!_
z^xRTqF+<hckfClUyAeyZ<dGXMR?~x_>#9=SoqDSlM+0rQu<;QT9CBk_N-f$ZzK9!-
z)x@}z-c+S(tC+@1!GP);8OrBjnL#iK>p?q3ouP-!YGGob3}@&G(1tT0{H(pBx-XYf
zV$jGngSJye5JQ|q2<2~v<Sc<A8<()M#W{h#Q>6<-g2zyjkk9Gu(^6h2L%evP0K{$Q
z=28g-E9^zEn1f|hdZ3V$88U^1YE2pZD=}FG-AZFAS;!^ino;`yOUX4;mA4*{a?vQ?
zzab-MFuT8@$Z#l?zabDmkh=dVQtoLb9<fXZ8cNh}sNNe)uy05f8B=BDvzqT6W$w^^
zd3OF7T1)xt4V8mG6trrFX|P@j=8QJ$CDoiU6!TIJx?%Xp%^H(ttW{csCzPJvkm2=1
zL91r9i8XYXstp=aO<oFTzK?9;Q_^wV%JPS|#rr8fvQA&)=!raj4cfZaalTU3#!E@j
z#zCvDxk68cPRpv0CDqCnp9q~cLUKZ{F>6XvQgS6$w+_QE2Ae55ZznDxR~U1vUvFrx
zFlAYxe>AGN<^xiV&c!)3-Ei@RqEj8uOUc(eU=BZqYQ>?{ESFLv+8U!{MB1HIz2_46
zVCU>FjS8x7ERG7APubE9=|}>FQg3@@3(kT|s1eW*Hk1GgrHL^_F~*qU4Bc1h(x0N_
zi`33XR7;>Ztf6pFsC=v;-Abs&?4@Lmgiy8_8z1$jBDDs*Zc-Zl9kLDe!1-;cQoU7H
z@fcmbpxl%T-H_HZkPF?A(LCPN=Qhx+nMHNt7`#oi0bQoL#s-XGsPyrrV4)iLlqMT8
zrjfrrm<ipG;yqN?*eVNrjP?$Y*U3<;$Tk{Ed~V2FAN@!;UN0Z!1-E*g(PbLrjfX;%
z467oT>fBJ2H@d9jk;Q8+0ec>0c|))nL(2b9s&gAVTjWwu$>^12yeK)jUFI})PjvRE
z(YUylepA978^|^mtQKxaoq7q_&?p)aUFL9=a|k6YHx$8*uHb*e=c_K~tqR^omwk+a
zx0gaupx~6h+^UwwlO%i;P?IT?zQ+<R5PeBn9L_MBdbQCf^Ge%*2JB4mWT+q#T_$xU
zzKSl38am`ggjcKfWS5?umaY2cKx;*pVVsp`Lsx}{@-0!RjvtUp)PYt>$;1>kp%Odo
z;?l~|Wfo5))4U||g;wmcjZtDXln&jHa4fov<B#T#ZnDTxJ~cWmV^qQpWg;?^^oefb
z4CUF4i7Kor!bX?%jC{1AY(-Y)&Lx1;#KMxbOsnaV>L>MkiVj_AGJ{bA>QeAbs7g~+
zWJCR_K=O2}f>mKmb!Djf8A^U+D2^4T@-BwjRiSL^2Fo%jnEuq3Ci@vR%mOKstV*Lj
zNg!{iPYdyO3{plm3dDuU$Yy%IOJX;uLZw}|wAw?dl?--$DCfGt_P><+=pbPG5-1-O
zACs_OLa)b?4fLKZCSSg!T$swrekr*yZHf26q(f2TtP{%VWOX2VlGOQ|nsIuUEss^9
zyzRGLW0Z-$aPqVFkd4%eVME<;u2XQZB^&yedD9d&BwVk9V;F61oLR$UYvW8CnJCIo
z!RrE)!~?V4U(ulZtc!K&KI`HP7pKu~U+{1;wfmE#8c)X$@*7|>+}F$&K9TSwgvml@
zg4|F-Dnr8CP$qXnz4A-JX94byOL=>hbJ&=8#o$KyP_p$=gH0y*f*NeH!QqsNcIfH6
zq?~9aemCR`y%h2-UD#x%Bg^QAk}XtUjV7Iqth&ME@P=yXmw>O+$^&DQp^g-~A4<su
zRoY~QuTrIrMmP{vp+xakSyrRb;C>9*b1w-ydqH;!vUn*a>lP=dPG;7+glm&D+2C*p
zhH}droQBb~+2L4>M!&R`^RXTT=H;J^CaWBYccalN-?+|evdT9!Y(ts9OUOl_3|_XY
z1Nj<8D4RUf?nayB!K0^Aeq}gxjt2(#E)}ZW_LoqC%DhIJ-Dq-J8!E0{5}ykd+6JCG
z@^8uw{n>_OANVvhndloDw9#*E0APf&>RaXAy#(?_{o+e1#uE#yi+O3(CUuXhZqa16
zZ|KZsIs$Dd%|?s6t`(xmfsKoYOQA5(h^?`3n&I{$nr!Y3jo9eI-l-6qJlMNbj~{uk
zH)?`h5}A9p@B!F$QoIyA(*dfKv%0Q!0IGaI$p~%bM6(^>EOUC7@^grukM|?*^hS>4
zOB(vk{l`mzD5n_9nyy5(mvURkQR_!_PYg+F{m4U&B(;|U&Y7gvl~e7uOLSP|Pm)ef
zO4{E@`|U>txLb`z_BZYjFNIvJOsz}82LUO@{m6K}SDn?aIYX*gKl7_kpbs6XxKs7R
zl(~j$*AE4)6i&Jp<?1e_Hg{d@K1m^GB4=fFd-eAtyW3~B$h6pB3U1^tsn!y$Y$rfh
zW_G1^^&=x23E&+!l{xzh?^W9l$y{BPA*`;*KNPv3k-626(NW?HBamI~J6qV@NXmLC
z<g@XH<dJq%h4&*f8yU@<6(%kr$0RcwX;&R-rOX`zQo>jRNa2#m+p$n(j%RXJ4;kaA
zwRb5TVR=w51>X^%Augp@mrKh-);RK>y6RX|c8sSec+>T7t~_`KtcM3o?L>-r$c6@#
z#6v}~t*RX)iH|)HPM&IH8g=BevdSuYn<$}S0JB^YCJJa44_V^Cvv@Fxi~-PcDFMYF
zh7rg-N1X>p7QWja=!8!LU@5K=85UKZ^ir_VflTpOU%g5|+SM^W4Oz^{OX=}i%z&=A
zs%RLnD;{!cSHj4o@Tr*JN%V;!N27-<Z~UW&z6RCbRe!^f4$uRZ_G8H1=OI%&vPb=u
zi#=!^S3Qv=;KKk2%7^lxd4Df|HR=kw5-wdzv6C?zo-IDm>zseVQPr%;lCwIX!$Qt#
zWMcG?HC+f5uMD&$Sm5<HwDRS<jOASFx6Nll#ksuIi70t41+A1qD5y)RhymKXwR7F$
z>j{<WBqSF0zq{Pi_(r(PJ$<0mT>CFSHSU6C7?3KLRJ?&yahGunsLG|_`v|Ct`)e;3
zV8sQhvcjW$C^UruM{#9(v{NlU6!;t$ipo&(=Ti98)PyQ3a@!@o%-{n}=!=g214Zbv
zgAWuT@Km>*!pjN<e#KRY<S_tP++_+M#&yU&4PEL^^Z27_T@WiPP5dMY|6EJd<(q~^
zzZ8y`;Uu!33+duM<U9h_#Rb*68JB8=GM{0DxXT)bo#OsFtUrc~yG-E&#pkkxVf(nl
z6h6>#E)|@3mZvC~Y-l-!zZf7bmqJcZb1sMVL3Z*>S|F@!;cEcoi#x67;~0+o)ycK#
z;tm<#++|Ilz-(*#1E%6zW-x#%4&>ESq?LrXQ;M?Xt%eot8`g4%?d_Z1>fY)G&;_~b
zFyJqxJ|!Ji{-qSFOS$iU(_?)Jc{;fyuz~{HG_fzG1{G-4fLx3%$K%v99SE08!ZV@Z
z1kmchs<?{B^fs#1N>Dgm9oYwpl=HtgS~>U1Y1nbpyA+Nes%tOaCH4l@wP`N*2GzBf
zc$ezhOPnWWcA-^f?Ve%{-9{Kz2L#4d#iqBFEizq@e%=+)am04PusY7}zK5jR5MoHI
zjn_L^Nb!<NkpA_clB82K&j!V+H{z;$)60qRB#Eq{_=K+NaD7}#Tl`I~EE8kr$}(~e
ztSl3E=*Dg04*e*UR!`K6Z)2A3jw*n@8=reHhNkBpES0j1dqu9_CZ$Cw5??fXyFno?
zn7th(K3y2Bj$((t%IfV2Sn(wYa|dF@7hTXDh!tOSL3gBr_Z8v{by%>h2c)|MSBN!E
zek;Jb3>{x|L3cO;F9kZM!&7)kWZp4I`k*@!-urSr2pW*^t&SR&zG&rkI8ZNz@<F|=
z{U`P*X|%uLl)aR?8|yZ+g|7^7E54RQgL+#_e4*Y{DCknsq3FVFbvTWEEwP@M^2HHB
zy{#qgt0sI>mvwlseNA!4(Qol!-3|I|4avMA;h?ji7huKLkbux=Ye+z7v^6Lo6dD}K
zA4{tn4sHp`>WO-Bl_=_{<9aES4f<?#@r`T&sn}8Z^pe073QmZuj#8)&9yro16IUGR
zmWeA4aLY6{sKiCH`%>x!wXa?|?JmSs?{!2|ki;dFEObG4TsVCwXl3B)(Zu7*$_cLO
z9ja{}ae-=^bV7IBg*npYJVmMplW$oWt`0dG;jucPGCqTRd%0gPg^Y93FM)h<nwudu
z^(tL3t&XCrk1H2Iuky?paLWgcl-4zGP>TX#T}nypbg6XIN%6Tg2&hF?Z@Pq(c#Ac(
zBC9z)Nvc861n;=P^|{3zs&Q@&>ppggG0HmmT;yDu+2;~#s8682dWZg;OML76IG5B0
zur!xMz8gcF;=OB(RO7f#cLKwnB-IcnSbP4>M?#%WDRO{jeA2e=9Y`HlPRL6t`3E0b
z(hm&>o=}yd>HyJrVZt7eYBAG2-2tPy6f#e3I=eXIv^hICLkC>~dDkQB8&P#=ecGSc
zEV;DZQJToBnAKC1+k;-|+b)*0qc5cvB<<)9c+92LbDs_ziL>BUFQkc2x}`hNF+S*)
z?m)-*IAV@42Nyo<k^<exz3d!km8?t1c^pT)@*p|ntL}j0xFBO4S<8LMkVbi3A2sTa
z`Wr5uJlqY}R6_r;fK~?>#s%c+z%6|!XyrT(d8#idCvt2J7rJk3u`b;=q^ePS%K=__
zic|sj8$ZZBJY;--=ssk40|(;*bX`grTth}Pz-K<V+Xj^0kkO2}@FBw)6ZZHZZu*io
zx^Y&Z`o_%GeSr2Oz;~B&xjsp$X&zz=wKs;?LiG)q<As*F1i;!m;4&^qS07M)gSI!I
zF+OB}Cp5-~tnUH9gAZBXSiCMsSI3g~A!8dgkT0b;p-|j&DR}fO1u4i@pU{uP^k67R
zl_l#akKseL=q{-SLHj#D2DgbZ0XXA8b#<U-d^B-3==;&c8b?HxHtY4x@h%G;HJ80p
zp948_2|$T-KxZzAKgp$_ifDb->$w!Nu8*oCG3s3t`0~2YVLd<1-s!vU_;`DliH<M4
zcbMoCHEFzuIF$|+7_0+3<6ZXngbM90PNhO0?=Du*q20l1<=-4(9bBDwu?~2R7o_t6
zDVKQPVhkPHW#yLwcGYt0NC4}-jQppgY@-Wyb}1#9EcEHw!nX#nm`h;~o;N$K^C~gv
zU4}PmJ-gsw9X65osRu*(b(N&)sAuVY^1-S6`qb<P7K_aH84zDpA^WT!kTJZkOrh3c
zOI`w>S}HOzVm*;9-aF4cK(<^8K2|`sd??u}rPk@k?l7cXsI5z>BTtt_UGWg!O%H`m
z>-En#^>w<kI|`Rx3Y|6!I!-XIp5;!xH!+4Iw5Pp|qlv2^U0*mS62;Zmyp8&+Ub|pd
zmy+x(^yACTWFfDKFQLgs#!<{IG;pXllhuqPoeOu>>(uwWNnbinhL-}~IN6!(Y9wd7
z6f%d-Gv^g)Upt%F+yJz=(P9Rk#Z4x2;aOZo@%o}#6jZA(s6~^-TnF(>;E13WO-A#g
zS~MEX3tG{nf>G7i0oCfOo<O$Hi}qT~3yRTXF$4MHCX0DNF$$^G3k!1zccDK;$;D_e
znc)k$Z8C?Vw5c&eQ>v)n)6?tXLVI-pUoHion%%Os>Td`yi+R^Veq7M5UM?gzna3L{
zQDp%8hDt<2st!oYZPV)mUzHQe)f41$n`8rpsKS9AAeT$Q#o;B@QZ})MN;DYTg@ke8
zyE>3CZbrr(u1PcThC);Y!Vce{n=EoT5Zz>vSMcVOBz%ZAj)=;N(*b00!Mu6_SzKib
zJAf>Yw<DpU;2Mo<xKX`H*Y1@qd{*Fxy%c_{;H$kPGJ-y9@@((YK$ikO<wm*$Tx4ES
zjj4J-n>Bg1tDy8HaDX`dH5utuKl&*W<^}H3CJUQj7ooN~z%Ffnbt-phlf!#M$+eAE
zt}@k6>~QP509qZce=qm)15%(HIn@uy1kTg8(5i`*m0scCPm-L!VR|gGEsfV?r4t|1
zCR!!AZk#%?E=|sC1jD<~RvpEbT}2!_iY;GCg>Q5(#n)s{I}~4&MeR_2O$Ie?o1A#7
zCrKru{Mm(>X|k}1nQ64J37Ki~X7eJ<n{+iHGfhS}U^7iNHz6^N<}?v8RbsNHYi6_l
zc|v+w(|H|u+Z4S%y<7DsFC|a)Tkx!oR1RD9r#g~7>;u!el0obv%NbypeU4NF&@lVR
zy^T7?Te<N%@G+M{-aA|5i-3fUI+q>rnA;}j+BcWNS=&gqCR4gDiuVyR<Wg#gGNn=L
zV;|Yd?ic`VWxxL{6WD{Y$q2@U`9AP;*PVK{@kzkF`)1<XUKjJbqWK?CvXID;vm3~l
zedO#$B9yJ_H@%XjB!%}`36Qx2@;-R?G^PPG*hjAJXrC6L)+nX;BngaBVs{Hb)&XkS
zD%05kYT1H+W!1)PQ#90@-A8V2RF~a{#xn}X?jwy1D9nd~*0m`2k)Indm`kB-9kVSz
zccl)#1oEvf$g_{W0jSaXp`cY0E6;XTR^3N_ZPZBJ$KLS`j7Ga1xSE^rkKLwH0OBJN
zD_ay}arWiaMs}7D1+7nqkc|z9&?Y#Gg*$f$S$#=4t0AX$lxDjWGS0Pm31nN#cLzJ<
zFt^}a9e|ok0p~jET>{7E*&@?Yh&xnSx&uM81?cMdYlrOYh>}d|Gy;;9rTr9Xq1XGI
zl1>in2#7~>JnEk*>%q*2bTVe=Qt)-a4DOIE4y?@%8RPXPo*gpAfwtK}TO3%MEqqr8
z)@BE6aUgAOn^t8)Z7u<v0j${}+Z(`|EzDO|vdz`;`m2v&P%yp=x42cNwFBC?1?K92
zKkksr`k+Sg4%ynk*6e`2oyeN4TCW|*njNygfvnl_daMDh*&&ZLz66&--lNuoEOLBL
zE~UH>fY$7g%No#{P59U)1p44Zb7sm5)B51Bxdj*N_#W<{ab2I(9WtBo)!iYp8MxdX
z3SLIV<jTi+_@i2wbY!2M4GLEF-*$Pi3pMj3iL9Xz1sm&t(p(BYgV18zWqKdP*>9)q
zjjGU>K=!E!w@ZBkIK5p4Ia=^&pc?fSY^(z)^P!-Hbf%OGx=)3-`avc8EkGCxV_yoN
z3gzdHR?f6<NmWyEDLf_|=su?*K3dCGZTMTVyJm5tRWnGZ_GncHdOJ<-0l3T-7HlBn
z`1Yw@&~ij^jmqV6+i)BVSf|_RvL3KtKNPfb&givfA@fVYGY6+^ND`<t9~vLjn$v4N
zGWg-P$rftOg|0?n^$)3&)x;X<;xubOU5qByh|txeK^F?zHQMcBeCUF(riU&FTU+wB
z?`PF%IcMScl-1rRVy5Y?zLXNaY37hL?UKN{RG(m6EL*?5{fR#)(VJL9_j#k`JAkX%
z-o*Q({q_;xTDV(CumKd!r7W~lV_yRK<f(A0q`&}(=2FO|4Bjmy*r)^U-a?NI9D?@_
z4G{`+2Y5p{?hvO_ExZhB$L(SR?YLb7D(z_PbgidSkC%kzO=j7S0#!#LZ;Dp$1HhZ4
zU@ZW8lO!xLU~iJdZIt+%q<}pf7)io>S@}FaBrORu%H7^a83pH!#3hyRdc$UrU10eE
zKuwYgFFMLIR3r-DQ&6Gf2mDJ(BD>OfN#b5KR9|c|!v>sJNy7Z4f=mLZuQX(mAXBNx
zq)>!W!wW3|_}V@s7q^KQQRw;yGzjIIm_?y@oiGYelN2l$0BVwi>zV;bP0|(!^}1wo
z4clm9aHSu!#0Mf(2XHt^Bez{sPLpdOUN%V!gkYzflX?)whV#=vAZ}79fn#V>gDnS9
zl2$#)ISwN02VC19(vVDncR*~=fP*|qxW^d4)Fcf;9ln+!p$=!aORB@k?eEJwl#~ak
z0SA7PAVqK0gyg+($~!LgF9|bFi)!Ga;6tLDbKou^Nzjf3(@6@{^Z*DaX*E88aFT+p
z4N%R8)Ffr6SW3S(5JX?J#-C00<ik4UYG|fRI4eIzs`nrZYxIHFAQS77N^;j$2OuX&
z{J10}Cn@AVuoj(tY9-3X8n}{564G1@TwE0mb3SV+dWiqT3-&;>Uar%r`Ha3e5Zr%U
z%BnW!Y*9d$%!@)gnrTaZ+B|X%0BVwi2XDx?CGo~Oea*0r!)DSbz~(Tv1lSx3&t9YZ
zZ7%Ug1V_>!fMY$p78{b*B#9C@)`KqzfDc~M@Fhapj}K|8XHZUFW{i#|Wjqo}=3GCN
ziuPQmE*0Ybk|0zau|_WylLYbNGUYLA460Kh^~az(b-Gf=K#W+?8h^Hm00~Cp;OeM#
z33vrOYK>vlq+K)&o6@`38%L`T!=T!HjXA&@id5&rF-mWGlZe!tuk|*lH)*~NDos}$
z+!)lFjziZN(3;MJ*8tihD>_k3<X3NH#qm-3vDilvptN$MWjCluh3FrHigX_woCY!q
zRRt-CFmt@GZ3je8lE{tfcLxud1IU{XO~%=vBHg^a7-LrxAFn}0x?P`7Byvg`=Bf1P
zcF9ORx*bhOxb=Y<)S`QfH`S=B(~JQ%st|wyxKEOxXMp!f621e2$~FT5#-OHEB*4g`
zQwjqZ1@L)_MpnU>tsOt8dWGvBz<VW$53Bc=Bo2hCSNQ%hsCxI*<EeSK4t)by)l0kW
zdDX58YK%#>y9qxSlWKSC*f*(mD?0rF4eM4XzX`po@PPsN&n0EkxM;hy;G|||^uU<Z
z%nBhG3I9m~1`oVXlHmCpv-;GZ92PHEE(ycpp<qHKZ_@yfellqs0#)*sy+5gvx9t5%
zmCT5NOR0C*Gze<s-82kp<t<ZUQY&wr5{U9i8fAc1R&c=p&L>F_VPb`>BN-;X?}#rL
zv()mUr9Y{a6&G+xB_sj^#)QUQ%3yv;U@p6UZgSTLV^ZTT*TboCFT9{0<<-K+A84K=
zaXzSUmre(h3U?{b<3JY4q)`CJ<RXS33(w{%URw+UquWwAGdMaO5dhWB5_{}OjmsE-
zF>y9sQ=j%pZMqn9Hx{+&D*x$N)TK*?{c4n8^4q=|=a*okv8YTHEO1GfUwT?cbs9P#
zEvi$64_p$algEL@!|T#<VBzq(6r48}Pp?ZFe^Cu9Y~YgcVr1AaYFH@KMP(}3|3EU?
zBvDMNQ-uPIMRl4eCqAp>)Sh0{rg#i>=^}XPlJE)|W9r7DGF>_ztWu_{iT&izw4oQ3
zX~qy#<&l(d9&y7#cIqIoc#xes2rQms=g~)aQ3ES-V62V7;QdqE&d{?<-7-+%NlHnr
zSb?#qb7yEERJn>D7>g>mZUV-FzMZb2QQuA;1Qyk;A`Hf&x}E+GjXGCh24mqlWFA<z
z)6uN;p#X!i5R05NaOVkGK?Y;tggkXxKsxIrk@w*@c*;tstk_B6N}`%ptif1R(~LD3
zyH$%vw@n>9bqd(j!HOgpn>tvb1Y=VL<Evhz8Vi9FV^akqnqX`y;i==qrVgG{-@HvN
ztjL40OA9OT;1clOc*fYqxAuNtHc!G+M}rO3tDu3gc^FpQz}VEh6A9VJu0!sW*}th$
zr_BCMl{!t&rb?am3dMsi!VJcSLY;C3Zz|NO1H@Lv)b{{U0hu3ClL(8`iQ@ut>nDK^
zFTIOMgU{C4P^u_<I5suvkb%FcQ5iHa_SKamG*BH*hqU*0@E!y*UD7H7A52X-LJ#KA
zRG|f9Q+W<KY&X^C(1zbopF?MY4Nz6m@c6(o8M66zJ-Pm@86BHHr_vlsEIFK7Gs6W&
z9lAa(S?ErcshEM`RGFi`rBBgn4G$UaPMtYqxI21b=Q~yASZKofSLnfTs?Z_3-l;=}
z?0Sa|RrJB&Irq}g#`}}e?sa4xGTEI9Rq+MGsZhsjviqnu$22$y+3QXnI|iB<Ll^H+
zHwsCsJ@3%3iZ~cf{i>jY;ncATIv74RQaSgXI(Bq4^U1Q}o%)qg2*Y`N9Y%D*aH?EI
zCJd+69kTWvT6f4UaBAHOPIy4W`k-YGXHZf&U@F}q(;f*Sl0+AQm*!Rc!Eh>GMIa2P
z;$;ZJaO&ND-VsvqA_(CUaxe-)7*5TrD1_luz5Vt7J9TfD|KF*4J5L23)xtN$sd*8H
z@C>K&?Q;G*kH3md7^s<)B+fu^xUTyfr}|ZZ!f>8!yG(wkPg(H=BU&|SYzH-~;tNJl
zvm(IY5^7U+-3A1dXcw63lIorJC1%v4T^9mDJ*v=z5mcic3GD{*$0P+)71X1QPZ&Wx
z+I1xm*__N3F@iql4#ghSvt7rA;7PU1`VXE|E8yS(Z50KdrJ!Ez<Lgm)Q9Kd^RcL<?
z05Lhe`eMYSoH_u6>WAw(AfQFNf`<oCC`kiHdX>8l4nbYp*~I8f9)>7Y+jWw_txl5g
zV0x7m-Y|j()Bbw?aT`@MOsA8-JpVzBn?VdCO4~Aq;Ymu(uF2j<W~n4`MyPI0j{l&#
zwb$_<(6^=&K=8C`>{RQ`<oOSJlu>ZtDO!zJ;SnS76LP2j*aFRZi6-42^d2+n;ZiUN
z8T$vC+GN)sYHE{he;WPu=4eA=8TW@;n!ym`ShdKAO4_zm;Gv(`WZ54oYDGhgLq)B4
zh;g8(D;|Q+s`bf$h;ew<RYb%%bUB-D0uD9035hjMsdUo`;83M2GGYLs_#x>8aHztW
zqo8OQBEAa;`dM)f<4`}FO!-6ooOiYlNDy831&8VxArRw~f;Qb294crVI!YX>Xw!AU
zp@ue{2@W;1LM6t5hOVpZ2PCW&+!vh1ccuG+voK)cLJn1S-KE!)sIwI^F%EUF$>Kj$
zz6y632dcJ$8y=7#mF^4<b*<qLaHwcahk!#xYmLqdK83ufX`3z#4ppt9Bu1i|lK@EG
zIMlQa_Q9c^Rg}ayRI?0|7>B-S6!3Y9mZMeZ#HEy&O$U#|LvEv&;g%<bm_kd>#xtzK
zA7+EDZM-v>jjC1w5VKL$Hpe{8%1D}&nyO2ISdJz{+Tuku3#`pkw0Z@Kq?ip&GN&)O
z;W#oIUCE52c#?*pZTzHGWn1EoGp~XxX5#_3@#yi)MvbjtirIL4ZBrsn%EWWSB|#`*
zz-FWBZM+YdjjA`}CT4@$Z9`&G>$dSu67_E5`C>Ne-8Livb#EIIy;LtVEfoa|bD)W3
z*(CtAbHf2+Hfm?g>Ql6O|6S~PI&NKqrN3D*7ZZt)KP2IWW}{kX;Kik^YI7h|*$S$-
zB#5rV!fe#pjW+|cQD-ywVm4^()-;*a*iAY8W~16x5XNj&+pS3mYHfvP%yxb|2+PQc
zD!bs4z`oqnmq7NV*bkyICJ<IfVHvaGZt@(SC1!rIJ_H;QZu^emDClA$uInJ?Vp{#p
zxiW)byfK(aA$}B0F#)4G$MsNyY+fjsSrDqDaEl29)j2Lv>+PSzv%`dDIEP1vXF`1(
z1!hcSRzHf%n3aA#DGTjDA2J_LHpzKljJ!9P(75L;b(xS3w*O4MeU9!7CgL2=nG&Ql
z>ZRa|0L0X#;JXFD)TPu#=cNqvqBINh%lm=}%jHry4XY-25F|2TC>_RFOhlF*#aPUQ
zMxE33*o`4*n;UL~FNvKT6JD+RbJO?&JWb;ZFg1-Yk||C2iSh~`3R*R1O(F#5jIk8c
z;N?B1iSem*-o*D{q4NwdVaA^fr<gGGPbf>!{2T;M(AJ+gDV(6GKXIHmLi0`J6*@ti
zeRg;pPe{eq@#P4VcL@W%_?()+OM$RB20bU}#h*AUeJI(we`!ww0CfTu{RH~yATQ}%
z4?sU11z1dgpN=9dX5pVsxR`c~kel+EfI1z9Q%nGzjzTJC!kmucDJD=(mqJF!igkqU
zn|)>rd%sVNXlaZSLt5lJA--Z9FDd2Mw(S%0FR>{td18sx!hohe$2jz#nB=u`L{lSN
z7*Sd86W)arQ=9>dIx)q%zAr~17qd`NCx!;Ou{H)7ZwykN`icAwC%SrhN=J))B0t1Y
zsKkVi<{(sJqAt;GQ<MN_+SwBzrxT{<)}lUPdT#JN8XjE#%t?S+3+ZD3o|4k|n=8C(
zL0v*__$ZTnj)rN|<_7xcsGj&7mM!em@)bTwVi#yF20YAiO&(PYpKxCu*Ukkt=~95N
zxujmb_}s!q9uGbj`pD^#zm%Lc77l-sR0EKOJw~?3xy-fW&Zm}1cT`$@jyeIJ1mVrZ
z3msMopU4JugqfSb51ou~n1Bu)ML0YYZu6rMhY7#>@uhi%BJ!o-LlFrsmk-K`U1Gg3
zu_fBZq)rVTipr-r?>cfH)exVFK01QiO(2U-hDl6ZP#l+mT$dQf<vyFh6dlD$Ok92(
zMMX>$+&hYkm?I$WKr4^SNBFr*%H7B)iAz}7Bp2v61xZX?1s(4?0}LoRmsJeJ(GhxX
z)_u}(6Km)=#8Ny-sl{jF4z1@V?$CTHIzDI17Ix@_b$b{mF##gF1UwZvypGC}Pu!~=
zg-XoI`*rFD=m90=RcypWRmrny_M-6QQ8n_3>XZkNx@XR6kP9@QA|)muL`RVlmy*kN
zhxnq3-C<SoSump`blt=?=s}>w1j6X-5NjyH9rU400F2HK@g5kVbT!I*9wGGRoRH7o
zse*3XG<|2KqPv8*R|zP?7uV2dZ%!37+m_{vym)8xOOeQ;vt{`LS#<Ui<AqbjUSeJU
zc=i%&s5X=<p9MZTg4s=6+g}QN1Gw716!P9R#3|N}0m-CB?!p7i-BY9zMz%2ELPu!1
zS!kh4z~=;5p-V{tpCr|rqP>h1Ku5*NYXGv1=YcF;Y>)u<>@G&B-FDYJ9L#Sgm+}uC
z)hEA{8c>;~3+itZIe#fR8oJ6S;4g>e%O@Z*hXA?H@Bj@uTUxY`K}Vpr30%<Gbdpa%
ze?Ann(r8#ml0f?{naxNtdQ_c!0#S4+_*PW1(s~eCk8F`G4rJ?~l^c4=$_Aq76ei>;
zN{(*H$}T+7Su(N#7CI}?%8ei-++>=eOX4$1M_mdZva&^~p)*y|{8CERcPpb}_*q+=
zpfndP=v69n$$(x^nM)ZpClEtNRn6yu-dr-F0V6s~W^|&6&XN(mHU~*78W5thmY74e
zs?_-efanNCHw!{^mU0A50EW(*;^j3e+R&Klqhjb2>4*;?b+?`COZG9~jc3U~M#cKW
zQs)yWptI=yo~U~NT+#v|g&mR}igOLk92DmoVhzRl7CWC<_eZd~`Pmm|$;igOISWQM
zcGg++d0$EnkS^~_*yw`Yzo8_TjOYy|xwyOcl|gRpxuF7AlORxmC{jLw$UQ>9O`v_w
z0t)__1@<|sNf0Q&NuTxv)aT5j@k0fwNcr4|Ryu;jO?-yWr0ES{^O;AyK4-rf;)Ao_
zjCYJU{0Sd7H<X<!l}`YAj$mywwb5;-Bu^4@x~H7hP->R~;h@`8n0x|oeiFboH)62Q
zl*f8Qx6Li#pxdV0)w^`tl*4-0=ioW4Up_aqouF%%QX|@E<?fzxRwqR0wrS(SrZ}p3
zJ^=?hQ;upR3p!KgHj)LMsq3i;=+BulxM5CR3LgahH|4g5S@xlzbr-wJn@<Ev9OBR>
zLSoO9Nsfq%Gv%*FSjKavtn@+=ohc(7Afl5+&?oRiM?kg-^w3Eo?*XO8Co|ov2f5<7
zsM_fh2J{iEZ91SVXUZZ+A&N_>5qg~$RT=#fN>tg~4vjfq2em_GPWh)D2gXU8{Bs^T
zQ}#H{D@VoArw=Yu8RWnTT?$!4YfibP3ng@hEOdZ`o=XB}ctTY~eIgOj0Vr+)9(0DR
z^h5}qp>#nLXT39Iq$gWi<2XDX0punQm}kHoM^%<H;(b7UuT(UB0`HR)%sy1+kf+*t
z)Etfnr^Xy|R0I5Th8)$v{v4s=Ca^ze2-ZGvP(MTVdY$FZkhzXBIA_35jY2s`HPoM3
zae0RjyXkqhL@o3Qpw1B{Zo->!2EEkf?)bdDDKVh?ROo!dZ*qipo51m03LlJs$V;jx
zN6UZ53;@G(hFsLqun1(9r$6V6_e35zGY(qZa0;Cv4|N5Co*@$)X*mwDZl8}jDnT8U
zHoufwENtZ@%1aH$*%|UuGZV>S(ehalwnwP5Sz)-Bf>zC$+|;OVbw+!~2R%3BrjD5{
za)q87vcQ4D`B2cR4@{TAT@K09WpBf2dAfEZ0-cY_mruk(KZi)M89V=-J)q#aY-KoV
zFNKmp$93iKneg|X9%!Xx+I>jCb2@#}@FAZr`#Mn2{B#-EfaRPnBRi2fM-|Q|a5+a9
zvk45&>6@Q-KyXf%MO^@#OCTeh096-#0)le@F?)*S)r+hGgOWuZ(2Jc0HDddZ>YzU}
zi{l+3$tKF@oi49*KofR(rGd#gUH0@r?bg$2Q5Q((s1*9d{l@{=Y~q6Cw!s>=D3`)-
zF|JxJ3B1qkB9j|eHHQ_`C*V1!%j7O}&XXkmWTOum8^$9G8&^uFYjdB{mR(Wm6REo{
ziL9V5JB)1HRUMT`pJ!AHQ-WLV)8*I(_U3dswo!%hbUC(Bsq%FAwF{nex~i^Dz;h1a
zX%pa_)8*O*Hs|yv))V6?2ijAljUVwbH6VQ_0G>G}E4#2WM=-Q`0C+kkk2jDr$7puv
zedtkj^NAbNW3s7nt9mJPc;oK%lK5O`HlxS;)K<L&jvJZ{1<s!$)fi-)pVDn6r#Eu?
z9iu6Zw0}n>(4U#N)F;tqvoJ4*mCPp)FUMp*1Mu>ppp_GAvX>X`<B!qBy>MxN1O!{S
z**``LdSwE}+lFstp{(wQgnzDCq=)-bY7%L3uLezL+`6k(B-F7f#_)yOM60A9dTO=2
zn3j^u(&VcF>Uo6QT5W(~XNOX7)+GQGoOKBRC1>(eFThO>Ym+CX<f2`?+DFNmi7}L%
z85slla?HdUYR^op;r~><@>Lj^Bh1$Vw&gk2_+&UYt?9ve08~Nq1ys)wxNEhYEm+<Q
zSfSI7<cBJ3hg_fu+YuKiLZG;wRaLuhTU_c}(T=2tGHgfFhQnS9u}0~-BM8?@$jfc-
z$)DuPYh@NMz+FxYv4(PN@=`B=T}}(}F74QOmR`WRoaW*j7^E|u^MdS0rOg+{cZBy^
zIVY!WJqD_;(F}eT5OSBa@RO35cJKny?hxCx0BdP<TQ39r_cZ#g7lAE}ZtF|Qx8LZt
zUdRb_T3OV~>i0krFM?m%BHwb#Tml(ej&F)9PJk+7{wyFDkAPu|2$eP@8njrW%X)ow
z@@YdosKpwg-j`Ghb5J;_EEOeR^>sKxZ7t$jTGuC#z?Rm<Yu4m;ae~rnot!477Fza6
zQVpr&2Q?fM=anrE4yU<h;(<&2BQ)0{fQ2Q>lTy>K4P6M9*1r1G@@h0w7qa_&NZIn=
z;v7j;R%NI>`2yZKgu7aXXva$;*HUJeLcXcYE&-oK<d_dUwRT#ZAlhUBDiefeEg)qs
zft>HAjuT>A9x{9#h=K`0vlbvOaa?j8h(Yst^#)OBK3__H8RF1GeMuz?Jk%?VlQ=Y|
zZ+qv&(VkwgXo5Kki&XN`LA_ua#o1z>)>E7%*0m&}Oq{#4fR2f?#N9AXDQSRXLV&H+
zt3}40FL8229V3tiF0(T!^@~xWP02bSn$lM<1Y?ANSPK;*E(ISMl#sZTdhX1>DJRPP
zToQ$ySc5~HOF@R9S_?LRoG!*WvL{X#<B6Bw!Fb`-cQIdBgk8KB-h5|N%|gwNI40&B
z+s5>u4Uu6CuRM!=+DO>)B&DQjlFuPegM1EYX!$NcUE(x8HuDd}p_h6A>Jo7zT&b*x
zqnRnS7OGmls_x2@Bz#+N)V&lkuZ<UR$h>yuC6Ie=-UwBHT8PgI)iz%!CKE!0T}nwP
zbqmPLrSSVOa>$ng0pT~e6bJ~v!ljgeNYfL<Z#_xM#TTAGxWA^~dZFA;1pU?vC4nNg
zxL*Ahl@s^@p(dQ?=1VEzceY9=L@crCHIgMRh#m?RHD5r@L}*7N0y082Ge9vR6xON?
zJWs@wECaI8C%xdK`cTkHS!6`R#TCJTiUl`V#1NZ_X&n-7VpfM3*Hg(9*_<P5m@gn{
zLWr#eBuxa(aR6x|WRDk)CZZGFwg8<8l|Em9&V*oG3+}}T8P`<<EGc@BXOp5s2@0fj
zDJ8Gzu?~5gMu4Q15j4L?>A;Zn4Nq)@)HS@d5wgDr)L<x~=70CwfAic$+df@CKl8pm
zeLqU8dCc)S3;nnM;kW<&H~X!9{;U7}pa1m%G%PCJ*uVaUOzEK<Lx!pskyj}O7f-0J
zmrcx0C^XYnZHo|i-Ms(i()m`~E~|{^l-yFrRZ^K{P3ueKQ?-du5zOh(?a15U^1XEA
z^SSjlMtKOjGl8{obORf_Rpox*tnr;kvNOo%h2V^##3qbe#U1u{#sp^oNLO@tFuwK;
zVVXGAW)Q>+AO@b1NUk)GUH)7`JZRYFy(90HoNjP>`svVlT|WMor<|@&>Yy>i1zO8!
zuFu|>pXD>h>9#+Ac(b$Z=T%h4tFL9mGx@uWsBYe+#6!i`Qc|IEEv33-sD-48>Rd>w
z@m=dk$tbmumP)s1-Hg9pH##e7*${sIe61S=Kx^F`#XG(0M(HuMZ1$T`;d|jQPM!;A
zD9hu!aOBW^*NuYDv~XTrB^M5%HMMY%5b1l>z@6l%#&i@qu63iR#&_Z9OO0w>5j=<2
zy7`>&J`3lwTx{R(&gYLc&3ylD>js%A!<oz>pqPal4X9<pMx%a>xka+eAY$}4e5@~_
zUT%HNlTZ_c?|mq{c33L3P;%`kmrM{-ihP|RNNMHt3@79aX+OhNL=p<_QqToTI#H#C
zSq{NPfocw+MGN=*6s3ky4$=@<6!_`LeV*Xz5Kt7k?1MPb=QrfL55YvEeqU=FwnQXE
zG@xIF5G@#ayZ})k%|rOmfGTw!pOL{f2=%Oe8_ae6TOe2>gyMwt76Ne=KtF`x1cX1B
z4jWYv!j&cgS$RVMP9*LP;Ws0Xi2`s2PKktX2G5CtZ<awD0&l|P4PiG?gCc~&L=;8T
zm43E!YK6muQ6GX~!tf8FFj1o*1j0P{lms!Db#@3rFcCx&Kwu)uBm}@jO^$f+m#Eqi
zf?uB7;PDvAsbk|p3N=7t^D_AGkhtqJeaaS#&CB4EFFrQ?T{yDE#xWTM31Ta+F)9)S
zAem?8pAc?B9)4yI&V2$}o?6OJ2xy7ZY5-?hr`e#Yxb0j{n+M;6BVU0mpQ4n^bXnoZ
zd<o!spB=(neks9K&Agm>l_E;lgfbi=j_ML11x|;XRu0?-v2~J$YvEFAD(n2H?1u17
z#HPgt|HUO>?6^#f&4V<e&0<qYW;j}GTH%OS3+6OLL|g36&3ABe+;xIRjiK8F&!{EK
z<MRnDNo;5Odt&oq3H6a;*S%5(^M#TYq6SkaWg*HmMP-b7l28)y6m6|Rs5(X8cFM%f
zd<nHGiTkjIxcyM3!b?iYm8tMjax*QSqwNZ^j`%`JEqoIUp1WAGpi%xR))8l@sl_9-
zRWxS+#`hE@hqywFp@~-L$v7`A=+BSI@oBg^z+D<jVQ2_<y%cnSY}Aj2u-RCyXO?Ix
zmTC<uZBa*lte<+H%3gRWxxv;JYbdp~d98LyD+%O{Bj(!VjT5GF8GcOmPiu)UPnc_o
zF;1C_2klEKahD!~Bjj3W-G|OsET}xCG&FebV@(RS@pgE^HaPn~6twQ~Cl(d0Awv98
zC>Q*vN@ZwO@8A;17gg|L@rZ2=ns5!YYErxSq#jfPL&Ggetp1KKFd7}{5NIFE^q7OC
zg+2VS`Lh8jta0KA4Kds%g-)7R4DMh<vVlwC^B{!Ey6IT4nhqN9lqy4^Rc*(wlLyK_
z##FL$GpICSDGj%IF^LATx&e$CIvUsaFo22w*j0uU5HY#Es<c2%Uhx_#3j}5WYEID0
zOG&%xlJGuoa~Z^Aeke0rc;yCtNGRqd)M(xfh}+RfET-Z1Gz7)GlpNd^Q>Z(lERE?r
zLg(E}$`>-VaXu%-+oG6och04^1BLeH2Q-v&jk)w#sI<AzO39`~g+>z&^K-s{eXP8I
zhN7}D-xDa5nsAtxQV%9ysI@sCG;4I)khqo);xG+2_aPjn)#ZK=hWR8Vzfg&>G*l-D
zVJr=`31W6WG*#Q|5)-w#FA3VfpxuP2yp$4+2C{XiH$o~eAw`pgY(PrHq=|efwI1o9
zwhsL!+@+xga=f@p>$i(GF0u>-F_(ri%OTvQp%!x>g`jog7^QuIL<vDEtr8{0kY4Rj
zZ$r8j8JC^_q|*Axf5t3zoWq8;d53mWmcdI&(F#KOfRqao7)mQZPYh{QV19xL1`Teh
zP<lZlZYY#q&;Tw9!7L5MxI-{YLotE?%F<AcAciuITgM4a07)xI)g@pf0(EsM_+|i^
z6>z9MNm=QQp)62ouYU%0%>yt>LuRtu<~-no6U0#(;Aoe?iGW9ROw9wdny{8u(6<=#
zeFZr0jS1d3?+IyX$io%{S{ib-g}|1NWkR<Q*3wXn{!%zb90G?lY=>GCl+p@B_#_Em
zhS9QxE~pj|gEzr8py>u~f-Nfr#L#8YCDe4|c@WHA4iJoY!8V}jgwM25P?!)t)9_ai
zo@w}T2%l+qU<^K@)>otN!bUa86?$<rJ`sn#(e%Vpl!?W(0Z2^<i)jU0jeaCIbYee}
z8+x(JX^eD`PxK=`(2KnU`{+bLH*G*C_K@IEiipmBij-p!e)CdtFv4$M${kD(am7)w
zS8GA_bZPJb%_%3aVS|JKoR(WCgx)l4vgj&}Zb<bR0&v>cw^e^(bi8=Jlo}mQ)R&NM
zEWtD{r39D$9ykgLrfC3chhUmEfTaoIG%Y_x(U-;owJF@D;e&Q5<PFW)7vTklPh$wV
zY4!CC0XGdPT!XmHOQ_c~nVrE3`W{_+9z_U3&`pEFh^|YE0c|Oi<ztnqHslw+gkmmD
zJ)s=wPQQfQI-Pe<ms00epe$|H?;**AW)$Yq5a4hr<eL|VUHN-#;^MGVkt6kQ2y|)4
z4;%np+Jx?uBmKFgj_1}ZnNXfzPr=#n>nSxneNJZQ@c2FXST!NsrXjK<gxfR(pG0rs
z3;kM1hzF#4tpu!CSy&+`ry(nIbbfY_w>e<u+@(-O1HxqJqh>&uK0Pop!*q;Bd{5Xx
zD|d~_$VaN{5RTK34?BqCyoB5|!f{^8edA9UdtABng_uySf^c3+zEYEkKcQUhRrJUW
z9>jSXa)*Z!3mOUqL;^hxDagZQ=4YDnCn@9%MQSn)CKRc12pUdBA+)DW`bGu!w2D#-
zp*=65W?zOqLfgU?TDiOm^YnmJlg$l};sGJJr=fa42<~|)`E|vq=PA-k0vIF0FA@=I
z3(8gL0S)&<K~$(M`dCeteMJ#o0{KFf+7KJ4QY8X3oR>cfLFW8|zEt`?Ls(=832Iey
z;6sr$kBR|L5DscpyC4JxHTVERU{HgbAWYUgTnSNV&<CW{GiKuc(WEA89{!3TTJ#cX
z)ybM)6aHT$12jachTx)B!K`6&r7bvE1sJsjy~%7`Maoy(WZ<JrKmamoYv<pT9C}gN
z{A>YL6}sLt#0H1JpoaM202tINzBq&hHH09?iv=|l=ZL0Fj|v_kFsPx-M+gjR=|t0Q
z=0fhkXs!`JD>gaG%2O9Yf*K;TLr73V@b(ixf?CCQhk&4$Py^VSe;hjn1vNMuqb-7R
z3?9i46x8w_F$4rPxHSVnP=nJmn$864aF9F`Y@AF52ECLVqmBd{nzg~)-#BxYM=)jE
zmQ6eoh@3X{$W)^OiW(fr(PZjxgG0WJKk*^C>jV`w<Q51*MXj<AL>poQE!vbM*pS2E
zlE}LY5P`2Qk|Bh^qqax3$e4auLPrgCh=S13q|`dlZ8@C&A@r!#tw1!D3bYMH+H`6_
zt$+}w)KD5AniM<IMsPe=g$P}08%niFTcadY2w!?BC9F;fdjSWN_|n__Na})^8g6%7
z5L3eikRKf!b}eT=su^NP+3^K8$txrm!qkxW!}ZX}-|OhG{mCY|mU4B$OAQxeex%TG
zZ{`O#WR_QNeqL)Hmvb&Wsa3Vvq+su(XqgL6YN%`Gb*b|d<w70=C^ZyFa{)>(Wu-9E
z-<2iC1t)#1%J6<jH0p7M>B5Ry7K3vkMGf`hTu4!KE7QaU1-+!=J-_f8yu318@A{GA
z#TBq0qR1?>|9@dTko?~P0ySj*cL6~!rKaue15nG`Y1FK}eFkQYS6-J=l1q03L*eJ$
z+PDOFfk(|}w#ay5fUy3nV0E_17^>2R9KECjpd6|Hs(bCijT#ClUdlqd#8*_60X=X@
zeC~q$+Qq&<Eg9m-apl65nnPJSfTe~ClP-*lp$w%HSZakFa{)^Y#VkF}J8iYZUC7c)
z$pHyjdMUX81uVUkm2EoLy$+gAT&V%o;lh;~fFB+*0Fcbzg)4mw+5BC=(n~3srOf?6
z<Us3+BIDfQl67H94VC4cm{LRac~?$ALxp-zNU2rvdJlm_3~(41tki&qaluLrfEW*%
z>p;YK2tRIsAA0Dd4~U{C)YOn?&IL8K%tGfvnpzkKD3c%A>|97wL$zBM($r8A*M&5-
z7}=6!18+m7Igl`(FjE6k)P*xOph=yH{j4(eKS>c2OtoxtB=2|OOfMy;TgE!d3O}Au
z)7z}U=(vwzIiaSPP&2LLeynWK)gKFE>0+`l9_?*pYV?qmj!cfu?0-*^RubM$C5o(a
zfRUXbQu{0_7lPCRrE(m(01c@sT>w%;I!h0k<j8q>Ddd~_>;mlQi~#QDlE4?LPbmcr
zz#Dg%=)m0wre{@C`?j&!0?N^~Yq48h<$Mi0+LdL{h|h7M#jL&zF0_~-<){-bW=QMr
zE`MHr>)e@o+weJb)$KKWGCeZ}TA^(&dKF9ow|VibR*0LYNR2<rH>kvd2F#5o1kBF;
zOWP5M8+S!q8dQi2C1$B)TqSr7F%Dku1<7h%C@{->wog(pgMi(*U|<H=jSCBAz}C1B
zg?6aI1o*Oo)41{h8t^o(e1L}h_n!Fxt+D~TcYXYj`QBYN@_|NEM!-v{Nz^U$S(rpc
zTH4v!BwHvs?`YLvWFW(Aa^lFWEUPCeWLqjuKr(~L<}N2XvN2x@whk~dj|)9!uoqqU
zG0OqVMn*P#ckM_d!}k}6Y=~-d<pMMqrp{b|R*_LI5ZWc=+t^2+D!^%6Kr}<{YZnsD
zkRaOyMYBZRxR7Xes0Rr}GvID6fy|)?fkx|q-MHXry?{6V!qGa;7A^={uk_+h2wF!5
zau)`zBa6NRgLd0@wQri&myjEKZ#@($O}PO(&Qh-2fW6_0#(_lZbs}@62JASs`KEc@
zajJ76);dmpzIC?l2rhJi)_NP+B4emZAl5o?ID$7Pr8c5aYaORs-%Fea#`xW>#`yM{
z9OK)q)a9O<tBFxgz5ysq;oUm0IG0j5eqeDffxPRP<O_YdhqyprDkouYs8i|!qjeN7
zaOD^5NREFgZ?}@AOF9@@4oq5ao_|v^9P<Q8yOffSC+<rr>Fj-r(3#uBxpbz0YaNIj
z2Xd_=de}G5+fN5V$C-z)!}a9b#5+%vTR?WWxE$!U-cTgnm8Y;H6~6Drr`9=8z_bqM
zn=1`ruaNGf0Q=M7v-8E<xem9UF9Pq=@8`m%bwGD~QK3H_;2jq@tpmGrDP&%wy%fZK
z6n5tl$eL$P0@yAk-~9@4hpt`hk&AHgwBF%o^{UJHfV7f;XX4PQ{Dd7<TRxO*)p>Gl
z$vG&Nf?5FWapfKCh6Cl=dMeJ7YiH|omaLMeB@+&lf~9qMxLqj+JG|hol!G0fa$iE&
zbfnYwwZwG219)Ujw>BKxPA0Z(+nU(6ZQHhO+nCtN#I~J@HGk&8d*1&#=j(lS^{!Q`
z)++7l?)%=m%GKb^vPpi*(jr8XhY47})jO2+Tu!{0C(;wh)TCc03<n*c8n}L6DwwfD
zAehot58Plxbvf`0A<BlIM&2#pxpC6UYtu8wNu^E|Jc_5WvRLqR2w3n~4D?9&Awl!e
zE)5_2sbtX)H#=Q?(_hS*TdRf~_^Bl$#rtq<;gLTZJxRJ^pLtk`h%tLUJki*7WnJ`4
zS>s8es%8v(F<O1CxZVt0wl7WWM!~UMQMt|)6GY;^1<;Xai{l!^E5rqc9!|@yHDX*S
zXRX5TrX}LyDd2`p;_~$r{D@bBm<`tMF6Vef`;Hw>^Rkv*+tx^;Oc!mQmsYVe*Oj~W
zqB9rea65o)Y670K>gmRo6l8_8jo2v%I!Mh|jWKbT{g-ab88vYHa7?{7a^x1kYM^h6
z<UPnmNN_K32tH}Uv_>vFEB$P0&)rpDHe#r}Ouf{^(7b&cQ6D7>uYty#i{@PY4`_?Q
z$g5$+WA_Q4C=_U<I9EIf+`KG2f&2D>dYt*)vie#}fq(2%CanAKwkHKYj-##a9FUu7
zU5|R7{uqAn!814Tq~HI!f)gsdFn%cxd8D}2tg}d|jo%hSm`b~#34StC>cWN36+`Xs
zTHv>O+s}2TGm4E~Rt?;+57g|e=YpNq!n-r&dI)(j+J8-*y&fO19qM#fM&Y2pO-o{1
zuD#PLrSXE?5JITrya|VqgnYIX?>HS=Q0D>Yr6t}9=NAiox&(M*zc_aZu+NV4n@5E5
zDhBT$1*dE3$}jGVyaG~YZ3-1Toa#ZTvPYSGsH$2AY_wNiy2R^%zgqg<VO1Buz830&
ziO<a2HsP0d%Ru69c(Z0)*rOE-Z_P9r2+ujpX#uATwRGDCAHRmfP6O95O-I63GJc>V
zIdzI)iH)XA){5?TgcR3R4W9*~4%BLx-7dNFs1;H3+KLmo80vBq1m>vR+Fg_o+kvjm
z<}LmJL~sVIS&v`DyOkXVdn}}BzqiBY_IR~Y!rR2*Z~D-07nhT{3GTg(L;ek~uJqRZ
zW{#Qgq;+mE-Bc*K>k_o_w&nvCA-XWZI(JqFD)s7F)I&98CI;qZD>erjcB$FZHsIaL
zP)r8<Lv7>>k&Xd$wzB0C%cE@Z{vo&4o(V0quRZLfZ^mnQu{H%U;j&nJ>1W`%Y>sVb
zea#*{lk5vT{xg4!7Sb#Kp(BzZCZNK1J)fn!S2yfuMQQ*%0ON&cs(B2#rmFcmT(&QT
zc<^eeX`;3r+67GC1wBa?sufoitSaC-FXHm`tAHeFriUQlBZYcCK<AGQ!0ub#?eqY!
zi&v$|1%GWks3MooFK#Lv&%jGr1aA-OWBDN&;A~iVp#|9G7b;12oJk*O=y~5J`>q|&
zcQ#sjE%38p|KRhw!0sD6c=3mhqF!|7A^`iZxqa&aM}0Of`;d#%>Pd>gw(@ku6(oJI
z`#dtPeOSA$sYgC&zLOWS?~ok{=239NZP^5TZ#bC!oPVPYa^NRmyFCfP#n<_6;thvd
z`>7*9SM>T^62SeAVD*Fa`&CJ7e*h`-g%b#EyS$~hz>IR7kVH#kcyp*?d1fUvoXcS5
z!;hi1G3}NzgkZAszM(IoPwV?DP@1!F3<olTOHp4hNCpD*D?Jl}OV;LQQIV=qq;&pq
z)VkxX64{M9c*>BqWQ>wQNi-;RBsAO7F2#$yLfIy-uZ1pwWp`!^+TBtoBDW6(NgB$H
zO_DTLn*quf@D)QYI#U#cBM@V=mc!rKM)7TxWbvfw?dRr!q~waf&DUB3!G-DRxEdmq
zSpbc23lUVwdSU=&nGy;owEiQU0pfV*0aZjl7sBy7gOX(;pcae00&zb1*pyRyixPCt
z(ECu?tVgxiq|zGTh$D$0cN3GeEXM`E<~UjYaT_l5%m#!<?HOWCHx(^NaIRSzT@K=%
z5oiBN&i5|3ICZfeui7Yo7U8T}tY&-VOnd!F+WcW6<0xqw*{Id8r4!<s7zAi3h1Oe5
zp}G7qQirp9vJI1Xw`Sc0OSC18r{e^4uH0>3v6AF|H)5sv*9}}=|HyVeSbU<US${Gn
zkm<^=QWN|d*EWnl#yD+Qy38y0kM@NGsDcwnx7w!fNtG|;-6UC7!sE<ewGasB@B7Ka
zq%-d<5Q!2OO>HZ;+ITVHoJ*~OH}kKO>g!ZJ0>~r|tT6I<F-IeJ1e3HS$136Z3CuHW
zhB@<@EAZDLO9a5P4w7u@fZ67YRI+`hNslr7na256AhXP0r4iTyeSe>HmOLlKP(M#Y
zHQ<=vXrmf=mh`(C({)`YWSTV`Cs<fKFaUfSLqjgv_jf2CHNQ=xd0u!VzL}ZsgSj%T
z>wyE9P<86jflTr;R>VUX<vs~Qw+lW(-i}wdBnQ?JZI6<MR1p!4@luMc#y1<`y>!S!
z*jDmeJ$ZnEs~Omk5_bhH@M${hdg?6L3ifl_+&!u5@{yCaMMR|dmj1%ed_ikz0Q;J%
zGBy;&vl?S%rva#}lH^7L9Y~!ELAnANZ@tKiUmpSQ8i85rl^-5XAx&No?s7e4e(lU~
znW&GWnZ^8B%0K{p9>*_E>PJnOg2$Va1PeYYVAj`4JKgKoB|UOLnDCR1VpI;}MREQX
zt77X6c5<mjYnY&xU+0Kr$=)#49*#0{+N%MqAO^;G*45C@W2}!b4SUz~#7_Z5u+>hP
zTf~}Pjo-!+><GLeRY&8-K|RbX39Z0?oGLKu7K^kXIXe64v^c;$+{j5~qRLm|Y*YcV
zv?vR=06#YT9SVJG)1%`OjIvzk)l4?@JRI7l#$J#2HxEss{keDDhsZAbDWi&?kZ?Kc
z>=fNip7su`->k|I$|YY>vrN3r8eIFeB0qjh?klkkYIt{&R&74ht$%*A(DEE))M|b$
zfFA?b4JrV&Nu`;USVaa-h0S6-FrUN&5P;(b<@Fk1@CHM#kE1$#I<ueJ6-Giy;F}*a
zPFFFDzu#(qH$1>(3;{1NoebL;K%doO&}A7+w=!}IQ}n6m_Z7IHb2w{X;=1j*u}-Ho
zIBilgVV4ol<S6)EmG~8@at6f8P5<!Kd?`{r1D7tShYPEQiQ#Xv-SqPGwv3H%?6+{%
zcjIQhBWa!3?dPrM1<y&J4wt9EABSu6;82s>U#k@Ky-$sTgB~p&^71ds0t{+NS~vU{
z;FciJBxhgt0mC)vw8@rqx7F|Aynp*eVBFY4w%**SPhfTY2!>|T8F|}(lC|;+uI%;G
zSF<xiN7G@w?ONA9l_^qULFO!Q9l+kt2$9`g9dwnr4jAN-5H9NdqiM9_jOnq9X~xw6
z_z`tGUbs9{yFiJs6fTF~6fe=ws@k|5X0FZ;GZ7DvYWzLE0E#)xcs6aLzeR&0S|XFJ
zPJbBt>}W79L=c0O{}?&D29V3tR5d&+u~ZRkd@|)``@A|$TRT;g!$fr%eJi=<I~s(X
z>PQ<JOG%??-i_0Pwm3JAHkpU){xx8Z;%PRlbSh0nE()`3B32Ar(vpqZRjh<19}I7Q
z8nbKQKK)U!%hv<jx2}_C#kWNAq7hiWO;p)ut%g5knIQ+Wih?k_Dj3$8deTLPt3j5g
zN+=(eqQeJ_s7S{#xHTFK3a}{zy(HUG41=&}^}gl1_*)UJ(E3>i8DO=n1$K#$7vBY@
zSkW{L$^u#%)(`a+IL!*f^1fqmL$bELm?ArG)uG1`avNP?Y%t2W{!~=(3kTpM5pf$2
zGs`VlIOVSN`v4y(5gT9eZs#VcAd8-G#Y9W!UN)c+SwU%9GjfN;4X^Z}F!+TIzQNo9
z4XjgeV3SUmmSRtwNitDKa-*&=s9UvwE#VrIpzJnAhIFPbo=#{HXXYW*cE%{&B=J34
z7?ZV6Veq9H>sDj7ulzwtNXJ5s6GRiJyL8Rof_F~7H0E`9iB(VHCLkwU5{@TTmLzlw
z8f<eRV506YjS$90DIDHrr(11hj~>B5;m5MU!fe|XXA4MUv@KOaa}huaxW@#IgE@P-
ztaqtHib}G6-*JIpO$Zu`!&%#n!jFkIbaj=kRFt^`G#yFM5*B)0g+aJLx?+2(i8xs@
z;}Zt<%@TFUm>K!O6<RQphDv43Zry0$U4;qSVOi~>cZ?I7))S*DaNvFtW4}3WZ1H|Y
z_}Xu-v@p!6G~**+2@~2SV#douFE$Fl3Nki+)Ik;L5>}zZh>=hfLZRmfB!Z#m3QQE}
zf2OO~7_sOy+`$H=CdmU%%vrdbh`342iHX$87`9I^T4(7Lhn+b+&Q!w)(Z6dFEB0{q
z{?HPz{$9(7dIpoqRje>#WeIAG{yve^-_vg-f#{53d^aNqrIdmq02~xAg_w-t25QQo
zr0GX6@uOB<<dOHbt5l5_Ojde)c6G23RbbmrCxbA?<_?pbK4ka8c|yJ_-u%IdCMK$q
zY>-(3@-YG?UQR(26m8^40ibth9ySKHDv-$d;mG0^G(cLCJ@)(cCA0JJ?8s!9`$QB1
zulx0MRb6_%K5V>+LO@IOEH~=U&5J5V+<3&ST;nvvEL0(vNO~lZWqKmcUtoTib?WE<
zlVMX@wV3hlyyw6~%v5<*nDOe%K$B1zWbk5>5L3U@aWLZDSntKKRf^P^cIs%MF~o8C
z;52P8Hg^z<G5wy^(E=0`2=j2o$tWlnnD&~lz|&B5;BzE15Nk#hY=h40b9OmGO2e8>
zK<qb==z)XIQ~WRy-`mORj32gQNpK)`4JE+^pVP4J$_SU2L=i?V0flJiPyo!L0IDYd
zHI+0d`HTH86B|kin+~A*@4&U!5bDLy%f1nK-p~*B9Z4W&l19bWl-#<Zwk<`G^PZvi
z+usNeMzE$J;in;HoQqrgf=AtO-?sy3AEVhX4@J}~CSc)Ua8c~B!DVIB2q8Ao6g>eQ
z=hylnXNA&kq$6jCe$B-&EX3@w&?1u+K-FBlloXY8e#ogJy=>sLk$$$av!KA+5e1G(
zL5;g<mchQw1}jA%GpPC&3ik`ZO7VuaL;KQz&JNO5W{*e0rgImq<WnTZSsO7gX!Aai
z9*|`~yXn$zG!n?Nh|VW<hdRk&lLqUV!0DY1gnqt`MKChR&TmQ+Opy;{I$nrZtq^Mz
z1LG-+>wS84M?tFJucpFl#@gAyJ6!DjCn0MIw=$7+JEP_xYqf_@f|f%)ZDVrlT=y)m
z$(PQ_&py!fs~SW?U9%Wn;JYq?o@8~|-CskJ9$ddyzUX9vi;d5^kZrgKxWg(PtwUC4
zi;;%p)vO|n&!!*Xp9d)?JXHg$h-_~ob@js6xDr-Eye~mkX{&5PR$-|5Q?9Mg)FCU6
z{c4qsRps_Q4^n6Ns75w>D;EnZ7srgN<x>9nqZ=8|)AL1{4sf>(8J~ywJBYZd0pgEB
z%gZguSXuU~J~1+he$LxD(An&p6NhcC-MQ2h{_N+INJ<!PP;|j3e*!Lq4rGGJd>8&D
zDM8qiL(WY<Srq5?`)r$<8Pk%J<Bs=-&;2aS?7UN;HQC83+v)EG9xU2DZe%8;rrVqV
z^PLw)-_5-M9-&2Mm7Fxs0c4iJ^X5;T3+zkh&u3nHkTtUT`o$k$F{&f#<^)QY4`*XV
zXOR@Q!Mb%)O?ksAYm8sWwVXZ6S-*bGgTXm%6i^@KrY;bbbj*4nsA?1JSkLZ1NM$3d
zp>8gL`7Ii61j5y(x^kV|cF=nwcw%lWf#K++y2m=WX`g0VeW{*h>`){1!V1<4F51lP
z)Gi>@tr&j>s$DSt7NB;q-iGxUf3(_$HK@M@riY4<IpTvDB0ct=Riw3H)vVY}?*RyO
ztHNkw^&26j^PN>>wchbpP9mffki-0LXN}N^3cfsCwFg;=>69#!2|5aCAK9cHXL*I9
z_de*NIIi?<&;{g2GvE%ZH6YAhi#fa=LaX)Y8wQBY&_uJq4yzRq%sW@8$b#rv9X3|}
zdI$=>)3??at64=AE$wgoS5PnR{7Q82gy(BTxmB|rDxI$s{f*heZk{QxiF(#G5%+<Z
z7|Wz_D{f;;r12{``$-bStXZYfdv)gZeBlGb+CA#>Frg3RkU1qW+NAX>wB~xsgUA9K
zekk_fwn(9<D$AtWTV%FBi$*3i!B}^1GJte#5r?S`a_`-e!Ny3x>-0NVBOS{0*IJ`Z
zo;UQP=?z9xA{@x%CQBr>9yc;V{wld12bn(q=`Tb0Jai2Tcdt-@h}2K#%}9!<r3!C_
zrgNUrkCt?{+{m2<Jg%#SD_!tfTsuHqwO`{e(>A=^$eHF8O;-(1s=Y6T7dE!oR}4RR
zV6c<%&OfCr(nF^Ov(w`*Lkn6{-tR!+=ajx45${fEeBo=~_8KKk3qhNWA|3GjfL$j`
z*j|IRVxcTdb8%JzkwF*Wc@=Aujh1~TRnoJgbl&1m!?~DRN%y*tdT!X-M%t!@;~-<V
zYlND4K+&gEoml7?B(hpCWU)XHS@IeFgwBf*X%_ol%fY^PPok+CJdeJr1ePEcp?8uO
zPy|8MDRQq8rzylafnq<LEg3Ij9O>tiz1FM_;1t}ki6l*bb#NVJm8N?MMZNc;tXUkX
z=5y+#hnl9#`AtpOJfxvnB(4Xmc4&>TEoTiGz_m;mV^jDy*$axMQJESnYFiFxgtqXq
z;yPgDPDNd7%L&JF@M#8d$MkUm5dW^?F>oZgSA!ZII$TXm!s2@IbE{_1uEoCZF1l4J
zMpnLcG<SU`HIw$>b|Tkj<c+7rfG?nrTs;Lw8MW~Vw_l6<M_+)rX9Oo=^!{FmZ=P@~
z1H@42B>PuThA6Q7vhe6L>pV@~W>uMl#zh#m5)o)A(8p^$A~4FU?O7r)$*V1iVn&5q
z1ImyIXkQHxPeL#pq}=YqFTMy10xft3c_fUYKsj9v3iQ6+py-WEC5LH`KqZH>44!{C
znBuj-GlODxe;+2taRp(kRxqr)xM5*R2j)77FykUcZ@T6i8!(+HiVea)RM89o!aDS`
z4j+Uy-5CMso9pWt_*x&d!8dU<v9U85i-r}oa`|~M9fWnaY&|J7OZy>=K~`;wy1d%;
zrf~Ed=S*r=2*2p~M(Qx%4(6R|<ND7k_ahkq+n~DPDGpmTWoyjwMH+8MvACZo$)sCh
zx*e=LdUbddm8UnN0G8a|zd{H-OLf;dBhm~(%N|9e<`)5Nh1*5<@4<3g=2*Mu^sRex
zw`rH5i#q|gpuoOSPk+l+uK(<|!AgSYgxm^qj~27gRNB<FicnjE=-7fV;Zm6cgrsDV
zChVRTUB4HtZTvEVIK3vZ-2V-*I@#VMaAwskbL+&hMbTpZ*h)jwvv7XZEL$_EpZSy@
z!wU8T5hU{p-kl2HD!NuzLj(k=@P~~{I-PX7ig4ZVhfJ8-Su+9!%GW(8cBWF#glNRp
zkeWkSJO<^fRtyGX7H4&|0i>s<L!gksSr4x_!sH=SDONm$b>&xi%p#-MGn-RYy?4gZ
zJ4flc$xqBEtV_2tF>&5|6W&tt4OY4(ZiMz$b4u`Gl2o{XTvzqhkX#Ma^~eKVE=fq=
ziIVEkQcqigKCncIkg0bf;y}@We6Zu6fUq$z3Ere0zk^J{H+}6$3n*svHW~@!Lr5+L
z^3>H@*3_26st_)v;XHXl(hO#z^aRp!GKsnW{V^q}p<(I(S!9%c=5C#E=N>mkDkHxV
z2yXcMNsV8i0}4T7Rb>uAL}spAFOVykf<kO<`EGLY>oVwJW`<UIg@K-xz*z+}ux3I>
zLf=u_3KkUndD|-%e%<ArXtr9u&$yk?1q=8-xv-8SLX6H&67=H}@$c$Wiwyvg{R!MD
z(ugQUYTVK;^l=8K-0qQg%JQRXwd_3ke)Tbxqy2vMaIJ)BlMmu^KG=Iz9Pfz;##0mF
z5|B}VUPTCR7j`%Cgaf@E_ECcQ+BhhM2)`!#8P|}=LzCtS2zvt!ouuT~tjERa1{71`
z_e4FYi)HR78b@VuA{?dG;}=O7*{g`orNVNLRIB53?@EZ=rNgq1@Tr3X1~{{>)l%2`
z$4uy#Ds@LIy(N<U(~o%{Qj$2)B{|9sQrI8i4YI8q1(DN<T?hrUm`7Yh{E}Rf%CJm&
zk<Sv9_Vf@z1N%A2g$Z8M$s$k0Aw7Y1!aa}l5Q7PSaQ>tV7B|e%r*=uN^GFW2nNu{+
zM|uFx30FG;<EAqC{XKzam+;Y6;Ec^u$UIfCb8OQDT-i)&mZec8c+}jcb6lyHB~m~o
z!?2Z(v^4=+GeA=TnutEgK-M`+j#*gT5g|y>iy2&qyiVCAiCm0)eu&p(GQY<^7r&4L
zDJpo>)W$^#F%hIHYs20F#AOx91-LCsd$TVT`sTHpU4THPHxLOW@ey87UOK%OHBZ#q
z2p8dSf=k=`Yh_K<nV8mK@Krd**%Yl{ttAFh%w|A$5w`UNti-4_fSw3}OxVM+pdGO1
zDU7C==r{Qchml90xTqs%5WAuv9<n=1piA1+&xcxmr9%o=kjL<HVB?W7F><e}eK+Dk
zWJm0RpfH0N#gsG|(!|k<=Z2U%nf$M?Pd5K+i^UT;g0&SM8Na2~1^2IgUkOZF@wb&i
z(l!IUzM~p0!Ajh=gz=5Jsv??fYNp(f5<Sb&J5}wE(u5$<aT=I|s_9<^he|5;fEK6i
zton!UdEjU!#q!r1;E;s_wxoJ~$nXH>NvdAOEUJI~8CE)j&g{p65=nd@gbjW+h}kg}
z!%wRsdXx*JKFUJ{Z8wM+<zq0qXWxz{ORMTMt)~PK9YS)<LIjsE(9tT8KXRa>oQo&K
zz$p`EFsc|LmW2FvH9NI>vqTW$=-J;-7@?n05@Sk<0v>86wc;A>EY+q|M)ZL&X9bPj
zJj-_DmPT4Z&%t4GrIsDM*Ukwc#89CGx696=gI@&H%<0BY;m;5V-XubAGV5m}k@DEf
z0?R@lEF%P(WP|u76NS@YU_{$P(zyVbolSt>T_7e3-yVSfyQu7zt=v7-+2#3bd+@7g
zRcV=eADiYu8pk>x!39QeTNA09fIzKA5}d;ikPbM1Y~pPE%E`CjTeGQ6X!1@gtnzYT
ziqY<U7Z-By_P`z#N!%;c7-nHiM`3E%V6z9EJQom1!<?jSc?&ymeKKKCNBU+#Y5ME0
zn|7JOSE)FotAV?dq&E<&SvY@pD=n|JtD<!vfKK-JK$;-C*4eiBMU&E#yi5o*gxkbw
z9Il2hAEtF8R8Js=kR>cMOL6!Lj>N1R=1cEx`D=dsGy-TviC>KO<P|=-^WrF2(E<ly
znLw8`Padbfasv-Eq8;(X+H-IZ<s+v|4KzWXg*Gd?--A<;A$M*gi)Zpkw2lSqcEdE3
zLZbxq=ZAo0=)f+TBNtr$y6T?x965T(cQsV^E0OmcUjQuPr=5$)!3j81W3_))U=3#B
z$4&@LtO7m4RA~DRALbndS*mMCWg&!5^tV7dv|;1z-i++x^bv=K!_D-Tlj4tsDuEKW
z_c^e$BtiyyAoH%6nX?vAcJVB~ViaZC;Y@Ifv+ZgS1v((pa>-r5EJI;NW!mYT<prK-
z5C&Q!7g)bwU=&Zfz(grvaDs`IXO{zRASGH#Ib_u=!_^d(IujLnD;eAY7hn;!*4AY}
z8k0V0od<>K#gHfx4^4o}f(SCx(S^v+b5{nEARAb4AOUY6B}s;kfDW(GiO=6@VTZ75
z#C!wKhdGF`gxoFtB6>OzXv4Dm`VQ>fzZ(it(}FXRrul80uU*6=-E;49cTD;MA&H#b
zxtl=Nq7~c--!;LB-;ITrH<OfihiSw}_2#Qp^FnX+jdDsRyhbE6lbFkjN{MPjA>d8y
zwt$?d@wS?hQ>F}@LndMlFhSYZV{a*jMI0vP5R9qmT%>E8^!j~AsK*{mr?1ZK&kTnO
z_TW#V3s}*}sY*vso`_E-wyHA(s5a9G-KSIzb2x0Pz%|fv*Y1P5t;W7clgD*D&VB~i
z9N*OmT~Udd(Cz0w%E5Ifk8B?>h4<{zWq-_PK7u>ulm4VLWAtY}(xFb5NBcEkk4Zba
z<e-%XUCi*b)&)__;Cf*j1fi|-h9?$rLjzPxB0S(Qt08DU*{yIN#F%dDUpzoKy@<A0
z>Hb{+pxRs;mQdP=)={^0UCd{xKGKarV$|+{7>b1PX;K44(y(U&*tudRctU}|B87-p
zRIM2Rft99P)xYk`l7RYVV;cDNp?P7*ZIk^+8DL+vxVBDxfK7AK#fJSl%jnWw2g0}1
z9?UQ`q_4hXrQ44XYxIc8|Jp=Ed$z4&Ji2w<=SsX5)yRrN(JmN66V61M{G~k*16k7N
zN+c4JgwM6kAf~MXq6t-bqCYG=avNUWK(Kv=2a~~`!YYJlP+Cjz<A+$+fq!j0Ng5AQ
zW-z(N^o40Z$cd&xAtsh?|5@=Nu;8^7WG7$~Zxt>02x$`1ra(QUiSX0GN)TfK7dfl_
z?wf)bs2J1=%d9Fk-AK9+IbO$dyzp1Jzp@u5m5Xs>DfmuXyCVkZlDf}sl)6gIpAL8}
zwV>Fi0yvRcuH47irXAzuYk#`HLBS*@VS&Y;87`%ZU1!n)!UL+O=0p#FwM%GKC8pdr
z=&yo|&c}zpI9NOb57)M*V1*-=6^g(xiHJjpK(GXCQ-+}jH!ekwfAMh%H9^>;z>WoD
zOtGEtGdOh8ISa$IOmh$}B9VX{n>n3b2o{)s=wmG*Ydq0(E-cI?$lwQOjF8ZGeH^h8
zg1c0)86;1zoE&HrIB-7Fr16bNTx8R7zy+>mSTulc#Uq?T6YoepH+Da`_|7iILKPvm
zi@t6}QQQ^gFva7UG5c`GuJ@w*c<VhkUhxTsIQ4+zW|B1*=Wz`CBfPI(40sC)(}3%d
z@+);tDl0)>uH!O*AC@rONI-6Wh89Xb^OR~?%!&$G6tIM-ujg!orx-gu-)R_hKV>6F
z)pC+o-|H%Z)Dp0(_lOq~)T+|KjIxD1O%fB!*hfIFR3$t>fUhJHH}(rzL>yrp{BeeQ
zekVRRw4L;Lp!eWXnEI@W)07VIRuQO%EJwehgOZB>Rzc=Yg3#X__zi_n-5DV)0K0N)
z*qV!`2mnANe4v&1Sc<!fMxq(((p0L&KrAe{SwxeezK-*RQUFOstmax?ei`mnvT5vE
z8Qh;FiKC0mn`E%}EYA{DsKuoTolqAC2PO4D*BMC*rP^7_K?k+QSxVt8f7cHT*V>HV
z?satkEG+6<#K{^W2V276;;(XHMT0`P5UsEuixU2bft86sM4u{Tpe5l3tNmYbOK6KI
zoMJC@)R*Q&LZU|%zHruv_qCY{h3%S{I==j}TAW%JX4Tf4*XN4Vvis8Cn{oisOf1?l
zdQ8p0e07+ThfOU~uLID;jg^T~g=Mwgj^=B{v;g8Vnbz4Cn26n+VR`v!HJS+-*;q_B
z;8xXz!Z^)2E|OfFdzuPoENAPD{Mz;uv?#01iAM9Ic&B9i6?2H!2dm@@mbJAX^@IzK
z1V2*pj)9_S^sbxFH1+(P>#S5x>^jM&OenOhz{^c2c&+$MQ)b2TSD~&#pO68`RjYdU
z<V<D=m2>5tD#k!%jNkAVt7d)H(UKdGFKZT@ES4mLi^c13zF=)uwc6kxDlw*NIF;e3
zLf*&djuaYJBLzl7{4=1*RKrZx!O5CVw`|bPvrmh8eBF0B-yc<PpzWNhI#o`P{mee7
zc9Ng=Myhrk+6*6BgkjH#U+9M7F595$ek|JUo*F2v`Y8K<-2h*s!Qe`7k@9Sa1L&iY
z*3m-`pg0p;U-@IshU$lfdvG~ZCBq@x&fQyWq$J0}4w#mhLfG3-ul!`{xsq>;d#dq3
zry9Y02zbNZ0vV9aIMinzuHC#m7ipb&84mKw!UKE5s1LYFX?|0*UA25-c&26_8Z_JT
z&+L*M;WSOZUPqgu%d@bW#-!KIK+r~%peo%kymo}(ssS7wsE4%)V;uv(hYm<*sgkv7
zUi8flq(fp#S@jW;%3yk9o^U41G5-Ec^&;N~XbPgG1pffG#=+lbJ5$uRy&ktFDL^UC
zHzqN~MY}kfXpxBHoG#2M<OZ9MZXF#Q3|TdZDo{BnyO72)IV5PSw98>ewJv+{eLAr^
znW9p+lbnyqDP{&ZnQ~HqQ!Pacsohv`0O<Sa&W+S|%%J5|?uIx?X(U@};3Ovcs)yv?
zyCE5u2#2UalP*{6G-1q_>PcFYl-_Z7Y6Jp76OF@}mimp<&jl$w<GKU#8kWW!J7c=1
zi^+{~sFO)V)kb6%o1d>czpGnX=iyT9VZ(F#3e-<g_iI=i_+UwLurM_RRbK86xf$Yg
zPFmhs{N(d}e`V);^!<I4i$@mlGfU3`6N#AsViV8j*X_Dt@9-t=Tkhv??GM`?Y}c31
zYxwj1NxK|Z#WyL(2Y2|FiR;+j&rA5rP#4$7!`6{rpQppO`D0h#=Y89r->r1MzVDZ*
zhTmki9ev=RqUK!Ad9Qv?#`?Z?#{TX(zg#-^{k{J*q7F{wN@m{G`<vZf1xO(J>Kkg$
z-TSZXAKM@My}xIkbU!Omw9O`t7O!!yQDrkHF7I;}lEyBIC>$2NMCWjNO}bR?bw77i
z6&9X?UUS4F&#|BI8nZKh-6(os*-%Kx34MKKk$1R9+%nbn)%IL}bn<;(x#DRWcZ2q~
z?qGYWT=R8o(;YsWXIq|<Cy(iVkS1S)&BXrZ`Rw|>!NZNnevlL1LFGW1Fse(B?3vAS
zecYn!=Uw-EUhWcnS?H~zL01*!^!bsfvJxXHsYJI{?K~~j1D!YXx>C6$CDlTF^R7pu
zviL}`+WzvTN8{G}0R`)&H`fz_%jr0a?*riiof~9W%M&xl&FOjsd}~}vgh72vRakH;
zHA1rfrHAkbT#r)M65B(Vw9HJS{8@<{Z`37=_o2R4?}0u(`Qrq{x7LBJXnH!-uBE~q
z(+Yp?HznlEM{AZk`5cP~<Hr^a<NA3;y_ZCI{a;4Isy&j&$GLzrg1P;tcK4S%c2xW2
zF3qWP-pyDp7daNuo(tC%bC-(EBk*3D)+~=Mi)VG+PLI`*F`d&KGtCaxYd&jGylcm~
zeS&^zrgny26FVK<N)kD%>$#>GbEQB?J3ZA7(Wy|&&+WO#E^S9xnftk!r#N!2rP~j&
zx;Hg)TC<CJ<ZgU*?H217<t=W2*VZhv$~hKL8oyhxepvA=zP_exA@s-n`fXJExq!TK
z+PzODw}b9=OXdbKvm-3+#>IYd!LvC1!q`!(B9szPn!y;?T{#THSMgZ%?yd=&s__gG
zLfh_j25FQKU+ZP<(+_0kNA(FKdvMztC=~LuRKu38@Xex`Px~&$R^v8iqOC}*c|s@U
zUbi}=5uV2%jV}A+P);uw!fOc3Cm!#HojM`w8ZAhi?U%xByq53F51U`LDGxWDpC%EX
ze1dC`uOpEabOo(}+{dvcU_){+wy|TPy!}u6Z<RA%qczBYI=ITZ!nR^*?Hs=EKwV+H
z3_r8OSbNNiay_)|@1I|LcneyISP-6cD|rj#qMXEXFOOTJoV*N*;8gk|JH8AP4Rxn2
zXC!zTWV!oaWDd9UGRYdPdM-X9cH@|We|s!Gi#$Ol+WgkD>GMf-pMIzVZhEb}Dt7-l
z^}$5^k{J7V&HGvPU~#rQ@*A-BQYZn+*v81w$-!9P`p=oIfdv!`K0W@QPkelQ77jK>
zmVf0;|H!$y|0L0gxH*X_I_WzZ<Nq!ABh#n<ir~`;3E(r}(;4c2g}l6fl>ZLtL~U)H
z{!810hMtBVpY_YE!aqu1djAxH@juS+>6F~<jPdE@^-YcON$?r|axSm$VEko^;orP;
zGR8*c`hvD@_?llL`mcg>;4?7N)8lLZr7ra4_)FgrpZPx-#2jp$?f$DUe>?e0`X|fR
zi%#*&wS&Hmqun28hVK80CGedboQ?mD34Lh^8@rer8Y_qi{t^CDR|R87TW1GDV@Lcy
z?WO?rKUHJ<ivMZfKP@F~Y-8$VhR^<=Vu_ktIT<_P(}`MrwXCqQp{>zhp8io}z-MFT
zVEtq3pDuIDx>WOYLlJ4IJyTrd+2rAw=ShboPA5iAAb_k53IYI3LKM!4#0Ny)s1q;{
zPJ)KGLr~X|!uJa?oxQ;#!4GI)Xh6U{Kf6N`QgMacnm|QIm3Ja)&_Q7%P4@HvqV0Tg
z{N26%(X-B?tX*5fS^Ju;C`3*mOcV(b*H=`IT<ZJ$zQl)YP)#6=#b^Fl1>jE2n;KUp
zDp*FI{&}*1$zvi%Fc@mx@H9tul<ak-lNtM<3dukx=VN40zl-A)5_fW3UwdqHLEl1E
zyyAnmPLWtTo$+Q=%z&}ZR;T?w*d&1r$uSoj=kkb^SSp*vm7P4!RQG|_0z9AVW#plI
zSgU6J#6aN17%v`Prbp5RRjw><H9F>le+R$Nk1iQygl%hfAv+l|95OsfPBjKasxCni
z#XJ+#c0^SmXz%@dD$#*6zbH*72~ASU9`+nym5@O)&3#w;V1BZUSXZGQW!XVQLnD|v
zQ4T_X|Aiw-p8Vh&fIeyPi$QRZvRJ_dc!IcdqrO`+7u|0JS-1yUGw!V@VIyXf&AKrR
zUeew?;LU3=wnQjT5_N8}H0xcs061j2S+T9+fsD$>x^y9nQ0DA)p^FdRK?6KQR%`Gv
zh4A6H$4M(q#zxf^x|e}Q)8Ib$bq%_DgCeRNX$X==wINEDeZzqWHmej&g*0kb6)I)O
z%XcMUzBy@*eyfs!%EDhEs-C}a1vRFYT0PJ=3f7xWMOV{DYV%=eb$jN_d|akbMy4!N
z$k+%G&TTTXMZ9zp7V-@(WPw;cj_yy=HUw071JY9LQr~H1m_?YwYRRxOxj(B%bUmLo
zmqmNiMrJM%&o^xBFDH5<Y=QkduF}C<tT^I+BEBSzIu!M0>5_4pizNtscUTenG2NWA
zc&XgW1^C|6_Bi?gtC`Env&?7?KE}wis*XF6q|g{<oNxf=LQ%ce;7s+|V)Nl&v3CT|
z7nZ4XSSZ}h9@w5^Vt6LdIABmhjyf?U{YsrJmRmBj*3csrWeBZ~Xg{x<?;jzgK(n_*
ztxYs|*|0HattK0|LYJC<nlb;=+1f9^l63CH;kjCh&!PjSv}Bwg+vaFVW*vzcrJjh;
zU=yv9#<tTY^6lBaQoCjfVJ#%t^02^eju$1-w>T|E^F<}wcaatvmdr_;bc3K$PuTJj
zW?r1tAu50EV@=$!i&H1FfQAhX^Bgu-G!7!0%Q^MRM$9{5OnOW9*O`uK71dI<q=H!l
ziXLFjmAGP{Mnuk@Gz(`tXFIS8U4oEfk#x$KrzOur&h(aO4b^hC`KFK{GjTBfpddGK
zXi}V^AE)>?D;Q^3=g=x{#*CPh;UDCz5wVFQl>6B574Q~@5B1YPs{Woy%7RiwV{3*r
zBO4-1UL#t|TCSMt<+Ssu91~HDs_Ac_&V@a5>ZcV>s;A1+-8J1;7Uw+Y1&bCu3gS@h
zkuD`1W(FS=Q!3^yO+E)9rb~PbgmhdI_dKFx^2`mcIW^b{86%>swti&d2OIZ8j-2q$
z<@5geZ*3%0jE#O2kC9B2-|L9O&(Nk9sFe#JrIt}b3pC(D8Tl14jN$IMXg4b);8xu=
zv#+{BLsT<e^hHppw)54#aJ3NDDU*B4NsA|B$&Zni>h)um;U=}Cc}@%0`l~gy$Gn8v
zWV6Q8d8-yiDbEy|IUT+ARZ`>Z7SVMPUHx7Yu4EhywO^Kf?5Zq0XkHto!)K?n@!*TH
z9(^Z5j``@<`S(hW57LI@8zbQ51NU*?`G@C#$^meNy;1XehRZ=;$qh3YQfZl4=V8Zn
zG>VnJU1Oq0s}KP@=ShxH4&jaGqDGFK=KR{LWB1DGA;{sDn>YV@l)ZiBj<p(9s7PO-
zDNSJFJ9xEBSs)!kA_^n*K|*n~5kn!tU@n4d8f<DNU15+7vx%{SX4OkC2^^B3GkX}Y
zvDw3!HbMlU1tCK@1qo#dmO^Rex^gpu)w@JXg3+V%L~}=qWf-N*v74#paVVs}z7=o1
zxXCEhIaIxq+Es;eEM-R2#MUuGW-Ob@ZVd#%$hYYgvld^ag-7ymw4XL8yAz?%rf*hu
zkv8B1NTDvPcX#<h-f(o0XGftQxRqB^DOf5^wMIzCh?8rfY00r~B8YUS-|hk>`$P^8
zX)T*YV?8XhL(Xo_h)BTOXG{ZCZPvHkHe%T{aG9e%=DloR?0%6`t>1~R<3}VPV52Ae
zjK8Y%K1z?SU0j0m`Y3PR&cB`;_*s(@zTVoaPBQhI;N4=Z=)7*dL?7&D9fJ8y0y`s5
zlAxCojdRsbk19FeL6O)R-rWMH>f63o!oV^907<N893N28Nc<ZseYcg)fD;kWRsQ|w
z?fm}0?e&Om?D2<$@0#w}^*P>1Cpl&eOmie_v~=Nok$I1~y~Qp}QU)Cb&}X-oxMN?4
zt`oGRa1xZ}iq?J=AN%3LK;o9K)&@eUna8hErSfE#nlkQ#1kxzqUrMpKZ=BBg-Q}W%
zC;Yc_w=!=}){X8Ns~+LGy#wf0_i@qIJ@~`funfHOkDybouK}8xhUr)YL=*~wXP|R}
zyFWlBMb1IjLZ?xw1|{qTsY`!7Lwu*I37Zk7!4Whx$Hq}0!9`jhbh$;SE`T>&!<@U-
zPqIzE5Yc!qawP|Y<JdgQf9zSjT5FSG7~IF)*rMPvxQ-NyXlSqze!nwbsCB>7IPxzD
z5`o+W;pY&^Dx@ng#JbHsX_g-==WSwZySwXfrdw}6Z0D_=;S<u(oSF3Pp2-(d5Zye^
zUDi**CC?#`iMVFK$yV$7R-SL9aZbYi_0$(hZs;qf>{xNEgtT2*LP4~Iv@}NEDP;Jh
zn4~%8uawvEHN1wEe7)*sP8xxE<b9Mo{;Yvw_AVT-;#Jdv{98r~yj)E})NLK6-tMFJ
zXziL>gy|%4_1XN8A_WbMjI-tUj_p<0=z_?tp;gt(%7?`_&IbU<JXeYNpZBugF}GlJ
zOHZ1Dng;LrJrpD@%2g^-Ii+A@qh}L{EgRru>H9!!=n23K2;knSb!4W*uX8^m?}JYx
ze=Zk=&exW<ia}%ucw3t;e9IO`E}Nku+s5=V+JT%tokNzRt-@;e^ip3P`1Xpo?f#2z
z7|*ld;9!uX5^wd}+S~hxFZt@s>$Q~B!~`^~jDxdBzSV^P!2z421C%H{9;#ERl~%*$
zVi4=^?}4moF)POUS?HH>)Y&)DHH(z$7xvH1TMKem0?hTB00F%90>4uPM7=n8)9?8W
zlsE#QQA9WGJJzKeOKi65x34Ra(dRyE!Xn?bekm@`<aEPTX86+5hQXVWWf;ucVHs{v
z#H;-}m(Lj3V^pP9Khk5ECXRGu?dvB2xU*C~N*aSJia2c{DER$C_B3#1#|5(~6Af%d
zQ}atQNuq*CLvr6dMn^$zYk)zmBNpB%Dj7G~M9T45!5oy%)hdpai#OGau}mv@A76AA
z%S_T!d_Vh8R#I*$@hQnMN&1)vg8;@N5+Ms-2r+XKPx<KPbXvJCf{!ef>Tp_eh0<0T
zuFp0J*-r4q^_jmNO1G}^UFwC@YvwnpD@B%nhiLp9aWd(5s+arDpRD5=d-y6|%LyN}
ze9H=?Q|6dIy(Bzpi#;=I<YlQb4~r7+<HWW`33HBEz)PVxzm+sg4DzNUHkH|*k9rVC
zMYko))Aty6Fjo}6YIE`9G?W&nb|0;)O%5c26%7b9NEATq@eOYh3>*;fMxfuGzH_FQ
zSMMIQT3Q-kZ(~_cl8bs&#Nmcx7}=BOVCf+M7y<xlLpnl5DxWQc>AKLDPIS?CX^iCk
z2n#}z{h|<G^HU?pZybOtZd}wxWeZ<r*W(4rvYiNp!~xx-CJCs*kz}|MW15)mi-=A?
zrr)CNn}T>nazl(4>b%)x0<4@Y$6A&r0oBEo4#FIdWm~0p`j4dKx3ju6gUsjZ!>C*F
zx2A+IWQ1&gMn4xcDX`QtBcMKF>N|H|z=JQ5)h4UHxfF@L6+*ZfzT*Iw;B|#pWZC3~
z_HL6ev>>zs2FJAN6F~#*AC4*$CRn)&30c_x7#s}u-y;@<A}Y=J7)UOlx#@In9j%W~
z-0ctjv~&%78d`)bEjj3BdYDoSb-CiIvtN%n9_e~Hn4AaA{eJ9-AkE!#RA?K}Z@Ae=
zIqutRznpc-bX@ARfd}zkf0W+Mnu}Uis6SeoYXx0AJUA@i$p;of>`*a@UJWa{(wP!p
zCoC;fkkOkB>CiQmM>k_~m%pwhsM)pryrhZfi`9O-Y4*-=u&+C3(TmwHgEfvdF??%3
zK7V1(%Vpyp^#dYOzn(hg%`|@XPO+Y8-{d7V?q?cFz0_XHvuom}Jz51_m}tg);(bTv
zXCnqm`Yhw=<q@J=_*l+!W2%&|z01`+?2Br->#PvN-f#|&=h1AlcZm%aXQ@G7AJb-I
z&FAMaSLsM(ukgDD$5}h!o}r?+4>^e>sc3m(P~l-6pGPUCONz7Fxh{^Ai~I)z<aZx&
z$tdW87b4qKB3_`v*4|2ngK8q@CY_2<50#N~qb~C$;;+@{pKQ2zh`V8XNZP!ets>DA
z8VZUlP}f^)`=l2UGsU_bmo{6EZso|)m-$d>_ONh7_C>8idO~$QZb#$Mbvdc0DrHW|
zdk}T`)W~~2CrtMyMnU1aok3dts|0&gM4lx{F^%-dS8&@UlLsKR2XdMrD-~UhT3kz<
z?%ovMZBT8K-I|@qhK$!_XCK#Cg<7pyem3~O!;uEGBuWU78AkFM)QsUM%w7s_=J-J+
zs8p}EJ5FV2a}7<CSW2Ad(nT~!E?*+B*>0h*Rfbe)cNl%Vl1ME}l2NA8)oy5YbUA3{
znaq8=?)^Pnkij3Ccz9f^!=vkyAe+@}G)6sH1iS0E@_U>eGEsDo3$XTtU(1NVyx8zW
zm^1Y=p(asQ5*-K!INhJuUp0}lsb%eVY8<_{AKLD7fad;p_MEr<XE{EUr#617Q?w3P
z#b*`H@Kc;uxR{CGds2M~g~1}oc%sEHhU|iCzazW3`If3QZTClTQ8_-!M^GuUf6t;j
zi)j<tP(O%o`n$&c_Wc|YaulcOZ;afsfnODL)vpBUG}V(+t00&dRa|k5S|XTq8tTzL
z;N*y8N=@Wk8GyhMZKzL;`=v$5W`?^OYk8nRH#MZms!z1)^9WFBoZIN}Gjhu4p(<>u
zX!QmOZ^Tu9Iv6<t+}o9~ycm5<+5w}-&x(Eg%9z#x@l5}V(C(zy>WxWCq-4Z1zx`=$
zl+Uc|0pKZn>!A>Cjuo?9n4BYW1~*@PfbEW(#vEi-cpO*Dd55D8<^EF;B-E-L<diSi
za&iAD*@%?r9eXh>j?)lNA=Z-zn_@qoiVt04`8H{a%)Llb^r?n;pSEStWzMkayN=wC
z1L}8dlfF<VOevGjRRo1CQb2OT!#0=Vk7zByV}fg!4BJ}TDSZ(q_?G}w3i$msGOHN7
znU9~qqu(JpBHUxF2<5y_8OentFX!A8YGDj9pLuHXsQGIk)4@25pq7pjy^BJef}s>*
zs6?KVJ#VjXCTK2@58AVMsl3I`c6AbDC0AIISa7A+fpL|Lruhqsr248-0)!$fg$jQG
zU!xE^U*5@0`IUoIjFnj!>g2UFJ1g;eR0mjG)rRC1W`HL0y_EOMb+};iQu4`fGM;Q{
zR>DzspuY_t7%tlAvpvFhurZq0YD@(_f74LHNn_@y`>B<_VOsnmo?Am4;P*3VO$HKu
zh;HMfha@~E3^tdC@9yaGX$n3=tPN@bdXV?lT31-oxFSrf4}p!(4C|7zZSnUL85m8I
zaEEY&JJ(%!Q-oL8wRKvmVRl{N0qvysYVi^&hA5mP{OSnS7>qke`dIe?{ke3>ExZJ*
zPO4m^q=UvdiS2&tqlPBEsvhk~*V&TJlR-|*iy<+LdDEN{)?5l^0kPQSc$oPe6ETpw
zByfX5(2FNXlh@>ECh|-W^7%9@L~>zV?N(45LuScGu4hmu#wbztn31p;jNT}83v-%W
z#4uZBGFq^PFT(6Wa4+cY8+DsH;CB0tCLkNgyDCDDeZMZ%jt4@IjywEsjlO26=L#UK
z%pE$Jn_@q@*S<x-n|8mMhMn<4hIdI&t>N(0k-lO%rsrbPXJ%kt#G87*Nc9_2Ixi(a
zbP%r-|KC~w$FY6B5YGUmzI6c8EHFpMX#4|u>~E#)J}P~=dpof}Tj)1AetZyRwSG*_
zknd4`9UyLO(6Z3%?UQ?CA9jRTG0^O!J5NAcXg4W-+mLRGeYT+3sCL4A`p|I6U@ruK
z&ET;&8i3&ND0hKkJ3E9fJ8S|zdGrfV;DQ%y0xNVo(NJZGHywT!fW2sSwHP{%{gs}9
z?~4X2og)KJVEVD(Isyf{<^h{PI%suLeX{UMkSn(dk=LUEsaiJ%3_<piZ9py1D=mv-
zt&l5cK{T0$&nX5gTIP3C4D#kbps~2=^b~{p*&xg4^@x0$>Va6RTyJ5`>$X78GxRPq
zh`g%(SPp}|rV!N{!;<;X4-SLnaSdibchvzaRh{=ML95QdsN$!RpZHgyvQyplgW)FX
z4c!@%3W_8H>m~zqA=Nqt_oP6n>-FmWM1atsAeuiN`hh;B0HM+Pn1<;2W=4*|cg+ER
zflNC0W0OrT?N9(VX6Tt9bFYFhW$1PInFD>w^dU>!wE0mi0q`2baFgoY0lA@kBLTui
zl&989@CyZ%z5o`Hq3?$b2Es+6*WnlF8HUcl*9`<OG<*(Jr<d(h+i<@C82#0cVR6TB
zxeG`ag^M;M28~fX@Bt+HIe9<?`aT(i2o$nEY6mzFlHsL>0u#;lERP(5L9f>5jY?kz
zbcISUe>M)z+V4kXH)96@c|x~y)ye&CL$|RwGj)B(-`fLrjc(yAqzn8CF^W3dnVR}!
z6QIK*vo!(D<LI<CAB2tLLCoI*sJ`i(Lz34CmyXFf!;CK!YNM^ZH5F7t=`<EFogL8S
z$lxUTbR#Pu{=~0g5m&kiTrO~evEVMo2I4G^7)PBK`0Z;ecw%^v2!eV@q`2T9gD|$f
zSfqRCFw1}yK!m_(48Y6Cd>qM&Y(KMia!xQWpe~>S5I4I3F~8t04d6a4fGYz#Ncya~
z4TPP+)oHU?P&3jpAZ+$20{+_oEf^SZObtKyI&_eN-m&5uei?iqGa4G5N9xOW-(7;=
z>mctFWS_l&NwFF1{~Oo-1G4^$Ycta`{);qo{BJmx;SYrT7bZ>jf8nwJ4Zmt9OxOg{
zBZxeGMyQuWhJ^x4kOV0ee?#*wYr+F~j3Y!f#BA8P=GqTeD2GlPc;2dv4?Wo6X0y>E
zaEEU+w-45LV%=fX4HP)JW#mjg)Dvsm>e*YD&Q^s?U$<7bx7eVstOz&=giB?ys`G4c
zjD?2+NNCk#h`IvmtaYTSemwhtmpxGtSJn<3^54_p{JkavA;En8P3m~R<8th=^m&6@
z5Vw~Jb8Hd~eH#-dyECuiXH$p;hDGr7C)WhL!72E!O;F{-lp=FU5oOLu>EKs#?*ku#
zj{pu-S#_c;COkYMMFL*P+^|R?Bg%!D;#?-Fqj)B%-Gmo<;Sxdbxzz8qBDEZf_aX~V
z1=s0c@@~<t5YrS)=9xSaF~^t`uc;S}u8eMtqtYMfZk-f8l3Op{Vn<j&)nuO-U%S%8
z&+UF}-!_`6dielm5tqRK?>_shC;sU)CZ_*T5e$ET|9>&`zmfYt+=8&NqoISjos+G@
zA0YlOx<OXo`inb|k=9UF7oie1w$N8`R{VnW|C27NZ*6Ynj!*t~68@hwioX-B^i998
zd&d803jWP5&@j+5(&N)Gvohi{uyHVbu?$R%|F8@aPWo2nh5|OGR>t`Bf8`T!H2gzT
za4@p}75!7bKXDqyud4hhp^(0vxUspZ*%y=XW#%uDqLZ<;3O@Va`Ts=3|Bd{q;n#39
zX2k!)ApAF@@P|VA->vbtIcEc>zvvUCFV5mmOZ_Dk)OR%gi;VeywT!ugqmz)CzQex_
zAg%vToPqIg0_OkU-1vWW$lq6th|L#iVQyoJPp4{bBVglb{;%LK&#LA|PG*i@EDaOG
zpIZFi2NNs(Kk2MYtoZ-0_ZM~amHK~M_#<Uu`@>}YeXz3pd(OuGKYm%ih8G*tpRx3R
zAFND&_@XaAUn>>=w+18I|Jb0%Xa1@@%h#CrQ=UIu&mZ>bOY-&pi+uVbk!+Q1%>OVs
z_<!b_|L(Z|uPigzZ4d^6=$)_dB`Q%RvUcLd<eIcn)kCZF3lIs!7aX}ns`~ZawbKNH
zZyt>R?+kEw^BObditT*2N1hXdu)`f=T^V|fSdtubvQO`h*M{g(-qhARAq%MsI%0kv
zhRb$EK#tVT*O#+xz6<BOWvu#+=-*&nzh{`2@3#t+0;3E_4Z3^=^#rgS-}FHO|KZ%O
zrtZ5gL>!KALvs)6_2W-%210H!xGzDmthH!G)DR5^%1iV&jX<8Jkxn$Tp~)p0Z8)Sv
z)0N?pB^u(on)(nVQZlJeBhGvp4gEw?A9ZN@EQnH3aVEZM?kho#t~dCa-fkbb;FtY9
m@vQhGad3`8j}(#jZ+%PIhF(MxSo<MN7fUE*wphG;yk>vc8e*gX

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..e03efc8c2789142d0bc4ae68e80f665922019e52
GIT binary patch
literal 67428
zcmV)uK$gEHP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&532i#%KdX4kdZIU*AxWzEGuXp>vqWl
zgd$p25hc&64_bjos4;pf!T>dhx02$|dq`*1M!k9#TF$`#&O*_u)`&`lE|{zvbviao
zULesB{bG?&X<-T}F$)k!Mv%}dp;8x+r+)&{QG1V~SOU*5WwjwTWJ|DQQdn0!<cWYJ
zS6R!B(%Q@1h2X33{VGayISVEnu4P<}Q!^tG($LjplPw)3A?M_R)wM)_Vakn<`)>Z0
z7k~et&G$d9)1GO6EH;RHX|O*1l&02Hu-PXHk*I7GgE9kq3+fE&%~*vz!W|HW#1Wc^
zLU%^F?5rz%PW})fx)+HFsZndr)J8mlRl;>f3=mOO7*j`9sKffRB9MTbScX8c>gFCf
zP{5)Q&hEo?A+(_66$a(9oj2T=;Sq!wA>M=;l~+d0QcdX$DcGW=8JW!sdYLzowws&v
zWS0NQKvz1Wx=NTW^KTk_&&{-uufck-5CvM%T}z7oKu*qI<>a0pl;3uwfOT~w<@vTF
zaM37-Kc$(KWd5cj1Q?MyyGZ-D9jATB`OmNseM<gsI_3t6GH~d~E#u#Ige8Of=;s&H
zq_nes*AW{Kl}UeYThhPnsH)JN%xUeHjr*I9+}|fViZZ|JxO`;$G4L~dl%EH~A9vLG
z(bbWZ=i83(67ZP$nW4cS2hVRh;(R)9cGQXG-*#;6;~4uHZ~2dd?ROn{{&jUE<@v7T
zQa1Ke@@ME-pXcUpI`Vksek{tj`?1CS$y4}eWSsA(@^3oj(XDTx{r#6(|2W@&Cf>@&
ziT|69xER{4j=U<q-G`R`dfp#DLml|IQ2zLPxORXk|FiC)@m;s7Kbm*b&qNE{D8KE9
zI;_{tj;hS+-*z11<L>)er3mfYvs9Pn$+L7XtoL0<lyB$V`tysGzw5UBO-EkJgB?{Z
z$iDAry1Q4WYrDyR)4?PEnjJj!^=~`OT_1=!wGYZ~I~HI+I+CK0z~8dJ)Qz73ue+-s
zf7~f`6ciHpDV=3}+X-p%RAhc8O5}%X^P7&;fKGN4Wq#Lj-KnK0{Y+@LO>z27Cu&y{
zofv!9zUh=!U#eg~1NrAeC;Lq|Xl_&8oKe`{b%VZdU_YT6>^t^{QkcmL*(uxZ-*t+d
z<4tk=naQ^ws^o7vR>l)Mf-=r;JMv8g#q?)*Og>fB-*lu#+t^W*``eE5+7#cP5p=LC
z!hhU}+Hz+nw4d)fDNgyMN_CD8%I`EI>f&~(BenDXZAZL}sj>gee1s1j{*OCK)pvE|
zW;(y^2po032!2NV#OE8~Hy!bmz!UiA_PFTZcAWF$#ql$}W*={m-*n_tWwIkFN+tV^
z`akv;O}rcIgYw&sd<u1T6y^DNVL#`3V!t2OHkV1}{g2_cD#`yVU)Z9!3`V*AfRwWn
zc+|)5EQ4T$Opst@QcB~=l&6!FA(z$NVV)ecfTmS%wP{yCS<g{M(4y3U<9#y}B)3s$
z%IktwVry;&yU-%W{AejRRYtWjHiKxG;)ZK>MJYpO*z~eM$ZiN6Wy(ae?0I1~8@nkp
zOpxQll$lKX2V3UYZJ8fhicF$oH)W1M?n1V*46kFiWP<XwS#SN>?8G5E{%m~dSrKwK
zZHDytZrWV3qC9z7pp~3XEA`QkA1>3j@3zmR?6%KXb)UtnXfZ^b26yEU%P6npUmEV4
zt~;3f8$vOUo$^)wfu=-R`VgA3Ug>9ON?#4ik$`t{DkOJp^C~2FZF4FlD{XTsyjd9t
ze&tk%E#zgIgRZOGNqS+b9_w<`pk6EeP{Al>G}6^mWnbwIs@kxg@sAC8`(dy~NmnHo
z()F|e60;R->E(Hd09`<$zarng91n;RZWSLu<4?s0q}QwrD)g+i3J8Grje1m2gd+Kp
z2X9fzO_?m{o5wL{T$a)F7A^{1gCPpaU~>SvH|4DTqeb(egSvGs^o6>cdSb$_y%juO
ze($FIGx)_1p?!k17}ex(x=>vEDF^)eZqsRdvDo%aY{Kx`XOU;L;zVfo)+LssDS+rg
zUBadyqKkzk8&$y|#g}MAyk<1$62}{{DTp7z3$3w;Bf=Y68(XJfe;Zq;5U|R-il~XE
z6srS)6^n%boMYE!zF4eVn;Ccdo06@Bv&B_$v23?IiWkdv%cFRqY<ES3I0kNt_;C#U
z+&U%a&#hN-UJ)T7+f`oOFQg(YQgw>0Zwd-Q8E=(wcLdi~sdoh6WGVOqgcz{u#WRkl
zO3E|Xr&)!BK##Cl8wfhV79N1>-DY(Q#AV7b?qXv=NDFyrTVw#P%q=nim!Dz-aIcwf
zeR61ZS0lu#F$oDlSOG)LPJ*dkEnFqW!@w{wMV!No8fFgl8PQfq*^~dhdgQPw>KGx(
zi^NX3ptbLDc%QZJaaNz)__*}j`D~pAd~(&vVQpcj7|VHYebPU6)#y+*`@9qhm?j$u
z0m{v`3K5{QkV!om8<?Y+TelpIf<zF8xF`$~&2wx~5Xy`IYJ$kW6z{kw>=k!hJ9#m{
zirp${X9nO<J1eXdwW!Zteb&x9b-hoRiOvcty`u$?aRz+0iZeh^Xgl}F(m0LJ@|<4a
z0$ZtUo#)miSs)!wUW3r#fZ$*cQ4>4?DD4q8xT6%2J&HaDY~^w(RIfFpsE6=JemRCS
zC$FWP<ddRRm;}PM+qs2A<6C)(9ZAZM?P1a3FMcX4I>y2U%S~yI0$e7_490-vg$|Fw
zqX;L!i!KV;8Jg-MRHx7*-lS;e>RF{vWkIi?kTJQQi$Zp;{cevgGCZ2BQmznFZjVA>
z=7}k7!STTXS5j8mz$<J5WzZIdY&*d=$?XYWks@CQ+>0!#k)-^Tt~A7_+r$5!Y?I(3
zXF#<&l9XT4`vZl?SJ4lpG~{>WAw;>ls0(tY>W!Lqt9S_14b(Wd8;2X<a8Yq2D7n{6
z;T8uoEUe-!(ixyMEaYj}E$KimM-)rJG_OO|R9?ylvAa@fQm?gJ;(^%tMPZgpguxwF
z0UL;>x5~Uig~Ti*lkK%<Z(Vt)yBM`;n0_<BC>?ZTs0hwWi8FRf(?N2L-HMl5UY3LP
zcR<LY={1VzdzSf0N(@ey94c=fb~E4=58mZz;Apz46umOzC^)H848i$!SA0BbjoQT+
z`8AtMsw~o>mV1KZz(%}k%@KKLSFI`b*_I-8qFXI%3aDLrc{+EE3R*c{$yNzaS-01a
z$cX)LIWrq?d|0KE2&re4{{;J_RsK`LL|Uak0X2^Gz>rgyKOG7y^6BhS0t`Yv>{1vj
z67%emiNTkwUs_WDm>H|U6N>CjKr0sbs+7x*APr_RrUR*R>%yydDRCMm;jGs75?qxj
zzbfC{hf2P^n01+j;=nXq7E`$s-m}&mz5;2R0`ze_%WYPK5}c}2d73Hkt5)9YOTP1|
z3>!yj3)J5OX=KelXQ#DxQ<{+H;mBfuuS|fA&#F8L!Iw-m@d9lrKF<6ry!{s;GlAh$
zojfoO!X~jsV*b&{x{5ivp5i){kJllxWhv}<Cfcmb-y5ToK=xFHSYPs$3B@s9hSZ`Q
z!eJA-bHA{NmG2CRoR#l<WkF5+_f%sNRr~-Y3CvK2$};tW2FATjJ*oPDD4fJvbC?-y
zo|-kB;zRm15P_`nwoq##s-Pm%0RTWYq*lSeZe`o-xzp3t_DVD#{6!-nrE1)02A>84
zK4Gm`1ZHnHP-aoGr0$dXPYFQDD!hwuW_jXdTSL%6rC9-&lclkfvhImdXa+M~&&qFV
zQ$@XB33{TU>e+5d$k%T}Oa?J<7a=A=Yaoinn2;ceePF_L^oICsD+3`y1I-IQ0Q*)*
zij0Ia;UWUQVf~Pf@_&dg^L$TR83FBy7GWmtn6WCf27XA4mwN!keoP5Qs0U=im?JXC
z3OT$XRB+-l3h|W)9A{DpEP|t1U~r3aZs9YpLwFx1u(yB&i8iM&a)vy6EgJDJ9OV6x
z)yUFXVHMkjIDG4c$O7RO(AuKJ*n1_YSSk;TM8@VhvM3xG4)Cs*X}rO$-}v{kT3DBX
z%AmFPLSr$^pwL+IEp9?R^Q?M>kW?%>PG`ZKElLQ6;xq$g=1dCUck<*ttjnfxKH!!F
z?0mp28Mp8-H{p>HqGSCKn)xAW6z3fcg6+f+VZFeGaK?6S^@H#`R!LHLrCX;j=!AFy
zLTsV_n8I3t3bc5n2L<B#7llYb17E>m4^Ryg6qw_2ZiK>3QqHarhB{VAuj4bvVO<IY
z@TjeTycqFnUFZ3kJH;xM>Wn9e(N20o-)oPohIp@<Os5_1RcnHGMj1dW2(F9<B03dH
zyqRpN9k1y(1+5Hd7C<j56fO!uyyDf8&|1e=VQbljt%WE5hOUJ*Y+Gz~a<{37ZiHJm
zA@e;0!A!#Dd+@$!!jHvc)tZ3#9+bGTMkGFj`CAjt-h)%131{!YDF6sEJpP-?<#Yy@
zH9_hDQr?vG6{sSysICF$Il3qiD!_`Ym_7~|?`{EVtth`_xgbq{i6lM%4(G`W3>r`G
zjX8K}7jqJau2_>ub;&G1rvXdEWa1{2$i}TGyJ<3ccjOCL(^D{j^`7JoqI~Z>`Ap@@
z7G<68tuP3um<&yU2qM;8AEVregZE7C;X4!?VaDEo+1VJHB~*iw+`FC2!q4C~X-%JT
z1^WZ)^6ubFK@N8HBIF?6os9YKaM~L3^^PPZYXs#A@1(WD9fa1<3U?4%Lo?z@rfx52
zvwl--ggXddm?`zIBc|AzU|H|;h$e7F@urjyfQTWB!r*LZ>8R)T3W$)ra0HmvFCH`}
zTER>Oj`d7qG!wS!h07ux2?t2*#ZNQT_0gxNy79|+8Cv#0)n_w-*@uH>wfSYFhR7Sy
z;ZRu=e%R3mZzLk6no!z^ruwF!6^ktYMTaB82-yb2)*~nd;>uq9aM}m0z*8X^a(WOv
z_E;n=b3U3YT9p{IivkI|AR8v=@O<-{P3A-rRK!dv4amDU!NGMH$rq*2cF_y1d_XJt
zvIAIPQIZoAG1Eee>!=@Z@WFHxoi`i0hvpScWSva?Jx4LwBU=&F%mEDiwF@YD;IDPy
z&k?NxNoEgn!qtPE@FSX7mf6*Xpu@Omgi5#YLd=AaJ#oia7ry&!>cX@nsFrXVbsB$7
zryY&G)(NkR2pO|3?r`;W0#2L^w&P!CFFK$iVm!MMhIKsZMY!=>y$0Is@{tyE?0GSO
z+BW&62*+*0xLZFIC&sDq<?cL8sCUHvHl;NI9^91gN<0!Xop9q)CxDDk_Th-9`f$K_
z-^eG%fKxMBk~<Bgkx1JSCB5R#Ia<7GPC-rscHK@Li(?7ZDXdmNwVMF=I&7bI>X2NP
z&Qs{qqp3$5gouwdJ9T6NSUxED4sM(CL8~KCfI~m?of#yI9U^s786A0^oGRPlP+*mn
z7jXI`e>lhHu<NT9Gg0}Oq>vPLLfwH|odELHX^=bxD~qrmQ@SzHMeG#3HNtu<Uos06
z9B*_J#$e!!pcmEzv7n~3<&J1@D;&a}nEiGNq89M`LBZFNRzs-5D9iBV4@1Ztg^PlO
zuXBAbv~s2Px)RKj;4HbelcyhE>6N{)D9Ph0BZ1Xa6^Z_+Q*6VRVjLF<v+P_?LFRU@
zr*4oyEH^n~j}AO?J9VYtWgV20Ib)7#;Q+%s`b~*ePR``b?I@}m6buEMSgGQH2ol5P
z%>+x_VW%of^b!9ZjH1m=V2?xuF?o%N2oe;QO34*a!dv2j*eNv}&s$T`^+g#NEzItn
zmN&Yi7vM)SSIT>!RNJX*5vY!))c4*2C%Q;vC7z?_Kr0z55b~@`Yw~$_WGLC`G;l9c
zGM6zD9fgPO6mq$;hFH*|;o1l0<&mUhr*7uPTp*RWK+L+y<=$Z)B;iQF4-7Fs1&7wD
z2OVBKpOnw6rXF^lt;yBbHfgR6NJ`fR<lq3I{7K^Oie}T^Vw)R_Lu<9Mpb#~~K7t4}
z(>8(#wNu-uDBMP{BC{UUwm}Wc&9|pLd*c=hAaZuq^ooS(K@6Ff_d(%=AecY_K0Zmm
z?0T!?ttc1}T3ipp`JWdgQ(aK9Yx@wk^CxAS0_ufn#5sqv>ukfs&sGPQD4aq@V)cYm
zEsi2nWLp5#R{Ny%kCklC!y9=gaS}*L&uE67aDN=)Ny*p52Z<An9N*{CG}*R~T@dx`
zY8M<Jao)Lkq72^IJ}5&ozXk|gs=SaFiUV1J#P!FuNs*KM_(!WtKyOUC=QD20x&DW2
z!iMOCyjK@K!;Rb8Fhzp|Uo`eClJUOAgkZka4c?wpYDg~SFA3lWNZYq>ELt{h4J3t^
zfDYTxZdCu<26A7&4&=W6VIZXsL4a;RAD7xf)CZ|HS<4b58W_=#A_IB2fe;=fjEKv|
zVv0A{NwpM_6;LW0Q{0Y4!aCj5e^fc~ZqioC5FQe$lL%|dVTv_tu%}4RZ1*X3mHarR
zd6FHcR8RQS8{m8lQEe?igG@*`4FLqD7dPM@NpoHV|J1G<EhvhfYp|dQbf?jRa<Y{j
z9v*xxgL6yokNUAsz74>HYwD2#E?h&86a=S7Y1)q`N5jwN;9U<6&e-+f;EX#DD^|F_
z>S4nfclE;R10^osQ>!)cY|{i`EKyNt8B16b`Z9Im{EU5aNslI5393XRaM6r0Wes78
zCUA9DF<z9MPsSG>`4r6sn~!>7LKC{M8Cqj|@Ur4E9>rPj`T8ZXJ2U4@kWUT1|3x8;
zN2P~D7h;iUGt>B|p4%AzP%jRDs1stGSfko3{~(_@)-(a!){0MM3Q!mWF#eu;y37MC
zrcDC^%Wap50TsE;=<i|GZc8^Et9G*&nGFw|b+kf;1;d2`;z_~JB8b&g6`(QVO>kbU
zRvz}4lnzF-nQBN6ggzSU54<Ux;fJNu%P<u6)#E#=89i<pmyVZ;w3qp*F`i5&sy8J~
zSn=<vzvrMP2gTyh14c3oibk^W^#`CN<B~Nq2Y9R>Olj5~Ga^93bi*Jfpv;>MD9NUv
z?nN1}i9Y-jcEZWPz%toZ8(>_`bO{i~wG6b#lA;wC6m}!aXr#S09$9I1UXP}391#v4
zoyCI(&!Yj!N~^<m;ONm=J5Kc?e|YxjFojhm4d)^1G^@zC-kfGS#w;~NhBdk*8?ec(
z5dyTKbgBshu%Q;|qJ#|ir9R*UBfaQ9XpVs4axlC}n**XbJv;)lVO&?!ndUQEyilDk
z9!4NE)MK>9)5_`KF?|(!Vr#@}Z?w1+d=o7$N~LI7oUj}^4TT2f^f`i5o}u`g#!mb=
zbbR@j8e_Sd4i`6iF1z?054eWn^uBotF<fYq0+nnu)3h$#(djqV$w5O+V`=$Lx3NwN
zL}E2Pms_WN(4*H7A7M==M5lb@ufoNeW9>vFYAXJY&<6w1=4#Vni3uXaO2v{IZ8lA?
zaEoN;?)YpBsiJSRMai{tEjI)-SmXO7lC*BPPcPyYB`0;lWgeF)p{UV}(^$T|Gd56p
zNQ=}z{O4~<wD1+g5H+c<z0o1BXGF#%1PR}P6ZzIx4DuzVl4c!70vwUXHQE*}z*H_%
zQLmOruhw(`HHwN3payrGH7RfSb8Ax7+KRpirHnS7E)@(}-_}*Iv7y%2BE|d=eqgG6
z)}mmFb*WAb5e5XbZ4D1g>&!oG2pllM;I<VK)_Fv<AxxD&#ML_Z8;tnSuQK8T7Xr;h
zO2KQW!G-XW1EdUMffCbvi&!bd7o87{p(dRZMA;$h(li=_kaQrl3__9~L8DOjXyFd3
z8h@=ZG(|ff?qgFTV}lR30)rYZ76cC+Am#kDRgEhz+k$cBWfm|l{FI(%T>A^H49k%U
z0n1U>0~9KVso-QYgp^eLRWq(5yBLDL_^U(lT>ROQ@m!2fX$VH^dT&8<vW|?921U!1
z<JzFD87qb!neG)|(kljv;tF%aHZ;Z>Vm}xo4SB1Y0uAZ>YS6MP<c>LC5tjFml3&t}
z$alk00e*|L1pqeq$rK~lP%X+-zP90Y1r)>J6`p7&c=LwG--=Jf@bG>#*L4S&frw~?
zSmC`JQI9#iGs7Ak|Bm=T-eW8L%xSD`C&L@P#)TKLiYhn8pQ$)=gIUN_<GC>a%}d-*
z1~^LGVHh-(vTi5i8+i@E0bne%jjS<aJ@0or8d%XZf}2b9VTU#qEC;;W5hNS|$RRVA
zE(~lf69WID7$}f~6A8wP#0lX!?b28QS!>F@UzA)iJoQfq*f<X~5t9oBWC$<U2VhZD
z{0x;4ZSbjzoUtQFIlq-nm4C$dVWeC|1alJ)euYDfXyner*s^S+0TaO%y9Q(^GO^;%
z{Ri6_?~F&0u(A?G^SL698GUhqpzegx#5o50B1m~gBTkq>r<)~;tqC$>C0YgH-Uz{N
zmDw<csxiX*2vYtLJ-#c8YJhT!lBoqeattW7TNwJvo4WBw<h>~{{eDQvJOG|L#(1`g
zQ|E|WsvCa<*hogNDYTv$SQUOB8CXwJl6NaEiShe}P`0SAl6hFB>MI5VsS*MfA;a!b
z$Mlt%S&MT@Em)MC9Rt!9CE3Kga8V3@gH%CdsGG{nFkNd=Afh*u3#i%J&E$g2I?o@9
z3=2&EMs`7-6^44ZHYXXt+yaTq4b%ynml%Q9^t?0yJmOWK$7rrq4Id<V9YNv*9O)bk
zk}^chO=^>o^%XfTxfg)+y9g=XjGvp-678<s8cqR6)pcqK5K(st=+gk|Vwa>4uqSpI
zm<54naU}z4h^h9{!R#@+nwUi}$|h#PLUc8KDPCk(7pr)G3I@o4bRl42yP4nRXfeZz
z-(_x>^Lnv_m$1vVNN1#V;j4g!SQLB|pbvJ@D{U8JJFl6|NFKw)XkfnR6d|OZU6(!r
z;b&EXBqh)Ad|CepvAAxulI^#?gBRY#IFUaBroA!^(zZWg#$SG9D&OxSVK8U#03l>e
ziG_ACp^*kOrpYZaOaY}G`xY{|U0Y5g*aE}CP475Yf!pR4s}xK?<mr*5%qFBVfW_6e
zO-g1<)~djNh&p=sq0B6$62Lq>yDxADTjr*&OHt%mwS=9f^IIDlm<NjjrozK~KN@mc
zF;s8RF2J6f3K9}T+U`eu#*^bY$!De~pJJ*Z_v+EDfkHNmLWyREGWRfY^z12+V??n%
zDvMx=bQYP!U>Aaro{m=L4eP2vjN{X_2=E@*!vNzrv7#46XEHsR;RQCCo-D~hX|=;1
zZCl#=m2_>BDauq3=m1dWHcwn+cOM{)Ede}^>F9K!m0!^<Fz+qF94G&=WuY^LaOp*u
zU~I|f*7UHCmG2%Yh0*2VThdniCF%+=!7x(lF$f^PoKiVZ7^|J9*nv5=^CUke@E%P3
zm`eJGD5FqUpcsH53DbhZ6t%wEN#rnt=c1`BgCX4Wtr?@0kOmTyi8}U$$Y7{V)=nKU
zhzS+0L&8-S?gKRoU_%@r<phP?E>we|ZUi+L5-xxmDE7dFY5;u!m<CO5ajHj6K41f+
zL6htDV8&$NYoHszPvks>4%W_F%LeE#x+@nUA(R9hXNX&kS09!QU?=qW88P}z>cGr9
z;b?NkEmGjZoLXxjUzu&a65)ia4NxmHz5_#DUEenTL4LRd<OD*E1mqvl(+4t9o8f6}
z@Y)0%OAZBS0!>aQ1DHT#EG~6<SOE@@5^tq%y>f&MCN@-OY>G$@%4r0qJwQtIm$7xr
z0gbI&4oJc^E@9?yYXgX&Fmw1y0kBR`CPt*I3g`qd;v66e#Yf$8MEBM$N2KFt0N%-z
zF3oJxCg+JE0=L<tZbbdnyJry5>8z;@AX1%Mw?w3pemN4sNe|UQ04I4+@dj+owm!kK
z*0x?Tz*gc>$W8E|E>iGJegQ*Ja8p7{P-1{39}b8q$duz8ZNBwMlqui(<N!zY%JG$K
z<k5CCr4Si>W{tLWOYDUvQ@SA{xyf*D@T#@2lOLcYvedQpBBodMY6%0T59N4oI$jJI
zoJ}TeLy^TM3pOE&o6OaV0!Xq4ryeW^%luuv5+?54dc}}C|9c|B>696n^SLNEnFbEH
z&i|fhYOQ+6{{IRKM{J+o8NFb@lL#LIy5#BC`_?N*&YS{+Td{RjE(%f*@|*=iW9!ms
z5zf6RIMUM-*<{TPD^1{fbq2TDAfz9z9Q>Odi07y4W)Qyb!i#VSy^q`T#BAy;Ab4M$
z1qs)8*Ny>bRDZTkxj4_(DW>yCj88!pQUIa%HJMc3q;R@HB;ZwD6o>>steZEq0->=n
z8rJ|p-Mno*VuIe$ilveTH0@~3wY-i;937J&#Ybter#Y@U7Z@?~&9%TNGkr9{6dQ_o
zHd!$Ls2oT_Z}LZSYc2{OgovtdE;SEDJ)6q3glY0gj87~xjFoN3&l04w$tj+cV9uy=
zB|xGYyl-I#Z9r-{Kw1MDRm23h*{Je4VZduck40nxG$dQR(w>@#udb!Qg(qzLokD(1
zqPix}4i$%J!a^X5dK=m*$UA65Tg9O)14alxluXm!03b>m+8Y2FXhUi`5*QltbnrtY
zJsMH)aq9SU);7`cCyM@i=sr{DUs}0a+4vkcv??0!lww%QrR;j3tRNqX9bg-0-#8eI
zpMB$CQh+`fq_2ju&ipsU4{Cv+Np=c3iK60d>gGdr`V|=k@q;oU=#-s8*5>XCfOGOT
zNh_M`)W_DzQP#F1T>Mgq!xUWVPP+BGAs|=nyrR_9Lu9UP=aJNES|LPNom!;Sc@hed
z%ufdhw_fk;a@#h%r04<lOR*ux`Fqz!g+g*WS|JCw%(J4@mV{1oD=Tm(fth%53H@rP
zxCXO?nKjOiqFj;?C{*_)0U?DN3*dX(eb<!JX0=E)@7R3zvrU^6E<mVvD)&}xzGqOO
zxT?nOl&;~$Ld&2cf-;eVw3zk4^oF3B_B2TlDbi2#+G&D(3+GxK4rM_>N#!OB%0?*G
z#P)i8<4kIw&)8TK8}%8RY=(?HQ_KNYYS~BN+dHZNAxTxF&`=Lfg$x&At@v|q+bNdw
zsaFV4o!j$lM@gKn0uJ0Mb&{<A7E%1$c0OB>>f~5c?5Ax9$C^+-ZJT@)c{`g-p*Vt~
z;-p5jzDrp5I_~<}w{!T65rr~;)TtXe4RsF3fP6cLEe7P<Iow8;(e#_QO&?in^VUV-
z@%6dgcFB*q{Y_3DZ^=VfV$}kL+qBAs@*Y)5QC_}Pbrd)Bv6UuWl~VfoluD7)e$)fi
z*Ux9uC}P?fGEDVlEmF60(<x%!Mpa>Px+<|ItWeczg}QTW1zo8ob*t+VMchrdB})BT
z-;}h)!=viUQg5pov@stQsioe>GPcpiU)-EuaI`C#dJ%GZLw$0Bwai)lSN^O_(mb}Z
zyymO`Jhg(V09?Itg4fn5Y(m{?-9PHoff7@0XT1rcRquhAay!dbl7HF(h@7v8Gs`Gf
zubA}q$j`S&2f9N7QiUuF6M~PL-depYVwQq;HmJs3k$nfBPfQkj#q+8QT7=bvx&TS&
zNAFFKyrp<_!JhEl*A-r8Na|h5arHMLVQud3()^)|%_l2!*E2TK^y<-jX2EYhNKrQ)
zxqU~HlC}5NEywn3-G=fAvz=q5xo{xdWThikpOBV*ZoNVfIt|J!+tGDX!me<1#dyK=
z&>1R5<HSm@tWH^gy?VsxI>AAL@?`b*>XW1ETdy1)U4<~gbUf#em&`O>5n43m^m@>v
zYD$+Ll(jw;uw{v}c?3y)mJIf}b%}*lxR#B9tl4Z}7+0AmMsn$@4q($&okpbd@*BA2
z6lIl>5l2weCALB@L735E2i!tkVvtvkpEWL&T=8@3lz*Zwu_L`?Ag>a)tw$UT-OHSl
z%0u@O0$dGVCLP=ZRnT>?rh7j5VSnxQ<VW0ouSY)~eLZ5FRx4zLs^cQz!1mhvc|N;z
zCzzR6;yDkDIFEhQ34_zu$JQwX)MweI^V?<ILnU?9JhTA^Q1^?yP&nOnW=E}+u85@7
z&QF(}=fS7%G8N+tcLv-sT7{SZNy%xJn+fM{+8+*(g2SWyOgL}Hscsga2J~>C9C!sH
zP5Ajc>zyo09Q_q!1W!b-$RzkL768NR>!Wrmy%50${pVmo87dGR)5}sZ8wOTBr^bQl
zYM7{<JEU8~LDPqfzxm$oid=%1rzfg!jt(c~*u73m%7*TAWajiyPN!r(O&j4*O6Ff;
zZpWuCF&C#EAte_fKBR+V!l2!UPLApLmhO;DH|m3p{ED7cbKon&6I!JBjx=*b>@4gP
z@C7H<l<JVa#Xk9_KInh!6$6FjsXlG<Y_2a&Ne`6Z*~AtEF!!>KAW^HU2$I3D&@=1_
zsa?GSpI~L^v)3F$(VXSX#(6X4N<t`5pXH}a#&_CG4tbS(MLEG-(Pw$HZ!l}~W(Ti!
zXLhRJQyK>l^a<GWlIOga6=lZxF?qniAK&T8eudXQIj+|lY6mO|BMP9b$*gigGlLiY
zNK*2mf*uUKsF(*RTC-vvpjlnaoiU^p_DgbuFo<5pn5zXY6XQytCSAINE`&8K5~CTg
zk+1C10}hIT3#rHS3Rb$Hwj|Kh0aEOmt1EhBt&n1sfcxAp8CmeJuDZIGg+h)Xkpa2&
zs{A;jWCCpqffm?Wm&`7JsXqE8l>>j?F9`$wTfcOfuu|hy0WTA8o=ZMzAZHVGEGcUT
zUOFz29lI!;1s+@%k#QC!B<<2`o+Z&P-8fe|aQm&mhAXbx`&0nrmHR+w<HQW_geNzE
zs`VQYY>4OTWk0(BlGJZqIQJPXM#_co^}B5!iRq|-r6Cg;P<D(oi}~DAFM$ZRD2!Fa
zoqB7%v+hy{8vOARu6hSv{0ip^ahBN)#ikZoU$$~=3WrMY_9IA)+RT|&Ax%Rj_ks>&
z&}KXnZt0*IB-S$o^8h7BCeI>b3Kwpni;~0P(QsoQWF+ZYLzo>Gg~M~KQ3W)nA%w__
zuZRhYDLfTcd#6ek2#$)$90~iVh|D#IijG2E)?UUuCgS%;Z&5%cF3?GakizQl=;e8*
zo29cF17pOFMY%|cc|P(u-Kl`}igrSb7{E3`$(fh_046LFqmCh2kB)%njG5~)h>&Qa
zqh>pV-cLQkVZ-y2_39Yt<Qcp3<P@ESQVf`;es%>~=M=pncTly%Rj!<oPF~ioC->~4
zP=R~$S>nRIiGcO^BVCgSYIh;|u<(eVTRK5rO)e`LBA{GwBQ0hqB#(@&cj3h#^8QHp
z+>@j`dPOD;LiL?sQVfT3)XibMzn@p7OQhM?3tR!2175%hFd}+EAe^c40WA0cDVd<;
znT(P0vyux~*_NpU4o(vJEQ;UeuPBQZQBz(C{%1&#;)R%m;X-$71b*>K#0OtpF+@!H
z@XD)4T8N`^62qvxqKX(tMX={eL0N#%9A6ge<>=zw=9S5Q;{8K_=}LidA@en$vN>aj
z7*yqzgbrkd!z<?;T=U8@2UeX|PB~!moJrzfhzl2yVO5L5#G^dQUB*GiNG%G)HB$GT
z@Qz1I1EvQcWCPx|TP2EhaK948I(|~pZBZ!1E4Mte)`?-B30pb%N(@6m+sYgVz~q}x
z?2<gH#IOk-RbtqTxhVM?Lvm9AyM`Qiw+F3U9p!l&#p2PA=6|oWxY#)!V5tauiaNaf
z0h~oma*hmf7f$O6UyA8BBp{+taZ`R6vbJ4-u@Su#e^Z%^4IkPv85_RDOvZej5Dxzp
zRq9-Yy&KY*z3sV;aXEY2k{g5Xt#TVte7b8odHZ<fIwSAcw_InW8!vQ!PGDfPu1SUz
zW<h|L%Kf?WnvVu^s8?chf>ggLLvxrIF;(7-ZVCc3DKD<#&?HiybRsZE=IfI`!z9$D
zJbEQFH*EhlYXz|XE1?-?Qg1>|Y7bUL8>XM{)|LNCQ<68q0d>lPpc(p!3F3NS5pgA&
zA+6RkS@!@br<Z@wFgM*5k^JhyBS%@wpfG>hQZTf;knQSCd1+}Z^%fInjdE=rq^+Wc
z!~s%{O4kPRzg>XrnIZ0-iE6;f_fC`1!MLYI;-`}RPTMkrpIikq8z2Z>*5=lMo9?Q!
z**Z#mD@_vyQ?C@`4vj^@Weug$qZT%^@6*)bm51D+jR@wxp)AXy5YHgyjH2!Y3<wr>
z!5QRyyz-T^jEq;hG784B7)YQZKp1+#89*R90S%fu5zqhv(F@RkBB25Si!`!sNv;EO
zL!EV28(jWgNzF(KU6j1W(nqZdDK7;}MHv-*dZ-h>oJR)&=K?}vqL+>V1k<o&OH$A)
zM+XJA3+2Ei6Fe5+=!@bom;q%%>7`DYnEJG2g0HF;<JU2P*fFmJY=o$}%1Nxk%d2&#
ztA>@C7l}wFI4V@8qQ$rh<HaC`LJb=zz_dsMgp@+v%<u>~EBR(n7d}J$nWkPm?_n!t
z!Jnk0@ahJKt<<}Y9hgeJ7e*IsrK~0NQkiY<w?;J7jVLcey)+_d5WR3-Cb|{O3zW-V
zI4@JZ5Vz9cO2`^X*=8rA&RpsQxSm^GV4G|(^0ORM{!#R*Y;%}M-KAc@J|9({(vHh$
zF_%+?(PGXdb;OFfLMm6Rn5(!;qY0e_rjo=i7~O0tN%c~#cdwjwAYx}7tHgEc(IVPa
zR}aE5;WeU?)@^#0%EB+gud+x$x^nd>q^sC`F2#OAldMGfiR>>{>3T&NSaxIX{KVNH
zhf&LPPOoHoq;tAAKBN=T%jJk_u-AH}?8EBGl3*_ZiN#<t?vH3=`}oq7v5hYctK0Yh
zY*qt2h<+9$#GkMe;ob6fkQ0m`Yb<+~l-My|2mu*@=BigtJhxR$4Lk<ko4YW&SaOaP
z*IojSbCp7GmuCx8ax9&6&5H}(aXVaGZ)u;`P$$l5s1pF|raJNPytv+7lf-%ld;t<2
zUBSIX>~oj?dO^E#cTJG1Eu^o62TTek39Yfv5Yps$pyJ&NFof=c`G9fI<y9n>A*<%S
zgm>t!&=7(mx=UHUvHZeVxViiTtz1Ou(s$#@zyL#nIJ)azy_>qFup&;-<>Dk@<lzO~
zaC`m%2EwJM%K|u*LCGKG%9m{hiJmUkDI*8nd0iuL&<hO$k%NwKtR)P<*L2sNesd$o
zGZ<A=yZ|Hs<msvl2C&aV)ec{R26drK+&rnJ1Ux*c3kdckrwaHL4|^wutAR5zF(L8t
zlaj32P+jw7?*-x7!7OPQ4^(==UOZ6XNH`iw%)08RwJ1XCzCpT@cLH%8;$KnHm{OP;
z&w#Whi0e#AWg{6WAk_!AGJ?X^BGT6A1^aqIQVZi1EzA~b+6N^pMoy1;L)qgGLdVZ=
z4WHyI2_1Qqo`GfuNH+$T>%2k*4TH;NUX<}m`^NByOn*X6chwv@`!BQZXRld<;+g|u
z|9S$L6lXdx#)}sW0{o<m;shc9k59_LhsX*ju|+`&;l>FYAFQG!XzOwn^FX;ZHX&O>
zc!<=TCHS_{x3f4U%BOtvW+f3Bi?K+Y0od7Eu~QU>G^Tv^*2rHHfDx4v-5d8+wrWr1
zX6Q7jd{Ay|=$jzoBd4fp0kCF#Qh4IzZtZ~HBIN)iJ3b$qe8rRP4V^wf)kjF#PPt*Y
z)#1{CCC1vYN#Xee!lUzNfJ<pAJ9yM};FhTktTK0js|PSy9hMzHWH?b1!ryfKKz{Ii
z|D=$;DN((Nmq_GYBr+2V-@BNJb?)4KS=qqrU%KD$9*J@UxZrM#y{<T{U#}Yu>(}ds
zgK@j}y5qq7UUwXL-Rp`2uRE`}!KYU5yyvR40q?mgZE*c^QTKjn9(W-!u59miYa-<M
zqlsWY0-OuF#sLy10tP!JV4y|K2t0I?W&|EO{V&YI>a>4Id+Oe(7=eS%<yV;k=juD_
zpK$S2gTT4?s+;EiRmxz;znrL82ou{?$nH4|2$=IQRAC~ga_iCBG+XfAH_aA<fM(k{
z{i}3neDqQu<RUE+I&uDR)=4?<PTf}JjGVeH75t+kzip8)=TvT0-pHxks=U$Q5_h!n
z?ZF9-Qx7OiaG0J#Im2Ok2w^>keLRJt<WJMn2g6VN*reo&Ww@!HVVyP%z0{8XpS8Ey
z)h$P|!{+-b?y!5%Wit2^!KndDfIToIw?~F279;~k)j%=?+i&lW5o@h|GQ0C+<}D$C
zs>8S+H-9!aBN$w<f`G60yh*&*dnP5`>piy)`Y?1-d<LBuI!+GI`c9F;jkR@%W}mly
z!zo{$MJ%Z0?@1jGah;;sV}7q+6E>COOD+MzxhBDyV;$AvEYmn5w&qH588vM(yQvmF
z5<mqflgVBIDq)T6j<tu|`$qt-*L?y6*Xv>-f{WR$OTtPuq0be?7iZ2ublViJbs)O!
z^$CqVR0os10o!<;OJmcqsT81_o=v5<17z#<WC61Ed~tUT(0k7j=;2l+_He5y<4;%x
zP|E>C+7#q>AQd^Bc8~;Ieb6==AN|nHGf`Vp`Er5UVw&#1Cj5%E_==Az0hV$_sD)(-
zpxEor9Ds$<=~<GjM9bqLOzU-=5~lS!SHIM%g$v+V)~N;Noqk>z8US{szZOlKD%B*r
zsU42MSSe@9huq2RK73$98H#+!oy_jfEV1kKfek56z`b6__J9u?@73uHl}>c*Bje4Q
z>U4%m<M~##h4O~ioingiCuiUph1_}_{#Q_ylr|4It@qyGqPlQH!IpWmj@yR;PO2$5
z{>60hegcz!-dhbc4LvfHR(sG(GU(j865Oa%(}8mtxL+@*tMgi>1|6LrB*8mZ<n<KH
zcyObklP|GfIRbbtM}ePa-ON?zxH{+$9l_P1TzkRQK`-mLUXxM(HsP8XN}v~98QPGe
zjtE10ZO|{SWOz~L=Q9<oaZz1$J*f0|kw-t%Mhe{5m0%N~55?psAE4H|qIzi{!kP*t
z82~xu9U@wSp$K;5CnXz~mH0#ea+;<c5KLH;loSIIn$yIzHRydYWtF4%g`Cd>e&x+-
zbr1xJ({wC92+*D6mcEj@e#M{;@9LG<?eMN%C#J)z`Zt3o{4<L98K8^I8)wuSyi7)E
z<Axgh%bB>-uD5@9<ND@T=7p=0jL|n^$`~f!j4AmSfMU~>#_Mcd=VSGPQFD^&<O*<`
zPivk4u`el>T?hnD44gKgRv)0knxtNTG8Hxe2pj`WDT?D7hqw%V`NW7R`s=wO!X@}_
zOD8cS@J;MZWJb;Kl@OUxlRO*JD^BBwJOKd{OFl7jiSTF!34tRu6&E#^2hGHZoCDFo
zkJuP&R%Q52u-z%V3HqFOuoZCkKu{={qo+)QVDywJAPk-|g@XYAdlKWN?7Xu`a$mp=
zL2_4u$6%Q#*~2rDt7?j8Xd<OoqJi)ns1aq!oyasaMQZdA=r)xVcY^ooN;od;9euMy
z2iT^GIMNG!+Dt1C71DYBC3<a&rfGs?`9)dH$|Ez8n&SeW0Mn|T1E+Q+^${j6t=SiF
z*90H*6s;6sX-|r<8h}lk$R;~MJuR%+=Z`N?G>B(6Ed;PxznHe!xim}z=F%_?cnX0B
zy*fd!J(+=KB3&;Lc$}^mqjx0);9)-o=Iq7#-Ir9TFfDhaE`C9S#GOqgbH$2yzF-e0
zL0;r9Bl3(0My|BU;NmMFei5;11e#6db-I#8>?F!w0>0Su1%5dzSIARq_fWKe^yEuD
zM1pe3BJamk`mbpO1tnaRII_viYurO#$Z768kTgm55sWnl2>Pq3w3US$n@Tr1;l&h&
z_HMZ;&@wepL(HaS3axQBCcF+nv#takhF7DN)s>1e%Qf@H*GI!<8j-`i^`;WP5{?i-
zFXvFB(qgzGRx3MWoTF+8n>%{VKrCGeU|j?NjYGdMkv!wj@i-B2`a-DFEY9C3K9I)r
z3*jahh06Y~ItsuZC_y2(Yq|s?`3Ul#5u<<TH^4z>h_Uk?vaE3IM}l=VpuRLX@zNwZ
zloYbPY0L;T3ZAfe1Wnrt9|cm63~`fA5JC;nmrl6;Mrh6lC^<)vF^6aLLC%f|U*Jb@
zOK=5To3dtUGB`q{xP^ZhB4~x@;u^1*hRM(fsgTLw2)@^cfQ2De5<(P4(D35*e#Tf-
z_i?>Hg6Fn}Zlxho6hH~maK|7JBT;9t>jBG%5OlvT(w`yfT)N(d=ym60yaaF6=?J_M
z_J1O@AZQ-ZNjbtafU*EabTu|HTUuzO?-)UU6kWbNN&QtW=MmcINsbZ3qfGEsd>+(L
ztN<Wx;AEX}SuD8Y7=F~w8(0KaA+CdlSdV9MJ2*+&Cutj;PpFt8ttn)B8LsUaiI#@g
zm}k)`IF0=Ytk)2y^F#tC9I>ls2s26w=n3@K5J&U`0of3d&nyzNA*$&)kwtWfi+aLy
zI$YKVi4nwUJr~xz^Kd;$AU9kqWOY>20)b2QN*2o59h%Au8=`lH_e?PHrE>-StL5$R
zAWk@3>FBwVfgrBNyUGb9+1T24D#U*u4HEINzj%zT_bK&|jM)3dQz|C%ea=MqpbT2@
zj*TrHU(xx`^_5`^Qz4IRd?DgdO9Zanv9}suh<My}n=s+)9io|^jJFrh)x7ccn~tK1
zVBfKqUM=ptJ|YzJm2F;gOk|cDd+ObThecfb6XC#PGbrauY{?H=g6jOx01>^kO#^gA
z$Sxcp7%#uIW<Y1MyGDqwYj=$@zpgDqav|-@*eq5vIy9|Q9%XccF|4u^7z1CP>8B(W
zYRuss1V(FXL3)O<q_B3&(yG4^XD<S{i4Ke<({HCPT68Q-g}%d!FctZ(+_H05z&2(=
zq3^u3oS2o7Nh>CT*m?S&8(-pBGVm10E)AqWcC8V3&BxLjsrU6<3DyV#p~u3N(o`6`
z)(FGcwL}!h{vJpa$BsP(tjA;N@Bz@^SUP}j=(mOV%xA(IKbDTt8{{2J`UT5-FyG0<
z7ciy{#hbCS%Aqpx;S7vug8U)AR3Q%nCm5gp44oqo$v$QBGm>3Mj|p<SA-KQ<WD!?)
zcNfGhz|c+iM1G2)>*&egcA}pqV%v3}J2!U-;ko8629EhwDFTS8H;GvHIlok?mIwXG
zbCZJOT>#)>n(qn#@shBH6MN<;z~YmFTt~WJn+%HAMcHIf{KR2%7hec}k1LO%i>oUF
z4+(xR5|X#hs=H=Y$T=8DkTDT0ult@WC`uOjLiPdEi?m6F#;eXV5vTskO1^Z<UIIQB
zEqT*beU@O50IxkOu6+pOJ&~Vd=+5LyiY^9ifOmfkkw~ZLPO@$)CZp}g`ckbJapVeN
z{Cy?pdmze}K4gF(S-=?cOSPJ*p~iCO8iSP0lQH^?Stv<9*uGS%9%A!w>}2xO&$_XB
z3fzH8uu=xrPMI%5{`HAVouPbolY#w1v?UYwJc&-xkMbL_qvsYElT^rM1W=^RbijcI
z;%lZ4Q8B3kn3()arR<wh7|!Gh7^bx5S3ue*=X1##_0~y>EA1LcTQL~<^i0S8seq}8
zWEVqGR+DrD#*M>^8AORHC$FxC%`cT|1o9Sm(jh6Y=0q}%p^&r*2=FkmvrOdhxT3dO
zje(`=znrvy4Ug9)TXyu5C@`FFz>zRscPp;ah#iCEjzH;Jr{l(UC`fQ3S;>$$6&G-X
zsX=nv>hYygv3bdP>M#IBr#5kG_j0by&-vlyWSd}c81#ujG>ge?p=@A(!x-UA=u7Ji
z#13GPyJd`UeW_F<oL?&Ci|f)G4rB9mb2@SfUcNgn64;-w-x9ZsLn)&t86*1py0PL%
zS8*1HA75OVtgrvkUm8HZH_`x#>T!~Hf+@&n=D!)rYCb`AaV4C8D6IBw^W>^fMD=v&
zu*Q$w#fI3`-+a~W{n#BeSFdLfDSZ-ni3tT8Op{Rn1p0VAe;%+-n+}(C13O;FAE`5b
zSu3COwNf3?e^D(bwN1@CC<>a6o1pm^is+w!#6Lp`J181t2AIXu(M%H`n0UD-aHa<&
z_MvEofU_k@9?Exn$8q6xEjlO^5a<6ulwEFL=D8S9>5l+2Nuq(#RC%`yDeqE?y&_Hq
zn7x(XWx{=7$2AwP1O_fHzc1*S({YLb_0{PTa3=us_<1!t5}POX`V|y9d-Ad46wzy_
z!<0;QxHwbit8^&hX&~bl?7Sa2%T2v42Hf`(htt-MeVNdmbM?#8`-y|F{q!%hTaqtd
zG<e>RzGw*Ie3?35DR`$Y1)*sw&RivJf+(W|-VxntzQG0Wh)S})bhwDC<r0MG3m5bM
z^5fq<{m1?9zx<y+Iy`p^pB}M|&>8>bKmPbn&mC9$JmS~?|Ed1p|MT-HfByTYC~}<j
zV_jAc`#i7z_~*Yp|J{H3r}j_n)7C%#r{{nBhkyRZKK&p5%YXfk|M<WE^Z)q#5C8n!
z)xRR_^UU4PZuj9I(|>RO@$dibkN^CscOPE=`yc-Hba=T|roZ}I5*XdtSxAR<hxP}1
zn}p)u_4XhB=l|pX{>Oj*zp9skM-8|2Y5#N3ZyxibcK+3FA}*P|%*ebu$A7+;qbO0o
z>E-|WKm8l^a^9(&cM8X`zCV9>`^;+pS35ayQN&&nS^Bk?|FROUJ5&h)*WXt{toTZo
z^WT1`eA=I#kD1h%->$KL^N(x&!+-tjUw_=0(K0(+W_{l`_xWSZev{+<Yg3cAQR^M$
zw6DwV`wsuB&#S#|fm8PLz`ER`;5X)t)c{et{itpTv-D@y`{xug+rG>4g4X`^#q>{~
zBa2qkpC4b^fA8pE4t_Vb3C0{%qTqL`71Zgi#pHnBR@$Yf-ddZA>)UGBb2R-F{JH7>
z?85%}#3H@g$A4q`e}3{O(!{@`8zdL}c67K#f2#?G@Le@rT)x$Y43KZD;ST4mrc0e~
ztL=&J5YFBCr+0g;{_8RSjji;b+TXMK2MD|0u_-I_w__{*h_@E`B)+W#7N574Xnnq`
z#*j8uqu_U{MLD+h0x0-%s_Y~0-Xk(nv;FH|z>oIxFTmj1eMh&)A6UwU0G+p*B6hy5
z2GW(cn#iiZt(II!Z>4U(yGM4UJJ9rZ<v;jyU%*HIUKnrEo&DDI|2<y-hz>P4lz(S*
zyZ>@2Q}8?0a8dkL6Z`SE)j&-CRufbCx7B**(!wj~{mat&(_cXE9|Q4U--Ler9XjC5
zU#{dc|G+|a|K&P%{{zc7Z<<tPx8GOv<5zlq{DHl(JdE$Qv)|?Pr&s+Yj{l8C|92TZ
z=a;MZ{DHOm#SWyPf45PAC*!Rq0dFw=#Ee`T`nf*(;>WttBfn*c{M3}BN9FA%ir<dy
zl%waZB*C}UI<SLpy;t&mMc~4}RFvfViXck=Qc;qhcn$pqZtc%*aK3*JKk*hi!i~Q4
zRFdz92<OI^ijsU^@j8jVRzvyQN+kY!tG$x%D<ZDoOGQb3;!RjWvw!!C_&Lo;x~DIF
zmE`+D?q41e|MugRd|$E1dB4=7;QMND4t}X8$+s0NZ_Hbb<)3&H=_Ze{&iw98{FI3}
zkg4-aKPCBoct}$4rJ^L?R|IR&mx_{nUorZx-ux^1zT$~rzIh3L=3U$nlrmPneHTBc
zItvf~RS`<^?GQ;^_tld^$@dijxcI7iDfzx4A|bz2l;r!0F}_yH(oejHbj<($H}O+O
zBT|xm>7^v!4(&R2ezDLb_`cd0zk2Jh<ok+9-SMTOB;Qv=LWD0BCHWcC>4LWQ?|u_M
zXFDx$j(_Q^B)_w?e`$yQ(#HJjk6%CdH#fR`6}`XPNBYzx_;cpXXQs;C)iZt4Z#Z1$
z&ur!FC<rL-R-P9klKkEXi+A=*JrdD=U#%iNzEorA$G6p5u?)S{Ao#s%^l;)Ww67k{
zKmQWiC6)gT%Vzu?FQI`}?#uA@`Cgx*A`-8EsknFz{C!2xh<>R!?GLqxbYovCDgoK|
z6#+?j--R#=Klw6l*w1gg4EuXt22w+Q8KIIzemBAs!2wo13Vx>=g2dlyN)qyIH4rVl
z)pq~RQO#<|5zV*2@=v~mb8(x$bqVtG@8BRz{T-a**1sJb;;r6lBJ%#WT61`_SgrYY
z-YirLBx_Z*Q1;eutH}*qZy<ig3w&wG%dCw5#$I6da_?UaZtp)bxHZ01$&_5*{yeEX
z-U?v$__m7eFBLMn`rDtwQH;6%;wS#|Gkrl;{|&v3=%F88jA2j|d_ORc3QKsa1>;Y?
ztp@DnTh03)X>G-?T3hi)S_9b==bz=Dd;@-yu>Qsy_&audAG}WE;KsMtX{-jY-&;-S
zzi+D{fcvf1<{xNnBeRXFZKb;Twi>W=d;={1<Qv#GuhDPpHh+f!wD<Vc;P$r{ajb@r
zskho{Uq<(v)qZXA?muMlZls!ht10*Fx7FHVYxM@&`O?^*e*-s4{5QUVzv~?E#WO?6
zw+AL<=K50cmHfo1@WNE<fZqFmW3N>QE610vei8kSFZUNygW}IPs&5p_#;w)2o}i!E
z$PB!jU%L85^t&F?UoC(yqMvaDU-I@pG}511uC1VuU)Sp^`rfgJ?7Ls9zM`LT?%fd8
z{zpc-f5xwbEcRcz`$hCSzKs0~pTpmNypo@Bp54HhKQzwxDgRjkg}?Up75$DYEPlNh
zzKDM6R&V}gjo;see#YFR1L<pLU(xS)&ws5+ezj@;^~b+>`X3p0j`^SN=<hvzjWxpl
zGV5jkdf5Np9rc%M`2Cj?7JYnbUsSl1(m(vanx5}qsrR<~|M^Y55&+z$TDglM7-1e2
z0ToV&8=}?2>+}%yTktp_xILWylqe8#I5`fAHtZu{#0Qwx!x;mVEMiXz&|=*rgctA_
zq+;O=E{u#-3TJ2-IL5*iYlz_eaKg($#C`>+Gte!D5JY0O!)dDoh(tqqKBJ;{u3%NM
z=R}dF3e4@{aGfQPG!TjMWO?UYF^>{bF@_S5#>xVkTbSBHsRJt=E^=9%NUp^2i<($Q
zG**trPzu!87yvyWfxx#=m^>IE!bwtxESBL6R0^-j=V2TP9K(nD<(PapEQ^>T6jL9L
z*GpcM2=t2~Z4vAjaq-Cbcm-%Sa&k%66M?x!L^TLC!i}+N5g1uEa4;&Ocq)fxD2pvn
z@u5t&aVqF4oGAO#F#V+X1cyi{`2I9>qP<lPs-Rb=qa&>fw-XA?M=H%Ls9v3-9!NpM
zFRE9YG25VAy8^UXh1#q^zxEMSAy?F9curBVJt@h(;269WjLj-0mQcRpQ`ohSpbFJp
zoYS5k@Yn<?0zMmmY;u=_KR-kc03c9ox`z;JaeX7;u{f{$1P`qKFf<&jZm}8Ucj`9t
z3ef7p(h|J@upFTb&>0pIA{zjXEtoO7@_l9*!4;=I=qt$|)E6I{;X!9(U<9oeAzW-k
z3?7W{3hKiIKU@Gqdi*c-b9B(rBeD-2N0$_ajJTTEL@*)4=oPFg=2Bz0;R(Duf)Nj>
zC}T5NrBVWX1pI74Ef<?n%-|A=O;*Wsusp27hY=(co3SmIq9}`K^k87hINqSHw$iP(
z#*Q&BagLl}OdTOkv6aZUK_vkIcFVP_8h5NKs&&=$%z8u0m)y#a6H5uT8`RRmf%8ex
zoz<l@+zpy(DIsq&IPVTys!i_-*wpxpZYkq4(wT-R7dlcM#G6(gJXBZ0hk%djBSP_Z
zObM#NYIh~IzjZ_t1ZfyPwnY}e?%a_r_9Lo)L>H9yxIr7OtxiE7EhS5Ct2F&mGVQj|
zaphQU^<73%Ido(_jim&=nR_9YNZ+p@7tLB~rgV5LWqof@Qfullj?TTAa$D)CMQX<m
zy0R<bbD*i#RCfTWKvus4-JN8|@1Q~Zi135^Q02F7&{SlM=%7`LHPkLrb%jVII?}1e
z8fv&SmS`n960DY6xFaw#mgvGeQc%P)wtVo)m7l%0ETK_w{>35-_?4vL7c&2^Xl1!}
zi4M-XSW5bggsrhal6PUL+4W8mpew1q(@?*X>VMaRJG$TWVCcHlKw#2)l{gw`yM+(G
zL*dDdbtScEo7zQ=!7F0JrS#@eyA_QY^Kd}5M}{~wdT|b3L8WsB@;zqgA+t)DSSUkL
zYFtTnb_P0M>1|_%`UPb-l{6gLWUqwJEtL~O`S;2y@}y`%u(HHCfxc6EkdA=pP@a#^
z>FrYzJxd48WFR?32RC6TnNKh5MKGyE@2Sy{(WrN1LJ#qCbof_-sg!yJgU3`lZ)Cd-
zr7F0RTr+bj!FPw!no1py$n#+8fevEN5UWQ=65N;-sr!^DziH(XxRRA+>~@HQ57PU0
z&=-ahf%Rl2y`#)8)NY%`A46-2?xQ0>|06-EW|#(Rx6V1E&3Z*OXG%nF&{|^2?*^?U
zmi%5EuTO|Mq=N?bBSEQVRk`1hMK_c;uOpLg%%+*Qkwt7JNSgbRpv3zrKC(_<BB<}i
z<ChrfJJRD`2|HTHmX8Fby5<T!6*_GM7@YcDLL!v!ApeaK>L>Kt2u%<4+6c7@!|x+P
zF}u#&i7UtzHemI3r0)%-lB9n$hA8?v*p9D=EvKd%u6Cj52JPdH1iwK(_oss~GDHI3
zku5hw0^h-!5n^=jMf)7e+u6-I`%9yO>SO-Tj<mob!uF1&xq&RAJt;k6EIJE1Qs#!3
zQ#y!1LZs~-QH&wd_6}moE5SBjJlY}3_Kv8Q0A+gz8+VAZy@Rnk#J<uE#K19VSNHKz
ze}hJK2VOTs*xr$EIFwVi51ij#uJv9?h(lEC9oJnUvh|LvI|0U)4qBEFW6RSAiZ!z!
z*^I&4#Ex{iSHfnX%SKl-)MX%f>A0pHGNzHpCkAb4u*k>gYPvMpXzu`doeZ@K`kGtD
zCNpqwv!l-OdKn-1lcL)h5vO;&@lc3T$EpbOrgw0JhRHg<Ywbw^zImjq4Z&tQxO}dJ
zE$u9^m4Zq}Ql>wU<m8Goz2oZ%V~rY(tJTtP=4uo<!Gh%I9XTLE39UOa!iLEluDlgt
zvWCGcdL{4}bZlRBIp1?@`xIm!gJkqd*cB)^lYv}ROizliDS&r0Y^mu~aN<YrNa`9G
zO}*MMQ66<9APHqD@5tX8VoUFp*(5}k-l0QoM0l0zn>6X!*|Su84zyM%2YXNMtI$<p
z2P0|N(1d|7>mx#`dPz!+4uaA!+Qp@nLj>u)65~86V!P0aCfgXPM8o(IcjV;>lX3jf
z{9#=dIT*pN2rc7eXI)K0af(yDBQ;SVMcY%NTm-V7ktHcas@}`oxdOB_v9M$<(`ve+
z`bqtsU5BphGJ}!9>PqlTsLJA3e;_KH$l)^!C_=W7j+|f7kNOU6+37)kI!IANtU(=?
zWlAvpsV&98-a(Wa9rp7C<<1qbZK%&4YTGeL8QDm+7hOg+8SO%BLmgoI=rWMgYLC9v
zJ7_*pw0GG4S5lh}0=BP!{e$8oXZsacJ(kTt?{&D8pA_Z76pK+u{_N;WZ68cJ6gAE|
zA-eazz~p#E#^2P8)4SaBSQVmw??}2GqC&co8smG&277Asp=vnSDLA-iGxRU>rYS^~
z)E9EG1_|Fg&a79!&cSur2TIiud)vTl+uJqhzHVx|be~A!`+|$J({5kzaN?+WU%-NT
z?1mrY9?)gDubCxmk?<r$mxW&5hNncBN1Wn%Q_r9XyDV(DKd$7hRnFl~e!mVk%14r=
zj~Z+;!57qElMN21OjLq^2cn$lcGNC(VLNKKbYYX34r<kpBukF(N3>8^l;dmgJ9nh&
z3Q^2o$;vXDg@d!zJ_E;Bh++Op?z?L=!hxuYCL?^6>TEQ)pDU@3>dQuEuMlMMN~*70
zEkSjXhW-k!P10n8!yy<=HaMJy(e$yyu^5eh>Apd67$T$U<)4fus~j1_qR}efxXx>`
z%E7OCCAHCjUo}Ku)pu23yB#BxO`e3R(I(sA(NlC+9ek?MV1O4>YBZVFAW97}=6CSn
zMw8R}imIza&xHzY1J51#H~S6!*@pT)ur)N9=wRy&(eQTwFs=j})h-3vWTC^g{sfr$
zJ9ty0nHn#R+NAEmq#8|TJF=QZ>pB8~qc|EZ?z&b8@o;rqJVcWN8#fct8hIf*ZZD$A
z=HAeVjV|n@GYwI9b?}+`kq3K&9Pf(QxMv9)09Z+{1kZGUD&?%Ms~vzUA4oDn`{?rq
zi>M!&)4P<PqwD#2Kk`m*q)xh`q2JtpbdrJfVhnX9BIsZY{YY-fOQrb{0boa-_$$Kr
zKoRPq59>)0>dIws%hh#Q<WGuDPD<L}$hzjD7weT-{tDPiZS8(!e>)O!UJ*6~FFVqY
zjOXMR_aoEU4PBXE>ICZ0k%~K2KTOWvaqaq%pp>1Ht_78*ld`PW#qN_5woK%#tZp!6
zUI{jRpIKs~)w~ze*#l9nC0f}|fUeAJpY=**Wc$P`wRiRx-m5-4kX8DTl?`f2KXO5X
zhw@6`C;_FUD>cNWS@NTkG1wyg$fgE8<dv`;&_Vi<nGN#CE5RstjY(!Ucpe?JQXQO*
zx6C~PAcZSp+m3}Qb36$dJ!Fi7Yw=1r!t$Vc$SDmp#FbRj<<fFxsOaDl^pK(L<vMd^
zsOSK4c*xWS*26&**Apq?AsZS{5)aoV0pd6hd8+-ObMjP2ZCwsNt6RQnH|VK;I>0Qh
z#1<WB77tnCz_Yk=U336it|XxNqhkaz&!gVE2VB}wE5nrzqXU-W;<f9EOL<a)4;{#q
zD|u^G2WeNw_!ML@$G|IjEoMMhu82>q@9;|a)PeUl^;FF7B>JQySB5KRM#n#133h|3
z?;)>t^&=(4!FVM#dor~nYt&!4*n`$FGU{CcHU>aYK9UE;`+NDT!5ZiyT<XZL=OJS_
zJWG6_*E#=!qpDbwC1*8q?|H~s9Z+H+Yq}6BS3qxUAyBRerF{7=V>y?)yEG*}26uU@
z6H)S92};=up`bbv#W?9_dVRUB6dfHOw-+a9b_?IXD{n`~9^o$c^np@yeSf*txC@ri
zfmCs(_vk>XxXU;ORK=C=qXVkq{@Tk0SaE@>Ix_FL(-a0A#gzi2pDOX8z~{J7R2{^Z
zSHh>JCUjZB2b$1j1|MibUv%^zC_<MVe4q${r@H0rysTj0SKMg{KOF!TcbUS6aUF6`
zLzlYKJpO1}7sRTUCVo<cf379!@=ZgdUkOLda1z<ig>-ROdg~6XiwmlC8JB8=GM{0D
zxXT)bo#OsFtUrc~E4@iaK0|le!mxcD2~TdhIwuvJc$TLmm~3b{g}-z_TCRjGLCv`w
z)|CYDNzsB}WeK|hkT34Eo{wWV@>gf8O&51yd~=sIeFC$s&mS-q-!g*%RB<4$o)WDT
zyp^&mTi$9|(Y|3V8*Fdi^j2G|8$cK2%3#1>No^$tEB{KWsVlkfe$!)p1$jF09c&5;
zY}3TPk{VQ?R0DD~+;coiXKX;YToIlL1t)-(0juJBt0$vMtvU*)tM9EU&|Z6^lyfgm
zL&H(e_tN;Gy7uB-qJc8mH_c^3;zn1>mn*rS^ImFsVrCagW!CPgrlH#i!!kf%u3%#l
zSC-i5Lht8Y5r!kS3x;JlyZavM)kY_Vy0!6o2lGi9(mwjOFAu7o7`x_KV7Kax_%?OT
z>j-c~Y#NGB=qiKj<4W4%Z*paIHSAnjoh=7eR#)rLjk~LL=trTnEKx7MJ1MEHFfAWZ
z<8u$j(DdAcrBar$Rph!WVU0EL2K%DfYaI%4!R$4pLv&%VtV18JvU)86E4~C_HXv4f
z(FJWltoWh}+Q63XE7UU7VZpK<i0%?xp{8;2Lw+0ssKpmu&<01KD`C!K@D%zAHEtLr
zeb84@U3NVP8j$cUOW)|7D_Xe*2kMoue^760|Alp`H~PNel)aL=8?!#Mgk1)>6<<qT
zgL+#_?LxgNA<vbhL(zrVGB}N|giTLO`QnJ6-qup<t0sI>ml-_RSH#wF^iy6RLoQ8U
zLw(-p;h?j?3b5j9sDsdGYp8?JXlt;8P-t)@e=Myls>L_(gZoT6p>Mh7+tfGcvt?>G
zvIL}}b)4Cju~8^EA+oNdMq?;dh-p`=IMS`IR&jt^U1NhvTr|54`8j>HFST;oU5G2I
z+`FzI2}62bUvxnmE}T9RlrnHtNqP-eR!(r08C2UmY6Yro(g|(23v<xrJSD0Jv)!^X
zTorOO!eberGCqUtTDf1ZgbnAUUjf_2X>Nv^saNTOX&JIJKQ1l+Lza&#;e$r@)-`WX
zivnR?N%h$2Qn{k)^41`r7LhF}1=-`RrlA#)Sn#e<plDoZEyE42&#l&>8t2xq?qio4
zMiLQc#wEi=vd^Wap+157GK2n{OYPSAaW1J1U}>(1?QRTls_k84q#DO{x)T`oq^O2C
z(X{8^d?eKAlp+Uc#wTrSGaz+boREfGtXG1ER_}*~15fB2nnozoIhZrR0Hg6q_p|{<
z<H`<Y38cAYwv5weWsAyk>YyuN+x5uWBdjzj@<bW3*}G6-hK%=DVhORa1b6tPSNfK#
zN!rm@QVWuHv;iJ-B}f@+z>)ZbSK10`;*)M^13JbB-O>hhjE|$n5$52+hh0&i8e1<r
z=St8N4wB=jtvpB$`Kk?&92aEFz*_D@hBUG<`KVEU)ZcKm$-~`nO(pc-pdtns#s%au
z;FdlTlyV-2Jk?i}6FIhq3*D#WRabH+a!6GVs6K#Ko)T5S{l*XS8&+;B`^bIB@CFXX
z1?akxGPs6}W`NIp@M}ZDEgv$PF&92$IAg*dAH+=?((L+}niZ(NF|%|ZpzjgjyDPb^
zJ}Ieb9%>e9ZwxgH)i-307h2{D0BbkEWn7RhL!L4pw7mh1@ge&=p)o#WeGdR0e8~F7
z;&nl~3`^dJjBO<9y^?BamTr8m1dpyvy)MYs6;y}29t;IJ=$JO7$MDhUEx4i@1nuwK
z3~mu)0&vEG>N22aZka73@41hrrg20Zve9eLag&8U;Q}@4b0BA~04NaybjFc1%mAFZ
zWwu?f=StXgZK@7p)Vn6I^SaPsmRqwc+n8bVc9V&Y9o~_C%qFtAxP@9O9V#%G0XyR+
zdwfELDn*$gY4CGJYzjKm98InKn<K1)s}nC~fY<n&)XV^|aocJbI@Dz4mjZT^kq-h`
zw=(h{Lz+Yv?97lt*i9Dt^ekbo0W8Lq2F)hVn?~z=mi99l-pC>Bf`b`sBDbjrL;00e
z@<3ECaq_{b{A_CW1B*rG`wVoSe(cW}>j!KY-d9qn8EnZb;8ROQCPvH>+2UqA^8nd$
zCD^QhZ1GI9W|e}|jecx{A?-qKT}d5zlz7c59>T5bq0nho|BO?g(Uon;26`oQ+90#A
z3&v%cLe#CPVK_o9?QI-QydOOj=R~5oY|UG!zv{IMc4f!{>^=13+nRE>-E!@OT{bd~
zV%|dohkEO>nsKCa;jXMsea}n!VmKLI3EIZVuFI|lIop-6ap=76ydt%=vxtuyfEMqx
zn1N^UE|a<NEZ(;sO0_7cmMy5oE{nMi;#a^CK`nL}&5LTW(`a7Mid`yrK`R2PWviaR
zW}z4RYcV5nuy<L^K)!gF#k`;xh19ab!d$^!=ub&<F?N{D@P*tm8;7FoQ)7mv>@=+(
zORtLy?PUPITnV<C-LkamZ**Q3^F}r@7qrXDh2&l4@rFw5GLSb^A_%DrkQT4Rc@IR@
zR~pF)a=Aq|1BKY>!Zv_ht^^l{hOEJ^gnNeA#Vc7T=Q@zB4J3^B&V~)H$==mA6rz&!
z8GM7@Ws$>y=v@|h1#dnn!bXGyz%EuC1CYf9^Rfc6xKjBUfGm%<qfSG?H5%7&qk5CB
z-78DjR^W%d67E&-)m{-Bf<9~VZ12)QSAurRjdTUL$TXz;{fP1h&}L1Z?aK9g1sotw
ze@#aE-Z)SQ{AI+tG+EdLy9l*q0K2sPrBb;|n;hO7O0I2`a+N82puw&00%#dr|K1kw
z`3(01-sIli^#e8n=V@Cg)x^q5uW;}uMb6)l9*fPE#%r?DiH~U$rRuqEoQznPCTBK+
z;azB}E2(LeFB>UrucX2^t|VKQJ?&6@O%}C7`865TxNUOct)3KB7v;|`%uJJoP0UQA
zg-yszlQ)|eVcw*x37Kg!x&fPMvbhO~X*8#ah-pf>XBQIFU`^v{@0R(<)SOL*Gj0s`
zk>y;;U7r#){^&0Kt^894vWI<OIu{wlRysxl7-pX%6#+ENK5}m(3F{U&o&g_oC2V_V
ziR~gF;ffXn_f6e0TdwcsN;qp9WNR{|>!NrcAwvvVPxp~2ja(o5$W})7(M>Rz`Tb{^
zz#i<Ij9^@t?*mUa@@#G)y$tv6o5Z(P7xTNK`5#C!k;sv=8_1V^<m?6!%2xIpLw3o1
z-utWs$Xo&2K6v*urU5kAN3QN@pAw<gmn|P7lm?H65z5>KsAV51Uw~S+;9pm=vdpeU
zM_1(LMoPwgXgo*98<Iu_6y_sA=~|Tg$j=QJ%vPGqE2-I*pS!4ouYm2=4)W}yJs<}9
zZz$Eo%Cj9KM<c&>3=F2f;~N-_zINbhF5w@mO;G@1lZcfic4Kk&<<$l|%SVFJr$Wfa
z21IBRoOK1+ix9H<igH#%PVFeob|q{$*X9+l*;>9I2}(K4E%+AGa9#;ouA|-+aBQ9>
zHd+dCM=*ZIfS}m|bQ%8IAv-&wdM0%mfu5D6{gh~-*8805ogCN^=pN1SsDEZ(4`x23
zlQBD2g53c#xI?x$ur@nnjMtlZcE}h9+GYoBabRt>@LdM1%?{Y&K-%0gt;&SjTmf1J
zux5vBZvbnyFkd%sYtPm3`m2%3bq9>^!Y%HQ%No$eEijh>{<uRf>w|>AJ7jAETeAc9
zb|Pzb$YTv;%?{b$K-TPdJ=TEM?2yMAJHeH(?NRGN7CH8lD=9Aopfy*(#=-kY_}CQ$
z>R_WeGy4nE`rxp+1s7w&-YdZ~N*{*IX6(9G!mdFbhJu$3xS1VI4~9MrI<n8s0y|dr
z-*$Pi3pMkkh)qKw3N~hd(rlOQ4K21^ruRXd{dU^kr@)Qd<=8GoxLxWS!0GKW$Wekv
z;{^JvBRGIE9|=mJGiAS^`;>Ug%6fQ8gaJbNxm?|_Lp~Cea;AN&S2Y#ew~h%1y3c8d
zkJhqOA3XC@e<Uc?4AQAR(j<FQQnNe&m)XLC4KR*xpQ;5dM-<m6E|*(|<6yu#-A<SF
zfCc-Jpp<h)uQjuFUkRQ$IAudUflBkC@j<OQz1AaxA8wh=Lan*b)l4eB-PqK`8Zosr
zYe1%kCf111)uTZd3feW=t<w3>h0b<8bfL5LN#63^R-Kk}rcKYj_V<aHX}YVgq&nX;
zb0AH-A~ap9PcSZKdf(pu!XH%Eo0^91^G3^e09UiUsqK&U+ehuz!relGG3or3ER<7Y
zUjf_6Q{h%hfdLTBm9UjEc(;&XqYk)x3q3M$2;Mt1L@3N1XdB9Lhgv#S!pop`+^%Mz
z9k**hr5$@aru9_n@rqEqWR~qHP<0gYreyU#0K7>F)&ih6DZ&y1_9jLAj1qs75;PA7
zMv5?By?mY@k(Na7?00(~)!A|0NL*2MUT?T}^j%>20YFWP3NJd!GgKmW-m;@Y#}D|I
zQpDy;<E4n-Vn_DHCNpfnd6go}Un<BHaQaF^rU-p16`2xtVbt(KO8~yMkI2>9#EU3&
z{R0^~<(inqPVqWn6rd(0SS|q6qzKnF1CW}OEePs$$>bV+qlm$ke#{gfh*TZG;iQbM
z?V56$Tm$j4DOwN&E9IQjgD^Inp9TVPQ^FoNhBh_WauB6x)q|YlAhLeIwfzwd^(pWU
zhz%NWkf#Xu7z3D^l%Z3HuVtuHhqG(y)#2pY`|=KZ$^+DZ13yLRg|#Z8=hisohD-e`
z!i>|R8n`I<i0I}VxJyV8v}3_^QUWzS0K!RGjSnE4l;G0_sOBST>ZP$;qF);bqAywF
z&n9c~Va9$n6thn_D?cTw_aF;v*uZO$iFHNQbJwR1Ku(Idxg;bfC2W6SEjsJeN|cQ?
za3z%@&|C~$T$K!SK5Hp@sQrl-?15svT&Gj>8MZhO+<#ojsxs$nv4gHYFLu&VOk46(
z=8<avP?I7&c%y$?J>FQSuNh`IY^IDI*c`@I2R4Vov)3@c#ijNU!I3g_z_A`)iw&eT
zDPj*C>%o^gfDJEY*oi><@exhc4EB?k8N*OyACEdEbIuNXMSISuONF?<B6O;bSi?%i
zq(E(Pnev!52GyyM`eRU?I$fz_AV#cYjXzr@Ko3Ua;OeM#1$YHKYK_sWNV{lse3Wi#
zzH_wN7zWkmYs>-OP@*~?j!}Bko4QE7`C4y-dXwhcpwe{3!Hq$!={R(a0j=pgcnzRE
zGNTi_34ZlfRvaIdo5eor0a7bBT6TkqREYjDs7Uw0!D)a|s4_^Q3p2<2+IB$nq=>Ci
z{qEo)a{zhsk;yn4RHU1i7h~)yV)GhQq}#Q9g2*Xln5WXC+to+v(d{Urhg%!WpcdU*
zZBvaZJIxqSqY42SfcvBfdIor(6k#72RJIuiFa|ZPA^}Dwol+RUD1gsXGBy=_+4|xK
zRj+XU19-0#@nQA;QpAB!^$OoV237B#dOS7n)}e0zt9oU(Jg?eSLX9!0b~oV%V^ZyI
z9s4HLZbhd*kYU~G<Ts&r6+SQk|GA<pb}m|z7M#?~j2;-1npq(PBjG<Oz~F)RNfA7M
zV^*E|lf&ZW$`xT)JQPf*<lQv@&`+j}L!e6DviB!d@|L|nsgfBna3%E)n+8FRyqktW
zt-NJQOlsw=Qvy*wDPtd?l@(ktfb&Tax-hXq)=?iO_IJb=j9F@V(bAvP%8CoPqUt09
z1IC2LU1Bi5A~Y_$er~p|4P#Q{F4x1UaWA}}9_3ZS<_|PaiZ~xsxJ##lNrk(_^EkjF
znKE|3F}a8#$i%a`iq}?yfzfR#oEaRQjtGEiXNo;mq{d|oz?e9juBokkQkyQu+>J$T
zy2^h#7Io>8VZR!CFuAv{#`z`KXe=sI1q)me=9iw<QI&=cNQ>%J;R9EM>Ev->@$kBI
z99THKE(Pa}#nbDO#$Qy!3LCg0ycikwiy9WnbWxcK_CG)-n<93T>QtcsV^N(Z%8Ada
ze(IZE)TVe0b?G8_>5A|Q8e{6lqB31N9;{NPtEu_Pq3MHORHhk2P?<-vhx4d49Au{s
z0*eRPse{1cId&dx!iySMkpp9G3<mF?+IEJXUFw#B0#8b+*NPPwi#m6P211pq_<^yg
za_c5wEa=<m8XEQO<UwFj-73OhEUMe-@6f1o6=pCNp2Nli>vlSdwLTPJFcxBwQ-;=g
zLROH$SU4e1ofbf6og%h<xCc*J3B`(?60RhwX~i0hMK#S>gRxtccy!y;!BeMzO&zRA
zg0ZQC6-qERRWNq-64h7;oEV!b7|{e{QwdKUCpLBPoZ9m?wXh-&#x5<az=JEmd*c~n
zcfPfEf7v_<PaO?5RIh>t#^zyIaRXyh^G*=5k6nk{DYJi5rB0dsn<{m7J)0_Z_P0|!
z=pxKuY$((zXYi&%ojO2lWlVh!5EYR55jAyTaXN8a0JnY$`0&!Zh&1?oIvYwAX%EMy
zMjbNnH#I7Q2FAX+a)bt|!|9Or-j22hflODlO27wGQ;yJsc{EjM!Pr!uLk`<b^*Qvx
zZ>Z0qGr<O^DrI<lV3`cr{JWl9f7XnS&7V_g4iQTZr`F7Hfl-I9Pe~TKQ)Mb<U^rFg
zsJ-+lS*_tA!`-PfhYWW|EqwV-l{prQu>KW#Fq|rM$gX$l&>_3tp+gmYFnG?rGL-TD
zWVCx7S%*w^r$SYH!Eh?n@tW*Ds?0GB4np?2Q^$^hBF129d(@3W%IceU=vPG?45xlo
z(7|x(SOpynpBky0`%WD@48?r1tazt>Wfa129$!Z%I$=0ft|AkLQ|k^{`wp!;WEVKK
zZUrYikYRn$vWGJ$B^)r7?vQB@LWmU6Mc}1*6@M_CidPW`!>M=~f-szV*UmdaDqaL3
zTtN;-K?uXCc@>2)oT}Ge|G!iBn*9Gx)oVNzcvJ~{ic|9<4&fP2<!f^OJCDDLO&G|T
zlp@YRaJa7f8>jkJfWmN|Y)vM=)2FQXf)TBXG`549Rq+KQs96zUa0T^Inr;IEO4J0V
zx}tjLw$vE)sOdr=s7Do=FoJ5-Kxj9>ACnSHRZx#IK4Ap)sOd@|vN*{VF@ip4gJKWr
zS<|s0cv3Z4|G|@L1spt(t&(6{3hGrGUmk@Q#Unvbh1z=nh{@^IjuDgn)BzxrKU~)V
z0WE3@9v(oUqzo<6t86+r1a+;kh|zU<7@}0I=_G+$ofP50^eQX7VFVAR_Imzt8&xt)
zr?Y)|{(~AfgBV7Xwq*>%laiX<E_)x$QYqq$P~CPp{)6hazmETazU?{z1W&7-m1@0p
zdH#bQWh5MUN><}lc*F?&gsszm+yljWiCwxs=sjlC!<AqVGWHKNb(dX#sHwYb`_t&J
z?~XEhEaU!AOEVZ^oL(h1L?zv~RN$eXxXZFXRMd)w7>9~l@et!cQCB<!pH=IV0TJWy
ztgDEKap-dHx(PVc=v_#xaZ06kod6D1x*{V65Q-m>P5_50oE!xu!w|7A9O!4oIgCU7
z+-1ri>gT+(eIP>Dbzg9(o)H2uPATZF+k!&{-G`16hbp@3y5LYlcby3iHMBw{#({>e
ztLz6NtQFiBoW*yg`+~DDVBtazRd(H_*ORET6*4gnb#Ir&f2e#F?l2BiZ3Q<x5TRGP
zGdR?>9fyEJMcZ`<I8?N~(OJQ#uq|rZrVE2ZRjVk8k*MYr0FpNjHEn}^aHwY$B{2@w
zEW;$mp)VQ<e4di!XcanfCDqNQgU8_^x6#XR)03i`LQBuaGpxcNW`nM6yfc`Ms#XCI
zvr*MH$2`qqBuz<8)s>)Ijv~6W)fUw(ur^Q0>J=!GVm1`nIDN?t$C26SN@g6zlQIl#
z<0rK$+fwT|^D4MvHXd*rj~>r#)YuB9n2pERHr2(+KJnaeMd*|;V6##6Hr@x!M%9~f
z6SG0>wxMoP>$dSu67_E5`C>Ne-8R$%>fScg^-{fLS}F+^=0Fk4($oQJ=Y|8uY}C$}
z)u&|j{!PvEblgmXrN3D*7ZXItACd4vvr(-x@Zw5Vl{pZqYz0+Z5xTC!!fe#pjW+|c
zQD-ywVm4^()-;*a*iD>%vr%m;2xB&??bg%@YHfvP%yxbpgk|JJm0fT}XujOkSHR{=
zu^&WbOdza|!ZK#V-Q+nuOU&G|J^~yOZuySkDClA$uInJ?V)pu*bJaUK#v6kP3h|?0
ziU}CiIj)Cx^vw$eGYdj>6mBtrpgPCZ)q4Bq@a!<58P4I+;h9h$M}Zj=%<4yR8MElu
zQ?gJF)M4Y}$s$`G7$ffuCN%CjOI0R%2it$9-abcn1`~0P=S+2^H0qULM*w2#O0aJM
zFm)w$(Rn2Uwb+}5`Q?4VgynK2oQ72sJO~n*Fq95sEG8mLk76ulLZi+xJ$7RV`pi3S
zgs+H|91~up`}3~x1={QyU!c*h@kKUD6MiDS!bgHq%~?|y0&~V#irL}iJ*TPRQ|r8`
z-GhbBGr)uye=?k6!q7h<mZ14L2%Mm;KXFnxK~sO?IB|sLo8T2XL7ROVJdP)%V(a*F
z1j@UDfm(b{P2iQFvp5DlC+NkWI4gZ5S-OAen*;#r1T6Xq^wR+^>0J*%KOF^FOn{$`
zA}nU%pH8?MHH?rS<ud_wIt-_n06HCoRLq1q9mP{jpq#FR4S^Nw2;DbrW(nWEO^j%1
zj1xmzY<HsjigCQ6?7u!+o9O>iGo>X@EH$+-psDQ`hyD|jZLJ*9)Cd<wRMz{1cj3fT
z%Ya3lm}<KAm!pu2S*WNJLxbE{8-opR3{sx@34VtYrdpo8qeVW!4{;PKG2x>*2$h(~
zOLWWZN}y%h*%KhA6J5`(MSY^{xxx3?@!<MrP6E_gNFM|6l#<5Z+|DZ()D`3hA7zry
z(J*cLxPd-8$|pWY&l0}W@)bTQVijmD20YAiO&(<opKxCu*Ov=y(v<*Tb46CQ_}s!q
z9uGbj`pD^#zml9aCJuj6R0EKOJw}$;a+zz#olh;3?kKhR9CZRb3BsF+7dp%mKEVcb
zgqfSb51ou~n1Bu)ML0YYZu6rMhY7#>@uhi%BJ!o-LlFrsmk-K`U21w^VykN#lR7nY
zC@P<7dDoHqD2Mn=^wAOAZUR|!GE8FPg5tOg<hsN-F8A34rsyb6V&d}SC@Nwi;oebP
z#2kU{4wUk^e1xC7qWl^eC2<8Si);n@O+gY9S3$>3XMh1E=dy}{I66Yl&ALxI-qkd8
z9AYV+l+@zuY8_h7yIP0lQ_}G{TbA&JPFS~xaS{_CqAS2t!Qpk3mVDw~?I=`Y7Vp=o
z8=wc0?5|=YCbCMNO|ut?Cy%m`Ph_V&fYd#6R)MWR^C?nd0zz~YDRCvaY<H+#WU)KU
zN<Ir_bcC*(xCT84l$bymogHc#if{*gC=&pqvqNnUj8M87={=7SdUH<n&)=znZre0{
zXHn5z!CR|3D8m=m&}VN>6*SwH<qKZCv$<0wvgmACzCae8z0~l+sbViRUH^FYQqxdv
zNLM}!d~^h}o4B^W68HviwSOgSd)E-Bnsy9GCN;PV4={I6iK;WQg#i~jLd(rU3ta)W
z6JUj|Bs=(|sNNLqWl#VeB`2=|$Tpq_eK9oy0@$-n4W)M5rg=D+Ut=rfA3DlUekC=a
zGD{cK-zIYYN^&%Gl~2H54%3%UKx7U9a-ZP=8g#a_Xd#1+Ky4GaptI>DpMd^+Bq*iP
zu#S2H?YCq$gJkq5JNX2n=t{6x6j^CKh)s_yu~{6*)<G#h=p`!~h@w-Nkf$U$x+N>S
z@I+_H$Oc&GtUxJ01R>!jX@;(d&nO*rC49)r5_=7usg&kdQhj|tWn>ILYpW$F%|#1(
zmC9T)pcho;5~Jn>V(2KV`CQPOOC~g6L}$s2P888uGNRY!AZbMdLUh(r<4~<ibv^+g
zIzrLSf)Jf0j-Uy^&{<P$d5wxTG^Y9}8Tter@d2dnmUDf{J_fw;EE&kiSbv!6d;$e@
z7Tw<yS?`}KS`cJshk6gixrSyAigOJ$4aNB;JD*thN3gm1`7X|qk&W->EEw7Nvd*H<
z`$}?vba`LFMiqSh8%lD?h~7|=i(mJ?eUMvwZm7W3)DfsaBq^Uj<Q^g5CeS`-0R{ie
z0{fiR)DbAaNuTxv)aT5j@k0eFN%`D}Ryu;jO>Dzw()0$f`OKrXK4-rfY6oY(8SfZz
z_!B;EZYVotDxU!K9KqUVYNK1uo;)eY>7H_0L#bT}ItSgR#N-oz^OFF!xe<eXraaag
zx@~TC4!Uj1UA;@UO*yQ0Z3oX`{_?q@?F3!Bk{Z!QDZlP1XLUk^ZkaYNY>K0t=M!+C
zGv%lTS<sm>w?P(krmm+Zpg(8I;D$MMC43O{-;~=LX4yxA(p~IIZ$1$yafm~k2#GyY
zCOIN5&Xm6zVHwYvveFAhbf%1SfQU{eL7%`69Rb-U&_gGUya$pRpUiZx8f+EEMdePP
zFrbfMZPNi|Ia3xn5>Z@9jnM17sLbeBP+gV1?a-L>bx=E0=9GWhabTRZ$v@|jGi8tC
zymFKrefr=sl|c@i(3P-hXw50NbfJXKkcAGA&~rs-8J<ujQJ)|pIsnB@z=O_^m7WNp
zGej3Oan?ISMtU|&YaEBiBY@n*0rL!)<H*W#M!XNG{YpvGC-6Qg!R$k24tc7bN6q1Q
zaB9pUM>W7dXUI_v?9UM@ZUXyrhG6Xz2lX>#uh&`r44LalgL4M_)JT+bltcZQ6_<Ai
zv74S}OXNbI0O}lJ;wHQqXV6Ps?vBsfo9YI1pAwx<_)U)RZWB13E8&9?5P3!Q<Y@Wt
zm;qpT&X9{b8Ww@f^7QAN@t(*7XU0K`8&07!<e{!W&@*I$gO=kE>-O2ykqPQ3wfU9Q
zVqqyKQC?~|&d!jRnoJ~zNy}$N*dC$IW`*Hi2}(6*a#JI})fw#_AN1Uin>uEe*edkg
zkOdAD&PRe$Z7?Q-yBw0oWN*W1c}!m;0-cZ2mruk(KZi)M89V=-HK5>3wlW;GSHhk_
z$C)^MCj7m}0;TMkzCIA}9HUPfKICJvuLB9qkIBFWEa#Yv>_p}qWjLR}<s4zmCNMb1
zHn(>`aE{5ME&$FIupyiPl^1;if^z^ddrIV0i%kUvC5t+s7mWrrV*8Kspg%K{;~gQ%
zCer5}lUF*R2~A#UU~-Pho<7LkdW;rzfpm^ip-<d@9DvOxE=X<}P2(2jO1Kx}s^yB%
z_PJGLa^tGzFk|`zJm;89?n380DdJBy>agLC@yNo)mC`YN+^4jqDN22Uy6cMA6x5}`
z$i`jOQHu0=MwKunxYa%;$2PDx$K=>X7RqCCY$H?UG5EC$o^woDS0~^(hw!usaLzHg
zwt>w#*3|UGc*=qHlxX8ed`t~U`vkx<r_0JN?934iZ5{xgPM60U$eGh=cISQQQFil*
z8`INeQ{z_kO6c&$-Rl+cxzKE#9`941>J@O@&}>L>{*<W3AmjX$ZtHS-gVXPHn&P1S
zJ4%86%)F&Oi8h;sc{$8vK7n{SUG_5oFCPg?Ik8>#^1^-m>2z@~T-qN2!4_`zPp1XF
zl7R7+;agcqtNRh*pKBKB;l7fZM4H^ILDO}9x~o+r)ag?V!x!2oO4a+Jr&h_U(Nc1m
zntU}tJ&$l(s|_@0tWXNBn>qjm*G(OOlI!wQFThO>bCai}`bE2VwU3hPT@6FY_0EQY
zd^x?VX{f#4)inH{%2&P$19OD=TEMnEr#C(s&duKR;5+~-q4@%;=Lp=j+RhRz?***T
zX-EBsDr|?XKohp3R-g!h;(AtP?Y?ETQhP-^>OGWUJDN5e_FAZEq^>)HaIJ*A-146M
zNv^zBX7K{t<+M=KP>xMr>IJaNX`!}DJ2sxB7qBj;xmpek(n;sM(D$R%<_qIH!h5Zp
zlhd{y1J&1P20sf3xhq=uN%fd^@B-5A5Zko?YiV>_uMYU{Y4lq!0$Up0)>o2mztL^I
zzzK9(S=6i7?|~#<1i!S!cFQSq1#GzI_@-LL2~cUwp9SRN5io2Kq0)xB1})a;vR<Dr
z`Lv-L)MAZL?<=Z>IoLU<EF~phwL2W4wia<M&9ns)*wRdG&6-?OOHf+P*wVz*Ld!lW
zsv#MEP{ZkJd1Z-%!)dN{wSi0gBQ)0{fQ2c_Q&Q8f54sR6t$nFe%d62$U10b5h_d8A
z;vDs=tjbV&@&&we2zRwQq8+b@t(G#o61JPl><X|gf@41L)cVrm1kol7P?;b!YXK>9
z1#J0#)Nw-1mWK?x15q#`Xx0M6C623K2i>6gysV)sG@q{|cZN9hP+w8?1s>{^#z`ES
z)3>~H;%HAVSTsS7!V*<~>7ZUPjpA%Ip4L;GrKW31M432uX#pJ*XQ}m$aY{)891{X;
zEvph6HonBk5gA4x4P0htO6nJ*x;E9<fv$<ZdLbAi1jJg%5OF2gWRODQO6s{Y|7Jgt
z?&pfw*@-nc)N(1v5L9cy=8t1)I7jxxF*Q8#@(m3yyn0jP3yaXy_QIPtM%66j?1<CV
z_{L|`^`MO|!x&z97W<Sz*z%;LdehWDM}Hdn=jaVB-vy{koW{o{|3DmisTZIw5l5XX
zl@)O`Go{u-S<6@DU3pT3y#+_zD`DgH;YA!aUSH-Fu=V_SBb5DVAwDaV+k7FJOb8Kn
zCDlWzTR>i}g!{wDAzukP2*1IVpo8!$TuF5hG(AE5){~-KeBt?n`)m5G7t;Mi&~Lqv
z5-4J;)vMp4IDsDsYQlMLzLM(v&Qj@wh^1z%MzYijqK86B%@<HJ5&EJL0U05i8K9UD
z3TqVu&l54#mw~>}C%xdK`bbd9zQ~A%iz|Ww6$@^#h@oaCrgf-u6SF$ha6Ofcg3UQH
zhxr1MCWP2pK+;6e90!mlLiTv!Xd;a0wgu=+DE0XQbS4DjT5vB$$hfW?U@6gqJd5l)
zl%PObS5p1$daR?rO(OtlWdzOdQ93YWeZvzQA$1LJZG`Oa0W}yR)cjw5{JZBa+V-jX
z`I+1L)cq)}<}t_TEcEaH?T`QbqyK21|LTAL!{46Zw^6hAw;!NN58W_#q`mk&7oF+w
z^TeR>)+eSY?0zkM)prpYs?gnjxER=beRKZO9Jfpputkg95u2TfE9)o72j)X5hbI%O
zh=v|?KFVGKBDj5YXf*(X_sbQCgGLfDl5md^J};BpV0`u-ic7-{c2N;z$A>fg!^A}q
zjIQnS$Ky!L$bv#Z7wAJ&_A@t+6S`F)z~jB00>Vz&{iY+S&QYMNJU;z=IT)2m_o}Ud
zubf`1T19hxmc;z5o;i;7{rSUNKf8ash%jUCBHDC=e_ceS0p3N#Q^uD?#53@hg@iX&
zi-{Wy7n3930+v!~;zw&Kmr~8_yOiD>U06z{d>33wt^Vctx|+xV&ZX4;#ZnS*`pZ(<
z?=k}Y()#5h+W%q^y+PscBGTPTYorcrUoq$jiPgnWEut4r$VJ4x>0Lw$`ok(J_dQ%v
zTtxn>1+-+_)dGUIy4KI<p!ZoopJmhc-F`lQtl9f#9{$k!iJpbj&ET&Lkz-^34M*W_
zofY~0lpwcGr(+!KnjvP!V&DwXGJ>Qt5)T?k{}W=x2FqtSb$!&KFht1sQB@%-MyR^T
zR~}#!2*E`Qo*X1s1nN2Tk`fkui}i}YLLWZ)hQL%Gq{fbwf1@W0b46DeG9iRh&lB<;
z;>`}|Pth$FOgu!j2q1ZoXc18JAXP$2@>3RVHt7FDEQ`ra8)8@l$88Y$8OW*^0)N(r
z9bip_Ef-?KuEiFDcmmKLuBazuMF`SmgQNGB>q`TTZ-6X2^2jKv?1+N<gy5a9OG8ZA
zfkUN;vSHnZxE9O)jUrlnN>EF!>~`4DA?PQ9D8hNsjI0$QitN)qR-4!rPi+<fh$jvR
zA&@5y5h08x@*TuJJfzgQBQ~vW1fYcQoQP2gz&Vl6BZTIxgda~z@`F8=f7kW_Uh5DE
zHu8srK%B=g2D!&hErJlw;>l$aoA&!DYcR;Lh~r*}Veue1H-rL3#)A;W;+g0eJz)oD
z$D~B8!)|Qxs2rRKrGXEQgd#u0kvTR$Wt^x#f-0=khd8Bt(U7&PAZg93GGPqF#=S9O
ztYY)(nEry;ygG)LA!JLH7b1k-gr6b^-uwYyM(hD_X~vz!=Ghp5X(6O0V%I`A&4VMN
zfSQLVL;^KW)C%Lp(h0l@o{CRkh0*7A0&7eJ$L0P>37W;(aMKTl$h{zv6TyAAjAj#5
z^C@4uq1732<8*w>)h7ZtJA7x60M34gEMR7Dh?0oKBX5WE?Tgur3|1j<W=EQ<NN{Ga
zV9Z!@Y+Xs&NHiZi+=N%crb~IPP{Yt(OSVdH&{&H<$f;YrKl+#!Sz;S?_KGDFtHH_*
zp*KGUN=^6Ls#Z62A?W3mtSoZ^aQIsyHR{NT_7P?2{(Pxd&|Sn=c0>q=@Rgl8*+Kxz
zj>K)TmYOZ~wU(wG`fJrwp}m$g>J`;cCR>L365g_>hy9k>Y*~-7s70SEs<%fy+7aL#
zOXg~W`*RIFs1%tHmc4-|CIqqUxNQhQEPI18TRawbTw7cT#*q4K8Fh5W)yEaFZD_P*
znmed8!7Mu><ztChpjSA3EE(wtxsTP^HuT!+8aNaih!_9*q^Q;cRqp4EkR`O-8`cB$
zZO7fyJwt>}6{V#YkIo$_83PE;4qk&;O%E=O_nt(M4KfO^`9PE-5Mc94as&cwUP%sM
z9<)?{^S}e*)*yJZcW6F=H#;s2LjcZ>OU0O>c1!n7Wp3<XnTV-9pwbt_47LQ{st}%6
zQoVPAe|n!;#5doe4u$W$lIpJWsc@wV-`UB^5ee|T#q26oYzL7?2;SMj_7Q@2c2I)E
zl%uR8qiPV}*)!d02;F(hxs(&#c}w}mh3@R1^Xe0GsZlsx=Tf6^x=!sQ9g0xc&W^0K
zPl#*qidO!Fo)KtA;W#_an~^xqj$8bga(j1N^#_rhy}$q=AZG_&AOz&>9r}?t&L>6n
zK8IR{`*doPK!$^u+!8ueqM)146|EGose=(|OXzU9PHhPW%{aUKK|pSW$OXIA56~6R
z4uxQu9f_BNu*{C+%rTX+u>(^Qpc(8yorHjy9mtdrFtY=`5(H*GDY`Q(WM((0%%P7P
z)J*{#W(T`d2#48iJXvHj@Uf22LvijCTVXe7NC7Q-fr;*e^kE|Vb_i+Nk$oV9wCqSg
z5CB^C9E}rB(+!G~?1NWOozsU3L{*HfcA+=n26;+!KVQKtJD^$tm}Li;D+IHAeK`D5
zZF7YCi=StumxnDwPXdeCE2Dar`BXSj2P2+(A>l$;%nq<z2#eW4xfa4=cJQ(V9Mw;W
z@(UmqvnRn@2#wjn0T)7JcBHEhp)tGR&LTum*bQ283^iU#a?sGef?9NgO+!fz<#Ou)
zCx$?q9r(o%L17;)OK2Er31ZM3zmigk0(D+d4WUY<{sijm0CR>wogM!cgB-(GQavN8
z^Gd2`^^E&hQy+2Y8%_NL5GI7^?BGreQ3`etEQU~>y*L=JfUVZdJdrrh4!COw=Gkj{
zLom;dHxPn(_5oFAujM_U>j?9_g4?iAoL7(w&O%**DkIn5lcIbZf^v2&>L8S}=c*3@
zId3@^oN%1I7(UaLuEuwku=k8|HHB?H6URPbHm@YRFJiDOss8KR#f}p~TXyV9A-H8P
zzSO|==TnlJ&Z!~dZjac?URd-neVW)L1K7$wz|I%~S9a{IVN;`ovJ$qk=jI$jSKe|>
z-5}`kifROP2heB3`jB~DgtTEYuHirrp(~#&%H=P3Wk(c32rAi=RyPEe>=U|5Sjk@e
zyzpkr!Cl>>52{b7tJmW_ai3?>t`m@xFlpC0vV@6&5fCQr3QHl3+7-q`*sEP(aRktl
zy)2Tj_BMjoCglpM<goV6Rb30}hM|L||4Ps_G@LM)9X3{UXxj;|NOY;&S<hs<&~W`|
z$WU=zmNQ7IqYJHdMY*U1ue_4`VCh=8-J?s_P8{qybnQf7Ldf^t!O$H<TXrybhtQTC
zbp6q#Z$SqBMBi$>lv<a*olt5W`gTI4b%s7&NsVZ8W1i4xUHW#WO6$_MI7&p<4IGXe
zLG0#d=K?c(bZJ-+`G=5~9X$TgrD1WV3c#H1gK%dTof<aJVYi6xA=WOsH0*+U5<au9
z#z~ikT{y;dY1j(ti!KcdlKkk@uprWpE_$vGy8TGB=PjiU>(Z_$u~Dd~ZhRt+(;*aR
zM@ZvGlBH5VUCMPq{Rp7hk%b_-lJH$o^-9`x0r}GFA)ljKmv)8EA-c5d0x&d$-|TQz
zgb<t^&WtO8S}A`=bZJ*apneu<YS#q~*Q8w+6dWO)9dWH8NM{F)e>Ac9_qA`a{;IAE
zsoCK!x)MCGR9BPct?1t;MeHXIYmKFjJ3>Ab;Fm_NyYk@HbV<~apd*^pF0y!B2^)qw
zY_4{3c&lseRZK7;0=|xr>1aCdBC0x?RC7gMN84)n;GCJvdbe18*J(CWnM9*otbCTA
zG77o8n$+<IvuHHx<K44>QGp9TM48vYgda_sHm@h6y{Fa<?be2#iP_Sz72ezsUtWj9
zH$a#7l*sDI*xBJ%4szjjkOV|CJ$Ph^55>29Mc9uw^i-3#2`=(0Stw_-(w}g$N3q>K
z5Y@VsT7_#q#C6w^)hHS-c=}#h!p6D@UTM&&xEu&^++9g65h>M;lb9IpuH-Wre$G4p
zbrMSv8ZO=D;I!)?s&H}I_2jZ}5!&^Q0Cqp}KjAXOkF@CaEU}SV`7X}8E6Ka^gRGcW
zaL3~()NW}yKlDazui;1wgVDo}Xni_pKU~y!9cfiv)OZ~?PJW=8^Fqpx99BCxKq_Wj
zYWb03Mp`fzF<wXJFc&Xg&-7v`z^z?J4zer4w!Z7|b|q~6)F^op#*LjHrP%Da)$^lI
zJMRJg$S;MIY<_sl)Nz;SWY4>T)Qx_Kr0$jN?MhI}?oTz+(R*of@96#1hUldjUHp1i
zQj3F{+^c|H1AIFl2}-GfE;NJ9CKlsJgM+c(j}*2WUWPUi9~jBN^72uGk^SxigV7e^
z1A~#{tEh`U5+f~H2fdLW?lV5KfTe}Ya0lMA<GS31_w03}{-lTvPb_p(!?V_ajQP5@
zFG(#fWI}wdXhAUW6E?LlAi2W9ER_;W)c%x2WYED@<wA&dq=9rGL_5F=uH3x65=^=P
zp-)E^N*5xudnsBMBJ@gf4GR%^CHYwfb|O!psS6Ey1-Yn+2EBq@2||N*5PW%PBLdpv
zalt`5IQTuZ8-aq~L)T+|&|x{)9O~6W_g{$?^6)Q}s)O1}kR{%U5ADb#?*uA*L`XO9
zi4X0SiQWYf?ZC9SAfg>mAs0mSO7djqp=~6}%)63m8Aw7`_TCP(p(kpzgEG!z$(xak
zaxT<p2Qi&9A#VpH#zS{x0J(V3wtqTcE*`q{ijgH462NS_0HYn4PEWvS2MYA@&=vrW
zeHZ@jN~&wJ8o;{m0*GD-0E4vRkr3DuBihkt4_Wa*zPb|hUP%o`W<}&8m0bb&>_>u9
zel5zm+Y1!q!7Hu=w0w&A8?RB80@i^O;@Ll|#D(wdfEl~+ogGY)9?GZPK{x5jx!b`>
z>6vo37Y62H-`FVhs?$0Tu+d%#TZURyw%raK3^8;)fiSm(?FgTnyEq6szR48nvH2cd
zA22>{7foQV@81!7|CD5+*1|6~>ag+Bs>Fiz+|Jx#0UY=`-Sy=H@#5tF>xFM|mwE@l
z#a-uaAY875>JTWGE8>Hp4#^bQPZcl$z`3~V++DikNfDb)l_;LTj-Uj0ewZMbb(d~0
z4q7jSb%*+O*Kr!C6;C$5Ua%E+eP4jBxJ&7l+3=(Yjjn1!S4prwJem7CtP^*AUI*&P
z6${m2(zweHeRh`EDioCKUJ3Cp9|=mkdZjO}uq*Cevjz3!I$Q(2;-cv5uofS89hX5u
z?<D2x`3!xEV4!yq@^ui<UkN`&L=s&Q=P0mL8%npYqUXDU>?`T{`hm~W#n0DanqLW9
zu8;0YI7_Ljwjd-2s%k62%@yS$A|anOD5lMDC@Zwf6#(E0xQi3S^`t0Y^JX?1D?)D<
zBcI_Q<YMGA9F}}L+s1*)x2tg|sO^8@Pga%)|Lz!)tKqVi{AKksKx2GwH4PoMH=DK^
z<W|FmLGBkET(4lOZK%Dy)i$)=-Wv5tL@}F%*4qnF4~FBdi_*_<1a?sR-SS2qwhKi_
z$&;dkO6&?W;a=)WX~I3#8z{m(ISG?voazmf;RbRU7@S*XZ|a$Bc40g^{#%1`6j7i7
zGUI!wZyQ~q)7(H<?^~n<2FJ)1v3F3E+t54Dzu7bBNkYl20p#vNlNnq%E;yM1W#hZ6
zyQM03SF^Q*9|scKfU$Am$qX19C!ov#v2h{FEHO5|MZjyo*jy1?hN|3j))_E1zIhX7
zps@F?Ogsh>dnZ86;9&E0G|Ezqq7*blUOOoTKZ~m45Gv@}mE@>|Tr;3*e8D`oOz7c@
zy4?t}@x-ke05&dCK?Anmg<CU#Zd|xEE6|M>Zta027t9K_3pKpx=QCh#e6f^EML;%V
zwi6ec%`$C@FXuCBp}BYl4cS*dk}Q>aUDEspfASS^biD(3Wlgg-9NRV~wr$&(*tTuk
zwrwX9PHawWCllNGGY{VL{?|F*Ue~U@y1KfnySlgPUaKm=t{0_Yay#Xr`Cd7T4td$c
zdy|*O8Ck=V<{n8ybA}bTZ7A4^DZo-|hBeT2GuWDGX7{yXmR9;zdA@iJ9ocMCK1Qzm
zL$KB@--LgV9TTXU5&jwL6u_&V)-D5(eGjM<(~s%vbmw9KQns;E`x-sVWV^x6e;&pO
z{fm7+g0vPaNqRg%Sv#MIBx_NA5NwOHBt{#Rz7ugG<pxoc_ht;))LG(S4}wM8pk?k*
zTeJz(qZ$Z>Hgwir@Jc!W=?2OHATUuyd!!iPtoZ0kE6QI<)lDX%meU6Av^!Bl08WyX
zzOy?sYe%_VzGmC+Ton0j#?JUeX^ZZHMLUnFf1?!r^o%0>SK<mS^OaHXTg(8Xncv3O
z*DzRLIdr-SYr}wQzHhiBlh%31&7qEj^Zk1nY=ts~T`lozg)NrEffhLvF!M07u?g!6
zllR~=fOntYP8+>37*0&2z>M9}h2u4~CBUwiF!=%W5;zP@jGTp={LT+~a}#IGV*{Md
zgp8$dMIVVVOG`iewi!d!ClI=;Wnc-Gs#*+waI%~UzY_btVd@>`Rv0W+;GCggJf>}P
zEh|5h)>7?ie#``j8JPC%njoT~cEomT*kw5Mw+YJjqDZP4fTZhzOrAL9%X@wJV}|$_
z%z`|x<4T&lC}7TqBx3X_b`Lld%o!uFt0-t0ldy9Kz%e{v<8FBG=EB1Xv9jw7HT0n~
zN!64UX2x)i<&PSIQq562SOhFnS}owPp=8J<DB(S!^lF%1Qgrf30G|#dud<Qr7m^0J
zV`_1{unIn>NKA)c9S8;?K`k{}t*l?4K?nc`v@hLMV{*}V-e7T2RHfB`Bzu9MKIkLz
z{2_pZdt;`Sz!frajKInHk(<-K(U(H%<uLnCInUOx>4DlO*4Dx)%Meq!lGc`>sqOtt
zD*lHCvKr&X2V*RjYF;(cjUlKn@!aH#noFTzR#8mzXQ&G}r(D1kB}9{FN(IpxW*rDw
zym#e0g^r|2EM6%!UJbDaslNk!Ft?d_QEs^Mxq{Xh2@G*4^ljT+j7a=g{B$=UP#EMV
ze*_r7O5e&>EumIX&tasq*Al+|ra4lkeEglfZ$)`uDPxv~4r>A$ZSUU)GlM~fF#!;5
zKmQ%nED9TLJZPxxq?7x1x)nO-kQ05#hrK7TmQ=YG!C~M{AKlZ0w)U@lbgLgVPIX`d
zEkwHGN(HA?vfX|@KX&%Hcs@<2*eAm~r%7WSC4nvdrrKnhVXTdnfGMp>g3@L1jsO^#
z_)WDSn7;0zf?ZMv+mBjPo-gkj^Kv6713X>ls#J#eD^Y}7p(;;hSQaILac+DBY#t9w
znFgqQM)HAyiO%Fb1eslDY-XxbK)0FjD`-#9&<c*V|N2Ad71ht%DTPwf04-%=Ec+wR
zD1;uKENKD_CHdO2B{*pljy&DJWi6Pbk@&%daMXq)l|aFuB`;{K&4*xYaN+*M2ac8&
zjTabh2vx&2ujDZX{;{EuPu++uFRr6|4b*$#;6Q_2(OHLZrC?mSx1Opak!pPzb$=g-
z&BU+IYlp1&WSYy78%s8fc0J8ICYE+0&A)%sADk&jqy0)xw80B~ef;$Jw|9BvjQmeu
z%x_&<>)s)^w~iv0g_VvAWtBO7IfB;C-X)PyFp_5`z5Q-Wp-|jW&_X7`q1Uw09ow9s
z0cSOeW_<o5Flm_RVG{tE?MN|PDn$rJty)b;f>A3r>J``4<Xpw3T?wbuweerLz9px+
z)syg#lYI7AL}nBIbuGXS_<?BG6o=%wTWdQd_e%@(BZi$Zm`&QtoA1_pl*RoOohG!(
z>4c*5o?_)G0!sbtvCa(FSZ!xrzw4k=bD`Bu?4Uj7+ffnAH<M;JpaS=zYpj96hSwAx
z^WfG5D7fbLO%3j<kf}{PjR9W~zS-6W@dUb{WK8(=`0x9h6=HEU&=XigZMV4UPr%ss
z>(mT>LH&a6-E2u^{3hQOiM-UM@`Oe~o{GqOIu9-03q><gxD_~}b8G_~Ko}cg4_VMB
zCLqQU+42BW=l5Sp_e12Fh;~Z?sPV%rKxVFf_)NzLl0e0nw2j#n%v#~Q$YcW52zScx
zHgb|~M0=vzIw&G*E2TAq7o2v*v_n+7#)E3?SZ9=(gteOQNBJ)uLCv)6$&*iHAll6D
zUjrR=MMm~#<wzh_W3)kcnq!j(NhhYR?o?ShC?PY=b4s%T86}nc@{2QfkVGb&-=F^`
zSQ5^;1QCzuG8q;J=rl>oFIvX}tkA{g(T0;Ry_td4U2BVvo7|<`4<<ZmSKc10^}P*p
zL+peSMi}#T1pR<ZYT4V*X+`Wvoj{xQ+T^fJYF!MgvyS$4<Q8P}*?Zp|==_bBb9xc=
zhL<*#r6!#X&_uO~h+><VJ!GH!mstx|3|XXAb4!KH@-pg~DoY*a4yg|`vWdG=uCc5}
z_D9WeHONh&W<<&W%Q4Uuh^8Ao(Xrmw&kjH7HY6(oe!4RukTBFX{jV0ieB1`3fNsY4
z-eUl@XN7W@04dc~)hSQO-a1@304cC|{J=iO&}b%uCk??+OmQ7n#a7-h%ds?+{8VuD
zG^G5%lgns~69#%9ZMjhNQdR=}Fw&~8@;kb2QfM4G{!4|}lmPk<CmK)uKhFwd@x{|%
zi_%cxOsIsa0Kpn1aLxSJdT8>}0HGRVU4Z%ZA7*h?s;KK%f)8em_WeXmB6Y4LE0C~g
z@7scrnR=63=6>?3#+A_Q@&limLsOdgiCPN|!mwx1=%oeosqY)m8n+E1n(@zB`TvCB
z&%j+}0z$FkYBNVkGYR$51DHQ6gEEG+@*k<P&;gVoaneU-HaR{}Ra67+HHN-42DMw+
z2k}x=gtY``hmE#PvH@MWaC6iI@e|eChU3V&erZL}1+#hi3a^vFe2yd{or^SE>U^j3
zW8mbMr!^A4*hP>ZW_LWzTrZWn9Ml*Vx!brbK`J0-hseWMKqtJjckjt-PiGL;XBz5M
ze^;l_b;D)rmZwh`uDO^;>Fmr!xa_j{7!TxI<KzZTP#ivGEd;+C483+uYJb(I44Q<m
zRWL!uG2x$n`>fU$m?mkr?tH9G+q=-mEtinoW#Pvm-~f>&EhRt)-vsdY4g)6g<&!f|
z={mZfSi5em2Yf|7Di<j)rd6bj7Xqp08g`C2LzI`B{k#A<rTAEe6`YiBSjsHQsBe=M
zaKMwwgZ*}w7GSNnlBO{Z>RRZKsTG%nM^APJYlLeMwDFoe;jvx62+pC!*2b_TFI<Z~
zt2JbF(ur;C+=Uq9Bkj+$3m5w=Yzjh#2X$v$ovp}X0Ndue>xKCZAAazek+c*);?7uH
zpO2IxQ?)3KP$$hFh3Qbf^1cB79h+R$RuC4~3mJAo?<*!zB+GJ;W`Gp4>RpOGY19ty
zfIOvIzjt`Pa-HgT$`FG<>%NumcoA?W^!lMc12HGo^RM*4l-zJa(s8BSrT1Fe`_k~D
z;7saTLK_CL%4mdk`d}7P7@S!KBGwoO1exqKTZ;6R{fwiqO!69FL|}hZ4N^2@^V{0o
z)6HP79=LF)=ZhPtGE6<vQvl!t<--plF$Kxtf6Gw^Rl|?KH`(rwDyJd^6P%C-VF1QA
zArDIPhi4j5ZDf@LoCS<TaKuIYz?^R@*U!r~2*c!_%O@~UmHmwY<z`@KHN0KHHqe1j
z^vjL#RGzt>hU0~=KU{rnusAeHh#f^{q7INAL3ZLaXPKfAc$pakhTKHN854@qB(DQT
z1eJ+iJLG2sW*TkR!DPQG@RISke3bS~ByELMxW!XFhXZkzVb^!eTD)|$7zju7*7vX6
z0Wn#yWZXv0E%;5E?$H?GXYgV{45A)kM7xbPPSz(8Gbw}#=8E^PcQ)4mgZv>J-%fQ(
zE)fZH22xb~=87NJ$0K;Zo!Z5{5~^c$23!(VFsTANABL3$spO(>er`fmJyj+elZSWx
z`aP0&AY9D9r*sN}jXy`W>}H*$C8iwDoVsiM&<m{tJdLN)YXu^67{-nT(dlAj<*Upl
zSPlO`#7qPZ&N_o)gNy^YmU*mE);?MjtdV(^VF^f0aZu4t4~y<iMI|{QWH4u;KSnd3
z=BMpp1PEz@!zKs&>=1K&7@L<|&an&wzd|FENF>`cexWMT<jWSraWdcnoE2M@(GNHf
zpV!V=<R*S>jtR#Y6Bg}!AA?;5_H$flLAmkP+TM4;j=)j4%FS{a6%vh%LoBGT!}fHw
z>>XAmGpPp?Pjx7bkg^X^0kXd`je-Qm(znEkovkb;h!P`kmQ;n_NkcW$pQ}-%RPFZA
z12#kp+)V7}A?~F&Ez6;rSt3`hD9~j54p(?Dl4j7Z`;9VP0H+)eN7<b+wMmvD9%e50
z)gYzirJa$B#Ns9oy|@0kHi?j!(WSqnqwteSfZSK2y|pTX+DO=tEK8WTNO8Q_0xSN3
zSN3mkdjmM>5uD}_qrOHsexp-hTYCn&LL0iun&01G%+F(@wEN_iql;D>J|eswg~?-H
z3}g~F)tR2nuQsAm-<zJQu4NLX%|dz)#6k|E0K6~o&UW1y!x2Kl7{!#`^g)g(QfI2Z
zr&}XOA4Pu~Qg5>bnWlhf#fBD#unC$jZ8iy#OSc45%L;H}@@daO!yLgA8z==vcMjE)
zvOsYU@11x)n4<}xshsw&L9|l17q!=Gg@7*w(<#{!YI(ZrWu6-ZWZI^VW?5SnZ|K3y
zuNQ39`3gWYO8M(1i4sH<@dGw0pD2LMMzjv)U<+ZoLKs6U?*JhOd)C44Lhp-txy3*G
zwNL38Vh7&XxMCq!Mnu^`>$ebI4k4b5wkyrvOa_(^850C<JVt`HQjWtbZ9&xRpIafc
z?OkYBkn!?z==c0Xm%x8&CSS$7{-laIsY&?7i9WoQ6+eP1yO<SM8P;&<r&Ur*i|8Re
z4iLW`6C~+0rHKi)4T+1`B65xp90Q_@O{Pe-UBz*lSDnd|k7$>U9FJ<Sm=!jmb_U0f
z=di=?&HW8$Djhk_8M-&ikK2fg9Z($|@T@K>#!qSxas;?L3pqA4i-Qag-kYnJnG*3Z
z5jfGAt2ZkR$6+f%(1Y0D!I>_nr3X3A9a~RImZaTDRvPa4i)?y*X2=Q~fmX1PeM`Ku
zg_DPSc9xZgQ-Gg@93xzsf*jj@&qPi_9a{8KRhUo6n^*%p95_gu^J~Kq65?3d$=8OT
z$%~C*LBHot(}kani9yy7;=hoXX9(NRvC<a52zSSN6X_B@e`D`sZBnunXo9_=rap!X
z<wX&<&@C9!)i=t9|5@h%y>!|x_<4Mm#tSJB%AU0IGeF16j0C)EdHW$+q`hkQ%@%Oz
z<75C_fK3ftNyd`vxaP*eZwIPBK1*|y#8DN*0nDDGgBgG}lsb@rHuNS&6CpS-gdZUY
zHNz#c0K_V$+vd0;AJkhLw5mCe=y$-=zoetgl7aq|wuc9d*_q=)V8SH>NFnchSJ+0P
z{FELvAnkm$4N|a$u3UEH;U0%duSJf6|4Rn#OOUaOI&6j4-&<hB1rz=HXq35Ek+Z-r
z@6aE9v$K()ifOY7)PAG61Gw#iSi>6916!~XAdCwph#=^PsyD*V>_{IgCzrktexUB9
z3C6(VGmYtgNsU-;b{dg@7+BxRXm*2ulMBtwA9Cjp(k&)R0+p?u34~hTB`lwRO9J^K
zhFbfAy(jsE2cmtX9t~?yvqheRrLCc+e;TiVXi#oR0{=xQzKAQzqe_aH0xjP}1<@`)
zd#F0zCqPq2ipz?xSZRnuHA5m1AC$U`%^N{O#`=?h5lirVgFqbf^L`+PxmKT{YPdJq
zgTIYWG7Kfn+kRQ03P+eH>%F{%P)uU91mDk+7g^s0CnP1!cCnxNWC0luS3|od@vtr8
zxxYd*CMX*ifGS6^!H<qP8NI?t5fvzkTFRUfu6ZHD(CF?9v}orq)`-Qi%w<`_6Txy4
zCv`~7V25uw8Q%abSGCUP6<DlyWH>7iExHXAGRxg<u&E@gWeO_wp>5}eS(H4l>?ap+
zt{0t786jIEBrV~O-cVMOt|N_Ce`bPc{g~yReMnz2L$Y=U?JKFb)CLx7V##M_{Dp(4
z^Gy6f$zL6x?__i)MOZiLpDV1Vqq>ab^u3Mefa>?p02$8lj(R=hsRqb4GKH5CaK1oK
zuZ|_XM1tr@SWN_#qE!&x4THLHDi$$T_3CchR+w9fr$H64%w8RBV|u(iJj{F2mmAi8
z#C)n3Ug@8gH2q$Sfk7*YPm!-Mtl>Q!(|U<ll~S;*=zPbmyl`PeHwdHjxj}QU?Gq<(
zTY?wArUILwdyd~vR|9B%QeDt2E0VH#W2^2>Ey--_*m*m<_o4Nvw4z%fYB_uNsgkiC
zg9XyObhq`@f%bXyHi_6B;DTvpdscJ|>iy;x+3s#Lt(JmmIVRi!dNf{FSDew*ytA~m
z?x_yg)LgrX<UOOY^-4D(W$;FHN2Oari+?mhq#O+cFW={6tdKbF0{wuV@q~Use_#F4
z_%45W=id7~hL#_8jeb}A^GLI|2V$s|_H?bF(9^Qtc9!cr;9BIeX*^(f_7~#pgDx`X
zeNqO<$&`j>Deb;4h`ABSGT8Yy=|>XKHuLpV6aq<Cbx3IPjnu4ak+ciw!Hi^YNnjfm
zSB|~NvJKSYO*Ef?;Ev-H7s2;}!b-okmhH1$prGpg&^AjdI{#hmH5Un#OU@`NTFvl^
zW~(L^Cpv@iJXT)da7wF)8k<!2IFM_+8`}i(O=CP_h0b|yah&&4iy#t)PDfk16DC)6
z2nprO284vRO=Ci%_E~L2ZtC#g9r*Pk$JH&52^br}9}-bDN;}XEbJ}S9NJT$j{D{R}
zF#se&+qQ1x8n4vYh^WJdwaMHh_%As7fX`3E+A>o>_G8{VL2z8pk4UD&+=YI|VZ4gB
zrK+AZ;(t3oB+)*MiS8)sUw7_J6<$q|O9p6>+43(cT)QbYkeM99ZG8cJSgX+<YO>_C
zm-=Zo54DAIf^^jfEwth$u$6$Z+O(H)XOLNjGCFxu!jf}knYkR3BD^}Z(X`*~xM!2m
z>Jo8p3TqjdcwRk=VqwJTL8O+W*7ief@@9D={^29cg1Y56D+N~_b|^)FL*rEw<Xk-B
zF60|_k9k2WKW5;WMb7KU<S*{Wcx-EL+bi?TdDB}_YU>ySnLHB@Cjly=GY=vYR=hOr
zn6xf2(PGG~Y3@AOuw{!KcOtxR1apS6?t8qpKb|?E&YiIPu)7qr#jZpF_R~^fJdpgl
z>`Pmnd2zV9I*PZWWv!I%aBS}kP<5BE>zi0$pY&WablB`~wdC3eenPOZwAV8^^XaF$
z_An}4=Ap?MfNGJfMiZ}24eLrxqDhusd}AMx8T|n<MZTOaWm{!Ot74dqr6idYP+keS
zSqYsUq1z?miUV1~7T|x>?z*i<Q+$Ezc3G<ISV<&hLWxuzXq<%kCet^DRtHHOAVWi-
z74<_A9Udotf$4<CvsEly{1`RzU3?}+e<aH@T65nNL`w#HXyVtMI$8M-a2-8YVpt_)
zjPy|!P#hW1towf6F=m$iG~~PZuDu1?TUC4@$}KM&{vFL}Sn?<qH5V~PQauStT_i+Y
zG-=A5vlM0UjtsnGf#GT<z7~bkMZbOz$#pEdeQfc;ROgvE#cShi?jjWJ$;gnTZ<QQs
z;^mgWaGrFC28;Sg7Y&^1sLK<At{EB>Y|N<ki_^b07I=Uz?Ld_PO>x=$kO57*@a;TC
zJz-1~Pv`vlk*13yMRg{MmMkDf8hwK#z(N#gJ%)5Z3J0A1Dv6JHXkP|>zTD0d=C?OO
z4)*gCJC(%8Ryvy#&LD0QSMClnEZP7myPeNnQbLnxUI+R=wBxeeJ3_F!X9xX5Y@O`N
zHhyr5$G$ko$0;tbf&)_wS~=Q9Dl)gwP+0Fh6Yz;pUdpHD+@vIR)C_Yj6vuax98txO
z&jQnVYr}GFhFWd|;o3Fh9{bf`aNxY7&`nM2@JFB=Ez^q2@8WPll?y-k1X9Ks4RE*+
zDh9Fl#20Cr!Qv@Kz#NJ1CH^iUIY~Y>m3mqZ<^;eyOC%n(_hHpiEMn^+TZ->SS#B8>
z(OngwSw-S?%?B2~@l5_`NNp|RoLL~zJDe*8aw<Zxoe~foE7lbCS%P0?>`e~h07s?}
zNxN;-P5Cx{?r^VQ#L@Z{GJDhInVjoHj|)lhfUvXuya(WFX*AC#388+n{vd6)nd5;(
zsfu;@&{#I*!DE6VXc*4y)F+VWNiO2Kg+$CAuoKY|K7SGsn^eTiu~BIk*}qXz@nV@q
z)^6sZ720!b)N0@7p~N-b8yJVzafHZ6j#8*SQ6fo+AU2Py_7_098JOF%DT~DjMwyM&
zL(<ZHFb(;;F)9Xt5(w+Ck8ePaOY$+bRWaLRzqn*En=3*>0viU-*VOVSt?ObNQ20e9
zuU9(T#LJ0~;8GM4Di7H;N6Azs<8kN*Ro4<?G@fd*)MU%Cp<?XhBtBN1g^L|bm4dy?
zosQt96uxb>qwkPA8}>!oI^iOE0<5DzPT6ZD@Ah)QH7Tl3Z>&*V?}2tG?2ZKlS|oKe
zY_qdUA@1V{7ZRBtrMX1Pq9?zt+pne;v~x^>INEi+?qPOBZ^I!8oN@*P(j@7%aij@y
zH0=tYNN$Q=eS<nsdjSa`PwI%-&VwwjA!1h(<S5CY-5$AS{%zloG3Io^?kiKm>6$fL
z;*kA=&rZdCs>>l>M=XdAIE=Sk`3NpUE=TLgN4C;&#1pKajB4o_Q~}mUKHA|`ab*hE
z^ne4XnCC}`mZ=zRhw{)ZO+~zOvlcrU?HXFrsm5+hQx!a71WTAh(L2EweKQc7Tv9Vl
z`BYfWF2QAyn@P+vpICrECDOfk=d>m;0M;*|pxwnnsoEesZJFLj?DrKA(Pk;8pt$vK
zO<D@1tpKor!-;{PTH3Q2uxHMPGX<cvWZ*GfZwuQjMBpnVebSCI`VQPOo^d9M1I*yf
zCQ{2+&sfGq8K5`8KaboOHgzLP5A`67M;PJ#v`6ybxk#$2djX9i5)KL8jP$evR~pBa
zTe-#Kr*S%Syd0)++B=mNn80VrgvK$1b73%ULk|-3QMHJ3e}~z8803RxZn885AzrZ<
zmcarXGRam4t|lT@fL$qVtMf7Epg>Mu_Y#Aja~3dxO9(iY#Um=hiKF|^<#_Mra$ve(
zYAowr7A>1<GFGCAfy!e{xc~<3aC_QyR&rlkxRwv8Q@wYtp`cD)KPX8v!#{bJ2mOZo
zkckLA3`@-_$bU8~4Z3Ib)0KnD2#ihi&&B6ynyZgVIAa2bW=2h4#AM<e<Z(oh{2G1j
z$UMbiIuW}w*k`-PT-)U3Qwy=WS<JLtM9^WOq!r2)x{USulWb_pHGq@5WaGEDqC~li
zr;d^^6CK^{;Xq+#N3WtpZYE!^{`pkpKq-ib^u5B|LHZvAoX`R=OyJmL-sL+EkRo)B
z15$Ez<9LmDguj%|7{PV9a4RvqvQe5R;I+xLKb`>2skCX?3qXp;Rq%kd3xavTUQjIB
z%c#ExFdv5L^^99}=*<dQ_is32&JfI(QoW?~KP(rRHqXU|4(f=?bad)0^FTV>s1$fK
z+j)V<%^o}j6ekjUyBCwO1F?cA8gy{$rdezL9D+A`sm=#9;+)RJ9n!_?SUw@49&pMb
zbiekPa}U@@4m)lL?%S5|y)X>)Or&K(TgXJYwUn|DZocK_x}$*Lg$K&xz+F<W$r`s6
z(TGx3Ru@~1Lg6^OfkZ*!nXrc@9fZ3zFAb8Tw3#iMeWF>~|BA3~^F#*^DOno&Ey4Yn
zU$a-#->;<i9Ii$tLi;dOHL>N&^@PUtky}3IT=;koMR#Jyw&d7=*Wa}u(psXNQ-M<s
zm2i!$Q)n>RdB#F<qMn9g@asB1N3%fFE1wZIbIt^y$3sGalL>&}66ZRbxwfBVY)Ui>
zcKRh{rf{viGC2=f$GK-G>T%|rYMTkCg{to$W(m%RWQnpFRmQ|?5_`PQ2Ly9P5XLb@
zJQTd?dxCmc+Pka#5}@Vx5~j03Re5_>kec8P5xR%V=@PT!UOaV+HiQ_<9HZi`F>&bT
zf=ABVi~IC+z10+FO-n8+3EvNwXC&vJ=T~EcoS`G6Ggxzb<J#xi!l-~GHdoU`;}SZJ
zTMZKFY^$eN!6&$yUF^JBZEF;YevWY!V{&(E4$=NBB^ETjjGeeq8c+sTA+_x&+aBGg
z*=sRlbRQR@NttjKP8(aEmSL#!idNd~0iLj_W(cYteKk+50n`owLw0ky-EX}xyksol
zWUa?fQ2I$y*V#N$2i;9#h3T_Jv-e<CQreKtMNS8q1+YP4i&-=1GOB4p)kf=XISuKQ
zIv{$dQlQ>UKWY!iYl|zgBfdi@Q0}yJx~u(4^Ye|n*VWQ_r_NAn8T%=s6%Bn#`bJfU
zS&X(P6ry;ZFI&?eBav+h&5Xg_(mEb3F+%jW-rzn>AbTZL3iC1TXm4XoV;RjhE&2_9
zNkRsffqt<=hG+1!WN^VofFioWprkU?e78(qQNS#x8BMraQ;y4r3DF%2YJ^Lq1>E@N
zpuHYtdHY`Pl{l7fBmB0a`Xnw+ny{+luz=AQp9o5Uvc8>Y&BUeH@n&rF8NvK{4}=x9
zU{OF*BDn0Hvqc7^tV>eybYwsV;G5vWmxgkLW;h)w#>Qu~vuaDwvU?CLO7Uu<qM1E5
z^6aHmW8^@LMD1Zkb^0C>FH^sMT0Plbef$h3&`@?H9-bgiaoJQNaBCO9OTs~;B{smU
zG?dcuME1qzV?--*u9&o5cyWaqpmGnTs7ij$Eic6ypg!bA!}#Iwsx$*lPy;#}$j>g(
z1Q+Kx?E0^GtU3i48VbabXHAvB`>7z;l)YY~HT_3sD*H_Sz6JUs3~ETq6#%WoBE=CV
z^bX?1s|i0Ut}y*LughABz*0ybQj#iGY2fG$khChzd_HKYA?fuR*jS<Q>)D#27iC(M
z`~CV;EZVl~igm!egzcMwzJePOGf*LLnL#fvUPG=a3I)qaJS@g%T{MXtDmU3jSb^nH
z?k=We(KZjd0G1nAiwGIjT2<M52ob~E88uu7Q6NaOt||BTE|g#=0M1D#%%O^;D*)XQ
z7$3@axSU9<k?_ZcR5vPv-TBR}gkaIGTMOZWU9i$V@Jnw|iNHpJVW5s$N=a(cUebgs
z9U1}@%ABYMcx9rIXNS{-e2=s2cWVYLiC)&875JDO3M}Kd+gDDxC%_d`Ukpsj5(0>n
z8FoMX4j*JD+t33<MU$+{Go>MI{2jiIP)WItsyAI4v;?;5*s2Mzpg_^IPz)DBD_gQ2
zFUltST-6nz@h>8O0oYJ&39}Qn7<wE~cIfoo7oefKQrpk!w?#|m?4o-Hy3zCY7GQmK
zxq0oytTFrm>h$6QePUDOBPzk26=cXK{}`=OqToEu4gg99txKJq`N5nxdRmQ^*Vol_
z-)Sin)jATA&Zzho)!P@YxW9tXQQ1p9g+OzDmu(4{Nuesm%J`L89-ngz8_$Oz<a;1b
z!j7$}49}a}mn<Z+G}S*QpZa^RUHlt#oK=h8mMeyerjrj)qh)G7v~(j4Ab+2aCULU1
zSW_~gyHV<GRN!8Hu#i-|X`vdsl>Z<4J-lMR&OUW_1ng|Pn7zS&0#-`jXiu~)pqRhG
zUlT>j-)N7O97MSW2a!r*2cjrmZM3?YrhEs5cJJqqBJm2qv<XGO8+T_638&in)QW71
zSZ}&I3^w+aYf8b8XuU;Bzz~=k%kOkYZvIO3@@6o&NyW5fKi3uva@OrR8g@EQ3BIgu
z?E%Fgr8X2c7pW;Oh4p0`4qW;5<u?D&NPojZ3??axA>gd^(ETJRxKyA~FdO{pdk~9t
z1&s(|>`;|P6fsu2dGq*F)a?ao`>q<l@vf8<{LY)^wykE85DT@FM?rit$z%NU(>CNW
zNJ4mA6AEH=JyV15Hq_-Vwa8Ja!Uwh#ph2(){y!9gQEH)@A0a0=lJ$G|X%`Y}buJJu
zsW@B{3b~6E3~C+k`2f4_uC=uQERMjeO;jd-y&5BQQWd@Dn|B~4W?nD#AS(2kG|g36
zK}+jm$1f(KL}INFcgzkc<q8_kXp3k<>;(<_)Ob1zn)LAzie|UlN?{fQ?dZ!;Ru-HY
zogu~+_@w}2t3HX@1=*cN3oN1SMGFhiHj-6kzfT96gSVJfH6Fg*K$B$pi(bOwSGco{
z8j28Oy+GH=V*d)2`nXH3Q-f>8j!OUm69!c)jGtgukZZK9wlbVOpEoCL-#?o^Uxz>6
z77+bPr(e={Cs58lu3d9|Iv=uZV@-TsK4VXPU!Oga@IT-6y-&$*j`tKiGxuY%&)#qG
zYkHoqLmz}ZnIE2qe{XfazIi`BZ{UC4{kZ&mzva{NeSBU$G~_l}*vl_GGJ8GY#rsUp
z{dm6Qdw(q4^znGV^nKeo&2zl-X{r6VD&LC&3pm|iqx4d&>r{FA;rnv_>Gk>CBRLyv
zy3)BfyK5NI)V|)~tDr=Bm{`KaH%)r)%Rh_!a@bYy`4ZccQqT>)@W`)m0a9}Qz43n1
z<tZU2M7m<m5nPXR35qxGxP;<xTH0UN7yo)A*XQ$9PSbcYV4wQfF!ppW_G-8YM|ZIu
zMy_1?;f$^P%}wv~u4hS?7sZvt6BK=gNa0bD{HapZK-1y&dh-Efc|GDQTPnU5-FfAh
zkG8_q#RFBPCVo;<iEgc0%YqaS>9&V%_0O?xWy`wHEmh0p${qD;2KW9~3s7kf=xByX
zz6T^1`WcR%H>5N4PLPl=&y$>hp{`4O!MRRl<?g*l)OhT>;(~_Y?%FWmxYP(vBzN6<
zt=?4ES@UzRE90|FSY3C_M>==RHjn!`A?+cLrG7{Kon|~xJ|);$gq&X`zEYNYHQbdH
ztgCAlBfp2gl7fNj{>*RlI;dRW`+#eJ=}nzV_mw)bBe<?AL5^tsRVVXURYEL(SwXWe
zA<qKkQ-W0`*zI4M{IrCD8_Vha&>Vxg+1&}n+Z@~DAH2;vJr#XTlMU@zj`ZNj$A_ts
ziyHUi(K<Qw=%vbTigxSc?QGbxs-Ek!K7JE@p@(~k?>(TM*B(<XyI|XUn3OU0Yh<XS
zYZlv6+?A6bG}VM!ON|;;w&t+P6fvJD&Zk1QdZpOYwVnRDSA)6Yr0-{0*OXIhQ~E-e
z>ebV!o8HY>iqzbdET18ZV6s6f(E+*Ttd?BCwtffj-TsM3`&7D_x_SVxb||^o$c=B-
zM{$k!>NKlTm)#oYrKFcnq>-+EpjTC-8og^4>~AyJGw#d7o4vfiPh(h5B0jzI`te0Q
zOc3_wXT`fp4xjfS8zz1<k#}P6lWgz4K}|8@B6JnqVVf=u(|p)iD10+r8)Vo=u-%ti
zwY)ckKLiBa6z)atT0*%jkL5^vBaeZ3HXvPYGd*7NPa<xIm!4lxy3Wf9JAYgLD*aQ(
zU{UBRB{vN2aVk#oTyPP2Y%OPBc+^}%jDLL8KJXy(u7!U>b}Ul6$}3{~+U`o?%ZRBX
zjDLKxBHWVu3FSSo9(ll*?L$}a$n;1T_m$`Te9QMGvUI7?$MGHiEI^DK%Gk!p(aFJB
z-}=v)t$_s;3jsaBpH~6`0u~N729|&MO#kq?x&KtriMTn5DLLso858`?_`}nu|0)pB
z2?-D|5YQRwe^FlEKf-@gI#F92r~i^Rp`oXtCt&^RR`DO9FS&mP!T29#1a!*ocE$vB
z^7^L61SA9ue<_#OcQF3yi{an4bTY<9=K6xRZUmZNEc&m3a}Y2v($f=Y|0OQ;rT9zU
zk%0L>4a6L5o$dZ>Fn=rgi~Fa^*Mm;!OSOZ(jicQkWrptmvLy(d9Gs2+EeU-|2^+hZ
z8yYK$3I1XJGgn1pM_XqHLt{sRKXy}u`k$$>eU<;%_m8EdjcrVw%m~>3Gb~YaD<@+I
z0y<HvFUtxW8`>KErRg6*1_Cx_4%R<?{j+3lS?6k=ZYUxxwWmtIcs6)==6TW~iPMRZ
z69^$|gMt76lMsb-A_)MI*Xslfgp;5lZV=RUqzL>%OlPjJNC*NN7#a}pexKeT38}h5
zZjPg(qsluGHRzzQktTb30MY(<bo}hvdhcFiQPHlg;jDehRuUp76efy<i0dsXM=te!
zdRyc}HmD{P#^N)7r~+`O=1q+&6BR5YPyaYxz~nKJBOC~|Zg`v}J52Vv(8-Lw{|?DO
zC+A~iP``ug6%u!RR9|~!bVlDoRlMwjzebT*I+gKiRLp>}##X2OHqa!249PJY8|U(X
zl~^j9#g&~r##Hx?)&e}A>t*Djdr+%p{m4M*#TYLhUZzLV301BlZZ$IMLvRDX(1$J=
zWrSmEb|yO!G88g2K~6OaMXD}A62&|n)OJW!AZYLXIhp9dnO~HqlY}NIWe@usVC5Tw
zWSaYq^#1%r8L_TnJ<5`Uh=xWmb)p=E{@yc3l05l7Hh?~9@Uua1kcwEr8F+%YbECdn
zGZ)<_f-KxUtr_=bl&}%A$wu8M1}|w(9`ME`7+WHgCy6>YS(^0@TmT$0-Hg~~aeqeT
zLtVO%MJRLjn$X!h?|=b5BC9p{sABj~+{1*GCS&9G7P{yDM$_P4_caZ=dV?aW9BBxW
zMzujomOaD%2sWz}OvN;6R#hq$$n!U4V7^&tjy|iB{>sAJknf(ic!C;}i>)5$>ji5~
zC!#Cq!?pP^w7T81W<D;HD8rMMDP(Nl5PsWaWQ%y|BrN0`TF3&idK}&zr>zU9@&=@(
z*rmSF$}o#Cht-ndWO9F059@k9ZY+uRqzzA>BmQ2uu|FU0iLeFs@3=?@Z?WQtn?rm~
z8gVG<$<ig`G#5({QgB!n`Z?8{^XputhYRqnyX|4*9#%7#m1l|39DJ0KXGI-vJV~)J
z%s62m&V{0SwZWO{qs8Xkzhd_go-Zs@`Jhm^i#@PC$Heedpt0YegdBBzQ2K>BTP(L^
zdbOcjD#{RA9npSXCEq_nNReiDky@K*;Jjgdz*<c<aG5SO|0H96&e_^8zmjzJ+2N^L
ziqE10rnF>?AIIi!QDzN^8Ks`+o52QJC5`P5o5<HE`%3MaNrcsqWXppByIEe8MBn1H
z7|mzZY~NqB(6D4q+NA4*m3qRK=P>i)tPWB6tM9AghMk-`nFTa#XqdlYV@2a2vbmg7
zFKooT6Go*sWp7V)Osl9Cvn3VHB2e@Ib1uY{0yQFXcBNT3+d12TRp}Ch9E+q=Mm;Tg
z?sKL#MQf;*vduSy1euA02?hkYi9?g(4E;F8v8`a7VVy&(xEV8IQigt#vqr=w4pZ*o
zz*oRq7~a=U0e$!POi~e)DjHoitQlSxS@as#TGDdGR4=EUPvsboV*H-|3hG?gJ*$3F
z;q?7PWvZ*D>%!tU&+md?7CegLQ0<W}B^+i3?-Y}&<}FP=`yr-_d<@^{xFqg)M9Jit
z8(ed0a1=9!MOkhA$i(;8?*<(?;hoFp{qtYjNT?Va{U{zHnJ5+Nh{I3OrWUAG3Lm7F
zP(lkd;6fSsl`xFqZn$VSDkR`m+%>Z=IzvOgXS(Q%piph)t8o-8hp<kX+*wXoJR(cJ
z54TjW9kC2GsU6O9TDaC<tg1caCDbOHHJ;2{wJ=I~rqIml=&h}g8fUkNu8HXC_n2@c
z<7%kgTK2MkXW>EfS}z?sJ(-CI|0V0udo1LbkA9hdr|ftyZAiX83|`)U7pK5KGz(M?
zfG6yYn%6y44*EiFn8A=r%gj0tJEo&itc-n$i5{&=1nitAIZ8Q*KbDIcIee0HyIaTZ
zmD5d_!!0*&&Pip_zI?-4jVe^6uh^6(Fs=YzEmIaqhmeTENWGs>9Bsr<NH~y-;F<=T
znn_m}WW#J?tf*P_+(QC~B<Rc@25fA0f2xfT@y+5JLpcQrWeJvIY2}(qGlJEdL`#Cv
zgY$TEM~Y<_rOc6=spe5Aq`$ruZ@sw52-R<>dMCAu3YA#OjHvO=BZkaaHj|wi2*P3P
zsb#YkU*&}d@^G{{8<d^#P-xRvE4xS=@P4FFmzA5Fd?9Z*y2#VR(09Dbi^&u$)uvh_
zq$9+M)zGx$*jEumx)bc1K*?T_g9BR2X3<y=%j}TTt5YHp@b+ob!0$F|n{Ml|Y#MmX
zQSb9!w$FCA<Wy@nqH6>Z$@@6y33KrmmEMQx(Y3!8;k@3<TetErXZz=BQo`3-d(=rL
zKMCI~MvH#et(EA5&D9~8UnQ_J@+1j*DbqMtZFhes=i4t5TgAUw;Qao&=atZZM9@zX
z>lw!fR5Tp_%1Ym5rPJ?31ay&q_i;VH*MEIEtQ&juF5$bXdwTgBfA|MEW(-VoBx|&E
z;e3&Kx4FH=4op%89R<)wmzTI>Z-}lFw4`tnl;*P5UKJnv!9suHrmxmILaCX@ZK-m3
zvP(@F_kIFtl<%!_EZ!@pbADI3XyGyc_3X9G>!Wp}d&Y`Kcy3QWy477=v~@SZP&O<B
z@B9Pkr0Yw7rlw&!79kOZqTng$tl-X1P)U*BpsS%%s8j<I_JY)<w@(lXR9~UDglTXE
z4b5?I6-n@r)&^Xz5vmK|4OcN|ul18`lg~sn-ilnw!QePHPV*nSe_gD$$uJD;VXkjd
za2Z@iibXUu*a*Mf7%$Yi-)J2A7X*nw?tt)fh-4Mg6&PY&XCF7qkCyW`v9;aYbU4$k
zwI8(e)=u*YX=qMQ_;yX_3n_|j9OW+Qr{Iz2kjF$^GT>&bbz+z28)^I|VGs6@BgqYY
z!IT{>j+KzMD@!PdmXMal$UA`ypAeHY$GlB>8C%6~SkBk0Zsw#Bm`C12x#7?1FJ|w=
z1uI@LEy%xSw7}2R{D!)v!_?Dt*dDE2Q;RT_B(6S_A5x^Kfst{#^wzPp0vlZrxjDG<
z{k-!2*DL2e0A!x4#QfZytODjHjBe?1Q&7{u9lwX7q(!-EMJlHhY;5#Q0<mQSoGg7W
zs0}?Km;oW&8?}zir1)j-N90}bN#xv8QRsYaX{#7ShJd%V=>m4PIC9xE71<W1m(e!l
z)X6Ne9Bma=yQi1>N<a1s{+9bK-w?iM!T$aLNhSUY_Uh}~urK+_^vk7`)c80wtc-)R
zN50j#|NcIkqXU#EJU*&Zsg+j4`L7_>PlZ6%w3uaM{VeqJIO^=H=$c=Y>Sy*(&6^8y
z7Xr-n8vp^k^#Y$M0-|0Vyy<uR2Fe@(&?urC_8n`|jU_f)^;?&f$mp{lHDQr&TDM9|
z(>Yyml^MRYv|;dOWElqYc36h%6!B`ezvVOfcNxD^s~_qyOc6&qviA0o0Nhxr943vz
z6-Au15EgtslRfrd*m1#Z$V3BM(bU{ZCP`EfX-Mvw$LJ`^ZT2&$b;QCuMJ3}Un@Bl6
zDVl@Qxmv}sa`C2mF_vj1?-7XZV3|pJitl9~$V$pBCO&?J)sjBq!61aOh(ySO7edUO
zz*jlEI+;?bi{K+mr8=0BT&A>Df$OzRLbelpc75V+htjR9e3N=6^_u=9b*0Gi?+}fj
zB~B()pnAUhF~>TlvHO*NX({2ImTyUsbkZDi&P&3hw%9YXMqZX0^Pni<E>3K7<Xg@m
z3wS9MCw57*!~kzPVpEy@?-38;sOYwYdHQbS4(5vD7i}(n+=kNP)ULxdwTb>ju%do}
z28jZQUB00W!v1|i-U#&TlQ+)P^6H)aR!d9c%PlPH335@7ia5M*3?uumYk>3+01N>D
zwILm$B2`Wo!gO8eOUFCuJ2i&$euf1h$*v_}z2v7xkY70fS6sQMjmQ?h$gaf;l4U!6
z6A}k>kD4H)3P+ORN{ne@x+@|&d7pZXwr>jJ70C@TUa0eClL@eLvK(z$ngCQ6SKbeE
zJd$md-tIe;lHbbe(hM@6tq-GaCD@!4K9do$or``dXi{XUXGTDMz|?o{I)evaB&$vS
z{_0XB_F4$xX848+T!P;jUXf*!8``r)zR-fu3K$&IrcVS7w0AI~@-4y2RY=If{^!6z
zxc@G(C=^j?#(RHq0nOD9=hl(>_{5#Q&<{)3u*bn)kfkO2T}=0rN}(<nTwiH$VvdG8
zpZ6!`L30(391*0syAKO(1Nsa%8Y#zoo9&mfPMD5Lo!0Ro-s%t2yI6Bk%L?^JN^`BC
zi-!h=1U&h`LWmtICeW*4MVEi1#McQ+%M@hvWJ5Z1PUg`~o808DX$fj}E<G)3BKl&r
zA8nYuG3@W@&RX<f_Q_z4VT})6+mFqkne%elxJUhjh}5sAj(IhWU%64LXWBD)PK}#O
zBdM3#O?h%n+^|QhpbHbtm`}Xx$oy!;KuMorJUKr^bPFHNd1_3R^0jxln1_A-UhX<0
z#IQS*!{d24)9hVhgT+~D(A&$j(OC2Gal}<R9N8oMronOA{%zM#N!*8=M3PjrJTa*7
zppMU@6w@WeS?#wju9J)WI|HPGkGNzMbip%`Z7LBjP+@CNCBuF-k#mzyMW~1B@Nc6|
z^F?Cu;NwRdE*|18*lv<GZ)dAW^n`|j;)<`F6Sck4zYsIUIvp1`S`V+~$kCVhP-%9t
za7Fe+twOp(bv>>};?Z?EsV6ICPRP3vb@|lDyFbQFcgIIS;kukbTK&J=B&s4$lBAeM
zdgRM^?UKp;klOt@&5)H!u0}1cB~CZ5if=Zkw#jbIPGp0|tFki>tE@t;)+}=k{%>%k
z0WFCV0%V4fd<He6xQa99!W%h$PzkElEA5Vx8QNTfQzVuWzjNs#nj@Fa5!h@uQP?U&
zs<b<d-d{+hmL$n2Q|W5gwK_T-wDL@5u`hc*hYB+ILlX~<YIS&YeG+7|nvF)OCyHQq
z{FXn**dY@|cewy-kNLHX2+fNPkA*o?KN4yZWhK#paDmhPdHug9ayGTBex}CJd;6j7
zJOya(DX{0f?mfxzp**(nQ=Oo7z$!hda)zJazQDzdf9^{4CKLvXAmfV`!x*v)u6{;#
zaq}%!Y1-}$<DqiAmk*;-WPi?}JBw)(*-+n$Z}_{$efoY33pt9@^fg9q+Q6>}y6RVg
z{4mv%Q>!2xA5mI%j9Mg|a2o8^-sj|qWJ*osT<(X!6>X?bjl0$Q#%6}M5^K4yNH;mC
z$*NDZ;`0DdX`I{WF&8;$bYB%VS+sJ6gg@-6KNXCe0PgMjt-Kh0RN4Wf+s}%9?82DV
z0r6BHzCGXvy;e_5QX(ZIzWMc>xlul|t_Ogp?6rqtxH(qLQekqA$SK@>@ji|_UK(?d
zRpC)wE$0ocI+XjIAV{cHImiiLu;s74$7CZ?qBophVR4*>_=>TfJUA44`BZ%95=+-f
zlVt8ilA@0_#Cx<Y11__MO$s`4KliEMa7=nboiL?LeykuUZju6$e>-S%DSnUE5<DWj
zbjh%-rJd9lae{viK&61+TP3rKv73IM10GR;<cM&OvHB+GeZojCBzZpTrdSJOi21}*
zlSj>81DOuSVFa~!nCM*;;uH*}7(*rUl<awZc{NURhP>aN#Y^QacDkdJAS=1dlEi{1
zy#|b@Y&6ARP$bn`l@cHnSt(R_3w((}?0kMBH|bXnQZZU)VW^YW((J6v>rowGaZwwR
zSC|2s$oE{{C)eSE$xF#6zrlFCsaXj}*@6B#v~T#!MxX5gzJra?#8zW6@CjQ(88?lY
zqi#+seciP9Sv<FfIKXc%XjKLheUNVby_+OFCJZ*0hwtX_{BaUKL#z#I0eXP<+FDmw
z(zqf_tQUce&kXCFvhCOBBN-S?lW>P{gge(wcvFN|*rjz^s$q6r;Xdtz_e$|1DTXMV
zBmBxR)+mfSNcw2kKK*a$l52PgSe;b4Mo9;aF%sLo)&~tu`tN$Q!=0y#I*$f9G0%p?
zFy>9O%2=~0m<7aQ=VM{!H%!Dp>XN_>ib2nwU$>f1jASBD2O<BSf`v#fjH}%YYGcSO
zdC&C>`hhV*ls#%BEC!=D0^P!#CKoZpR+)?ztl^6=vme|8y7NlirVhB(zO4z!2J-eD
zq1(PsmulMsp<Blt{!^p38S1G52rF}&PUfoEkM5=S7vNR9-*m(F*a5?vB&gO<c<OL(
zu^iJ=G3gUCFfZa&y<epIl_{N<G9WsL*RlVn7Qj(#uP?+CK&fvXz!VG2;Sm~tzaIN*
zDZ7tqZ|?4PEYK$URgNDYL|LsLlQZO7lwSvk8ymDNG<*BRF4?=?H>?<FcGB%fpiQ)^
z6u&J<H>F-%P#jb{;a+`cxMZ+rLcnJ5*eeY{aCnrPK(X!ZZ!X(x0zP^43sB&KXKVt?
zblcHTWr$ZDeinc|Xmzz1I*xsno`G+_43>Wk_dkN^$Aaq!6zG}<Yyjz?)k*cr!Ye~A
zUnfLfjs&D?T^TS0*-N$owLmYo{2FbATs{q=$uxXQF<90zznNr^H~$HZ#Z9ND6x_!K
zSw^o%<kM6S#9HNg4QpPv3Hm!j?>vLZtJ;s{AlPdXQLQm7nGb#cAXpyHU>bBs9kBAd
z^Ij!r)hQTN{ABVY{|Z!gs=IzL+<3jAJ3~@Ik>poMo&a4)wT^*ZDNyQqy?Q?pAT%h5
z<`0KHpbsfPXtZ9YL3+OF;Un-JbHH1W3Fkf>vWdlQ3c$t;JriW^6%eKjy$(Nfpbwc|
zWQnUbKZ->FUSk+;QoS1>Hxz6VAUs5QYP|%%P*CYJU=bPmKFDAoJS2J@eu3^G=nMkg
zK=4Atr$BXj*<Q7E_cMTz+dd478;0{8K)NVAv_UawjN<-xAkmMBeIn4ei6BIvki8K*
z!2Xa7FEtdHXtpPL<PZ#cwO(&j`ZAykRC@W-F>uyCKO(znI|#^Qy6uY}+;28?>%XQa
zFK_sJy1_2dEu4jPfnOj-P-lLmrasyP=<vvFjzjY}I&IDe;oy1@^S1!1Z#d_W<o$q4
z$K;%5CJ+j>(N@`<4631Y8V#7r4(N1baFTqyk`)mD0#YpEN;iPZ1&%Qm+{M^HoW&92
zsPh7`6XK?c;Xxt@>miZif`bgg*m`4;?x4dg1C{|10;4ei&m;43B`dQ1%-+a3!MuPv
zfeJv}>;lC6f;%;Ud$j;A4D2B3vu4*3wg*<G%w|B%NXvk5*e413uLHDTV8Ago{NU@*
zK?-_Ci);902!PCJXmlQ^&)<A^2tU_A-p0v3dH|DRGuZ#PU;B@f^<Td>Gd<(Ko@S2!
z?T%&m<3j$+Cr$T%`D6dv{i>ZXZWBn4AoBPTp<WUh778pu5~N&=jpkj}gb(l#_YKt$
zvtj#^YcE`}96GK4X|pmubbp<j%|?sR9lp`rK3Lz0b(>K)P~iBQku&)~PpomXdv{Gb
z`#WU%nzg#U#X5auMZkU_Tq=uIoo9n%EIbrILaQD_)CJIwT1Tqthtqd>*<)34745)5
z|6Lu<&s7-+3Fb>|siVD)^U;UWr*&>YydEaZ(Frv4Elil~A9)pXO(7N-7Qs^=T;uQt
zC*ZdmpehF`Mdp$sDx8th!7t?A`#yy40UW5Z>O@&g`1nLhguIZsVUa>clnc|vxlB@r
z@k~-X3D5MxC4%0wsS33swH!)!A`6cNm+4>pF44{q(-chR={yoK$Cwna$!Cquj4qAC
z(x2#VKPb8-zi!YJJH!I2Ci}qnN=*|#yYs$v-DvvV%Lg!vxCH)xui0NK@z0_$G5rUM
zVEE(s|JR59x99#3wjgZmXy{;W=Va^f#}WS*+#suO{e>OKNNcF5i%<z0Tj;AgD}A~2
z|5GojZ*6YnPC)*56~Ui6ioYwZ^i98f_l*CM6#N@qpkbhAq$i+ZW@RK`VB=u=LK&DC
z|3Mifob;{C4FzmWt&9oi|7s`TX!r-F;9z9`tN3Spf66qBUsL%rLLq%Sabt5+vo9p$
ztDC=AN>0Ysss!wRxBpWR|F`gGhF{y!n33QQg7Dvn!XF6be_P}4?wk#r{(?`Gzc7nG
zmimh;sPAa}7Z~&ZvW&Tdqmz)CzQex;kk<dF%)t0J0Q3JhH^E;E^7lJN#O4dMFt;%!
zp!;raBVglb{x9P%&EL(9oXi}*P#PwNKePD14<=Unf9hG8SPA}L&oAictM>oy;SZOE
z?GKXm_rc2Y?>QU$|LA4?+Foo-fA-S<eXuh9!Hd51F#Oy4Z#hP`|LKFCfcb0kEMI%#
z&v^b|J%7-rFV5HVFYxILM6y+}G5>?)5d8V9`R|4M-`n{AE6WUW8wP<Wy7wvAM0Hfj
z9f-js+oYAME?T80Ku+wiF%czF)zfzd(!@}9e2qcO|AxgQ%9YajW)IXS0%7|b#<~#n
znz1B4=VTw=9WFi6qq;ZNJH{I>8$4ot3gNtYLLi6g=*{_L`>)3NahamNMfw-4n|1{A
z>fJ_w5TJzy-fG!Cf_MN}&Nsc2z&|**HJE)jMvLPSu4wK~y}tc%sDSadg4<wd%Sy6=
zB~2+U&`=s|x@rjWT5M^dX)-O-a6%?!np|r@qcTmYl`iWPeu~cIbuvb#)H-}ba!mmm
zU22?TaEdzpzpewAtrxt(zuQMH_-TKR)GN9q_RgW{i6YYcbsEsyn2SULjSsQAssqKV
K#p3z>rTPVqI7J=+

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..dcf06f312ad2b02bf07cb0c964adc10bd30f2230
GIT binary patch
literal 67336
zcmV)zK#{*CP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&-(N`8uc5ryPn|+d!FoPf-9*k5AZrp`
z2M&TYoq&mSx}4X*tSg!gZ`rEy9!k-<%C#FZ4uC<n2+S*Ffn*^jG*r`*N^7w%Z4|sv
z)U;z1#VeubJnN_wqH9i*5!2=<b0mBlJQI7=L0>p*d1a2m-D$GCVz6gsC7)FS8c}qW
z91MJ|LrG#0>5fQP#?MwXB;$6N2C4h{g!dJXYy=4}zc|DRAoKmQU)A$x+W<O>Gomkr
z$j5y*e+!TIXCWq>Kd#fBX}^)7)Zv+f^i!8oQ#DoxK3Fq7r$*eMCQItUc!0nnMRWn`
zxTz3x&!j+;x&)osOf}>4G&+LB+)Wg?+Yk#v5sIS2u}-GimW4i*XX-(ipjYA^u5Dcq
zxsDn{E|59Fn@frcg_gLDVN4R7AI`w8?-aNR+MRi&D&C#%_Kb9d5HV0tG40L-Fvb;M
zh&1Wa0*I8-PCbMXe%@7yEDWliNN7}Z;e+XQ-@zi7clv?T=nq82{y|i(56W*lLdJj+
zwmMSk`nMgCmq$@t9s4iB`I|3NhTA_#_5E$fIX^`GXY%Vq_<z$8d*r;>QM;yp+c9J6
zxs`r~1^;7j{c$($z^QIYxZAhgTL0LlKjkZ}jr*I9*x%SJKfh|nkMBA%){4i#&ydc~
zgW)$Fd48PgNXq=S<2?6c=4Y7DKhB-sbi?U1)h!9_TaI=VSH~IllO~Ef)PB<~kG}I^
zH=c##yKa#!7`Jeqk3W?*S10CgI-(By`KTi(s)Y8(9mn`Me}6^>`R9rJn~pfR5g+n%
zJIejrj?MS;{U=LQ)q($;Znzel-9S(X^dELx1tIs#<7Yr}eO@QO>Bx=a=qSoOzwHQ%
z9q*=}xz{(!Z#z!>SyM++?r%G?037bVp9xI+aU1@oBQMR)j-ou@c4UbO9T(Is>$d$(
zM_$U49ZC8AfHH6U-TgDl0(@NNzv;#+zp)z$_qW}yT``FH^$*H#ISP#eh*Cc{9mBuv
zI8W&vYyIY?h5V*NXO2yD=;1*6RxY0pUFK&(Dt>4;f80?@kmOR7Z{;%Z?4&FGB)pn*
zr{8p%8-m_XDqPmS?bQ843;P*ZJD+;lZ#qJKYt&szq5JmwYLgEG2-X5o*a*MvhCrqM
zpc@JPoft<-@TNij%xu~Zo$@ywsd^4|1Vtsl{<vemb`AAsczQlm)<5nh#kR8>3D0-k
zF8fe_e@1l0r$YRjj?|l79YOK)yN(W<7u4&e@DSOro!?!U(#v7N{kduC{o9WH{LtQi
zD$%3#`QLP;+CS705v-?u+mUq_@H+SzF$JIRh2M0X3UFXYJ~aBb9qHA?>*MF<gyDPS
zH%|dRTZTHeat(gh@!DTEcth-zZ{863XJU>hbL;p%z0dXHe!sKdXY_Tim-ld6Rp$S-
z4{kn>=!U*g1yohuiz1lNH)$)(l`XkvU}S2SyfdPdl{RmWBa4Nx*{-tDqR!}5Hrk@V
z!j>j})Ga%HA<@K^)k&{1(I#P*g%*#xNee9=qJ+``X(<8o-eyF~sSky%QAOPrC5@J<
z{035#hC^#B99Qk)L70{1W|A!uO|t24RSi2wVo{a3+bJ^1!gx1*<4YS`O}&l4pA8H0
zETe3P;d!==Q6WsTZHyv?w#qJGsLgUYHwOvKn{&6nl2YcU5C#=3ly!AHGDy&DJ9ZOn
zYIC~@HkM6Q6lGW*m!iOEt{%HlHn=`^qiis_B4=nmA5-z`G{dVrq)hcHAt?jD%1p`$
zFkIowbR(!<r5p{iG0GXCqL*}7pfDzXD0xKJHe4a7uSv?8H8{&TG7=E(k&h+WvHM1n
z9lLKN*x|cxB)H+_8%cq3<p6#_fxmCi>f`t3OFChFC7)4?wgO&moCwY3Bth|UFCR&~
z)0<zLJ1=cCb92na#2Etn+DzQ@t87<QwUxfQ%>;h4HtptfJ9hh~zT!33{DyC1&F}a&
z*l?2tEaHb7k<f`rSv%M}8X;)PlcxW&c_S?Dn-rLi^ais4uHvAOb-5^XAwS8+bL%v7
z5i72N26KfqM78x^VGS@=^$Kf1z1#lCOq~v6!eJ&MX4LPkSInqaTmznANT5BE6x#yX
zvGjR2J@CU(z9gYnSOcor_NhLr%4?rnmz;roo^aSN3f;~*Dk74C61CHN#WrNo=n7EC
z;WH!DFBGBez2XzDELP1#0z@pd{%cS}>swGm2vpyL8e+c!-}QJYrUD?aFUDO2LA|2I
zs0P$l>}Bqq>6B?onPm7!Q-UO8L;~Yh-Lj%M0~=WU{m~_Hq5Av1^$BTc_tq<<p)qtO
zSlM(xvmC`Du}g-?zbS0Rz~<H^3$54R=fGx0Sd1Lh*#15THMSl(s6CFTRnFiA#L!k5
zf(V~(nGc9?r3I8+U1Bj?-+F}XwSJ%(3)$M%B}buf*o&3k*$OGE)V_;aQ6=&Lbni_;
zD@So|T|%U`kQV3=ts)>1WY(+}9~!|H*Mh6v6e^8~wuOT|c|73SHhCXpJHNMX!58K1
zp;QZTxsN2}fOIhc3}9KSE(Z9mEoW0-!kwvvyd$Cl14LY1f)`e&0WLq&MR4J+tK7Tm
zOvP`J*bNui7V?4$>RZIi8Q<=Vxs)e>5eFG&*(!?;k(dF|zS@XoZ^D{)R1jXC+#60e
zgtu?b-G6k|C8R^E95~b}4p@2wmfoD?iDrE0lt4@r7e6HsQHZEjiW^E52~j^u!CsXV
zaH#5w!fq(>eNr4|o~2vz8sd5viS9@ooo7YHqU`p`$XFEAJ}WZzI>N!r$Y&TtPbJwP
zJ~_%BVA62}p3>nF<&5G9435qzdIdh`4CUoVNOh}Jw22cAX~jp9Ms~v=q${an=kruM
zbyrNBVP}QT1G=&)F)h(lS-Bz!`IQQ#cYLXW={>)6A|-j^m^!y$`gG|((jDL@dG>Jn
z^{+)iXf42D?b##h*AFfV`I6@li+{W_l0SQ)6{58&h>$N0AFB9z*zTW_mWB_Nw6thp
zg1MU(ffLN5#GaCtb&{+$=a<KXJ+6>nBuFe0r;}c&N0$f^E$opB2}s{nHRWP1hUF9$
zDF+~6t4JJJ;O)`b0i(^LFvcTdDgyW5Ks!e)J(9kdN0-UC!8)bu;YDU!y56{>q6|Nb
zU=D@cAkks@BPtUoe&g0Uv%Fk5E$}<=Vcj|yU`{gD1M;jzX%&<MD5WUI!&D*o2X93|
zqAup5;H<+dFI+7Tvz@Zn&?6BEP*H>k-SYTf6#g{aXSX&sUV?UaJyuZs)a2)mG_UBU
za~+NmR&{zQUCeHQ93!R7DnTxOLweuHXQkcR$apH+mLa!fq1?)j0*iK4DkTDXuF9lL
z<Fhd#4v7(l$k?RB`d*4)h2O<4Le(KDa1p?ApbxTa7!nD?lXXes$79lD^CF%oN|q&I
z#>XdGp@7>Z?T^lN-T8h+3o?Y<3YJz&N=~>AdBDHfrJam~3%j(Fk;Z8kcQP_PvpU?m
zsw4lxE&{&5oX?tbNyz2UsgI0PyL9Y3M#TbmFQu;9W#XG-bd_I;Bm2^u(V<J)Rr!?=
z)r<L+NVUx(e$kG9gY)r@VGY3JCA2S_(i)KMYx5EJ^SZJr>jJWd4GA*GOR2>+bz*qF
zc32PbrHo~(lsmv@*{o=J82A?nb3|r`P3n=EL2VOyLpoiSb1fQKmy$7BxhZV^nz7Bg
znJ;B^v)JY<bHRhsw3U%CZj}hv4dHk9Mu{_FD9I2nJ~*Whkm9$8Hd@2gFr*hF?>&n9
z=Bfa8(?*#zk(R)6#4qLDzbV;b$>SID_-#<*fs>uJmtPSV5=<V_h5<TiWf=R1XfX#=
zsf{v)0566`vy+kom9V#gflAn8G=&r4kr2R2;Yk@PIG*j0lFA!v9TO;!2%PNWlr5w|
zqZub!vFCgPiMY3LnWV%@xI)GorfQX3*04dmkRn2zGvU4luuHVL!ug7^f;(Ogs+fR)
zN*zx^lQphE^$<EVab66tp8<>laT2EIqQn9SpfjLf&ZG$aBU(iM$dU_-0@<=O8(JFh
z3_1p3ECZD!MkaL&jx_VajsTvEl?@M%MH6;p;JKVh!NLZfiva^NkXGUhB;5Q$VM)H}
zTnBWE3Bhqu^2@sR@q9c?c#Iy|5tdfJtd6z96A0%5@v5vhgLrx6IvB)DV2G?0W@Q|V
zr=khOaJ5?!7?g=XToXXyqU5LaK18O(q6my9IVnrB0c^!oMPiZm&>BY^lXY$Y#2Hx`
z6!CbpuKHMnNLi%97z!yYiy|t!nLzv;sS%ctefdK;b69A^;i5A^@<qTvj8Iz0i6aLd
z<R$TV{aGc`;r(ZV&vQUzFA9;K-VHq#7)7~A1ZBcv0tRoj^TSHDJ5xHW7q(R_ZdVj^
zKv~6)NCQQxgmqb|&%EGGm2(^|i1T@JY?5byn49qH79|%2@O4k#kzL@T&!gCI@V{p+
z#hWDHPzCu>?iVGOO=xuq)NTN)I}(vB*O8I255vXjy!wN%Vm!?B@vK^jUluGIf0y5e
zieE^1c&TmQ_T%Hj9U?`y%%bGF8b8B@HGL-aq`bWkP?A-qA2tO#@`nvGI{Cvm<dLa(
zBvf9?!>I}2fmu*^h?`@COGhnGYxLP21X{5s$WMT+Sb^i+*@cLLY4Ekii!7pi*6bFk
zFa<-1T6VcIl2TaefK@RWk2^w%trey{(k)E(<Ul}-Hc=Cyh&N$)-;fT1=Ot>&2m(M8
zvBjIfI&W<8c4>;a#}<WC^n5-w0bavlZege<Y>FulldvgPNP2Lz8cW{+q%tNTa89@^
z7lohBpXFzbJ<y7?)RfBkCPj<i#Kqr)_YA+432Lvy3uUQG5$!V;Oz_R{4;g~dVNPhw
z3Iv3THKH<KH{N1R7|hqLPWbS3u@jL<DHc4xI$wy^c!>3jVxiO&B*B^zO$nJ|O{kn#
zDwBsb0V`*sNfU}P-i1a8zd(8oVd`RoXO|Ex0H&+}VGaZ~0j917UP?4M3cRUMTQLA@
zbN!k|(a@#wFW7@)Fn$EB6jkH9pu?_hjmHuy1z8h-C!#Z~0lyQ$8K!L6qa!>cNXb-S
z0b47$<44^#OyTHt>V!cClC^?7hR!EP1))<+p;d%VSrq3FUFwGO0A^fkLOq`9#UW01
ziq>F$iLgLtNP!jNG0q3MLx`Oc6b#PMXAl^gT{y6=E*Mxx4-V_sRG5hhO&?uiTW*~i
zI~5#u>`Fl^5=+IbV3Ses%ZRqv5&B`KS`yRL3wr~R9|mRpNKz(%={TNev~svv#4HFH
zE)Z-?-k&#RO;F_%fTpr2I7R@bVssDnk^dPhftRkCO3Vec3VLJ*Xo4mjRA34PC6^es
zL?%>sK7~!SWdpk%ojCSXDNJb0i2F8$P!mYyFr%#*NGkD1oC8He2+afLawTssN@%2u
zgtL-%L%F;b1?dX-6ch^+j5Do*rp(|DgsVm3yo}wVb)t)4p79Dc6ME}7(@<)r(gS&2
z2<VakDwSKXC@Er9XduO9&}-gN8pNz>59Cj<%m7y(aaJ8UcZ+~!^DBo1eFu+H6TD_e
z<pwi>Nh98SQ7~f`pftGwyK}AimLxz*Q1ERoH5K&k%4P!wwZlvx+|G_?VNmcX7=O(<
z%hW&@fiTrs^wZ>l?6i=XaI2kLI*Jp}I;LEt?kCS1U86vTH&eNS{-_&^mvB$BfI&y?
zATwRHotv29t^_$*6tIStGPp=PQX`GErjs-<9A;MHEEhm&$Fs|fS2iL$3{|Y7mI}<M
z0vqUv?)an_h66$A(CtkSM!oYu)_va__@n9wD8;)|ps<<hC3L*fjF#SoHj@0=DajwH
z4yZ4zJf9;IaL1nd)1iPHyvYBMU<pu?eSB27KS}%)>l$7963Q5b6>x9zyRetCuFy6o
zngMH0H2Q6nk&@l?&H;GoKFOhVfHXma+$mig4f}gX>~(RblQYa_hW+}3LN;Kxwg5Hz
zByiqLX+1S1Q0(E9Ahfsuk53XumvWql$Xol=x}nQiOHHl)yv1^SJN@dP1acEoprr(q
z<E46D8!J%q>yv^3W(KQkd~8dquq0=f3>9VU3w!pGB2Zch5pJ-v{VGLgD=A7zJ55p~
z0;i2lc$$PLMff~xFN4G9uY37Cw-yS-9ozO|6}g>qOAwJ}j$(B0v*t_1>Q>{ZVs>>7
zvEW^uRV<3fBkr}O0P4_Vc|9GBtiV@iC#&>*Qg{ji8DIfM@CN9Zkn09;OvrVPS5l$!
zx1Y{EQv|It#@~K9DhMf|)ghw9QOg5JiG4k4k;(j8WHMhDA*(TRGUWHU^P1L?;`ROL
zas#5leN%fRuWzj|IeT-Ju@4ux1Q!}yylbJeMDbngocpESwa(yW8boyUw!4-+IC(_+
z8y6moyKCXWxw{q~oVz`lOMT%87z?NvU=@-QO6h0_<S)gfA@Ci_Oa4&b)SY%Wbs=k-
zx<KUaY$b1boeI&v-6oxmY&fOUL7;Blrz`@Sk-0`(qa*9GVuD}-qGsRfBU%QH6%0Te
zYw4fu(q*dp;n%HhnDTY08>W2aZAyzwB+5f?O<ADLL;7^1&BJKwiDZy7e>SIhjnd^u
z%WAZvlzGgNOFyIK%z?&=UR-t6dA;E2Ga^g1i>t2Eu2)wt&WO4bD!X1yeejZN7uQ{d
z%dc!fY%i|7s<<Mguij*DO1|Q_K&Re|9Q~>1Vh$c2Y*U2*CfptMglzNqcx1MDs}q)E
z-g++<R0tlKH|oz%?s=6(oxJwhiXJL$I;j+^Z0VeoFO?~slf5|Dp<V;+fyX@uOB08J
z^_Z#>b_4vbs~blvGe@+_!~x#U&cQuoZvVwF(q>aHNXBfmrR171UdtX{`HeAJGSak+
z$dVCfwad!0l2m9GA}1rBO?IL-&tFVQjZsyyH?@qRl11tlAd&;5wEFT7+Sn|0D_JFb
zu%bBQrDW|}l(Z|S-qdKmXoY_=)#u`$;4|0;%Fxd{jiw7B>P4;#ET$NTvxlbd>J<8N
zWV)aa2h!CE1A*JJ=^h!hc}L0b0nnW==i)bL?`DPXL36i`|B)u*{I8}zr!2s=FH3V9
zwgC#XQTA?}0RvaOY}t+IuP}Hol0WK()%Qo;AegjZ$hZ#pq22o4;FnMHd~<q1be=jb
z+%)4fr{hCjfyS^Txel67b;Ax|3{unC=Q!@$#W=R+bbTbVod#|lY)%WeibT7k3%?Aj
zg9(?iF`TH~Xr;+j^_MfX*P4zfAigdNY&{LmZ&RV9#%LjyQeqa2soD~=U@Vgm;zDzZ
z1MAAYDe0QRSSb&g;MDxo-$Pe$NrO%oL<Px9wg?@*HmoDc)-4Kgeoz*;9CDEsBcENi
z)Aa|p9&=*K^A{;G;rTNyBHYtPAk#)$iIPAX+|`SMWd!ysU6V)Tyrc_MI7+C~W}Wdh
z4RzVV>6zT@cxy9FB{OBx58CuGC<$HqJMAf5syHg984H{pK}x?eriFJw*HfbxbPT_Q
zM>=zFTF(&I!YOMVVxxqeMhi^mq0`Gv&Xvj*RS~4mn395+J!8VcZIA_1E>R;MT9+TK
zh1k*W-yo!>0(q^`ORfWiu~?l3+SYDNk#^mcEt6B!A<|$P?KB}Xqh?W(Qz-j&n4p9I
z0Z6O03ZuaOX|SMn9S{uNQu)J0Ng0t|11nCKCWFJ*P?)j7acEt5>J9K0)^D)__lpWk
zGQY-z$K3K(G(XW88Kpu-L6`7Tj6xKJQsW}Q=FIpPtaY=Dn1O1f*eMfJ7(Auzrr;^K
z+?qnCjON3p*eU4;sVA9gpf-49%z4*Ct0TC{;uF+EQ)$<RI!+aT)Iv{<5T%@>0SQM>
zz$_q@u}}OJ0zB#2g;#*7jBbMuz*LU6g*o3ccJ%;(@m#stU}+~pUs7_G+6H+1nb%7N
zk4jVF<jkfqfS<Q~Y@1R=8{YVf0`aCX(p06o!N_Go>uV??R)KKLuQ6e@BfVz*(2Zt>
zyh$y$Y;k_)XUJYdwJCE2xh@g|1~ENGP$@pJF@#Dngv`HTnBk!eoD4&3Gyp2)cTvU`
z$=DKlHi8{<Y-ffw!dci*M=IhaF)nB<!!$0uPKU(*#EmpU{Ewt$+-bvqXSiny#aYpw
z99RW=VnI*f65G%v0;A)QHRj9~1oq6=s|ph=0s~JqL56$EjBzsDQ#Of{;hwGuGTPHM
zLFhDta(+Ui8ItqU6phQ(fU}<Qxrb73Oo{E0d$Z$VW)_VNYD#|qcbF+NNBmKdlEV}*
zL$ya6kA4}-#(4D8*vKZZfR(P25!y}Nur+7b-{37cxfDoFIU*FgNWs-fGmSA6O4UkM
zHcG}ulZo~qa>^#*G>ySflYBK)p;{DnV>mdjKW4QY7QhdN&?uH;v1Rs~`MS3oLE+s0
zi!dVk9Pp!Q13WSyU4N31?OLUq@#4JCjAp^9CAqn7DoV3RhCc$AXeyk1?Ji1i@?w;O
z-AaAnPB)qlh2*l5U@|eo(2ArCXqA?x#7LTa9m<%Ayn>S*n4myD!270xKZe4#cF9S_
zL>s%Bh7V=n>KZ=oh)eQ=T2^++kQu2rL4X+C8CZKcCjfKg<ygjE$sL$MXZpm@6tJ<c
zp(#KORY@gd+}1TTgSejqkPQ+TaLK0HO@wGOmUl8BNZ1wP2Ve-hE~<(~!=}neElOr&
zT#_J2{&kCUmO#E37Xx)K0pkM7z%I5jTjU|ra1UL=Kn2RWB_jI)(h?P+e8ykrkL7oT
zUnf~(gxIY(AOnuQ-ITaUDk3YgO?W$g2k+;*=}UkFvAgM07t^lLV#XD|g1~T<I%A5F
z-6|otNKE*`0@A*E!_H7pdqR|@!4*P(yd)xaOH_bnoLY+k><F7L3HcksHolO^xkwO6
zq@Q!&Cxy6wm?dJ-glx@?a>PM|-^rk(n-)7memG9Nm$sxmr-sv`MJYuhxINULxz+7C
zHDxGS4*|q1E4LfU2_8&VvZq!WK}t`pv>}BNBV*2G7gvy)y+~vWaxQg7T$OVPJ~8Fe
z#V42o^PW3E%A8BxOALlnxkjcrElLh>X38a>Z3oZv0GNFEE6H6dt#8V@h2vkiE*{}x
zPexWeIuU?=WRGrs+(2>N<0o-}Jd%V-fAb?r$TVwvBnh-cKaVB|Pw_+9$h$H!f%BQX
zD3M8i>L7r{x}7=*0E5>~)4TvBaVonpZu0me=!d-Q7lD%)na!+Q1o%r!H8b20&>9j}
zF#jae!nO71z=vEDcYH}Ze-i)U<kpAA(o`zJA^@<RL-PjQ!#Ol>R|@(`<Y<>B{0dzu
zQ_z_>V<<A#&I_%~)-HiSY)mNW>XP%}IWPg;prR87XsC8dHJpUtKcDKAsqK##1(+mN
z#kEOPh7-&sCW9Uiixj8~CguXS2ng|px^B&+RG?@apJB0Y42Td-D+0hFdV>kD+T^IU
z%(iZFQ`-b8c4MTHq3~Uk1Je-E*yL$6_yw9Ahlc#?qsi@O1E4(e-vuRRq2(V$W|(LV
zzOWB=7$0Ed2%l_5I74dXP1URyC1)U9tWf69#N4QEIfXQ}tadU_n;(vhWq#n!8Mp8~
z2L2?6|7@KS^h7%60N_qL)u$(J%DHt)@D<xSCF}_#0&keG%cMk%RJ&Vix}6dB+2ABG
zlyY3{>O=q*e&`|qi~3lir}V8;jzxz7ye|#@2jS+b@X?|q63nR45j<z8QzFn*mjq#%
z+h<yW*sw$VR+Dw#27z;gaX)|~(eOw?>A%+WN*P4Xxoc>I&$-np*;KMHFt}&?P_EfS
z&$uCHzI7c2a3C$pKsy-KYv~hxqTALbH>8Zz@xG3B^+^b)wslGfr?&M;NTfzDT#(KL
zWKy@ZE~5*e4P_%{YHFiJI7|j19V%`{D?$K6saIk+jp~&cPGjq|*m*P+TC;?6r$PQD
z>qS$J*`g$Wr#dx(W>ND(0PrH=@E<tYJ6nnBbn8?Cu%3*pk#4&t$#3N7pRGe8P(3=v
zvLcO39Ym0EWB4dY>oZIsTsEKPrXD5;GaRzW-fc9NrrGEaT7Oa!1zL9i5`3H2o)3H<
zuN{xe#SuWmEa0Z(P1>-U`_?G|@VMh~`M8(#6Yg$Eys|~{!e!*r`B7-N5eat@a)Pzw
z1$D<ICkUPH`#}`CTJeAt;^rpMT`f57vnq=+fIr6u!Tzd)5$>;gB=%t~`I%1CoSOre
zXmGVZt7se~#Z+Xm2z<dd^k_hQcpH2k8V1#9W;|pGr58B=D8U<LZ~#tWli83K)i&g4
zGI(yAEQLmF@ImDOrr9>=HDU^O8&nJr0|eqCK?W1qqN&I#jlONrp%audQ7Iuljv%2$
zf(%6&?IwI~rgt-7;FCg*0dk4=E=Vyz?ReOzTN(Wvck<AZ18Ad7VS?=>aV(=OFq%u4
zq1c}rg}eb$L7Pq70d(HPMGg}?qe6Cy&hkuIS8z#EV(&~n^F*Nu*RW?=85>36m-9B7
zQsUqNXj4j@D16ifCGlaO`=gz%FoS!)&1>TnDaEN+$+9nsQa3jo6m8z(6x+qA#E*S8
zPLVPw`T1rm(;*1gxv?b#<g(A!#)CW}%IpVs%A#BxTml&PZPrO~4L^3^RgY|uW({RU
zzVTmz!_i;fZCl->cu6cv(fGDDq+po8R`(HM)|oS-$q~&6!=!*fDZ4K*hZI@h97wb6
zzO}k|+}_Zw5xLO>qa?~B{R(Iaiz2Bn(yec;wR~t#t2WP!oY$hz2q#kU66)#GYSy51
zww7>~;Uy_Ykctr@<-)c~KV1Y1Yp~fauEgGYN|DCxxJcudb}=gU@H00?#m;|b$$XKD
zQE{l0AqDsq?Wxn0lzWqfyc3>#m(b_g4vbj+=h-*Q*&=d$+bdBhwQMBVK8sS@=XoL|
zy|zyqLD<fW(}HrJwx19Y{jRONKGDxQT@$W+KV3(L+3yG3k&*Zs@I14sSRENN#!F=x
zr)@u_E9V)#2tX^~Ilj^aYR}%IDV0DM#7Z~VE|6XplBgmotaaW={j4%@sMva5+r1u)
zySH0B&`cJ|KkiLtOC%*3^=#Mp;zuuo2(Iy?mqi3>)}qukehnpSK#4ew=^UkJM8#5A
z(V&ZTs{=2KoHpuLF>M9VQ|IZ5YPYDJkR?~iZQ$%HG@J@nkA$$*iYY7XI#sluhL2r~
z>t*<Ws@IjE2S;>g$gu%ItTTW(m9Lz!d?U^}t~7!VmT}dsIasvylJW)ZwOc)SS+!N(
zkin|0eD4CVf3tnyK<%b$6Iy9k2r8BHzF9v|m9?E)uO|x^*K-zCS5+5@uZhk8P(C-h
z!aMmSITnd80aR3NTFrRsbS1O%F~lsVmmW;WgyQpOtxfZ-SL{FyC03!0?fIAEAKUXU
zcVU}ouH7Z@T|OAQ0u_VuWEJarF=i3#?Y)?TzqU@nZ^1b5X}c(VG@@K%h6gTR%jl8c
z#vZAAEDC#|RC=QU8;|p@C_X&kv)nh|nXHt4R<Gc!@H%Xu5~FQ>g0a0$XI2C1^`y<K
zvG;n?vRHaOX;XjgiETpTMliJZt=oupbqap=deov;dc9m=pXuGVUOB+A8Gdqr@^K7S
zOs6gDu)%5_bL*A^oLjeK;oMDA!9$v}4%)9+M&>08SMRmKXC#xB)hsqs*GV3Bv|}qB
z!oZ5&pRHF`&8$8-lxOR+xa9)5q}h+9X%^**Rv8XsBwiws7q*v3K;El5NmwnF&718Q
z$!6ooYn0JnG>%5vFvS67%e}+_m!R`0iyZpMM?PtW4X(H<JJX!o33(qD-?i3WX6_qY
z&}k3DaR<0z7)NkBxt>TPtBQLa61aGLZpQKT7Z?5=ULYoOCn-c@vwPsia2n~82a3Lc
z*}muNn?+;utAs{al#!X~>XiIf^vlF4j|(bXN+`}XPP$4^NV{wqGs|WRQ7(KM>(j%k
zPtH-eb%tkhB<(+Ra^#nwy&(dJiT_E74+(b3fd9~kq+#N475JVdXhbi=22geTC}{xH
zL?7~aeH1xG!I4hTzwktzCcuNF<ViYQ!|fP~>}Cmiu?YN?oUu&h(=q2+Q^ff<s4O5a
zWdT2wGcJBsS|E~H0xqIlgE>R`4ug}joB?vVm*E6iGkui&jCkeuA+H$@tO}okp`Z`F
zw=+AZ&vK*TgqlEDHb9p2DbsnzEcID#w0wy4vbMm!&?m#Y>8|Y+rUjR7pE8Z5*SF7(
zMsR;h%b2Kz&}Y|#aF)!H1?b8uTSGr}f}*?>@YLx?eTAF5&)u0GyLIl)^w=?TbEd~g
z%Uk-SF{!Ioj{z}#QOet&qh(YVqM-;Tla%m%b|Hrv&~f_IO><ea7zqM(Y)aPvvTC0~
zva<xF?-jKLgw{^PR0c^AdM7DE;5;uPza9zTqhE=YzqInOvGj|^^MDxY6@rC`sYT&g
zcy;`WoaaEU?ZTst7?T*U&IzC&^-KZGAIg2B(3N2BMRUr9TmF)1JnK6o_>y98!eT>&
zrWetCd&N%SU;WaBak04Ag;xG*IY$5!)hl@F!i%|rry|L+SLoD*+x0@iNkk~+ujEG|
z`<HHv3zz1l4WE7crH8_WWZ-_wPl_TbUA5kc!Q4N>r9z@^hG50zkcq7s9d<?&d_}?c
zUa?awO?Jx~aN~Nb*r^+y`d+b9DDFdOvZRavFXN|Duy5TbpB1kUkm7HCjhG`E+bg5$
zV#Hc@MBXh5uOUEbFA~QG&HC0JN3pbp7pJhlSf-oNn@9{^1P(bbh`Rzfq5KMg+<*$#
z?~30{@je!*0vB_9(k>C_wI~eyn;4&rLU$fw2hsOl0w@PSUlL-)ANW)6EB=kp!Bj4h
z%>K&Iup}`06c(8>{oQHz?-gMM8|9)@sA;MtW%|Qhqi8ec3<dA0U`<G`FzOd2j2XQQ
zf;U9CLa`81wqO=3YByHy!Nrlr&S=A&o-F83{^!)QXdR4Tvi?YSNH~D504#&m^H?PC
z>498UkktdZEYl!H+*O7k;+^Bpcq#-tRZ~AJOggVqKPyZ+ZxAo@+mkx>u>e3h$P^P+
zn~d=9XfYH$BxDgX$lS6ykfn)$a#!3@)QC7Oz)cy3j=G}?G-|*f^;6HW2yh=sLSh7h
z;1`9_^m&aCk@cl8Dpx^|gK<=g#3?wY$bht#cEX@!noGv@`}v?T7LSzChtz;Y;goWb
zT@^|i%E1zcwlWY7H=e|irm!Yy%K8Nd7KM|{>avxD5z5#iFgx?SqKT2GB)Oev#d28X
zUtIM`j0;+p+m?e7|IzIfV^gPESiDTbNIlf8(lAh%%dPS-qJFM12`NYEGAuS$FjY~R
z23EKUdboiXUWgsAXL><xAjHcHH^We%HS=<gq{P>O3}P*Tj`3ZHX(3Jk7RC!r!jMDY
zg$)554j0B2Bfea~4)}%(;j5V^NHg-e5?IS+#BBI6FK`8*Lbx!`8Xz7#VG^?MK@4e-
z^0Ugxd;h7M_FSSRc!3ufg)uY0GfOMKL6b<szXAapKXc(T+Ji{z2dwr1Qm$8JAU*i$
zO0MI=D-pJxkU0f@uc)jwXr;|Z)E2SBUy9nQintNAwMNq_n+}rYEt@?c%lQNO`0!@>
zfqZ*7!7CeJJ{N(Rbbtr-%CwJwEmtiq25dRg>f6AulwH)gghKCR(J-&X`8K14$)ljN
z%&-x!6+`R7c!=;U7k(+jv%K=#+l`?}gkj`#mLNM+RLv`~9hOe7#C9Y(FG^#2X)K_U
z*pG%3=0#!-a$YD3Pm2&P{BUKqhGZ&WEuy$Qn8m9!qPU{XjM|*0<h@f6l(CK!VsF=h
zW=>IwPrXMAeCoK75b)LjQ0+~7q4(6ay;9RNpvyBe9kE<qndyk-av=)0NX=bs;tL=X
z*A*gH^}Z|l8=H_o%PRuQKhnPAS?C{`-!b^g{Kj#<WqyZQ!Bxwzbyfm59uO$k=#}`5
zR9COWZ=kkE1&I_v$8u(zU1s0o`0fp@^<ix$m@F5i68K{=JGN7rERP^CjXvH0E?ai<
zu08}Pz)>yaZkEoB3f6!qK-KL^0!M)puOx5)`Y#HnI9T$Uum^FfbVn<BFHj=*{ap#+
z@QS;T)Dfw51c{%W>c!7qxnwkXH3W=!A86%r$;I6ej^hj=Y;ZI#0>6A?xpv?Qb_#C2
zP_NZ1YaA6_U15g}9yAspNy>;ekT;Mkv?zq$F!dQ|XAi9LpkQcEBOK5ZlHdR-?yN2p
z9yoKn^2`TigL-&_1=IVbTP)oyUYX}GVR{!h#c=iFfSjFR!Hw9g=yhv619GVR-7&J4
zbk-~w926d<a4onh6SOo*E&_*xI`8sFv~j5u*Co^DSE(5e=SD9nys+0V3deKjr|8^j
zi0VFE^%Ww-3%$5r4}0aI1H-wi>?`BD+|L8e)xirlCr=}H0p}Py2+_ybhnzyDfUAH+
zgPod1dXj=(MD&43xDG_7JGk=?qK7nM7>nH*V%%UW_R7>x)3B#sCZ{;mi-XJS(p6)(
zr5Vzd%#ZXG7Asm(g-ladHI4vlT2k&p(}0oIE8!nOV2jf70f!(kFAM;fAzf~vi~(bP
zrI)IryXpwHOe{KBmg$93>Z^$Z0trkmAc2PD(N*S&<Hd#JEE~tTv2Ao|&fErv46AK;
znU|&E1?*TpT7r~I1u!pHI4{f0yGtKKtx%6TDvkC`cU>P>&sH)4$!zYtOJE6gm1Ay~
zXY0YRTs^Xbs{>Ki21HppAL`9I-EE5y8(LAu1Y%>^t(U;s+#RhDFFpA$3W^dE+eJy?
z6?IWiWE!|AD7v(+6co9A2~g**OAH`(UYHKZ{B)JcArPMXhLx8u&BA>^TB)ntPP<R_
zf`nzFr^}<*P{urpp<xMcuDVcEZmv47NYqGh7h2QZvxV#a=E5uU{^rU9cm=7!uAps(
z2|6(-4uK##D-jVV(OtUoje|k=?mg9qlb%qGqP$VNc`69b1r-dvfGxtB$D(rC&Q+Uw
zv%;L`j3{r&^K`jc8%%fZdVt>C&lA=n7$Dt+5(5()%ibkrVt7R7G_aRQGLNO7g5~pG
z5j=QeIN;2~BcD-t?ZJ^>gxtu77i0%)iXOh<027VTNtJ*p&Q+1Bh4IiCrJ97~9uuh|
z#4wn*Q<8f`#(D;rr{Y&De6Zy&gTW8pe;<_Or|`63SVSqpL{NpP(D9CWKK>2XO2>hT
z&|Oxy2NkzJNgY4KHG0G;g5sXy6ftm5a4L<ft4&4$0oTMQBH)_%R1`7_NG&~+Hc3eW
z83okovx!lpbTJBwTBpHLRm=Lhj_dq$p48dmYN-&+iN#V4w0?56Sf2ov%@0Ddnp$6{
z9nKX4+S5eo%CU%uz!<nFMou$UX+`pJd`USF&gTM&=``DXP?Aadop$QuAOIC?`#NkO
zpOmrBs&y>uPRV6u70;e{e8n47ZP_^7T%#ieuPj7i1|T`?vLt1!7?<j7pkPuY@b;4t
zxi{W^svJQ(3VxMWA6pb;NEd*%j!%+A8GL#^M7coMYe)1`a*IvVO>#@5c9Ym*>-F~8
z(jL$43)J{y+xCQ(|D^Qos31apoiz;a0_FHBsQWsi7~aK$tswL3G$gG4c8C&tzs^|#
z^zW35-1;hr|2oT22H@CEd=?9+Yl8Izbh)tPfGb*vWeJYDl2E*0yS5mL#k-E7Te>hA
zy|rDcomLRtyge-;x|ur^{<^&*d<&Wd&n;-auKceK6}I$*4vkW}#UfDe0RUQuX6Ift
zGhCVvq{4@knw}a^v>_2bC|Hc?WL#D$Pu-_9AFMxET{>9zi+4_y(zw_yTDLS-&iR(Y
zimSqJX{^{h2wZlrni&r?R?he-g>|(N^jkV@X8<n?-zJHjFvnr)hB*$CzKS^xz_^wk
z-Ukk8M`M0y@qO?XQ#FjiTdZ@6qpKIDIJ$aa5r?bSKzrgP22`j%MmF)8@%ggpNcFA9
zPapHEUUD5N$45S$`rrbq3<NC|dVVo_s-9>)qY*ukI&*TjdT}bZdU1Vj_TuV1dIh(U
zlY8_E=I9@G!UX227dK9mdFsKPd+O+uTbgyQCO5R|Tp?nrUi%$^cR`7E<I|Z&)jsnA
zt-4nY@>O-Ox<14K_aAA_Kmr6SK)KVW$A~Ha|5^K&p6hZYTMz5cUy;o^jVkjV!L9&F
zfZZ@8m0N~85_Ak0yBa!%VEf;Dk@3WsYo{vT%>C6t0(*aqcX9GEIT^v=h!Ghl8-S_n
z6XB^tRVIpXP1Rw3Z@Q}2{X#~o-{hgmgjYkkIeU^uk5MRwukcNQWjGk$Bv|Rle3M|A
zYH<;oX}pHOwVCQ`D5N;^fstAHZ%P?9AW(h&ro3XKZ+_so%;=t_lRFbwS^Bt@z{-HO
zyxzIYf_9yHJg2G}Zx$Y!*Aqy(wdc!ScoVYC`uY?zYulIGF>zF{Yw~7(yOS>eWoCyP
zf;?Za71gpwcTIHZW_vxHskTfmPPS%C52sWw(5%-{+YJxr$}6UxUJ6l$9!WS5m2?VE
zg<{vcrH3<B=F`noD<>?kN2CxfU7V@@jDwGuP`kmUJRnOwn5wM9S^_pD=lR89(GXMN
z<+|hZBZTg12=?AVMO`O;H0<@u$q(e}>n5OkeQyGy+4Nb6VfMhMT3kW!0vzQbl>U)8
zmmdV!^q{DEFE$c&^<I8tl1bf<oII43yAJ|vZnDa+YnGeNa<;Flm=59Eds`DZG4nd7
zM~aBJ&S9?8u^}pk?)b387TlfHp?s+1@O*|6qIxb4B}DaH9EoU5Sk~y;a6MOtNRYd~
z7ic+5ZqKN)d2iZH)B6EM1?a1|m1B?rzq%KDQD^7PXX5!X@#@W^9`mr{;`7}Gciw$!
z(}UM=h?KgM&txcGg~YIV&3F^Kat3&FqLN=W^Rxd=0IT-`v+ofXoYWxvXS^9vciw{P
zm_st$p#U7x<qolcXG-1Yy^qbjyZ649T8m*Cr5K`Y`@Oy|g=4Nvx5AThj8HqwW_`RF
zPq%+vPWPRs3f*8QEbG1GJ`&&GH{m@<G<8>g%6aRZOKf9%>dt+n4<#?=uOtTfCSi^<
zI`{ieBw>#C_?3j2tL#B3F0ylPIFfiFZw}^!zO=OI2Fa0Lyh38e$Rm#=8dBEq0&{-C
zCnCpn3_Wj2jwD8|G~vWpzQ7KEVb2%(V?aYS6cm>buc1ttgCNVBCZ1Y5@lRXT@Mqn`
z5(i2(l&j(br|tuk@Sbo>GRHrN0!tG=NN`fB=OJ*CvVkW!Ny)(L?NYAo1V0U>9~op7
z8p_)^1V&nV2vHC(E@%Y(RHl}XeDDRd(cL2lxp0nvHC6d!>sP{ikPAvRGlWPQdNNvH
z<W;mW$er_y3rWgT(jax@i@3_M4P^!zLMgrJ?(q@~r7jwRDWRo?P)hxlfR53s2M|gO
zp`+%iN$oRgt{Sc5$|*uvwp>v+qkWh(iDeqljh%90=AvJ$)J$<7l9>taDc{>10RjiP
zZC?c6AS3PzEKK;)S;+LR0k(J{iX)*>C3pY^NkB%junp1#kFwRfCZHq$qmkY`5xkAd
zaCPyPGs_kN-s)%DxtL9QpDIEua=Dw0l7{I>{8Z5gkqD|wPM2Hl!IaJiL1063BOmGc
zD^qjJF|<r|or6cwE*x;5vu&{eBX2kR*cIGME`_IG4SKuUHPPtiQJP){UfaU`Xo7hL
zvGQr4jOZzpRHGElJMfqz;w!~O?8z9A5R{Na=det#-U}6&_H5s&Cli3t#dDB0`H?VF
zpeg!(XNp5Z7pFp=N3a5}#BYh^)FV26OYxl3Qoyz+MT@_;EC&?&e#RX0j^#2buY{QM
z0dl15BAm!mXx|A(8u;$|&hz$wi~rhM;YiL~{=U<k%j0<8X}#r{{zzEp0GB%8^ZTHH
z;`7SF2a(3&-{iMA#$=Q-EZ~k1_e%Fy(~OK-FpZEfH<7dEO>i2&f0K&|1NlJ|VGCLY
z*XMO(A4--j1lie)S`f!*I`O)vGQk-b2L9jVOw6qJf0I+PyY$A$m>kzf1|aH4a<*?A
ztxHwlG<*X?((}tHCI(5MY?AS&W4d3i-gJq-@hExG^aibr8=#=57H%lsz?Zx~;h2Ub
zqBN=|4kJ6lYeq6Ec*#k-@u-T}8L(k>OApCN5(C@m3>!&NpzxrP>;tC#8+xlZ=x8J(
zfLQ{j1~g@F?9#~aeltCqm3;%C#{D%8^D)8Kz7bU;BkUD+HBPL2#%YZVjJGV^6$AL;
z2~pI~L+~J+^o<T18N6=n9T}%?`Kpue?|4gCXvC#k9z#b4p(}cAz@*j1HZ*X4K8ko7
zf!2DX<OT__-cY)cQQjgy9~skaBCZ=aLAz-KA&h&aA8gEwszhhcjHyi9^%?M0UQZX3
z<+qeCllW|L#Sg+xKN3p!sC7JS*;it*mo^Z1{kwRjMh0Fl8K?wauT;snS-WWR2Z5@6
zO?8zpoh3!H$}Q2=MNoWS+AT7$TFhD_0;`v{3UbFE3GZ-ah-Lc82f(tvWJHp}Eq$vY
z$&glF>tf3f{;=l?ZrEjdDF&>xeWg=kWE}O<20<M4(*Cf3v-VXqN<N__1w<V6lKz2e
zx38jM0%*XW9g-VptkVzUO|N)JB1}3#gCoPFofoM%Y3(A4lQzvvhDn2HID&X=T)sUa
zy3dt{QJl0?jKZXKT)_j~r+_j;!O~Mxk-^fF(tZC^=MbFK8FGFkD`LfS=HPZnKE5M}
z2=jM+5EVMRW^NJ7J9W6=Yset_L2PiJQXm;Qtx)_C(ZctJ=%F0Lt6EgX@QM}{0e4f@
zApUWP0-lfrX@Rr|)Z8!Qz=$M~edG~fB~wG<MW3;fslmT01yzG~lnl9Mi2I8>VL&?m
zyaWqJ)RKVV6r#zcx3y_;eN~7SMP@w!6p9PtN|GIdmz)vWLV%5c4<_rxa|J=uFup3y
zFY=0ENz;%^!;+<;e^rU#a6toyvA-lBa-c0<wv7QO@nz%~L|H#CX~*Es;AQq0P~*Mi
zAA=MbFG0w#3_aAn%`mnhUCWHPYWQLz85tt33zZ{@9*NLofQo!cPx42d<XVFZi<dfO
zkZrYh5l0V*{EsLr1s{y55~L7a7An~RI{5HYzDLQI4Q7zRqYIioB0e3j{wW3h%KWMU
zS&h1ubUK4N<BQy8V1o26AB824PS4+m+obpYRVk)OJB2|bfe(CS{JX*+hK;28$upp_
zUv~Tp{5gNmS+Bp#Ao+9NRWNhL%2%~JV{Ly`o45Q{3c@7m44WcMQs1T+liq5{n3UDl
z1=8?Au;nTl<S?KSiO31jU2JW=wW7D{tJW0qC(6;=nHL>{K>pt5SEcCf{HhkcmD2dw
zx?N#Y!;(lZoTvt8UhD7AgPf{=)d+H`PU)_ICRFkf-6in)Pe~=xUuP+ISx3Tt3J|yB
z1>!-`cbN|sB{poXzk0^e4bB5y32cuf7~FJLP5Ob?O-i1Zu8h3n0)Bh-uR3=`U#?N(
zG^BvRVM$w;Uw(4by<dKk)GeK(ElKK@me+=~ZE3M2Q(YcL0ULKEwthw=o;i}Y60~%0
zr5NR_5t5lMm&#5KxA)~ISKa&eQCZ=FG<fQC@_@0SM;z*tqU~Qie8ZBcPNt(LQ(bx#
z$%&Jce-ENN<FXAR*Z2{rQm{Gd^>b0#OTPYRkX@%M4*E!f+mIJYPV>ulIPx(;)hN$*
zP)s~m#EXk#?-5iD>dr;Uj~poXrD9b7lAJLO01tLYUVx)-i)_NAmMAkzBS<8d`Wi;}
z>$qcpdWRZd`>GTJ)F%svMvps`=X-$PZ!HE`zUDhd`2CJzgyAB7UQydyGhW5`nKK@v
zJh<JQaTvr2|9=qeeMLFtDaqY9u<~tdGsb&yB<bvN_{^0)=3Da4`gy=dLTTI)=y>Nu
z!nB><fJ^vsQPXNTh*@>T^(ColH<(!!b2ms|)zX*vReq-`cv;)mRHX#8^a#3<CfbT4
z@Dd!hnyD1LQ{{IS<kfe)?`@Z_sR}aJ@-<ag;#;e$!Ursuj<c!`x}HtJo6z@J($-3n
zuLc*%cR4+qB)7`IfWLi7a@)k))m-XQl2nJ!6`i^Bkw3U49fSjt&|XIw0?VW5|Mc7c
z@YLVVfB)tG`CG+jISt+rf~vTO`!E0NZ~yr@yI1*C{r&%cs{c3t`h3ct|Nhw{IobSe
z9yX8md0zePU;pj-KmF%_F8^FUZT;(ie*W+O^soP^4*RG7^1uJD|LOnnum9)gzx~(e
zY@*XYbNP8)b+2+B{yDp?WxxH8|NU?O+o#@nc>M4G@^6=j{k)BN=lS0*!O@xL$-JMT
z{l(s%u(I(}Z~y84`al1_|I@$zzoM7Uqq?>EY5$`PiupK{s{dX$iAK&|HvB%n(90gg
zvOo0l|Mq|R@6^k2rgEGq?EA0~e73{#nbrF5b}}uF>}3bJ_}$C@V<pmds}iBsKUd<8
zWnRF_zx}2%q&NS-e4M+N^79(|@BY)A|Mb8A?Qg%Gnb9)axy<T1Z|?JtIcojb#sA*a
z<SkT=@?15&%kJk6|GUqNi<${<?dO4UiIsvsn76D3D(Lhhx*?d*KeFCGyTB;xEXxD)
z`u7*pKYuoSt)_o`e09ZiF}k|`cui1c?AU`<DFuI0Er_SyTFz<z$4WS(-dZcqsy|j^
z&(ZV``Dp%;>HnA#*3Y%vap`aSgX#bE$sh18yrUBX?T@1)ZSz~L=7rHu)$;CB)!xg{
zAFE-dyw$vZE#*I~wg%rJj@R)I@Ag{#7vcH`tH1n5R)2cl-m%FQ_v6@t8RD&#Oc6g;
z0;loT5^&?EY8khtYAN`WY8-y_0#fjgsj`o}T6Mosn&sdB0)8vM{sJ;}$U8da68Uj-
zTzS6L#`+6OxxqL6R%`n&Eal5~^i`?0Kiwlwrb!kS`Dpk2T3CPm3;5{YbM<%G$o^>h
z|07=jq=*_^O@hTAN4M(VFXa^cNj2`o-)ag!{;?YH$hVsCl0R0fHJ28zpw_RY^$&jm
z^-xj$`<u{j{{bBU{6m8i9OS350pnIBv%j#6@6Dg8tn%lIzW+|o_rI_=hV${=cGkO`
z{^3=B$l(8A(f@~xp8fZ$cmIX8`(+2Fp#HQ`1&j1oH3`yX{SVB@xzHc;c*o{PjgCJu
zM1E;Xu2=HyCdD7ew!>}oR+8YyY84{8x85uHxgtR9uZoiVT#>-PuZoiV!fU7}z-fJU
zgZ=Y+_=UHSiC@2ZD#_17wEeq<_DX)Pc#`mZSEKx6rH0G)t@cWOu1Ge@uZoiV!kY-5
zx<CCQeoZqr7!1DpD#_1-Tz`K={I}m;$<GzT3Hntp1wU7V2lcC-BtKT{7i0WZ%knS0
ziQ^|<-sc`ay@_8k5pVeR-z~OR^7HTrd;h8^$<Gx*RD4yG<mZaGC%-C6@^i)QfB)ts
z_?35YFqvVj{P-?@O?5)J`K1UY`EiJY94g<Ql$88jk?arOsy8J+R|KH)RZ)_kD|-K~
zbW6YR9`04zpMMj-WHj#myM^{jejM72{7r8?34X5D`|sZREBU!1*_^&AO7e5XWxspt
zujE%urvsx~fBH@Qn(cI)qkq59Udf*<?Z3A}|K7&@+i$;r@E>k;_f^#TZXegDCc!^u
z-h5^%++Fo%U-|=w%lMV8JUdE^>)FchU5_MxHo_ow{i>HtuRm7{Qsu8|$p!smwGwnf
zZ#4veRxLf8yoK`Z;rz#6LOFL#e_+}4|G-Nq;9<XpCxq<J<AcfItK!T%<)14;#PL;e
zw7=9M;gw$%6>#};MFOtgccECUUwjz{rSS(Zqy0x-1_6d&BP{i&V>T7Hdk!$_rQlDh
zft-4)+4w81kx1#SrtHE$RwHI0-@+EH&M&=$ebPAn(Iv>Qzk^L^_&YeoivKt`AVY68
zVTgXLMzrQzO(`;es^&Yw%~dT0e^O0u;CKW6D_-EwxJsCn{$JS(oV_Hi(mS}d{>tEH
z|Ee<kpZ)x>VSH8S`-kgKs<ic0;pSER@#i>-nd>h<@jpJ(C&2W-qPLMA+RlqH29<)J
z2WGG<zSTTYVn0>`TKiVB`d3<;{=3$u|CQF@H_G|X@-MytJJfc6@CN<^JHGY2PRqgd
zAFtE0TD2S;)vA4s?hmV#@w?W__zSHqxD`|_1%FZv6lcDHEdSygSO-=22fNLGzyMmS
z|88*W$BVeEM#R`#ZI-Xm{b9A=o4o5US-gv63vV?gnEkODjE8yyWq&pHkH3Kv3H}G)
zz<=l*@a36F$&Uvn@ReT`U&$|=3J(lA4(PT1SN2-f77<)uUHuaMi7)r>riS9LII2&8
z(c;$XM^DhNY-A0phOe%EiT>0>`nv`2CHfUd@QHo;OC$ZI<yr#o{JmaZ(a(-OVk5t+
zzM@}o?j3H)`d3D}e#Ng;3U{QhW9b$Bi7#XQozLOletRXq;ygRSGk<BE{!9L|2)Fs}
z?JN2dSD62PF?@-B=~i$2%j|!?3;l|@mky-w&c32Q@t*%)ll*Se{@ZW=ho}FQao;ij
z^BMiQhmWzkw|^P&vVTA9|KAz)*ERh5m+j4K|I{}B!ovO2|5wxV6D;-IcK?6=P_H=Q
z1Xrz`#o&gY2*kQuLfn9-yT$3j<F_!s04H}#e+s~GSCly*Z?_B!0iErZnDh&(ey)HP
z<0io^BE~=<yCsK6V1?b1SBh|ak3g0uBr&MuLGVtuk}<?P-O4xvzkyzEX{!Xc*>fdy
zD?&Wn0x<~J*(uVkfIqw8I=etphsf@^<#p#OqgOq=pl-=Q;`0`0ZZfqIn-&QzZ;=Rb
zP9&a@^CY-*%jlJWY`Z1q1ZD=82gC`fa!WKlnJnFsHv!T#w+w@bbdPR%7>7o}t*c+g
z<m0e(i*97}qZ_X`Bk!SDbIVBTWVCQg>IFF0+>+b#l3<)-*!B>x9YM6|Ol?bM6Cm;*
z$ti3`l_(zHF{<PNft157k1CNc^9jkFnO&Iv4AOuN#4Y3LcA*pHt+J^?uXd#)B?_k#
zE8!W$5co=xo*khMzA{2Lx$cjIHe*CbK$}sB%^K>rk01(nMXe0k*#w#&$=wTf!&{NT
zy+I4-%05hfO21qI@WJ`woc8>N$Ho_NB%h7nSF%PxmVX3vZqT1}5A6tx^riGY`*ol2
z!01oLj1wo~E91a++-CYpwA?1so{M(?EQha*5xglpT`UCP*gUg8lhf0Kl;8=;eXT3L
z)E!^^DaOV?hEHD!THPzUO;Fipd@j-g!fG50>9&7~pVL93N69j@jV>wE8~HwugeN+k
ziU64HvD7k{2~Hpv7;$?<vH41hH@N?O<!8H{rIryhkqh7oXmqnYS_H4}%~U6$#^JfU
zMH<}<OnFNS>S`q$TrDL#mig=N$TO<77BrHm5sswu8-CBS64yp080(1gnem2-Iud>y
zpURR;a#f$A^Qn<*;7GD*G}Fw$xg!bZU8ZR#|Eh~}p_cv`-J94QW<3`JLnS+b&%7C^
z@J$^_K4gS0^hhaxGqn0tqH(gG`kR%WXaY})hL3G=3lOQ+f;yTOf20c;eSIW%R;RKf
zL!@;i*=i)C@wwFMq~l70TjIO?NGRPEGnK0OW<d3+@ZCz{*dxkjLWds-DS!(~Y7RZd
z=-hZ86nbhV-FJnR%;(T^&{T7%yH0n>!W*LK^WX>Pp<NB5sgg^g!a?X$Y3&PHx?S`V
zwV<$OSHq#PrV<}RQy6aHN~osKmV0M~>+OhWdGpFMm1?c!mS_|Pxg(*`$jACz5zU@B
z(px5FFnMErCdEmGzV1k(-3U)TWrACeB>J9)dL?V@k>rCb-7k7Dx^7<V(3$!g0KPy$
zzoi@v+HUgUlhxJb#yXN%v_<X0Cw@fPa40<yWmLEpkAwlm9(e?O_`x-J1d%El<hu`L
z>#ie8Of1T9xSoJE98Twhr{0xxqC&dp%1H7#ozM^E7AH=^h4Qb-+UTTiID&agIVb2l
zWnie}nRO*s_?+H8rIjJAm9T3ky+MVj(M8cw1AF0_@1Wl3ZYNhjjRdmK6|gbjU-8Vd
zRD+n&Mc`kd+;q|PS0c@QjHLKFqPu8B;86)r_e@<?D_TpO9+jAOCkw(8qWeuNjn<LO
zTV}U|&C!zuzqZgFF4m8F1MJTz?-$xmn=OBg))MJ_C4m1Up%gQm25XIw|L2P60{L!T
zbn+FZ02h0Fh33)4AAcl=62`?JU!i{Vk$;a_EovGarhIuv63e@2=3Bo-wvxti>vFtT
zvgn=*seELdzC`F=TOPl9+PW3C1sB;!g&ETOrWDs)uBW2YE^}b?YTi;l5uK(yij}M}
zE)w<%Nw15pq&5t{kBH*!dfrY{$R>{@wg=cJyeo@4{!xGPNgh#*PRZXd3$cswq>{bX
zmAdjs?(6NC!%u}9<4Ce8V?;}1G)APaGgvoV9O*~E>`#pf)t4mc6<X&b$fi(yu&LC`
zh3Q>1v9+Q5dK$tNddwrqra7nep_b8oedIRZLidR!y%N>paI#d=>6~&75#`s1nkJF7
z_q3~P|ERy7Ms)?R>tac-(0hCDs=@g!_{|?gw{uOkP;TNkujIpZ*j*}wo-R7`r*?`l
zv(UbH&)dXG_FL~&&7jMARWqr}V1%h$({>rt(6W0^TN>ha?^R8QChO%LU|uJqR-w8%
zWi}ad|F}qFs;-xJ(&5&4o!(>`^Tu5vN|jaNEsbT^NxjKBK5Ol{0={`T`(3b^3fYf~
zr@Z!cOW8_5C66TXO;s`qxVUL5Uyrw}5u-7+8v0F~<ux-R91(pt`mPVUb0!m8O$`cE
z7vFd#J%k6}_=6~K>Z5cUmVHcO3U5<gLBTZ{$dSwSxgs_Na$<O!YWga;Hq~1WXN)FZ
ztv3-P9noD(;>f9FYV{_QI`V)V0qvqg{PO11L81(A(zB!9QtUZsEpIZ6Z=w{}RbeH$
z%8}%RL6_y1X{VC2#YI$JVc0qnT8U#^lUY0<u{@$|7p*9Eo=R$(BVmUjzv+>%U3@gZ
zw<?Pq23OB)@|C1Iu7vYP5(}@YWt1lb=}(C6B9QeAqpLUB%3<z!E7{UuVaZxftH~SR
z^@!hR*U^<C1*#-%Iuf3Vstls*2T|Zec0MzJBAJY!l9tNFBUH%=<uyIXPaUXBQ43Wp
zORut^ukCrtY<{HUI+98G`bLf*+eUp>SKG!QWn`0?%&Uy-ftT4u$6f*3UkQ_WRiEhD
zD|Y>nWdG276++BpjW~krABwN0)f_~8E>5E(xNos4-`5e{g;}TCM)lRHwl|ZGqUNk~
z%4|fFoT^9E@;5Q#>0Pe(Smh#kKjj#sO!UdgufB(DGF^G?s>Zoa!NK)5lm6wrX*!bZ
z9IQy5jP8{)>k(w<a9v)4r3wY(0Vt^rX1l#zL-*CDrbGADrj~JW*0kFv9?qnKf37IT
z)A+&N1F8)7Ic|w95>J9xS?J+yctXTHa*7jYQ-$2}NZ1x|e|RllwZb_pCisdQ<s-SJ
zj~Xm8!6#}^l<*a&%$0<v^N8+5m#ucug=MSV(1k^2IwYST$t{t+%|#V;M0b1zzw;5?
z;fY56NaihPvp6_Q>@zsNTtxCma^77@BOFAP7a8G^3+xD@<4=Xh*2ODdNo4MVEFMYp
zb*Uv(XA)E$!Ldn-Y;YWcN0Qw~eHMM}I2OI6U%H0#F&;$Y;h*#(tDFq!UeYRGT<3|!
zzQT8VB(c#zck3d<sw*mFyOj~jCSO;{mXU4b(NlC;mAqwMFu;Sv){9JQa;&?U@sA{W
zDyQ`kMOV9?iwZ5B=l1*W>^J(eboCw1$0N#?(V(K+uK+NPgpDdVZCy-W71#RXFz{D6
zZBIEH4~<%+?jgDLBC~y=Gb6*wgDAeKw7BD1!HXQ&Ts#~}b_R`@bYRaF#XFMCz0imy
zUD)d?#3Bzie6+UZ!H!gG&lP3kc1vskB!st}_V+SCm2y_c)efM_2g!}l-uk?k)3VHI
za>N^5zmK;q?{tv9K3CNBoAbvbp({HYmNiXgwvXhLEL589CHs^_Z6<=U3cc%*(DJ2s
zJ!P7O-qpCmIa5ypdAl5D)#9LJ%8qa(cQmrUxkI!q`#We`pDSWRfH&2)jOTOJ8ReKW
zc*$*#uR2bhbfj{pYC8!@E7z_c38mXP=~@_3k0d_s%nWxV*>WOhWp%@WdL(T6Hf|{!
zjpi+qMm>mPEv1!h3DA|99h9cFWn{x>YTQ)b*`K^ueRj~8+Lo0KXQ^$uplz~xYC1|F
zpFfgpY~2!HH~gcvWm7{oYT|J_lB=n0%glye^hg-xiZRK|hDp?*m8#^dvt6`D08%)j
zY};6<GRF@)=x^pS#^DA%k{n@pP)!7K6*R<=MAPBYI^`U-gMOBwZQ(jIm!S=i!(65|
zSPvsHMZHK7bJ@^9Ni4EbJcy!m@>IiSX-ZU4A+I#}tZML7o+2!B6)?*YF;Spd%w>s#
zXE9F_nF^rA#Buj|P-O%%&!Ip(l1aH!iLC)x$^nLFopv1vN5Y2=GR4G|S3#y6N$g|Z
zKLuIL-gzaj#SC=ii1MlN9Ue(Owe#MFp33}=M4uc{Ot36({&*zp22uYA*o2}VSJGlx
zk-zUqa)xh>_}5+Rp4PEXmWsUEKu|uChvNCY{MEi_PS!99NKEN6s@pB)14&(D&L5d9
zIjbEV=5kg$O3Y<V2SUY?^YciY*Iy{zmv1tb?@~9DrsQKVlehXJN}eO3bbBEbR3!nR
zCH+i|FW1b!o)A<gu5R)Do5?-R9%0JiQK67D)Ax6`8Z*H%DoB+hinc+jn38-{peklb
z%vyn}n7#IL09H((s!ARm%k&==IEtBU;T@%XDEJ%`it30uRr0A<6Pm2xjV3gi!H{;E
z&2;o{6rsru-Y7!wR5kJlonkhODzvnOp9+A*Os4S8xDL6e(WPc-9)C2g31U@46F*nP
zpJR!deA8%jGx?@>hLgyC4y21&m-7g$iwUY#Bm2^oWaE?G${NN_F?$`>A4A4WrZ8y}
zO=(anwvQR6@J7d(RPe>KJRxDS(Q*oZsX$uH<gnhTIg`VBlg00dCW3iO>;@oT%+h+^
z#&G1XzO5Er+`;%}CTkkzTN7@p0#h+1R;d704CK`lqIm^xrQ4MyZ#7o5Ev)5+?QJW)
z)vd%0pb2u-FyL*aySicJ+e&wJizJS=(qr9V3VtjSG#m*EY^8~PBrzzb6az9fT<>@+
z^-KfdV$1TGC^!MM8dw!uOFijPD$!A#uC|t{puN_jbmv~2hK-}1t*P;&x*}`GgJ@H2
zFp;P(<$^hq^Et1nmIpICDTP_PhMGpVB@C+pfw7e~cPsOjve8NJ$5|1LBen^K)i}G`
z>gv^^6J6a}yx#aEpAbby+Sh}kCoQ{Xw~*b6H)5-)YZga<Bg&>xd_q?>TpveLX8z``
ztg41BS60oIot0J9I=XRHwT^xiN~>Mei-jlQK@hL7<a0M;D0=Q@sf1<RB68i7z@`Nu
z`Dc(b&E8f~h?&yn2yW+u!D<zKIK%2~7qDVe5atGA#b&yo8;BK~>4H9z+x_Wk8Fe_7
z<e&wv<w&w=PJYvAIt(3~>4I)J0*?fp)9@79bT!@>Wcr{ROz}2N4?+Vbe5+mG=$Wgu
zavKg*n@jyez0LJ6Stoj<?;EG=k;L6ttK*i~Wx%bNGV(NVD@T&;qTVt`&y`$<q6xFr
za2g*;Ha(c~nIl5I&8gOBOt?~NH$2!!l&y30Q@Wo<Vo{r2eO~lXgyAg!D>l12h(?=T
z9Ymweo*hJ?We%X{iem9~esG?dPUuD=(j&>fq0eShyM9X`6<g)ZHd{7|f)gU^NMbaN
zQiPaRwaSrhR<+6jZdQ#Al{nMvK9YDr<*U}6b`#>NMG6U1ki-#0U(yBLxN!PNDBZx-
zt%>K#$`V}F$Z%>(OVqgMIubS@?!pYZoF_!_;A}Un3{!<W8sV`TP#GJZ?Y3~gno=9J
zfXdi#waaO4xSEMqX@Y6BxQYC1sp0}?WC1ynd{Do=HO(7pQ6Q{FK4u%1E|nvSE-wuN
zwK!G|BDCUIY8tILR+8E`P&6jAR^tZO#!~C3#<4W4^Vq3|Cz^lEY&kTujj5(lpP;@P
zSz1py+l}+%m{J>HX-qkqT3ZZpsO=SFOf}ARx+O5|xuO{2plQ4R&PSq7hZH%WnJX#z
zoAC9B6Y_|n|2-cXz3&<hp3u=XjVRN=gguC2F{gXF0i!vRZ2W4|(bO`h&CzHX9drcQ
zc04lnh!&c3)PKoh^h=+6M~#lF!Jd$u8tIj8WUfCFIzb{K8)-*3;4wDRDg88XBsTC$
zw?LZMNVjwY9b-M+(hYQsDf85kTr1Ut4?7~KTDBf`&XLd*2g$zG);&me`KlX`91~=$
z!CG!zhIB_s_89d?{dH5DdARGQsYL(vRK$Q`OhB#%Zs{YTbmy_lQ+-5tBKy*C(S3cX
z>Ck;$s=A~40IxhDih%pY5AHXt<X7z@w=TmQ9E=IjbtGYMbs5co&#dRy)=_$0Ml*9^
zU4}Cg_E=Bc^bswp<*cCk`naX@0DX^u?~dfO`dmp&b62ydz24O<s;|o&544Oa^VZXV
z%a|Ztt)u#S+TK88tjqqs&=~8ozB_;i>$1LCye3FjW64{Wu{{c7NL!m!!_SfM=n)E1
zkgX$#4p%)G1=-Uv-AIpNy`;C`h++_Ff8WjE6d4o183WbTK+T+TwoJAW>qSj-MC`KB
zW6!ZB3w_`MZK=;e&Kv<Kkp^_;i1H_QDYUJ&<MkX#HXWO)L5zCV1Us(@9oFvFY%P7)
zjm_JdOmud5YnbSP0)DO_TM8X2FjxaSV@>w>K!r9_OXRCPqHGEs+Ki^={dbNq4z8AX
zu?D=xnzAxC05;Z^8b*gUS^1%Wt;xuT0M=R<`Ojevuhe1d7#ug7Ec9Ww#9jj|#*`tg
zjXZC*w9ZFpzb3<bp#1~~YuH5Ah8~Ra3#;To6fbe)gRk;yL$mKJ7MbrPP&R?aK4Xj@
zWW#u0lR~XwOCCW!HB{uqh_#DsvDWg;1G42v*sMUdd?dFNO0A_IyJ1M1P+KjMCO=oi
z77_6f)~X(gPHXXJPJJz1*+&wyRphjp=s3Z++RZI$t*Bufq3zn+98IilJ(P1|qPW@|
zrx5>&*Dl!Ak=*90>&K_HDhqiIcETzfnWLCh*T7M4RaP@cIuq`y#i{RkNnaW#!y}<>
zPIgsxHRNnZl8vMDs^t}Fo9h<&xB;|SO^X>ki&dG-foC!0mTNQBqM%xhWX(sC55C{=
z5#)$ai&aMROtqLP>5e1@AQemwT?4AsW;`LAMK9LZVxB0*DvKH9i&a_76U8W`Rtqf5
z5s-ec;pwo7$&4@Ll(TUZWgQwbno`N|o_4)1CbU-r_;Ms{HLKjxjDOR4S<EXI@?(N_
zwQwO>m3h2SiOQeX$lq)bQZ*ngr<`6Nd{vfEu698#r<l#45S4JR0dhGKE)I_<mU30o
zsKkn~9Y`1xzN>+Ru}sp}0toY5Nw$qbtVL}%#wd#%2clJ3<Pp62ToD@)$(c>8I1M0+
z3Fg%T$YM(F*8s9SR<=5gf-7lU<3_b2UAyKjv8~{TJ(Aq3@YNnsHiSMa@@%irKu1D5
z;YK<FE;5fO#uPQsW<{Ru73aZX8X%{?A|rh*4io}^wZys<S=b475o)Ueb}8$tQn*Wt
z9Nr5hR~Dta%9M(*;np_+v>L8|3-|Ja$f=es#SgL(oTp_{iiwq#9^v566<Pi!>9Mle
z(0D~wdg5cspcFmVjZ;gkOOZ31V0aVSs*$AFihS8tX}J-;aU{28+0%yNE3&8!<)=)F
zjoT(myw!6>(M9>Q12a=(VJBv$q=lW38D(E=c@btsx;h~<MMgKUnIfAzAu%P*=|seo
zl32-hATb4NnybB2&PQI&S!6hKW4N{~XB%;<UxH^fs2rB^Pc_IM*2Z)WGKjThIRl1S
zdrL)thFM$gZ8G*QapN`cF-w^vo2^^Qb_qy0qKV+VsZ-9D<GVSMoV5knnoQ}qC|+C0
zkRyp9%9JM8$J(-$NsYS_4A$)YStfAYg+Eu6-F140r#tS{Z<#HDd-s*Zw=FK_S48ta
zNNysLEoV2#m$l{Wh6rUT`%NQ-?Aq^r)&<BMLAJel_i0Q6G+0}%ZZDrwLam#Z9HBHg
zSzDI?WDQWu+ETuNT9)8n?WWgUyQ^y?##~!&ZZcY~oyIeHDA$%o1`6|$P&yXn+VXP)
zgE^AyTVuB6=ML)NBgl4R2YJ@k9^jq+H%c+F@@#v*qmf_RJA<k3_&TG}*AA{`DH&%2
z^s)rnYCdl%yD@Y2<<*9r<s+f=so=7)fe5VxXC1-qg$r4IM0ZwQPHhj(wv_MlNLoBN
zn~mlBkx;tBT!L>k05wNK%W>2@f*hOOQZ^b2ak*#wOano)1n6q~Yq{)f_vo3_sXILj
zOZ)ko(vlw0`<&>V9N6x3FU@g}KWASzGw;&L%+8UpJ1~RGWs8HgSuSHd-o&$9#yDu3
zm3dAZSeqq$R|9La99tZu%_*l<d7(B(K+6DYmdo}AShIxrI*DQHT^+B#dRGR8@g2Cu
z<#JgAZCnC#HQ<lS<+2Wl<a0$if<}+Aw=c40xjfb&YnIFY23fQG^;iR~SuT$?JHe4;
z+dbBUEOPdfBMC1A(3&I2#^HTT_}I<gOC2_vllAvg#<boXHkaUHjs0+W8rQL<9%9Yx
z8T!y=HiOGuuHfYcZf1GWgVBecj_kc|Av+fK-!gfz12ywpQ8tZ26l|;krCBE18!fh!
z2$$@4@gSNGaN{yLwnGsvlllfYeI)Ebl<;V5r@uOa1C;qlC_!hM{X+LC@m34#;Rz7~
zMERLq-Pj=?38g#Jw$!VbiX+Km0{N_uDBA9&+){k-Ck1xQ;-VBYm`?3}O|s`oVwN+p
z_7WDX!#KWds1{l-QCvN^TuvFsLB~2>mM-g#1^baux^tFZ>y8b4Bs{a{ly&t4m1bSz
zL#<hQt@{mrIOS{>wPr$BcMvkmS~fLUBTX%h7*JC~gEb;_buZ{bLAy?V^kp?4I_YfH
zLnob$Px6${wrXiP-yH0>ul0Q*Go9}0BZ<xz%^aj@M?}-1`UK<3?C;CUzvK_1>qSkY
z`>dqp+riZ=D{A|r{nl2yv2d4=V40ZyNG9d0v5z3zxu?RVlmZ<P&5>j)Vel>?!Fn8U
z*AjZ9a|m9`HAEEVa@s~YE>}xCO1zBJj?2^x+Hsi%6xy+t-L#%UJsuIoLuOgF0#$n;
zZ$cLD1K`b-uoi&cToFqQ?9CPBXLRv5S3>hRFs_LCs^Rneh_obX&3>2nQ8hcBHxfq_
zo!1+#mA(rs-vQKIQQ$>;c!olhoo~0JLdSRfOIMW5g~q$0{1z+O7mLiWj`Qk@n7^wa
zuOO!{G~^Z0r%;hsl3nOAJl7Jy*Y**aS{uBGK-WLW=#*(<W_BvC6M6t@u7u?RpyrCW
zuIWH(u52QR*Cmsy*F}-Rg?_v#K8RH9;Bc-iTU#;ZX>xVqWv^%=@T_#_Bp$@rI6rj)
zajztMU<_?&u;C!Oq8Sge97iJSJFe}IsH;!TJ4kF$$3cEY++%bwHCINbcD|ObPVJoC
zre5uw-1fe_ojuJ1RL6mTMf9STDAMy*a>^T*`bWf!r$yDdDENrd&Dpt2xFWP;z;vzz
zHQfQ>Tv?0{5YCnGX#=YHh>CjIvRk5G>jcq<tmMx|*35^s>{p?9`@~uK2~oTUSy;Vw
zUV}`mBZ{7zK6L;&SCpH}h2&gGw%=KcmUUt!%EszkNnH^%7oCf%kTK^YmZG`ZAG~05
zit%zSotjT?GY7)`$C1n^=bX*#psCL@J82ZJE%_<uk*fo!xgs9C=-*P07whyj!y1Rp
zE6Wb79L7=yRt_c4UcK2VPPI=2$Cc3mV?DeU8>BT?lsz!kgH3gS4e!d>iJ<-Xh=yu<
z_A@UtdZU<q-0GCfxwf-cY0tIPr9#{v5uJ)7R&SwVu0U<&GR<RF@2O6O)bBmjsiiBm
zcVfgsR`O>v1oWVn99$f=j(}H?N3Gs#6w@y1m5<Vzny)!pZ45ot=4;FWZwOJG4|@;2
zX+>R3z4=;iJ@saqZ#|W!DGsjp)SAYjt9P`f<-x0i_P80HvYYU$m$2gUQFpUgTRkAP
za!Jdsry>=izxPz6YjbewFbYKmDY`K3cwgHNM9&pvYpH&h=OMF$y!psvob^<sD=#m4
zUr}W9>ZwSVY5Ro8>B^X=(4))L$JC?CDAL2F4W_3ST}y4J8dY|h-ch3p0qDSet_VE?
z-sg(g2YM>o8wk*QYFb4C^qX`_VE{b<K2ON9DbJU!FTSVh6|TR7_qw8dSiHY0%7LWn
z6~4dsRK08H@u_*24t*W0>XDuDIBHi3HTp=kyApoTN2=YWW8X-%8`0?xGS;n5egnO$
z@PQ8e=ZJ2x=Av!Vf+IC^Mi2Cnnpq(P{lb5)fWd?JxgtD&eMFu3XAUbbSB{8b<)L7p
zl2_FLpr5?5973w(C3}CQN?x+}N2=tE7&wx6hed-(jl7D6ky?4llo+X%mre<Z^0~6?
z16o<Z1s$Bv714#k3YlAd80_!F7xWQod8Va5QY$Mi;E1A=1P1hh#+_m?KO!2JT|ZW~
zt_@?P#+{~zr^Y?-f_RigiOnB0&lTl-q{5v#9gI}CQ#_9y7Rf8i4j7Y548cu2dsp#X
zYS0<olEN9Dqtg)qsP;{<mladvW(+_doK5G@);?03&WyS1Gqvdq|7oA8OQ#I`S+WNs
z_x4$GeiLleXDU+#3mg&io1WGlmAVc{Gu5fW2abs8%;Uh!!|T*>U~+h!3eM{@Pp?xN
zf2JB%*uW9-Vr1CQ)UYVinaWhK{|=e#6=gS5ohlTd&s3)u<&@8ge(IZ^sZDuI>e89u
zr6b}Ml#HqCGnMJo@nD8Bokh)$9GX7pnacFW5JcvY+rzQd8VA{-gTTy#?9f4A<~eq3
zZNf7(up$TgTnvWypW1e~o*n8o0|lNdiC!yKpwHB~!!?jpxr!g?GgWTf1oVl%9j2kB
zz8!fGn5k|RVbEu)+hOm}Qs*knpiiEYjXUdh7{yp03NYxCSmZ0C^*kXf$e>S7$U~<E
z=&Y|O+upec4_OJpihU)yl2T18)}YT+(-~{fSBX*{-B#-0p;N$09jr)#zETG(l%TIv
z!R+cGim@bcqOVlJL=*ItN_glvu~G+*p*?S<7FOgzU!jE+cyI)~w>)F4ns4phUsj%k
zhmHmd)vKU^zVa}vxPiV>^9~5v`-(&EklDXdr4E_>D^=>KdUmSRQQuDGL6<OtzEG$`
z&ft{_b?5-Glri-^Ktw?1M^w~>nbXN}0dD;($cKmCCDP#Y=`55gX%G8KjoM}4uhgg+
zG|<=4mEAQ^9ZtKn_cGe<31m8=8G?LpYRc|<a2`z+TF_T2&n}1UO7+?G!7tQj*O_1e
zs=6{B?<|upn}5ZV<DW63edW(nX?77yc1x{!!v%UAx;`aY=$0x|F$3LFW%k%hpOD2G
z?lRmhb!M00Zq(w-w^W&ZQpEaK=s~wsp<Q;pr4H?~>kS>M=!2f;+#{pR`;*abab)c>
z*)0{S;tRT^LhY}~ZavC5rk;b4y>6*vd#A`4n%eGhqi|*M%^Uhv5eMB;zbfdUTk2Q^
z9dsKSshs<kI<_~8_sO#2E%j?gA#}^*Yp;n;=$0y1kqO;W>vmcDhSu$}3oNy61SdSm
zSRZNG;|#iz9B?Y#F4G=Dh$~7LfraK({6V)=yox~RmWnq+5W1z_ZTlTzDqeyRj^GYP
zK?vPa^C}9VTdLmn`u{C;Z<GJuQuVex6_`hfJ;hS<5{K|~OXb_-{I@**DmI~$GwF(Q
z20Vvry1%hhzY0+3mM7aLli$*(toVZNC5mZmdumq27j#d}N`S!;#7Eh58{jC>CNR|z
z#XE0PjinxKx)AWxqY6#vo@%r~XxHJ7xe}(zQ;%kRLig08O;-YbizB%rx~I>%q1Zk3
zY}2v9^Q78j{d=BNBjDgcHbcU;<f&I%|9TWJDvt!7Dzv=^03SKM+A(}&KXm|b<qy|&
zfTKm5f`>aOlq;jf^eQ(U96WVx%Oazz@-TR)+NP5Pw>nqEgVU?5@P_VrFm12rpWCRA
zF`bs}%k%H4ac>Yq_t3T(!|+^5%x;yv53|%2<&31dt#bT(s@wWH{vCZ=bpr4_t=6m*
z>#fT3@99w{;lLBJ7_Y)3y7QB4J^jbkDaK2z(*2&^<BWPZ5(Xh-f1|0Z?E0OWy2`fS
zCH?i)DAQvZ_dB(821E2+qm&J$lCDcCaHpTR%Cg_7s1*&-cPeVdL-dWJj(CWCR;<qq
zi0C`dx{8SCJ6+CIHvu~}dKD6@?@;MgCxD$QU6BzTgyKh}6TnUto*V@sV~Fev8~v;}
zhrUxkSDErV_4B>6eGt)g-52as&xAnq9SXYYwqU1%u3bloohrKOx?rb<t~wL!)X)l*
z=o<|kSJ@9D)(ZCpd*-{+eZig#Sh$d#Dm(7d<4LKr6*AFx>fS1gf2Z<QxI^El+6ZoV
z5Ya2$8SK=xl|#TzMO$?U*r{l1NoPeqCEH3(TXbQtQ`IU;qF+?=6#&WWJ2h>=KG>;e
z6(!Mks@V*a=sSJUB=C7cc1Nqwi6e<_79Bix9&$^18BTgqx+%2uD0zle_`@jZ+LCt$
zqok@;0K_P%YKt*XBN$1qB&O;}=$28WOG|B~ngwg~ge+cxA}L0pn2o0|xo{jAC0)rG
zNAX-4LtFeLR%MxLoine3D@Mr!Zpov^GfHY~1yhWY$Ja8{#gTo=bHfqQDPh1yN!45O
zK46qoy*F-R6x43%>Sk))(%(r+y<75pF-q#)($$01y``(`p?Z^PDI_e+PLXBV)PdB_
zg#*SYshyeCCuH&do0`wlacLTC`kNJVF(5+zh=dm!CDnQcUL47cat<U_wt^~-h_36f
zFiPs|k~agRq|VOZi&4<nrD!r!V;6Dyjgo3xK^UW?+Ac+%NUg2Vj8XP)o3M;KQDGMx
z5zU92`UtZ5Q0$wii~+)GD=cFa?k4xnv&6Vt)<?h*;gru9wt_AOab263i&5j>IajsP
zvAi)DP>62@Qw(5Kdz&6w>6--#W(0(4E8Jp$pxWEi)p+}R=h<PP8TQVj!!uAHTY(t^
zX7#POj1lzfS28I(b+YmP++w!e8DriX3^eZEQ&k4N!}cFnZ||);gF&3*-a{P;jd~>P
z2q318gnbLZ)RDwR=aF=3Wp5_)oA(6+%jHON8fHvzPmsvKP}&(|F^DYPim@0M8nt)R
zV;4ivXI{AxKBBB-On8*e&#T7gv{^Mir_rkM`E4{!_(6JwkAzapSy309Im=jzQStKb
zUDWW7bzao&W})X9U|`1Y8%{AW^tX#8XnYO=+tbz`oD{aFsXsVQY@zuEyh7X4W*-fY
z<94aoIKFIw@{XWWE1we+cqDX|W6-lbz4(K((noSj=U@6J0YGiXq9352HoT-~J%E1N
z3a}V}pSB__M&O^en;LD5Fh9y?0Cn0KPB8#FZG}{f3v=3vrx>7|jwBm`6>AIKH`=%*
zzWp{B(bO0RLz>y{p!<q(JfhoweYS1T|EXp|OKzWPYBHdq?U+OV_K|JPJEEZxPDT{g
z`@p-feW+z%QQL=_j{RjT<YELWYJ1lp7i*(u!;3-6Q$OH$*xppjZtv0}AMitLg-Q&3
zG@DR~L0+O$&aOBur=2|jIc=|cZY=8URnPT&kCg|<pK}sWYc72Z;OR<A{^oRExuA~V
ze()Y9`RIjd)5i_^Xe*!i==GNPQo~pHTv1j*Yh}R02-oCR#_)mra+|(fut`S(zUGKp
z)XL`uHgcQibJ0hZ9{D4=vzCd&pDT(1$inXZma^qA*S1+cHB7p#)Z(MZ32<K!-ne+7
zoms*MY(QI>xdDD?-w1~RbZ9HW;TgEiw?Z5Se)Vlr^NJ#}so|rD1ed!Hx)VFq^kibA
zYl}%88aj%~hFV^6<lf35J}&xb3vM?+7VR4*F}R@ECIdMxF}BHlHoz2Z#Yqe<KenPG
z1_}4J;vz<Oy4xw;<MI}M?uhQ!m{Af(FmEwiLBA<TVsI6-t?3NVQF11$7{t*QdTzvh
z(zdFm(Q(95JXaEnuc~#lo>jGu=2Oz~G0H9Rg$}ISopBNa5YZ9vR5-l0(vlDE)wV(<
zM(}>^xB+^Q-2N&yVvtpGuQYo}Jh_#Pe2|@T1F3t)h(fl4=2N7^07A4CDRCrs*)CVR
zWU<?sm3#!uXbW98xCY$>N(>N2d%2oM5iU<3$^c-rm#gj02&Jn@@41E08)MKvd#4KB
zw$k(+K}B~2Z>{K{3}3FH_gXnsXtpKG7hb%*a;Lb+qP=AKf-Kr=s^Q70Vofz2f81-T
zX;d5O%13~YwqSOHYx^U?H^9~Yk!0H|hB(x;F(8@La2IYccTb3-GqQz&3vHq0Mxcd`
zfb9gV(2?8@K35cPD(z(`fVPs8#{gs-k4;~int=dzucn5sc3VyJu$kYMt%QGQD?j;>
z#DKyqov6Q+$oV6=qe)l!0RFNwefa<)vlAfq86MD}y`)708MFmz8{mTWN+<aM`ty-c
zx<<p?>IvF!%4~*YbSpdg08w-#>=i*)8V|~*`z>X&9LVOTbU)}RD;q@74ot`sk~_L7
zD?9K+d&<ZLEVQRnx*vj&a3g7kjwqiII_gOBA@i29*XT^8G(VE)>-#B_F?`RZmQb2A
zE$A64bIO38sLUxw%>iO)E35gK=*=k;8W_=@GNUhwXipi@bLAk@iUvZo=TzgUR;4;0
z0Eo6wbR!@{dx|4y02tbHs4a_8r47wgZzV$?&=GGSb*FsSm+WKUjeE*KCS(21RObT}
z(4Oi39%Q|Lj%Xsdo$cy9igR|&9Ex*xHI3qYlbsLN{T6I)e7=i4Wn}Z+?1_=hm$hg5
zypQA#FkRk9u&Bb<zfh7>M)X2S&iuO9>4V(bW1#|PQAbdLBq<*ta<>q01GLYcpx~bo
zV4ppUI)VZm>C+xSefHQIKPpg3%EuyFX$ulJ*oOB=(;Hy(9$RgF&VIwy4rjmN?-)7!
z2_H8W%1)We2Y{X}SlhVT=#+0yo-4T1J>;}TsT~QOL$@h0`2cXfFMw?<VzBp+$9kdL
z#!~0dZA0$r6}oN6VZCBIcy{J59}8_K=-QFQh!&;$bq_hKFGT2+)5gW7*vff6fCKFz
zM>S+Yd&t~|ENBm1PYs|yd&uC%oH~+x5c+S(ZH-y>kx)8|UFppSff74$XoHa0J!Fy-
zaj}Q|)r4g{d&o);6ww|s(g6|en*@D;AKC)44bVgT8hH<r7@y2^iyGM~$3^8%9~jVE
zu(n}9S@w`cP9lmUi4j_y7nK?P2%@X9w+)RsUI(?IGKc)r#({C9P5wEL>>+!c^U79o
z^kF@hsSI*(LPwHKqcw-z(t#4%T^2eZq34Kb8BeH^s1JyUHlVlxJZN`W=@%iiyXb-j
zXT9BJq~B)K8t3r11&|vYFn7lsCo9YD{yre~D<w@I;C-%y*+*q|d8#dsn%#Kt)tFt5
zYQR6c%TW#XXA2cK!2awmSo`3hzPs%8ILq%YbDcCeyW^)OQO;Hl^=Cv}-cE?!uzR*7
z7y1CGvxSKpcr$iSFLk&(K5uWR8|XeIIv@B=w(xEP9M6&Dg9(T{qIj~G`*&sl4A1Uz
zQF~z#$SlA9oZa6OxpQXhX>sEe+Fc&%2n5|-COEVlJF#w`O`S|oTdB>DBo<4S?j*`f
zjpJ;0d8w0$WM|Uy5fQdqsIw7axJN=M=1gvC@>}g*-tnR5y4=)0ZYf(u&vjYgpm07C
zO0mH-8QkHJ+)eg2PRrf&H4^B&mA-rs3;pawiVa`)?^y!{*JLZ>s6CSG89J_s!)M^{
z-OVZ8p6Tm@fM>V#N#jG_P4=~u(0n%;*uZjjlaYOqIa?Xd2e_OqjM)H#v)jt;9SF{D
zvZw=qa|GECCqU&zA3$(65VI#l7PYb|XHc@J9lhAnpeD9|D-ZfJZgRXWB-tQ+-fr?r
zJDRY`D-9-RH`&vh+^xH%MI9iWtyJiP`;QISY;Zwx$~4U_%8}$=%vH+~(e^%7WO8#=
zvomA*0G_j(OzuGEJXe%IS=7mfE8~%c&6Uz_`nY#!%cdyx0d?0AWmBljhLO!()mDo1
zv3r!55^lA3lVcm~&2DmRlZA3OIkw4Exf_1%famO{tg8cf&Q5sR0GzX%T-#uCb}MRn
zFrILrJt12BC?698(mnxrW>;C+ft}fcp^XjTX;*o?LC)-&X7{}h-O6r0xG~*THZ`}Z
zN0JV2?p}{5pNnRz>G9t2sUAU&8_h<7^Cv_x1{vo&bX%3v8&1Dn(-epHZz~1*Gwv<*
zzG$-%n3tWI%m;{<U1dK5c=<>u-HENTmnZk}yQYhKa%sN>1e@IK@0u3$yabG=jBjO<
zR`(;~&oPVX;Xaa>#5B2QLDSXzbZ3c3s9lE|#ur)#rRaUvQ=??jXehaxntT?Zo?E!B
zSvn22tPl#WHgy06SDQM3lB@DlPv9mybCX|5^egS+Sw2dxRyB;0t2G-2`Lb(O)2O{#
z)inN3<tv|of!V@*O|UJ`t|gz0bF&sb_#Ob2(0qdG*#dXXvTg~>dx90(Wvl<F!m_g!
zG-26l1w{yo>zR?Y`;^s6>=k9J_b9`%HEkUBimPc-*KI+#=7qeR@*4S*yYfny#S^&8
zF0Q6gjzwPT3D{*9SKFZ-OP-}CSeIQ)Ejxp>q;sD1eJi#3WPDqAuX*QWm!-#``bwI?
z&jcZNM3bLHkJApGAnkTyyC$%fl5Xo+f&cE3e(RaQmXdDkBe`$Cq}zJJ3A9UC)U(F#
zK@!gdzm%EnhEwJUvf+BiH`FR8K&3H%CdkDtVAxEAO6lqvTCAkYdVap-UAk(d7Apz$
zKB8EdJv)cWQd066yTcZ0YbLIxG;M(iY$;7`jhNh~mQY%yWlMvpMaw={6hmtKAcj-b
z^1P)S9H+Tb)drXNTWGGC0G3QqekC#e`k({BQp#7ISY9Q~)Cs%KM|4Z}oA0e&g;nWF
zPd>pryKq;t676_I*=i`WBguBJGCKmcML6c2r^c7&+Y@avfy#J7vnEKHBgmG|NA26y
zY<S4n9TElOf@V!1F1}6u+H@n$=h+HfN%Q$g?#|#lJ=8}OeZfOLuW{l#&FNEKcjD5X
zo>(-V9EBl@{-%R^VjB5gYW!MHzNeawCE;P>oTUXi#`jd~m2pZ*1CDV4wq}b`Hr(<h
zjvP^A1k%7^c3w&RqDR+;`r7H5=&L8e7%m{zBtyiJu*r}@;z;7T<NiDQNxGjS%FYhf
zU{}kbAYD+ciOui3so^`a$9Gf1gO}fEc=GC-8lNn}rnV<<zGYO+Bxi^3s>T<eP1S=I
zUB(!m_bm1)L)h|MN%W?ue@1@_{WE%#mhS}W;=ANyFaLn=^ioftF78{M3zg-*H8Y{s
zTv^L!<Xw5Lh`oiQ?vZ5U@!`4eY&^cqBgoe8$Lp@_Pm}m8S8nr3G8q>l>`0=AQnx@}
zjwJVoeusP{bP&J6k<dZ>3P%zhgr>(6zx7<vU3_l$2j|!6x1OZ?aZkVXBqfmhQmaS5
zd2j+h2x7wX+<YX_`E^U76WphoX)%(iR)`*QB{iR*X595f69MTin;B4y3xzd<f#-1_
z>Px3D>64!Ls6G-(w=XiHadEk4K*huj=HAuJU|PF6H<;C~hU2N(C~VGtbC^$%G%m!}
z1WDtb<~TqaciH2Cqj7JEZks@7T&d3|&>0tuYvNvXmvJ3Az^+6OvRllqqXY%gI+Eyb
z)nkqR7L5SXO7}Fsd+0!y^^GUiUFsTdt-I{+jv90kYW`2Z{SVJswB=Lv^D}GnQ}?5^
ziuvfDv(W$e-~aZ%{Z@Y~pa0^2|CfJzfQETct^M|Izd@DmOR2g^d*RAiS@H9D&&1+`
z8S<7dvd;K4Jab1>Yrh!^qQ-Y;;?ONOQ-Ju1o|}2IL=MdO1sTDti{2LE29sN)LFhv&
z3d3Sp0ueWW!7o#A=b({1mPgbw!bj+>-uD-8&dXqt><kLH&G3&m;Mg;|_H`bVlB{n<
z_ed2qqg;`9^SFpIp+s!HsDyjRn3s6E`@oyfbvK(HpXy&nCCBtltD$396kx`&ipKnW
z8soEiM&GTj&p)ixPy2tih)(zZZV|=Yd@mv-UyCTZ^0kW6?EYRwRAU)YVj;cM&)+NQ
z%*yvl`u#$JRQqco!IS(hq;!?Dn(ktXFY<daCH3srVw!)yl(5>KTuZT(l0xQtDaE7y
zZYjl5{a#AxC&xYV9Vf$55*hxxloEWSrIax_T1&!NXelK$?_Ej1TScju`)d}2W{zd_
zIq!Ye(P#D4b#|f8Kjx^_)?Zsj@KpMxcy#o!P^Mm^aHj{BOE=HGnr+%GmriWsR}fRf
zPVYwH?7_m7I`K1}43DsMx}_67m^|Im0}majUtFm-ddr-C9)uDWK_hC?EsgwuF1xrH
z0XMtY83X?OTuJmPywffk#*3;x#aKs>*t_@_;kiEowhceOPfvN|Qn-S6KI+%faKOrN
zi;djTy>V|DkBc!RbQ_eqCrcxV0bCr7ZcJ-xc#jx37pWp<n~PKt%g&)x4Cua#PZ4mx
zzl@4xNN^!SA?$UrDZ=UNmLH|x6QreA+da@f4z)H$s*76NIbjM7imB_CKJ74u-2~Sr
zV!|O^BteA>2fE8GT>ZCWKX6fDa~ANWyp0?f9JnW$4P5+*n-k<h>BfP>#he(CC!ZmT
zI+5rUU#Yvu<>A75lI+7*a<A+tVDdt0?F$=#+#xQK?A;hv+VeY%I2Xio2k^i}!N_6H
zlU<Qi1}=6*QW^N=R@|Qxqv#TM9vDTJh$8U>b+Ws=ED_GQet8n(1nfzYcpw6?(!`Uv
zIVY|(9XLn3;G7(@U(L8LZ-TD`eZQ(R3h_?AejRT$KWHMaeCdPU94J?Q)OZ?v@loT8
z@Rc8R_$pk~i<^vkN5WF%tSHJvLfCx8$$WdPr8LF1^HKx>+s<1-qikm><wqS3o-4S2
z=j^xgtImu`N5arIQ<-1&jqh_&B9fNLrD!*2#RCgFeX6A}dHEF|NsDJh8%Gc$NrS%P
zRP$Bxil*Xub5R;r(pOzcSkV!C=`%mzBM6H~QOy;vphI3*!)@qut9#*D^vO3|@jd$7
zY6l0U&-{!lUQC~^w)-u`%vUmqIsAu}_|{YAL#{-@9#PBR+(k594Ttucre?$a<4J~i
z$;IMxn0YoolBmREIWSJsW6z(LI-bYFnJ4c`An}ppGf`4AKl4g@w<DpQP*YP3C`WR?
z<vG=V4vjNSrz45(Pc@D@n@T5DuQT4~RNI^@lQps8()XF4{E@^`h`*C!*5^>e77Jmh
zU3B6c8Z@3&aVplxgm49guAv#{P|Ik>IVhb9UC(s7p2zoE02cbp^Lr(5-lvX!MAv^L
zly2W;(-WcZQ?B$%w!<qb`J-3}O--X8XM4{Sw?wP8<kHAfYrGkqS}#$7Pj1sHga<C#
z#2PsuIifsBqO0G(iJn$U(Wi{Ctd$Z+=azlSgM6*%KoKZbt__bQ8$k<RM#UNzk3JM{
zS-G6_v2!f3@%q?mIb5(~t6jXSD&2?q$UC#jg{q7F@JMdMd3vl6bNDb-3WfK0(jV5F
z8r5|uKIOZHMxM8h<gWi=dhYs^R;r51HMA$GVTH`Z#c5bc|LWp2tni{7$$9Tjh;ILv
zTE<P9RE0-y7s+^?9d^4Pw_3HPw^O8qH7@V3fB~ZGM&4W1imro^umThCAuG9(qrk^d
z-%xm>Bdla7@R7){BZ=<zgn1m%yn<{Sr8hcl<1roSHb0X4y^eGf)K+qodDuLnJIeH$
z*M@_1gnF*zK|W=k+v+Vvj7lZfvWum#f)MeMHgyF>;!qS;a3)T)(@_|pQGDPBs=<}y
zqpGK<M9~vgNSAyRHJv(f6t#^`9C<}nTfZeXPn-b`f#DUz8Z1&74W-z(nno*jY59Qu
zc+YFH+E9UT96nca-)ff*CndLcsc=#f97+1%<}GFCQ!k42@Q7}Qlk>0wt8y_O9!YdJ
zE8MQilU~7UxwsB1crNc!;Bw=b8b&8ZAmI~|crY6abY)+zA2O!9K%W)XGZ*Ufsg0u|
zu+Iw8%?10cpy9mhlLs>AJrC9OqUz2}Nzp^#=Ac6>9B-$b&%KJVPdydI*yp<#&}x0C
z5=t$BpS6GVl|Y@9i~>i(noK6WBVu-MK7mtaZac@m1b!YtOq@R5&cUyXwXAkjU2keU
zR9(*itRsj8*7CuqwyvA%+D|c0%oS2Y?^3YgE%HQyR<Nhu^|AJJ6ZJ~*_M+$s9Ok<8
zDO2G>f>vlDy^FW3LLKQnKh{2Of#uc*JuQ^(su47_207((McFLMux&LP%CK#{3Y1~X
ztL)19cs?SEcNqyzTJHk$=4u7q*z_Gk@99l$tlHNtW*g|nCN14jjx9^kaecBqu$?aO
zXyvnWVMlA{K2g}wihI<B9<3cr%|}G>jAdzT91&Y8ZLs4mBx!|L)!TXp7kiNlOIl;Q
z^0w42`n4@eF~0PP)x^eold~E4ybC2-FTmb~5k2MT?f803bT_$%>)>?Q@?2a)8MrW^
z6@B4NY8-vyKti7o-32RL=#j)*?z%s@1?Fks%LEcy2L`DN6I!pz^d=P!Kd`r!PegIP
zuJjR_v%OaLKvA~Ds~kymRW>%^B;FDOUI{tzrdzQZVJS!Q)`}G-yBV|QBcXKrq7OgF
z{huph-NNqgP1ZDVH{N7S4{j61S6D|p7Vm!@I5aO+VI`Eut3LgKPONE3V+kHXwi@vg
zE}FuMLFqM1cd=Dj(gW31_0>Y^eI)7`%1d`M6^?(evaVqe_oN%FVP$(2H%Y}5_o{Ch
zbKS*1cqGwZncxErS1s=)j_5r3y^KM{Ro(I7@)QAKCGO0tjPQ}jnktnXv1=~!!3qhy
zC#zs3Wq^xRu#z$0Na9nx;dm~pz)HZLiz%>9^k9`;KGB0!iCpVM55gQ+<96{B=`1|^
zUiCdg#_u8*tdp!;US*ea#ypa2JW42b4yg{SVC4wwK`ZzmikGiXnzOK1X?CI~y~-+|
z=*u8?dJsj2Q;~m;_FiR$bM!xw>>T>AVujDthBa@9DsiV?tDYI_P>P+{Rj;zbC$7+!
zMX*ksp&}8igvEN5b|(vfS6SjXTfF84WyK-mq7kg~qa(#2crFd^7)2mh3H|jV1)pKY
zF5bUN0uC?I*JSB%vHl&&{JxFEw{;}>VUrHTi&MI*u;`=4W9B74>hP&~k$z5Ee=qu|
ziOxQfY&iflMf!Piq%1mC&y77&@*BpJ=tbY~bv1g?7mPR3ixe^*OE1b7QWr|D<h9e0
z#67J{<`sXZD>ziW=!0Fv19-tLT`&E<3;ub^(G|W{{J5vAHkjP;b`8B(^t}dOfa}J)
zLMh<FkXCpIyu|nURHzEPNa3!2OMIJT0P@n+3dci1NRK4E=tW0lNcoQ>9~6o(;h<L#
zos*rNgbiNw5tB;Ei#}rVEgebB)x7`CcF}?*bB0td6ujsQUTDIiFBk-f7oDS5oDc!+
zKOu=lS7?{>VbSNiP?jZab0{^u=<7WfG|z9g^#Mc7aU|Jt*qOGsMr^mlwh@^Dt|Siy
zD?Sz5=__CHf!Wp<zwRe!TOT}JBes<>utG>;TQ)igUv2BC4YP^uJZfL+lT*wQa(!s}
z{lz3~Q^V0G+cMj^m$R*tc3j-qws(ke7_pu1^A!_f0<G5IhxrIjfvZK^a*SJvsn^#|
zQaIbPzsVf;k=#;^PUHpG5kw!vC3Zy73mN1Vr^_SBr&eC*H#UgLFubO=<?kjdvI%oq
z@8z!vj#0TTwk_YbHRkknfLmu$rQfZ`c(h$uXFS?3tTUVruC_v!WLti58@I&wMowxI
zFttYF>MO~1P_wq18X7FnG~(kL-nP8rT+|!5)Ed|Lx19Q)t9}zOwZb`NyQ%HT>quWX
z=ny0L?0ngzn>6M8t&x$^wzdPX4JKS_HKRXl2WGLnidqhRX@ZFy$$f7EomSYsOrX<h
zXjgMC#=vx#vH@4v_)W=xE6@-V=JZI;0A9>#wfMC;H(wUdGuNjLvdBE+o@?ZsH^EDv
z3U0-OFRcJqEb*lk@QNw9Zv`P}O72?&MfhA1%N{;B6RNacwm5Trz!1tE2`yFT^S#=F
zn9f`tFR&~osA&x_iwSC4L9-ZHe4i_cF=Plw^?pk6FD6^JPw?p<Nz0$y`%)9aw8F4&
z7hziCmnMX1<zePsof^z**L52xS9AHue9%u_QF%NzTa8V~F2b}riHgj1QU>H=%I{mj
zxtP-X*1)-#>v{^H%V&6vV!Szd$8LIN^QvbqI-Ypb>UK-e!Bw!xrUbqfy2+1(Qgl;a
zD4dm+z|!jB>og%tE8rLtva|w@F=hL$pkqwQerv#Eo-d$Xy`PNT<i9nbErN4acs@<p
zdMn6AvrXxCOSyV0*}zTUuF9TaCcR5qaTA5$kwmwI@v3*{F+sd4dy`p~?xGaRs{)g;
zU=X}33ZRUcG;cs<Oh~T^5XLUltAc_tlQV4JPU$lS2V+X%TL~mEW$>+cOE-bTD!~Y5
zf-+Vj7VI(+Rw5cq$i50attC3F27#?9Z*Sdj%$NXU6}XIvhp@tgYvLh1k{F=u`Tfy%
zp^TzuD7?gtRe&`n;8;adn}`T2y4=u>Pl(P}CG=PYVPnb#T%pl7Wdg3)A_hyx*{U`Q
zPFa5I$9gek^Q~AnCeT^M0<t6{tQ#k#iI1=XoH1}`HE=T~;8`UM$V|GISRpg<@>h79
zO>Be}ZfCPp$Cv!s1U{?4Zw&BR-CWU_;AeHmpR-x?qiJg(7Rr<dxI%SpFU?>DQDe&9
zTQ8)>ggUF(-=@sH6&u}vowdUKn2A@gh3RiXnl(-bCZt&dRAYjgwV)HXw46iY)QXnS
zpyCy5ke6HH%^F7_6X5J=_k?5uoHb5Wwo<`2j$WoTzpbDPMIqP<L~N$?ysh+G$||95
zOi;51s>Tv)*1*)*lBPbQnBJ-Gp+<#BYtZG}g`~BD3SH?BKN7k&Rb}21F!_T16F{s1
zp|M1WwSdRilI7fh#~e|<)y4D=J$NzwT@PNo=nmangT>y2Bx{h^+e%})k<s8t^2ORM
zWy{1BT7t<Mz7rFgtP#d*LW8vnZZUzu8sHXN^<80{%NAI1d_yLDSc7fe1Q2V`&07M*
zo-2wMTl5xDf2*kVIG3%W4x<5An9eOjtB-)jD+*9Bvj)h;1T$+F<YF^F;D$r)NM_*S
z(QX2jwead$V#*qz785|M5ut7X#99SeYco}GgI?YeAl7dF5)(YERrHzgVU0W}HZ47b
z4bP@2e{RG3X+n&(K(^R4HO+|)5ZQAjcaaH2)<D15TxuPiCTv-&<CgfGYo5;%Gu8me
zn3Ci+oXsZ8Sc9hCgc)mfMt21eJCf+{)CkaE2@z`*{UwOlkwkan@9T7Is14Ma@L>(a
zj0qpsaMGLbVJ#f_@gQPq!r5=ahc)g4?Bc^3*9A7aT1J^oaT7H#H6|EYyO<gih^#?e
zVZx9#Zb~e3=ss5z{Y~|IB)4<zt5$Tbsk@sFHcBj0zGv_=CWgRv;WKZPQRB2HLckV4
z7@I|}kJ~2`C1B%*%90ZB2rMeGP@ucFWCZ+-uc5s}33w!TE|n#8y#-iY%d$3%ySp<u
z1b26LcXxM};7)KScyNNdL$DAWg1ftWuz%S5>~qfj@BP+1v*@ap>aMDpXQ;QkRtx*@
zbR5tX3U%&1yR7liB+^>Y3T9;p4kLETtX`l~NGxyA8?kd>=*;}Iupkq(azL{`Om=up
z**2^L5eF>dY2r(!d^>8n_>(}=$E*y;QQxYq0!Jk5wuUh|tK^lgdYR(TlfJw+MlI0?
zl`%9xy$B`;+`rsBmZ=Quj2~}q%<i_ohi<pZrh5r15P4pKqk86IL7;jTu0d$+%gIm|
z>pSv|*tor=fU&25d6378{K{sg)nVL$rene`^AQps``P0Ocz>r1?t|j$O){#5d`OAS
z9SBGC|AgLWL^fIwWmp?j#Ego-QOkx!K80L(v&+_nZ-j?m4m@V1g%MJ92HchJ8K<ZV
z3iv`M%$^iFBf;{G4TQ4<q4liL_Ouw;uGd!XHVDx#mg2J!xPfUQie0bn7rRzPc#tnq
zg0;fw7Td^nN)?%p;P@Z}=s`v&VgPM47!Iqus?xj9<f%GOF}!P}D11rYqpJyQLPGQU
zhz0JcRxLqw%+3%T0FL?8vx+<C80|2!d>Al%A^Z^H+C=dA0hC3afj+}Nuc@<4YB2mS
z&-2CYyplpegF3bM{FJp?Axo3J(d;bSS+ypyjcsWdL5Qd0s73tif~68$0|FFKOx~0S
z!gVklL&l_tc7%>yQS7xrIjnV19GC8t^Su(?#<HhcC;srq8LTV%Iig{3MjqtTYi@b$
zy{z+l0=B{g)*>0~X<-yUz6-Mfi%k<FSCrHCgvSo5Xlovt-(dCTL8NqoNAafcR83Za
z|GEu7Zo9HFBXe|1q2CzcQ!7z)+B1dV{SHx#-1hxRoE<@VTm&l4-Zzftq>jG&9kPBO
zm^uKhmYwpx4{H$*efJc`<Ox&eA(m6P6<-P;NK2j5ViOyOaJ@^_o2yyeJP03-nNiyX
zRWS<>Eelb=vCId~YmKUui87;bII*W8gxZhk{){U?gap`HF~RfS0NO_tVd|lphXw=}
z!6NPL%eNjE5ipj96@rO3AjoWmpKVFW?aG{O|1|flXvt14%=WHm?d%{@$HJn`3(aHz
zj1kFWDQu1KnS`}xhY^y7HWBTxB}_#k*{#y$Vd}!C&F!VmR#8u;__$0zmD+<3I)ePb
zV+ueg`i{s~Ari{2#BR8Cm2cC%olS*zb>Z(iX)<4A-#1MF8ynW<2cZrBI`6g^&ic+>
zn9&j0!DVhhmi+{!X!Mo3h4Kzzsio=D9wbR?Q$=%)zpct*LbR@I7^2OP&hqUf>R<ww
zts+vUJf80mNrSYpYgXN-yKG6K%KA-iPVLnDFuIM3Y~%F0wPTHUQyT5Ls^6$<L@}(J
zQVtQ7al7b*THHy))6+J8e&h~a%~VucyX7B3;V<G<@}#&rHDyJ=-sHQ-EHPP*M{7Xq
zn5yd#9)FhQ_`z|LPs8&A3*t?qc$P|X^b;b{@DrI4)&4*Lxn3Y=Cs>+XxP5MqqCCD%
z{V(b~E9q&hW{4H7R4iyaQ}^TY>6P;HZ{#OR@6$={R+doyrrQj5k9yx_ZVVq|)sH@J
za%xOJD}wvGlCyRHq8aQdG%T;cmZ|TSgQ6ZuZeff*c<_#y3tS|CCF~WnP%mKz;LC3R
zn9N1^xlh(E2(zboQ&I_9%Z&!5pn+UDb5OarK=w?q?1%1Z+`spbs1&`F{MJ2PsxgS~
z7lnWBWtJUMT34?QyO-V=YCo>~lOw9Aww^tTnv)rcqnCv=vNdU?KHtPX@pUk|lGUnZ
z8;^BaKC&L`+?ZBn-YbFFO5Tb2tI8OM-c(v(eVP$2$**P5QSyw_PQi%)&SX1TJ-I|I
z1wPs7r*sfUT3OY=%3ffaPpq?v)1Td8rw~5!Wp!jxQ91Q^SQXXeZXJnJKOrb>jdVgO
zY>UKM^35Wu!SyxW#5mk?GFWs9jYFwyIng$v)!c`Ubw^B@r(ZPCR+ct9IBQMm8Jy*Q
z)(-K<V-AXNdcjmvuk&z9NG45+&!!H!*5sn6eaGegCT~=qhJs@rVh<aHn)RImOv0!h
z3npV2C=oUYRBj#(giJ`Abt2*y)(RS$YQ+RKG&&iZ_Kw12C?#*wqgjzV;$XT~okik}
z6)em=NCO>cA08Wj%xN{E)9A8GlCx+#0~%d>vqKbOs-B~4Z|xBK>GDjk-fxED0Q+za
zU6Jr6p`Uc1{dl+cv_Zy*F3%KJTJSE<O&hLFxT3$YC*1FsXY%yCYGO`oK<%`3D`xoS
zm(gY_we1WfMKnc#Y4f}A4%6Ke4NBc|pW0i0;<h$7(yZRgTGj3Y6ZN2j^r4}A=cbvN
zAN<Vj1S`8(gEbXKv8xHbb}8No?qbo^S`7udfc97!lnq23b0U7NLE2cHy;OgknSsTJ
zD$Aru&;)01XnxTT%F@>TGcS6_PmDT<lb5Z(ew41z4L#~I>erB1b4{iUb^w)TL19n{
zsb*nsEtAh8`2!kOZC~oz0IqBdt*8<-l^czS&yl3m==#m=R=#m;`HvMc<{G_af5C2A
zsXrq54Cb!u1s-4UBf*+L7+(*VuXZ&f;^HV+@m%nwd0VzBsLj)@OlM%MAQ7yg)8!%~
zXd51&W>2fWc9F3KVwODvI(<}7{KxX%AB@)*eGj^+^u5O%lc`C}-O#f`fB#7A`uc2F
zn!r@meOj=_dOq}Cb|G3>sqav;FD|%6-(&Y&#3AQiQg_1+;$|1G(@Co&4$KmVSUS<#
zS2C6ogMtvhZ@GAX>usT1z`ftrP0QCqeEfCIX24k&G`eR6_wwtyWZ1(XQ%^onJuN{S
zadW>xPlEn%V(%yb?7gkCyj(b<!EL!}`B_T73u412vFDGBfkzuoqMn+OdRmNfzBtw?
zg`B2oi=F|^AYMxBsDm&05{vG&3wOBy?>$;!W!*PMl6JhqwDijF!f*`+_q|Y^dyz5%
z979$-w<0zH6ns2>>9n__A&35Cl%IW|%KYl=zfH&)a(Shi`)&2@KI?%J8`QosP(<(t
zcQDCs@MSZP-j0Vjd#4>$LhrbcCtnw-D2!W(dHaXmd1V&c&yGq?YWv?3YV4U`P3K+b
zNXwqB05{L#yvFTnaWIYm?iW;|7vo}^zqnc<3uKr-NfQgR@m<5XiA~>6h3Jm0PPyW<
za$dLPM9osIMY(Hn%GyyOnb64E_3WS5zhv{4rI_>QMK%0+-&n@H)l0*ldws?1%GO3$
zY^ktYz={I&fk9?rnt=ZT6qxnpNA^rMoMhjuldn1QY$QmH92{F}E<G$CwEO9?r=ZT`
zO<AnhlUIbUL%6M1piado3o5a8e1Sp8EMy@yd&<!7f+k>&Jvqk*k@nWB`ti*X6mucj
zS4yeEvq<`;43xM*`cCKqChvaH0CCTo{j`S&EoH(K&jnWZYy*n59j_Vz(cFzaG>@2U
z&MIhm^Zt%y;G>Maxoi}B<3U?oX^hUBF+HdAdb8PKKyQ!Ql-5qa1p;<Ilr%2}jlBR_
zN%){7qG|gjEJG`!N{f*~cvZC4fT(an(G2`z@8_i$($yZ!C7;viY2+nCud9<7@Q~_-
zdiYzM(wA~g(DO)o5$A^!2=Ag2|LmH{)_6ewZF8&BazTGez663_2HB6Ksl=|mpA`kH
zUlrO4;KKruQL#0_SN0+oTl+{qi{XMT5-T^I;T((S6>Kf<pt|28GRw-$KQ@^DPJxVL
zN_k9S@%j}PXb;S;gSz&j%pc2cwp&J;x6nI_vau#)$6fdbuO5Bm4aRC?b1IyUj+~b?
zZaRPZmyL;&5)rO_h8KiR+Vd{iX8S5tUf{McjuZoO=4j*yQpftTx_GxVys_Yk?a3$Q
zF2|R3o<eUq9$Qwu(fGoV{h~0L8QY&;u4c77)&&|?dSBKH^*dMIk~egQeCH&gVw`XO
zMCQL*oT_{d#KmEuuzA5WP_DXn+IF0#@#xOa+Rgt-fQoqNBg{TInfL?M2<R*pF$!1v
zzQvG)oa^zCj^GnQAB)8MW7)d-Rf6-b-^z<O9wmaMYdnRgAC9?gIj<o{wd9lO<>K!6
zr~bsLMCG0WThbMLY8J^*^KV`($Rpb&GrcL?EE$_#;uz|4D4zR~TxoHhMSduA8u`P2
z3|2@pc+^>~Dm21;dl|x**GU(}1B!ycT*a8&r>aR*q0jJ|sv3PYqS`5Q+rhr$Au%a_
zw`AkHDhXx_NJY>u=g(S$*NDK=VOuu8Eu2QWt|Yl0Ml~K3bxI(sXui5&<FRJzN=gqp
zbus&$cM8*D6z;kUw6v#XR~M$=U2vJfhW48*D`{=(jfL3e$gDUk*d<$)mj(=9n=UIs
zB{3=;({`oQjm5yi$fmNcn#X;*4^y&%3^?w7Bp6u6lb9zNnj&c@CJHUx36@bVJFfpt
z(8+as5V@;aV=vcaD=I6vkzx`!V%<Z0<Ql60?jT8x*GpHFcMnA*dX*v+nMwR_Jjjv}
z(UJ>LGCbs51+6R7xX^GYgGI|m4RFc*pG;a`xaq;VaFu=49ym<mX~aWNfal<$evP9l
z`wHJ@;8BQh^tbCI`c9!?agdqiEmm8IoiG;>ThZ%ulQ7J=o2e;w678bk9I_%Smr?d<
z6<nUxnpdM4zd{=BM_O6TR14MFp&je~qEv!!hM{arLCwR=xPw5hDIi~(>{Lg6k-7=T
z<scBhjd=lc-M$HYn9aUK(0Eg?_aQraW1}KM{>;dArIl!ih>#T_b%Z^3@oCoVM~z5Z
z7P>#?*j)A@?=B2G6PRI0DKCn*m9Y~ki`C2ifawqcH7?yneNYBpBZpT|edNo&*vc=-
zZVCw9tJ`tVX7FL0eF%-K>z2a|{oxL~@>8TUnC#Z*$XZ<`3ur~o=CUy)BF9BoLobL^
zNh2Q`>Qk&aR~0oa*KOCsnb;tISF;R$q%o|gjqC*Z`yOso-n7fUsHJu=BZaXz8Zrw^
zX4o7U!Y`C9;)i2u?~zm65BT+8iBU^(z?*4RP9ah07LfX*R><GJqBol!4pP|-Q-7Th
zj9^1;!ldztIYvabr_atutdL+2<>YJp!KI{|4mt+Ae83S1N%EBwteUJprf?h*=0p+#
zK6>7ObnF^HAV~A73nl8!V*(n96|oVFQYBQ26?#}Z+XfJ!#rX~i%G3MSL>-8Au@MYH
zIEhISIn|D6Bpf*J4gwFx=7!sGucsV*Io4W>C3bLF4{}JbtOQZeO4@IbP~b^UrHzt<
z`92qXNT9<Ac1X}3Whw0C;f)e}I967JC1x4+xe36-JE1`bMR%9d4Jw-Ry@;M={@YpD
z^xG;kgz$2kDU3s<zJEACg7*bMIOV>0juT|I`b-2R2~&4InAd7y8)a2^0Z+;PmCqH5
zOHgv4IqEE$%U0OVlY*#aQ(-0I*0}WSTFD5Mzwnr-Z+*DISIAF1w`ntOb*~r)!p3qe
zn?AUJ@3;;WN2604f0crE^E)CbE9t~CfPuAIXXG;S=$^1i-h&$}VQrsehQY)wuGM5>
zStxTE_J9F;0N}x!gBbEN7N<dTq{4BT89}7Qc9;ofoguG(lVLHBs886)gBu>oXmJl4
zXZ4!p$0=%Gbu|ez8|@HKN`oe=n0flM5lTAh>BT2pD7}>s<=*d14ID6I3=uy7aL*nX
zh8&T-lox#<V6+v$4z<N@sKIAPf;g*Sv~j0csj1Ds7x^@@Izd7rZBLrYePAf5E&;n)
zoxO{kcBs+jUgJBJVzmUf6!;KEUs(cS>|7`jNNb~9?7#&JTncODF>F0(PJzQRv1%{%
zdY_>x^MWik>Sl=P&0-6iA9JC7XGRB=A!bo2vO{x<MT&?*8**|9`EJw@ZW?{^bCCme
zY1c8sP3~)@^<owMAjBmh?z2dO#;(rS0c%%W;cSj40uHhxw&I*Yaus|}tYj|xKQ0*>
zgMU0lTqvsA0iqiz&sJc8n7#9qEyEH+De@*R#RDAxQN`VuP{+MU8~d!iNe)78xqbWk
z129(Dy^^Y7@|3TgiOF$}YkIY?ZY`ynCTMH8pB5<l^y^&g(bnWUkjcS#NOSSzgX>2!
znWBCj+y}`AR+%g<7eV7s+tnncLVC_nZeP$(Zj-;Qn@?Jc%EI>F65v9IE>_~Sa71;r
zaG-F(GAQrV)Xx;H-Jx%v0)M4KjD4CvOUpNPVIMobb2sza!!FR=vb9I`!R?vHO3*B@
zt}2t#9AP4jnezQHyG(ldNuY{;`+S@RS@O<ZECUnBj`&V~`>D2y9;3W7p#|^9cfC-9
zb)8!A!>%SIIzWxc%5wW0XB!q)fo3|k9jcFG8zfeuW(%s_*6G7fty%6~7fia+@)oEV
zr!k>sT@{9OUHo8iuI?E8Hq~!^O5T{*pigP>#*m6|ZmxYAp!Ez4*>tvdHco=It;*ed
z#$~R>m1cKj!Ho`#i(pb4E=+W!^$xU)Ke$~+m`+zQPKJW3Mv%5coiW8W<O%zrogMWB
z!o?%!5g~O$4;hI2NyR)LagdbZ=<66EjwS|;QHwgV5n=#qduCd#r2|FolHqwq{tUrx
z3$Xp9O0<F1^nU#WxEuZssk|`<Ip;dWC}yXT`2<IfK-I6o?rOm3%koq|i`5ZHEx06h
zMPq(iPFh@PVj}NtIq?Ow37_lW18GtDx%(E|2`b^HlNf*_UXgVkzB(?_!?HONZF&&-
zZx4EK>7p|o=%fxqqL;Mq?S<w5*vcHCJh3^3{K?=sIG+xAFcc4kGjaqEV=fkTV$=Xu
zWms%ox~O1%Ro=Fdv#g~Nd548n1qT=31p`Xk^h&2z-N3D(-wK7+3%?c4ojV*TwOzih
zG(9VV)C6zqpsDcgJEJN2`XW65lSU6AR{dDhK~uxL@rWseuq-i@R3Ws^I?iV$Ru)qF
zC`o5mb@FRQIj|{!M>a&~+Db!vBnvVh^*Sg9n9PK%{o>!OQZML+=tRxR<ebM(Y@>;c
z=WMUV*N<91?02}u@&XU$OzP=$zF4IcMD0TDTS-ABB+P9rXmAz%1G6~zTwZeiX<=qR
z7JrB1H_Pj)eXaF2yOy-($W(ezo|<4ve}i-0>Y?GSM6JUmqk*J`Ykn9)esTvSA~mt+
zj%FAq5g+FpFOo@?tRVAy=8tA>-jicNlK0G<M(%~Hp-BYC0YClD%W(SE!bcynecHGh
z&Z17<dR&wOPs-S^%jn&cSeP28?sXA;Hkw_I&NUUO1V_1;<-n`h4a#*W&d;r_Td`#|
z9r){qunTL5!+T%J3L#ZrPgsnvqddCyLT~5QlM|{>u-9RZ+XJ>@^VhTXp_K`*{JNae
z*Rts3G4KukfL*FR8bI^Yx!d*&Bg?KWJ5BZ1JJ{<<)+$APQ$wT#f8@dH{XLFYld)MI
zgFn$>l&NJP^dz%3;)K%5()5YoZ60-V5YlXy^>;P6R#JfnVPHx*Cg{R3%aOop(rb1L
zghBzmPML(chfL!HQ<ffayD?J)k3D+?i)aPn=NUNV-t6|uEszVj316|UNd%u-!p17O
zbZ*eItSbIXYVWxps4aq%>hQzqa>w;yJFZl-W~04ESy0BkJmV`!o;JtLVZ?=+z^agg
z)Pw4<knL1&*{fdoq7-bTV9ifO)!042v}M~-5kmph2Xk}B?Fw}oAgk5mr#4Q6v>o3K
zYE{}goNFFP+LY*6+i0EqRH<sry*_)CI#_Vw7>s<yT|k{XSt#P3M&ApD>Y>F<Sh(<*
zi4$eUH5eJiNAh2gwQ-s1a7he3HuBsfr5QQ7c4rVLbhh(Wk(1~dolUfr_ANL~tK9=z
z(&OQ|?5L<s3|`bzja_B(s)y!0%{lJV7wCr2pSEqtB&FryC@S|Qj?=fTrkR5zZcAyM
zr~_9RyuIr`mO&*TEUF&3OVBqc6Q1+WA-&__;VN2~79RJvdvgu55l8ep4v)-hg)UzK
zbm*nE+EvCnFhtlF1JVVd12!|aVEP=%t3AuhQ|a6>2T)r{yfJrq3R%}F=fHRDmH4O0
z!YP)L@a(@?tj<X5V=oo19n+6XsdhUYWgeo9L?bDxGuXotAXQ-uPhI>0tpvGro9q|<
zxr~P6sj%UZSwbP98|VjqAtt<<#1c1P!kKS(ToR!fU8%<>d?^#+PF{>(AgfZ~L&*0%
zVprtqR?$wZ#b4&PPWPS}*9JY8q7s5AXDF-u;K|)}Ny(2p9=>Xt{d{~7m1!SB5|e7R
zUIR&t%xra^z;D5K?Vtn)DH{1?N%e*lpKeNT!3Ymh)<uT7i<`PX-9X&ByLvcEv2P|L
zh()yUi3_bJahX@pKU|8c^b;`|;KZ5+WoH#}@ky0&d6mWx7?78rL_Xev`lvo4#HlH4
zv0ABkSG#yI7rA74&>Kk=Gq`d+DszWTMk=MKKH8xV;l~@U28PWlRe+)qtq2c!%OWNy
zqk60*bd$Ib_dDmOBE+4nD}b&+uF<%=_d6%uCuA>x+LfwN>p`zr%K}k3<;!TZB<{S+
z=-FQS!eaw68n?l66NQ3G@E)(yenQP(D(O6{7pgyMgYi?_r?>JYinot=9_6^*@DB1>
zi%qt87Uj6-Wt)W9vn-h$;eMc?F+gw4zGBn{k{0SA0jPo}_E6k-JiK(p2Ald;&^`$~
zcMyn97Bzd8!*n2(%r=RG3cE`wd0Q!Pho%~F@1bY}@1~G>#qA6l{6e*ADzS}Is_dmL
z)_V9Q>I)Go$i0&qvg!}rWF)%?3YbUf4KAvs2y)3r+rk_xAqdrEB6fi>6t?|E;wR2G
zG*JGiUN|ecMQf!H<#vV?H_Kp30y=Ch>+lBQSaErGh}j;@S5I;3To~|UWn6^YoJW^{
zi_3uq3JEED$Xk3`j`@Y4vlxQcSW)6Ktr=z<0DhBJmg$q&#1uH09J1&Q+!Ntqr4TZZ
zBAU$OfZ!-<jgK8X(OPE`cF79jT0j$5TcR6mjRf{PO{pOVt;GbO%r8crV~r*26XXK=
zDK4ZrrLL%n0n{8OuusWHN{J_)_V(<HmYD7j4gwDadUn)OsfHjM5^6|ideH{{T5|;X
z2N=H~=q<LmJWf$7Jdk0O+~AQE<|2ZQAtjqn(1|pnw!K@-=Amw;3pm1ay;DlHOwds@
zWJLr3JRPd&{*(f9FpLs}^ol5|O*P0V1WitCo-p>UP_2oC4S3-URykQVn6J3EK0(Qi
zkQtr;3VZ2%Kf6?PI+#WhDlHHzQ3j^Y8Qkl@t**(b>;So#FJI5~hdW0CZ{S&JMZ0Uz
zH+V$j7{z*lgV_eU<@J?O#Chk!t#(kD(;qx9T8y+nDyV1xHsA|cAgk$}QdFG%2nmYK
z2n-p6RX)YlAZI6)j4na?f0W5=l-slQwJcPf{aT7%)V{2AP*_@Fwk!;Tdt){%KqoAu
z--7t&3HuU`6}hzy2AP!q?DS7y#0*~$7M2O$>WVw;H2%_mvPoWS3q?lsnMLv$D}{ae
z1j$TEN@=fo^GgkUpCn18mrI;tsGGc|pF~jvht(!-afAV`Q9gWpjCD%kIJcJs?EI>F
z;SEv{`$0ZNaZ>%WR0i1#a2HZEiKqRvw##bKNpCKWOPn2SRMBZ1En#`lslkIlHCYA8
z@LGbJf(K)`ay0z`0NoxIV~fM(54v+7h75&?Cra2%Q_mp(R}57LS+u4@&>Rqv5|amQ
zE$Xc79Rtr#n9pe`VX*^d!v_KF9&L+&A}g1-MWG@tmpJ&{5w+6^ddYT5%6kfLF4qn>
zAL^lO>>z6K3|Ewp8L2GK%iv}RDGx8<c$PN-ix{qhQvNd!s?M@<h|{<)pJ;-!$xdXV
zi4R)M(}rfO)o~XIzvQVwc?|D0sX^V-mseZ$$M8Bn6%9SX$|r0Oaa)OcmpLO1DP`Sv
zz&O-WsC_wvrZLIJZlE5FaXoFDg_w5LNQZ)(`-+kwze)V$<S!yr1mlckqm(sKiXufi
z7~VmUNU37S1+7ml9e#6dQPk>$RIL;ZdmxV49v8U`8btboyOWZJD7yw4A{zW)6RQ|k
z0eBRWQw5`yK1wxw8xn!73VKgkW=DAT2j5HPt{nZ<2Ekhen-SxqsP&I^bqaslEf$BY
zxO5>R8Ru2MK6D!qgU6L-F+^?cN^t7OGnL=$!+X1I!fYaaMKoWF$nG@p06tGoU!#Kp
zOTJM%MXUVgG+h0>4rZkkeT^klv;2Aehb2mMbI~oBgrj+~+oMMEDVO15-1?7`eu`hZ
zk%-$$>$^jS-9t1c+YCl!UQW6uWnlD>2`v+iNA?Pd>jVr(7zg89&Fg3!U#bq|#RRJ_
z^mmzwwn_J@Zs?{WRLHrZeW@Mk;Q+{cRkZ8|&S}^4iC8~Hy>F!8R|`7bi`4t_uAL4$
ze~9djhkSyNlDb+aP{yc#>w4t%9#u?RWLhWfaa1n<Jq9&Q<@hurbmJ|hVEwLRsTE~Q
zq#Ihj6KW}2hOI>FkWH4iou)*OQ;a-K1E!W*vPO#`v3{LIp``x8skl=7C&t1WZl{%Q
z#PG)CqA00>7mU0Zc;6=5tCD&|3RjG-*yqBKgPLCp##3z@M`@yW7IRB2gHqQ${i6B<
zLqUiXy_Oe82<T6_T*_)-9?;;_;!3Wy9`&{lF{+EF@WnU#_f(C+waIeT-H?{M0|+Z<
zlJqvYwblN<saElh*o~A*=Ly4npiaNOcLP7pncAP>kEun==Uxd6OVKKMGk9tIGk3;#
z2N_+b?CWW>N<!?D3**FXnIblExt0|7RFEOe#wKD;oDV^0wzUG86SiX^tsu+wjzQ0b
zquD(m>k&(n$|afY>%Y30mP(pv2l^y$r;3Y$-HY+u(U%!yxoJjyhN?*P!pgTbTNq-G
zo=MElft=wgwX&Rs+Yw`039fG(^$49)EY{s9^r75Mx0l9UDHxgD_zm{O7i|<wEK{xi
z4kU+ikQQFas-BaE;mZlw0!Rp@FhBf&>iBvQ0nWlz0b%}ZQHG^%eQBYWB`BE6rv;xz
zXPG$=l<KQy8$gX0hrg#J1(o9T5SUtqovbNTsBP#32r^}#ahr_W7Yb)P_zL}Hq)>EA
zIw4G1<)K0ngaa(ZPX54Fj^a)f1;4sLOzCbd!0rVWh+)g2o2%552q$a}XrVzfNiwKg
z1T<C`DGWKTfuu_G$i;FJtG?7lG*UKt53NvCTm2mJea*-z9E6YzY6lpjW%L5(!Q7g8
zt1`HwXY_0nh2<NYAVt0&YdKAdEhYW!H;!>v731Y9onDUX8Zf$a4_U_As<qo9D6Fqy
z-wdMJtx<h_Wv3{Os@!pd4{dZq_o~6?b<+23QcV$B%DA+J*X3*%u_3%!tE83B-gT1k
zK=f@@Le7Xa&ML*8DYP>yI22)L@qRWYK}&(&>SWd<y{)Cnf~zXExHuajO;zc!v;;Z?
z*<yC(I}|VCf%=U7qF8em0p??RsP1-=aUOq81=*(+%Fr&fgXChRrBYkaeEd~zkcWJi
zsv3R8+~XqS`m~eAr3d<J3@w5d<uZWcRmXWJ>-^WXE#wT;_ab~+B>8}-dQ78hM&@QP
zw|Dv=UE7!nMG|?!E;#DrIjTSTExq;2T~9I8D<bW@?YlGjUTsMeb*+_RO`HZeHM|3$
z3gc*ubV3zNXw==)qUi=9SClaARi_8oH&`jJCE<wi1B<nSa4iVp`7x<40!V%{j<CA!
zIG&a2!ySH=b3W;gRg+TBb@jFxU^T3hh2N}zIr{d3BsbdLmkNd0ZIJnb6wZR60a5{{
zei~_4FtlCu<!{ucO)!BB4PvKoC>B6Kf~d#vsj-}LLS^}`H_n9ypdX0efDzAdF4Eo9
zJB_e9p(E4LO%W&KcW3LZCDTEanrT5}w1(;V>O+FD#*nA1M&8cFd({N9H|V3iX$#54
zxS%q02XbQ0+^)CCV1<?5uq`#k&BZo9GvOYy4YO!5T!z>bB|JM&4IhjwUFO;<(TZWs
z5RKQ6qRTJjtBnA_26WL)H~lzW9{kfV6t9ZNotJi9CP@*#jFu9|6MTmGleP)tGiQRY
z4UNTWT8eyD^gdJc*9A$@Ifgl`pH=8|44d`3(bz2%cP>`dc)>RGsI`Rz0kToQ`=N;D
zVpaGl<$v@?YggV(k)iNf(Ioox#<pRAFxcgy?IW+|%PM<?<jyobhSYaT(@rIn&wZ<=
zWef|4M=`+?&2~fuQJ&rg!^kW)a(;g~YSDaee1Dz|@IOwCt@I34R`tutQWbnXpN(J0
zg*_`cP<($^esvTujKALL5&W+BO5Wkm*2GWjd75&S_wMw17cbaIyeztOKwJ~>dVce;
zcHk-adgZzCzH-ph^LBsJBzR+r{PIneUvj1D+3Us9|4(Vp^X*2wPsiP#jrYg?Ibp1$
zSGh4kzvE8Ob!Ju1i|*;o<gC4_zKz$Np7+Uzy!T23eXG%ZLgZLvDF@d!_xHkL&i=A#
z74pZY$O2xdDKE#vo|k?{v$6}&JN|?;PvUq%3*RsH?}a(xh)t(#*-U-|Q}SkGhF*~V
zH=hSQ172P)1nraWu*f%p1@6lP-e3YcQ+7r<EcH9TjqEo1Cy&HK0Urz4_13Ap3VWoi
zdcch44jUfaV?}<ix#q{$@(Om!ddVo*M68E=RypLqro?o0PgXffn37U#SffQO&UokG
z_ouT)qtDH-f;n$|#ir^UldqE9fX&OWiUHw-CjVtRqIRcf;%P6!sArpmEqkKdP4Ro%
z!>cHDPI`3o>TNeET3ol98r;kSrZAs>d713Z1+9tglOGnpLG3O$vgyS%Fn83s;SCeY
z)Jt)M4D(HO#MiYA!xQC8_&JouEp2&Wjtvdb+7?T8@c>`l@e|)b#h^W8fzW={r(YGn
z1>X?Rh{Go*G6Q4}Hm3tLl4IWO*;|it=kPq2FDjgQ%WNiJw^nSVRC}pvQ<^s!pANl#
zA2rkf^Yk0$Lgp<G=k<zU<XRqJgk9So{4l5peVv(9{4r+<X$J1EyH~g4r@;m7=osKn
zu!CpYIwHt1!~3wFzHz76v#p=Ug`!+q;sDuwvZ&W2?X97^`_fef6+G6ke7aGHs5fTG
zp2)hP0nVSbGkFc2*Q-#PYv>KuV=`#zux@#f^8La7U{k_R<K(8;)36Ha{iY#{VCJF%
zG5fj#53)xIk)-koBKJr{;1)uGG_B@4N6$96RiN18>1wUx5rGJ*KqU<aa9II=MtHlA
zVmvpQUbN*)cN{CX=)@F-s1%5O!JbLaHTQdKmZAAL>5^_ei9=gQ?o_U5+TO2`JH~Hx
zu#V#Y@H$++lNH_Jld$KObVsgx)KBIiA_8-dt)C~y-au?TT+|5EC#?PSc{VwYIkZQ1
z3{~*2`h)Q~zmyl<(O*?j@V1?FbNJ->4@TEndC>K{&K=DkAw|!!^}~&s*{h&j9xoWi
zec-tF7}x;@wldd2{^yl;uV4SP3Ct*F2XyK@1N&KSR;<g;VNXN*_^giJk5*1e3Os;0
zTxgo+6+Sqg=aB#(X1Cn)ers8!soK-^hWt>@rwV88VCL%PVs32zQF1h~fnx_S0Y3f$
z004Gw4i?sb_^kip^YMLDF^YS+NvgUTyO{(2W_<9BnSca<QB)Yf3}7@h2Hph(J{tdh
zXOwVsaQm;;7W7Q?OaKnxuqyv*1Z?-ONwEA|7=TgD+sPcjsAOzu4xj)q|0P_>*u@+;
z7V|%S8RgB*tc^t+y#TsE787vd+yG`4CMJOXU(H2<f`RQ_0c`*7AnD@h?(|=i`CG_e
z+>b86i%}IQ+Qrzx)#*c+srNr@X@HxHyZJwqD6o~7xreo>xr(I72lHQRRWWyUbayc|
zcLjXtO$F{hOXCF6ANu{!l$^PPrJEIi>)+Fou(oqEcL6X;*a0;wW^U?e_Lro8HDm^G
zvT<{KjP);*d1aqz`Fdf9H`g4i&hfAD^Uv~U!jfl_qbHHT)`W(FfTo~|<;DO&(N}AQ
zO~g{*VXjfM4P*g<;g(aEcocx(dggi*qLbrmG*Jyt*!59NY)oLfk9q?PPRdkYA25cF
z2iNzmjo0oKc6I%lYMz=uIjW-6Bw}PSFbTay<>;jWk1z9r=q6PpVt9hq_uoOh=>*af
z$|OX}s59RVf8+97D3T0B*w;TyQ|+hvof~|Ozte<eW>oYyGpXAm^b1coJgBQVFgs;x
zrY&CdCtjgRE}h7FHY;YvS>deJe;H_$Mu+8|j!*Eo$4f3%$mY#S{l!}Qiq#B0o9Acd
zW4KqNW&glT;>VIG6;)<L(Fs?sE@k&~#2;{t{JRfZ=8GADqt&UxSol!*&=@uC2ppxh
zG{qOT$<Wq)+CmZM&+p^OE<6QA83rj>GP2HyCm>6t%rY6?TXMUzV`b!qDs>nOF5)^m
zVRXrgFvdGi+$l=byZ9i+lwnUMVWH}hg{RO-Qtl1LUQN7=?<fjLcMMj1>tDpo*eup+
zM{oovd-B28E}%G*;e08y`KU7Nw~&I7&>5#B*NgkJD(`DEMQtM3a#lo7Uj+tCh*3H0
zp+{7rh7#__>~vWgG@BWp`Wr06dc9Y480$=mXmjOYC>pc|Ke6wa_D6HtrQxb%&~a$c
zs>7bWsDTSk%W?PFmGoDBy9w9yy&)3O8J}<Q!Coy~X*`lx${emKKwvQJp0@J$7{?eM
zw@stsBt<!K$jTA-Gf4VfU}~cP#^JMndzi5*tRWDbk>-^C!XVEk&K6liMevpHt!miN
z_hD^8q9<c`@(lH4)xr5}v?tmTJgEIV6S~=sJ7EU(Ddne2QBSrZ6_2%KlBlxFqUeu_
zrrfzR^&Vc(m+sd4pLdA5c^v!;EY{E?Ec{E_M58Gx4Uy(ayGR~1Rm=76v~SH0uR#^t
z`^bWkU)A=$iFI*>wB=fu9t$`0o0L#vjt<KGq05oXE16ub@0R^y3a^doJgZ(16fLSk
zzdcW<Pd0E?zdB&Ar4X{nm|k#{H9O;OA6QUHIsN4FSS2fH(~eMD@=J)oVSiqJ1&s}(
zj*Qe~4XcvgvBM$e`O&#jzj_>HIXu;Nuh3~)03$h|I3rH?Nh2p<jsYH#%1xhgm88;0
z%=QdnR*J*rOTqH%vXp5jkHObMdQL3d6U2Cl1ehFN_w;iI$<Ik6a_b5=#|D<)Y3Flf
zRIH*gj6ieGrBp+7qI0+9*m>G`+Q2m!lSEyM<kCibZTatVC)OpZX%}*=*F;6w$in~w
zB7Ec#DG8>5JW}{}2=0jP5#RY(vf|Q)eo%8n$0rYe+95!$K(;ZxtD6AR4DwA;7m+O*
zSvIX6UKOAB8`fLU^TgFIXP8ar9{s|infVOq{;hjj`>4WA^GJQ7tGesl=7j&GaL$Hb
zMGCGh#-oJW%H)-1T*JD#(SJAGa$b;`l#y5ZmS2KOiLKr<x0*mDYgmHAF_21XclCDA
zl?U0qd^V`yxs`&Jr6G{!K8E#^axHn(G1kOyI`wb&vI`gyg*r$PEJCU{=1AAP3~LqA
zNK4+jIp>`b;hJAPjKwi%Hwv`43m3yV#w~7b$7~+ZWnPDyt5y!!hZ?o^XL)Qq>&}<8
z?(>ssQmq<}X6>3;WPQ`<rwxo&mMG10nk81m4UKy&cvA^=v~FyBxis1NvHVs`hmMb?
z5~1f5e0mQ>T??=;3U1Y0@8nFWSBIg?`)?DJg@&fV%0Y<4K4a#050yjyp*GE8PG?}_
zm___$pi``de}Rh~t3d|to-Z@<X^{9=9%jt&QSQxlEtg+zH%Ts^BJe3Av^H&v*Bn)t
zqD96kjTyqD%FtEvWg(0x$rvnjyGg~dX3XD62J%omGZ53iGJXqnV6!k+(f$6^LxF@Q
z;?5NbZf<pVtd9~+YD3CgPDAmj1W%>3az(uf#qLGAImztaeYB}P%{KCr{DGIH?m+}>
zkg=UWos`8-+7q}sH?8vu_4rR&Uq;stn7_tzT5MIrkPPEbELt@OsQtdDj>4L8z}Om%
zfVX_MbBb|*?njI8Sh~J05dDnA7<0TI@k&&AKAwiB(O6@Kc7Qsz9FdV4|16Hmc!Yl)
zBGW6rx5r@HBoXgpn-hL~c}zwD-8N|%qUo@*?zI}vsYAr}<#pE2@yY3ins(({Vg(SL
zx=VnaG?RE<`FTGxwq|Y~$?vtiWuxF?x__oREo!BuN1I~&o#e%4r0Aq}rNkI&rWVEe
zGKq_YKSjh(jo$tHX16A_;BJxRGV%3q9?j<+zoh;HKtDyiZ-O9L(Qx832UC}wLBAUr
z*m=S2+tut&|JB8?Vf?|XbilIV@x=-8a0fMR970nJN37hp*&^$1YiFA+gp@2s8nCx6
zKPlJVa6>nE8L<>N-9^2f?}A)=zx$Kd1N2r=O09fuO4Z6!J*vz2c9ST-1l*{_6Fu{|
z7j%_Nd^;4nn!b{Mez0%w&RX(`%IoRJw!2M;weJQD<sdQ(%-%zed;SU5)iuq;BO#+v
z5jlpO7TNj%DI<OYxg0TpNjo6zEJ9a$^9Z9%TOBzmMo%bWYE3|>LP3PKGT?EAQdNj-
zx{N!0Wt`%edMd8-QshYug~YvfTyWn#cfQ;z&pfb$ySh%pYjP1I8C_rRAog-?{=3He
zT4z6~FjO3N3qpunJo_7Cp()-~&S8_%NVz~GXY2KKyF24b+g_VM&7`2Hj_%}GK-Xk}
zsEWkeLEeIK8WD9abzJlXGhvQaCw_T>na&9XSD23?MP9@oT!oS1cxgGOvZTUTX*oHZ
z{3F<?F-aL~+?%vNzm|#X7YmH4nt14iXVG^su7$Gui@7=pp^BF*3k$ATY>4x8NijDJ
zSbMtm+hX;rYfvUqq_n3B!i!XNaI%gUUfMU75Mv8t)(4j~&noZco_X#-VDmktXJ>8|
zlyTP)3`-9iLmLNfg?v<GY|1q%(s^VN<720i$ZhM96qtG;9hgX<Oh}Mk=nUk?r7rT`
zVs68ZVrCYKB4%q!TO?t!gg@I`{>IOdLNA-7rP{#tGuwonIGRRRWcZHP=If`u)Q|s%
zc*FZfaEREqaCdirqLO$CfBE@kIDmR-^3R2=?C2;wqP&Z{Pl4TN(C#j$s|%b2GBKuG
zshwW^*<2{cyK)FeM%<#gaW?i@0$t8!Z1vnH?NjH+ruE;7=fZ4tYaqb_b;9py!V-Sm
z0-3i$CTiTl@E8(n&h0C54J8g6bsHCz=-AV5)sZnTdN-;Ilet|;m01A{43WrIR9Pmo
zPI#uPG>KX_CrVlU+bo)N+WSV#6XY?j9KC%MAlJ6)`za$xMbSsiB!%x!R1f{<PP_<f
z^0DA{^wl>qDbf{WIx;)faRw@i>;24H?eWNNUs8!uEo5CERjeTyJ?#=Wcm>k^SjzNL
zcK{MwcvdpLQad?&3NniG$qy;6DRKw=I3x%*F(}!{qNrcTh}HKmk0#V>qXntbY4;{%
z7C$+vBlS9_pgV~?c|HoY!5P+8zQ{gN`c1x5deUSEwM!&Ulc!QD(>~pH%y9hD*#>C%
zEhN1%2rj5lj$7l-_(}WJ6#IUyR#KqD-78AEO^{swNt(OQ4qXbzgJ04lJs^;Y+F0g%
z^3#X>OKfY>EK|36J6lEZAAMdS!urzU^sfCCt+D=OsG@%1dg(%#ZNZ^6lKx#1foSZj
zqZgj^@~W-f7F%2Miw!(`;F%tuiUgu495ZL?Ts$Kb5K|CPeOOnx81>`dk%k^jrK6op
zojSw$KO#fX6jqY({uHD~Q(wA(S6q5%{Z#n&M`0yVgeu34R8$Jo`^y*!Z4{b3Z*p8C
z>unL)(d)!>taD?ifOuZG`S04#obthTZnh)M3uB<#Qfj-At_KP&a+`hovPv7-UAm#x
z({+(_Er9iLu~T_b$C=p2!bTPLIyMx{dt77pu2W>_d8(RJ&1a7y$>(n{UZyXE;3dSJ
zQ5D$^c@aGu)W4fiT0q0%T8+uz!FKk3s*@(!d5VhKIR6+Jhzi;!mw+QH&3f%mEu_Ef
zaBulpmzccO7x8B68Tl|c2U}XQ+r@e}t{UNS&Rgre5_d4%`LsJW3z?^U;EE#0*S-JE
zF}Tlkt>M$JfF|dK>?78LQnyuNn3uZ!%r1^R%(8FBKTGrM;ERU_hJ<|up~A^sD#oy@
z5G58n(h_UM<m3ypdU9Z0I>+-FCoQfER`f)4I~N}3bx{NG+78yNUYK`x45w{+aQo!(
ze&LM{T{-`nJ+&6#b@2Z31183}jxO%mGI8lzwT^Yi;we30CWE3*c029SGkMJ!tAa67
zB5OAJw*Bi{0}e*!6wA@sKB`yLNbX}px@>^6$N4PclV-W+lqmD|P%gjk{#4WF5(hk<
zQj^|Z*0qM}x3>e{(&3mMu@@cg<2KT5Q&lN{Y6=-jiSp#oZ+o?ZKBc%GY3^DlhJ<b&
zO0UeY%KlO^U*HR$$Q;wj1i-$v^i(qMR*|_k8dOC1Xbhj2bz0ApONAXiIPmh5cOiCD
zw0?HCi@{E+FD$OWTxqH4m77ETD%t5ezt*yUrAUpvAc#r7jYlZHBViZb9bxEm^)nIM
zkcV!(QvQg#8`V%yi@N)5)N*_DCnQprJ48#+cad%l@kbd-Tr(r;MWQyD)P7j~{@f<m
zN>xv@X3rA0>t~f02TaFQuO>IDLGxvWsrzLP(H495nfjm?B+B6CWNBe4(-=XM>JdVf
zsWY*)+(5V_jjE+K*YPZU-oXh9Tj`TL#^|P)g)<aR$8`+O%JA>{?PjlkC}bC8s6M4L
z)~xEace?21TTJ6$^t=xhW(h?k?;X?_@EiIkDP%X9jnIu1A#MdOzW?HaO_tc^1+6(0
z(laBmE;c<B<4J!@s!mpr!3HA)&kPa>(oE)QY+im(Phk2Sh_&??th=MkmHWK&s3?f>
z&?-cGgw>9y`l!JZbwv0FDQ@(ATedgpTbMXHu|zR~DVNCddrTLf;QV)8$DLs!Ozzk6
zVN9Bw_bF_5NqsU0x;v@0AkPHg)5nKJU8U&z8e-NRke5U}jVmEKER7VkDo93usxG>I
znI{=@8|>EK<>8KDO;6@o?1v$gsIN;;xX~l!v?5xHx7}4?93Rx>FeY2_zXz!_&uj3R
zi5WM$`yM%7v~-C^JnU&a5r&=w{n?YWycl~#&IPAC(2ncZxjBOi>aj6$8*pR4UQb*~
z@+THz>#G@SvjR3l9}r)KD<738YrMFHZ>hQB$4Ilqy9C}u8Em0;-wqOLc&-Vx;k;)=
zAR_F_A&vyYZ0B|!Qq3sIUI^wQ6L?ICRpNd5321f-Xa%vQ7p_vqsl1D1Bp#~CcNm%n
zJf=+>l?@bs?9#muSoB7?;mTTcETO2ZQ-V^H?zMUpzsBl`9FSaiWI5I_j2nx)AwLCU
z(jf0FQ`yBiO}@^6|5S$Mj`ohTBUSu-#6m49b2jazQiEWM`^aCNPbX9jn+e5j1~<Q-
z{JALHEeuX2j#m6J)%WV+a+LlQeYY)JfcCTG@s>f7g3Ka&3OkY93OJFP*@RGGk!<hx
zv|!PgO3`mO;1?L=?q}DE<ALQ66(eOfrUv=VP3~#}K2^as=QZK^-?AW+1)s|M6x%&;
z1wIKXt+5=g>sBItYR7&a+BKbXFy_2RZs%mNaMT$OdBoRIBg|mquAR}#T(vBIlFF+l
z4-T9OU6zN%9%Nj7?WTx|i$u)h7rfp-dl*N~l5B<h4L=}oWp5}ZV_p#{*^9y{XoYw7
zsdeuCfeMPgQLJ4o+MD+}sxjIx^1?nN-8856+b+Y{=cVF#N*oC!SLCH(yb%O%h|H0$
zU8WPck}G6sM1yq21{oKfUlfizE%!RQOqxav!=1<T1`j5=aZje?2-c0$YIxIWxP|1B
zXTKt?uUW~#v}M5SRYIS9AsYS0ett!t3`IYgK!i#CmQb@E+RFU3<TcMXv;*fSS<Z-=
zm?VPHPxxlG48`an&dOA*Fr5IDsok(1$gO9(R&CIYwoP47PKXyxly2ufL)uLrlx_oW
z<aeFkCb-86FubpujPjSofsB88=Rhyp0w?P?f9)~9$Uy21MWqk-7Avwo7E?a5feWBs
z)&<6BUs^Kysexic_#Fnl>wz4^_XfZ`f|Lf-f=sX@>>pqW^&4?LmvZ@Q^yY1E#)GY6
zU*-l1!j#nnvbw{*d<kra@ZyA5fahu(+opPTBE^e?=c3$v09(hpObgtA^-}G1ge1Up
z66-aFM@ofyA^~lJj=$6ag+|7>4w2m4B=y+j6!y<&`V9vya>^;Z$ha8`SB84o9%uvF
zgH>CDW8m6X=^OGgXR_Ea-2VV&91m?ETxe(=yar}~RV&-8fUE|)c$E}$@iRDG@6v=h
z)LEt#tQmf>d2XZycJVlr{;TO@n#rP`_4PQjlJyUGJU&Jv)v!KJ*fJ&~GXKUpFplq@
zSBTcN>yRf|MrT=MepP|&dtrX#s9Ft?se;(MdtpjMCX<j`+Mt!1?mLx`-;bea6US2@
zgqGlP(!GttkVflFy_r)Ai)2D-$AS%Ewb}=^Wg+S6jOqf#!LZ<9n%-Rcz}{p*;jwyI
z2blyXhYz5)tU+%e#@zb|sK(|uX+RsYj4aUkmLOQOjM@XO!QSM1(WNh218L?#1k4fm
zD2=YcyfE-7z=%+l=!}vABOv8Y!Nuj7`e4Jrh|rh}goL|?;IjaRA<*AUA49a66neE*
zy-z`Y-t^(vTr;0-fiiv}!Wxu>$0_cA1(SFi+a-g184E=P3*Y(a1lk{-<)?*#5X<?f
zgdUE=q}BTwlc@~s9Fs}u_!l%sUm%&&q!SG6A>-zG2j7bW<Lcbx_{FtQPdC&BwvD@}
zA^0DdpO{k}>FEy+!3O;D>!a}eu5RnIp#+3J<U-A$+H3B)6!{%UnYcWYYyi;+2YvPR
z@zCl|ZX>}HIl-N-%x*FdmkPpC4?;RN38ib`<-&(Jzr7_nA>5@<6X^0o@RJfI$&n$V
zN$OzH62d}FA~}2G(Qe@*ZG#s<Q9@#IK+j?d2xTgA0<B)Cd7%8jI>8Ddyqtn11H(FX
zz<c#T&P|+PnX;!>Q8ovbCak6)ttiXD2)M>cgsy`15D=hobpnxVu^|e3MvAM2<N;t-
z^z;VzbZ0LCTO{u*5HF)tZ#|$X@mXB|JFfi^Wc??u&Bny?Po$aqe}`k4KSIcV#iSYk
zuXyZ#hhO!RMjb+!P{beJqP0t6A|t@1DMHnX@v%OaH4=l|Cy-*A;?{3o@a{yZl*4EA
zKdx6MM(nQgaXRRccq2DhJBJy&acr^}h6o>CvGAns8A&#*cW<xA<!HiYuGnik+pIEG
zRs`>cAf>b0)%w=E#v{XlB()eZe>n&1sBxvOx<7tJRyfp<Qr8a|4B9r}d0&=?k!HKV
zmp#~NKO4C(eO%=eA?jhp9T~&I-oQo3>Bz5`X$-f)u?d@a;~hmdIfA}fgH+#3E3%dm
zSLcb53;RR;dDoxhHJBSyL7Oa_m6(`Jl|%qGFEU2d?9=bb;yhN_{X|yTt)wR=u@aHb
z)9K1J;x*i=x8lDa3NJE&{4R;kaLY7Yw#j@7N!PeEzwsxX&a5t-{n8)UUL7>uGV4#D
zCHL{bs;J&@oEbY4r?*}=t{N;g{ro|*$xD#`x6S^t#J`Nj%F6za&6qy||Nq3$|Bl>$
zU<+dAuBI;5PHv7aAA$J4;06U_dmwfoFQ=ofElw+DZey(Bt_lq4|GQqo*xuUC8$kVc
z72u<e=I=^7V@qJ{p5@;yMgB$?=$V;Vm;m%_94r84PHt8p%D~F<FO)&r&DhS`RM^4N
z&K$t>S3hA_(+`+}n}zEy@?(A<G(8J&DIYTwHFlCRx3;tbA{oG8{$i=RncHgsxc=_{
zK}h{We5?@Yj^-?Y4+P=A5rq#3<$r7A@8R4{-2Q@3)PR`9ho=7GiWs|^{{_bUzcgd*
z;_4=9W$f~g0_2SUMKiPf4Z!?Qbp!q~$lsqBaR(r1VeMcEVAQmB5O#32{)h3GWKC-`
zH!D{lO2f+hv5Nou#md3-uX+wvV6KAy#~TP80c-y65k9!=oF7Qm-!BgKf6AO(|B=f9
zbT3ZU4`2GfUmUC-co9$z^FO`+ZpXs;pD~yKY{12{1AXFSJ|9@m2l@o$0N;OsPe2gK
zQQg7%1IYn=eAoQ9;r_Q9f1q4{d#9|m*@vD!fH0MR!&vSgpx1w4NzDI^lPS44nz@?-
z(IaY8V`~>j05bzKI|Fcu)K+e8PCSf2Kn}>YbTM|avNm;PaCEVx`P<b+f#{!`wWEXB
z2bf1K#>2wI!otMG!o|eQ#>vD=%fv#(#6<JoLjQvV{sYd58Uuab(ef`7|FwjFL395>
zy}Vq^E#Q~{%xrK>|Goe~v#_!QEC7G=I5;>z6#j7m9R9^)2kxl=esTZ*c$}<2P5uua
zkoYjt|KR<9Gqp6w5Hm9~0%lrNb!G+zX21wV(F=5$8HPGjQwv~%LsMr7oN7c9GXn-7
zhL|}Pb(V%m=9LsB0&{l}cwR6#vnmx7R-i&6C_f(<>7X!&WH8UXG+^9<(*<NEFtMlv
S9J*#^mS&b*s;aL3Zd?Ef#A+V^

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..a6027ca201421ad9d2782af4304b31b09f22a614
GIT binary patch
literal 67677
zcmV)cK&ZbZP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q${qkhhEflIM#e1|vq9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R_|JK*d5
z`wP%!{}g2s{xCbApQ22{AG*DF^oJ;u@P}^J_A@e@-*>TRP_UByB>Zc4z_`7?Ma$k>
zb^eb1|CSwK*Zm>NX#Zh$(>_I+gg<n9|NjqBCgBg=+D%bLHxT~N&5WXjB>>@X?f^6Y
z(f;uv^!0DJ10MgBWVFAZ+jV`)G1}jEn&&RX(fY$Z(|@_=`@i69Y!mW?V`r8){i~(^
zy*sbp2>riF>3Ke-_xTsd?xqKlVBZ~7?+vkdRoz5*-|+w1b6~v3>EnH0e2w=t>c3M&
z{uWE#`+aP~MDyFZy^pf~W>|F+;oENZJ~!8Yu6{-NzT;aC)_&hQit>F&AE|s-M^XO9
zGMK-$!1+E6p6}P;Z>)mN_KTPm<@+gK&o6>jl<zw}^JC%J{<c$lt1O>OUzG1VzR%Im
zwJ*xwSc&#NBl`2l9r5>W#`e|$KgF#m-%oOWJ`sO@73KSmcj%8>KN7z0_PmwV^J6tc
z`L<&>|5$sr|HevmJAcf(kH^1TiNB>H_HMrjTT#BB-utolDQrdgzT^9G`ML5%`M%@(
zN%Xn$MftwtbAPV92!CfSp7*y>S^0J?{@&I3eq(+LTT#B9;(F8i$01yl?>qVv9rml2
zl<zyv8O+-{it>HOyYHQ%^*7eR-zTvBc~AT;rSW-w5wxOwJGEul`4BV_zVFuiFRNaZ
z?>oLbe6D&?zVG;c>wm6#QT~qVG~T!2{NtYZd%DwGP5njCit-21{?tQ1b<Ee-uRr`R
znQ~0`pVq|JJ16Ja?)Og1+5bA_|8LEAJI33O^KSRLP~R$GnHvAy|0}-OIqti?zdGN#
z!nr>G-d1nk{$oLXZ=SX^k$izgYl0=q@)vJ|i?+O?I36;K@)qkONcq?U=}k$M1C;l_
z-jt7);Z+%w^(J{!-ZFdqLTUqq_0+h|`0)=y4R=kW%_q9PzK)&b`qa|879}lsMZt?Y
z2=D*22sOzV*CN#<-@@~zT=9iZN=<vL_V(|&zQqZ8JiKTTDazRR(!<!2CpajJcW=s@
zEyqsrjWIo5cpd{vN*h5aRt15Ut>Baer}_^v!5nrTeL5+v_+-JSw(;rBo+C)&)4OHG
zqiB&o23yjJ2WwDbGO?cylGbeA2L!oN6mlg$(8etu<TGwj#?TMNvW{C^uw1cmNxm(Y
z;7u`&D3)N%^-=y%aQsbjjVL(&rkF+)>>NY9v1H#E$s>?rL@xeV@NH4ZqceBh=;BfC
zfJG6H&ScwY;?W5nHSy>Kj~X}B2^Qrl93aJjOp<egMJA>#gT(tl6U$C8=={N-eGmNz
zf@#FT9_PkflqG*&+cN)nQB31q|9Y$W_tq=8^QNHNl|r#7=yp9YG+vO>D^Kr5=ud9F
zH))+5cr7F$c;k}`fyY_cD+hl#IN_76_Z*$p!bJ!+yeZhuixMBE@oZ6I*3LCq3ds9=
z$09Y3Hbep@kEG<JyL#Q2bZ4g<bH-T=Qn0*nCDUNI2w2EBA*V>2;G*OdEtc{KLNu|E
z*NsV@T$1a?(qi@B?U>@Zb+L8gwf<~<Vn$u7f8EjI5?(o-&I5T7)<^nXOBl<$C|tsH
z2(*4xr<hEq&23R)b9b!!5u{k7UJIW}%%X7NuiVOgvb7edkLqzmlYc%j`oUKGoJ&yh
zQ;R}DnYrt_A86*l`_?4~-nT9}Zf*ECWih_zem{~DTdKFMS2A7~@0C~0qENW<u3wZT
zTt`rX)w+1Ef$^SOrw%iH{Y{4@KjrUOq~K$FD7GV6+3xBUElRAz_^$)|O}W;#YnOT?
zUl*l%1^e2y^$Pa2x%J93s?Duij&5$<a(L2yE{_&_&^HnDIzWmkxO#L9&$nJVJl(}t
z2lMhWK0pfY^{rbDuW#LAF<aBepq#bb^GA}>p;EgZ8d0;YTaHMF{sl#(<)M!s3W00q
z)-6YLZrze$(#W9UHG6c$T)5%wQ8!%P_H5l^L{@@<d)e-q8tz=XDNeX@?b><;i>!nL
zcjueZaKz!Fv=R>7i#8?RxCCwTQ@Ha?n%cE4v?D0hDY#*EA)N1)E`y1C$#gPI+(PEM
z*k`IZZxUL`g}!x3CP>v@dTorpXDi%b6Y@E4dB*tXc`KOowKpNZD4lKI_-blGN0Rch
zwsp(T!o&I|L<2|fyfE35hkWYIZ;qW0d!$Wl5pXR`9N6c>+XPR{c1kChsi_@{grAB3
z%nma@d`iWeIDbzG#l(SoUfReL=j$n{n0YQNN_7kAIw=(^<Y965OsP1MwAgz}Dxk?P
z3Z&vq$w~4za)Kol0~hEiop7cQEehEWr_R~6YB(6rt~FT3!__uCv8H2^ROn~EW*31g
z;L##8JD91nV|K2hf%`o^B5iSYd_%Vf9LI}7p7dzpJu~w>d;g7gN*-CJ@Rdaw(I!Ju
zp83s|91CYGNzo!F44;tJ2(OPlm*mRg6Cr^I2t7Q;dK%2si<U*6>^R{>E+IMLXP%m0
z&U-nUIlnZxl<Rp>+6V%LB=^mmvRdOwJ<lFJ97gP-MZg?Kp0A67IgSTR>YU?%`ngE>
z;rP$s<9ba+hsL!VH`t_C#keu{rZa2YU=;r#N3Qc^<oUcP9P5PzHjVYlXPZ6JG{=SE
zL({|)ZM8Yx47jjcT1Y<Hf<n8($Wwihz}q)vjpI$p*85+Ql#zG;qHts*U+{KIRPsgl
zrs%L3j&8a_MsCMN;b%QX>rFy)E%`mL7l-3V2lwKDSN$Foz>&M%?)cmRQZWDKgJR_S
z{Y{8g!*A%E7}#95&WX`DFg^YA&1kU6Bq2wq=f%LDy7{~u*iv`s00&4REO?wJC4RU>
z!SKT+3MYOzCE-X?t|3L?#0sAL_9^$;E3DBOLct)CMG1MZOOFo6?znWbc-}g8Ng?&P
zEbaXSz|Qq`=d3m_ScmM((eHSf8r}_yl2?&kIyMl@WU2WdAO))~$&05x`=(^;{VzR1
z9CCh1SR6mKNRSphW$luo$S2082dNK4m*}qXk(0Bs@A<&kbdY#hqZVOgGya`xp#YX9
zIq=km4Z3Jja%?gsxnpd)eH8g(dgUV0!7e>t-jp1hj7;9aH|Z+g-z}Xh-r`NMC<E;g
zt;S}q=!sT{CsegXf!sqkJCYRQIi=8gj>e`GTD++jg;IJVMCX>8<*A7-5@iQh#gsbJ
z^P04>I`+H@X1#Lz`tK5?ej_+21gT$W4YYFTx>)cIw%K(P_KC6Ursxoxshgtbj<%tr
zv}49;e#;-il!rDHo|HCZRc#L_bECwFMufl~K`{JDu35tj$3!bu@O@14zs4F4-LCCQ
z+n(VhPtu!*!zm>#9t?{x_y^Gf&og{x5vW|Xe6!o2iPiD4ToedvOBG;Iz@(Ncz@ixJ
z#BG3+;%yt?q_z(poHnGmH3!=o^^S%uhQZ)^d7rm=-?R>%=@p2_=c15LJsvrW0(orj
ztyHGKhPz})wQCJr&`SU>QA_J!&d?BLCXKJ*?r?3hh8^^#476j-{ozBdLDTX_YnabA
zD+6Lny~=Nm?~E44W)IFf*ZaY8TboNn4cCH8MDa{rl!12e-Y@AyZ&D6lCP#x5x^4l(
zPV~tm!9oZ<^^+y(hC9Gzq%i0_X_d4IzEO)X=r%5^h0PSvMS}3YU#R)v!DY1p&grVa
zyLC|p+OgDLZ&h=AOBaRV40r7TgwmQq)D|U{q|@AFhywI@z#2r#rFvMyXQYE#!)J7P
zm|;VgwbKk!$}UjUT^EPptaYg(c)czP4=g-i-=x(#pI9CV`}tsXB<v?8LpthtLw)oU
z&5(;Sj-HT<F6YJ>7R^QAuR`<fdEJ~TLDnVac%v=~e<O~@MZo!R&S>R%d5*NJTGzF5
zrYtN97V5-3-XY~@8n9LyQgh;h?o$`^nP;7qef5Nb+Vw;_d$b^oCl(x+Oj0nqiDr&$
zXu5`x>6IO?(beW`anbbhz2Nz2T_T=O&_&3hcDz6rWuP4*(s}G39Z%3j%F!-LuAfIM
zHO5X&X%XT)k#ToX^0nGKhT9)#h_d%CO8!i;dbN}JwEy;JVv4EGBqe9ajj|}odv26B
zC0Z@#hs&qa7}PUhaE;BtrA5m5;o|6z=M;HwEJ9Av^c9=~VN=er;kN0fPxYALsqa8-
zW5|AgU>E4LHy(?Wa(?Pdh9x`2DJWwyO}{D8B2P}7`Rx(=&s<a*suv;V-1u7Pcj{P;
z*(!?=hefI$2S_pNMisB$w*sXH+QF%IL!cHVwsyk>bi7FrhL%4Og3!26S3B6$cpG)R
zLQNL&Maj27<EvzmTK-PX@E+>K84mDmYKo~ZEsCayTcJ%&5%1hKF-2D=PSK-f7;VRS
z*d`_6?qL7Wmpk~+E#KkSw>I=)o)T@~%T1m5Wy?hy`Z$!-HuP<%70vlr=^5g;DEu~b
z@aFpVsb2Bv3lGjlYs|4o?9})-xze=H^o!EbIqz`4S>x^5=}TKAtoB9epr>F_vJ<5F
zqJ-!$!Nb$imvDfToxlggfLNo_+2I!o3VsGkLd*DxC981pSZf-ML$Gw@z&{g|lYhfr
z6#9!91UYYLqD`kzzAl4+-+*DG(X`Oht#Jg2gK6x=v6y;sET&K4K+gb_MZne3;Y6@@
zYN4QMwo~KD%cPxLsQIW99CVAsURbO7uopxY4@PTvjxGZGq}Uvbl%3+g!?<QT?q;3?
zLCLYre9IUOBz@w-HaTTFY~p4*6=48h6b^3aTNqqQ#9>B*{UV`Pv>**~>~zGa1O=mm
zG}uk6N{8LqjQY%?u-ibJov^etBO7w(jv$R7VEfOePS}Dp4BL&?`uj^`HEch-G*~=3
zOvi8JYeXAAnVxX7RGa#E)C0ckMT)b*E=u9R)nW8u_HnBl#!AbpT@p;%T1{v6NZrx+
z$XJ9p@(lSNix9^oo(_voW3m(GKnp37PFI_K!0nNysGwj9R2}FvdsCtT!9dK*qTtNI
zYx+&e*85+BtRK84OjiIcoi;cVrVr^(K=6whUq6eoIvqg@f~gayV(J7rhmq0-CxZQN
za{Mk*%Hz=ToDi<);tvFi?!O)n+119vq_y!#QqItCb;=p0xls<oj%R96@~e(F<O&o&
zKu9TZ?qk0oB)puuW4#%W(4Fh;c$6(lt~kBc-MQkrzwn@36s)Mnug1Te>&Lj3?$8XB
zUD>^3Eu<~ezGs~r=v+VP&&nF>Vgi?4ccSB*H{FVEJgU0bU|2C-ln&Fg!Is&bo4Her
zJGZmkYQ1wi>o)D&&OKT;xU0JrQ7l18R&<z@gOr2m@P8P*b-m-UZ;h<z(C<wee}^k_
zk-!VQk__3As~yr!(^2m{q<6}|_;_Y@p3?Lr_s&CF_j>Q(79ZigH*l+I=OD&BNSFm4
zc*Y#-o^K74le*Ko2+ENp@G$=1gmf~}Wl@rS8zov;gZ5BD>D*kTWM@%sWhi1*8f-lu
zlx1;Slw2n$>n4wSPvhc8I~gVArA_5VB3`u9plCE%EQ;aVq>N;gG#(lcK{=9?j7pDf
zZ!T7`O-5n)8+YMO39FBpRH@d)h@!L{3?u}K*e4|&kR}BTip@r`hm*=pNL$)QV9sbT
zinbl4kw)&zx%Z%@rU<vzh}r_oE;Wwx5-&0QbBc9E;n=A8pF`XOW8nMW_<6bpSQIcX
z$JeQ$6@k3OQlDLOBBhn!rF@)?f`_vTzWq(|XiWK_Nbr)Mr<LG=>1S=Yl=`#w8#cyy
zZmmXRiZ<7xNT^8K_FM37QOK#>#)|?@k&p`8kw?L5^6<*jqtSS>QKrtWJaSrO+2K$+
zK=?e&+B5dU3>2PaAy$jPqpYXzvcX)UbF;x^kHZxdUI&gT!O=^~5hPv*`Kea70jALE
zHt_smDm!!>v<IS~TctgxPJb@KDF$*8PB9QXzf-?C@`_tc-IF;Onm%-MHX1*SUZi$Y
zeeEz4wHteoH}WEMT;yQZP5qTud%L+S(;Im#LLa+6@TP3~Lc52w3^0nO4(c6m0@acn
zm#YVubZ^=W21aeh(VFM394$&XQ=~vO<V}>4)!<&IA{GRL)<upOIqzbLNiEDyr<6j@
z_>@-28K2S$(|p)y#E?GPXv2`w+O9{vAP5;{oLX<Y5U*Qmal5GM&<N8m1b<MyZWk3D
zD&TL*7Zmgy85N(@;oCLU0qc9suX+Zo^cDVnu4V?O?yrfJy~1|@*6-q(Jke_Te!=ox
zT;8c8;^G=l&ZM&w7K>I2J)GLb6`q(2G^2WbH5w`SLJJBzVM0`0r&i{qSWGPqU#6Tv
zy-cw<ldlv$I~OJUz{%6*qfVH?te5FPo9|LgVBYEz$IcNsGVFu}n3uX?0VW?R*}@~`
z)?g>XRP>-<B=jJ|=U^|6mI~30(GGRNow%}O&<BU)boJq2c|zYBY|l;)8lCnOoOTl?
zOxjA2MN`%kX3><zg-JB9%H-G#n}xQU$flve2ZJ+p<KS>Phlwb1YtmABikCES!^{+^
zHQ9s18#Hj!ShXmjeAA@$iqsl*1MlGfFU#1X@LLc}IQtLS*g)zq%z=TlQ^-`;5D`%3
zyaqePQ6|4eQ-$n;jiw6O4w<7<=0)V_tRKp0r9{v^ndv#SYT`E_5wdfx^c-~J;=#=?
zgK1FGaNIPO#$Fr>-bb*_9!bhxx;Y0d+qx$iX(cmo8>UVp!$Km52L@-Z)~RkdN07u*
zMrkJT$Z&lGX_RTZd6~As3tBQ@Aa7~NkO93pVnWKw-WVm-bhS7XIa%u)L!xBSU+FqG
zy#NqgpXxTyZe#NtG{!v1yAWADr#uh`Nc3ay<K_F{$IJJ@Z<qIDB&U3HmNc3-@Y+jC
z`aX1OJAEHIrM=N(b&=sXI^^GJj8l>mXeIGnWAhU&Laz12;K4}rIq7O*l8<~*Nb)If
z6|;Qk&x#bEu=&a5wMfZ*ot+(TFZs?^5>GAw-D|DmG?ojlbr`vIIQ9$drzfw$RlO*A
zE7D@p9{Qu-q|G-NIX>YtrT=hI(o;z%<4WwgM!6wdI+c&jRk=v%kJs_l5s!l;njnnL
zBid*_Nv~-Rjox$Pm*_j!vDE21*TV(=U;1#5OaOutm)}BgwEVyg{nJ+*gcJ^WlNSNA
zlm_1+9CAuWMo<h#hfF`=rsnG7q0mcph95Tl<Bic>@}D;vUF2kcQ{;kQsX!_F^3u1)
z5DGf-8w0$$4vGflLJ<KiO)ke4G!W@QV-GA~c2EW$tX9MaObr#`TN%7?fRx;4bVI{I
zR1px32ADoIV7Sn8iyuizk%Cf%1G&O6m>N_e8!N{rhl8+=)_71T?4#j&s>qPY3_ADd
z5oY~Vz)2+iWCVsbTVwcy)Q*-(o*CG(S{dHN$d?8)j-S%w6<a0!L9tcR77RCsvz0+S
zreD3G$}4WC*}cW}G$^VW_p@600lnFwG9!5C012T&`jK3E1tGl&2vCZIp9uPajkxil
zVy<n0=TAjFH9VmzGHOv6as{EyN8f=EtE4CZtKkJ)AzBSj>k8v)c*7&q>i{V~qqh=l
z6N(vo6A(_;(wI}xX3cmkxE?Tu$EKpzR*p{wJ?Sw*`<tTQA~Ps%3coZtN(@B)gr1=|
zyM}lxM&hkDqWSm&J7F(UNZ+F5@<`xMXrzh?WVR3@2lI!ZeK5Rm5$0L(hpXKYZOG9<
zK~)svu`+`qDwN5vkvy~oLn3vk;w70nR56v2Iux5&L6_}hM5t8ZlM$iPdruhg8Q<Ap
zVmu5#t7uS85HUImAzhh584)UL5si*RdB%<5Ttjx970#uAR^%2{%xg;%q@rRYyC~-;
zJIDz$mBMQmB?C)c^Mm%H2;ImziW6Nyyi7W(NZ&|0@>{XMtDTHn^1c#^?!iFf0~AId
z540J3oIHuFqOnITFG_~iLQoH-6`7z1j8;j-N3Xn_3@xYXA9*(snhibwP~r`uvEz>z
zTJHKjL(6l-m|;YFudJ8QXe%6ik>a>#ym%zSR5<xceHmN8c_hcgsBU_^7Ac3W$=r-8
zry{s0IdVRk7o{U|9;W+63Lz9+2XksF;68F{BIf@@E93p~a$SU!C&crwbeRW#abw1*
z(kUTe5yqA>U^M>~9LXZZ6fe{8afB;DVNqg=N@7@)*r}INFb#+?NQVdtEJ@6mU~&%A
zDOP)I*%n62p)xXz0a8laFkq}yYKH;Uq|!f3Aydi`F<^XDA_>xWwqz4S7}Yh=7|c>R
zKuF$E17a#q<+~W*Dk>+&fJK44nFFL;S#7Kv+NAPtj5bQ8=tR~}d`xk8b}_Su&kJMh
zl@fvskP4MF#Ggb?(UFw+9b_G?c4k&dumD_8$x9r3B{&_H@mWfNA`_H2WdIPU+$sZP
zK;>TrclQh}%k=-s;xfi-Mc$Xu1j@9qMToyw=GdYz;S9pS*e#`?g*3%LperoGKn9y#
zNPeiSH)9x=GUFB{XM1bpP+OIBXPIk$Y&m+|WJu&o%9iNI1Ry2{#$H|@&h)_pq{ykP
zwSk>Xd58w1Y2_*!a=|l~F^-gjxsD(p)ltJ@qNYyqi6~;_RW8akD(lja<XwrGi;~0V
zoyc6GO7L8i9KP#pnM~LmXk}I<Z@)zuTbgN{*ZKF{P?Hgc4{X?P%9hS*wA(7>by1i(
z3$dXkw{m9<Y1@@vYc%dE1$W&@$tTIdgcJO^Yletv1|xC!D-n26+SoFMjV57b6WfGQ
z2Pwx%i6m`mVWuSQQ;WzXZPOyg28z7r1MNunS8lW^OIsI&vb3pV#jSlR1^Y-!eo0$<
zI#R;5x0R<&!<|K*wyuMT=XRxxFH)w1yEv1X+5`X2EbS5%W@!&yfiPiHM}0|EQ3kxF
zQM+>F7a`||1K<c!U?-fHSeal{O2}V?<fW932_Ok2_8$RdeI^vZz@Ov{Z^@X&3?H!{
zxJ?2WSd>6*AO^uABxu7a?gM{GSOzwU7;&-_0V5P5Y7qt4<nmwb__TcJi;`#+O{)fU
zBf5r{DhqfcIcyE#g9-1jTKQ$dKP<}F03s}tz7HTstmb01+=qrp!$P508fku$hF3!#
zIFKw3kP@nb))O1R4iY2=Ra>EE*dS`eWC(01#C~t+8wU4)5IPL$;sxSi8Pr%fA4e$P
z@iTXI8ZsATJI5mJb6m*@=4dWLTwjGu@+Jwo<P|!9utD%9mVuImfMQ542TIBT(vVFh
z+c6TkD3G>TfGmp;Oc7|yvEC<5LDlQ^lE^bnUGfN%N5C>oeM69mCr@Cr$+&NWusyzY
zOW+ybx+TnuZ@m)aO=kD?3QOdfp>7Ul4R!Mz;@mog7!(Lkyze%g9)q8yuzZ4Y+J^TN
z@5UJ5#Yd^Z8B@SP>%Ex+EQtV?MJtH_c+Ue<sttnoJX@!P%6Ya<3C+aIWZ)<jIMNYs
z<LB8Blnj0!f-Eh<hQY*C&%$X6N}T8dbK<kS$*gM#cP&t;MHw4x)M^JmduLc#kYc=!
zR-j1v)+0fr>U?Mbk;;K1yT1Ui3`hWlkOd<|0%#d<0SaKt5OE6-t^=e|KwW9-c<v3%
zi^dP(eHjqy3KHxHlHbG)!yo0~Z}!6RF7z=&bZ?=P**M938au;cvpy!Av!M7bAT&cn
za6zRRoNItnJ3xwQ0dUO*f%57sz%?O*C9O$9b~}QU5OGpE$64@j%OVvs5`vsLG4U9!
zvM7P9MIbsFwhFAy99TrcvkPNbd{=4%0R4^v##^ME<7Df!4Ob5)wu0VUgq*Sh+s%oJ
zr{(t@^e=3A@eLZf4Iak=4}`t%*dPYOC>URQwr;tK&(<v=5w+3|NJ%0d8opYXh_pWz
zYGP2vj;v^aiU9oL0n%axZE{RQE)Yk<lndx_Q4%q-GjcJzNCR-(pR%SIT&o2;X$Tu{
zGM!n#CmtJqr2(X(FfM~~?l_nR7cIatNg<r(0Yb7yx}5`quZ&|b3In_ol;F%w9I-{o
ziRwkTQ63E^xHV77XPziT9E~5ED1agJ&qg7Cfaxb#QyRA!wSgZBCK4aD2vX%U(w-Qr
z2AMAyR#1)&s+ETILURquxg)+7Wl(bRN<9iWHb@(`EZedJ`V<~5C5M!Y^NW=$)8Ixa
zMkN^Sy)lZEjZukDdl#dU@NA3<eA?QWBHS8o*!c?omwt+Z2oB2P9YKV5La`;BZiPln
zQlb?bQXdM<xF}we6eRM&rW7BPvM5|-QSM%!R0ttk1A%z@+&wq$kg{=O4f)n9Tol1=
zX!7^HNfId=#}*IoXX6+M05#)UJm<y`5H>Mb3;NhD2B6RoM#*?=6N4bMZK5GyPut{x
zlzW%kjEJ>Q!F_6<jcC;_8xdw(f)mHq<MhUBM?HVpW6!q7Vq-r07K{D-jGb3W+V@$M
z%-OeD923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY(MMR|Hy{?uHPO=h+V9_1{+b
zb{)o~)L|SV)yqDD6MIF5*J->Kv!Aw|#%ne!=DbehSh_{3+iHDfMYGp!wSKafu>&_z
zFN238U1pK$y1HXTW4o^I7}40St2;(Cw(IK25zXzoKVw95yWK5DbZxhL^61)b_hmL-
z6td_BL+<S|PlnvvWxj^C@)Nq$k2uH|X=*^h5IZ-GrCaUB)M_H@LBk7PYz7MGN8N1e
z7R)FU#TrSOCxENc6{ilZ><H3DrP1Qkb>qc3(iNRe1+Xj0iwfc@ZXzWi&;5=FW-6Lp
zk;ha<yW)tcuy#fPA781|2Boyzob~)vjl0zo^o*AD=;T;0b42QaUE!@%(HDi!t`l>-
z^^8hI|5zlxqfX3`U2=vpW#U2673#@HM{j4^PV!~Z6{E?gOIP?MpEq5Rm3#s9CNxhz
zlNRaYDb<?}V!XDx!W;P_Ta@T@<eP1!234O}BE=x`>DQaqK3|5txt>v$mXk%QUO5L>
zuZB6uRe@(}N01-hu|2I1`#U$1rqm~AFx6*d=GEAr(|t2Oz>U{8>qEmLTwAwXgw6O6
zt+FA+>5+zqgQVd1^JzrrAC`xZmJiEANDM3wWv}QmJ;0>VKMW7C0XD-!GIujRI7EK4
zKIBc=i4;OBOy6t|dGPkl_OSNu$^nEc9p;|i`_|{mKdCM`x-vgFhUaB6%s0v+vD?7#
z^bCa=tM@Wb4vep^<}`>YYw{(dS!7nKTMTh---^}km!4Z=X1?aR8}E9r(;yC;Nc%i#
z@XN8>Tc>dZq534Vo~=`i<k|Wpv-I2<S7fM?-+8xpFKLJ~Y!TEU2jY^3^;+w0TaU04
zF@ZKoYaHIHOEAPs6mVf~)(BjWUc!*fSQH94F2gcO;Ptl>g}IS%vw7)huuU%#_g^w`
zr6aT315WU8$UDiYp&zi4N18JahbK5O)guJMrEtRz-~HNpr0Rf_>z6G0%*uYr>fg(B
z0nb1$(?$3WdSFe`myjQSwm$iB`LE%n=>Cf%qr)_Gyx{Bz3OnW9--oV?@R;;L?@4@i
zNJE%F)#^jeYxrgO2Mr&UhL^6LUIq-jmyxW0fE2PmXs^l#bXUv}{Y-sGHsFiuIGMt)
zghNy@LiB3&A=!wB_kt#%M+he-!hz&CTLi9{2i`&X;zE+k<N@y-Koeea-~m|S04ZlE
z^A$XSy`qNTE$oB-#^j_9jd<E0K_Tx4KBQ9vkNrM)kECa_4_za8{`aAfXnIKdl*XS<
z)Q-xd^s*A`;w3LE05M_*!B@LTWK5o!ivq^rKq?~&+`@e}i5Oo5QywoknEUK#<#%M$
zp7Gx#DmZFpuL(l&E|W_5!CC2=e)0e(8T^qrRAvbZLIeBM;{hJ|J{b!Er+uGO^MjH)
zW$aAXf3Gq?3=im2R}4Z30Mqh9BvY>lECeO=S<X;IF7&BWBuyTD5)F|d5sQMszzDJ^
zj73?RmqMu!bU}2R7b7zg0cS9JBM#|{qQH2LW04Rf0*&X=!lS-HzqIfX>$KV&32JX&
zx-w9XfnY#M$zRdKKEhD~Pe>6gv9v5#bttH%Uow6o@TFf2j0tJKq&gsWCJ>PJ*qS3@
zlJKS6GZ#;R090DoOPuk<NMt-in9rin!;Vm(e(BK|!9s}x^-?rZXYFSO9QCVK8Buxt
zs%3`!|0TAmUll)tOH;8;X(CAQt38UU-+D<P)T-aQAP|n#Zz&M>sS1lP25=pL&1H(|
z3U=SJ@E{bd-+WXeT8t=QFU40K0Tp(V6tZyZB#6kg)n?FHJ~eI$2O`@Rg>fnfe+v{d
zj1TwKJ<!T2(*}evyG3BMTgORp>k5f@y}(>!v|9-Kty2L3fBlwC2$n&Bx$S|2M0|TG
zx^Pj*J6tq3twab??05d^;MnLVN2FsflVHR`5~=RRP%nbny%bLwh<A8fWz1!eIDXt2
z6`_T>^+$db1cfb%_>T=xmP7=JE(*gXVGnw!v?A7Y5%M95aMUitB0^RdULYkXZh#8p
zx}O9X+(TlI1R=z%aZHyH5fce;!<-NTZx=*jQG!SP(Y1k4u|Q{hNXhZ*20$qALV3(7
zB3k%Zz?K&&tCN>`4PnQAYHuMl*(=-#fl>>ElPpJsb0BqM&}k$goM%Nz2jr)dGC`S)
zz0XHx;Djn_JG&_%0a4olIQkLU?G<Ol@Nbt@4l&|^V#>(w^;Tc)uD`g3fKMa#zDE<m
z?|Dx6d3{wF`@&Ie{LjfuZX`y-FA7}JjHPl}^cYg_3QA(sy`PnTFu;S#FGl#j19L<%
z{sAD%`3>;k(G25)3C!8l=QEkW8M=gI0}rbplMw>2R_O`B0#p9(iHnEOx0Uwbrrb8n
zZNcYq4RdZT%OP?s4q@z8B8HpN4?-pNgye`s4lmpcq<XkDiY2o_yud49;Pe8fKw60x
z$^^#krqX!KPjR3@AcZB`7YV^PCAeBk<YIglg)O}B6_7*Yg{Ocqd0{0W8D}9WGvx(I
z;Vz&9^Q_H_4|#HEXnKy%Oij=6nOW1zz2(FY0FGH8K_h1e!X=~TN?vliG{H=ESQM-$
zQlb_GEV?imrQRT`YN1&3XOP5AsB7hB#UJ5!Zp=ujpGfcWN|eXH+;qJ#mu!*H4Y_6u
z&l}y4kLH!I-XIGZos~b7A%k97<*;xPUi_sDIj<CQpqd9LInDy4+IeM+2Q+%3o99{~
z%4$(E880QumHd4)m^fWwTuc`9O4~+4;i6QUVtmQbh{<`Y1WK%4s{~3cpMtuW59zJ4
zC}XXUK$6FdaGx}t-pI6El(uDK27$wUh+)rU&s?WUsl;{DCR({h%Be)gs8<ekkDzOZ
zm6l1TtBs)}G1X<cMfPfd_A^g5H+fTqC+5I<<xC?_)+=WkxwPK65jxlXVjKd4t5#J3
zCdzh9k$ITN?2SSM_>^OoumB#&5MG3f3B$RHLYP37v2R(@BPXRi%?@mL-;$yy#92wv
z6Kf`Ph<-)g1#&8n0q-;<GOyaVEa^N4e9MxKxq27w18kct@o>D9=IvXWbUvY@Gz7Zk
z_2ymsu|pf_(C!#=wFpe3Uyqj6W)eL_q{j~+seKhQhm1M07+t}1$c|^h^Oq9ny^^Mp
zWbaCvcAN{nvf+@d@10K-CiE`~Q35*HNe|}&1z4^8QQ+x&B~b%bzy%`C2rTaf%8+`z
zcO}s|6e{mR69UkIS88=S?w#4y@Pm6VV1}tKOyCCSg7;s68CDe#ejIv4FJOiny($$o
zKp+-jpv5lyHg1B>#MH>WWUY}GgS3t)NJ88Y3Wriw;bwDL`3ZZmC?D7u`9nl9F?Az0
z21G=s3}851&H-X|94<_J;CU<pfK@s=>9$3#q%+k!eKx4XlDHubsp2sNXNy<vce+x%
z2VdYJS%qF8@dG)@uH0~-pezE%G1Y6JogY!=ERr6*(=<&`mMAHMUx8xKAGETE&MY_w
zygyo?n`09c4($A{5KLmtc&8<kcr=T`1w!=>ubgxk;DeGfli)W|NCzSVa2!`CCjfMg
zAOWn$)Qf06re66MI4>%f9hUB(;Lb_IwpVsL%-F2`^CEQ6st<%#bdbI>okJtC1i*<{
zV(3NuB6nJ1iE-pEl?EtCQK<-5HO#=S&{F^`1qJe*7)&gJ^b$nVqF9F05y#2tAR^RL
z6jH(u<4xf@ZDF?bifJXR)FKh-=ux-a1_4gBnjA2$3KxvUg(5TVI*`Md8bzUUnPAFf
znW&e*wA=-B0lclC5Q8i=zeS3%pc<;np+#gbucUvVe=SP7%mEPQg#rKwF_#yNIAiXi
z?<EWwi(|crQg$Q>pK<me3>hv5*SQaqW>D~%)VB^-yf0za+;tmVSG0gR21UUO9}c@c
zAqkRA*zUdq#HHxzVU*U)Mc@P;NLAh*$4k(2u1I6T)49sn5W+4fIVl(y9ge?)NO)f8
z2f)g6#VZp~&xMC@b7}Q5yMgJ%a%nGN_qj8^GV%SQ#v0~%b8YpWgO%@a`5hSq=uQkd
zKn=R<{<?>1xxEBc=ouJyfW$8O6B8??+YJzjUZ4$tQFMl3AHrI6rxhiwie9)5NaA$Y
z)AHs<)}44G?0QwKdkGoR3ku@SU921P<}TI?6>yX8rM&}_(w+AzU@N`wB+@?Uu8S6x
zK-?8oM?g%M%a)*-P815jYP#!D@boO$m!nM>&O<f)UIOd%0<Hj{=O?9OxPaZvGx}h4
zz?aZO-DPkB;;0t{22e>qDR*vUhTszK)a7(0Ch8|8`6rzraaG;#Vmfqs7vLW7S>35t
zJb3WA5crUaNy?Exu<j~(0-)GW%EWkcBNK4e<s=6v?ePog#<#~;VcYKQoX;mbt}~v$
zFmzpLA;j7Jq>xht$aQiGG3CVbbti@(F@HZPWDF2<rx=mf1M!7jNesjw{-j*_@f+N`
zH7!zL&URPX1)9!2C|t^vqy?+|(bDK}xC5AZ`;B&LnegdmVrWsw&>QlQK+)TrfF)h5
z0kGW%fy^U@wsRxyB(e`H1?Z(u3K@#^O$_a0r%X+Yu-a6OcFKqF(dM$+#}_fbH)%z{
z*iO-ggVeX$Z@DuL0+4T;rTx0&fMmW?dTlWz6cQl4NCZ%?6M!h|bxHt;eJ3=$oOId{
z(B1JH?Uy5qsPLbZ!DH_DDk%9n3kf&xiliYXy-rZV*7J}(1Z`i(F5|)Kux311o#+e)
z(}{lwX`hz@q4;%^5U+o`ZHVb#7ZPy)kGiy27oe^>)()uakOc<n!ekMGBX3j|DX2@B
zg$(MVX0-!d<&5WY=9|12(N!t|Bf3g$V5tQZmkmmn_K`;xts4S}VpWGySy=g@RGRLk
z<RoW&nf#;`v9v^~PAorB>J>{=lm^zR5|x^UQWvGlu^NW7Jw|V#?ky-(8u3_S;f>NG
zvor@4O;+wGRkYKXA$2thfaKW7gh!pQCC4ev6O0(tdsMM%0Gq8;Y}6}pA%n4`NvY~A
zdm?R~AzSWp=rL%kUIYl*3QBhB^{~K~dOa*g%W5*NcLFEjdM98tM+`Urg}+vvkO2U!
zdL^;`j2==fP*ZO$gk#lnjCF2;a)7`-9Q?&TSdl^fwrfSG-*!Uvu`*9RF<HH*-l44U
zQ*Tw40per!P@$lD@MZv(-oy&Ps&_L3u<C7%3P#5lpX4u<IjU!S7DB3bJ!>V^+n@E6
zJnW*Z!IYAxx&X7Q7YFF-#R0l{!R*HxP_kgKL{wQhSVt<2AS^RgMiP{wN&^i98uhAR
zZ2^VdAifz;MUxE+W5K9%fW$r++s!T<+O1AxCe7LpAudqHtL#v$^i{?xmIEt;7Q(K|
z=7q4U-7v<=V`V)<b+R(Bv4B|`;8@@c2D+?XmghV(pgZjpvh%T)8ZCh+wpOM>gkWvv
zMAmC7lOv0|rAd-S-^yai!f<KS%z;4;6idwtb2N>z23;9XS*K3+)gvp}l>wH;?#fEb
zf_P=g&60U#>P1n#-5!k6dz;ZXgR;u3%<_F@dS;0~n5Per(yXi-iFOQHxmirG4B;#|
zNK^TNl7z05dzLLMdpk=TmQ5bj56f(i0*MEW`yh3g`}u7;IdJ6P^l-SoO%I3jp@^c6
zn>S(=eJpPUi$a!1gJmPj>w(gehdd)JKUsbgmZ&V>3d>lQ{{@9EHy;hEVU{0<1vAUl
z!w{=-2W8pK@)sSf%2{3|mhMci6H9xRSBfE3<+nmi)gj*&i-?x@3w1`zLB>*~<wRq(
zQh3@9kaE#<7(Vt@-ntbSm8{(BrqW%P8~QP_UkBZj2gg=O71zdAOcmFLT#_vGdX(Fe
z)nLoD$%?V^exjzV+@q>G3m57EQXiX}mE~*86T7P0(pCFX^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9j73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<&t4xnALV{JOD~y8CWf5p`e5sms5OTLV<Es>%vC3ap@CK@5Bf#TJ
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g*V@d&7xNN)_=q%F}K<2F_2zQNMY0L()tR7GjV!FKMEoDOg+gnI^sahvcA
z<Pn;2o6t3R?q*b}H->CZ&TuMfl`{lXK?SZZ5&~B_%WI2#^(^s#=vWX2<7W>Lk_S4^
z8MviD+_*JQW3(<PHz>%t<^^40zj2F?Jv5j%J>rKK1-Yh(F+M=bAXvtChWZkW;)~O1
zT4X#k6=H@wr|zB6)Ki@%V!?T<@~Kea)$zcHU}~65@{y7xZR)-Ua<8}3if~t~w|B;R
zGa!7u_A)I=5##Z!jN$QB&G)Io&iSBaU^-p&8M%IdGS5A_olo$JfakLvVe+74IQyx^
z^T=IRv^~rU6_D@V8L^)&1?*$aj)?Gz{HHOcasz0TQThNaIGJ8RqfcfZ9H2y^i82&u
zf~qVA_aPNLTFjN;zy}95HTt1+3637pqnry`3M(-K_Q#`=H)zJp+zv->XXSn@`zn${
zvIU;Gt~}TZE6Ie0<w`@L4ZBiRXg%js>PXVqa$w-+s5BY+VJer#of$f&FFl-~&UddA
z9SSK^bO2uI3-16~KaSK;<OLld#V;s%$boWI2}YjwMr9>AVyBq4<O5MA@rcg(03)t4
zot!!S7hnI59DZd?Im4?et;zv{r@Sj?_Wi|ox-;KixmrG$eKu;EnSQ2Yb};=cf7CHH
ziN^38n>2@kB%(?_TcpezlXNh@T`6onm~Ez8e+)9KY2E|fbkwYrbEelh)5(>B=gc0z
z1ViaS<f>f0MG28&x}OgKy-X>l1Iaf?5Im9;duG<^BPmUphR&4mDS?2*GduAJQl@_D
zR)%S{@*Ewht~AsoCDR;f?(wmwPWoU@rj8G0b}I#QQ6dF%aBvXzO6~N?3{2YH7p09Y
zMRXBzv}qSv?aZZ=6~vjPJ$0cnOIzux4g+qbvo1<9rlU3XY*=Sjwo+ytHR~&_)+e&q
zl#A;Vh}xC0>tO?~oL<K#nDy(h30GRMzelv?4ZHHKrNAlQ8tKQ5bZfm>Ci2{r!+bc5
z$d%~qO0kwMHgT^gecFTTH0ftMHx09}T?y7Y2b5r~TLa5m$=-_+>L(MzT{+ez3CyuB
zQ9zQlix0Ss#wH6B`RXML$e9}@3s7&E2k)?H)9rF3DLL4-UdcddCiD8DXkbSxU*9Jx
zIaXG`BVey%?9ix$3E%*CE8GCb4($ZTS){wL2b?+Bf+tv%gnN*_fuo?)qrV7Y3@9K3
z&-0_O5*()X!c*}1Y<LTf2tj}{93bVFXLZ4s@hoMMw!DpwS`z|@ID(Wg6OfDR+yEw=
z8QTJ(@H|ujQ~^S~-wVycaTFKgg)^~RUMs(d^gx+_2jD1l4F`^WA#gY%7zNU?2+0N8
zIwcoW;=<uM5E{rLBp;-mUN~#yQ*of?btejqUjTs+E{P*Hvam~>dE|mOS(F$LAyD#%
z5})PXy2XG5rLri&AEB){($9s+vVI8Zl*DWaN{&c32Q$)T@ej&#7d%Y<P>yJ9-4Zco
zY~2E<Wo+L{#26ah55HW9HtP?dL<{xCFXHXU=77Q;1)j4gsc>|O29#|<@GMG>u5G<y
zbgla2;7s<Q`0r9GF91<=2?fD+WFNQ)wsUTsQrKxuUX-zc7dbSo0ytWfYZL^M!`HLH
zBrQ?`LFqwq;aC;cl0(ZYJSInGK5V>4Qi7Q>={mH<0)KLpFCjS8YUhAuo^_`53*vfF
z5)5jnQ*c)}ReoI?j+I}4951jdhjXeBu@)tvxBAvC$KSVJDGWm2TBMu++#HLL;9G?7
zT9jaU+xq1A>GgF245-GcU-yP4=7{et#4(4XtWe1oC6G&^`s`{YHkuw3hzKs|GmnQu
z0;4&x3J9Eb1Syfx>KMqI!s-+t;+<X-7vb$_y-CP}V?%rMix79R*dP>HfN?>1o()rO
zQQ9Ev+yP3gkJSZH5O)-nz!w6(U9^S~0uPkbXsni<0C%<Qz_+VKC%&B)o%nXDZnsFW
zi-hdwH(-i{{O9mN7CK;1{N5o1JuBlB%-|yA(w<wd<iyF=8jPR}7iCF?vYdmkh9XGB
zMTw19Ha-GGoU}sRIf4yr(GloffQ(KQ34t~SC5EF-e;a`xbAq^7%Nz$kYe7gl;>QbS
za#0prPQk%Cu_=UC>3E?RrlrGQTez2=_!UCNJc1Czk*0^Ye_?Do$_f<@rvvsvP@RjA
z7)Jv11Ze~PbOgZ{FsQ@wuqXrV#1?&uUu}aLWs7_QYP{e|7bUSr>32x*jiX>sN!p-M
z9VU^2PxY*uQ~;|YsCe(9B>1du=^Lo`1amEdoM7;U0~9tFvH@3CI-Dqa<KGQfv*V*>
z8f=^rg<lKOhH>ja87UmxqFC`NUgU+ROHyI(I(+wq%ezy$hP%*cSr_huBF+RDtuTUj
z%FvfWT<)82Tt&LJxrYP^wRor0L_?}rVCpD}w4=Lk$jRBFY4ksR{fA@i^Yi_y?<rnw
zyvgs=?YwS(AFf~j@!x;__b>Z8-~W^U_dox9e<2Ft;C}eY1HF|pKl8|F<p2SSyIs<8
z8|#n?RK2q@V1;0?*u3sWC`e|?O?_Ak-5B=OU|LwcBF4U<N@10^Ma`kWX^fvi9kr}g
zCY-!8i`D@76!lsZ8yOg-xVDI21$)H^q}ja0j<Ovt+>G=zD9y7YEv{-@Pln4A2?CyP
z7a&H&{~|iI0=$$v2Uq@0$9!-b&e&7$t3eCBio?}w@ZR)_D{tN0Gbt`U?z{P0OuRn}
z8{s{>)1GO+krvcvf`;)^S7TFp)e@Msg~~mKSaQ3$6A$|62`Gt31HZHWFxY^)^SqZC
z$ZaMxfQJRoO$9gs>u1u*BI*9g^2Y!?i6hcR6?Q`j)Z6Hyw1KJ-7NWo^4Z=C{QgVn0
z3teL{V#F?Nihdiun*JoEG9l2#Rq>@wxb&)=@56{YRRLQ9^BIOd8QiJxl^eklI$2OZ
z-OtU^ohE78kS-xQZmR5)D8%urOI-eeK-gad;`*Tcwj(8Js3R!1ecSQ6J_K%c?7xWM
zZ@x%LHFYHA`nF>VA_e+qm?1tS{5RclAHawDvo=Qmwp*sIYq$JN55mX(`AtV`GbAGZ
z+%{hSwj;dL+>AftJpbIDzv;+b+|-ej`@4>GMsl<NjKG}F?f;vOJSF(WqJ00w#9`!N
z@-sHg$LaE$Zg~dTt!_A!{M&Br`Z%e6#-{x|yZ&)U9dV~Rk}|*R7%JGh@^BFTOyzZ>
z{I(<NZQ7}hq|9$Sj{D=F{h7(wA4l&$?#L6`E_LLY{jHof#FOD5|CtCS`^o;BZan`R
zx`}Xq(`^BPZMVeFK&AS)HvaL~c)2un1L6Lz8;j5q-0x@p%lC4szv+m(3-wrkZnv3#
z+i^_Ya6hY<q5byY)s=WIDX9z6f7=0tF>q`CBrbVfqrd5f%eJu_3HSHi=Es%%vp~;v
zN&ohH9cBY`6y^T5BRI$_zqnXRz_*<2$ZGnzX%GF|jx;vj1_@#78|g@A?+wYw4!>VB
zVdSNjl4Ad<xBOP_87{+)q&(kt6t2?5k=_tpU3$?!?kM%Ct0O7Tw;h#9Vp#At=P!EK
zZ#qIfLq)Zpo5JSbc6`RJ#jRugv=7Q}J5v1{JS#~V-(Ot)+?B+iVaWf`8h_KR3ynbc
z)*_5=51~GN*Fb-UTm3^N{Y^Ils9fkaD^2N}ZVGjt808A2`c!y-(~){{=k!E*zUvrK
zy-=TjMu=A_)4%CJeLIGy*6&p*mWP2x{xjn=Hp=fhDr#k@BPa@c`K?yFYy3YqciZ)?
zx~Qjuvm+_vdj*xwlYCM9O!MKNpBQ?G7`lmYRk!zB{ai2E_xttzaKG;Lq8)ClPW!*~
zAzKd;8dp$%vjSs8>GF-<d04fJHZQiz#D$`rms}5`l!4j9OYo+s72qsgKM^*V3QpN5
zHMV%nMEce7K`BdB%5h-OJkJM39-|xOLuaHN9UlbRvYco*)!@`nYE&@bq+~HRd^At&
z0OG+%QIB+vkCq}f?>uMQbYediX)}h!`>Ntg@a|cZHa-ZA*=mk#okbcNaF`pX;?Hgr
zKAk2e6@@>%mahU#Zd69C5EB%qZ&P-Wjba*bM5?sGXaWSz5%4J~OE|`}F*rnF+#7#m
z;ZsFFK1kQbtyuYS6}z%_q3oQol4I_6&Sf@;B8W1n#!8K`S%B9fRLBUeuERIOXPR$^
z|7!FdzS%;D;K4Rqvos``s9Be0vttj%2f-Y!MsliLJutCXK*)`p{-%$F@Q<@B?$IhI
zM2NCKn-d~flF^5BrCh1NmKP#~&hO0$5e)Eqb3&wvGIu6iDZv9|;?r%?ymkPNKykk&
zihNhVM>=GhD-tLV-6Kflv`IS%qrz}?G-Yrv=TKAHHJwMzy;y%@+Oh+}3$-ZK?H60&
z&DyP=twRWbFS+lUQj+Q6YhF(NCs|uQ{(RgWt-?Q8xwXPSqD;8k)+hOD)g{@etg;}T
zS<!a$jy|Y@D@SK+ss3z^&X`|+aF_yWKENO40FF5cMGl7Ah6L1b_&!<Mx4MLAwXRU0
za2l^RoujD1s#H)15Ps`CxUa0Y+NWaI@p1%`CMY?6N(KzfQSexP^c??CKrcM$Q8xLZ
zi$3SzTen!1F6oFo)W8pgkr-zDrkqDc1H36{#RBxUeI^$``~QN4xGC|FaSHKTI2lNh
zqf_fd4Qurn(dONAv5a{|`JlpMd$vw7y7p|JiP5!t3pYu2wu<t}leD#R@1weTx%XM!
zJXv@oDGrM!|9)C2md&Jk<p}5YsT|>CJSpN`TB{JBktn<hpvl3}ad@Gux%`F~Vi8;0
zBYg5t)FpY>w>~+tJ-jCbv9bPzUo2`~fnO|YURxg;LDSC1b&p)PBT309+j=FZta`;p
zX%+Z|8x}Cj2!={dDaHrarR{-V!7SSYzhXT0RHt-^R$d!I!J6%HU%?*R<G#`*x5s^*
z`9l@*0T;DZ+?T-%Rx*Km$mCDXFt{T~)h!mxCR*#%sC+a8UI+HJ!vAvOLer4N+_%4p
zO%~>()yhdLA^^H?;D)P5I>=2L0A88RDnOW4De2l-bEZ|i2Q=oRDOC(Hk&95B^6N?r
z`-@Wxp`y(y4F$2J0q8DQSp3e3umPyh?IeQ13Ri8F(lwDpyGRVD#o2U9F+gB!t9TEn
z-@vp7<-JNrQ??cWE*DNd9fUY~PMrrcT`{flvnEcOa~^1p#OqfyaO@NnG;p9<EDG5@
zvQ&VAnK40K1k*7=T?By5SPoW&Gw1vi`!n-}boOFC4v16lF8E%vT0*wNA0xFM4+T1q
z5s;lrsI<X+J1l~tx|5MQ9VT}EsR+P8Iz56yMnb<mPqe~I^60Y2N@29VB_W*U&r?yx
zxuNY*&~W-RD$HcUQB+|jfNo{Mj0om6{IWuUW@>ZxNcW#-{&I;%YCVh681Wx2M0<2q
zAXeU<l8@Y<_DDVky!VgfgSfT!c%>waXflN*nPQLL1|yXxdlVgpDEmdp`vM++dx(w@
z`4lm4-5@Z@vnWYYa=^^(NbmBa_X5K5tpZP?XkZjSIoT;ktA`&lOBQ7?8)b2~^3{;B
zvM3zLL<EDBhcTmW3&(*POi|qB*-~eM!lC4CZIxe!q?{;6qrVx^rfP%YmTwYTAuPA@
zMc`+;6$3W%%wCkrFdB!d@4S?RWH)sHI1H@<S&+(9u1b%Bq;?B*))C`xw*vlvL2bA8
z{4o4*tK_Tr*`|~k!>`yD&XT{PHz1O{%Jt%S{@Kk{4a3{ovbVJVzl1pu%+78l4>)}@
zN{DC8WxI510DH|YstNE<zX@o?crQr<LPzWpJ_M0W=?qHB$eLOBN^E7Tj57rMzbR<N
z8^e@bhR2{)av5>}Otsw!!)2-#28=C~5!=%u!<m7hK;|x;3P`PtdS$1wFGoX>v)7>n
zO}i*mfU>enLWM+6yChWJv;5jqd7?*_Xme6>Y|2bWy6K{jPmsDwQFFjfS>>n!D9SF=
z1aK5zl@Dw93yl8+?{Xso%PH#JVen_HV8zv>1YRXeIBzFUmV+ovrYd*DT(Zhx1Hw|&
z^gBt3Db8CrBc7*L#>AesbDPpj;TKtyQ-2eaoD6g96!!@m2A-_%Hd?V_b4zko4aQd_
zL9Z#xlz0&R-liU;0Q6zC%A~~3oQhM#dn@X<VuJ8Pq3SFC$nZz_X{4Lmkii8&D6DE5
zKQ!@2+7(%+BwWV~n49z^SH}G{RLnOCOEd>_?Sn0YcjRB<r<k(OD!#8w^an**?x{$z
zuy9gxj#AN3y2Z*khj*D}+9%KnVp9yqe@`ChI&KXtP%2Lpg0Ue>PQ1|$)q@U729jWb
zaBvT$hBi~M30DI<XtbIjRGFce;D(dCY<`G8%!=LFP8JyN2*ais3MMsdnxR|W5FQ|<
z&mIL4z7pah)S98)X;3%HR0w1e7H@wgoW_$B!fOQUT}FMNkgy<qQiA<LnGF<@Gbsi3
zF``Xe2utC#vNu`^rwN&qm?P%GM!^jrIOxMsfyo5)Nz4%wh^M2JlPSW{)8S)6+k6v_
zXcFoJN4fAV9Z@Xig^ZH2VlL~1;Wce#wltjHm92&_fAfMy!NFYVYFRbw2vT9v<kt!t
zB~M=$63Q730_Gsb#Jf!J=Y#L)wmEUkmO1l;+Depv$3xI?F&#;Y59|6lFRWbC4_{b0
zZG)3yV+<`mDK;M<KW9?-%PBSm@iQQv%%5lBIxDj%u%68e253Z!zv1A_iB>SBqnb&Q
zf-99Ucj8Fua)JPu+5`o-D2prokrnbxu38yZkxpQp8MuxZg+(C-Q(oZ=4mya^u?Phj
z6&tzh0ghUK))hT@LSA}p6=WQk@cRH*wFt=@Vp_c^Uxj&PoyPp00OLoH7#jRU3rKAb
zZeZ1f>39onakY30E($|R1Jr8~2n2>}xG?tq8lDTNb^J^qKR)x9pP7I883<58^&u<a
zO+gD2<m2H@iWX4g9$acf<a-cvru4xMxcNoFt+2pNVg((ITs^_>0sF)Xeh>Kxi$cZ*
zzLs^NqdpCD>sma#J;FF0uqQE$rq5Web`!=dfKL`_pq;#E`bt_5Yy;Y3@S4#DO=J_>
zu=Vboa3SeYE(E1_Q!aSNC8}S1Oi-hU<+XkiEs$a$G`*W*AT+%NF?a+aqmge)0o|Mg
zDm0nT2~@Hu1Psh*yY`4%H{KTQ0bU@qx+Z{7_|+GMv+U{<vpfXPXa&Fr3`Y|H-`%4@
zJVZQAo3P4n01B9l^njBL3Kz=MjcAOxXbP0?Mn0Jdl`pdktO*4aZ%1pFz7Bn*30oT|
znpOqg2(@Vi)CW9HQ&bf(JFO8HJDf-+2f;zyPa|$0UXND5ec`mRR;ZtsdVD~Tt~m;t
zI{YbCP=0tnE($S7@fK}5OD;;t5C$Ur7eT@gIRs0P(MSunCdg={7h6-E7UH)q5*UH&
zrRm&B6xc<`KWOR!si!I5=;#2{tSOh3aI_YPfF1S6O@0ud*)9SxVWG`79Zc7$P9MOz
zi-3XP@n_J{k0h}dhLRY))`S!aZ~<#VZJu}{L6;9?-_$%B&Fw@CHu+#W%;JW^kH9Kf
zO$f|n$_BkO0at=99Nk2xua^LjO@M_RAQaY&I>REhk6e+zB#*#`Y;ycCXl+q)9LaZ6
zwr@u{s-UERp=6acouiYdgCI#KvQ146B%+fn3L&O>I`CxO^H#ux{KdnX4qH^~S`<P|
zpXx>ipV3O*jz=AM8Pc5E1Z_Ire;~IN;Yk*SXx(|rndxvIk#i$BXFQoro~{5ZL6;my
zx*b*<yrs?49-1Bl#~hsqI6l-3qA`ZLarC+L@Sp`IIZgpn*$tqR7{MZYK4lr#{}MEb
z$?bM@JYE-R;7{V<Fx>-qu9`3>dm1f`psakEE()h)>O=T<%Rcyb9G~*+b-Xwih4`u{
z>Sx5P45a+CBI;j6BQbdciAG{pbsg}6TqMjV;YiE`|4IX<e25*DE{w5v2o^kof;FPK
z(gZ{8SG1~DL5hn&shumYg74kA^iqDA7-K5qfRz`_taITf{j?qM{bp6P!PzT+q^l1n
z&2_Jm4L$EwlT)-imtHrY=h9czhK8lAsttyvEJSQz#asARJBoFh((8LZv`l!Qi;yd#
z%hQ2Fvq;Go;H;bJI;DkAUfVY%TRAeC@@$|yK<AdHnV%RVreJzvjF=q1E5`W7;L=dE
zD9KCd`v3?J3WkEa-jpedVy|yXv`~H1OyJ$!!M2@}tW(*Cj9fN>4nzvhiUKg9qIMu<
zFA7+P)7+HDick_WsRCWCWECvELRRevEHR@&VMSv<81F!PVzg|hLaFp1*0C`FtFqEf
zwc+tnHW>@%n8{^=qB@`i;Zjl%)(prXCcst#gOCz6ilF2h0x1(1<fCaAES4F{-6tjD
zj4C0i1BH2~Am55s!A^_iPKg$G5OgC`Q~=8*y(!UZ<P%!SBdIyWZv7-BOXw-=xVJwk
znYj$%qRB8RED)7Ksu!T~INd2HK9vHPP#bC=gxWC0ICN9iGzjOTKgk~f*y~2PxP|oP
z1Zw>xXmB|v07rjPme?E{BTg4bi-PfipETBdP#|Jic#MZ>M{Dfsc{T|bDOSRjLcxM)
zpQK-e>pUe~B1pKv$`d-5NKwKK+ac43A0DPf*tSo5ZV4n5n?>T@&0V(=-MM?2=zHzE
z7Zhw>PsN7S?RW;Xhr5t1@(H=~Pi;abOmCa;BZqopOZ@EE_im#hr>2}|_VGdC*EvVm
z*Eu5|+bZz>xE3jE>cUi`Id!cN=foqsCeXA%01JsahF}zuz#r49+*l{mqTCqpsYQYN
ztkEJP{OfjevoTyHN;u*YNzsckkGMqumlXIBxJJO!o12uDt48~aGV~kmFGgR?K|~2&
z9mJEU%Vts72^<2#MBQPDFmcqy7lkx2E%4_ax*NeCV8hlO+mP&V<W1dZTG373?k+uo
z({9ouQgH58Y6SL6dh1KoXo#{db)?-U#bTgMwF3HkLy&SQJq`Fe(v%vU_oYoWc;QP0
zTa=O76(oR$6jN<e8d9X{EeiBH&O7rnQ-{onCjeEcneDpN3G+rgE0xuDO?Cm=QoDF+
z3vvReU{aGKedXCT=?2d`)a@)W8+w2IN3ODJlmdROH2gQ^OD}+San&y^;KgOXG!riS
zrHaAq1R+J3qaHDl4Wmw&3T!5(GNG`U=)KfvGcgqay-)?hR0yEKXu@||qs>GimTf+I
z{9y+3(ep2lDw<66WMraEJu8`L6Hih6@TK=3o;sOnWA@<R*+DhKCl7tq44--IKN{=g
zEA!D{hdK?kvkOPc(^~bzCr@iRVp`yg1_3{cto>Hi!#ga9RXrTmby^@IX_CDl=d-C7
zcJp6BJ0`3pm?5f&TdPvxG<=u_bEaJ;2Qr{PGpx7C?xA8_Z9KC6G@3nRAF2d*+K}Fq
zG&<!p(&~{0BM2XZznW@<k1GvZ_yN3pRh%R0%%caQ@Y{;?YQn!kh=8f&M?;Y~8Rixx
zTgjQ>WR}W)4`$};jvp=y;VY7A@*}#cM^_IXHG{S<mGoxNmcaQMobzSWY=fpRr^?Rs
zo3M<6FSLy7E`;mdgblcIZh*W1M`#<TdU1hh8rPi#Lr7BvZl_@!chnK2?8Pg|X&Bc9
z1XxxBwqZjWt*Q7-bE?=fYiF8HnZ22&vuxv77u2XM`+3VKtu`g2PTM%H07hvQ#*ou8
zuJfI7Sv2(@iRT120>4em_@!^B;@(s<nzoUKL)%fZCfpPFI8OR@>Ek%*m9NlH)6Z0z
zsAW)9I#9s!^uLhZ<vYPPaGnr4TAdQ2;%*JrlJ=m{;bel$JEcP>XNPpK>RikEb4QSH
z40QTUX#H%R;z65frs|Y~D^hjf^2)G{hSG24CTs8vmn*Gh8nm2k4fw3`#~neMA6~l#
zfY$Qty(#JW!)Fl0(M_L0`3&ni*pRy;r(&e#T<NUjcc8m>9cD1O9HwlW2A^s;G|{d9
zfX@@1@bc?TU&7<B>rLO#-BjAFC3c5(olhOALD$28c9^vLybi$ugr}Fi!Y|Az!J6LT
zv1wQwQ<hT8B~5=c<N<PEovL&ABTWFef5n?ZJ+MXK8IOE(6LM}tO_Ff1r<k=H-gN#h
zg$gFdBhr0txcjjJH0N|27mYF`j42!(E9wAz;Avy5BiL|4nexdR;?q=}urc1O=Z_-P
zxL3V&9Mq=5iH)Wjq8taMBd`NIr_mQLw?J$3v`Z0zE67|M4!3p$oq&6$FcdL8n>e|k
zYnam~vnUy$qs;}q#+Vq`(kXHT1)O1Mm`Z~py~k8fv;n=<n3C9N2=co1;SVqsKy4_k
zWGb85P>#t6kHAbG^Rf}(A+Si;a(G~vkhU9ME~XN+4G$ngByRi=ZVVODMLtgkQ=uF5
z3f1*(corKjrT8Hn3d}BT@whitDsHednCljVrN~rAxf!A+O!b(V<73KoZ7AktsutZ)
z@yl3rx}hG_VZu#si7Q}2Jy;kx=9gwoInnK9loO>_BMV5lf-fZj86n;m0ik?orFcrK
zKauHS0*+rfKWo!DV|ODhDB2JRBn8>fMqn)1P_klUFxb#Va{?c62+Htc2xPRNl?+`e
ztO#dAVvi&t6S{sw6(<{X)UGU`E3uF`x_E|+Ccd2vY}JLq@G#|hGgZh~8K9kbhm155
z9SudBY)Ix$hOEkN187+rQaaDB&{u@+GI_{`3?(P7qM=;?0NMzv#jIMiumes*;I0<w
z7q~(GJ%`FjSM3MJmyM~z6jcf<%y{J%<sa!$P6#!HD;pueGQ~e|4H+Odc;Yfy$Ogk`
z3?&^GWuBx={0$z5D;p<cs`&~rhGNaGpT<JXuAj!9O)Ss@qzw5Ml;UFw0vBZq315jc
z5d_X1Y!6*v3^O;{<R<h>V~o^HXRh5_gnJI37P_g7tH`&B@l#=Bx{V2T!)V5v+>~}>
z3tp$@cwdU;$Bby%yLcZh3ZnUM{z)VUq_kSv`HmoA+NkAf7xg$pl_<L!T1->`6PV%A
z_^4Z?%u~=Z(h_)S8E>X}Xc-xbm8PEqq#TS;SQ(9VxdvQW9UL&TItE&K$X`PYXHtit
zH*Y3&3^BZC3JONsGT~&>3uZTyI;MCH`|w2%wB1bVxWsTM85eL+i~(KOC01dh3Zlmn
zZNaWvoWd*RQd|LZi0rzx(y%gLk3Nno=6b}tGpNKCebRn=Q{ORwsPnggSi2^9OQLAG
zyd_nHf#+2I0*3mPaJsSDHy;%Sc>Oom(8>=rympLs%bUl#p%{SORAvlG_jc1JVHp+%
z<dj#Y9x>w!@`7cyKrmyL5hX1t`J*l_3?-vs?1)cRzM3KHy>i-&ab!$;qr@I-PjLw#
z@T$yaw3DiQ8#lwEK+dv2#@g)Mfs8e~C05vHmC45hrONhuQ?_(KBqtqPzMuhZsB#Jo
zS>u&=$aJN3eo`Ko$@C=LvLQpf(iwUFRLY~FzDgxU#<8_Hnu(J+O(vN(v?9T@X}C-<
zZ5l2Ne9G6112t1cyT*HF&Sx&ke3bMFAw$}esrsQI*&F$#2S_=7yy%z+RavU*n#lZ8
zUh|gad6evW1ZAQZ7JK5hVAd?Iqspsgrc|Zg+Emi1PNK=A(=@{vDuOAgHz>&~Neu1C
znH-$cyefCtXjOh5O%eN1ImniFW+f@x#5*ywm<=_YD$Dsz*|MMwHs~hseWq<8nfge|
z*s`rn8Re!GWJY<@3Jzs@=Twwat~*RQ<+{VRoO0~(EvfwC@2oE!m5FXjDyNEQN-EbC
z#<cQ*M&@~|M5!sIe29<0bUI5=fX<}Mds9;Rl<EdeE7Wrg2B7!M@;B5)3upka4^R<!
zDI7`4NkJ8wfG`pafn{QOpcG)lKqmr@flavE+xdv)2FQd{EH?qiljVRFvXd-FJ*NU%
zunD9Hoh6@0+^K=)e?Lh{3=5Mk5*g%+0QN$)ZPvC<IW`?Pz|-Q>b8ToOl{fmh3r4=H
z*Nu<!ZM`T7bfGSxhBWzS7pV=suagjv0&<eRDbZpFAne$nrPGjy-sE3|jvthPc7j^4
zzK6j%K`TPckl6m0Iwcb%KM34x@|_uKDK>;fu6CU9P2rXX$grlcO+z8N27i<x)Uzq1
zl-ZK4B2^bDF<)>O4T9z9E<)|PCbtjYRSj;P)lNK<W?QEOd}&*!M0{!Llw)aIpM-nq
zHM$Ya>_A+ct_}jm;Wr$hJ+3YbphM-5_zZ1|UAIA8oS`l`tg-b;4$T@CVR0x2z|w0a
z2c39A{7x615W5T*7u6$&c5hvBXt%oL(C)2Ia_r$F_DzDZ^z}u^aF%lbW&LEAG6MHf
zlZD(yBk+~(l!&-(vVJo?w8`FWzztZG>O<ftD6BA1G#RdKWQ#p;Ms^(qz|!e;6hPN$
zs#|6NZf{CX%AC_CW3s{V)nq+3;1jg2a0n!((vqJ9;B=vt7+q3C#|e-wDWU_lP+Me{
zF^#n;70m$M*_6S?%+}@0z-_n;NYUoQ3W3Orl;=6}Ut52+J~8%3$N34~1L5$X@v6z1
z`=&$-w+8ZM1B@-X=!AjOws#mN7HNPG^KsicB@A5KIwithQ=f!^Qw$$%am}T1I&t8n
zbrPOhR{)9=!=Ls#{&D??{FAYFIup6CVKmWzpg10Civ&qQzHd|Nt-){EobEYTADbFP
z9i(U>L%8|9^+=}h8_5zWg$N06%2}2fv{mVg{DM5RFXb6Gnj8&C7){8+G_W2`Mn*%l
zc^kEgz@HnnifO5BgR6+!a%`&zJi1Y<m~c*`77-Wfs8viRwo$8yD|Tr6A`!YNpPpvr
zaMEkU!LU&;1q8@1Pyb7)(+mZ8(OTVxEMBO--Bk0{Smd*nwGZy)MY+g{MEKOJ0EY1<
zF#0zoTD0mxy4ujqjil{1aB#zA-G&Zs*xws#<))E7kXUta7lGWJfL%5560mzyYMaCA
zyaGnZOlTIfNnW8@l#OwtkbSTPMFfk!7E3T?oZ2Y2J{Ak3LdZb0KQf#~ZARO?<icoE
zdKn6<wmCOmkb(#x0~BXtW#^qx>>&zou_q}veKv1WG{u?~wG{t?<}_;?7llm9qo`e~
zYrB)k61?fII(dt7>!(8=(%x|VLgM--sNu!?wA!2<6uFCc=TRhDWgPHiW&9K67XQ=3
z+OAvtN6vb?+ppbJgT5%fcYCrFSIr@B{4xPy8u#3|8id-VV8wmaB$7}sb@KGSf93nl
zU5J&rpPlQA@@%^hYy9X*E{fHLQfw?+AL91NSF@99Uxk!DUB^;Ux;A=9dj|F%+a7uL
z%}7dZ#<j7YeJ{45DC3X@?AK@Cd`a0iU!1+qzWL&Ckiq3B(zTy58Ii4RAE(aqOKUrE
zQlg%FV@=3U*;jzb6yf9gp(Pv7LrI8s)FC{@@-_c{o*QG<Y@?!~2D@g`&)Sk#hRBcY
z%s(=YzOIwAWu*Onon$2b$8FM2?a;h~j(+y-`fDTpq;9`{X06BV_KWelm<go&bMS5+
zN-U@=mB|M$UAz69+vPX?R>}gd)ZpE<U3JO2tFAh*?%I@zWZhj-l})NB=g4xL_t;gG
zF8oHSF^e*!`^2%ww2V@R`d)r6xMJs~-vw9f+|;}9>Gv{qIIF?hrmY2U%GTj558Jk0
zi!~<P0cwuj`li*b{@v=%OkDo6^ws!|3}KGSmz^QxbY*u%e^XcP3fuk%b<?0>N1}^<
zXG9`Q{YuVyZoiUqoV#-WWJv%%g!4%dB>rqHcG)(ZwP1Bw4Az3ZnI*~BN#Cp+C+7KV
z-Ey810#y@y7`nyBQfFi={qem?2=L_UN*w01tTT!gFSjEo)hi~}Z0i*hYi)aX#>5mw
ziZ^5wO-6HV<tB*$B6?S}C*P_)(%17P8|hgi-CB6;c12?na;Yo#p0DPvz)C)>yHfuT
z8(C<YT~JWH$r+5-dnarGANaj#^E1LA3UR4dvj3`H$^LummE)Cm44cH!+g-hKyz-xq
z9xe9h7;YK1SZ)2>Z8S09es0}@xBc9@WhwH_NONW>a=OO`imlt$C-!x3Td$CW-ef`w
zIp}ROA*CD$$b@#Ms7%Rr3{Gy9FkbckVca^ih&${lsI=}|j~v==-O8bjGP<2j>7XGA
zthPSYiPhGpI>oB?vTo%YyZ3ABGjoQQI)xPWYwHxN+IK5wGODbcan5%|o6?5a`)=h-
zMwOK_$Ff^F<K!Y7(jj|l_fwr>EM@M%tFM>213@2MQD`=he9_C`ftO(~gU7(#>TT;5
zBJXYMl?RN=cY>M`-Q_#Mi?S2^DhTmA(&-RAe{_{bO4E3EuRb9(3MX5XB{e>_9?6RV
zNDP|kyVn81LZ@{=;M#F%;Uo8Fr!JJF{Cb(dvYxnKTd$B=_(0CBnCfy<<hCix$zLmg
z0{^xP7S8ZS?kXo?6RE#lT}HqF&<})i-wLxbR21ogxT6=Pk0!egJS~05zX5MdAJXuE
z4cr-5wFn^|u!<Z>3i&9r2x_2o#ZlSJ79CKr7(*L>Vo+TbK@9N6y$Y}b9=Q)$wgW;r
zAR*`%%5fiEAy5o7>Vp>n@H+a?n$C_XX;EPn2ndUp{CUK<c**BS9E_J7gMHlMcwT!8
zOM{L~$A_c>zz5lf)WC@|aLU3xN3?SA1A3!M#?TwuRaPebrG0AK!=sAwmM=M7fjE*=
z#8EbzxRMVfVwb$=+Fkf2XvJh^7gONm=_;;c6X(<{(ZD%1>HJD_MxS~^PaH{f*(NEL
zzKkpx#I*>VB+j2n4RPZ5VUeM9zQ>-QdWz4y#e2n#!7|bVYLwWfed^gaV}i1{AmNK3
zH%ZCiOJPKsSZ7!n3N-bMAYkA_4p#5JEB5$x;@>f*s{(m49+^--uZX6|7hJ`LW!hV>
z@GyY%cc9A}GUdAPXNg3+V2L!e7EKNddetSV0K#p*I$CR8E=fS<^c})adMQwaAWJU=
zv-FArgN>&P{}*90N02IVCcDW;9>Bi~Dyr=fIf*6pQpirfri_`0>*<&DLVU7cQVY|T
zwCW>fBS*%l!E170vL0R7DVN>@7k0}fJs{IG`&BER_w~{56V3RIEqaTU8QB^M7pDJu
zC4roWH=y5o=Hu)A)@_gYuU<wi#E22mEGc>0-?7B+;q_aa9@(+|mX-WwX*p?vH{|yg
z+Mb~jP``EYBM7eF75B%|l>@Co#J3j%?GB;BB`H?s)&+ri_InTf%lYaExZy7B_a6Bd
zyFi%eE4VBNSCM~lArk!VrI55h$g4=jU=4pFWbf7`g3@b?!WlrI?@}NUq}Fe}C2rK@
zyCpfu!VcI!CnZMr5btPFMnDB}{J0bzJuhwu_CxOrF!}mpXoY>emt7DXBaC5EVp$)Z
zC^yVVkL;-T1!d;ZU2{X{tiUb=y7da|x?yN}^aQzM2Ohobh<EIXNA`(?I9voqaKeP~
z=;%Qje&0g9ZYY8Z^#YvYLYaIiG;YCArYJtCr!NBA;FJXM!47z&kv`Y}kD_@VoW_s*
zHxB~s7O7&R4S&S2YdmZpJycNfpjVLAgS^UKaas?mnVve@@!bGGRn&L>jq8VSW%()h
zmWsg&6yQ8T85?DN*3bEsaq8=n9_S*BT*rS`csuLDl06N$tO+;!Vp)#`T8mcjd?D6W
z=>A$YmvOJb1{uh=_?wgiSDBPW83CV*lWGyJq%f#HTSzbglC8`B7x@dpM_P4TGUC{(
z+^+bnwT>>6V1#vzq#)lSch|xUekq`9Aqp$rKd0)7onjgJMPX_}PBoy3G5kBRi!uB=
zq8kF=c#smqH{}8XZ`jSWo_QF#HMC;n#z=`sV~L?RjqJhjD|6|@=#`U<d3eIJFlA;j
zzwkoLqJ@#c>bWQvGk0bT%+ZSd;{~W;c_VniXCOn!3-<z`IbNU^)&tj?sfQWs<wo~y
z13ZWeOsfIs!wVt;Uv$_kkv)|kQf3~os$589jPP>dpfL^0fwX{puKb#y6aWw51)X3N
zCnezm=FO34c2qi<7hC~S&b+`0@aLXb1oi~XIY0YAoRk?0gg|d0#mJQlIQ3){^839h
z=QYs|y`2ndTse7OdHyhJy5JR=>gNJwWICW%qJD!=c_rE-k==zm*_uZSDVy;^ae-Yj
zS<x%Liz$sRlPDvz98q7$iS){Kht-mx`YWRdNU2U#P^MpcCAK3)(*-t)DsHaWFoa?q
zDg^LSEY_lMc<Y9AA*M2;6r}}TN;+KxLQfzywF)OQd(~MKuJtn-Ops2M)ddpUIu_F_
z|6Fyrm2}!!pqZ*T6L_5!>yYB>iF3QB0lUC(8Ia|bZH^RSuWa+MS~^434kabKz<Qav
z?1)}tRl=wWkt>kNz23AlI*tg><Z>WddnK257NxG_@_`uwg9Dk`UXaF2=k_hP9CtyF
zJ%w@@-i5D$ta0y3bnTQ4S(8~Q(pAB*0pHwZUuF`!_fw3c0?>7ZAZ*K3DiL8@-jxT4
znj?#XMFQ~qu}CR+C}rY`z-zvGD7V~k)>m#hl4%zO!DbCu_FlQ=nNI7KT#hQBUdiPS
zfeB3R=2=eAW$I=WmkZasq0Wp8`g?_O<st}i%7IAem09jM8!Efp2UxBP3Z8!N)VWZC
z^$5}cft~m*)<{<ZA{?mRhdu>Opbse!@Ljr~*Bfk?-V4Hlo%pG2Va=XY<z0yH4Q@9V
zxO^LDw7^Wb!MsbcgPGH-#%P0Y%7tLxhN&B2Ja7%js^10|KQuxbI$hOG+u+jkI2nyS
zHb|2Y7l2v7p|aZCj<9krQZgZ9zg$574M4K4pvZ>AP*%EG2Tmf=de?aap9JgUB!#_*
z^D-f2JcABaUiPk2XiRnEfOtYYXk`x_ORQnGNMOv(9vaN8Ui^#P0=nrDF7N%JS`Ry?
ztJEz6!aV9aFc{1$MIXUnu5!5%4HhC+S^Kb3yYJ9I>;_IDU%@Mte<ISzS(k#<yxj{g
z2q%H(Z{XT+9d&>*LYXGwAH|+VOetf<T!n)fE9NdF4VW>VZkQuT?8dR+An^Q=i7vF<
zB*2pkEnvc=<tq8XTI?=QPJ&3We$`7jQ(kxiuv)U}RZ_AKmJlXUS3MGfUad-6L|MYZ
zvx>=)=vmQCa2?mFZdlmsR5v1momdcPQ(@9XU9aRWY?xk92A8Q1c0}g3dSM%&PS>$W
zgapG;phDEdCv#PEX|QU#Q%{4H61B+^)y&n4b4ZmfN}5G`#J@RyC<!jb?n1<v(+SqD
z84aSDP4(b(@=$cozs6+%m)Vh|xD9-0Dsg(b6Mp1^n(unk0G-a|XggY(7~Pemj#}2P
znB|6CR9C^BhPngpdK=wvi@9$QdqcJ5vYo=BYvtyipJ=6^2qc;4f9|?zP{`d2G2(9O
zMl{8yUPK#6!=4wa#LZQQ;o;_@>y37E%~cd3U=aOQiM>~XCyx9Xh$T#L?z+K{IO>Yu
zKH80koX4dGYZ}Y@y@dYgD(_B&NEe*NeUsmp=AD~bAWjG(bk{|AKR7&OJ-NAqm6pml
zLU$?O54W&PEDyIZ@5_ffRyFGv>A@th-mq%93Qa{sVGJn$d#`_iueW3Y20$+~4%B;L
zX~m=@U+Jcau)#BbNSLfVl?6}p@Kn|<{qSVoDK|zGG2snanqI&k5AI+U-&&L#<00j)
zzsX?DMdBZUmrn|-F8}8Nb9c&vIi!^J6R;maiXnFz=r&4znOM9gCKn}n{1BZt87#<s
z7#2S%aeUB{-H~}o%8{hxxWN2R-nm8Lm8%i}X|z-OScDrNPw?q8)vdif@#)+W9hSyV
z%FKPE;xXs-*#cKou;9GKhN6%S;?<)$I+*!rjxjpp`NuX-KUxbBm3RC?!iqqGIsh+s
z%B@MFSA((olZ17Ok0U9r+D+`o@LSjLI7ieT*%;Bh_$$i94}qarBDHFcSP~jfJ}CWT
zr8DAdYhNW~sC(0{60#JacKs@3G@X1<Ht9Wrz*T}kw?~X1&iErf6a}LBm7wma&}d@;
z_WhHh9h{uQQ~Q$wr9s=gH=TKT6!hM7<_XFE8hg9z2t-PL?_EbAq3t_6Vb-*ixQZBc
zD#7>HhRt7xIU~I4z|RP;&o*xx&S&bff%BG?19Z2rxIkS$J>Pn+Y$sME(4BRtY(ZUP
zEN#FlyDwEg2uieJ^wy1uiVDYet#;Zybn&t@gDz*5bEx~9@mhy_6~o{bjFNB84Opcy
z+K*IOz&vQ{&@8fuM3*)MX`ordRVt%P83OZC(Uo44r83wFjB!`5{FT8z5OE*UpU9Sx
zp6OD=Slq*z*~a=GrM<2CAnsKs<B~dcvQEZDeJWbF)L?SumKF?=aw)Xr3C&y5R=aN+
zEf%OWTJQkzzd=EpeRv=uo6?1X#xgFYa%Yhj7EFGr42;zFBa6kPs!!P%RB8uWxf&{Q
z0gHx8St4?4dtWectKJ|eeN)erj^Ir`Vmbmd@yy8?j(YiEhC?qOl)A}>3<Q15dSKxz
zx^biW)&I}h+w|O;<Jw{K=U1Fz-$7SIeUX|Puni=Gz;<U8WMacNKu|sK4U8oJK3n8k
zYws#|y{GEbMFHJMe77V@k0esmBDwAtSLUn5FRq+?iywS&ApGWqM}CULTKrg{T3DgL
z3%>82ng0lPNVrXnLjJw)uZhsY%@gczZtj7S<K|qAZsX!oJ_UfZCR2G{0&e~M6uYAv
z-r5JCanJi=KM?leefb}V79j({*h5`m{$<S&3~YQ@GjO!*QmqIf0V*pg;P`FKfK6)b
zg*yBJYhZTwmSF`eAI6M#!mLfJk7;tLL>o%Cf|3x*lF>A^yaqG8>e##mw~sb!DYPun
z9D39$P7GmlM@DohOBuh<Q7wL-qgwntFo;XFaiox#%1t^D_G>E4<*4{KWwjfH@A@{C
zsB{3$HAno!RB+JAhtd)vc+UhvnLw_$k&!^IiBzUHpWjd&EEFU|pM#~UAzAIXUC|^u
z3YhiKZVD1>)lZh{kP}>xX`LO2(=><tHO94sRNhlsK@_ue&<Zk?sn9<x$OCw)OTlcp
z?9TiuRpJK;nVk7SpaYC|l0smtrXsQ?psSTp9TLQGCwu2Sb==8@@+3t%d_0r!U<X2U
zO<~~&LUheaf?7eu<~s!{Z6aezccV>24+VoZk->+>L7T`sH!7lU&5zuu2&XnHIcntN
znSlNTdga?kjTp$LsldCJGHarA>H^2~epb1_tvu@9=~9F5BLgL0e7Pyca39d~&Y-<S
zFF+%>F1jY$RSPMof{TMFrAw)At&=dSRBJ1^IFu<c0#BTJ_8LGNy<f&IAgkBQ7zaob
zIsc4@J&lkimcgj^BcpEJ@<OR5U%CB`>0u8m`4}f(>HGlDnq6ldkVUgAV;|x$&aRWK
zygHwHz(h5i7VmVbG{|&adCtJIr>-l7$a<1g6MFF49_kAkhXQ_IO5g>ST`fH9%Jx$r
ztohEK3eV4cA4Vk@Y`S#&g9kMRHLoniUhS|eteJPNRDiOkf~F)W3(w;4Q{uaM4KegA
z&QBE>qY}c=!qYeZKK1hcfK(60?;Ojuruc$CXaahtMMa2D!2q7jDqS<Doae0-G64Us
z)xpzcB2m&Ce=r-~K;9sQNt=)&^iNc&Jv9*(^$ms~)@&-B>1=$xe`iVO>pd|Rnb?~!
z43vxA@lC103+WMHgKzhQwlTqYVn4vj`oM-TLHX>`jV4V-O76f+=ZP`_C#lEK5w8$#
zS#B7M6Cu#l2$vBzI1{r^gfv1f_r%PAc|x=fF&a}Ct)o_m(K=}55VoU_0~CkJq;auk
z)3{47XlxJ-RE=5_WN3YRXS|=viIUK=RN<Ao@{$VIrBvvKg<@0>CSq(&C6t*=k~S5b
zY9jm8R34j&BvDgtpMZi*#k{&uuvaOQy(8JtRQ?}Ayrx`DCsGdb|BF(6OoC~N^O|&P
zy&X&i@0yjpXDVqE;apSMpD?H=`Q@a*P^A=AgmX=$!s3KYMjM+j@jWxsqD^?IPGxMX
zFEtgyj5w}K!EQp9)M=gaKG#T2i-|cLDrQ;=MD&%KKMCzJEdFN_+GSe)SmU{DioFZ%
zl7llgPOiH}Lc+-iZJ9Ji%5NGwRIB-C;kjm`{*8TK0L+><WI}lnvP3K?q|qcatWg|Y
zN});hI&et^C)G;tA8^t|%Bmf$Uw9GlsCG}>1g&Cxgp+QKk8skh@!<`kY0*<YToRT&
zF=Yw4rHq<w;bUQ~HI{w>;e7<Bx+G2j9w_9tPsz;V_h(_FCcXb3$^6-Ldeca%xQi1x
zGG^17gzhpK&=G*6BvE&|lvT2-W~%U5Lm?R^0%oP8#!nC}n@YgXgq=uH_*oc}OTkye
zC1WVErvM>TQ-0Qc=u$92xIvA>H|2>u2jghU=qs9P6G-r*KLe%0cf&-$%jhN4T7KPL
z2VT&AE_}nH&R2iNa5QnaXOBa01n=gTf&osXyc~)il9q$krL+DlbHh+XSz0Mx6qL$U
zfmhUP8cBbL`gb`gP@St+{t>hi^G%<+cv0ZfqE9;MMZqUgKE02S;Fxrx;B9acot5_m
zuud-uBA4(wJ{aJ)%zNo@f>LoOK-EO(l%eo1e2yL=y$NQ}5mQsW!QG^mM=Nb!t-zgs
z_}IXFJc42Xue9Z%17r8|;lo42`lWE*;2$SnpgHAVq<N!{5gvT;Qt<XV;`2yeSJ4wa
zikcQ6ylCs)KLse`F1QxgYPu+A37%@_7bQM0%mqB@aF`tC{c^5j6j=#|>lkHV0@o5?
zEP@Ik{eV<%b$MtaD;4b!MM;l30w5*>2Dr3^g$Nqg;K8AFw5qeTY_davj4q+t8R`lq
zOd4N`RFkHIlTP<8y_HV(F3G(n!V|b@<mDBJPe=!PmzZ7)%{ERh{N-JFQZ6ao*Cd${
zcysLcC&k*|IxiMINDsoLUCK(U8Ycp0uL4v}y1H+^!OsPkqWxYDo;JR*wHlmWoMI0S
zMO%jg-O)Fm941V~*I;=#N(58c5(RKS-%Ha6_w!wC;OyR0AM${=sqYB?A_W?o^fTYu
z?g(LfDQvf9cj&O$a68(BW?f48x6<}8%Ts()QqWOc;nSYE;fJ(!huM}TOg3G@x1m&1
zr0ovq-9zJdk?I@j!Xkfg+EFLs3y&oo4MB*Xp|Elj&d6hhMhNk;q?f@xd92_VvD*l0
zyd-$<EvaFE_Kn4dxrxwlWARaK=G5a!BG;<C!nY;|u{4%M#-8=;fysevTDo5BNl*Tz
z$w{Bp#jC`gaOT&w8UVtvrX~i8O`QleM)<KJ-^nfCBSz5-CsJpO^<FLu4)t6v&n)lh
zv9w?i^FrxbCLP6>P7^wcFW!0?0(`8dxy)^@fCjf*gKV0ANW9fhs%R2|!Ox9dFMPm+
z=eVBMCnB7Wsrza^6Y$|L2Z)0~Z`GGlp*47Rd=TEP6gN^jHVjTfZ?tnWy2WNYI8KBl
zo4aCLY<+q7nk#a}+zM{NZ~qQ%!AcBnF}0VD;%ZD>P&cDnyq654Ta1rt72HC%OT_sb
zfNi3o3U8qcr8m4c=fCkyq(fBF)S>sH>2!v~bI>fuc0Kh>I=3su)-18ZSSJ%0&@tut
zHXZR&@Owkp70DTRzUy&i((_%fCzo<hWnrr)k{FB;AC)pbjepds2r#Zny@JS)FZdhl
zQDPSKlt6_d<f_m+!=<dkJ7A3hojUYhFyU1{)<>O+lruj%sz^CfG90<`hMWs7sbb{}
z4T({P#z!><@_E-<)lmPaR+H5~swIp4qgJtKAC=NpF%))rIztV;m%~&fBvxajA+85T
z8v0ldd4%@!QKiC69aX8IO%g4RGquM@ox1SA;b-3AD46wRoB(+hCFLBUiHf2aQ#iF8
zr>^{-E@fr;U8#80u>gH@(4zZX3PWPOYcV7iYi%$nJ;QM@cV0iAiDW6G<HdX;HS|zY
z*GtKRLWyA~V;6MYCLHhdL#}fZ;S4$p`R$bzcR~>#U5W()E@WggPL_jVNd>PX-k3yl
zGAe=`3?~v|57;%IBCW)_y(?7!y!fb8q2Q=B)IDOnO_UCgsbTNUjyn`%<G(0~FNYD~
zMuq756G?K0?e{{B8qfNu!{~Rcli%ZQegqDCDCzn$ogx0DA|RCMU`hdXB<rFxn&5k*
zBS!bI_fAg%W&MM@nz;VKO--C>JtK0U>1yDN9B5jbkYdc~FrA?Ur8Ih#xa5Gt8E>l|
zV^=iEe?JvjQdb2AvuLtLI|Bzc85Mv~A8(tSXDq?yAC)S)<o>9`Sd#EbonC>U+R_9=
zV{h+M8?v*#k8OkwXp_+Ad827GNogc+8gG+YK*TC1$;35!yzOUE5QiaO{)wO=gyn*g
z%xFt8PDj(0Oc*|}zz+$_h#3B$5LH~1JCB#L)D^>;a^1r`kN{@&bw_w9@39xfKgNE4
zeJNa9cmz*KwFY0|YN>a95I7r_CC&sQ<y<T`rvlOO-}XHuw(4iGlp~TA=YvAy0bCTi
zqD_2Ku+(5U=?ZJ{NuiM?>VxznSt^QTDbj3R%KBBA22*6~>Wt^{NzlY(4BPfGH7kMs
z?^#HudYpGLy#?OWkRM+`P2Lp$7;{BQb^vkS6lq0Bo7Q8047n&0a8U_oqAp6$n=n4u
z%@tHuFqWK`&j0l7KRovB{`W8c=Qo27=i<=`jTAECU;gX2e}3+^YOk64_5Z)B|C_%(
zuk!1^zeZ(4Ti@1wnD4Ll?Azb|{`^n>{MYu^_Uh|z|NQ*#fBD-#+4R5s%YXl`|MY+S
z?SFp$?cbiet5-ySwYlx=b{l`)diM5j|MA~{`){v$xAFSl|MK@6ayA#$x{*@8{XOF&
z-EUUq8rtvV_Byf6ueklo|N5W*?|=H+|5aQDni}5MtN+(ZX&&<>XZ|6Zy|N^e%MOdm
z4{!-+<`-Q4Z~x1`6PNQ&<-AikPPhH~hqu?P+COBH5m?FP09x>q%m1-buXUkHz|?$Q
z3Fwe@1B7QKl#w{?56nmT41c-C{@p*V^_Tzt^UvSz%xIY%E;HNr%f0@wrkU@5I5iW3
ziKD!)H}7TlHN*d~z0z40uKBM9OCMRf_y5CrV>M**zI+rLO6~ne*8A%QHru|-@;>$a
z<HhvX*U6^U^vB1S8sB?#PyoLg+e9QDRhkOT^JTS4T=}jQcoq7x5)hd0TFOQ6Wi^~R
zn*O&-!XKIb*XiryLI<yP{rGQ8|Bp{TF<bA^3B>i~=#WV3T}_#_zN$tLkE)UIoobNJ
z?`q1E`DL{|u@7PWoqzbW*XmEm>~F08_GecAfN#ZnY;v~va%`jhVkx8iol1zb^R8v%
zcP!<r{b4C1HQ(7EOZhjeK^@lzAmNXRvKQUlB2rap|9A&{Yd`)0=&1f4-5$SVDR=l>
zysOC_<I8Hm{=KUS4ESX=>z`+26~C^+yqTJQCDQzZJK!aMhp&uhwts8-|I7|R>_rU@
z<?oCRk0S3{+kVGVwmE;flu7tbwSq`~RO|7vlz+1tJP+TW!0cmb{ox&8*Ff=)520^=
zLIwbGp}`4)@zvPi6t7B(_xV+&d{9%B-M%mA$FJo4_#J0s`7pkZo&8=;e|XiucBlWw
zqW@D$&-vx*J-=h^e&~TD*jEP?-X!1EM4&zD56sAYE1T;jFTSlCqvN*}ksq3pw41%z
zMDfe9!PM}sB*K@~%*rV6uJ@*VT@i5XkBXvvT@j#`kBXxFz-O@QTC`uM!TI_-{J>XW
z^4kwiMfrM&u<w0T6y@uRH)qgiHI%=s)Dg|_UF}Wzx*||<9~DLUfiKY$`~2M<@ne#a
zA*nui73J$e?q6OJ|NiYw`MP4H{`gUkgs-b1lIll2QNFBrZS9}kvHSyHB2)atSZ99q
zC4NXn90;@b!KWx+4-bJcJ}Qdxbw#A!{-`L**A?Ne^iffiuPau<@{f8X{K&Vs7SvK!
zzWf$HCOUyU{}6<td^yB>r=7nzgx{2}D<V?Dr|2c+>xzgt^-)ojuPes*tdyl6_zwBr
z^Zh;XLrNq3VLrGN<;$U6!_F@jnh0N4Lr}nvdZK(?5q{(!6-D{FBJve{R21b$RHuti
z+uz+2Kc+h^I17I8D#~}3_Am9&U+S1YfBSXAzj@H*r!adTA8At);g6{|ubC=ymu0@D
z-!Qn$A34g&=qN0~J<9WqM3nE1uqW*Fqh1Go`0HvFk@}+=LsWlRt)2bL-az<XHCj0F
z722nT^N)XocEQ`fq1lW-@evw8S0BUM=WBV2ia-Z`R1{wD>x#4gy2sgnSC2h@-D8j6
z)gwR%?{6Vg!Vi9o>z?!*AEW=7kAe8{A0uq`)ioOxPen$1*CXLO)ezC|UCrn3>8;{F
zd{o=^m7$u|5S4~s;V4SY4}FAlL72bw2=e3K;2;RldvIg^p1~on;k%j=9e!D@{3t)F
zHUG+*g=%pM{Gw_ke5abs!1V><N36iFakWw_<6qedOfHd-={-1Qlm2pWYkX8$<9k2P
z_^<B@2nYLRmA*eJq+|1!KZl_hbNyi_{^K)!QC0tn)<$sXhYw>I6bWAs%n{7sT`dUb
z`?8wbuX=O)J-s1)`@5R*xqn#=frB{zEdSsa@Eh{$H@?81IPrb(IgNuGUp}X?8sL5J
zYQp<{Sq<*v?`m!Sj@~vxGpHH~->C+OBfkL4Kllaqg?atPY4ax(puNYh2DiU_h+{Qm
zIeb@B+QToa{aWSSzf0rYeaPrh)%y4ySAmUijQRrY6G8OHzre*){>C2oQ}=)m%M2-B
zUYG#*`>6P){J^d7!h-99ZuYNiwX$9~un$&0NZ+yL{$grS{1HR-b=BE;wffQ$^dkou
zGp&5E`a$}xh4fbo;DhudhT!YE_q#^=L(3I_-Ou&<CVg$#LpspUs&CSd824`UM*BS@
z-9KViY7K9sZ^P1?^c`Eq{)Nrq@88~(A2FU?&zIjd&iEnwS$TbYa{DHI#}pR7UJM_k
zA9~fBKdtfoQ|L$3JsOZcnSGPKV?F=1B>B~${qwi~q4nQ0?i}-9@96J4e2q13?#BAq
zzaIAgcSrs448MOm(Zj~8_H`?eQ2NXNtLga)mU>^i|DWHKD*<$Sij}(<!eJ)@`a7Hu
zHvqfC>-G@!TSQ<7wE9wNh5?bjgt~SC$Q;f{H2@taq2U+Tqb{6CWxOPWmvc`PL@b<6
z#gTqm;dK6jpM1C?OCeBNI6VoF12dfNAjkk2N+lZUWfM+arBXmXNda5sniEJ+8s+>H
zP7hNA2?%C1O(1EwQivg}Kqv!hOw26f(Z$LFx?7mq@-~Tu5iADr#Es-qI(|_TOB8m+
zLI@}31i=zQ7Lb6mOUT<j3ThQjp9Vx~2syhaGCa$u;h6j(z8rkOU|BgfL!R*A_`FO?
zfozfC^ku0i6HijmYhZ5a!<KO=Lb+~%au0_yEMnw`D^3pLyS*s4a4;&Ocq-OgI2|q!
zHY1!@l|aDYkT3pe_#kwzPM~l&)0!Y)M>u0EoCcm6-4IR#Pjt*b2EJMqE>H5&KgCOI
zy4f5c{$ta@>KLpE^wfqELTm>8I8{J*b%?(RRY<mC)9>Tdt5s|uq>%CRmeE~Z`!_GE
zh%a{unDsMi3{n3s{&|msK_?gq;3XGA$(zpvZ}QIrP$)LdN0kONZ6|2(ZCycw#UH~+
z9Jmc$3OHWim}ojgsf$hL20%T6sj0tZ(7M=4xdxnDFqt*74urxGoSlXI+b)LSKYohw
zC^zzK%)w8AM{nwZETC&gSM(Hv`%Neo!SM=*a4EINPdT~;f)kvm4?;hT6Zj}ZAtIAO
z?7_pd9%y58yOyg^5>^#!g6Lj&or|)F2H_SSTUlirgpeW^TuSu{zjVt{DQ`OB2*sAW
z(<Kf32o<tdy2}`h%9p|xF;`7&7$$4cLCP9rje;Ls%AK&KWUO%9ig#l8R;Sbx>#(mn
z$zmxHa2v0Z(#<0u>ZPz72&koK?w6FSV}%-l1X_Voa;99euyn+tGrUzqs3%EecEWn7
zjM?xbh~?zIS~ZLpa%g$xCPuKmSX<pf4lU(nNA$f|TfLSjT5$7vl2W5nPF=*qdQniy
zWwn<2xpFu30Aoz~5KCF5TS@OrnV4zM61#AWMY-wWN%*2XC>G~RY~4zFE#=Tf`q@y-
z2SXx>OMzGGCDmA_I)VgS6Q$dzvTnmK@=|<(kkKMyDLZ?E1Y1KLLyRqD_^y~~m%wh}
zR9V(yLkiniO4SUf%}YVg2jf#}VT5>#C1H9=D+$Pcj3l<9*b|1ZaR8`5SHG81?N+S0
zSjtFk2uc}J&kcEOFNF<5qOGQeA<`C8Ut1O6>}l|Sy(Ih@Uzo-#L#EqHVZR;h<FVjL
zQqJ}~?56aWm^ujnXAfm|Fq>7v01=col#js>W-uz<OqTEJQiO|3$k|u=1v7}KcPa&g
z_d^J~Z-|K)$arALL>o$PU<iYFDLLpTNyR^P;Mc9}Rod#gq+}plz%A$IP;vmX$_gFK
z1Yni|3!(K55fDRZsSIY5U@j{|OvI>|88y0k*9&2#4G}9tVKgqKSeu%G0CSVRnU|E4
ztF-lqmKlt3ZwRLtifVr;HMN5=+6(~}V`{f%n9fiZGlR=}OlZ7@@SmY@^Ow?drUpv&
zF{sX7O0lLC-v~q+3<__^p&RqP4dJ05v!is`qE2fFbs9=$XNbsnDeRXrP!Zp)Lk241
z`=#`18K(*&vBu<|Yq2R3vLXCH%%-j(5|#GP`p6Q_vW^Q`hIhZEI@=XF<dTy2anxje
zqflBytE9X!jyRt<{**w`kQq3}L8;!xLj6D-4rslWEe3-m8j=Rb2(b>4sQi$I*bkww
z?3YqcaxCS(QCN0Eh~QvYc0=}@7)l-wqw1xw<JySNC9&s?(Mf(I!11NvjOmbhW2>QR
z@(IOPzoff)lp53!Q!*6%gkA~36r+Y<&rumjACPi|B1x%bz>ZK7Q$rNWP`DIBir!E*
zRO<-b9*Ur1$b1}Qvg?B}=|JcQ-(dd4Uu;wvT&1VR$e1gJnA@Q=um;d>3~Jbh3_q8W
zX#p+?*S0|w`BHM(bk)M;Z7^4aA+XA&ER=Kigu=2IvI2#i<P3icMLNHfnqX5`J*U{D
zDx=RBhMqcRSn4+zk3sbt$%R6hgP%*vAvN{PXJrUl1gg1ZoFs@`AIgSoWm<cZgk4-2
zhmwMW0ii%czDhRAq;V<WFXcz{BdLM#{L!UkBP35KY>Xkye+W`z$XpZ^%DfudS!B<J
zqr4RKT>9!I@S8wPc2>X$rI%NdgHTj+Ll)>@s_aY1kJz<q5w_?>DW)z9(x!2&MBic)
z60%F1#_<#iS8gN7*+wzBl75XGw3k9YAs!W-+z_QHx{~D>5@ke}mYq0*=+d!~e<Lu~
zgYP}n@xlJ?(z=oMBPlh@NGThNU~Wh#5?yk6B3eW+WR7JZtI$iLA@NBl9=Rc1Q)E1H
zLoSu5ki$7XL{bgrnzs_jq4?wmnSCi_4HB`J?s>(=ghW)>azo;$=+dH*lr_4vXk@Ut
zlnO6&DK*`u?njQ%)cL>|wY{MMh44B?Eh!MU+~&%ElM%=`J7NSf&ZrI}?AayooI&!a
zKooPUl%Ziqe3a!g>}U?kIvPfE@nfY+h9a9AVzPxvu}0FXKxA`6QqEguPp@qg7U~A~
zK9in}EMH;Lv!R2BA_m!{8PcR6r`{g6#Yun@8i@@#-2#5)HtVkxIf%g;MvWN=?@M4G
z5L~vz8bp_sY3V6a&h1jaxV9lUk>M&6ik5D;?p#XePm--mLEm|43X|rID1f1WMuyy2
zmx8@ou>>Q-89gA>0HjqT0Abir!&dxj@8aed$c%W$i0fr243Z(E)}?Sz5PuA^ehJks
zyGD%H$e`=DSnPLo4B2O01A_1~Y3CIK_7Y&@PP}lkOYMBYn5pnfmr`q^qg3lc>iL>a
z7TGJ_6HL1K!h?cIHDCFpU{cH%o)j3!zeqK}`a#J_lhTdomY0I#0@jnTrdE;EI26j=
zV1;>6vh)&>O^P`}$A-c`8EiU9fp}gJl8W<wDY+(^l=W3|vPo4(e9vfA!AsajlRz(%
zRWKC1t;<GLg@|m@uopyRa~`D?9ySzA$`Bs*Qg8$y+gJ#)Xvmx%3i^I2wT;>)8z}%A
z&Ca*HQHO)C*^4H9d$%kh2-B;G`J!&U8>Wk9WviTJfiUscBl(u75O3&zmx3b#`O2a}
zBd$=h(P&=2gj^g=>hFfhzbSa>C1tlm&34S%K(mlyiXv|?E=Qx0`7s!vFNvL}7;93Y
zH*R+g`Y|H#h62xDO5UlPL@MI;Mw7yfjAx<1S(j2hQ`b$~d^D3Pxna?7QgxBvJ(?`i
z8=|Z=O#?((nX(^{a)PB0Z-}x+qcmWjmq3O$V2Vcu2!uhtB=+uE!gkwrd-Fr>cssC<
zGC$`N%ku$#G`zyNqI}sdjrLO5a4Nli7<bc<W9{)H1$oyW{ZK*PA)F;U5Aa_V?%$vr
z-@(;x_ap5XZ&iL|v&M6lD>s1Q#p_ZkfrVAtwoAa_u@44#Q;->wxcQOU8Y%5B1syx&
z;U%Hx41ns2PG$&znv}+0)ZnCNyMf!Kg@AD0eq@)fc%_%Xb`0!FZALyg&#-1zu}Cj-
z61*9V)RolWmWw&5$X?RU<zsJnboHZzVTOm<7YU{O<`T?^F?uO=viQJYWSRDX)g{X`
zVufA`M>8?q+VFUncBBu#6c_<r(bTLSw=aRU7TA%F><cT9mS$i0BnoqQV<_DsjsV|S
zb22>R5&u%y&(6t}*_mN9ogvx`P=QO}JZy{zN;SX*u1pP9F*5xq9I7F@r3V%33TBxE
zoGgg!=pmK3Vpcd_x$iatyuuak%_=NoQWna+>X4VZUb}KSSOrsjlEi5^U{887A|-k-
z^q)n`68c5R!%Hc35b+H?WQ#_+flEQp2u$co3}NLE>;NQObr2EyE-43uKzknAorofL
zvD#oZ3d&7JVL81da@)b2uDH>`oD}Ei!i3imS8h%oZ<}>=OusbesCDik%^8XLE(IGH
z(eN&XCq?G#y9D-KV)jzd_rMsXTt^8?4=UG>;g25L#Z~_j*ms#hFNIyr8WlC^z-#%X
zu&aeZ4V3Qhr6prlU3n`EQ}2n`c|a*<r6$J)uN|f2Q(7{<u7?!mibVJ%i9JJTDo~Rl
zpNK2_g@tE{y*gGYrrog&n)>w|ob1<F;2u(?u>qXPGhVweAPilyIUo&{F2kZq<O<@?
zrSw*QmgkaC%;hNj)TNZK0kz&bI^5&k1%jl64nV|>beE0#qz>XP6E#9jx-xfMN-^&U
z<7hy|yUQwlEK4}|5z_Kf*iC%^7xKyu(zLlt9maX@!ctwz$}(AjY;#$k4`iD&AiJHB
zB{DX^3iM;->~WXv8RE)aw&xOQPm<X2sL7S-`7i<vHEm=Ja>1%DrG_(c1fIIdxli>y
zf2vm5GvnMy^*#`fgkn7zQmK~LP_<RuNvNI$?xaT}n5sK%(HRM&_>(dEK>j(D?Tn4#
zE>-(%Ouq#4*>xjGQsa+`V;QFr`Snt82$sU;ZtB^gQaY^DQ2SiaD}!q2PK_Pv<0Y``
z%UfeA5JQ|dcWLKWhs`oJFS0edOE*7(FVLt`mOkxUYWIP}6avc-NY|A%#h{k^mht+W
zGVD7tseJ3LWubWQ4FXe%RXRfWx{z3xl1p_99&$-}3~XxWmvR@wrf%MmZp(MD<5F)N
zs{U(DT~e-v9r!_w(A9I#66$xbN-eu1P2}?;p_nXe@dUxRx0r%p6y&PoTIdzC-~lPu
z<K8IUMwfVkP~5ascf?@66n2d4Q<pR`trOfY^*k}H3#FRTsg6n{CSI%fN|CoG{#{&f
z%U()x0adxTl4g6T!(A36-$OIFv4psXJF>_5?rL~r7CRd*d&J|LR_G3+h3~HMIwrBJ
z`xI(|W_3i`_H7y<E`i(BZe0SmsoB69p+4PVv2oZao+8x}E>*b0?sLoUN*k5P&B651
z4*gtGGPr1n?p8NtU(lB?;qoVdR!5w2UuA~wh6}kb8lo?$-0WzG?nsX5i-zcKmTq|L
z7J_XB4Iv$=GB0VNOlLlJQ<uCI>IIj)6&j)8mba*2cf^SDMFqQ;-7zT~V<}yivQW-*
z;S$(+$B4LjZDawb4)Sxla_D4WqdWa;zlR73$;3KIsX=aZT;g$Qdn1bdrJ&mhalf|u
zhJ0L0eM3O5r7@>~TuU97boHfMb%&YS*J4)-V_NEIVE|L@E(~DO&U{HZ27;h3p~f&Z
zDhSav*%bullG5GN;_t$Ab-W4qqR!p%Zs2RECy2~7)Dx_nz6QH0k-3Hj<yZ~_rCJJI
z9YbEOE@5Gim`Wei@f30?>^bmNIy(-Gu`|U?NBUV`rdlN=1?#$m;*Pp@M+|3Q{CkPR
zMcumhR;3yql9T$PiMk`lgv<G&BVFmGP-Nh7%QGp_E#*{CnyD`(r<#DS-b;J%dDOGz
zHO1#q&vol?m2wsZ`098Byc7(!!xdM)2p#E5eY$Ev1Tu|LN4jL6u8wPoINqtAA{8&x
zq&r?dU5Sl)pRdwZKM;6KbJRN`;QQPfGeqFr>YCogRK|NHLcIibTpIJ^bFt-x5iB*F
zq7qQBj*Ka97v+wp>Pvy_L7o*CsOwVb=*(8&=S<EZ7$+6!rz7e2C2>+98K(p_lBl{8
zEM3aVGJ8f^MxO&+<F+@4`iAhFL(>A`DcDyp*nn4T$On}AiXH93I6Ax9Js1G@VP?kh
zY2x*eHxs)Mok-l&k)_pz>dNSI$s3gDOX$@sj2Ioj4WG1oUrMb)+Pync+g}R0M)Dt@
zvU~SYRoF8`=WOg5SHel7_od{QA4feKZeru8Ygl&#0PDzT<U^YC=x{NY<~&B0#2Uoj
zkdizg_6C*Y0iicS>_O-aR!D27a!qx>g)W7h;ZCURQyn0qOJT<VB3%-ChD}D`txKu#
zI7&IyW2@(tB}%ffFcyj90RcFqZ3EHeL&`JKTY15@s-cu+V|`RgSvHn9gDe{hrCe`A
zs`H>6BSfp$Fn!Qo-2r6tL3?!v*zHo-aUPMEz;hm$xfdx*5Mx4Yb>sx|K_whMi#~=r
zj-T=a4)u$>-;h?0CFMg}IhLIdY14y}Oo**MTb58|;)!9<R(&bO3vAUr6Q?;>dl71;
zrEg>Nx!_tI8`PDFt53+XVG=vF(S0=ajk_IVcXyybF98z+q^JYZ)u(ZUQrl<G68nX*
zv{R@~2*fURe3n4GhuDMiK@~PxPYzwG_r#Nfuw0jttO6YP6e)S_p`IWPkrb@Yng3=l
z5Qbga_@p!xma8KzpLc2FNJs3-CDvz2!!BhUGVSpWZ5-K&y-OLNB`}?cuS>{<(4~;4
zr1ZWeDUh?+m5!{>ouz63Zy3UWF(UY-bp9j{s=nS0)ZXb*tD!o$AYL8n#ig)e$3fMp
zXeZ3vmCvjLi0*xA+8{2w6mKBfy+B?yLdeT5&3l%-R9>`8n5c!W@fgylOc<4Z#QRX^
zcnlFTtOK-vDP$QEGjU&i6+GL!^kd{P_AdQ+K^S(*Whk(hfKy|YEPSnm>?40oOLm8w
zgDcV6rPLxY^=dh>-22ZZ)U4H?J0`5D(OwfKT^jnl3+vU(8RRuMlP(O05ht3fm*0sS
z?b4T!Q)owH!<&NDx2v0w3#Qd^S#k@u32CNGZXI_n2YUa0y9JSEp`NQ%_KGW=kXs$T
zJvST-`T^SbQrJ=5=uGPL!i~;c-9QWq?$vS0ecYrR!^z1_%JK3nVOzsX%1xRvlGJ)#
z7$1;|;iaj9m@{h6tE8Msd0r55Ky&ql>%=9nZ^${N!e9m;x23sCtEWllUa)%F)D<62
zX>L%l;j-o?9lN~R+@|`$4bPOTup=q53*gnuK644!|1jZP3eFzbc`jw4T<46E-1Rgc
zxzJo4Ns--X-tKS`ycBe_Aswv~nb;A$%@Lrgmz&`&VvHNIk#Me#RLPgXt_>y@Gxd%8
zpc3r$T_p|>=2C-J4i`zM=hM%X{UJG%KD|pC3bJ(x#hWzh4QW`Wue*)*OVlayO-CwY
z7b5FYa#^;cRw3!yQLDgad!wDY{8YWkRK05@d6Qs9Dq|NWt5-7POW-jNGp#pj*s$b!
zlic0=mg--K<0L(KLyQTh)#32#O?onXf?pJrE(bC~BayHd{^|j#Sdd=4>j!KwFoheX
znm(DJH=fomiE|9eB!pHk$7ye}KqKtri-J-vhjPGtKw3$tbD`cMUS$+=9SEIuDb?e6
z|GuV5sxA`px>6E$q>lF{qqIXXHEF+Y*olH?^?aW3CX+N?aJ<nZjW?c4VBe5kt!vux
zSmaGgbb0K%FkBrz|K6w~BP_rrzz3)M$RbCCJDo6I9hq{yNkR5}LTIMpz`@9y^kY1<
zd82-e9Jt;jN*yw=K|l5qf~^tX+mZ10lGroEU~B4oBE*=C+Fnv{7s9I=T3N)Q;3Wq4
zflV9PYxj{7?X}4EkxAPj7cYrDr@+}lfpt8v?jt3-qF3w#9UA#$ZyAV{ODguYd);3p
z>BsKiRSGg*gZF`c?8p&$31r_9hm8tyy*Y2?j_k<jx|I#6<Dq(=x4{}QLH3cs8c{>`
zf!>@!MYa%K9Z^R%1KxIrh5u66^=(nMYCPU=CAjHGQ@W3o=xE^MEohO{a|^%KGll0Z
zzbh3h(teR<^HS<fvLn~!R^rM_$qy!77a)jBVMm6KD7!OauIwYbGlH({L$h;q%&vrQ
zbPQ^sRO9J7y)G0a3GBCned*9qa(fH&)r0Z&paVZis@<R+9y3d<GO@s9VUCGU!oM#D
z@Owb0iItWNRL&N5s{^@nDeQD%sui!J7Xs)~*zv+#H<WUoLyC5kbl609T|#oTLssY5
zSz@oHYVKeuw}qfzH#28`mJqh1l65A96I8NuD?;w2EY!kL5Dw02TRla}c@JvV8In*+
zHCnqA@>)IakYpxTThOjdK-#KRcAa8zhwRiC-KC)8gFz~X?<M8p3#sBreR?T4L~hiU
zEVJt}C+=W!?v5|F1pw;^<FW&qcES60NQVXlaEG+$10%~8wyOh4xI?CEpbd9Gug>JJ
zJET>glApW62t6R>q6}HCk6{4X?WY9j4(ZjW*Viw#`YB3%e(2SR_qCOLwPTC!kfMzw
zw_8}RCo|zDhtiVI0E5($>s;C){TD~q4(Y%L*tQ)|f^q(BVYM!$)*VgLr`p7^14Qf&
z;X68DvpZy$2C{aC^k^K<TY#;OBYbBH=9;OE*_0)^#K3kLq9G}^GShaTgEv85Pi7%W
zeq4gJ(jX@VN5Lt9=7MV+2sEcD`nd^~bKN^N<pX&plvW4w`b9yhc#$poK=0lzV>BS%
zm%^@3g(}7T*ByTgv~?-Py+0^cv{Tug&#A#|^>Hv5D%}J6&IZcsDN?Q<r_MY8vEPDi
z4TO5xPNjJu(#wX<^Au^KT20G<a=3G!kJ25t(;9sV#U3<kB-?(H!k!`Ce5z-NIHx&!
zq%*=Tv)e*Yy(kZgH9)H91O5!#2Rp6}wtcAIQA=*nC~_(FRfqb4loZfw;1;mGtE-6#
zherO4bo97oat}Eu6jvrUZ&iowLJqpAUBFzo8^=&$&`m>t7zBokdDXX5BOkaX?Ye6`
zAl0%o_5G5B-qi2LN@(nMV<B*l4_@fDx1acvjXLbO6v(}g+AVP@Sl7T+^HN|ixTGAw
zK4`c8Og<qAh1g;i`%7V?l!QCPEhOO%Hkzw+hj@h?+@bFSL0EvT2c%r4+toP);dXUi
z*L-WIqj)F(Rm4Yql6Gf5X*Ipps)TO}=dUDTKfpySNwuV&0Y|c=VX;~%RY}5(S$@M8
zMPJwIUrF*jjfd6GlSC$v=(|ZRyQEQ!6AduZzLEs4E!b$RQSllu<RpcScMM0`*Fb2P
zB;iVTX~}!&`&$R^Qp;{?)8ajX9S*P_K_zA&cUaQ+qg6#L0a(Y9gf##YT9RN>9I&&!
zXf6&W2dHI`E}2Ea610-fNm>smwNwPpA8_qV5_y<dEz;r!tc)*`o-76&RFlS<i=6U0
zHOluj(|wT9O}3V{plvd?Fjt#wEpfWZ7G5TXd6l5V40EhvA@c`pz)52N&d)wIQ;tQP
z3fxnaV7+npqr-aWKll}<h8q~}c+XRCY(xD8N5@Or&3z88x)?p=O4y!JM*JkbD`I`}
z;x*vgouuNlH?Bn!U%inpzFG{tEF=j+8?O&ZLXRDlVAdSnIPJ#njI*wD0?!<mgd)a<
zSCpdF*qS=;97xmHI(M2*gpLfTjV>*hHt=a&+Z}-clEj(=ObL;HNgEZ}P%<Um?ow*P
zJ;dh(pMvFIQt|o5<zHHT1p)If39YmLi8H}jtaa$}q8oU4OIjU2c$`ZL`(L#X1=k-4
z^>9fj=H>KN=G|-{4o#BK@-F_i7~bS>i)EN(l7<7Lo;ELOsc|Qhi;X*YltS3OR#no-
zw_~095);m$@I7Q80!Na_Lp3zTKwzCpG3>!5A;qu<mxMIKjx#-JIE?T%og{K_FdAxq
z2x*cOZ2XQDnza1UXjK5ugM#?2>J18Ff%-2AOzPQV3<_ev`jNIf%V2s?48L{4K{4!I
z@@7yD3)|1sgh?U~C5Hv>zl6<diwy;9kp&dledlm_1H2?KDMRZR6u89eU&`(Mt=A38
z(tX4bWoasQPf==B3a~#0B`E>>m(tNTS(=#c9XdVV`KF`=7WgG8<X~bf!tD>lK1x!@
zG%ZXnk@`u>mZbKL#o<Zd56a)|5)Xs2b-S9PXid=m7*}QrvOf@=CP|zTAOMnvDe+=Q
zTYfm%*(ib)zL{JSrh2`(qr4Pye+<aWz0`eh2-@z0;&S6N2G*6p`(vCc;y^|Ouq3gk
zgKdPzu%~GC#U_3MmT6ucK&>SSO&7AQD9}3qe@hz9j7i}tcYrY|T;&chCWY%B)lk;x
z>Yaj>t^i|Fu*wzSlCU_tIyW9z@&>rH8fsVP#>H9fP}Xi;29d_>Ng5dFT&ub}B)BmN
z?7nlLrrtY+&6Y+mM-_4M&B4Ly+At}xH*bX#(s;{EJD4`T$+uukieot!j7f1U=YlaQ
zjq~;T0cjP1W1}>Nf5Bk-^(Oy<F)5DA!JrzVK$eTam=MTvGZ=`flOzmp;ZUi!`)X>F
zO=<tLgtB}FE&*&x`JbDNQu&{dwo6+5bgWzX1!NwEoVvBuIEC%nZ>A`1;TkX|n&F&K
z)Gpl(W^f#vV4jf?b~4W%yARGK?g8^~B6Sa#khAmz7^`K7*|NQkMF}cE|5%iuMD&jZ
z*|=y~9Tju*DH`T*89SGnUh!{|!p4o0IM}#R$P31QX_!QU87>KPD7nrej+%wH)TE*9
z&K1(tG_I^QJF5iaqAI>97nj1u47e>Amcg3$pF|lAgt1K$8JV2Griqy1O}hC~Dn;q$
z3o>!>73ETDzb1D7rVUBwCTl|PXDX4Lta-!%W#l~Kpk$=*`=gf8le8>ve7-5&ec?7b
zrMfRl%qi6!!D^nQO||8y$dPS~L+$_rJL{5A#4wz%Qv)tLNvl1-O13I_;8>Kcau67c
z^0hn!*ivnk>FS^IbvlYQSn2nRvK3AOPm*fG%S&J^id(q}TvDx=sf)nEFS7635Jm3P
zB>-pSi=<1yqKuuA?wc~UaFY*c#k!RFO&Kevf=dGH)aN%v?3^;gY|2>p6^xB4I8HW&
ztlSF5rj(^y!IQK)tmRlRHt(>L8vllnm21J+6td-7a2uj+O3nqNV)G=09CQv%*MLo_
zIy;}4$L9TY%B0JLLv2cV-w>K|Dj1tGb1HD;*c6&@E4T!FJ*n%v<l~gGz9}E4-fPCD
z`ACigW3MW5QWmEimRzWMNf@~0Zc0bG5{ymhC|`n6armvtmtY{4f08ia6re*&|K?S6
zNLAmEjzgOIrgSWg^Z~8D3mphX<ugbEd2&qdkoLX<b35KA0qnj>!&$T`BIQXic1cJ%
z5)51}l7#!i=3R71>ED#2=}Ry+rKp?<#)cGqI~0sf%kiMzziBrf()^vWR4xT0?eR&V
z^#w-zq=9d5WKtX78=2J0j#J`}8k$4g%GF>v#qE%?@5YZJW#1`o$CUNODR1R)FdRkp
z&f93Z8w{t(c<4UhlE_0B0;fop&%tnrWH}uS=M7d~2P1>;R8uHoVAB7QcO^-6!1$~Z
z`KPEJ3KKn?vU+qBYa7WgVK~J!9TSE_N)Mr~hEq(-H(@x9z(abyQ&JD9^-f9sc25{y
zqFU|=!+D*hf5LFyX62wTd{+_h=mCpU(r|J*g>aY3?i9iuD!Z3}mB+zzDb;(IF7A}D
zow~SFzRKrdIOS_O9Xv_N^(oJT;S{lQJs3_A+X=`R70%;DafTipi1|@8%<jSL!q;Fp
z1*)74MrLYC0%a$XIVFwV9ga?leo%OJY3M=eS^j(3SmaM+yAKLWITehcu<TITqYOh`
z3VT4vB(3u|!Adx?g0DF8D;PmhDaV3=;4(=f1D!Jt0Us2e@+=rZ;YrtmOTmq_%XlC6
zMk>#O5xkLh-4cQ~(yr|vaCv^wq}m5>n_YW3_!!gsM@{f4V}8J2B5CBE@|3;^BUY8j
zHpOXY5j>iNO;DK1A7KQgsT>kUK$><_-;0aVC~bl^;;t<pl)2qd#46RDBI?FU&xI!`
zSOK~|1Z~D$*N5PXPS^b*_@dKWH3R`{x)=lnu<2?L6u@$N7(w}4UJnmw#ksLowyf(z
zQ23he4?*Ee&xa>zH4xMNAt-_6`!E6$SpE-}QftH#Au@t5yXNA6GMXL{Bl!L!kBD(f
zAe*Cr-DkQ7913Hjo&P}4n)LfaK`VcUadfdY>G+3|Rvr)IP|(ulVH}jmAAHP{h6y?p
zwsLwHhwroUdKicdlq53HdFwM?0}da5OlJK;Iwqxlas{bTZ$FfyHlz<9%29YMi~}KQ
zGS(l;NRyU+C?oByr5_4OV+fv08mzfMSggn4^S!2GM6fALtrY%qrKH>xUPVqC)cCWp
z&+(Ri7wExl)}+}V3R079e<&qQ;`UHVTH|qWC?-ux`JwTrNh?2mXp!H-B^9IXjl?(s
zUK?chft-}%!le|WbX*ufJST->>risad0`yN&L)HXDcRYynGbKLjmG)ecsrH<!fd#l
zHtP4Y@p9U@Q7@^!UZG3aR`6#voZ0yP(tw4Yjju1w)gfPBTBc>1tt4#Q>df$|8Zlb4
zQNqeIVm3-x2Bx_*irBW<KQ5zkkC=@DHvJ=Rv6d<wB%Y*Uv`Y+hEY-Hez^Ed}PWg&7
zQ`r!2v~A%hSP)ZV<*QDc>Wa@gZ4y^J8{c&r-|=R{!%n0AKO2Q|n;I;Ia{6IBvr+oC
zq3#xn_&OB7a=Vy~B3OPG&ukRI^1PUhBDf6{Yq58YmExC<7qe|@8*;svjpDa;F+dS4
z-;3G!4%E8(-_$l5kCWMmj%cQuL`TTOVm1g}`B=>6w4ch!Vm3-$dRfdy0o$5bEg{=@
z$jlZLSn{iwjZ#*Q6%#xA$gyI=b?KbL-Vj~yoTIramEgd)Vpi1ZEVKKpedJm(t++UO
z7CoTcA0IhVOq`nM&_+Ki1J;qJ#6)24gJbn6()}a{t`ZaB!f%;<*LOLGs{BO2pd-(S
zXF_D0v(?v?Do1`16N2Z!FJi)f?i?EIr$LIIv(@*&n26<>6?gr}J7OY!`#B5k4h&%N
z>2})8Vx29J$LCCOHo*z6?h}E2jvOPV0h4&>88IuW{VkKTg~=UaZDDSQCS`%y!3W8S
zq*zD364Q2;*mIqMhkg<h>d}#(#5AB1&*|!VW0cy*rDh#DOH4STp3~W|;~RF$u!&ed
z=TsAy4HKII#!RdRI5V~wWQ=<Hgo=6&+eoIGxGd3n<T){sso_#6!;sG5oTi=+Sf|!L
zGbhB6<HW4A5to8eYDPz%6B9YLPSD;zkyPshwfdP!wUU5?17U%l6V&M^(rBFswNppd
z30n7OCeAwYpO{FTbwYVeCo*TfNGKI^+S|B#9r{kpx|tohPt1<w0Z0B56PLUr|A~p4
z;0YS=C$5V}z`NPUtF&n(n0;V4n?08i`NUS&BgePZ@4)!BL=o<@N5H)ar~DI3)h3vu
zIzDrRON_0Wt|M28iKH+mCYh_&E`iLI#5-`5n3)?Zi##v-!fa3RwlUjNeeas?p`Pmz
z=Tu(jEB=u`=LmB*ks9m3QR0?su7?KbSz@<%YB|x>jbl7~u$wUQoRIv4CFle-@|nh>
zQx=a0gyO`+TYwh>Z}nI5RWB<iBz`*un;a)5GGLu(>KCF-eiO3-cO1D*TtfN-ohU>6
zL{6+Dyxm0jj}x%MPZ-~h+$d%S5IKJM0&oerzLZvcB9YW_ZRg59b^Nf|GBX}TvcBK2
z%#%mC!zWCbN5H#@@GD1-78BuF&fC#qB5T&6qs7dmS;wW&BWKo82JwlkSx2rGb5KCa
z)nX!V){(2lth8B2-WHdT3)89HkCHUUUFSS3$tPiX6Sn3f_lr4Zme}dU_@vg43_N?7
ziF_g}+7Uo+BJ0+RlBE)!F0~v+`t!~<K9NrA2y!=J?mzOvm`JB}YOjx%;FJr-9Ek3D
zTuM5E5*?)<pU9<kgtVIjl2bkyv(jljM_w2c(T84?EIGcxP}g3=le&(#ljDPLf^%fC
z{#AQRaJz}@T8Ew$vvOx0c~;EIo%JM%OhHh}wPGT9){$$)MDDCZ&x)BZRLAYj7UZOx
zCgfm_rHs#(B^(4usd(r%aS7SlahlODDfySija*tseiIY1#g1}|PrMaA2Tl>Q0+b#3
zMNA~ZI-551iEu!NDa2<*13Ft^mWk)g1FwjQBv?mo5fg8qM{W@l@1zHhX!m5u$JC?T
z;uG(!N8q@Ll%8ipwMNp<TV_X<P~=kB(Zq-(eJ8}?rm{VeEbDA(&J()sAzE%`aG$fK
zHqQm_)<-M3A@>r$5PN&Q=L&KU>BMK{$~r>IP2|cto9gw1(A!I0<A!(kRNs($d#Z2G
z5{_!X3679+6F7vkne=G_tZ=pz@Pad(E&Uq-5RbBzPXquuTS=d0MF2Wm>h}x`Nh<gZ
zjEO2Zz#K;@%AaCR$~LlYoh@w}X}8Yq>Ic$tclCqxMQ2kbuh@}Cnan4$Zk@!-P2}7<
zo9Ow8oLh&%LyA;uSDJe!-8x%(JCbf4CPSY9;v50xo{5ZFM+whoWz;%bDmOA}T?&pQ
zB-DCQP`Zm<dCcd6%v;i@0YkbJHd<4B)={GaSFv?ayx(tyrU3Geh_;E0)|Y^jrJ@gA
z0v={3l3|?{DCLw1?luwO^(amGEa=w}l5H-CuCw+>tz0;Zs`A=d;Mj1r6F_YOy>^zO
z`OHMOowd~F#-uH^i8)&u9>kNflD|G5WRxImv%>VAwbXYh6=zX(MxytlROEBz@Sr!>
z{2pcyp8ypeVb>;rhi5_Et-wCFNKG4&eJ+Vy98B5JydLl+@rYzrXUV=jUn}e^nzkoa
z;8|tao>-%2(Xc&{?&>U}(C4Pq5~^($<nt`4(Hl3p1sxd?sn3$0oJq0H;!D*;3aqoF
z67QZR97uq|o+W)4aM^=&;&bD<{|MtY0lYnn`fy=$Z<(A!#?7N{A?4<I&l$v=5{yqI
z$vOhK%}kPY%j_CbZbD~%CJxs#k2;6ko1xAj`IM@B<~g1OoR1rB+h>OQ%7u6)Rpz}g
z1gXe-VFXf<Q&64xws#}9)|t|WA@I)hce}-}jNOo%Coya@h3e%@>M(%nXG$don*B_v
z#K^04=2pkM-a-$vm(T54z=?t&_b&=cxen%1ubyM0b^Do6HICAqPk{B0kZlvF|1+fo
zBVX2;+}5v#s>mu3UQ_xmGGx6dDCOQ!e)0*O?KwoD&B~5-%Q!mV4tps$>yaVrOxmYs
zc~+b`WCcM8qLW$7C$cFV0n#p|#zI9I*|E-)W!iI5$tn#k_Dt!`&~%URYZI<1M+wO%
zlVKg<&}O>0oM|7GYN5&W3}2ZusTjZ1{X^wAi<oC=#RwyGrnF)>X`d-GH2k<Pg(9N7
zea?^-8t&j{&<c(8SVx)5Cwzv^fNt$Df1DvJ^t~lznLWcQ%0%VUArysRn{c#0Bi_s{
z@FH0X53Mt#Df<R9u7)58)9d4^+nFBg45`izF*u|;BR$p;0&OBa))`WrdF4GrcIvto
zpCLmvZq8@GP>rkgQL6HZ>-QO($2{)nm%_ep3sSbr0WT>F<>FpDmr;Pupe9{ri8G`l
zBY)OW%JB(P#u4ajB1Xie@E(o)S!d949W4uB6zQ|hklGBd#-kMEvoa1nNx~_D1X^cE
zZ>|JdXGm=h-0=q0=74E*3>h9^PddtEJ`twl2!b||y6Gq@`9u<}Gg!KhB4<d!g}Lku
zskq3Fb(nB`!pL?68k;b}Juec9cQmq0!-{u?EYk>yaz<0XkbD)`x&}DGywv2FSPKoM
zoX0LhbeS%X5|&Tq#X16*O@xy<N;N*=+kA)}o0Zt=bQzhE*y{ARkvSl>dZ3hRr)#Go
zV$P+Y(b9G=ft&#Jb-Jv~aO^%^R_4rYb(Cy;!aw{79X65f?extDuE15T%c>l8Q|mG-
z2X1OgLOziX>i|%8?{~1wpDwd9%=bs=u!+=nr%M@*gXx58K#__?8JiCt2s$<9N^y0R
zM110f;s6#l`G|2kvELIf9jD9KjMtFUWo$l|6Iq(^m~#5yTp>Kd=~BHBL*aC&-UzdB
zx-88VhT(LjNSz4QaJp1)WI;Sal}#khx)huZ2>x>^8+S#-|GA`vpVWY)Y@bmj%n}4)
zm!e&{vz{ceA4tM3i#75=o(^riGG`s7A)m;cbp#xnNS$@MY}QDfb-EOE<jy)>N_ytb
zy5(Jd1`}_G2g%GQl4%{`$R?6$olX_~Kvs6?=oM4wHAa(?e(*G5(#R{{))BC5BHz|A
zspQDF^&F!eJD*sO(w9#>!X6>UCZ1`J$!3kW+)Lrng;03MsDM|jykjz2BbU}uQuB#q
zT8C({CrP=$O-5^^(>f-jHR2E*la`J^M8}wL^->0EvHN`0NQl|2+*yZd&L>i59g}*E
z)LE~2y888MFDYoWKQH9OIs$_&<ixs^I$Rd;0tZ=No+8x;TlhiEDs9jU;f9Wqm#>Cb
zdcne0tJQfa?AkD66Q!E1p;oKp)oI=RGTZp7aGAF;s>llwHIH>xz$MSR`on{Obqy8v
zv7_wbmlUYhFlX~sGW7#NXU2XeCQ!!Z1su#VQ`ZoGN-@4F7U>ZzY&Bf+Dx}M6MO{jb
zplJ^C+NT`j3#qb>U}LM{O4p7U-q?TbkYhXsw4-+M7yvBTs*KyGosVX7J2v@UE~Lsj
z?P#L#(%wRSLqrM(wlY)JX~8q*5^@MF&^0c5Ez~z;W(!RfWM&I>T_Ca}oY(@=>@-Ka
zuw^z^yD-}*EBQhQpwskXv~osH+u|Q0v{8><fZ1KjLb=$b9=!^#_arHI?WzF7r%{bw
zh(UZBRq2H|#i!A3y^vh%G})~evTGgWDqmI=>TFrat##UBw~(K0sb8e>J#DIEh|o6G
zafwhRJYRr79%8^=l#Y$mhH60?3e2@$d-t@VDv*Y4h+kX_+khNf$clB8y?oVqaD>}h
z$cuGaS2qxT0M9)|st?=M7o=b7oSPJWN^rh#lpU4IrqN6tuPm`sJjgdw4|tImxN8C3
zd)}GM7ebyNVYF6eyE?6XRH_9>Yx6?3s~06pSgWDD<*Q^#2#K{2h9}NZFQwRC3j0aj
zH;xe6mvUz|&}i+oP+s$eyjF3biZA4~iWBNM6N1DE^;@<w91qBP6@qdtgwhYC8(+O;
z3D@k^8#<-&c_H3T92lQhYAbQ5PcJAmai~x~3p!6I-S~oD6vAXJ=uUBnzh0?dy$DNP
zBQQ^##lGuq7H6sVS|Xto<qMe$;!rPNy-GY;d&lRRY_;QSNtjkPtT?4_FDR~Yrkboh
z6laS2+GlZw*dJh4dls%1aj0OgO7-w0sk)l^Z+27C@KQK!B@RRR$QLqU#Zj`Rg_}d1
zuAXNNsH@|N)z{JQ!uq3a`&qcggtD41Ty^4T8>gpC9BSMPk$K{nddB;CD3AHVMJovK
zT9qFwPWz}-+%@s*;ICB-fQ9T>A@tUQCsCZnX8osXmCTkbjG(6cEO;nI9CckHE|kZ7
zA<aq%z_ltpR>V=)cmj$z?7KE;#8L0Lk0U~JRdPH+(i@Il5eh=TkRdCS$b2D3Rs^lp
zt5RY`P!C?nh!qH^`xGe`V?YsJFhGPLTMI^t7bQ#g$6H;%<vxP8>V-f$5nJ8f8&oK-
z`7PIc>lhdY-ggcTrkIGOetHdMsh5tSNXJI@tN_3(2Un6Ul%jmWT``2$T9sERVv3i6
z>7R7`UNC39Ncn?Vyhvd#Ygkh1;DEvG64(p8o-PUJ5ga}vhI+16Iqh{1h)hnt;8PmW
ziIiK&g%v^78wsx>y1HF8IO*cZmKDrb{v;_ki~wE>#>xm&I~%-8vmTx$a_(FP(yNDq
zVN<gZhd~qeLVm1>#u1b>3|X-k?79(>)JTyPA>|t>vLa~3{!icj!*dsHd)0jX%KLg%
zZ9lc<F~{rL^B@2HxBvFdzO~nX^}qk+?@w@Vv~Pd^25}TZIGDZI)JvU}#VQ7+p&_AD
zl)d9}ZU_w!N;hEu7CFSn%|3qHduM6ybpdbzHlChF4p&Hx4(!fHjyNW=d1nXOOiiNT
z!GQ=x3JX74#c!s+oiR?C+^`go>La|5LL?joJd%6-P+X*7=&t_hvO|9og2xM!j72zc
z-X5pQGV!+af%MR8u8gMe%{}zpeqhUz7~+M>b!K<T-lc^y*K6_5*8-X2^w;(MwHlk9
zZC|bvApbtr3MZh}O8;CZFmQe@llALGQj7V$NZxtfxl9yc`j^WjlWEp6QABJllXnIr
zE)!+B(lQYYL-E~}rhw~Y{Cb`6+2&)N$br4q2?D3AU#=3x;Cio;{;L&20C=qsKJ<L7
z5MRGoAbP?0SRm_{%i~*FIiI(A?_+658`RSHJVjo&w%6)-tqI%r_;~$eO*7xWZ*jl}
zIlON8@IMZxhJdXf1c^rd7S~|-B8TE|<HQXCMsXmA@S-@gLvT@~MhKxrkr^R~6@?3O
z2rOEMLI^4f@8fVqc7Tuy=Q4o|iv)O<7!1KT0b;%cZ~%YeAfOXS=n$S0apfc7oQb3k
z=k`KO(@@my2kyfmyl2$!(HrEbfSyngB9{?-gu|7zrd)(WuueD#hftkx4-SDk;piIz
zWHN+oC@OZTSK&NMp@D@$VgpzoiP<dFeIQfJ&$l7)08tNT-*8HLxcY`u(!<X;gz1dB
z6AI7?N8cBr3N-@S+n|jGk(^Lh12M9nq~wUG5kTn;;W(idhoGGBo(RD-OJ@&(G@;dB
zf@%b6ln#NTFckgz;I_CK;H>TrA($uJM*<*E_?N`yc?;*>*gVh<T*^Z@&~w|TZ4HjS
zK?EqAdP5Nr;nEwxe?AA7NZ~(E-64hk#EmV4^(<GM5Yn@pb)KZ44~P*!KhMm6f?He-
z1?YsA?<Hh=7iIt!X-vZf_Y$hT;*gd!I047zCB0mLpAY>A4!|J*D8yF?|CtU{u^ChW
z=?ow>pQ7Z)-rUz`SD`xC7#8pIupxwEC?2>e#U_3mwul#@3OOh~ufdWL8@GM<pT(YZ
za)*yvZ0>WU_leEBLVC5uCXfYwZ?Sp#FVEr25^e^_F%*idc<RQesESC35K_935h1n|
z%d-2#=0zXw!m(+ShqrJrq#_*uLeUdX<}QuRD?RcuT>`!@E|;5E0(cFF0w)@rhGQEx
zo|VsVC~Bg?WjJ;{pjm?~+`RA`JcwiSh<Gk3&vHdgv}B~IUx-A;OElQ|VpG|@lpJ0|
zw~%iNi)dwhOhPjdlGAn629$w?G_NnsB@5&U0&r0<8{A+og^l8>xk8Nso*yf~T1m<k
znh=P}1=(y!f)I<s*~-N?meZ<Z@Dh&YKe0|u;o@tT!3#Im7Aqy>7G?BfaKw$ZRSR-%
zZ8CF@hgeG^#659w$67<2<X9BNFI6#1Y|}Aui*4eXxRwTpYvP*k5kfdFs+d;Zxv{2t
zh5%&zL&HNxEG1U8eCv1-^3Nr{7}3z+ejkeh*^qSLMM0@1S?Qq+Z#|)ChGq>jMijQe
zvo;p@p5e{tQV{3vl2#JXGwyA?O+W}P`{_-|-G~x0o`3$Jgy1qU2C=tzg}9U&55=|N
zdF}}XMKrwOC56{uu+}u54))qdLzlg5h$9-<gAJw2o}wXMLQej~Q`sdXzl5w8DH&EU
zM8k_^%%h%Xme?sIA%2bQ$T2C(4NsymgWW<7Do~<Tz>QFpL_<`Ln1Z<&Vs~5;jtBVa
z#&mVHFd*IpU)Ri-F2-pLoxJ%Q{BUEsTHRn*RtLD@24Wp1A=%yUX@i(kpu^YQ1tXw%
zH@NCv3Ok3Sn*xeo(rtOEZwR}&*f&h3b7}HmGM)8IW)>W!?zZKj8w_t~aL|p(M=yhe
zZXmXyrRQzT`DP5#OHm8WAigFI>;?=(C~BbrC=m==Xa%JRg)B6nEkYp+4e11u()gQN
zl=9TLq#6Nj>;?zjm}OEoAV^|%b(IFv31f`)iU1V|Q)md36jQsGchzaE@)A!9Mra-4
zX*NDt8d3wqB$~{S86aj;s{=FH)G8*jChI9u&ZNQ-8iGq*3cD{6HTW`S@U*>@LR(x)
z?%g5dSk{m@?YOiJK6_nC&a0vjTF2sikx<NOma(PR0uRAH4KA}WASt`&zY#RefFS!Y
z>j7gH!gCsMXdytS0jw4Pbe7HM$ud7LZf`^T3t`e?@R7^lW*Y)^TDjRiNn+<Iz{XP7
zxWfVWX$aXLL;DLU=VR!Z%Q~)dLlU=qZC{kBz9HHMAGQo`vr)$Hrzn>h?Xdx=HMGaz
zBpaiQZ3Y+F5QftRWfwu5RtU-%+F}4%h9H~<AZ85hFvR7Lp<Drm!2B^Jis48bqpSCh
zIp@ZM8*SkI;VIH(N0whW(#DXm#b{!fScdc()$e?XLV-99u^3}$+aXwE3~oCF<BuWv
ziBSA6%7bD~tWceXPZxr98a{9Iqn=ae3gm2fiju5%Nl^H}z9=Z=Bnk&=V`qtdP;B*3
zClFg*5)&INx~m%GjbNU}fczntry)RS2<B;sA{qjETE!Z@lq}tmY^i7PdyP)v2%BgK
z@_8va(ZYOQN=`JMBA+5%5!JVPg^cPuOOQ`pk`a*h=#-4(aC8!liHi?`Mh$+k(U(RG
zAtunM;S`QO`2=)HH6+T<!v7}$Eth*h2oY-VAP6EtU$PHw1|dkO!4V+@3%!)w8-1{=
z6k0%l+Jy6e2=QqM&l_EPxg=Z&-D&W!4WT<PCD9`Rbf+QI{w;F=9bcW>7B03SyT3tZ
zM^`Q&gJ2IqKGPVVWp)km2f(L6eF()0w272Q(J6P~bQ?l^+AQHGz^B2(Ho7jTaF&TK
zK#IYmCIr?rgw7As9xqKR1lBZo)P}uxG(2j9U`;D$pfJf<I1Ggyl#)3G05tm3hTxnA
z&!iBX)23&M(*n6kB&R{K4SOre@URVIja;UR`e&sWhftgbZ90V6yc8?WbR=YS{YZ$W
z!PzTptIaBr=L0UW*`Fj8pIZ$cu&Lc%SCC6VDcM}_K58?D=@JaL*-$h<gWGHf{%P=<
z4Z%MxA1%U`W(+=ik>F2*PhSZ9Y4G_A#soCP@(*D@4UU2#?B}ISRARqYBbq4W*<jlC
z@Uaae8r;(BF>I&-NJP`dhnsCEjG*EDGKd>}%{>wa1c9SgSMggW_YkZ?k{Xf}gdzxD
z3RY`Z@3<BUNoubfe+Wrx@Wl-xNe%9}@kWwbI-v&Q3tAZ~!f0}WIV1GGYA|<%!REAf
z{+m}6c;bf8p$0GAP_V#D$uHAngF=x0XbAId<>&kHRtQhrXh(yu7nu+`)XEVz1P--@
z1XLk(sKGZk00uR<=7zwawjxXH1){aZdx#LOLV_9`c0(_02K!ks5TIqskr2xBF*xIf
zV4enN+yKnecFTX`NPs795aDUeni9fz8hmj>7*E>}lEQdeSrem4vxdR(35E7E7%79W
zPJ<mY1nac4bcQgUx13v}DQ&vJV>cAq&)}dRZK@eO8ML8>>dgQk>8B_)yF=|j3JU6J
z@W2g0Jq;eXQ8`-gno1AcXcE!zz>SR8XYjra;XV!Cw;|l8mG|wFBz9afP_WNSs4-Gx
zBlJQjQlBBSQD6t+H8}+Qw7s&#UU5NercUwVASmdi+|y4;P{Zp(G*hp5bim(BST-r^
z@WhSQ=*n+!#SKA44X(H$sHklS%!G>C_HTY9#W$cbF5sxa7uSUxy_CCVUC7Z(xqovZ
zN3Fv0KYnEJ!V8k4)w(GA(azr`<o$$doGify$>5sn0)`q~bN%pAU7ojoB!Y<|P(;7S
z@LcB#>1TM+bHPUqkA6=0sAY(K7ktzlwhI@2)Zl&Vis@%=S;Db|w@4=})bLvA1q*#Z
zO8#+U#)Ibv+5+)yen~0j*L#E=+%JtV0T@SH-%H{N>*E7oLwY!Z<2ytC8N%bcV*VMP
zk6khUtbB1@&{2agt{;W<HF)DXFfImPTvyOPLy|vd&_7FGTvy1yTgK$;*6nrYbYVvg
z4!bV!sKH~`k4^&5!}9T?qX6&n&bWYvS9=$D)bO(Jf{z*=|NSV$*hOIY(QyFefGd8W
z!Nu1VKhWU8>qn}&<DK3WA<)WS*N=_>`0Kjxqy~>&C!W;cu<NH0xM9FidBy`Yf7Mqg
zKtm=>S13S3vP>6})R<D!g(Wp4-gH7qt&lLcjNOd*`Y%eBO6B(mU5N{2;))$;@bLAJ
zE)Nf1SM)#wP{#oyeTr19=(b)6K3C*F1IW(>BQ*d4Jz=C4NSy7$k{ZInIV1mB#)@;r
z{WC<9b4C6$1ljl4dQ6FGft_~D^+u`YS$B0HBRzOz6n64S3cKw!HYxA$_VrlmrX;N^
zc%Z>o_i+JB4JmY8asRB+?7G7K8A9m0;{F*T=zB>2E(cy0w$u=w&;>0uu;B{)cPYi-
zAY{xC_RvFGdS)he1p_p=0XqSv1}|V2!1PjT2L-O{NQ->S?0VNArJw^U>_G(_OTd{$
z;gTHRO>f0mT5lAbrQ5GFBd;M(v@1N|V*p3L0hU%yz8>1%SoyASfCeXDXE;D3>e>|#
z&;pV)a(ln_o4d9*_M^MDH++QsoxIoJB<uo$8S;2LkziJ-zFm2H4Po$Klv_HuUbxcs
zS{+C(ESTXGb78*>?!d0}yard^#}(tx;LYnwtZU`XdkODa#f!E#oOxfA2gO`)3i4<0
zAaEw$wRADKMXV*rkxPNYh(Xx6lJnXbSz@OHbG=cjdDixZSMTFY$ZPQGbtUAr^6PbF
z<2CqhxZ(gBym;N0?mLk5t~h=M7hG4mT&tkK?%LjniSH2FPm$^q(X3X=iwiks@OyFB
z_J(WBrNAe{pafkKJBR#J;$2I>T~`=DgWs+bRAvXS_bynO!Ee`*an}G0b!FVO^4fLf
z+ch}kx(gWshg?@8T|=;Z7dFh&+4h#nY=F5Yi@^yj2EB8g0C&2G9|%3iMZElWT@W)X
z$K5AM>>5H)C^Lg<?pxM4=<lv<y#1xy`&L~44&~p0GwZk>xPWFIzGg0@S%-VCZv_PH
z6-L~*(A@|~?tqhZ+-`1}VBk`De8c+IQ+x?M)^Wvhp~pHRru*iO?+B~z+tn)Nps?t@
zT!CFkvtI7NFABB#4sYN~@dZM$uNUbK2Vn=;?3P!SI8Sv0b)n5VoEtBNJ;M;|d#US*
zVJ>z(G0LTJPmFT?#9!3>E0%XJ_h8>keM6KAH`d`W?7|&)SQZ?(ucr{&xegUAu$PI#
z6)dpBis5^Rzl|?Bz#mMpzJ=?CL$L251|1AidGBznb%hV?4bLl=#NJbQ?ykNav)<7+
zq^ZIOc35_Ncesgm_yfD*2liItb(?yIFx{q(0(;A-PIg4B_ua(Z0XKxAbQsEfH?7$N
zej2Uc9SJ&oLv;6Y`1MV}-Qn=-i#xl+;nx=h_|xI>>x&Y+!{OHzT(DbJ!Q22s@9VH*
zD~0q@*fnma>!6ftPk{w{*&}_0I)w;b%+zry#XT?Zmr~qU=_MSOHZ?qbT{y6AgIrON
zUs7@9Y7!E1IZAB3b980Rvp*c0Gx5Z>CbmzUOl)Uj+qONijT76pZQIU7zdT>u_pWu{
z^GBV%tE;QJyY@P3pHFvHjVxfKH``Xp5X2%)>0+i;^xZ6Bin@jD0cm*j<)(CX?KheO
z-;OQzre1oM6sAyG{L`HRC2a@D&r@TLkZg06+Rg8X%VU1R>C1KL>MCjpQmTY6Ll^7@
z+P^7;C*(R4VPaQRr{o8ca2O#WV~()0P&A8I<!%yjqgPk&1&LJQHRX0=L1Aik17O;Q
z2)WT~s!7yBNDTDZjoi8*su0Cx4|gse0{6pJmv6@R?E_9-!&}j`#u!S)au8#nX?5Gv
zo;GU(qvM`NQ>U7q29-wv4bcM6RU9EH3gt>BP#F>0*A24#`l|cANC15~LX9gR6k6o<
z-)T}3xUU3gR6^9aL~oYysJY`@8G(3~Ns&rin^MDMCGvqCeZ>PNB_`runLN*73ic!i
z*LGOXM+erpH~F*%GE78i&b@wzy$cD*;-Oq)Kf0%nO+mZpsvh@5KbffBu4i?2RI#++
zh26eoQZ<oeW|>s<MEgEfsRiJHUS)3AL_axWx>mS!w|FTqUAZ>91QDD+G+sHF$r2Kn
zG{CKJJQ!^5;Gc_RIJrW%?V>+AB6k`)!~ZJr4U!A_SuKYL3nJRwi|Fi2uJv4l#IBRA
zG?Fbv?Oc+iD|s_FvMu4<x*T8$kx}6ixbC<!!lmWsr9gEB9{=kXj7P4F=dE@Hc<il~
z!UMu|xZH&?2Q+uA8D3QnpPS58zBh99F95!b>T+*1<uiS~20&6)^>JMac79YfTn7d(
zTV`GO8(i=r=)GOfG(A}=p64$QuDnjp-fxdgqoPRd!g`&VhuZ?4RBCz$0&k>Y?E=e)
z7s}m5o`Hu1zcWw?8qA-l?e#+d)!%y-hepBpcyRr_t~EAy(9Q#=(5Q-4{ouLV{j~*}
zbaZ;?|E!ViS7DE*Zh%VP<!U2er-2_Xg4#Irth;{<K-!-LEH3nDM=yubLudl!ACW*b
zho-ea8g(4(V4K}s##4}CoutcXlJ$rB+YGRagpF#sTM86R;kFl1jc13@K2g$y({Z0g
zR2lpDw#$!tdmg|zTlH-5BvSDhn>DK%t{)czr*Zc>><C#Q1JCZrSRwt-LYGg#dLGtk
z`E03C{+{@^Ih}J*tXE>X&xe%4YSD+Vy#==8ip?#Mq1VN4&vny~Jy(EXhiKt_+x))l
zLcj%qBD8@1S-scqAb8}C7e>FY1%3W#Cv?P>)51r3V`46`=_D`BQwPJdWLNExvS$ov
z*0_Q$T&t0{#=~A^2&xdUb>8evJ>6)7VAGr0RByGC)F8R7f~Qy_Vqg$W=&Bo*y*VX{
z)Pf#g`;NLqRM#Qpk&O;A)3(n&y}w!54sLfTG@vbc8AT7uhbI(5*rY?~u8O~gl+p22
zT1EKzS4kDcNBc&Ep_JUro>=jND#!}JW2TC+#%IT#2>mvPn!1|Q-zW@yKY4Vcb5q%I
zr(Qt<(da_G2oFMcbq{wkP5%{$a|(as)qeEc$`$lbbiIl!4z9dx#pmG2W$s)ux!J}Q
z#B;tNs@<)vZpB^yEY*V<06kh*tt>8lP=DcQe51qfIwDk9cX1tXQ}rII8ScUr;J9wo
ze&*D^*SR-pvvwx7KWe>ZXLg%K&9N~H>2OwV&!{C?S+S%&S*hj=!NO;zE6Hq}OJL$M
zD){Qy-{?Y?dja1&K^lolyd_hMm3x~hVah<%63-F*Gbz2FiGIXdr2T#gZ&fDVRj?I1
zKlbY{T#CeaRlExnReF}eByAmDr%{S8xI0nx71@HE<Qt`jWk^!5%&q-SX-~bXY6t6b
zBCi7zhd_t!Qxv;bLic*C0J&ewO%bw3cT(+1;89U!E9w{sw#h4-r}s$j=(ioAgog>u
z3<)&iiVk?_#ho!%ss^XIXs3uPYE}oKKxeEzde}LTh?PP;cYS3CfgbmRW83_553XC+
z=3mc53n4TUmH@6;mz*G}(j<kA$;bsi)m0=P1$HZ5j*M0bv|fq@^n~g@n+Jt!wAHbO
z2ZiMeBfVJKot`|iGvzdNn_3Sm(oEX{+VdaG#V6ryb}km{0mkng#u=cDD7tV_)YZgY
z;*<v(3ZAjiv}~KrpR-FV>5aOnb=jnLaC$Um-@c-Q`*-$sIwZbtLV`RM;kDe1Zq}2G
z&8?*u5P9}=oIoL{+S!D|ud^2@%>`k|K}YBKb@a}7%!!GzxZA9jM00R#x@uO^idX&d
z#k(R&QQ+^U@tETq_%T)}-{Lr&Lq4&n2*tWmcdfJ+PUA||!j9uyMG}?IZlw*>)R<dz
z8ZKm;N8XPohIbAWaitGixD^#(0<~%RQxhY}nzGu;*PXQ)+a_Gka;^<rdMs)y+iU2s
zJ0tE7_)>60S1I8p3dd+Ot9=)7d^-w4Uzw{JT2fT9foBu7S<<-6I-5Sf=w7`JFsJEV
zwc)VX>TBpVIVXX~Ah!I6`rDoh_pxjmKFz?-c~x(~F)ZKYeeKdiT%WeZ%<J+XT#-C1
zb*P;3&HHRvfaIbsY;KmIU`5~S0=d_!p8B8*;>Jgfochv?+)7e2*SXp%rPfqP`-)#p
z1k$6Q?lB<?anf0g__4kS;BS}|@sDDtrh%cJZAWrKtc9;gwJ4DtBzJPsb-<wIKJ9u)
z=v;JtuqG3N2NoZN<0*y2NcgyF=v8eDf?DW#Lrldwh~fDin;B^J4e<_i)32b!aHK=i
zEiwOLui(F;89iP`+tKk^ufvooeu0m1e0bne&R-E&iivenWw9dlAw-v}e6^ti<KMV5
zp9>VSN#>w0N!BohhR;d%RHYF@8i8s9CHF^adiPfALgy_~27Qs)qz;%u%i3@_o9cvT
z*Ey}Ew_QE_TNT{bvMK)Gzx^rkGD4x5p0C?0Ir`ShT>>C!{XiPI4VQF)eF%6x%YiMa
z9Uu?-)i0T&3+J6J#ZVvy$dU5z_Q<GRJD>J&oX@lg+04(c^5n+7$cp47qr)M>WKRG^
zqv}$9`>fO!1hO_+ZA<~5lOKCe#7W8QG;^q?>BAc@%Z`gg6>>r`Wl-<0o+NpW#vKfF
z*QR8A_rGr~gw94fiiGjZw?nz@sqOQg3{P@nypM51xk;79xT0$MHlFfEL5AFB4fsHg
zPeRFvn@*p^ai~;_0R<NhaXMoRVe5AYIFk|d_hs<Um;x=3a8dCsU458?1eIBnAD41q
z@Wk=$l1i}Jt0%itl`?ejK8g&@e6;CHw_Zi(HPI{$Ay>cAqN;n^pUdlA8y{j2@p2r|
zi=R5dob<rm#pft7wD4L9JQZz5t_DYvSu~gQ4+^IQ8@q=Bs}1dZB;>gq9C<yiF}WfO
z-`Ts3hOH|4KHWl-tNWtdhcC)0c9RC@1Htv8Qwho-%YHS1Z4wOuv#z&s>&njg;eb0I
zyu%TTJ4Aek3gx~mv1i(3Tm+qO-R^~n1d1xmwUb?>x@^enQI~ch)=8}&TzPY~L_P0+
z)(h5Fz!6{Kupgy`tqp^{7LvDpm$ozc59JjRwQ(#<1>~&tHRVT<pjcNC=hN?Tn9dnP
z-ufB~SdjRhx3e<(oL?*{Le~2lOa6BMH1GTEEbShJwM#XK(BO4A%UV=!MY!eIh<Kf@
zMS;+RXSjH{S<O!{UQ{m{jsGX>tQda1`G;i?lS~ZcvP_@h-uN()Die6>%b$#^V2(db
zZCUUY>Dp6>-o<#x_(xl~MSf4KtkS-%Baq#C#!*y1H&Ec~MJ?U*+JB^_VqFv!!7Y=s
zJvwKr!Z7##=w@?^wyahfYJYgW^BP$jL*Zk^k6{oFUBG}8LmXyPK!&P~+7CDz0!PwO
z4V&aZk~Q;4Ju<Ydvtrx|;pwc9ej@>;Awk+6+_qkeZQmvnJh?aFlgap~*Cd@>#0kZ<
z$aWNL{QMhlS6naJCPh}(!x=&X@I?kaq5z<IPJi6QZR7b(e1w(=c|ijL8Bi-&7-lLN
z^5X0jeh~NB{R(3QbFTjuaEFnoa^@B`k%Rdt5S(8|l9Pv2dF<9jhBq}B)Pu2tEq}vd
z^9z?%bl+01iJv$+DL|<K=5HhEbjL&cjlff~j@veC#ZeN#$(0Wr{d_~oq31)!OD{kY
z@r1J^vE8#`g1SzHZU-PjN3n_SA{Siu1tRAA??5<>U4K8O1XI5r#GUDW)%JuIY+@?6
z-6P2Zi(nus>E7keiSQ+=a*NOz7{gJwN`aBqREdkCcs($uT47pMO7SE4B-=v|@FV>U
z1tB1e<0SUQoLr89IWi1Rc&6hXPz>;(>m&L=6_m)hPdPpWPS)BQS$5jpx25sxxszh$
zZB}ztxXTiqJW#WnO|Ph{Ne6?xljMSRbPg9S>XTTnQ2o%QK_mzNHG#U*1NClgW;uW5
z4K>bbVfq~#3kgY+F8fm6o;>@q3pAGwSE;FBF)U;sqe%mB&(qE~+j4&`U^A(6?tko=
zuXxu1-8rMKGLJD2&4g`bp*O})ti}`E)<lvI2d?eSW=z;aH8Y_r`1HbKDes2*?#%pZ
zj@r$;hx+S9LK_-`W?cmzwjp~yaZF%Hae2OXiCdU5RKy-I_=tJ9jL^_^{V>_RP3KH+
z%7M*c6OC{|p(`yOBI1HwV?rp&N!$y5tQ3u)xH_!)c3yp6q{33$c<fm>=X%p5`Y<D_
z!;yw+Pw|ozb^Q0dy<*xa+;vjG#lgrDXgA)5CK_kugybIba}7g(yy3HUa<e8h%WPK@
zFohG7GY-?aYSYuOBVJvE_3M7c8C%csbhKB%%fU!a^y^i^b(MfB3KyLF)GD(IRXBSi
z6;&8Iis7gKan6IW3L#fw%)oX<tuf^y=F|C7<R3`|HQ~HT5>VYLY^<swg*%AN)dFlm
zRq5*Ab>Xhm<kzVBVZ2HzfNrF(SL`2SFg5lYTg0^e_M7Y^gR>q!Qj!O`hoRMmC79)W
zHzfJr`qemZ(ougO4A?k(6B&*(9s-~sL)&-#HuC-o^+Q;Qb9;!W1ynry#)QI=Zp{iS
zdFT72Z4e4`6MGhVm;3bpr4#;i^=%bB&dw$-xm)=L>hXt7Nwyz<mBH2Us9x6=>=7E@
z8|2Zo5&ny5(gwobrTR+~ib4;W4(E%Zy?q3^vK!8NeT9p<#_lXu?*F}E0NMg+8UI3<
zm$Fp3Cu}u87lzD6Oxy~)em}Syz7|^U*F@OzUh=BQ`3)_->@dEDRz@suy@jnn<Ff%G
zehHv|5^__rATjjR#?%c|eHV47?H*LdkXKmN7mBWeGlwJaUX~Jx4pEjenyN5#Aors4
zdxRj8MRc(|fsmavUdD5;Z%A@PU)|j|)5_}sZ_~Ezz>V&cGERN=dUo4xYg29CrU%p-
zR${wAY3%6;d~9>5IJNZ}O{FW}5TK^N%XJRd+h`0e;c*ER?@pGtNM@Ix0)0LMOn(o!
z8a$YtsYf@ljs!|5_<RCJ|IYLzVQ8P@?bbI>yP{37@O=J0kvX-_PYe;0nputMZ^;f_
zeym4i?y@?)<&m5^M5tuFaQ@9<B)fHC+cWhf@IoA3Z*;!9_BTz0;d@LFw!dGSqY-#}
zBxF&#_7)>(-jK5PA>^0zw=g?yl)oW8`nqSyRfcIO*$D8acoA^a@-TOv!J=#b@Rn{Q
z*~LOP9oyIfn?wLWp~I}wgY%nWz9u5|TP}GM><9t+mqa)oM~Z2ZA`pBz__5sWGih`I
zgA9Z#Nx1+MC($FY?P)&ZM<o1HK=32%AbmNApoV6kK?esOJc2=82&3b4n)7DbDj{3j
zBqUVLiWw@xJf}8~vFBPe|6ZH(1v*sjiW5B}%tVfBU%=_u&P6$*P@Tmqqw8d0tUsL)
zAPcdV@Scl7{Q~l;co-TrY~!AgxaLPV2e_>jWH+CWNKgs5S|w!wo!{arEW*-LRb@A!
zUK<iJ)Xge)_|XWLfD%2{l8XK{!nl(oqkNbZv`1lOA0aiShdyuUA@HmM#IFzlvCR=z
z4DcQJjgmy?c4Zk*V#z~=_1$J7@ETma5)15yh`HjZ%8x+v0R**+6Wwok_<D0bBBnO_
zu=OTD-wIT~Ac69ebTM>(w?+@Nrf=1Fv4@DoTrZR9Ikm!9KCR4lUNuY|m1Qd8?J>O)
zJZzPAi3+g_-^_%km=Pb8YA+E+G1LVw5jE6989d?2@2#TY7T>q6MyFauU12rQ$#Ykm
zA*6{LLT#<G^3LQ9zLlY?>m{gJX+V)Psp^BOJif(En}#g-7|9LjiI$luDQfyj7_l9i
zG@K|GtU~<$iI$u9`;C+`o$Yh(ET4<H5lKnqt1?m^a{!d(w?8sJy`e4?&M5cN=Qs5+
zXw#jM5`NeB!dN1qy%-}pOF7_UdVhJ6&L|wG8g_p$bzGVFUT{%xgDn~6te@0A!pS9K
zI;IU@sk*Y;kFI2@*&*tW$OV0y-nRyiS(#OGea-PUHhqgHrMvnDk32P9_*-EeGVYEG
zt)Jwm8o!{~;B(s|!z2Qs7#@_Fk0<(qA>WiO{pfaWiUD<Wy*55oHkda}V;XAxy7o7#
z=E}WTbiE7)NLBF*ZI`w9DtJLo*vJts;t0akqNW$SZ?%%9P9hKKh<OF$4WbAatuEUA
z)0Y)~dk{?ftHc7-NIe))D^(qz#C*;dpC`L^MxYYa_#UGX#4{(W#Ny#{ON%E9b+5XC
zBC$uSd8yQoTAGZC+)~Go#izy*L!+61*K!cW9tcfeIdMe?R0eJzKk%Ze{PzKxd|4^)
zn?Z3w$VOM=c~;G(eTBkmFintYdL`XJF({;EVm3CJ!B!*gZ+scamfwRJ(h96f@nvSA
z*0sg`TuJ3R2HfT0kTd{+$P{ie1$y8#s=#uiLJtfhHuYPHVaw|M1m99yaPYbnC!=}a
z(3QYb*nZ2j9EomA=A#JB3u<)%1p>XfKxwoUjGNk#WVu~q56hPVyETa2?GH|3=jJ+}
zKaC?}dF0F<QXp2}gDLD9PmK7(>fl_L^U`$Xh6Bj_Fqn{&bs(LS8P{CNV?|cQQYyyc
z<;!!RrP8`&&V<0s(vyQoXB&@33C*tAvcO1fV$cxu|IxS<xv%}}AOvU<MGbzMu)P}i
zAYp5a5=3@`?((2IBI%&-@l7{<nl}t6a|9;gX*Ja%@J$b!M_(PKd>K|s$Z}8d`q#P!
zFdn4b7gh@2g36#bzDXhq06sES@VHJ)esi~YB7ot&DRfHez3G2S>bZFYGhyR<B$KdZ
z<9}3%P|V(===aV0J9oBt7@cN`TX_3VcV^?w`&oI)z^!&bnOZ13v(Ykb<$F>3Anz}c
zuLQoYGM*jKHXd)}z0@MTHXs!Sq;Ewh?#O6o0qtfJy55>eQ|?FXR<qm%_+CG)Kfqe2
zgGOy|2k@}70=Ns;3UPUVTBkTetgo@&P99u3Qwj7dX9R8?t&l^4ZLL^Yb|EaBg_eNo
zzp$AJ=yl5Afc!z{+d-GLcRcmvsa$D0I|;}<apz)4w(jlh(z$UOJ%_1zwmwDZdA7EU
zQuAbQAg2{m3)&Je7*KweQGB#Mg|k{|lL#o>+)(fft=xv|8cS359KhHv7foC8xN$w{
zECicadrgMpiR!c|m3QDmH{Kz=*d(48h674xLH^Z$ncUCK4uIxKF!7Gg(AKo4Wdn>>
z(fJ0e?Z$(C*Rjx}*6T$zN><x?T<^0_<6LmAY)MtLTI$VEe}#ZXcBeM&jZi!0%A4H6
zI<3C({>#C_h{ua#UYsu#;Ce7Tlk}A>HwS^&t^I{c|3oOdYCP6{crFQBsjA36Tx-d1
zPt!jLPA?lF(pAD7U~Alp6M>_zs_BR7%!ZDoTM3%;;3GkgR?c6PJVaHq;P>$d2k&|C
zSnC9FoSe#D8}MfGrGq9xHC%J4Mt$tuwemZ#VGeV?=0xh{p0hES%32%xNdBu46*K)H
z)kRQ=i#>Xb+KPn+)i1r&ER086;&A;eR5Du=JZt*sFyM~;L90x4IqfVpj)O;*^OiH-
zr~t+hZ>3!UqE+XlUE#h3$zfO0{f5&rS}SeYIHf@A8Mjf2e)EBQHpr-DLmMR%Xs68G
zfrG(CGR>WGNKor?uzP>DTvWJhkB55Twrt<AcBU(2yd2mP{8u;Fu*!rUe~<Yf<A_nf
z;U<1lzxnW{&jDh&c>TIvmC$(<eu_r=Q+$~dpz4Z!HLRClpM5uK?~nuoj>kIfuPYB>
z1q-bwKma(2ESsEbEN~>c_3tJWjXWdd6zAOH3`O|{_0b@Dhqhwg;fqF9MMCl`9%3o3
zf%3rQX!tqlw$>q|q9EfOcZh)sM~i=?J^s=G2`pD@RA@&JMe=3J4M+eYWUG`Y#Tc<y
zpe3Y^&sE5CjtfwffaV6ym1{L|CCU@PMC|LfSks|GDQWepw%s7Y>Bt3FC*Ea}2&>IL
zUD{v!?30Sd1dx)(F>VNw#3wAaV2+88a!w&yM^hc~Ko?FY&~8pL78?*ZZadnUb4S1F
zsS}}MiWDa}l+u9|W?a9aR2A@C<HGjF|3Xa($Rk6?*vYYzfE43Ea&VA!nk!3Jl-V<&
z#D?5~vPBQ7O3zk!U&wu%CV4O68df;T8Iph$;XrCl07Z?SyG}&T+H2<7@jp_T0WWoh
z0cg}H@dWPS@}VQ|h_fVzhu8|=3&?7mSnnk+GghO|phPPfa%v-{yvHf#P9lNjqrn0(
zM}Ens9YwcAB?@PgJgLdn7<0$R929I^G%BO&kgTau<MawbC&2{UYQ9M~PyrfiG8mgX
zF1-~#T%%ueGyE;qi4M??vPgE+!gZJI2pY)LN|5)IW$_!i#cSf}JyHVfC@HLLo?ev=
z*6UuQ@Xf#bN;T5;C`^?%qd8QOB&dz*P9eLgjWSIMG9<&L+d}7MRfoaH-$e&kuUbUf
zlS+Ct4pU6Usar~w{K&{q$VJzA$}Sy-gGSV3uI&|ENDde}LE>sk*%!KrtQVqrD?nc}
zZnQX#yxszBcU<+bO0q4@FcfcET`R)9Sl>$op=@rSWGcWmwbUg>bAjw>feu!;y#$>&
z);b!dOeS$v-f7N}J5YaW?UyT5cUiwbf=Qg*M>VYaS*XUm)Y?}_IFNhBCl{6m>Ilt#
zD2|mZJjt$u-KT)i7H!!^1>_Dn6G6I|8tWiFv2(!-%f-;05`vD50#6gIIooy_-?LI(
zlXP3<Y$j5Sc8=yT<ZRuv&I{14Bp&5~#tax`P0qK-03F+731Bg#qTm6f)zI~nX7@3X
zhhTi|-6sfZ!WCdkwVZJBSjX$Q0|kYWkI@K#Bynn^uv0W~YSEfgp#7t3m-a^AJ;ElD
zL4bLi8}a$pdLi2()hq`_M}DsDi7A-@PmWT{jN7cPd`H)*qvDB=0D0IldhtmB$~uGZ
z5T)>s;9aIwutv?$c+$O&=n}4i4M7k-(dIK-l`)iRRri|2ri}w}#^l>32U4st!p8s%
z_JQg%CRy0&Z!olSUsL<|V_$!_SDHd}4_){RYKCCb3%ga?VIOx4<c(xcEqJ?&Il2({
z0XMOq3TJaH&W`q=<OpjSZLG@hTyfG#2S{<CapW09^~42;uc5taRlHOVIVFQqJ+jnu
zn*1wCA1cY8di*S|$kO)lH&oHuIU2|#SaWvIJ%O^`$IU8HbM}Xaik*jnU<qxYisWoL
z8SNYKnOeBOQk(*<X!Kcr_P2-gX@s_ynbOpA`{q~jjYC|jVTJJ)9jf73$n#<L<SJ7x
zXd1V0#ibgqVxE1^?nyMFswLuVHD_RahAJsEXGn<iEbk<|q{5^fQnSR%pf(>E4qW;U
zVwQcBLvv)Yn%#SKUom_o^qXY-q(gLp{z>g3wC!9>10P7Lea4+6?Y|667q{=@n)NI6
zw?@AUwxYbo5|VjsRFQD}R3U9a+Wkb6xJ*v82eS+eD}t6Z0cX%<9}1>CI6YkcdIat9
zev~KXry~cJ7UOPs&Lc0=`p)1Lo@Q?2_+hJO?WsyknovS>0N)HXeO2Nbhz>xH&<E0o
zJ|`&DT)rMrO(m~fQT}p}Ow`)=Thq1pStY-kuU`YICN@A-4XH<!YEez1R65C$+HCp7
z!{1m-+JWpdm}uD)8Ds|{ZMOFsN`=H$KG<;C2z+OW)@ip@ss&y6(c|UAP&~P12#;-j
zda_Xa_hl`rPu39S<Xc?_H7m2U6LbwHJX8#ceqFNmrFP<ag-(m;bG@&s;{f;S`UeC)
zOTeCz3syCi2^%!30P#XwADnD}pBLUQTu@E0zo|$)G}vmrQ4?`+=gMLy6{=>d1|+Co
zRi_r?plD^d&s$`}2p9yW@>n#c1vE{ju?y{vv`+kHSq5SSDP`s&&4LyB8;}&jSvItY
zbZ3(11D3qt<Q+gK#9g%Ve!@$$s}OdHe~;gVF_Zd=(_$`kYQ^D1%A4hQw^d6j0%yfF
zEj$rGG{O(NOW{?sXzCjYUS2?RsN6fILtIjF@=hsIukU6`ED8%$>_VffB+*q#n{0_w
zq(MwD!*iI*N~j46P?;OS8djTiWQOWZMx&|R+x|Ins7*W+19tGUSsS3A1V`Hz-5U!>
z%RR9_7S~VHc8FE$N>*y#(c4gGal1Y5Dz$8ZOKURZ*}LKp9=X`Vo|wr9+nGz(?Wxh6
za~#k~h?JatE*wP=dDdzobnYIWvna@r=yiP#CV0IPl142I41vP>v*^SgB%-?l2}~-n
zcv4W65ua}$`?Ie{B6+jQWlgTo-l(&L`9O$(e9002b?rj9!fInDbNhwxuJQsl#W$0P
z8=Us(q~liIRnXbsXwTB>M*3!j_0Gf}l8CDx47w%lmbpp@YR6n5<5X0b1L5=B>->LJ
z;}@z~;#B}vxFr{`CzeG5Er>zeiZgxo>L5*)leaCPE0>e?bo|_D+lGm8A&gg8izE7I
zlVZH!%R>Ilii0F)E{&v+fUAvejK>ZCY;zu_STLauXxr;#{&8qS2GbVp>(y%vJJ;Z0
z{5eXFBKlPqrB~kQb2YveCiaykDRv|7l_oWIL+%u4xk|f-!M;|fF8jw_rW}OcN0HAo
z`fTTmy@Y5_Ezw3%D`m3B4079PsR0#BM4N7%(gXI#p5Nhj;Y5)Xy;ifyTn1E_J~dt&
z=9E60w!9x4Q~GWno@dyKYfq%3?n=F&SSygHWoge_F#on{2+=0jQVRrZq_frz6o&M5
zbnt~h{4r^?9sgiY9=XgJ+)~`Fwg%divMzPCsx9WXId=0iM-=3(pYa|BXY3V?rYh^Q
zhh!uEfqs0BW{aePu1<=x@6h6}vZ*QwZUK^?<wJ;-wX6-`n0|`|c-BlBbKTEWHOhpB
z!cVxFMCQ<M?(r`x;GO&{)(sj05{>I;WPVnZ_Ui&VKueJm0q^T}#n#?QL%7FxLM)Hb
z9(+Ak$pby)XVJp=YG}{m_>30SbtgJIh7$xHQH4hk3oB|W55gH$Y9<fH8P!cGD*_Jm
z8tX4cyc&D#35|{Hoj?(Af36V*#6yl%8N|au#ir*4&1Uk{_eqnu=T$lH?r+jIZ#PMX
z_%%LOLwiVT*cl?ZTMW+onfUT^%cgwzlYo6S#ELcHPqoeapRgP#hjh?i0ZeF2K{t?x
zl~j=oEH(nJ^C4NpBZ#$9#j~~098n5pEBWg*is~!i^nb!C&H?h^#o(pg>oTZE))G#>
z(|8lIVTj=HsSdo<HA_yUSdF8XNt7Tni2}UQB$m`Z?s@}b2BvL<)O4rNuSZSyJ?H~o
zQWV>n%oR2g7Xa&451U^TQJNPR)YLuhgf*&J5NDt^d&=dHkTV~@ljAF(Gm^iuiw@mb
ze3gd4_stL5n!<S{Ghe3^U-M7n)MM8u<<z`fqe)=_x;5GJk~HRA2$iBOKm_r>7>qt}
z&>yu8i>Y|kXo@Vr<D|^i0*s%zzD29AKuD>t<U8XnDX2UOgaZdE&ixQ{rQBA)VLOw*
zW?b^BN)799|B6<lq&HU|4?X2KvHY#hYCifxobkegdq_cwb20zct%H;$2Am2-rI%;Z
ze>VC^$*()ug6O-)z4yns3fzWDYdsx|)`@x39`6qZ1Tgik<Zm?q;}4CIfa8+pNRm=#
z#64g|<*zVum9$m1`&f1v&^tZjltH9-4xk+A7=8)4Hm<IA0<&LCm0)T&&5YKS-&EDk
zB&%%m_$awDnBkbiAqd4xysp~4ounmt3X0UpJUA#{1iqdhVGbEVbqQfE8D_Nr;fzLY
z6nJV!vQ{_P;#vHi3ZcZ(7fl>!OO{Oo#}$@RvH%Uw6)kEgSuP{XY7lr^(0K4*T(4qX
zkOo~$mTy^QpmhrxU^-3l>;+TrSiFI4BP>NSgW9Xt!^^G~2u~;LsxG1Bkh0d-&!Jbh
z2Zt9KrEBqn%sWfQ?E)hek&4!}L;AHiODDgbVLWn06Dw*el?9#Bx~>x9RDw&H2}{4(
zAh5opkueD)qjif555ZV<VBT!#KbB5AK8d_smKzW~o67g)cBern(z}d4$jP2$t&zOw
zkz}3`FbXp%T5C}Md@_?-n(%GYkyK0gvH<NUZujMt0}e<&7RG>mb`0^q4Ju2D;CQC)
z<~iUpa&+%&cTnJX(_*-sUCFrPU@h(c(3Q?bg>k2hxf!yjS^?baJP&o>CDV~ETFWej
z_lArkjLcrJmyYDG6?o~u_@W_wQhfTKZwCaxN8`_@n9rBOr0+5o*Q?C9g(QE@V!B>$
zUoGSkUl)e6KR?U=>iT$ei~>Ks>pJVdufDp^>vXw~FLZjoZak=VeI9-sdb2)WTmgOF
zPuGCyQ^1es;w`Uto2`$H2lg!;4~@aIi*|f2jc5=4jiEFCyD|Rvi<D3Ag*7?g=X=am
zRq$(!%FB7z>#VIVxZuO333dBi&$4Dv*WVDI&un1VJ5a%KN1e^1UBeTb?@7y=;p{Gi
z<>Hz>v8aQ7mOuaa5De!E{XM1Yvl8urH>VSNw)U%d;ZVD-;hMMnluYT#6o@w<yiAU&
zHIwm<g3oWu8}DWz`{O!<LDSd^as-$Y#ajmS3GCt<z3Jn^e6Lk{{OADge$5uTk>S(h
z{XiJiWl<pO4kyeYGItv@s(<rYX3g3L_!p>r6|%L;UX}8gKl;&}H$Y>nqb^!4uaNfP
zI<P9?RWgLDb5*`!GS9EnRs+{j>5SR;tcd8JU8Z8uzS%p$`su)+ub4LZ(#O!_Js{N_
zm-8X~lvw-W^%?u;MOd`Z+*=oQ-H3pi+Tr9i+&1k)z6O}RKrB6Xq<wsTmB3)QX2*Za
z{1@nk9Xj(m-It#J*M(Qw$VQ$Q&N~n1(ka{AzROD!(X2hoJV2#y&HVawPgCzDfkB_U
zJd!{?Y4vDJ(7^D?aq{iR5ow1^j&-29t1{TIvpB6*xud)h#kRm)3RT>uyhlCTMsLLJ
zGsTii$7$8F+_~=wdCH&R>1eClzixbvvt^|7LTfpMTA%;nZtv_`$@i>pjheyXsdRcs
z?)?qoE4D-Pb6~B_q~Hm02-)XM*L$Fe&n`btR^}kgeW?ca=XEK0+qD&|YXkqn{^3U>
zjuzzCz(+kb5hXM^KWKe!5zi}5UPx@VRV$vQ%U>O3AvkTgLjnei)0W9LRr+=w6=jMy
zuF4SCxyx}N`F|nK(0PIj&(LSPgLA)xzYm+=(Xa`Cf9%N}?aO~OI@mUNmxU!>TQ%@+
z-9~3O?BO-f_>`T5e_AzguV{4mar3i0j%{^!20X`cUYDQy4(Y`ebbK8$PdhGs7XQnz
zwQMz2ZCvxhzdBj}@(E)Wg>Vs5Mj&Fty>j>z3^gF<X!A5O=oWDG`jkFJYm|wNhp)^Z
zy7^e0ka{h=0Jsm!y4>%2sdN8ZI)%Q}P0+OjxNj^DRvIKI=gX73zrO};%AT9M3CrTb
z{mxhND)`lSx#wYmwB_YSntgl(>-?(zu9ba4;hD&1{`#f%=XU?!+*9Zo3U~MD;EQ6_
z+$qZ^u;M*}BrlPxuJtZ~cz(_L&+7w*ES;FYLua2LTL8^KIAd!g2S<BjeXD=2Yz)ld
zSP2;k|M?~)BxL2}WMla+|L1@BJUst2F^IZ40u&wf9gPY9&G?6>&-isi$RI38$VA9s
zsQ*Rz`2G?8H)RmBv3C4l(!c2#=@<#wzSJuGN9arLKZ9WYA7g|JN^Z8sgbecfCdPzh
zgiQZ3F0XHI{H2TOzkL~GjE&6ng=}02HNRMl{|uaviJ6g+Q2Srv!e55J<Q)iE{-*=L
z-p0xHe+}l}M*hY9r_0xeLGjD9y}q@B?LWp0-Tup#Aat~MGXC$K@RyW`v9p<>u>wHo
zALf7Ns$lG3<797W>_GU>x+%c@e^X=sy8mZ=|5+(%V`~#fQ$mja8J3utrK7PuA%mFZ
z*UE|*8`>EC%hG=YnF!fgINAQu^&gkHW?ZOwxT1+R0#6kecsF=?=Xg_LNmEI`#}mN<
z0|P-o6H!I7A_zghuU88ih$O<p+@h%KND=x5n@nHhkP-UVGS#BspPk-*6IOA7-5f*5
zM3;9YsntPaCr|Ql2cvI$a`^1ndhc9gRn`VpaRL8kDhg8)iI7CV#C8{yelPZUep}@K
zZcs@ig2Qk26?N=J%a;;cA|_Nqnfh@&kInmAj;KGxs`hDy;xNhcQYSs;K^2yXLC)LA
zpk@cpGdTA6s0Mgsbk5jFQ@HF+utt?oJel@tRLF$2#$K)c)?Y929hP$@Cf4~8C!tt2
zgF7>6^k?-uMkDxKwx^N1?g3EE>WPWSlQ~X2tVEBj9j;Va+;VutoA4HSz6Vn>(g@ea
z^jvm4crbWyoRVe)j$B=WERtm^u=$WCPsq;eb0Wc>E4Sc}P9lb+lpW$3$O<u&<R7;k
z>HWF!5>j1-8nh*QQ4NhC+5|Zm{k<2?M0v{nA0YbVK`#bDfy#iqbLe<+r#gMt25yE=
z6j`JPdQ+awND(8J-y78<SbXGNIp7;tQ0xhC9%Sk~6o0ICko=LpGfV?E3;WW_AFES^
z%|lo+*M!gC`T7kAP}!`YM-;*aV;{#YHJR&F8yQ~u>P&*V-PSZ1Y77c!vZP_i>eL3P
zS@#V4!r3j8u@(N%vZ>H0!(O~8f%DHubM{yk^_Az}eML;%;R|U@EH=4guIH`QpNOrb
z4gqr!=yf}1Oud~a(1s=~k}24UQO>N>GDSUg;^%V>&1J#Z+z;=M|EvqD@cI8qwoQ4X
zmthfQ2?bK%rt^GM4(WP4Z7hj({TZ6NKs{Txw!0YX3bz6GYrRZ`ZnWf#oke{~9JVj$
z%Fw0YG6Td5|FT~e?wxGNTDVZ|;s$-|Y<?VmK-A1;<6UAlgC1e#T~Ws$OH`-}HICm$
za;B<Wt#zXLXtaL!E89Ip<_}F*I>;C4;0S2R`fYeBSl4GzM2S8&ApMs%6OdgrwOZRL
z6=?{sj%qijoa+}ZtU$NBNUKfKe^I;MZ>1(1u*{H>dy+Oc>tyAdTTVXnV*gwz#c$q<
zP+T-BfNOoYD6{sB1+9jJ*kA*roX)1rI^y-&u3Won0%bKg$>Jc-c7_iv!Kd&~wC0OS
zrq2RBJR*goHu*YHxt@r{1;U&-n|);N>iep=VLO*jdLA7+2KE_Zj94s8Cbv_{rS(_d
z;t}ah*}GF6lM0%}Oi2aPa5O#8tV?ml0FCghU1?UX7Ooa>6^3|WhXU#35f2OAhpfp>
zu_~ISOtTGPAr{gg!hRth(vZYhLtifOAC?GCh)y9DJj`j)$%DO=Y~e8pL)3e?$Ysdp
zh7UE9V5)u|iOND!1tY75RYU8di=IPTOIj}2>ZSB^DV$@G%&MuckWTquXFN{I992)0
zCp)S-F3rz)&+-<`c@@OrS|Xf_I86=SsU}p+8tc9HgH0CsnTQ#<CGL5}DCAjcU9zfh
z71D;p*lc_$#P`?l2OPMNol58Ya$lRtXqfAKsU9PKQva$Z4Lik{oTpXJf0SB63(3<!
z3Skyd#4<*@<)+^#lR#Q=)6BeV4+&OHch(n0quI(;<IGzQW}EnZZ!vEE^j-3OsIhYG
zh;^`D?Qo9E+@<DnRqZh+9++fWcQR+$$SmcNOgE#Wx3)rVoY^S0CaSC7^_x2hPebj_
zqMJjNl^4Tvy?F5SWI7IdLDs$dSlA&K^D6gV$>BlTkaB$py0q^;_Lsom3|J`$zK9ok
zPUm1L<X=j|G^P}K7PdLWQ5}s!r5{(=m{BSu;7&P`Bh&)~quJ;YLnm2xyVV??S)D{#
zJaThpTr}n_%eQQm=)wj13iW>k$9_Rq%9I2!pd_F%)9%L?Mj0{X6ZL1Kxcos(NoU9p
zv}XBjte{!((nW^!O~{EO6x`VK;Zz$XoY<V0sg#P0x(G+1xO`2y0mbr7qA}j+(P^xq
zHQ6GRTIR^rMDr*F)=%G(uSWd$FwGfUjicISnQ{zuTIAT~5mR~$`|q797^0yclgp-!
zK1%bClwlaN)@VCpA@C-zmbMYr(0$)RoL6pdbA`Q-7$Qy&L*DVrFDH_5RO*37-;Pkn
zS3~|J#k`85GMxOl4Up^>JvgAZXb_8Wx5x}Wy*?!&gKn8J2~f3O+jL!zVb{QCiF}{)
zw0W_;qoi586<Z?=Puj=DjGv9WEcZH0jRGz#B6+@-Hf`lz&GgMyC5Npwb*Yn0d=kBx
zj})9$uNCP-%~qqBUB`1U^Ck*;D$zMrY<H?s^6wV_RtawBxl~{GJmdS02>ZxlJYxC5
z3Wnld*%&)4b^07hz%Fy|KW^ss`fjd<bYqU*C45$OPp{4hhT15xqY)Y+*rKHK=L*a^
z&Fsu~5E9cEsK7otJjETlgLNI@B}Ee9G?%sZD)>1L=KB&heYDn5icQ_`ij_)}oU2NB
z_T$MTeeRTE@L#!{ayv@J@{a{>W^QC&pRDTK(pKEVvb*{)E$?HatU3t?GZC5i<{lv@
zT>koNY8s~E5Rp(R2%SRC2<`MjN{XIAu7*sa)AUQ&3DFkcJ;VH>sS2GEp~Dk0G{ePH
zAjAK**6)0SQkjQrxQab<qn~J#bS|p#R^UPjg~YjWn)}$faJkwn!_>cry}n7sZEzI<
z2(PWR7J0iho(H<!Y8?9I1&YG%KnQS(X5=&E8RFbz9yiF3l=9WHH{ag2Ix(!Z9JKHO
zr}%|6G{3S9bWG(6D~N3zWiRO`<5Ol)Mu%T9;bp3||0vBh(l{gI2y&Mr%MSUAEjv;e
zBOz^D5}y|(AuWxSa{?PS4v;j%zDxc)x=K*HoU2#az(prG_k9oTRv@FVkfR+Bs&K_5
zFZYJooFH417=26UXIIBzOO$pM5M?q^Tzxt>xIjSzEA4dYt#xY!F)A-&b6`dFqWodu
zmFocnHpfL`ZuVaG7xpHCZt-z_V156+fV+aEd8tZS3YQdOOw@EdsYNZ4EMqsMH6sy}
z0TI$0t&Yru_*M2t#C_07#OzW*$Q-b^2>_EO=w)Rx|07fUd&v|H#TK@w(KhVl$ydSx
z`U;#D4^Q=#z8`-Hw%qRc2MIj#_V@eA$_Z9}tiHYt`B1J*{k@Ws8XJR0l(Bbm&$S%$
z+uvt*u!j>vCO~&Aw$!S<SO{eM{1w3VCwkdfKLhh3mNxS`s%n8+{oL-kVRK&YQjn!)
z1H_-NM({IPP|TB)FZEu)K#9{I9!+e+u60eiuE=_;X6vf_JLb$sRcOSU)}7+gR8|L4
zd72MBeJHXiMVi5!Eso(jRh-)0nS5H`F0(4F`k@}vBx!^LTXzo`$gPF)Vd4l<LHJ1{
zQQqeZ#Z%v<EjPl3Ocb~!UDcgrqC^>qhUA`Ew2p$@W*^g6<}PH%$Rzxv-%<|G3TBWD
zE|#%u+<YmX%q3b$dxT;;IHr;w;(M6~vXXL(2~UX*iPA^BSVRcs5hxkR!l>!v1j>ik
zCzHz6;rtXSGzXKC%hWc?NZmGx-))6nT%HA5;B>3Y-=tp1J*Pg&U8pkrTE*gKNR!Ba
z(Y)NZ&9aSZ>=LSYF2%po^DiloPncoPdP=wh3q8`S<Yj5G4+`S%V*#7P#94=|(8X|E
zKZ+V8`uS2(>r3p;hTTacqnhLA7(0zyS;`9kYI6(V)fN|~bR4d!jrS!$74!+#O60-p
z@(*qh_3ab!g=5~Fym6(JR_^RKSy&ifZQ)prQ;NBl#o~uy8QD>0;pm}&7=nOm!#co4
zD4))U>N+zPkF_(lYYgS|h6a9<U5m&0o0}3&d2J6~cI~V-ESvvVb}debBGZvrSRB+X
za-4`J?3)aCLUjGl`vQ`a_sQ2NyZS&r(d=O3`D!nA8GlPhi;>2qaZq(}rTtKcBiSbD
z?Vdv^`K^o&%|Nr6no!y%!p#Yha~WZq*{J8ddIi=R78LYHY<;JWb7bg63Sg4zt8)S1
zH6O;+@C^^Vh@d^JEW<iGq-%?Ez7eGfG$^`Rp9CIk?_gM&INs7lSlHaIx4%EkZ<kaI
zj-)v4y)P+`?z+vXX}BgXVW%hL!@?!>X<z}ixM;uQ=fi|zi1Q_PwcT3u(NO!#{`eeZ
z_OBxc6ltE$!+ab69>a|~>QSEtyQPeipGU=x>jW@wHHWDkY}x1~`TE1f*_QBygZ+bo
z9{f<jr1oXwn3afP%WcVV)goVsa?-joVeQ)|au}w5-{!7q32C-3Juhma`rx!2ZJ53>
z?eFQ%n0I0K$l#3Pj1At{jn18$@o`(bMfSo(=-1Fjzna9Y+$z@m-245K5<B~ctVU`#
z`Pn65!w#d2Ayh1FF5$j4{i6;GEp?jt<l+$3HEbm7xh_S@$Ikh34)H~`)MZ+jX?HM-
z*W+-y!K=s`hpX72yZh%xUDe0O5qI%WM3=~$2IpxD@vfnwxHl!4B)M2=LSX(uHNSf?
zwsW$R+L<n%qqF=w6YMW<amh&dyf45Yg@g|*zp1O7X}^-hsa~fn#9d|R%&6ULkyJeB
z_{o}^m$U=1ldRdx$ua^nzBaG041KK$*e$()nht1pSlnnjypf~CT;fNk+r_~X-4nA6
z?hMg&zZs6h)a9a`DF4bv-ifNquSVJVF=nzmHVlc>;RMm-S0U7?BKj;zj%}nzxs2Z;
znbZfX-Ivt>TdwG0)aX*=c>AjGW{qx><l5j!F<`tZJN>xICfsDjI$P`ahD7e)m>?lY
zVHm-0P&I<5FnuAik>v{)uTr_v;xLh>%{?$lW+8Ew%@E!Yv2=mLZnKHTULIVb-D>py
zmrQC&l7c#g0l2Q!+HS9v^LysURoCZWUYbBi!od+xhga7-UN)n_XoPmW0CC56`E!&5
zHbHEc8x(jfpk+j4R%m!E!j<w7UzH#$i3x@Wp6bWvr<%Z3-?;jj63gi2i?Q?UuetY&
zBkOhVS&kp=sab&L1fvyE@mYl{>;&&GQuNs8u2gq?evs&Q0<l5_Lk^+U&xj5l{>2JS
zo4p}?bk6tEA#|$D&uL62fHsLW?SuG+pG)kg&&QCkgE(DJUBsp}@`{j)emO*&iJqKV
z8PV9V;<7{JBGI_xK&SRT7iYxJlmxEjJ{UZ)+M1NuJ1t^%Q~Z?}i+u%#i2+SEeUcUL
zN04&k>^k?^hzX;IiqMIImFsT=LoWK0LEqz{y<CV(3o%Ee?Xfz2EjdOnjp^-CPxX;o
z{J&}#bwwv8P%{&l-OQR9<+A9ygLuf^xGRL2;Y2UxCuNDABFz=<<GSJhVF|R%KZ*r%
z-Quakxy=eegjkkBobU%(EbKic8IhB`;Vy*6av2gR#CY)HQtjo^@MB6W-6T#>xD`l>
zJyntJ(Kq%x&luMK(vj=kr+vfy-5uhHE%m!?1w~<#9F&sypxL?bJxWXHi0H~W%?3z6
zp)cx){Nj&Jg}k>)VHs^Z^*#$e{0o*d{Oce;v7FZlGo`TP#f+;05Wx`pnYSv3R-g(t
z6^hdcZt*a|t034h2u>lIM)Wz!<L2smjPCsVeoF=)jThi_M<-rZa+x)e6<>M{9AC+3
zQXucE6hK9?zi>pkaQ+?m6&k72#jV_gZz)9CNQt?jPEKQklM<hMrN8+lFgPba4KjiM
zrL;$`)ft<QnqPi{`FK;a9ErLW^L23FaKT!i{Smp9o%y$o#zesL4-F-}KP;Tpvs$U^
zCWSBJ*;S<ezO#X=GO(Bf4D0WmWMR>vh}pdSw}%%`6Ub?RX1ICye!d$kT@gv+vQR)b
z3Om0k&INVz!sinO6kWYYt4O#T_ib2xxM%2<)t?l@%<BAo`f;z7!bNf{F(e1%l_8uF
z1UHD(k&b=FGwGrmWC=u_6uCM{dyP>to4uw-4NXQ>J^G>c(?y*pgRJNmLsA5@`WYph
znPludQozM%sM+mLQZRK%@LGky7Y~Sf&+*~(?^A)_&n6LJlJaALn}N+t=|%6^9)WFG
z!z7s_Mj`+Ny<zx9mOpaggY4x=7(p67DAW5vU64Dkw9V?ETP@p~pzIKDswkayJ-Rg8
z?kJr)Zpfb+-3@ThWnehz+YB<-g}w}byB9#OTYRT#w?_|{-XtNl2E$T@x(nrgJ{OWd
zvw-uVUf1|Ws9&2fcq)NnLU<ngeQJRm#dQ0?JcAVbRD(>iA{-uJ2=wW3ycTnKt8{1Y
zZpVOaVqRzY^23w>eSbQ^zD4@BLb$TS%ffTCjPFvs+Y;kM!*h^tKY?vxTqpZ(!MZAT
z+d$%?+lqAS!y_d@y%2#mK*wBbfI=gq-39=*w~3v%*#*6G80X=jh0fUpml?LB;7U-h
zTYb$zyD+MOSUL_p<sJcV3kJ(=Lw!$B`Z3Ttf_b`T{u^LA7}ZkUvdBuX%Qx{6SHu1(
zTGs|lfp(J3V2$w0jSC}9u*;``bm@lA$p*_>X15be@@Bp8I6Mq`ia|Z>uqBLoB;NHk
zU~CmGH;87{n~-N|dKYOVo|V3=2SJ__sA_egN&J}m2SM`q22+qb>Y(MSPJ88$6{k=%
zaT7^T0xNKtDQ@~fNMkjIZcK@J1(E^P<Nms^YOVddQjoMYdNsbHU>I;P4IlPBU>{PT
z@EF}c2N?OMhK`_j%s}rT#+`a_DaIGKsX*(}^nQQmS%LVOrq}9g2KFJ-{axa^*_Ub&
zgwGg(hg|O#%oXhi85lmQJgr{5ZwRFHIk>0{V-IW)82&d#9Rb14LHIO6-2mu(!{-2X
zM%iw)b+>bn;kzCz^IN8i9Z-fye2f7AJXT@fJDAwV_&y2b+jt-<Sn%GkEofhGnx`5X
zLKOS6{P$oiMzwA)bjA{}OLRv0(@|))9$ymMDO(uWV}|X^Hl8<YhV_N1iK|<Iu1=^c
zOmin;UGTp!!|2m(DJf6Z{yMxen`7|24vw31fw*|?qymkg>Kjg3WI1g}sn}doEQG=#
z*4oOO6M<FKjwAk)nf~n#OpcOI*Rq1*PXZd|vBewUrGm#;^KJlk2q$sWSlXO`AMvqM
zq{tBAL^ZJAVuJz=LfN}xzTLxzTKF%6q69=?fnG%9;z^ce`kKB`azS~5wS(nBxZ3&y
ze1qCGz`M0TE)8s988c?qQMUV6CQYXyP035Za5*N31aADb5D=iTHGGk)F(LB0MhdG0
zWC+1b>F9JGX)oS<c8EULAl}9(KDs~?W70VOFRuL$$ogMgn}w12zeqFZ|Ak|j{(+GH
zg-J8~|KYL!8-CS}AF~c%L=k=Z2v;wP2n_+3APZC~{DI+BQcnQ#7)y+9h+VsV#l07%
zPzwL2?|HL4E@Xe5huvC>$PKy9%q~dZk!_n<H$d?ChM6nrKo3y2*}1zWov8|&x@M(r
zXTHu@Ugp0afRw^&S?y8l5Q7W{65pi96nP2O26UjQd^~+emOWMxSJn;~@Y~hl`dpQP
zkzl#{A$7FZdNJ}?{JhR1gx~cOdt@8~a|;_Gvn{7=wm#S#%RFfEgL@3w-~{?^15)`Q
zxxh?PRGBM6I_NK@*S<H=yFVwotU5`?PXYoGMIt`f?9d2dBkK97!t9??hjBlpcH&<c
zMT&&HW>S6uMS+}(_oDMpc~_}l{0_19V3TBQmZ=;vfJ1b$=fsOfds>IaVR0{}Ya3Ok
z<mQVP;1CC_lHvo)j-fqnX6JqDrp`pw(;GB{v<UhC`s`nx_>a?m{$%~H&zSxJ{{M@i
z{~NjgXKz8o*ul`=%+}Gy{vROzU)v3``c_|i2Qtzc%IcytBF5(WDo%=DkpBO)i|JdL
zS-KHY{=d4+t~YHM3d8sO3g1)%P0(Y9IH7lxc51aro!V`^_CiQ3u>?6mn)d7W9-BY{
zG*KkZ>(BGyMB)ieg4-scacc_vcdw2;?*m<!N>U`IbFG9-77-{zqz;tfxiwpxEvsUi
z3-aTZO~#mFp;B-1{@9)>xWYSJncY)vixMOQ(|GBv&HwxoX&BGOQ)jS;D92n0CJ23^
zzzF3s8ezKq@7Cj!A7B<7DX-p}CigJrqsUm-w5!s%E&$)m!Imljm|?huPe?d1j}@SW
ztqO7bZmVV0*iP^(zuR?NHlQ?-WG}AYk)}htj<opb0XjnK^%+==6DC>V)^YbcNl)u)
zlvfgQEnUBL#JmXW$ZmA#r;^hgB<65FMosX3nDsDyf`Z4xCqSh7XJwh>2!7Y}6L(q0
zOu0gJezj|k6N9kVBgWb@^y;xB+2>^6UA^9Cphx4(SXT=<lkp5Lj?1>)-Q5DnK`orw
zl{RZ;wJRo})K{Q?t*xsEhI!+MJ4H%Ss#22iLM5L`eIlCl7d?@{4$iF%YQHXgioFX5
zG<Tw2e_g&Ak&yEd9WQ~jM6uY2py`A-WqgUM(@3U>+L=Zv!aUGmaFPa^CW=uYLrwdn
z4mFw+J`O`IUJ#Oht|=sbsA0PEy<iEA5Doh!^0Hr|;@*6%GdSJObHO+JFXveCOX9Vz
hk#vrEIAG7!2D$Zh5lEnMt&groEz{`c=JDmr=s$m-bPE6g

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..b629c7e6242145463bb012fdd78a014c93388d88
GIT binary patch
literal 67596
zcmV)iK%&1TP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryOJF?&tGwd^5B&+$RIOw
zD!>q6zynEdW_V!8kN{!VpzVR}fA7tRwN`M~yLE2A+h}xmG4A0`GWZprE9~oh|Igp-
z{eP^T=huJzdHl<9{%GTT?yq0}|9}3EU;qC9IKTe;|9#lk|MULe|K<I^|Ks@I{`dDE
zoL~RvVdvNX`t>hg7C)K)_x*G3Kkn1M#yEfU_y7O-<^9L~{xK3>U;pLnKOMjA*87kC
z{_A(Q_T%wKgzWaak^W!*{p&yc{kU^-_g8B_nxC_cclY_j+qiD~`uor0-~YG2oqt;&
z{ri7A{@vf~$M~QA{y&cY`S0H`;I{*{`D1Lei{|%p^XK_7{jN?V{7JXF{kXPIq5UVF
z=J;`sw)FzxPrCUXTo?OE_~+RF{J5{~{r%NpKc4G1?EmY`_uhWkxz7%SKbf74AND+3
zHxRz>_TGM<TbYDE>2@2pGP;5AC*7v!#>xfA=3m_XeO^DtZ+8FrZ`u9bug|Sa!k^5o
zpC4Np?LX;c{c|gm@O`)TOm5}uM#7(TyWf}Fuv!2T{;4H+&#T#G_xr1N|8f5D3HUny
z`U14sKesXoe=<9tpIe!PKk4>9(H~oxgg@zKZNDS4`F$6A1~*o+pM-z*1dQAJdu!SI
zsLtQ9|KD-~?7Ba;GTMJKyJ??WnS?*-_Wu7LTbYDE>DF#;Wpo4KPr8|LYhejM_=_jN
z%zv~$zJ$L14R65XpF0`t@8@=1pZgf??>o(N-^J1TlXs^7^3L~v#ogE@_7kq1S=;HK
z-u3U(dHrV7|C@xK=X3Wy|BAi4$$=!;cNf+BKrCKWHxb@1{6BjSjQ2Qwyx)tj@qR}A
zcY?@YV#)iwk8PM}eml4KRo34Ot4<<(+s)qh=K9aouPEPleD8yG-nWjTeBaSW3g6XH
zl)tbH=5Hx*zHfu)`*rvWt6;PJvdxO}{S>d~myK4G?>j#8W8vBUwo`kHET2nXl<zyf
z@6pe-FUnt7iT1uD`tzqJ;;+4o?JWa-ZnvU*Kgs#2BL4g;%J&`bkRP{xBz)iPc?+xO
z$7+c3ZO3l@vG#2Lg_Y=b{+M?kkAJrke@R5_-G13@MfrYuZ)NXuvlZq0j&J4ibLETj
zeaE*-^ttjy`M%?Gf3Ca;e`PJ6_qS45`F1V-+SB>gF+Vq3QNEqx(rNwU5-!U39sP+8
z`_oIx_Z{a9=4~BC`M%@b_fFCJ3+v$T8`%E*O#CIG@p*pPXhr#UYRj<mvC%~MzFY6V
zta?$t@A&TUx#~svzT;ch|6KK={1wq@ykEolr)T1?$xd%E^_PuSlt0<ppK|D@jQRTd
z^@sm8Q;zBWZB2aXIXTaEzfW4u{?{r0e`~(mHQs)lce~ev`W6Ap)cEiIU-8Axao_Fz
z)%lhc&h`2Cv3m3Nk2mW3@U$g~qy`qP36?C&U+4xGZFxm;C^C!k-quHuQrQFPO-Ydh
zl=r{hl#iA{s|?E0N#2zAo;`jcwE@CXHLf#${DV-#UDIguiLS4&V<)*jwWO{^Nef<4
zpiu|m{ht=0CK=;eq?+V=^SmineBqN)(;ln6{d=x&ae^L-7cC-185>`E7+dlN2W9c@
zO?k8B*eSj-riX^-F`%Th5rkq@5NO#7PFZlO{~#00Vdv4OlhTS$7JO<OpWf^_f+Rk@
zTUI=Z7WreaC7n=MgA$X8^K_83X7j!v$d#gyEBS#oZt)=1xJ4O5KNQP4ZgIhK#m1%m
zZMg(*ifKf#1Y@p`@`r-sZ<1?7!SOf6G@@YV7~+j3`^HEfffOTh@yCL1i$WfqdE!PF
zkMaa8ig<J;+eQ<QPVlISM<;mHc%V+OC|BVCDF$TPIVV_TV%joDye~Ad>;!|(AN<+(
z(2pRPMjY&M9?V5q`_JoG<{vMLX}s%SZ!!PgdIfjh6m+|CQ!EO)T@MV67k25DxA!9S
zCy(Bnv~CV)3rPsx_~b%BISYH`;135Ue6sbPqtjZr2*HLo1;=?&;=?qaElSMVxh6{h
zd4KO%q{h+4mVn74DLLt`UN<J)+3CidaTkLWEN@)NG#D-d7V=HVDbgmmC^<!or96TV
zO)TVfW0EJA<hrr6Sp9c9rg&~$Y~6URKU<%eQP=8UceJ>KS5Bw%LSBURk$%?_#_}!-
zmoOaytzXqCCevwiTa-B59qWDsDb}dh!lw|kC|vj}k8+=Etp)0%dK}T@pHGZ_uoXY&
z+9>&{Md3!7dFr|!Xy(BC)+Gntw=Owu9r!n8F}~+{Kavths<*9IGF}hwl~2v0aC7Bb
zzbI>S9YG0J>*2iy#(Qp^I?VL-HyxJz+<(U+1s~hPZ99^c?XF(Y;*NC~|8-%%Dc3r7
z?NX2A>!MVzU|+koUctULw_bTiwYhc6(ao(}4o}k0<<Vjf`X*vt2S_mmSC5Y2`PM6k
zr?>d(U|v4P2S~xazIDst^{rbhW^4KwgtL}s{zy_fRO-}2B5JmE%Mt0)zaWUTy!7!y
zvEkaeb;}W*TeoDGBr-^N%^p257hZUK)D4ffJzKXJk=4e)yKHw&4R5a9+)j9M?b><;
zi>x*W-p)6r;fljUX|*}<F51-g#v^ExpTe7GlGLvCpdCS}PQeYU2jP6T^cYOMOQxG)
z;uSL2!#-2Qd6UpeF7&NSGC`vDl51o1JzL=ho7kW8mS>EAp09#QUV9Vri;~&qjjyI8
zbR;Q1Yg@PcEIh1lLNsvo&I^-0dC8~T{N~vCut(a&76H$~#D#r6d`+NYwo@{}OiArn
zB>YVLXLgwR;Zq{s#Ql3}Q%qdA=cR)@alfA06*KRJMX7GFyH4(k74opSd*-e<lC;=+
zYF9v#Uli<$Hzg;@-^dBpt{8YgPsxNcH_@Vy{c!4>U8{zR@$6cIWjtJMgNijBlcYdD
zQ=44`u7F32%<N#M?vB~HiU#iY_=u#%+3^j%9&j8l3VG6_1$}1befItvos_(?OyMhw
zGNMg}<bLKiTXHO%u_Q%{oG^SsQX{-R_FURm7N3Y6c!1EuV=UERrd+fv@?^&eCvt6)
z6Mp8Y`Q^NqqnYzdgG;%d7p09LaFgV@c~e$vJSpedBgJ9FDOv=~ape8FD464Tz@*MO
z4v3$NgddLo3_dPxDmpZ--MGOfX%*wf*qiRGaf4C(gB-c;lacrHqHwGi7T7e_E7dl8
zBx#Nd!-u2^6>YUS-VC^~TT)0WZ9$=3VdSm8NZ{?8vc~bIWb6Ge?Ua#k|DteYBQ<!t
zwN+B1dsB2-3`aLTAtR6DqVThxTkB0ib1nHja2AK-M+eX1fLHw<+<+rbyWR1*1EgU7
zO@(5l{{ALJtKm0vPYfKcTld6h9GF!9)ENynnIz=sq+Sf1shjHMz>&H`1~@>9%>v~-
zDe=R#6%0RITj9hH=T111lxxVXaAE~de*2Vr?G@JO4545U$)d!5uuDpZ<8)klSv+4I
zyCjf$JeKxW0dR7Cy*aDR2iCFo<>+^4rUt!XQSvFWOV<X1nJgv$1EgTprTyY5&%P<y
zdjCr*h-05$+ANNrS|scisIqp+P~;P1lS1kP(It9oeB|V;?0Y^iHeDnh)~H1o*^GbZ
zS}1^}X&-n>!v<M2DLFQolH4&iy*`S3F=@Gobg)b6%bSv8laa|g_$FD!`@5xk#arkU
zi!#t2(Q0hwik@i2_JpXmDA@Oq&5k6+_M8%EJx60x0xfjvMd2<z5u$TT%<_~(7m0fZ
zPsNlt)AO0MvO4yB3TA1!ef@WBq<$kfC^k~R&>Cpv(DkrD54PF$684F)>!s+}Hd8M}
z&l7D!S82zL)BKh{geealD5#V+WL0esD08F4h(?6K9zihtNv>JL497$(R`7jI^S{O#
z4!y4JO52{{CQs6vhr_u`S||*QF!%@20?#viW)Ub{wba>d(8TJ{EEffvwWSEKC}2`c
z5nxdacH%a`N%6J~a8kzy3a1STZq32AM!BQmh+!~zUf%a@zBjFdXVL<pd@c(4)I-Tx
z6zs?LK1yW@Y<NqCM7!3&1!)4%L@lj@IYUE~nIyi3x5IVJ8cxugGSH4S_lJsHgQVq;
z)-csJD+6Lnxyo;i?~E44W)JQ<m;PXRtj)DW4bOsWi$YCZl!12e-Y>~SZ&D6lCP%|A
zbiD$GljxIIg2g8Eluy=9H@pEZBZWccNvoty@QqT0LAG&OEo|l%T_kMYw}zS@9$Z!%
z;GCWc=&g$~(2k|{(pAmzEj<*5JKS{!5K3zbQCpN)l1_7zAqvn#fi-L?m*`;)pOFk|
z4WH5DVTJ=;)=o1_DZ4;WcRd`2yVfO&Kzm&jURY3H-=x(#pI9Dk_VdB&XtST(8In=Y
z8{(s%XvV%M<LHTf(dFDY!=kwe{8dQ4J)fI1caU{$bLgmx!rzFiaS?DooHJT^U!EiF
zs@C<aoVgbk1q*fJ9q-uXXBx0p8@uMj1Kp<{=riv+EBopR0kum-I(xLR8BZ)Y9+{+I
zbQ8@S+0b+iBa@aL+URO?ws>fI`Cg!YTGtj&6?74Ds2v*Uq71ZSi*#Q5M~4c!NIBX?
z$@TMSrNr1NDJ??WCo=9XN@}aUW4Qf+geZIOqU6sct5-XjPy26wCZ?F;Oj2@&JSdBj
zyyroAQ=-*!et3L3jX^yF2G`gOTw0`@A0CeWcutY;#v<etO<%!15H{r;8(y1k`c#h@
zp85{NHiqo?2X=u@d*iW4xzA61$*^RnI0a!$rs+2&TI9)zJHI_*|Cx(QL-iuWoEx=;
zey5Dpn60u1aapA3aex%FZWQtQeJfCUpdFlQH#XFw#L;eefQ~l_o1x`T#71a5r>h-o
zYJ814v`~{pd{I&tXw*s;spaqF4DX>%oZ$f9rly$k(xPaJcoo{z6rty~i7C1|af%)-
z!)QD1!#24S?hf`3eYu1GJn|iWeQQG><}J|%zTDJ_U$$Jdp^rmIZA0INSkauyO3x6#
zMd7z0gE!Z=PxXpVUr;z3tue<Uu~XyU<Vw>%(=YCh&UuIX%^F|NPG8z0VYM&r4tfd}
zB|Bj^U)&+OOrUsL`VtP1vJ?1#7!Yd|Iy?MALBY>JNN5>9vGyulJl2{<<Jefba^Rl{
z%E`ZBFK+sa83Z|RNTN-*P->S!z;D2?(P&!e>DD-c#KAQ7;#f?*I2O~VaG_@a$|B(D
z=x`!fJGD@dG~221<YUrKF4TO~2@bkNVlS-KeAo+H77C*^sH2O(KDlj<MaoX`-(g%c
zU3W9@fuQ8rX6iCV14*BFuuV>x4x6}{ZbcZt7lnfx`W6P4JK`{-!G4j@D_YnMa_n@(
zs00P0!)~yfR+SFBvl-=?MPavrHalTyX+}2W&K*G-LBR2!O`UKAX&AN}t@Zbp#%efz
zc4@FsI!xDZ<ZDD5Kbf9zvlN^9c+>;F>_v*Z!7lE?fv3ah!|dZ$H;k2*SG%+^X=^pz
z*&}5~qmr=*apf8EJr*IZNvIBsPh+wZ=0FQ6l1^8feZcLJrl_D`3KSjaG<#E`fsKKf
zmqo#y18w?E$=3T{gRCEXCQMHNEuA(v6Q&R8O+fIA8MU89S)Gm`1;NybQ!#bIK8KOg
z1}B2^Z*u%DQtrp0<vFprqKiM+SakpOP-Isd3zOEyBS|?!ztt&cnC3<~3_H}+pyXE_
zI^+rzKS0P`;ylNGVUzH2>W=khKtgw}w?ipglw5Iot-Eu@^?pI2TokOR$FIh}oa@K9
zmhO-YlwH}qV=W{t)4pe&9Ozs>$<N9f>tX_zU2me}o;SUUZoI0x*kD*OJ(Ld9v%!|x
zork$|8+RUOxz&2-an@_vd7OK+Zg5v`E23C}lC0=3DF-PB)8YRxc<XwHvTu#7=#cMC
z5`Tv)a*@CbXi0|b$kmSBP18~Dyrg%^!1#D)b>7nSB=^osTJL)A;1-qe-W#~pbaD`5
z9wf{H3Z5~?x~HyTa#D9%7eP6a1Rlm8oY<X=bXk;S-$scR)}TGyp>%F8QnIrsw=xv5
zDh;-t56ZH*ElREvgmsfgy{B>Uqn(VB@Y1GoBM~p!X;3tpEEdJ^ZBj-uN)iu^hoBru
zN=Bu}wl^26*e0W}{Eeq@r-aqVOrlh4Vnk6|4hA~}g4ib|9grpg41&!@v4@k&Lr7cN
zMqtipFp9PvrIAMN%enWUrKSkC)`-#q%q}&K^AayH{Bw$RMd8>e`JY4F17qO(-}rgD
z23Qm@FUQv@p%sC=#8RJKb0VeH#>@S2Hf}uJRq*X^JCDYc4~jNk^7FLXcwqWj2QGL0
zS?3K0<2<)kqcKH?Yf-eRNZQU@@NQAasXWGu0#1>T0^5;S!D{mI%G;ySc(PHZ?ykIY
zT4dSbQaV8Ryv*7&_R9<u-es|^7J*k;Pv2#OxkUG7gUcS5D=2&p98-d$my{z&d=Bzc
ztzH96q19{P`NI@;=s0K(wt`-j_ME!?xd^8i$VE8CK=Axd`R2$cZZ-8z=3r?0(979q
z{4jcv+D-Ab!%Wm}oI$?Gi_r0qgIPD_S3d3S=BZ3?<go~S?DD{yvdIhW9+EP^D4IGb
zcf1J{OLAPU9$?bFNi!H2r5Q(Sp1W|gDB(<z0M(E;Q9@ROd!2$<5DZcmIb!6zizOzp
zFgu+R3OVCbQXyx2N-9kAVWSa4@@S(CLqco29`(XT$SC8KdfSC~-4cu2MNx-Fn06uf
zgW`3&DCkfCe^b67py$Xa_@oTquBi@K-)nxA8nDt=`1iS*8JxOn6Dxa#dH~k%;+;Iv
zYN@|q`7SQ+)D>}YjVEW)*$In9D}@xNc5#I#<^sv6w68`Z1vRvwuoEUk(RFHNPHu~-
zrJ-iZ8I)#<#hKJnsCF(&_JNb9%}1RugISvCK%06gCNOXHiEHPG92s`P0?bR@umF>a
zO17Y++#2jen2HqoMM4iUd=B>FXekig80}COyooDI27PczPFEiemN)dR!S?L*pwVeh
z!EHBT!lbPPSu|x$VHQnUT$n@yt4xl~a9C)&iEJ7gd@wjuHx3SubC`%Cw<ay6r+7&N
zH_S|tT9Z9Eyg>suja7>h!Z%G?uSl(7H}DSr|FVoN3crPo31|NS8yiR+hB+{hb_$v5
z8X^M9oY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt=ti`PiA@!t(y1^><HO8S9%UQ
zaq-~hm%%hBX*g~gOJgq%1^N+evqzG$mtM{R%eLN0Mq0@X+=i*s$gq&e;eo-Kt97ay
z?hz#Mlu?>VJThD#K^kS+ZeFHs@Pd{M7|2^1GGst+j+l_LvNuLaH9aj3K~C2C#*ipk
z^jEshO)mg8u1|FvXt%L>4jN;g<XwoYo>Lx(10?z}`0?_6@Z;tC;J3^BF_KfhIZGPN
z8_@QWlD-e!+D_kxZfS4ySY2c|t`7Nk8sn7Y1X@Wv*Vz0-i;!!5F?cW%eNMWXnB*g0
z6q0<(Tg5CN`m-X%Cv1Llc`Z_MUw3DR?j_&ZO5(`{pnI)#+{SXjwGJb<F2{a>{q*ED
zxT+T=UqxC>+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qefKI^uDV
zL=%Luc|;q{C+RiKq0xJ8{1ScVx|TY9=TcnY|D_N2$OIrbarrF-N6Qb~&_8{}LCDP^
zZ}K8wmXhE*Hiw+jkr5Qb(IwMQxT(4NP!xKJ&hW#gf4nieOaAjlql=vEZ;D*-D-|gB
zzP$9UF@%DS{Kf#Uu8X2UxKKnuOOwm71r0=c(AWbDm>raX2dfqF0aHUo_*Mol93Un4
z8Qsuu5mf|4qXDK*4Hz!;JmN=Ea!Wy|!i8Mn7)%YSkd2k&lfyw+M{B$&6!y{ZJXK^!
zWCopk^a!(lD&QoNelh|>hpjPuLSjeDB+m?NS*;9jV&qGM8OKk_@rtdI{Giw>NehOT
z!`aFp9@DSh5akuO)9l{jdKv`PjQd%w{D5?Jh|CBcIzU3GkbWeWUO`B20s@pG;U|KA
zU?Xl+RLpfOp#D_UQ-caskx`4nkSlE3RQe8tSS3XPSPdF*g=jUX))mIppu;27>i{V~
zBV7r$3B`=P2?!@^Y0Rl;vu3;&Tndaq*;Lfp%JIpdCn+PezbX1HGK1o!@Jo~9j=`2c
zA!jJgt|8uvk$9_(Xg+FSC+tNE>06Xs9&Pv&5~-pBnJt9K!Tcde9}F*Cgn3r{;c9n8
z8*+3IP!+{^tjwT@3S}~EBoA%DkVqY>cuA%XRZL~14#go>&}BOr5h_vmWJIXs-V;WA
z#&<TD7!SkGDjJj%M2wC?NLQv%Muf^*M5E(So^fM1*N|Ojg>xyO6}d$f^V-q`si@e<
zF3S1I4syawrSRHC$-q+A{2;w3LN{`b;zm~xFO!Zc(l?Th{8lXRYA55?eqRYi_h2CL
z0Scp!2ilB1PM$<o(byxF7bQb$u~84D6`7z1j8;j-N3Xn_3@xYVA9*(snhiPsP~r`u
zvEz>zTJHKjL(6l-m|;YFudJ7lXe%6ik>a{%ym%zSR5<xceHmN8c_hcgsBU_^7Ac3W
z$=r-8ry#f}IdZDZi_#G}57Yf3#U>P72XksF;68F{BIf@@E93p4xh_KPC&crwbeRW#
zabw0Q(kUTe5yqA>U^M>~9LXZZ6fe{8afK^EVNqg=N@7@)IH{LXFb#+?NQVdtEJ@6m
zU~&%ADOP)I*%n62p)xXz0a8laFkq}yYKH;Uq|!f3Aydi`F<^XDA_>xWwqz4S7}Yh=
z7|c>RKuF$E0%9sp<+~W*Dk>+&fJK44nFFL;Sskn!(xmclj5bQ8=tR~}d`xk8b}_Su
z>V+}(N(n&*NQFuo;!h%{=txTZ4zi9`J2R`au>f39$x9r3B{&_H@mWfNA`_H2WdIPU
z+$sZPK;>TrclQh}%k=-s;xfi-Mc$Xu1j@9qMToyw=GdYz;S8IBv0F+(i`^6hfvm6y
z0~u^~A^D-Q-i%>f%8Xl-ob9cVLu^&jon@~1vE}ITkRg#TDO;i+6M&c;7-xBXIMW9Y
zkRqqD)&_Pm<sll3rj@H`$OX?_#<)@r<~o9aR7VYqiJH2_C!&azSGg$HsH{svl6NI$
zE=mrcZz6MvD#3G6a`>*hWinxNpp{vbeEk+>Y-y%(U+3TRKuty%KCofGDO)<L(Qd1h
z*F|CGEVd0Txs^L>NZYRTTBC7SDY)xJN<L{HOgO=xyJm=(W-t<$zY>8LrHw69*k}?~
zHnB|@b&ztLlt|L16lO}&KDCHU(l#w(9H7X1KG2SIf8|D-vb6O;C`+3%R=nD$Qm~Jt
z<d<}`rz0g?XIpvNG~8L_Y3n(dP`4{(e33F8+{Ky9)E@YEW@*<}VV3sL69^MFWz?5M
z6=lF%8nr7&ei3qhxB!kI1$M%DiIoXPrG)%NNM1_lm;jPcV*e3P)@MQi4E#yX@YWu)
znBgP#1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsv
zqG{EDZbaAc5@i8zB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OCrs0
z((r1?0|%1D0a8L$(0XD6*g=BCplB=93>!p^m<)jpf!Oa2eZ$}$5JHC`UA#a%EQ1;g
z=i><BJAUS_PDAE`Z0A@ceU2+R!5qy+i07-2N!}zum%Kve4>kzi#4=E_5Ks)s<v>X}
zKpL{CWIIM87X{K53y@_If++%RIhKCX6jZ&mmqeav>XKKOJOY+!>KlSgs62tqCgZ*h
z!uI&qErDlz>y|JtzV%9wH<{g+7M92}L){$A8tUdb#JP2fZBQUQq2FydJqABZVfh5*
zv<>ek^u`$AMWxi>j49xtrElf{YexXfqScN7c+Ue<sttnoJX@!P%6Ya<3C+aEWZ)_l
zIMNZi@$+m5N(R3VL6#O_!(d{nXW=vjC2n+qIZ-WdGV2<`T?-UyQN{)vwc5eY-WgUF
zq!_QG6(~}^^+*t@x*r-qq;lZM?k@l=0}?<XWWflL09poIfCAVuMBD;|>i}sKP*<8d
zo_hoHqVYp`Uj~G_f&@E)<Tr7{@JBiLo4s(o3w_KG-CO8nHcm31#?G+Vtd9xjEGT{p
z2+a@?Tu^BS=NjPD4v=D609>;{puD;Z@Jz^HNo$gj-Hsq7M4W`qaTYw>vPi{@gdk^5
zOgu)bEJ`425r~e4tpckv2Nsd=?7|op-<8+^K)<7a@fIoPIN3UF!_|X{t)TZ7A*Zas
zc5|ZQY59Ez{R>-Oe1nE=gU7MJ17YtwHi*G63dWb7ty`|*vvo^IM6I*~Qj&;=hOZVT
zBJGcbni!O^BP$x9A^^X5fV5aan;g@S3&hbd<pO$Klthf|j9knvk^mg<r>toP*J{B|
z8p6h#OlKDGiN}UtX#lAxjLV>$I}WD7MGLS@QV6GcfRL<_Z0Eq>E8`f9!T|3CB{*{v
zM{H4YqS6RA%A?@~x8|w+nKud%N8^Vk3Sh|mvr)(&VEPHxl*VmFZQzH3iNr@Of<*a@
zv?s=@Vb2!~D=5bX)k?#9p}7X-+!0@kGPrZ{Nj(ZVHb@(`EZedJ`V<~5cMd5R=NBti
zrooL;j7l)tdt($S8>14R_AW*x;n^4!__TE}MYuKGu=5rEFZ~n+5ge4oJAw%BgknoL
z-3pDEq(mz=q&^gyaZ$V`DM;jlO$k0IWl^}wqTIbcsSrZ81_JT)xqEKhA!Xyn8uBeI
zTol1=X!7^H?Icn*jx8SE&&Dwj0BXjyc+QO>AZ*)UE$CzWHUNc&Fz$@UwrvoEwoNoP
z*weOsK+3)E+l+{{&yD-kIUCWcQ#K;Zwl+>&TaVKluM_qB!x?+FGZqK)*^gM9=V$D^
zO45GLqGZl~%;K7OuKjWWr9*4xee+z~<r0jzH)h4IdhU%`q$IQ6Our(~+VnQWCV8Ii
zGG6~}g>TnoOiEqGv88(1M{r}W$nd(2*JAe5w%d5kX2qP>Z5&ItNcCE+udHbHdac$^
z_A++hCF*7HaHPvDQax99jA(4n)g2=m+jDith{pC@JvpMeJ@;pfXl}2&#fYx$bx$5$
z+v~o}#*0E0-C)SQJ?6=fdwa~+&{lpzm-rDE`65jXC>UbrCb4v@)0k3CWIbqj!Hdm6
z0r{w#ZQX(yWujOkDf0wyRl4HTA(b6Lx+pYSe7at|xJSC8vnc>}C3#UmT*XZ!B;>u{
z5y4DBvn%qL!f00<F$LDnDB$BOh1#H$l$*1jpQ3TMQbEsXNsdmA^)g4K9M~1!N)dfg
zsCJ#0<1IBR1^r`@s7IZcBfI1bWy*v?(G}`RrK7hqZ6~Q&bj4^=b?FMfq<Yg8SxF73
zH=%h_O<JT6RjM~##L%|7!W*fPElPAcQfFJKLDeUgNHK_1{d&{dr)JojOO3L$oGeoH
z$~m}tHOxV-3aF_aL4MF<ds-iMJvWl3)F)>!)n{bp)!5bPz8N3j#_OB)p<xlOty?a_
zW_*ZN*%0FPNW;THQt<ovG$Qm5%R}sz56eUB7+4<4UeRTGfJvi&7#`vPY=(zq?q+;&
zZ28UlkS}E?QV6XueX~8}#oIUA!#cYw2N14wn0tEfTc0ccq`Ktj%KYFMo|nlmb(BS7
zw}IhF4TTx2_cBiojIW;NG>9o{@+G5LWLBzM3~_GXiq-9x)U7cyU-R6JcfHqb5SLA)
zeV#P<<yh{m(>Q`qeUe$v)+t8vY<-ehQg_A`8LH%WzU|#>H^d#b2<ngnaqWhst#!Ap
zN7#v&K%1mB4sX>Z7~-`R@L+D%2t1Eon<1I8DBR$949g?|?QbOt^C016^ODnGn_eWI
zzhvS{M`pJNoZ#h<Z<13&KVT(~G-qB8PjF(YM{Eq2zzsWm_iO8sq61Q{U$W>kEBhs@
ze=pMoJOjN<7vVeTfi+2ALVo<&`sByuzlN8h`!9}+4%5)_g0mwi?38bRA9^mrW6}q`
zC-K=K31I?Ns}DJ^;g{hbG<;MNUb=RA88DzPBU%3dDfarHy($&xu9zYEnflP)fG?`!
zW(vO&E>Xn@(W}*m_C_e)3z~o)A>5b<2a@A#5x8O=cn9T+i=A914|wMQn(&eX55Nis
zNI659uiy#n6*UBJVITB2CMR`iglc~Tg}fj5kZuhq`+e{oNzY~<dPboB_o0wzdPw_}
z#Gg*oj>@C-vJ&g!B`+)hG2#TlSG!1LOx~G`0><D%DkBQq!hJSvF=_-;9xphU`|N1t
zcVyF^@!zynaMjFS6NKPhCYA7mv(h#F<N;1H_#<(t%-Sdj4eV3O13dD5G8O_(`#z`U
z2O)LJ*qN^XUS)t79?++r7=#c2rsai5rd|<P2ukR)oS}$Z=u@{ynmqa>8X`j?76pTW
z5oA#qi?Spyg;F8tg6K9cMrI@e&S3OLT+$b}0^>Q3MM97WB%VtPkNO7v(!xiq(`s`h
zsJ(sZ$v`;<f&nEZe?^LYgrfwWkRn)OX<4r7P*6+1Wc)<nOTQQx6TAJA=z!RnKtS4K
zYmS6T!k6;QT)YJWP-$T=amEuPk?{;+K8r#RJ3@i_C8aTfg%StqrD&qg+RqF)>Q}8Y
zqVoDx%Z&a153x=Cs`wc^nu={o6G4Js?NL<ymL`EvtA6W&KsZ*vB|zM#DlEPjz;y&R
zmno(z*nP{wgHW)3Q>jF>7*W7pimy5XD(oaF_QI{3AR^ONn?Yx(YTVi!h-_OF#;G9u
zEl|ubKD<}=Kr5$A8xX?m7J<=j9XG|TCnVza0&|VgZn4>K-3kc!>$hw|unYpsZ4VqI
z;@eBng^NPo;i0){B|?y5zw=iI$3{OnA{~2~1S1xbNOdoUdJ)X-rFhCfyn}9)F_%H&
z`0-{`gcj!3ANf%b6t*bhKMp`y5)mZ2C=8c`J?Np(idfS{NJSLks9lCdgsd*SK<=P;
z0V<H|eiC4C4~abzgb=gFHC;wTOeDY!b3zEbT@Z;y2_E%F&jv!p0-f<8CC9H90HMGO
z<uRv-XyIc4TVABBPG06UgdO{-vxU%PuW%y-N-YphvK$f4fz*jXr;&tko)sk>ke^P<
z1Z6VzK9$VC302f~c2hzEqP7EY^dqv{E6#}F-!7{hV#EW*l#$&_S6}U}zqp2gPb2oe
zM-##Cc~AIxeN`Cy!clGf&&f<4Bu2w83S82RrE*#H7*g*FN@CQ#pOt?wz=O&!M)<x1
zb3`%z0U*oy4e;R64C8?b%-NLZGnv2{x`bo{533-P5dyGQ=?TFCQ~vIWhlkL&mG<DK
z+&0W@!RK-fb8arnA#yAZVeD2ShMUq4LL~Ks<cLHLFWd~Idbl-iOJ;+3fmgu5=><%I
zv=T3r35?rKrSX`b;y{By3QM#v5`u3^aJ81m#rP}=TX^9sAcw{aPXS}{!b(6g&O%aV
z$_tXhT|fusS(_Ih^5oFa^c<g=nx5k`v!<74%ZVQV9J4@zM$Qg4myDV#dCBe41T)!T
zQLvs!iCPq}=)z=_dV{R0g<{R0K@vBiu9ce=e}vz;F(ajZBE8EiQ6B$t)APbyvPD8S
z<eDu!Z*)UGnpeVl!(Pbfto)%28T863hlP{y;xA>$d8Lp8)jUASaTg%f&MRX)pwScE
zJl6_QR*RC!c)6oo$=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2
zklrebGS>PCBzepT?@80`jZDi$X<IgC5IEe281_u|%yp`iN<24hqLpi;oJwSjdgV~}
z2)cGyX_<7o+88<#Q(cx@WUmHjKl5bskT+F$Vh*fV&NT95y>h0JOY4mXp>y3Y#vw4c
zYE>0rqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0p
zJ1Z%AV$FmO(XXhxKu+Z~;GKp<=2iQaC7t(xZ&}hYSMS1ofNhf{9*&pNynRcPP8B*z
zL!eteZ{BqtJEV~g>5d^+i@-GcrL?RzljyNUdi(&A+E+1i>@i0cqbryW+3_rR{!#+H
zSJE_+>|IIIj(ee3HXM@my;D_TLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+8
z3@OKZR}!5=pz<y>ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$00}b0%o|;
zt5Q(|1Y!{eTI|Aa<0a@!OpV-2)*5*+Nb87#B*YEj=1|Hi+-xo@KVdHx<pUcde~3sX
zrf$T>z!uRh0~ijMbAVVKhYJ%Qcpi%YV3m$edTo&_=}h%bpA9OpByNafSMeHxv&Ad-
zJ6$Q>gD>!qtU@o?@dG)@uH0~-pezE%G1Y6JogY!=ERr6*(=<&`mMAHMUx8rIAGETE
z?kqS5ygyo?n`09c4($A{5KLmtc&8<kcr=T`1w!=>ubgxk;DeHTCc$r_kPfyCz;Rrm
zoB+@{f&{Q0Q!k?Rn0n=3;J&C_c38TDf;T4(+g{o2Fk`d!&x_DOt3D7~(LwUcbPkQk
z5&$P+iJ=$qi`;36CB~7vL>izVMWrG<)i49QLQes(6cp_5#9(3(q?aI?7R550jyO(E
z2N9v3qL31P7&?XPwuRZ!E2fpOQj0{SqetEH7z8-gYI4AMDqJuY7mCcd>p~7=Y7~Xa
zWr8V_WujgJ({dNk1@N|lLJYE${1z$3f@-KPhZd2&ypsNb{<SFSG6z7I7YYC%#9Ur5
z;*7b6yq7R!EROXeO4*Sle8$;>Fl2ZfT=zaqnnA&5Qr<dT@xFvvbJuHdUC{#O7z70`
zd^nu;gd|8d;kf$_5SLp|icwlK7l9Lau&eU*I9`IDb43~xp3YUqh7fi^$w|Su=y3cU
zM8fkzKLA#qD_)s^dM-SKn@cOr>;|S2%cZ@9-RI8u%Eb4J8f%#6&9#+22P@y<@;fpJ
z(481^fEsky`*jc1a(fA?&@(XZ0Eu1lCni=(uNxo|y+9iPqv#C7K7_UCPAf`U6}@mB
zki_XO)$-;+)|+@E?0QwKdkGoR3ku@SQ>+*B<|&qj3b;x4lHP$y>CSf*u$5kT5@{cF
z*F%d+AnuB)BOs>BWlPXZCkh2%HQl8YJUt8c<!BRz^H2@Hm%uu`fGYs#`AO**E?_tF
zjy_l&@Fg@+cNv_3IO+v~0aVgY%AE(9A-Kdlbvd1hiTX)N{z+y?TvhkGm=2lV1-J)%
zR(FaO4-`HZ0v}Q_NjVY-)?Fn}02KR4nHX;#WCG5*oa6wdJ$@nG`1bfJY}>t^^ZA6w
zb;k1-hOP@OggCpO6mp6HxlT?Yrkr@b?!*uz=I<wki~(Zq6eIF^Ail6GiGdizpOh;<
zeuI0rrbP<O+3qU4K-1X=g-e+`X~8Ogv@|+g?f_=qexsdQCVaY?7+MrE^u~Tjpy+K*
zz>+T30NCz>K;{uc+j$Uo64{590`$@+g$%{|CWiL0Q>LaxSZ#_%JLO~Z(dM$+#}_fb
zx7~_>v7Mp=hh5+5yyeL_2td9amiFt31Csep>2<`AP)LCEA`w8nZUCaJ*DV1c_MOn6
zIq9|`pu6KY+AmiYQQ<!+gV)^gRZ#ME7ZPsX6-h%(dflLet>-0s2-?1`UB-jeWzBf7
zy3rX9rW^kd(mo#rLh<V*AzuIX+7Q#f9wgxYAN6RlE<inXtQ}C#Aqx!DgUKQUN4}^m
zQc#aD3mMcy&1wgF${Ek)%r|*4qN_v#Ms$_fz)}k+E*q3C=_9W!S~mm`#i|Y^vas?)
zi8S3y$VtxlGWkg=VrhvIomhUN#4DDlC<&}nBq}itr7lX8V>Jv(dyL*f-CIy7G(uTo
z;f<0bvor?<O;+wGQMA*TA#pVdfaKW7gh!olB*!Vq6O0&?dsMM%0Gq8uY}6}pA%n4`
zNr~z#dm?F`AzSWp=rL%kGy()|1tmN6QY`SLUW&zNSxv^JCvXxjJprpZVz~J){I%+Y
z3;<x2mc;rqQlwa*rgSZYW0g9_IyXT%KwuvZ{$d}j$e?`NwIY;nJE8hmnWt1tR_`f2
zloftTS7jL>Dzk?Q1(m{^0a((B6@XQGGXt<nw?+k{<BKZ!OJ$BqZO=kTrPs4oQtAGz
zr{rN5Weuj>d8!LAyLxeeu3j9Vs~60EtN|qp21`Vhm4kJp(g?ybQ)MJUDXKKkU_+x`
z6|60wup72-22{~x!@^iF>Kq`k55{)03x{^A6PZb~_CtsZl<_J%6f1p|v5Muu%Akd?
ztFn0^>}ofRvGQ11&rqGL3~Vf5mIgQ$ID>&MtC!_H&kX2JJB93gtffXvAd0P(sSqJp
zn>ms7+REg}qHbxDWYM>>Sh6r&8Z~oZ*awQGW`#MLMp=WdjHj$qC;RG=mF&s@%VKwB
zrDZ|9vgBsTyfXEosNQZ5M(MrHXq-V=WmabSzA`<t#2?Jl2S{mF){8_t2CdvICRm1W
z796Ch{6I-USIRxh7M8u8r47p_kLrhIwnu@)gT{T3I?Vn2Hk}-}@^5-LT;HaL!>K5u
zsN?31SVbSpTfw4`<<Vf-$ntuiwB#Yr2+L2F--IP9%eTTZmgRpzq07xjgKC)N$6>+D
za`iC8s@y?YcC-9N2di?HSBa%N)9b|2p5>KdNLBf*5L0!?x5Xl&<^4jP(Q=Tn6lpop
zSgjPEwgaSGG+l;|eU-Ov1x6(+_qwTc*X4nJjO^D%_vFQ~6;j2su@zIrvmuux3%wrY
zwq!Nfa&59=th}G7DJ%D=s?NfNdVti&=4NI2+VaG%>b7*%zEu5I-dq&OJvNUotLT<j
zn3Z;2SwLBfw|vX2)(ii0jtzT3PU?=NOuDgq76vXiH|qwMD_q5e(^t;w!{tk7ePS1s
zIZ7CpKOR+%kMh~G6mq%s9hg?-`p@#o6&%0<%LpJizN!jyMH!$>^A?G~QqCEwz{1ZJ
z$$;X}#}@9un6s=j|CLpy#}*;MD%2H5!RWFGv^c(0%{mBqTAlG#iq2T&uPb;1)v*!a
z@udRV#});`D%%w)!ZO?yO~Pv46@;R4-xaCCn&1`9;tGG_JI^}f6&8bH<i{2}!>}!d
z*LYU5ssJ3uV^x$63ZpZUC)kCWM~e1gfpr()5{s}`h!BgkGmPj^A@>S1Vy$<ECb1g4
zs~ieLsw%<>W#x}842qTKD^iNp=@m%D0`?Vb#a}!sBFj;8rJ}YR1yw4t%TX+)!oM7)
zP>zZZ3%*qRn4^RV1I!k)Gg_%@n%EXqBhXRFw1U~(xGl7?6$!;x$N`w`RX%T#a%tj6
z+F2oYp2a*WC=ZcPTjZWMAlp=UU+m^{4*}$kuP{MJF^!5P#92DFfI|m*RR$!kmLs4M
zqic$J<nX%U9gi2UfQpIq#;{G=61_2QQ+4heEbR=yJaj`<lxAFP=N`%F0JlQ8XHXco
z3C}=Yp&7RcS(Eo}MwNPF$mZk>r=nIlLqHW&;OZhFaFw&Xw#Zk{5)X)u1z|9L_5dMy
zp!=MGTMERDSMxMR>w<EFf}CqU&=vL@ulU$QgZa`Uet1!kYl;}-1EdUsWqfCdFTp5k
zoKDjs<C!TCGvqmC?~JCN>NF7x&R3PHLWNg{f)T;gFqx#1k|Z7Kz6WwI-DyR*E7sdP
zW4##=zO=neOH#ymsFg81YSq+F6?RUAmVxPX(P!lP0m?l0=ys~$6#-AR9bxjIWH|e&
z#q-ErR<u3L3Kfv=-Wjo<Ed}gj&W?!iiu|WBrE&vklu`NsEjXE8K%-A)9~_`WqKPsT
zXo9LN2KONmJX*|^;J^n5HZ}U8bP0|gyGJ<}v=mli2JDYVC2!D-nYkT~+|J7VSoT#U
zhhz&pb3J*m6;_f74a=2=LK}9as?d5)Rq9C6*m7Xt=cqIp`e7=U#+?~DrY}95pze3C
z6di6-rsx2?(ih$VvVI(?p~wq5K#E^b@{j}NsuGMm?TyMxa>PzCZOI3sOhSpy`2ZuX
zGM$_`{TH==M-IO-rkvqbl~&~d!BgIqGyDFcp6<-ISFV;1W}l6kW~QI%njK6(%O7=&
zO<QAlj!lxoKoU_UpDj}6jcIo<zg;P8KA3H$SAPsLt7+Z?-E`Hglyj!nIn&9Ng6GU0
zzXU_+K;)`izD0>G#dJR(0D74cOb3#0kRW&@DbCES)kjjAG7X(6;Zqv|JD%BzN02i0
zQ?D{itCi>INOh&5E-9JjNOO;mJ$2Ftb24>(Ftb}Jn2QoAn1h4EX0OyvpUl9d-F;Eo
z*iu9nAxE2bk=4#zN?AdiS=v(%DzmheuIe!0RyymVBx5>SW6y?lW@Rg7)={&*(rSGo
zi%q$>K7puR8M_`f;L7QBe1ciO4x4bL1^atMTi&oM-&z8k@~x46>`1qk#xjxTrX1$O
zVMMM(XIF}~WU+~NMd{NXT&GDt+j(f1h3!hP);*vEYrPs+-b(gfln_6e5bnycuARUf
z>)HxPvUc$SuhH1{!bHA$?FHn_joJ$kZ<q(~uxZonawI7^*tTBDKuIR^`r_8WiB`V8
zPgHWOtbRwpUdPxWQ3(^k0q$0~0ge;e368T!cVQ1WbFc+ZuqX-lAbA5<L8nK55yBWy
zKnR}qM`0y6OznlI;Pct=790_R0A)Bp$}i9Af-gfYWs<hMjgDFq0*E+*lrR(67uUG~
zOgJ;P1w!F@sRF11gwWp$&BAdN7vhC8v0Gj%zlij}Jpm8EQRo^D9Q#7xa6~W)q+=11
z3$}GiE~vzX!*d`skVQy7NIJc6*T|>hK+Wq;6dJz(0wG)yM{HzampJpt1#hw_F&;vo
z<PRl2%e{4r0SQWFQG!20TXCeH3z2305Yj1$*%Fi-kzNjFq|4$Tl;<vZnEas}(b&2r
zV$9gO1y0M@zLkhEG`t^vxe#sEA3%r}>WyE-+mX!yg*^&9XHin%=-L_(wgthnC^@>e
z^@`E8>XU;r*@NQ0OQ^g6MA5Y=2(}~pz(uf~bL*6wo#y0485?+!L((dMqeZz!K_EGN
zJsV8YA|()%6p{<qs<4(EQeNRPIWqHM<2{lR%#=yjAuSg8lcRhI!J$?=2Q2ffGo@b;
z*Nc*1P(z)9yTYmR>)LRv`~u{7fn7PAQ-z4NC<(pQw{AK9zV*t@AoQ(8$_c>Du?Pvi
zMF_7&36{65PmZ5nUnjtTYOMNoZ)jqU_})Ssb2!Qhm26Q0xg@I3u2y2BNufYQa6zAW
zC=LmX=EN!>aM}^1L`JJ?AYTfrTY!jn(k3p#+tGTHkO#+x_U0EM?qsn+D6#<Kg77>W
zrre^mLD;zilvp3D2cjVExK#pQ2>5o<8b$~_P*S3?T6O~5)v^QMt`?p6c3O1e+o`(U
zBE=~ZvY+38DH8IZ!v|UDfI;zlhY<9vj8ia!i;zouZoQHdCtGVUf-+o`wKJ6E9E3F#
zK_V_n9K5pe5g_8E72?hjY+#FyK<@%%bfQQIv@s|#93A@G2>h56#KT(VIQUr$LeddG
zUNDo3ve<G84%UfHA-qb5hF+MK4u5UoUV7qJ2pRJTLJUWe9(4c0*mRT?DjZG+?1i8@
z7a=i@1n3FU2Kwm;f-hiDhvi{W2HJ@&`V_y~1~tkS`2^H>!IdsbVvo}Akl-6f!Jd+|
zL8CfMA_br7SvRQwRz*<p-bG39S-sLXQ11!mS_C=4;0p&RY%XL2uB>D@QKaMF4Op||
zqh%Uw+!BRf3(|&h>p&SP9NeN<@hUX(!qX+GFn1lk`@-ejDP6-|Xtb;g_dyY70*qD|
z!8>K>OR-(<n{Zr3y0*E;4iakdPN|8;u3~|yqbQP&?!F->XN#uM|MK;pj&;t@_piRE
zc(w5+zi+qmy8V5*e*NeF`1LPe_I1AhC;#t%{dqWy$187Ujrix6KOGq5Wr9Jqh*Q2b
zga_LldU}H?)=DSE@v@40L|m9v*n{P}Z<T)ju+*w4(**&Irm`3-n|b{=lY+Izb&W*7
zij}s^)d<iSmQ+AB3%Lhv5KO*6_yE0MI83ml;0`1nU23kv^`Vxm@=gm3Bvbz@kM}}W
zv^<Xuz*}Jp!tCK<8HyiZ<f_Eweoe)JKyz7+aQd`i+0D%8vm~3ecGNk<wXGVh{=lVz
zj1Fz4_vr5C?@i?WS;z_JkL$E&+8^&F9Ep}f=X)ywk*94+>iChRfy#EhxL`Mf@4VrS
zU0{=ln0fNrTUB~15^>Gh8smmo$hRr85!gA0sbWnO8#s*>z8fpG3K<QTU4X*n1_122
zJxy?STYZ{>O<q?nt7O6)AE`X~2LeSUsMCa_7vY^>iN{3OK%t<>Cwk^C8VaIe4j@+h
zBY#6%vqG$u6>uTHmNqD7vIbm~>!ODW)t|C*LLZQ|RGR0#U9S14gDpqwpg-6n<Ci`1
z*iLx;t{b;j=hh<O`L>&VY{1p;`ejT0rXzQ*t0O4m{I+9Q7P-NHhSg@@@W1I4r{cWT
zDNl)i+X)%?JUTzM%ypQ4(-CLxy48`V(7)|ytnHd7^QSz{byoklBUC1XE$`=7QSR?L
zc9v(w$^V(I&5yg_k2~th80rX$s%QUkM?l=-X8D;h#rswBn{K?28oG&af7i{Pk8A5^
zYRexN*&lc0eP@?C@&@eRbqq;j<nJeAC=S&<`J0X?Sc{mDpSod9b+`VwBQl%Tt@|@_
z_3IA);|{u}M|41||9(!Wg~prwXX4L%-0gqdQBQ!WBPrK+9SxTjUy7eq(pYcDZ#wdc
z>FP+z^KHlL++U*A5r!O-5B@hD@r2!vI`UB)-*!Y%Yd&;8Q$YH7`hL?9FQh%{$TxF*
z+c9&t^CA5i@a@~X`kO9zdwX_a^ZBkz`*@#!3jDub?B8@8A0qtEdg`C=8A6<WUJk<1
zra<r;K0<8BOv9g>9P!;%WB_NNZ1FQeWH-uhJ9@cS(2<n;+m5t1-MozAA^DJI{<x!r
z9#=<Do^P+eg?P8iMnALg<%hKNn~o5w&PN?7W{qz<GL<i7ub&C%vkPOt=?0N4pMjs7
z4Cmi<o0DSv&!vx4hSqQX{9(|`PY8wIzB;gUP*D7tcApQ?@i!eSLzo>YbNaU(`}`0@
ze};GFQ#Ace$3jCuM^c7;+wnSgLH8$vBueuAO}EbE0(KJ!$v52`7AH#4KQowaqx`lb
z#BT&Q{@eue@omTUd<f}3W6Ymo`yY3dbU)P*;jCx-wj)a}q!REm^wbZn;5Xf%J7m<t
z&rO-=-*rQ+D{2@&(<kzwbNq2fsU|}mLGf>Qj11Q&-@B!&eCRa4(-mkvd(@H2(Ei??
zKb~``({Cl(=CaAW|1sQFDfxe;HeEUpZCs&TT#AoC+hi=d(=)PgUT85wxxQJpO_b}K
zv~99o#!Qs&o43LoMUwpz1^s53FN;#cZCQ0~(oP1-*oGH2m|4ckqBMRfgo#<kO4RMH
zDsc{Qj;bVAl)g<otg^Ff;%v*Pn`Q6FhxD*43XPRTp$!iO2d9jcNT(u<l1PMFBIPu}
zF(qXgB4^nuNjT67Tc!#C2F0@gU>hHVGF`G{;ax^u)-03{Q55+Q5x<B!hM=U0a1zGA
zZ`LuK8*fM{-h^~EHb%tSvhw1QB)_-vj1E}jD&hF1Y$YE3MxC#rC?euUSE0xtjkXn&
zT$II6y?72-m?~1~h{HUpl4X!!1t52#oSF(`I>4W+h~}aMx3aF&LDCvdg@k0PR#QX>
z0AWC$zfh%{01<-XS>{vBLYX_|_%BNAVWr|b5UX3{%R6$!nwJLwaPG~^hmiG@y-sD`
zrGV8VB?hBY3A;|g9|b80WG76`6$F9{wt1aNlwfwA$&n`9MKBFG`Ovmb$%e*GSuz%X
zkMhiJG~zn!98IaZ4uO?;iLXDhUEYo<Udm)ZfNUeQfCH7h2?4-ix^K$W_Zu~vA=4d6
z0XM5xuH&d)35E#Hb*y6@3YNW(RPxn~HLPO-3%K{KN6x3Cl~ZX7cf8>V@bbBJOs0Hp
zDDUj$bA#T9NSY%kIhlHe;Mb^78hT8ad`wS_!0X_?IRulrd4`k`43|^iy)`j~zI$t8
z3SH1Xa;x=g^JB%1Lhfz2^ZK>f&x84W?*73nl04-gj1$x6)+xuj`%_1>*&|0fb{A|8
z)weD=QiV*wDI1`w{7{0f%BP%nVVAKV?%_q@UPnP^W`)x4+<MzOjc9A@qk40<>XW0j
ztxxQPZrg`qC-jqB9}f9NDZhT~gnn+0{n)xntjqv{rmRYY7#so0E8l;NMzFJf(Ry)j
zy<#-Xi9}RH5EL+wQc%DME0!Xd)n@eyW;LDp3qlsKbB-j%RY%?35f0wk*m}iMR&wG6
z@uE2$f)_-Grr7I@V+n+1b;{u|M=KJ%+ef@iI(t6iW!CGnhs)$pwEh=f*)3iMPim`s
z6+uCZRNZng3cW?NQELjmg&}KE_&y@Dy;b5Mf}LnodZj+_q?t)EQ>O_-J2uyl*N>4W
zX<5J3CHAmY1Xa9eVNq0v*zwIS_DM+ahe2k+1gqGoyrbI|MuT_5rfwXB&bKX)2G4|z
zty`MW_{3hGAn54O@ora2-_`MH-@@<m)AAVq>VTVgf{nFK9EcRH^4sPB?{y*}dlS1p
zDT^~_F2>=g`m_iPEX7+{8EmK?wI~c*jv1d?j_F6@@*|R#j%Wq8AgH=2Ee%K=s~|wd
zT}Ld+A~9?@RL@q4Xn-PR<$+g5fX57#c$xU6ZOcAG?XEWot(>18>8$_NRF>7DCa}Q5
zE8^F~A-t+EAQU()V6C#uCSHzHA`oKR+bIzUf%8Y!hIlEqzEvI?;_p|5iHgY2PwDMO
zwY5b7#y(^Hms6Xp!9{;6B@*Z@?Uc5HGUSWGh$(=+*h3f)hw`#0Oe9G&$fAHjsm|CV
zz%*wdL50`Q*YfP?6e|GW`N*b-PQtZv)Z8=H8Cit*R3%iv-&Nr@Nbazw5-Lz5<4r;{
ztohH-BrjRpImr|x?9n|xuJ8l!8iiUFt^u@XbdcZ-Eo;?EVFpp|<warSFBGpu!UW;l
zdOBL+^m}AJKuyR+;ZU*Jt)g*|3}A}J86z583;1^)sZ1z+xk|<;AIHJ^%E$5Kz0z^=
zq+8|iLE$sz@g2xpqGRKwWGB08XXGiiyK=ASHQjTs-WMM$>m(t6CNw4}h;}RQ5|&51
z_1;JESG%W#BUFsFThXzJvYi!%Fj}~pl#z$51B1eHBq`%q_~{eBTd7wkepgotybX3!
z20T2l!|kS@&QXTgZt2HRMD1287HqtBD-6g{>BMer24pALt<^@x->O^1pT4kgx-NY1
zhZOY@sRedR^-jIgZU$aM4|)@#<@yK!+=$a<w-Pmg%VoD@2q>O*$@cZumF$u_5r|qx
zR{J_hi4$=>XvI-ht{;G~?9zsVbIGoI&rVHuyLKEPtgN#AGFQPW+YfoKhGf4;lY}Gm
zQUn=vt}M5f?U*q`DVT$6m!7p$!4B1RdkHkkE?rQ85w+T;zlhN(ei!&pM*QWM;GS5P
zE-5)W1%3j`$u7Qi{lWM;qy{K%c4@1^UeCgMNlEVM-a;%u6zF?y{E#a6y@(xemtMY(
zYx>g5*Dp*-l2HeuiCvOZk%Jx1SW$8YrzVL@b}}IdzJ$YQVC`uKu}MoEf)w6_Xyx%|
zWyYk$3T^h+KqRV&x7A)tG!+BhUBx3`5iWM+f5sAbfLPg-R@>Vz9&ATVkQL#^Z1L0!
zqY~&zN~lU!c2%fpHrqytb24RpYbgX;W%4zEg;?2AQF6s*1&8GeZ&T|Agd3J~O-gJ^
zR)Kw~IEs}uwM|S!mqSb27M<Kl2_eYJf{G$Ctm&JSxJrjOub7yEQwZ)Ki$cVRc#>^M
z)M%YWj$cBDFnGQRCb4QQzan%dk8ow~DVj#-yoG{o^7sM|gVmyguv+ns0!9NRsbBI&
zWfkj}z&Kd>`X#^))XN4X*KcSeAlT9>%g^v$3>l%IX))U1MdX!3?(QTdlXc|niWZ?k
zX3mz0JpsC6_yDvn8w8_TuHHCdW$6XHidAADN=ez!CNgM(EHwYhidQjsJ#EGfBIU`r
zK`7douLe<L*0{@5jO+$;ne|ah%e>%m@WgoOxo~=$7d#G*uH37Rj0XcoFTrq3K)HdH
zas+`(Y6zK<7!90c6ND^rQA}vCZa@^Q7#bq_SlXaNM>GMedR9lXGMOU(!Mw5&PCNr;
zlLp9%(KGG{pEJRd2E<8BF?HM{Nh1ivBf2m}*Y8ezya1peegpW^&&dhuIGhl*1?ou@
z6RZ42l*cn6Y^r{ssUU-+&Yo3*<H-$B@J)HITIDmI2&^|R5T}MHX~1us*@4JR5MhNn
zxhTobQ?c;C9bY7HIOGB^e5Vu46F?+lk>3=w@+K}UNI;}pFVwUrS_B+J2xEVUYlda+
zk6;9mMPaJD!q97zYnV`G5hjT5;KuI?!6qh}^}<ApM!~M-SPBjemqIT%G+qk55Ygfm
zwE|cKz?&7sBEVRz6AumAPM@?bEK*z~G9dR<<KBd?42h0iDr<5FR=*W;;)CLS))`9h
z2a(i|kx^fTglC0R3A8-xss*{=^o*dC$gZ#grF_of5yk;&u?J#vg8Ci7pB(x96o0Y@
z>LiFifMv15n+#7km~()TGYj@WyW7|U^=@NNdLs??_nvOV<Q6|N#ZpWKe!Dj%Tkn5S
zDDF46i;Gh?_Y3hOp~Y<Yk=QKM><PKDD7l}G4%N=OP=TS^StkT=)YP>uykGcW76n^3
z{VPY1@?;_P#^eU*nLA`kp(Wso^(HoQgES!}r;fHL`LlQ;x=?xHOjs075^8L3nk4)H
z))l-CtH05~K+F|We(swRt->TtwX!n+qQmNL1tE!?O)CgV6mBu)^akik$h2@%Bx-6*
zL2$YmPGoXh5Oc*kugAb#K__B^!bWX{D~XERR=|?byMlsQFlP1<(=S)Ifi^qw>s_6M
zQahrF)xHqsU`=HXF1##FH*2JhSgZVjhVK+!uBi`{lR)7O0#^ZYgc6lmLfx8x^MMCo
z?P3c2B4szh-XmybQ3^?z-3Y_{s2AW?2vWRA7!iPst#B=&N?9RW0uFg)9&tp#VzH*X
zE2EmMpe_NtY)#;~0J5;g$cST+&<l$-hk9{5L%pzG831F6hdJS9H|1XwZMt$|X6l3j
z$RrlaqL5i#eTXcYwsC8^1z`za6ppQ_7sr-2NAqG8!{&8APQ*;pnH6v>!E)j4&QqNR
z?uB`(7jCk7svD8Yxh-^y{zHDyK$#P33}NUn_aa@r)3hspT&FF!STP_iwxJU}pjs9$
z2G@I_#nIw?1JKBn2_JYXNAdx~=M_-k^R7+<?c_IZpW*6331aX9Kqah2$UCF3=(~Cm
zy}hARrwy`0&9YVq^p$D=?wWdW2BuChM|WC48z7BGs;I3H=pi{YVI0%ANkG&@SvfN0
zAg6#Vz)E{ql(^wrj}`>VMuEDcdWf|q#9F94M*n9=K#d7#wfm)BSdzCgW2kT2Go0oK
z0#*d!G>d}SD3y`n6dmz2*7P!_-SY?vKJ4nn2|9bB728<vrt_3r&5y^NPbnbqOrWpb
zdG+gYbzb$x>K3Ly+42*&{LM~#V<WmfAnL8@{Uw;7$s-&kJ<j}HR#D-i(umwU7gdjR
z=W8!Va_?MOKHDhXx(KXz0!u>ELk<*_$P*kOuoITDPjzC&6E3A5`_832={aLfmP)K)
z*%p&qo26Z>(Y4C*FGv7lMVMf#Kyz7GW>LrvoKmB08`Wu&!Vy8qGa>Oq3^D;yur^Lm
zFe0R$*h7#9R@pHVUOy`FEJ_vdc`%~Sl0H_|tvk(kMkxgk`67U6c%yd;?p&Cqju((h
z%p}|Zsbr@Nu?)Km5!Pl8TB*sQ3GabbeWzbjOcN<&5zxS%MJuydYt33QmcLkx6=h#R
zD=zaSTd|p0)Wznakj;4vEMGddk8Z_v>;o$%lTu8^&akO122_R)q~UF|&~ElY;TD6`
zu`FO)tK;rOAV;S)Yincp*lV;)ZIn}sOF1U6v$xF$pZnGc@$Mg#`sztf$wttyV&s7a
z@iDW&gZMZ+0SPh0Ay$(6<RefZJ_(-(l^_tL99is+8!FR*m-(U^qc+cJpnUF~1?8YQ
z=AK(5&Jy|dkCXi*bnTwp+6~5v<CBDo?JEljZkHM;<Civ1myu6AUO2+-p-`b>wU1RV
z@Cm03l;ic0;23vIgHyR~??urK56WFP{BvhX$Xi!@?w58$ghUx!S{=4FuY2r|8$}%J
z{b~0UYq0prtJI|KYajjm^`(g#m%j{ud=5YBVzL`3z7O{Z!ms14=ZVAZ|1ew%k$82F
zc2kH{so%S4<*?80T5s%_n-?g>fTIC}#u|<A?dI~TDDchIRT*^}4jRn>N4vPb6kXcI
z^;MzZi_4qxPP=XjR$#_;QRh<e_3M&gg>!mclC1I^UQ<#Nm=W$;BWQRMC^mr?v=fAg
z*JLB03AkO%5>{FFz&1NJQL-V%ti;U*Pi%>#4H07|SgdxTq$fpNW}8GCd}zN2#|?;f
zlAl)!N-lw9Y-Xh_5+?~uQQONCPssb6C@e*pW1PSlkGkc70ES`d4J|#ZrjW-b3jhih
zPpN}+O*I(+sKYcF091Nj`oBsRPaSAgqn}f%8m2WTlr>ChPN`j3t2v~r@k~dcUa7rp
zmQI*caCO1DOqYI#bxAjEs+K^ENRN}Wa+chd>YnK@XKJ(@f6GpaOlEm+BjyMzfQPP(
zABKxTd2CF8q50u>DFdc#6wH8;=FSY5GIX%6xdC&2-CP46%%*z7fW9?B)-~X+mer+=
zTYuyHq5K1IbX@9!;SK5!EDH=5t_eJ^4e5d^1I*wo1rfKw`<Vu)Ht=4{NELZ9VZT>B
zmX!m;ZUb$0;s9Nr!T`Iv@F+5rDsfPdH)D#6X4*{I>wZB_8Acthy6_=pEnI5%LbriO
z6m~*T*oUGKJfUT9MAFPxnIxGrQ)bIT7<eQ*07o@Q5C7=XLfQbNx+oYCay_h-u!icC
zLBbDBb>oPpx^YA};k~38FVina6enEv;s&o|*_0dOoM?7FGM%Oj)6As_<28PTz9d6y
zz}$^v;J8VRpq5Oev98C_n|k3SI2}iN=-_=kOhuj=;EJs49dr2xuuo7Xz=*-g3=p^r
z4v;p7LhJMl=(%BJk=zokKXNDlX0!oI)l?0uF_cIZvl^gOO;xp8&;OnuzHpFLm#e|e
zRUlSxO0+OvxcE%9zZye^B0%Q=MNXh(cUC{MuA97<-w51BB{RC4*4^3RI?A!qZKOK#
zojyiEX?1#ybR+jD2U$L`MoWYIW|8-v9xu(2n?se{d*ha3-S$q$(bOF2IMU_Xu{WmX
zNY9Z<Ni9+?nNX2vjF1cVP1)R!4d;{&O5}_jbYOx6e<aTg?j%zIzs5i#mHlhHKMjQe
zTin5>eDX#+h1}Au(Fy&al^l2^$}~ElbtmCXTa<xzGC<c4UfA%dXB=$9OKmF4*kDQy
z&pf)h{QFoD$Rmq_kmv?UM;`wc@{+0cWCPTTDNU|5Mx*dHX<IA;wpo_AHl>I)2)gFF
zIv`S;63ZH_ih<X`MS--Sd^Dtt1cmH56)u5QfNp!3YLxyX^jCv|V=Cs_8YEBUFE-c`
zjtU=X#P3lZTc(l_8szm==roc|fXjLqEB>|>&ZLyghHxfTFm9;cl<_l-Mi<4`91R7d
zDhh{rB&O2NktY(I(W`C@Hers`u}F*(VmHJnF&n&D?uq<`ibdjg8)7~b!t^FZz|$+z
zP9jcAyV9W13tl}kQz8;87i3*@b}Gt>{J?4r6HCu%VZ&veB@^=dBBaEkbYCW>*wEW_
zGNw)23$Uw;GSJ@Q&<>DxXscJGqQuAPqG+h1R6%czQAdDOSd%<)R}A=6n5|;N(aKOd
z?N}5|vY{PIltLR)0L~CGgx0^>`C-ZSCnU<D9gI3jmR_ls@>eRDkohYWZ@6+(a*ZTz
zpO8F;Vp<xC;Mt&W^i7EtaT8O|7zKd`v%x@$2C`WaX)+0TXcTN2$t-?v0hy7^5@XZt
z&d8=z0CH@wAP#MOLRb#n=fHJbA)*}M8Lb%HN?KX3>3{{!Xbc<_3s-_lhW7FREJ}=a
zQsy%RJRLS^VPRg2P2R&yY%x`|Sd<KCr88zx@&Z+`>>?Td2+)KNgjv<kSd<I{<|#0Q
zNgX!x7%akxKfz2>fQhOdt1%Mb3RBD$a1I|t$1D=L0@+1a4NP=dl#U6*cd4Qz_Aq>5
z4*d~sBY{W!0ixpr{b)}0asquG_}#XLO0R4go0onOvGAwZ%vgAu$n1v0#V%f0i^O<y
zj05Nx6|-&tsIY<`y^*MCSJxk51urp_=D<tbLtctq^bXsNI4M&N9|I78<pLs|-!AC$
zhFpES(mQT9E{=<6lgv`Fi_e-Nmg!=U)*`gAB`mxNk<nn_QzxG&z1hut3-KEn=aoGX
zX)H0}TfAg!({+na@F85cCJd9sMYYj@uWW>nw3{l;_52_qQzHcBdE>#lPt7{T*jpRo
zwoFV(z0Z(sZFg-3Tr78O1_-scY5Yv<F>TC?c|8=7jD}8C$}&_~wi_oEfbDkUq^_w2
z2Qm1}WHFWJG62q-N_ZJVsBT7|S>`DpnRApA!0MO^hS|leAMLmc&)_}K3bqZXMa*=m
z1S#&DN}@7k6PqBDW3$DFCmlbA+~G>tV)~2SQ=H2S>&ClcsI_hP^@Hs^c{gK^j3(Fn
z*0){BWmtL~uSLNTzCvBUZ^oQ5KgRAyYX*_)#-_U}^^Ko~z2<=@ByWUF0Hok#38%CO
z{4_MT$2dtuh(0C`qi*3Mk;N&iKTS&u%bt<~jS*i;95k4FkIXFm1vM9xOd4!r6>LmT
z+s1q4m&Ge+nvdQR8k&JHZYZu|PZzIRJ|9>j<fg~9uhC~ZqHm+mY{dLY%j`}308a0t
zYH5Z#HR}}wix`&n=pIAOuy~dAH<^$MlV#vN#yE&fVYAX$u^1C+tdG8g!}w6fm_V^W
zqHU74MBMdqWsa}*1+s!Fq1R9ZX^BNRj9DpZ%M6Y@p|fq-!-hz=$}nD($dJy<=P*RR
zHQ{IR)s0kU{4O&6Pd#y{7Nv}6q#qq2c5;pYq&Z#lObA`qERolKx@HO7m{V8I%ye$f
z5D+lu&<q`%nwp{i$h`4^Rv2hQc*g{p!hUJVTpGYDv!vo97bgc;mh+~iaFLiOPnL8g
z%45$0KlH7|L<?{#=OcDB0FtQOL?mBj7jY!9is4wK#J33Ck*Gjms;<sltfi+7v=d@M
zH^>ZF6Vn9(iL|MbuVvuhk?JG(W`G!|jd23rp*BWXC7Nkp0Hh>!R-&^9>#X(#lGRPe
zoyqEk9|>I<e?1<8D$pcma4j^Wu4BNxYbxbzKx|(WY^GESj%IV~6$gkVSO|UGRB1Xi
zjTozB9r!F@RX9Kbf`vLIdv$97%d071#*oNPs0<tMWH$Nz7b##w=vp`UJ{p|asc{u*
zhas;W$Q}nsfg(aZd=U~xMEb_~6-LAcVMGK#9{S<)>=5gSsVu~jKY(E$^W(qs(vTC7
z`m2CZf^fDCJH=3uvfx#y7azi4VG3Qrv{0KaC>MjDMrbdFwD^_|sskkA$W*VKr6iXD
z%nU^(GX-yhsG&`uDJq&-c}?Nf1}{*-;TXb0Tf1q?h&;Xcp=axsBhtl!Akrp(h{1o<
z`dL#0D3p8~hSdDl&*~N?V15YjPhINkXrXB|c^qsI?Wt|O5|pU=BqmYY`sCnx4UT9}
zee0H}L{h2->bocl!%(xebp_ZiQXo|M)+>%oA6u{BU$313=nlYB9!bhE&aGPxac<p`
zf0G-^!W+R3LV1$fI*9Vbmu3*;NdoL3%G14dO01OrY=4xadvuOYjP9vlj=}j^ouY+=
z00JO4*X;pEUsD2F*bAQo5*uuvjj(MYG6jr5A-mD)NZdCAtU)2eElL~od4UkORa2Eg
zL%eW-&@qj&fa=2fIobwh2Ycv2z&ntLl9x9;jHm^h7s;0+Vcn`zTzieSU_*RzQ-UN@
zG#3Sr32e9l^LKJQxdxXMMnp9?Fbh~xE^P&Aor^N{H@PYgS_!zO+*4YUo9pyD;UXn}
zI^iOvnmFz%IE6u3A5wO$kh}GEIDsJbb~u3`n_e8x6VL{C0I?veI0vLunPUz9+r$jd
zc3d>0)}Kg_wf=;Cto6r>G-~-12vX7|@>$!c)d$d(%%+AQaRvw^C02HnMe5i3B4o_e
zc*&Sc<0W4xTP&pX#Prl)lTkN!9RV`$ZM4a!dmC+X>e)ss7*cUJ?!bBOd{g2*xHJXa
zVQ`)o7^)a2z*I4gpsL~<umX-G1(d9$OmcGWdm%VC_q`CDo3$6>nJARlH)%tWW&Uv?
z%?bm4)<#HsMIzQ7zfj0rfR)YK3JJP7YbQWlK@p+@q?o|<_0bY@A<#@o0!W5l(M_ku
zyVh{(&W|vJ#&Xr>5P_y%0H9K~sTTkV)om)YT%=0^WL|@<jG!dg#>`kD)LxA%9!i>^
zI*QV`Q-St*wT+oc>1gE|UcLCDP&c;pup_^M;c`1=NF~E1&q%ya3U?Qv;8bdTr@)~d
zq_yr>9o3@T`u^GpmyV{|Ip2f1>8)&;qSQfz@_L`2EiN;lTiRV$Fd*CRdOjhL-hCTw
zQts_<@I%k`NAW|C?Vo-m+HI8DroqkoV?zb$+4oPZ%VWQu#<FOw)B4ojnOSVEZnU@+
zpSIm-NvX|&8{zToI*M)39<SRcwxj^OcFHfe&olPhXGwgm3`e-Lo~hdh&3cHkbl<f-
zM5G`WLzm;TU+!^WpY3udp;!^893H7-C+)ZUh<4rWQA}}r|N6P#?6DCdQ2yiDTm>16
znd`^;x!>*UuNS2lwKBxJ3YdY?&;4#+f85Wuv1<K`1qtfq?`PjxwPw3WpYPzx4gjmJ
zXiP~Z=g8ufPl+Wt%ON(Q(72!i@nZLLZgNvUv%Y4@P2rteB{@rQ>M`JJ6P!kr`Ya(S
znSO6lQgZmNgM(7HLS9^yVBfO|48cA-H-RD82iwm9(i)DPC96j6g~ZfgjoBuqu5m8P
zCZ=W`*S5>4PZnS$vse?ivlRpBTaRE1^F)%g=D!k2vK3q@qYnh{UPd2h)m*7&L^ET?
zN|KT-)Y>8TGtC8*7|hfP-~>g&%(-h6kyIm1C0TPxQ%NpdpPEYF3_Z|hdYO8hg>-MN
z2+FyasmEDN_o-cv8t=;Bpsv-KQ(#%WzAMZ>^s_Z{hUcgD6;oGO{nGNfV&M%MKvxvI
z0TjI}0v)R35v1xC(~NXYDxkfUa-Jr=-by(~ncP-(KLGIb&2DpIiZa{$T7+-(tzt9`
z6vtLqnh_jTdwNmUA}N8EAsrn-*|d)IjIX9GBu6`BjYHXVWF8~rqbh0BG}Dz09>th)
z^iy^}&qO$xj$(r~Sr<`7y_Izl)@tV5y%amr8MT{$PhH9V2JA-EAtxn%_n~kL(^hZK
z)++}qOY<024m}KL>qiBq0FzplOjnQG7QJ>`p3^AL?zGJfR&Pf;M%x>s=xOuoy=|Rh
zxV@tl_kY)QGf-7sL7y-+uF*M~YZItoeMGoCS>wKX<Uq=>j8`s0Em=r12Qtyhf#}UZ
z7)<YF4a7qeKq_f%Ju;<LJ#rw|)?*D-2HhCcz5V?)Dw8%TaqK(H#+iy+X65K#mcQ6G
zJ-~iwhwgrsfehEQ%l8EBvO7)J>-%ooC*t#NTZixlcBffA#^80M<h|*&z9{439jy`R
z&d3BZV9s{$TZb5hqmd)f>b@1(?&VfOZE$yaDQ8v!R|sIZ9M&?F*#{s7%m7bH+ySuq
z9O>^^+o8-p0PO9qQw|-uJ5M<v6uOt54|hxVYwI;4$DK|r6wdbYJZ70}FUKR2le+6+
zL4;6u_z>V5>Mp4Q{-ds17zSm0QQ&b)S-cM!0yBmvzyZ`JE|0PV%`Sw27d>BxPzYXf
zkM&U=CfvhA6<0extk8$dgjodI(E*RqhhCbQN<bgwc*M0j%E6TX>ce%i!%Nr)eT1>l
zqqYa`%d!j2_-k#Ae=H6=Q<3Ze0BC^Y?n74vAiMjR+NUU8G-mD7xGjga&cMK~8U_Yd
zJ7)$=M!9#v`Pw)WoUffT!TIu8L*ySaAIzD;Y99)5n7IC?OvnJH>{Dh$IHkLa<iK&A
zXd_%8NWT>a2M>6kx>SIY*{5EPNkO%u-X_FSVOCm{awQx}w)0a`IVSF}*}31JL|su-
zKrGXg{4jA@O~uVboIszHTIPezFeSJm+MrK8E&w0xQwj*6b9$MVF5q+md*-EpHR97G
zWgUqr{Sz5_eM<iXJZd1}93YHD&r!rhGDY?!go||HnKGoLPqy;$pHe&#6xXLj3K)9=
z0qEJnMF<k~QjAHIeyhNlSVMujCem!bq<vmE^B3cHVs=*v5Qx|5Wo<%OU4SJ$4DyLN
zUlpf<1Dn9M2LtQ+Rgo#E8eV26AoBK#(PPE4+zQuRbE9toflq-b^${G^%l?D_Dne5&
z$`vg>_ZI|)OKt=N-t`K=yKsCisVacb>V<Jk0OU?&<cPbA$vkK!J8FfYB3-q@DNy#S
zRv5~S0Gt`{)>ZPJL2+GnEd<UT{Wdg*P|LD?4FQ|Igj3ybd6ifl{ciGK-FQ<OMrZiJ
zeut28$G`N6^e^^X=bpdRD_{;d+g(832x1HhBNkIR>9>pz8K-vykQ_o5V?W=F()_iE
zcn+<?E5n9LEWFpjp$RZ=AK6EE<&zZm&yn2>E4-ly-Tdz%@7!8%AlCJpPzfs*bhXH$
zu)p+2`ErXggeLe>AYrcnH}GXq$e*+ocUlOKAjK9JLcJjoz7xQn@rC`#kwE@`Xm8Hs
z`XeYDJB(kd`)XNDY+*E#@mI9S_`E=SqVpdh1?L6fZ>Z@;bjYLx=PP;*tI`=pourOG
zA{!uOKT<hiuI*)?ydg<v==PD6Si&e|z=-9Ak%{PbJTebG&<_;%N1N>lF>etVIc~YC
zaz0=c0@V}Y(^YI9Tj9Yy9`K?kNo$H;#>OYbcdxKEAbxt;_MVGBq+1ub8h%z_c{1J0
z<_D8#Ah_aVp<@8#^#COa%$YdzFDi2(CH_UJKUsSv5oljkV#CiH&Gr3-V%wD2Fp|Km
z7L-g?6xgEVbQE8@NXZx_zOq*CsT>_Z%DQ61SZrib2ug6K6znScvM9kAQ^smqO<e(F
zEkIY?_y8Y^5VJOA>YORaI1PynhEzvH86)!Ch@fyHl*eUQjEFqXYQL2Z6Ra>H8K|%?
zUvBhDykw@F<kPrdmN~wOc@tjXyrO}B=Y)IZ|D@*Ss<6|5I=q0NnQoHOQ9waIq%0P?
z2|%B@M#Pk^d?dF@*2zV6mIOjxQxFn*BQu`@&pP>Hr|_;baVmMOG##W;EeaOZPO@8R
zI!MZLnK&0E*?pmvJY$}YwP+xqt0jWZqA<g)fon>^w0!;+LO4^pI=BWL$wRS#j`~f_
zxJPv&jC+&@s}=Yc-=;gWB}8|^o^#6Fr2_Ivu<xMcCWMvP3*iPlKD^*)z-TWV7N973
z!JJq+>%9<6EH9<Q1*Fyh;pBzyfeCqGcL4p$3z!3FI)@7$uVEx!*cbqAS(NIQqh{(E
zpi~xtw?TlSctKboe$R<U0RRyfhG7GUy%*F(!{b+_jaz;p!S^v>$G4S%j5s@2oLnPX
zr592IGHDn1KW9F{LfycymO8-`kg)4b(8dkcQg4+Sd|?5#FOeGTg^qyqVb9>Y1Eh5h
zWl3dBowGn4L+ZR>3;?ReY6+2$`(SA(NJU6pOjMu+Fr#|YZ4M+`CxUE7(ZyVQ<YD$$
z&8~fm6n-x(f}R_1Q3l!}!g?3(PZkUGLLNXsofp;sY^biNzJ^r!!#i$!m{DC;-H4|<
z^Jn<OX;1c^t%0d145*5#^T_~ewhK*oQDTi0Jcv*_ClbNIaJndafld$?x{er3tF8#c
zg&43}{LGD4{U2Zl`~!9%R&|3N$cx7}qyfCdUQh!_=JtXcK<c&^+<@n5xUAENusec8
zSczPIN<59V*gHd58Y<MdA{m=wwS|1z09x-daz|;=U{}6IQGE1yQ~~7`!E(vsp`D2e
zrd|L8h-GlaLpC2-X(ic*P!pG_yg97u4#04hu603*v%0MdcAW8bL3#K$+3TWXsimdW
z3vB=nS1-f?7+Rf(1Aem$*$c2CXDDWa7jY5zX}s)R*Nk&ZC~Fm#)~J$0h?rB|3RH#N
z2x7x6p+^$orCDwVKa^WScM-x}U2&j@x=RXvrbQotIWp?b6)MW8I~Ux4M%{VA8Nk=&
z8=L{KY`yELMHsXzz_h{X<OOg5uadJo!4V{O<9LR;aXh#w{M3l1dU21!RpTmP%Uam0
z!V&?8E_BoFHy{YQNq~V5g_W9KL18zp*R5{E^m+6#AgsZb>aIHyrc@6<Nkfi<t7t?+
zW`w&W=5#n5LBe)IIx!1WC1pgL7*od22(YQCPiBU;NGtIIU_b!gqHGXT(MOkL1mL-f
zJR|<@2oeycTz!a$m6FAx5W{QeZ;0VF@Vj@xYOxcJ9x{+T96$}$P*)|7hCC-%G_XLw
zTwWp~gR$t?OXy+l#Oumy!FB5bgWO%Je49^HIs@<(1OzYOt2{L>H&VOa(tY7dTyVX)
zOT52MbkXg3<&Jfg`wnEb_>csw%W_EWxKClRb(g>e6Rj6&MH*zCrLb4PUGDWM<|Av-
z<<V+c3d|GO0@hJ?snHh?zQnrAxofFwTwHVsdRH#GurMy3dZuA9M$cVgREf&RVs$U!
z_PJ`SGiJ}7IiZCAW6`^H!Y?kn;0F-5=c=p2uswHO?U{n?^3fd(<a3qhX{eCk3gB)i
zqu|2tXsEI0DDu<NaCv0yzT9@mX?9fxTJe6lxD-uquC1Pj8*6(@A-K7^dNOV<E?dcS
zVI|x=!1N5Y+j+<zVp|UV4d<9^Dci-(^Q$-J=J|bqS8?+QOPjlSg!K$%=C3P`y}>5x
z83_|;m>2jhxK!lqyIh_PiN5XvM}-y56Y%7Q`^HBBo#ww-xG^cgZuw0KYwD~SMdZ_i
z1t60Y3?7o%k+bUsrUKa2EF<|6D66NCaDX&09Iyrk$(@oaw5nVYB$gE`17tP-K-jY#
zV*~3@OJ}D{@d3<yki*T&m`S?E2jLQDu<ahayWlR~++h;ofS%z67PC@rRgv>0jNY9B
zag1*1Ltwu?gfog_M@8u{0}jHU12Xu75QaJy2z_NFBt~46i2>)zcKn7~*kVR?bCD*-
zn@hh!98U~4&q+sy?I-0Ls9w6zoX@UV-})6!x+t9VgI{q?64+}DmvoGGU_RNJQDHTg
zg3*tklpLl?&3Br;<ndpWfo^$ZR`gx4ekbIxlp@gW-hTtt>9$V;;OUbR9EuKvCaxwn
z9ytM%&L?H;+ygo*C<jPn-;Ez`;9gO>_DG(d-u$zLYkm;mA9k3HFti`?#_Pyd{G?z%
zAd;b@`bdzHYrx9<r0~cA(Hlk>P>AzhJFU~GqV_GeU~9Hp8xI@0;qBQ;504v8213xb
zvqS@mP9W_kgSqY<7LDx~cdL`15ojN`Lq|&DPHB1F)FsnlMR2sb?k#MEj^|SMUx%iT
zJCY>?c%`GFK^WNgCNFrbA+002tQRHKPhIF8HA?Xge4*$8#)lO^U4(i~P&?t+o*Wif
zsAp-#nz``37;9EfTZclaV!}ys2sTrHbVIPgh@ttpVwO-yA}Davvf4z+Lo7&9G82nf
zxZf;Mfg=fF>`2mpK!o*0IlhwNI+Tu*^A_cStO|%mMv;}o$Vf7GmYhSfNeP||By*RS
zwj<Lg#MStd35i{m=@3O<LU4x=EjhU}3$KLfo}+NTG*9ZM7g`k8IY;WIQ}>rsIaN)h
zh!B$=zyPt*6gsUI3Uxa=%@$BNI*k_pKWlH(vs;d9ht2n|IKz7fw<A#>q^1F41IZw;
z-5CX$*sucx-2*!?lKlHTBG+2`t#a2})u)XDx{vri+WOeiCPghS>P#}QJ?B)?Bz$lt
zBPR#Hs_$uMR7%h}l|>0b#2*PtHT#Um9EfJdsf&qps)~{c4b|d^rfOlqF1~2o%v?Cw
zoNsQSrNbTG7tmgFD$UZ`RYDUr?uV(cOH@^O^E(z_y0R_-6FMieE-k$CH%lGZ0p6qO
zm9Wx68Fkow?qVK*pCOmTn}mtGm`7=%yXvSt<dRTcyVoT_r{|DMLaBvzS2c83P6=cd
zl1oC^z5$;EaiBv!2|8uR7oP-sJFo`f-F<}IN)aA3;q1UlkW+##lOd;sQUmP_!ArkO
zy(Bp$;ENveNywbpbv!lvyMF#!5u0aI*#tW^uAE4j&J2~<u~41t*rU8?a#>aGG*sh6
z9aZB*)rMEHo_%<(lWucvd1cgVsDpRt-0;Z4<6RZtUaYioNJjn_C7yeog2VYKZz!$T
zugK(fPm0ioUwbD9+z}#m9ZrX}^bP=9bLg^XB=>$w(6gmVczejLJ_k$X;HLX`IO0y_
zBEFJxaw{FFZ`G<_@VY{&H^HNJC9rMWRflsF>G8&!0=d`g6(7#q3T3qO1IIeXf8<EV
z$AGR1vi~xd;}k<M6Fxo@={a#O8cJRV7}gxTxJFvZIh3mon5#M7Ty=nPT~W1M0H-;W
zj15UHnN<BROoUmN9p$qb2ydKXa;SWoQ-sXKa!qkI6Uv3e>wjV5&gaWz%oUYyd#G_Z
zsdcHt6ru0U&y`$6&IAqh03hkTEn*hZ_eN<1*M_p7h4WgfW{OLL8O{Qh+fY6;`a5*}
zHR$ia71@)LdIvg11+Ox6<_TV9=u;HD%ILCafc%<o_RiCEWrt7Cfqu|^;+6285>ZKm
zu9BfFU<c3y-BbeUHQ!vFASRomNqvEt?7b9aLfxq-mT|^=r&{PP+{CgSU2rR-5S=Ny
zz#VX=ym>gmQTbj3UrAl`Sg5h3OJ}?;K)I&)^a16X4Cc8=t-3fDwbVF3$(XEGBoUgX
z9LQcb;%LQnuZ~4gM59lN(2na~9gFWkvnW34O7hJaGajG!QlA-*ar#!qhRh!gEI{>k
zw)O=XFdOf}X?4xkeho3WB0>zZyP4J+Pp$4=Nr4-xv$K5xH#`s!-7wJfi*BgSUffw-
z!xL9QB-%8YAs18Df$Lz8r;r}(@D$Pm9Znah(HrnExA;`--2@r%6!j94l&1tw*;vk9
z!$xetR92n|e3O#<6k2U6;}MgrPbF?*9`^YrDI-8_DxVcIx=*FrLelriyl;~pozA}k
zgTx(>IJ8;VA52|uLIc&>ya2I+H@Rwcf_+@oU^nzPV?FFe#cNJ*l}*uiC5kLPxgF=4
z*+&-evI{Qu!l)85wg9zilvKmw5=@L(voClpV#J8(nh0SP<m(C!AYb(c9{lY^j!lq%
z16~FRL1`TH7AUQwY3#)p%a#zZoSDHv!z<9W%8@y4DqweJkn8M&U!5yRP?~bu1LQRo
z1Wb_E6iFQ4Ga-IYiE09CNH}=*u9uB3Nbl+#z97BpwHz$^PV;qE6zo)-^GwRKTSn(9
zv(*)#Z`eb#E3@-NRO}SH-ZUaQVQz8<=Tgry@to8R&m@eh@z!J-@toQSMm(oB0$BNH
zqn9HQU<K$5jS^st<{IYA5(k+F8SxfQ<3(H39zY`8*|sJE3$4NQn+Rh42(pBaPy?0t
zBq&S4^HdSD>1&Me)G4;dNyJqf`os`&)p!V`cAuiGoRuVHifZ8EhZ0mgQ9@|p;bjxh
zEveBkYlHA{#>5cJGLE+X09DUbz^{mSYm5^X_?2K(u-gY|C1~nDX%Rq>p!owEljx9-
z0Hp$8^Jq*w$2iKC^*P(5C4)CODq2#ct26UV3~{>>m@&lv3KT|JT9|^_1hdCfBdf#^
z$Hzp>=apc*6Sz`ZaevVf@=7pqICzeOQy!129|1}XBY^kf9*J)e3vwdDfp?5Nb<<8Q
zNe(fze<tkYAtqlU5w3*YXM}@v3mgywq``DrjNtKW0`7E;@hWBCc(N+@$_O5$;FC!S
zdyg>FAr54Eght5d0Uj!k66hI1972n2A~(PYuC}?efPYudqzb?Va?d?jIi%?bu`uu!
zf5gzNVUY)YDD+2;FwGh`EW&s>Kp*N5vo)QuBf91aQ4XTWrgL}{fz1O^y#X0Cq+*D7
zh1C`aEigqHp;UX>k6J!&@KUu*rUTb1BZ+}C4zjLXhld79LIUT7KJNnVk^C>ZOyH6I
zFS^ATE<@#dJf9R`dU1C%T%RZ0HC+h?j2o{jsSzh`Yq%oO=faL~BKaoC5?l)i1di}^
zl%RT7Yv`E>n;lMf-Xv*(>myB?0++EsJ^}IIKa=zUZW<;cUR|mlgrL`Lgh4TYR5s@#
zQ_I%(y~5#1bu|}bMR|mpjDO#uH;Yg1R{FGwu=nknVXV#V>`W-M5(^rk?pq%32~gKZ
zlz#`=$Ce>jk?TrsFhQ}F?nKNAjO4MINq%ldf?{KD#(`>QgNbcyy(I>xZ^b6fjX+Rf
zuO_&7$Ce^tB>I*n*%j-vO*RM|wL`fjCL_<u<2Dg^zIALtNN&1)Yn0pg8l^TEXucap
ziEq5pYD{!1UC<b%A-MUxqeSQt6L?IxfQK0GrXtHj!_0uY^;%jWaHbc%e!@6vyi4S|
zpfmnTCYs__e&$A`sq&#rL<Nr}drQ&e(hy&w$$327h>Ke|LSV&=wKP2yjjFsbS5Pg{
z<28$_?n#mHF$kFF<g7Pd9`6dVb4%MBj%-}CJP=iA`nz<JS88$POht^dR3nrw*f_Wj
z-TY3_lMmg$PDYFKu5^OseCR@RZW>&|;!H5-jd|W$MF=4iV;AWGD?n3`541$tGC){!
zlLkW{l}#E9*9!m@hO0_#ZRL2H`zsT~-1vG3kT(%MJ#_aq!PhtDd*0kfL==2wF!)GX
zI`_+f@wQbw6m^=sCoz9%Fshb=1Vf7h2~vh`X=Zx-Un-7SJo-uP@uiZ3%tLi@i3y@Q
zz2_Y+D<D>P3bHVfXLjfcV<OtSNJl2f247N=$&mHgzSJmdDQ^-c$Ox191XU2hE_RfO
zyN6;<nT{`1T_ijZ1x1HHs>jOeM6TT;Y?-*8c<EfGGyYdT|B2Kv#R)Sjyj`gGiOdl%
ztIR}pi7!Mn)8`kan#maWu~^DsO+6BP7h`^@QQ^(Wk8_JT!D3UMh-e@3U{9Z4NO&d^
zX@I1s`m_o`fuEBxh$UNJcz`DCmX|ANR&@Q7P>w2Am)e&qH8Jf=m29-3Q1n;z#-9@9
zE|4d8BJ<6V<8}g8ngmK{rz~qz4BKSjzFe>~k*7mG*U3PBI#?%eeufgtPA7wg?Ju>+
z5QSP^oKm%kVKWZX85MBWVWcUYpaB@KClohILrI1wvbYT8E}j6v4tr1MNd7XAZuypz
z;c9%TQ}auZ_ylftAno+@D3&mMF&*SXVv<iuc3-wb5oQi03!k{%dWKl*Cy5GPkESQ9
zhmy=sCwCk*08$769ri#}L~(M{kl~=eySr8eVP;oSCDuT)+RFjQDlaRXsuU}nqfpd%
z@Af7k+$LYe%+y6g5uejZ{-!TJNfhK!#8Kz6<poS|Bs?0g1JR)tUUwmG`9>$t!TcPd
z#_Jf2#sTWJgUMlZd#i{JaG_kJcY5>4jWl|ff(>{Zx?X+JJiIPF9QQ7Fq4T*l=%!-^
zQpsOYQ;)%uxYggHnbc=KppY8>UWQ21hL56W#3up?>@TPh?}O|TP20ULI!6<v=1OuB
znv^>UD3pn0;v75_r9P3GYUFjn{n7+9U0a$<*xyYDhJfyCQ&VYZ${7AKfd_y2Hz#Q$
zMA12M(K=pl8&Yr$l7H5Ns<oyW#?e!e{S%&omv(gG##Y3n^`Ih$l~*T_0!8U`zDhV}
zqX5Ea2o7pH@_7cbsvMc%UnCqlavL1^^~uVSu;&x6C?#B511zmmLmwbz)umG4qR7g>
z2SB|YnNWExZHLD)6y;V2?S_G<;`yaWlaNod*PRzgL38?_*00JnFHeec(Cy2_Q1VX9
zr71q`%e-7c@I%UcZ;6ptkMm{6`7%%WvLn9C6C^C%Sqt&pe-*tGnXf+fm#LwI^Dq@m
zkfle_2U#p$;CMF*CA<lVvXd-^22+y9L^m^m60qPc90g97!@v9SZ=U|+{`X)0&mSE*
z2o{waP&c>>`7i(R$A5aRq1`?W{`&tv)&IvoKcDjFzkjJbcYXa>*R^V&=k*_d{_FEU
z{HK3u|I$8f{rNvV|NB4v`JemrfBG-~^*{de|MBPl`T3vz{M<LUBJA_b-Oq0K;h)3S
z-u~m?{_7wA`BU#cy#Dt;{PpRG{aEP${cDmb-8outh~A<7!QS3@ulZeX|LK4I_y6}l
z|M~x_UIrdD+}5Z4&-c4|%*zJ*x4LNs(O@qPXZN4z<){dmZ+iK^{V)GYy_|O{=bgfF
ztnbf1ynSZ1|IJQ<uT{MyKjGJ2{<oEY22dr0^nPCnD2$cP-@pD)`Lw@xK4zvz`F4%{
ztAAeWpZ@D#{_^9_jF#EqGVA-kxz9h=?3du`Z%s{Jh_82)1WNpo7x*`yS9^NFXZv|z
zeLt2!%zty<SZ&mPzx}9g41NIqp7m~jvf1`smNzi{Z!e~Q`FxMHn*RRr-Mi^8qwD*(
z*959e=v-BrQo`R>tLU(|7HP7+tpv>DTWj-U{B1RSb2R;L0NUR({U2l2#~g^&@ZXsJ
zpPzgJq~6g9G4<`}db#M{YMnm2@2Vx8($}R-!S7Uq4f$5n<;u6!_QXDft9Jg~Uwf_o
zbfW*p>TmzZ>L0+<zhe`?{@bzDo$*_1wBKLKJORD6bR_z&+O;6DlwrV}{bectW;LXq
z)eE5D?^9(TdG{WX22A_gJK#tA`4?bd#e7F6n#^xUhp^<gn&Ondt!C$!OPPY-sg}pi
zw-QdF-&M)np!3W3pMt-42YmGJC3egV;J-Ef|HuwNZeI<qlbi9|(ILI#TWj|}u#}lH
z<*lZWgm0^XROhWGmYr{__0FY*SJ3;HrS*63fPN{W{`N=c$3LJ0aIVwfbk6&3Y`E)H
zCEfjgS1IqoRAsl{SM=jodVc(YZ=-FjCwzAHyPW>+RsY$Y{u_(_A2NE*FIVsR18et-
z9Y{g{?n4C{;kTLubXol!Gjeap=ensc*1hceEkop|rX(GkZ#Pl=c5J5{>2D<ozOB}Q
z(R=H?lJ6^m73)hyNxrWL3XCrmCHaZh(C>}X{(KG2_wV5+-U2f5e(k9w-wzRf+AkF)
z`MzSN6Z%pO<!>t`wcamY{VVyt;%L8m_pjt9-b4|}{qBzVIn8K@iTu)6NxmQC{^b$z
zuRmVN_Z7>f{G}cR-&ZS;{nvVud|UCl=f5_`@=v^p>lfcK)|ubEiJvkN8B+bFpOSn(
zJP@ROsVK?!6+xf=rJ^L?S44=>mx_{nU-85*-@F7r^DeF{wv3f;-^I_VPFxLrQG}9w
zJH%O}fWPphQ1X36q&E7hdMWw7Vx=JXT2YekE5`U*DN8@`9`c6n_xHq48I52Q`O-^C
zz8%`CfP}Z61m9O1<5zF}m3&_j6ail<O7eY0AacG`l;mejr;Fs;zq==X&URYx(|_r!
zB)_w?e`$yQ(#HJDk6%CdH$QawDtdoEAL&z*;O{eUJ~LJBuAUjIe#7B1f96xpjv|8e
ze#-OWMv~tfq2+DXmwJZlt?#Q<RK=HS472#QS}Qv9w^}2=`S;c6;lx{LUp<_E|4V2$
z#Pc^SoAD34goe=UFT>mCdwq(EARqWrQORe%uL$;xFBL^F_<hAnJO8z!#UE<1*CpNi
zF8cZjga6CRxGDF3<7L=C@-jf<^ksyte|OAA#RH0e)jP_>@NG3DA$hC${3ERaX!}+Z
z^7h+mASdBlVEHFs!nxr1-?{|(`FC&-iv12wvDx1a4rvhIYRZfFZ8dONz15Ts;Ja!8
z1~yfr;CHIY4P0*^e#Q%Yqd3c~jQ`GFVD=Jpn(yG0ZRp#<t?{MG8o&4RjAD8#jPuR)
zC#u-~Qo;7`{Tz;B%=H&P@!vnwH#qaZqqh+~^uvoW42pv92j)@8@3&g4FUW-7tmge!
zt$F_=t%2?Kt+wKiv<56P=bz=Dd;@;tjeg?|`~zQnAG}WE;KsMtX{^?rgG06MUq<(v
z)sVvEt)`qN-&Na4r>$yR`L(~T1|TTk0Lwr52KGhp{l?ekA25LS9={sg{`Mk{)xc-=
zRujS5x7B`a^6o!m@otd$z13{|fuq1~hpp8cXy;2~fBze}5X|4$1OL!D;EQL5l5Y=8
zz;b@6_)31_RCuw}bwKa^zq8k>BOULTu6_~yjxYBYQ-k8qII3@u(8jIRx1OM%`H&fS
z6TWoyi|BVfq`z7KUqnCS2)+q1|IkQ(YPkZ@`*pp(qVFAhtIiu=tG=S2aqiuqpZ-Ti
zx_`#6RFtz{yZc4-JHCwl3!lSZf4q{Pah_f3$3HaA_$mKcfnLA%_7(k(D=dD!7`}*p
z>Q-<5X^r3i3jK_^M+ef^&c34G@t*%$ll<zV{g)sA&C~zLxO2?^az}sf;cKjM5#sf-
ze?9E~?~eM*HT?e535z~HwJ$1GO6i~eUro<<u+)3o{r~)?UI`?KOto?s!xg0K2JruI
zLfjBE9$u%1sNaH}2(bNd`cr_>4<~XN@cVE=(t!dFCv!*i%#aYyU;*4Dgjb+o6hthX
z5hKNB7ES;=aQIOPIG>W#pcr2O;CVRX1_2@u#f%q#Ih?jiAj#8}pj!oX4ll$YSOLNr
zLlzbJ6$~g(An7fEXF1C85Y8YJps2&i+!QMdXl`L@D_j*U2H~Q4!-*uA`xMLv;f#bX
z#<Xx^PQaKJ@_-cT`$<WiKBJ&k;Ur=U$K*3=tr+5O88sY}FE*!eOg<cz;nfY2A0T^U
zIO7{ZCK1l?mk9QY>4d;QaRq2La&j3R55oB?s5S#rt7J$K7+E%OFe;*W;?$@ZOABhY
zP)1xbYlJhH4ha8nQYat;=M~i14N(DCpehGd&@0fieI!-5o!EqDfUzw$18+`6u7vXc
z9welQ%`jYqFNBf?pDNVH8uTTR8HP^<W5y;q!$C5uAQQkbcq>Q=a_XEfVgL~5e*{&i
z?mBrv;jy`rdfv=`qhk|&VVDVkKvz(oj#I%mu@wSzUiS$eSp8wN->Cy|Y=)&E&?Gj|
zatDc;Vl(0aSdQ4t7jo%pK1GHI0>>5`G`FXAYcLW#CHY!+?Nmg-gc4Doje!xgTJ-(F
zY}N<ki_MLR+@S#s>G40+&(T3gkH}R3cK_JQ=W-lfB7*4zI#r>ECu*rN^7I7W9l?kP
z3>{a3Rs)_YZd;@Wh)oWYbI@x>up?c-6=WnO7==P)2$?VR7SZUzz?8ziL0!FR%Uff|
z5IfRy<jQT`ppmvRpdyn%004H&wX7PySRLd@SHx%58&ay(R(_mV<gx0A@d_que^PX3
zbsaSg&9s!>7X*1ha)m3%SzJd=jnC-Bwa}53G*)PcP-aV+!$GMROZmo&B`P0;;_aBL
z8xsK1KrO%BAdaphn&3*%v8sSjr;cd3kEs5LE+{8@gEm@Qoq|4EN~GRaY5KL*>O#l4
zKRZJCJ`$92#fZk?N>-LZbksrMcSUTbba*Uf^+oc85VJ!^oMEgtVQ?!wwUqG|lwh%x
zg}y;kt*Pz?x;sge-a$9^5#a~-p-Os<kjN{ke8FHa3(-Y%rmejqHVlO&28muofw7nx
zsw0nWxrIA;17nHnv?G4=iqP`GD_0Kp-m-*7K`nSCXtaZMIAs1`(aJJX8G{}!l-!{s
z?QJmULa!9Ju{xu3JJP0x4D}AKx)5<iM>5q=s(=p0!YC?>JN3Ov91XM`(!AVqEn1~Z
z2CZI*nZH+7+$TkBxRjo9*>n*01<5cvvgF3p#xL5#VD6m`<a^A}LuQpQu~3HM`oEIw
zEZ8z`IromJ_B-N|Lsa`6+=n4v{f;<^5X%2b>J@@hqbH-{Epbku??kcDL6R8a!~dM#
zKBZ0Sl25Uw5iIo`IYvU9^u4ebK}!0bT!;Y@_}&q;7$So2@UH~<H+nCPHK&FKl{Ke^
zRxz$u0(Pm6xbqN2dq=|9AVo(<uzHA&{Yq-mkd(7Txu>W0aZlAH`t^<kxWUA19ij6f
z;`E+`ig%Q`L+!T7Wa>zf5+XM5AWn>FDAf$pVC~j9XS7*6NB}}q=2vo14Z{byVu%K$
z7oX}AO3>HAwiuItuUTzs8ahn50Xz5#Vk&`Bw~<ABO2E4qNgUEE<859@@sV}<QvSov
z9J?VB@@_a^jiZj%u_eYqsjj&~PlZk!fgF7OE};>6B6OP4M0QX)hEhp(Fy@9x%e%qw
zi@{=cowpMm<Pt&7^6L%F6(-Jd`bVz>Njf?>A!8^@d~yQcGTVis8%it>;)@tCho5dZ
zu8pmx93$EqqhmzcokemSN-WxoYw`|pX;e^sV{uf_d}FC8C_dylz2%i9I14)XKVr}j
z?qG5bB~<N*Vhkl+?VyCd5`5+>!A*#Kr6Z~(#zf1|ej;PJl3E;7O@k&Z2JPxTKI(7K
zsP4e)hDgaf__afH;(g%!HpJs}McFx1Ehx7^v-nD?dv#yhk<#~;t8-5uDAvp(?Qn=q
z{7UMzb~OWCCjOT`sLPO4xZ|2uX@`4tJ0<lULOz}tT}_uJ8|@t+ualux2XxyYheSt8
z-4H2w*Yz?s_>-dB8Ix&@Hy#R6>R1(FG?qcf6QY*6lKV+D?RoH!hF~)tZ2DoLmUfod
zN<k$f3Bn&pa&k@PG<MHNf>Mpf)oSTCb2W-wm_fFh4sN1QD(*gTCQ}CQUa1noWDO4}
zxg!65AmUAZm9k;k#{>G!mbwB3CyJY1xoV#j;iCY?rm&@^Q^DC%Z*e%oXzJC5O|si`
z<fRSeI`2q9k&>Fn%2II!Xcs!<Mub<X_M}PA&Yq?E=0IzO$uQ2G&7rHpj>H~Osoo!m
zs;dK~>LuwRI+DR&30kRRoXE(pAWw=RHu8=<CRf6ip%smrxFgl;mEd#n(fnb`PSU}q
zdPQg%Cp+tE8j4eNJ{`<qSCT9~CCWu0>lp;AVX~FW+zD%JX<}i?TBg+$hJ8Kj_v|`!
zWtSO@96dospex9}_CpSe4nno)htDja2#I4lG7LpO>N~WhNQ9ma?zZT%o?%&rc+h*=
zp0|vTAJQsa$wE1OBO&6Uj{Hqm!nPfQl#vah*61>_C%nwjWgr7=pAt-Fs=mI}J7_*}
z6m{7CS5hAx1Z;<>(mUAnqSI<Fj@A%$dPn}xAg|GrqFk7LscopfzSQ=?q(f2TtaHow
z5G^ox2icH14oz2p#`9Peo!;e+)M{6PmXXym`g_Pma;gxQdIx`DC^)!hGxRU>rs+!9
zIje(XblTcDvqqP#jWg}NKdDl6#NIYA+xB)1y04p>F5TBnEyKmxX}2$UILXWOq^QPY
z_(6UHx(xR<vxHA1JPFZdp)b(JMVE;VhRWzoJ%b_?_j-r><4WFI<s9zh_U>?_d?Z==
zsKF)^9Nd{9nx_t@OiIer*+IE^MQj(kP;Bj2a`$+XnZAl{CR$ZM7Wrt>*{gQamDHDH
zL05{)y(dNOEwfoTI9q*Z;P?u$xc6eCjYcCJh^i35R4?w?E2xe?S5h6-&R)=+f-GK1
z^>wQysLr<8RG#{8nJqzeiXgtjX&6nL9gf8il~vy$3X3MYy!?~VWR-9DM;onju+~PC
zRlcENNj854xd<Bl(|uP3w%aj6+2on+JlbR%JbE@6;7BzV4F>ow6)LX!E2xgjyx!2D
zO-}18s;&+_7b>(3Ja^>3*>C92Hq>`;PDPW6zM(-I{ni}-jA$~^cPY>&3mvZY=ZdP~
zi3MhAyfkW)y5CT#BLC`0aTcxX2(+Oz8!hg-R){7CHZC5ngq?v#Y}o!!is~K7<_3Li
zG`g^pJ@yvanNmG|<iW0dX-|sSxMv9;08qnT37+WyRmxdiS33YzK9FRD_R;p<ftF=X
z?^1q_uIJ<Z$UD73DR@Ogzqx<B5_IKM!?LFLLA&Xo_EKqnw(L{nTJs|hHON?9ISYD{
zvHFogUSzB#fs^0s5cm=059*-gM+Ug}8jb94+#$NsAaqCe6+g1S!HnwSLF<{P&5ulH
zH*{rwsS~I}M=I`A{V@Md$F-{`cUrGISwGUX;7Prb+T3-q`=o>|6FDoZ8*Hh5WOw__
z5*w}NuLL*p9VzSm(8_iKbY*52hq@mb*&sl5+*Ic5FT7W6J70LMva*p?&W~KsAUgHa
z=_mn{sUO+ZzO#hg4a(9hVLKadNFHh5rK$bM%mzp4m0*;+#w0Tve54Lqsg87Yx6E$@
zKnhpHwjB#q=J;h7{ox^F9MqytR=MX&a&?59(m+F8Ni|(AEe~1aAo+A<g(!B6rzCjO
z^*0Zh+Q52vz|>Bph$}?|<FmaosXY)?=j5pdZKj7j)kTz<l7;eJyFpL&(*b6=B1{y}
zEFQANfoJg`iA)Ee<w^pIAAFQo#K!BrU&%swpb|a}fTdhuIO|wC5UvCp9mo`q^`%yI
zkal&9PeB$lconaNW+|X6SH!2*KD-h>b>O{CJr(mii9YF|`g7&3==h_Dz6Mp_LtgFb
zM@p=gRZPsDOzp@T^{-s)LF+gcmWsUEfS`ON4~qBq@>e4Vh>LLPN~$>-!{J%t1HI1q
z7aUc^nk+f113E0^tPUtK<-X{JP`LtnV+(<DMJVOVcNxpM)LqFiIyQs5yw!;)d9DPd
z?1fNJS5grJw0Udiy2qC%6xE3`Id|-TSF((bZ-l$t(+5h;wg2){<1Sc62U5kI#xam8
zSAfO=RdMhdUkNmwzxHwgR$QQ}UU-y`gr+dyDDJX_PnGyk;B#Cks*a3<SHh>JCUjZB
zNYmpkGx$Ig`l6#BxqYsL4MPzEPt}Vq)Ro+$1Ha-<OZe#ku(<Ml^uxFgxu>B^of$y-
zN7K3>R=qUwlOp`NmZ-}&4UO(D-}GTPiR|Y>y0{NHkAQV?LA5U9QjJjNGmH>-S;MeX
z++T<F$B=QCDSV*#T(&T5A9t9-2RhEBf)mg3lmwFvEvN984oHhDSIL!hgvhWZFCFL(
zhjjv9Tp+9t<cmA4XVBKV%U_+XHeK9-@y%V<^a;$iwm)DhzGVgjsNz6gJtbNxcq?UB
zw!GD_qJ6_!HrU?2>8-X_H-Ik4mBE0&lKPYwtbE^eS6|6}_nRJTL+-}siqI4k*rthX
zNayG~P^tmB8tyqBr=Bq&T%6fj4CfdZK+Awt@x9fPQKeQLh11pdRuyQkOy_b-Irri;
zG#vF@30|y0b?wEw#49?eHZhS<U3;nRQeAtg<%yYHD3w{er<#UtBMi#`fw_W>NnBZC
zqYJ&CcSRVE*e)2B;q2~vs8<`E80yx>>#Z&Ml&CslUmjFFF?P+fz;4wW@onmw*Ac+C
zsc9%ap{oq84_D$DEANQ!u7;f}tFz_6%Iazzx>4C_42TyOO3M=U;^j$rAgEW^_}qgr
zG(GoVsgz}G6}j%askf&-ey;R229okCsmFHcLt(J2Lm#fPdMyDfz64=5AXa?Q1#LjA
z_@WE?O0xSa)H2lJQi2mJT#G9yj=`ySB@5+z_ezsva0FfnbdJGO=t`V(>Gx`o^g$aE
zMEY_)2pW*^Elc0%ohw?o1_$buuzyf*YyXLLsyEu-aLQgu-HlnFS;AKaxD{VZU4wdC
zOYK6vt)+HnITT%(ErZkeO4#(olrN45>TNBxzG}iJb(z6~eMM{?N592`wRPw-W$ZEF
zS9~c|gB4)K*H8zc(biB0q0!c02cgj5Nd8z_hLi=Kpe#$&i!VB%4Ji(MnfeBOwoL6t
zmVi{Wjx*abHVOqNMAntmXbhzaG3{y<M>-`AGF-J>3C9MNxM+4?Nxh)<rB+V63vp$Y
zGSn3$VaO+OCFmV4oIVniGH_K%at&8jPH>eWspu836{t4l9x~j8Ip}hp64is*Zdn<w
z3OO3#u?$cdpTTyKV9RHy;hgj<V7oZYDTR>%8{>j$S=~f_KB?jYxT5N=>p>%X>zX&H
zMS-xcq<ZXhsa#QYd20|*i*s`jr4{E^)6j~@WO&yoP&6*Imf;51l{3kJr17~mtozud
zh8HydTx_{Cvn!>N;j-C*`ZA=a_PNw<oge3t+5nd3irDVP5U1MSHAbp&T&FvMVNZ%`
zh!ahF{+o}4I-OGF0L}QMZEXgmj*Ao0keTL6@X+f0&~V@hokP<IWjd7v*Z`w(WqUHf
zXs(2fr#79YmT}sghL)j&u7GXVBkLPsrAcT16N}X^ZTA5+I#Yu^CAl@|l{TaZa;1kd
zWR~|yJK6w`@u_4Y1{{e`c%`k7CO+wwHlSmC&@F91$M`sE9AOSFeApEQs<HL5b9~VJ
zMxLZAU|V^R9P(8gAUQ6`n1Qw2hYaZfB{^!;AN4m}ZSrt8TvG}CH>ijKhH(M847erF
z+*G%e^El+GzM`DSu{B)izOmJG>AoRVjg-6&@XAx73b^0+LGIxp<NG7`A;TLu7#E=H
zO3L6GGMWKC^TFLVp!9}}X3T{T8P1rn#|LrKhU8s7re+1IFSBLYxDU{N1o-YsZmUm9
zYMO_dh1wfK%|i7Jnd60)xdOo24R9G3q{{|W-=OUcXp9fp-wBQJA?tep@Zdw%Hx{o8
z(q&lkK4feovD%eXOS5$2b0v86ECngZ))iETyB-V$Ip~-+q{r~l=q<RS8U*d{{21IK
z#suJu1Jz|f&D=6u?$Gz6sc9S$hivrv=D5j1pKyU1^*N9;ZbFF|pfgv*pX5@oqqghy
zTnU@5kE(+h^{xqgd0pr*%TKc#eb<JMw<{5u;S28u6TMKtPYT#l=}>{e4A>c0sxq5U
zq2_9-ROoX>YzjKm98InKH%C|pS0`S~0IzX#=?VaBTnWz%+Vx7<aOqH!kq-h`w=(jd
z%N*WO2cM3K<EF_%pPnUrYXFP664u~((`cQ~(takxdqVpO4rZ{4Tv^i$z!@*A<bkMO
z;^c!<`PtO$2NsLW_ZjFu{n(!|)(_Y)ysxBCGuV<>z^9gqOpKT%vc=7K<^i(Bm3Pg6
zZ23sCR7%b0$2J(!F4WeQ)RD(zQCB>KTh~LO)2#lCQ=ie5eI+$pO->sm2X(=?EVCH9
z^0*m*E+0vj-~{bQ55+l=C@x#`7V2O1+6BA1l5DPretcW&vXIxrm$1u5#!<|BXy8z9
zT~;%WbS~VL)v51!NnZ>n!z)4CIN5dC)gWiP5;hK<*PU0Swssb=xdCYLPKz0M7Vk2d
z3(w+x>!DPOf@;}<TI{lz>mYsw91+xFm(jea7CVh*q{ek+r88t+c0jdk)f3n(^kRQ4
z<^{#rWibQ!;>u%Z$iwVHYFS}nt^j!*4W16~Fqz>Cxn(vEMXA(x1|-at0J>-Cb#bA+
z48WHw!KY@oEUo%CIxmZP*Ft_=&@L+%l6RTMNW<)11~SqxI|!)^kd|Af*9X2TCzQ()
z<Z_E_1`4s$g>3-2c&7{dG2~^wA~p?`*kNoJ62^t^G9Y2RcQ%ZS@2)(31|W>X?NpK)
zqbzbb5WUMHui(umMfeaQ!?KGN#{gt;!Mv=1EZ$^E1IY4tJL)tPT%&OfH>x-3+P$)b
z&kFpoSHf=<e6?4^hM>=yJlnf8(3PN_awA;<E;6sE##A++&6+&hyUv5nH9(yHnvC?l
zai9?R%ZPPRazP{5MW`(U*rn|+mC9Y(<nZ25a&4oOtE|b&hFjkS&@#CGy)EAJ8SV$X
z$-TYn2W$k+)3#8miItUJ;owh-oWCJG7Mm@NrwoTid`z1tRnK+fWW>5OIkOQA??PK$
zNll}C+1}BzA$;RXvSr!RNF?k^q-aPad?lCw+%`G!R!@qmi}Gg|W~Rx)CT6D5!X{*<
z$(zlKFmKY;gv>M<-GI$B+1!N0G@8>y#I#1Nq+Li%gEft-Jy$+Q%j>{fX4mV}yN@jA
zN(TItsPRX4>2KwqGLSv&1Jk+4Aoh{v3^2?-M=Annn0@5l_65>2?PlO(u7qvxEU{e#
zBwW#g;J&F_X3Mp2wh~PmZh^OeU{)8!`v@6wB{f8u(#Z9(k8EY6*4+eyncqLl1g^XA
zCq?XTpm*?eBhTO#(#vq~zDay*buqsyn*V_$6Nwx-yMcV!N6u~#p=@QpF{G#6=e^HL
zfXr4}OanmXO3?Pf?90_1?NcJu+M;oU(%{Gty9FRKfLivE@&%}63;uN_E6eN}5})oP
zH+Ph_+f1){1@(rckpYGINKm>K<v#Lr0|s*??3-b><>xNy;45Ie^#ytM(Ki4&Mn4ji
zYGUQt&cvVl$ghozo%{56d;_D=ZU?UB68^E;6a^qY60x$xZY<8eyxL%A`AAUuR0!GF
zfCz1ZvogWv{dovkeMLE|A*XhfX1fwLoNMz6*laD|j|8P0<`#U*0I0bVv|LBME8y5X
zOKh|h;*Mbai~&Kj1?V#TYlrOYi0YZtX#{#!miAMkg<9`(s&{f=N1%H&$D{ttz8=hc
zNGD@<t^{8P%-~i|Qv=p!hm7%h6VDDA<3QW&pe+up%@)4PfVJ5HTO3H6Tc%Z+P@5}2
z%K+BwknIg%%@*d1`DAyz{_4{)C>Y;`TihX+HK2`KU@imvafe*i1(AGG#1R;J40}6~
zH9O?72C`;{>~A1zcDx>IKx=l$V~sDt4w>ZjvDhJt9N&{GDK7+|H9O?82DD}qK6V9x
zI{46>nf--neQ?;^f{PixhntCItv;zcWH#fgyF+F(aJf4ayllYD>}Yy0^kLAEeRdYu
zv9kZR%Zq)GdwjdJH<Bf9!Nv?wnk&I)5L#@zOz(p@`|Y&7Pk|e^%duUGaJ$qufYaM$
zkfQ{T#tHOSM{odTJ`$8bXUcv-_bKs~mG$tH2m^%jbGf=<hkPU`<xKlluWBl;gvW#f
z-RCsKM{8NC4S!Q&*DP+7Y6j`l9%+(2DXCc=fXi%Q!3G$|w@=lAmLrO56qm~_!*Reg
z-`nZ39<X3P5|nbz=(QfOfv*J59GtSDo<ODf(D<O%oL=jZ!4J30W}((x=;{H4%ywf_
z6KllO(yRfQ8k$%mLRXIlT_|YRXtzq|Ll-*R_0WaR)|RX!>(4EY#UE5(`};)9G~Lx#
zQk`#_IgqAZ5t=U5Cm7cNvSxex6Ms-$Z)zI4&l@e@0bI@YrnW!YZy&W=3wH|%Hh`kJ
zl7(_=>?>e9c`DpWDKG${xe~Tg2JaRUY}5gFZ=pv94#9heh6shZ18qY&?odmoN_ZL6
zj@#7?wBvRSsI+5m$F!bGJzf!tm&~#q1*(oh-juA~2Y@#z!CC<HCPi3cz}}>Y+bHoj
zDM9maV5A81)ywDk5ot;E&VIM|QJo#<jl>mI=k<nrN8bgO9{|*(sPLkrJVPa7=Pf%b
zbo_vSDMf6qG+v6h7dx^qHkn}q&Z`t*{!&4vfYVnRGDYZ9smPSD3!{b?S_1I3eMGL-
zCSF9L>mSI_Dc8g-c8b>tqX0E2!EynhCPlce8GzKJY(Y@3OD5Oo8$}GR^kb&@K&0vb
z4ku-7ZP%33<Qj;VP0@lNSSjbE9)z*s{4@}Vn-ccGF|?_{mV+oos~+SW2a)vyuI-O#
zs84}+Ky1)}gFHpJ#~8rWqzs)pd@VzrI-FfouMQ{I-j{dSQy!oO9QY|hFRWD&J-5aw
zH(csp5oVkg)xbr;M?^R0z+FO$pdAaQlM<-u0T52gYJ33Uqy$?Vpqh`Ush7rXiGFP$
zh`wZvKbx${hZ+0TP|QBzto)Ry-h(WxVFRy0Ce{^I&s|#`fSeTZ<C2h^l(7AQwdkx<
zD^WJqz?D>rKyxv0aaA(R`K+brq4p<Uum_6ua-B}iXV~IEaQ|^7tIC|S#SXgqyx2)c
zF>T3DnMbYxKuwD9;En!m^>|~QzGj%=u$eM;U~?E-9oQTS&tAj)7MI#b1V_ry0mpiH
zEjEzWq=-FmtOsA}06usr!<PuOA0N?F&0s%ynK2AS_VK7wGUx2DSG4Dhx>Sh!D?+F0
zh&8NKObXN%mnn}~V^Ez6sXqqQsneA@24ciY*7&nk0`y=s4z7+`SAbW*qt+O`inNPH
z$EI{s^PQvBhhb1{zQ!Ej4JE4c;TWYiy{U`To3HgYs5fc84Ju7n9NZYxnvO%)7|@!|
zgVzAsBQrX&o8VV(WySGP`LWnXJwR&ZM$2wckqXg21{LW(I5-V33RMOvbYbRrU)v6d
zo)ob)s^1+vWDX#2J~A0+gNk(X@?wl#MSQ#l73p?;K0)M^GR#xy(e3IZ_2_mK(Zj6|
z%%B$CTWwQ~Dm%>>P@@U~7=Zhv2zmy1pA_LcFsN)Z5MT^yT15hkOgg17fKdRSr(|p@
z__DR*2UV|d{R4Qf6!Bs8{!+w&Q1uGmKL%Cro_ahr@7AGj0IPasw>+=fRYHw1sdhKv
z2V+w0ZXNq3)ow+nKagSF>f|?}cNIP`0ROq7EOsthlNOxR%#0owlbTr}1S8=;DZt=?
z_el{ve`8ji`X`6Q%atp_uy`n#P|3S%0HB{t8HYfXyk+lCs^l$ue^MngV&F>Z9X1Vu
z8hJMjgIamZl$g}YTc-q~d{V|fKr1V_U;yWnB6MM5g{-4KOnl!FUod8=<wZ+>QY$Mi
z;EJk~2n-k#8h44o{EE=H?E1Ocx;_|_8h5!KPK|rv1@$Pe5<dPw^Q4ILL4~_?I+#?r
zOFWMQERrc>2ON`&7=lbZo2z(jH5eG(mcp6A(dmc)sCK5<V?}CQ#sG|ov+0`pv`=c&
z#hAOXs7+V-PsgGzT{7%fV-F_3?W=Kq2{syw%2dGuSA_Ycr*%}Np###QI#u|<6=6Dg
z99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_t_UwihW(<3g)&`Krh@$skjbWq-K08ID8N`$
zr-^dnv#Ouk(~H^^kD)GI1TS3?UO{6_-B?tnOUHv%%5*g~KRGmQ=tX6kF$9%)BzriI
zTEjth>L9RqkexaRES_WM(MNbu11oZ1tc}6o{Zre{(6dY3GEm@2N%dN>0%K9<&d@-p
zauq)?7FBND1dIiJJ6%JgzMVV>EUH^Y7>q@AJN+FRb*{n;#=>*hcwpU5N3qt20u07N
zEON@wI#0+7G8hXd<f+pF=&V!3whzC-Q&vK;VyA>FiE3K024hi8GuB}2RwW+YHg)jS
zDPU6vE0SPr>R^Quj7=4cuX>4UECf!BO%;r2g0ZQDr;ZbwI(SZf^ES1xA`iwcEv&$U
zE5Li>8Dn?8wfFn7c@myF8f>Uu1r3bN!?5B8#-`?-AY>oA4!Kii|E5ZvGW$1G>g;+p
zRqE_-r+Cmsn8Daks8i11O@%sjfY{2I`W_%EAoC+?>cZl5;<x~A{S@%wrFRi&@Yy;W
zN)>4j$EHRdGVnJwDuV{bzPfUR2CBp9koMk=wg-VsSF}pN2UAmy(1Uq2RcOK3RGvc)
z+fDU3wBa|@=g^s815}kVJU*~YhHU;_Pp*H~jE>EpQ)vznOAe>j%y5BGhptaa7P?bq
zDrR6fRpzK~=~J>=!$XF<Q)dnt?v7g6`A(HN7K*U`6?!n7Ds;%Mck0j~yWXKg6@4&x
z&b=~}@&07AdmUMaOm?S2ReZs4D%A0s>^`c@F%1qv_PSHYj)5Y^U}}5RjY7(5&pY(1
zA`XUAzbfcpICZRo4u(&SRL*^;jva<#K3P`0Q@=6_VK|SkqZ6GloGMq53B##%hpc^v
z)*Z47oLaYn6CTL0K4{s)8I%$Zm`ZoZv<D$Xis&Nn(!7d47*55j2!!EOybM7YPQ7dA
z9U&Djf)K7C2csZ_;nci}LKsffYp?&`se4WSf2Zm-o(epwgl~#d^CAx68BXPEa{fDy
zzlu#5$eENP&OmUuuKOFO`c;6!aGq>UCco3CtoVWvt%@|ZgPK+G1tX|g5nylywJA-v
z0Rbgy0#jX4y>nY?jC#~`ArRD~3QZV6HEJNV8{m&g38pHjM;V_mf_l_+B@kJh<cb(U
zpR+-+2lcG!*bqFanymleNwoqF9>`Wn@L3A#RU2O(g%`ymK~RO-djN>Z>D3n_Ci|%a
zKq!B>t^)#E)D%2CfI>+bTBKLmbZ`jjT4NET>+&!}san%X0=GIT!h`8mR(Qh*9!%}^
z{NpyNWSCB8`||t;HEsqmj3{l(7=|Y$HM?E*KA5Fa#2KNw?Q;AF)op(r{{em5bpi;U
zRy!-zdh7E12R+J2IPjFL#;fp%5%>vPr~kMIiuDq^bbru$%&3Pe!60PpA86_>yZ%s9
zciHx*(O=&kW%O9a{h^j-FvK{$N^FQqx^Jn#LqBnsWq+us6%8>C6}93a#(|=)cnChL
z)+YlZ#^G645fS6i<=k}>aH!F{kXYlCO7A)W9IA9hMhqYnKO&s~4plfg3QC3{;=6F5
zpB3jY4)t@FDSxP+^Un5x2wm5G!J&Fa2*fz0pu27h4i$7CI!YX>=&tL6Lk-<^COFj4
z3Y8cK8oI8sABeD4a9?m1-<9qQ&cc9&3prHTb(daGqRv*x#5mNwT^9eL@>RIQI8e0}
z-0(nzUg^%@P}g=G0uB{z*CF6g(e_4X1)svUsA-!n3=UPTq9jJ5no|Hs-Z<2>4fesI
zo>i2@I8?I?lNg7-Xe97?N|vKl=){#&H=7O~hlkuoFT+hwif#%mJsZ!k3V)aly0-Do
zU^c2+1whP3Rofi%G>efmB{fx7f^IpA=+ahORI|X^JSD4Fph$|@P-NruB{v*LW}_>a
zaTHI=Ftm-I)T(Stt>etA;ELIJz->HwJhM?_E0|(79$(v37bp9~bHf#(Q^J7FM%CMR
zA21tLZ^li`2DRIUx=F3u#yd&WyN&0I*{FBhP!Fhk+fdg_^^$3+Bv_aOMJ!8G2dJGJ
z4j8jhJ7ZR#lGXb+HP6#=GYyvhX2o1g5Fvj=!VAqtwa&ncD_K?MK&Y}6RB=V<x(*Ao
zQD-;a49rHI&ESjKps`!iWKv@{ar(_hwXGnG*{HT#Qzxjk6`C>I`Ed}IkrP#R!4;wT
za#LRcn=i$F5S1~3usRCMm<@N6=kP2s^ON-v;D~U`cML~C7ZY(^2Qe43*S|Sey`y8i
zF_@qbKMJOpfKi>}dT2-AyihQ+AXG=;783}nb6j1mw|@@L4ilQ;93CB>3H5Olm@&bu
zeiWB6i+(*N3*|r^Ha?y#vgLs>^4?%V<DRorWukYm{b%a!b984g5$AZ$R7XmqUJ1Sk
zKulc;zFPoHT}fSZUdcc$_GV#zd0#MLxm*dSVbuf=f<z_^rNbDDiOABU7>k+EsB=t@
z-57$ldB=_L6|s_I!mD(D-Zj2Jn_c4zG}<-3$VO?xPo!7)NKmRdYwAK^&KOHEJG{K-
zG&Ou`oj0|6u+Vu1m@wl{hEq%!`X|H^G(QJ{6SVawP6{Vz>Q5Xej?jD)yh0~vvrmJ^
z@q|=t9bb+>c~>w{i_fVEyb^R4$Dro~z4#MnrH>>__g~tR06?99ML&UlI^ZR}>jCJe
zqX3Hu@Y7L*#Vq{O30I?r5pq*L6HuqaaEb|_(@{vpOqkPAJjDdc=}OoTSh0@KebZ)^
zu=j0ZL`!3w7}8?96Wv#g;}vE9wQX&p|4Yr3mOQc4)WU$KKF2uppO|cG<%p(6xG<u!
z-Y2{ZC#G5kEb7Em)AfBh3b~ktiaIeg$c?oz*zm?6<*A?GcQ|3H<=H!0<P-c5N1+lE
zKAMA2iHW>Kx6G~tTBe;n0dhLg_1s$2C%T>+e2*Ouu0L}Upw>eA7=WjgH2&sxUb&#I
zAUAxJNj^uzv}tn#eRPyhe2$(a?9}oVJ}F`qXe|aj%yLa0WelHiUmn-a1vcqQfUmhC
zt6F?+VIz+Rp9_8D^vGXH&KeVkKPjpK$if~YOKiE!wd2mGmPvP%T6~T=0iFcm&BO~G
zW(l8Q13JRYP2h)4MmS7BhmIl~o(Z@4QHaBYU;X&fyh0KA((s{(1eePP<-{&Ey)d!W
zwT(%g8afn}Pqn=3$bFPUd?xzn2yQolEIJt`F>yh0Tn2JoVjP$IYywks6elrp`Ee8#
zF_CcZC@x}-Kz9d9d0ali&s|aOMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=&~vly
zla6;a4IPJAiYFzt__|t$*7L5`q4|__e9o37?9d78_ApLj0z`BLcq%x&j?$7(+^Zdh
zO3dQ@I&}l|K$87cY{W!X$+KzpBJt!=Hu8z=ln0QyXU;0H6=*(1N=!hAjv^(lB$w?D
zwTmovhgr#I!Hka3braX12Z0h32&1z@O+yjxpbupNV03n<?ST<WS0laW5khayiT?RJ
zRnTplrtd5&x+{2VRR?AG;u`ww&8dQB+p>JYi+47^6p1W4Tb3`7MQ1NHyl|@6OHJ1w
z&t7U8stxJNXMvB7V0IJN_E!Sm0Iv40gl+E{;#AX)0m-BWci{o%?kQ1qMz%2ELPu!1
zS!kgvz~=;5p)1J_J}Ig<MSB?(Ku5{RYXGv1=Rsdg&42**Y*Rz2-L`2S4(8X`O8JM5
z@{?al4XDi01@*UyoWGJB4PE6E@R!5%<r5H@Lx9|8cz_0-EiGEepd(P*1TN@oI>{%X
zKOYH7X*8^(o<RF8nav;>J<3i#fhf8Xd@G8qv>wE!N0!(u4rJ?~lpA`<$_Aq76ei>;
zNseyG$}T+7Su(N#7CI|X%8ei-+$7D=74aFRqppMxSy^JQp)-}z{7R~??^Z^}@UymB
zg3?^HpjWBPB?EdvWiBylP9TPkvYO8Yy}4vU14eX~%;-cBoh2iBZ4Q!FG$2H0Ej13+
zs#NC_0HPxl-7E;vS>gzq01TZq)t1+&XhUPFkCLHJ&=DU%>TWsLm+WJ}8_$w~jEwb%
zsm>=*KxfhYJ(2bPxuOL@c6O-uP@HRM=Aby&P}5MHZ?f}=b$<k#o1cAgmW*udo3mhK
zV`rU3pZAsI0O|6+f{iNJ{ToVh$%x)il8d{0-#*B#JvUU~YU&77Ad-|%Aaaioa1&^s
zvw(tsW`TXqYU&6S;G|D`0_t<-(fFYPm85)bL@OOZ;wC=BXVUZru=&iRwmxUS8EOY-
zzZvfsarhHHZf+<$Wh$Ql^c=z3W@@8b&YnCe$myPPT0^N_2|5Sero`kEfb)|8wz(05
zeWpCt8@g?7bq>01%3Zxnw@o>$cYO|?!~ErQL)!_ub|p2UjZ*IJDQ9&;gl?HOE^LaU
zoaYm8pflyD23gRVGPgk%bf&JSCZIoO%HW1MbtQZd^xu@*8fMu?g3?{=N^d?9C~=5G
zn+S<LQzkhgF3yy{8etjFnX=LgMRcZ&bbyFXCPAOT4;=y7CeTACjl2hv8lTK`uNrI>
z$3^8%pD>`0U~SU@WjRw8ITBG^NsZ9!yr|6RS5RG*z3tGL^L0==ROXa_+Hqi<w8=l`
zkuznF<GgZ|9DVxWGL=CNoY0l9X=u$Uw{)R|&X9!;kkE5QXc?YRB~hOsB02!YO~8ZB
zkd>YYp)*7mG;!8DLq>WwOKTj5$0LB;!~ydRnB&OGaz?xlsPC1MrcdB~Qi9os${g}k
zJCB;f@!-^$Lyl^If6kDj8rYvBRNMsi=M2HxCl2ao$X>6r{24OWkp|}s_^FX7=O~Bz
zGb=9d5Mnny&z8uAJ^|D@!o*E@GtQuwy4)R~w>Q-d=sqPnpYWR;;oT;1JXgX8BOvmM
z>dDda@0bB#c+QZEIvN&%%<}Z-objH>182rTiyKa%GvuMJK+rQ}f`gXh5bO5&s3Q~9
zQEKxmsl~!lPNKZjaGaeXFEyD+4wIJ8im*LGoy`ivy%Lma&g7;>eycOuJ3i>SAvbl*
zEU{JSxgiT2D4dT3rTV~_4DNDB9+SNdr{yv2Mg%$^r7xd|g?<i^Vl#IBoi(7~Otvx{
zwO7KPLC2Xmd?x(8#{#A7nRXutc#hF04IlC`+1G)D=Er1U1D114Ms^}|jxwB2;Bt;I
zW)m2kW1F9MKyZ%9qAmc=6|f<k0F@Vg0)le@F?&knRf|mp1|^F+pcjn>HDddZ@}NI6
zlj9vB$tKe09g|l&pb1T0X<%}W$(}yQ-Fl1`b%At_QlU@We;k0#CN4;B8BOCB<x2Q1
z##PG|q3v_4$mGUV&0)s$33$#incRiWc~ZomY}8@H9pjOOjVq;N+T5qKr722%g1YO9
z*c8;I!N|s4)lrJ{c}A5mCAif-CdW3gH^=1IMi$Cra%>}0<uUlR3!ZaKSyw0EIfwAH
z32@Faxwe7LIo8zl#CXbq_LOMjM|?~TNZ$#7XHJ)uUD%l;7}`7lJe@9&H;^-@)9lXs
z(4*|;6E~)(%cjPy>Xp#pjl0(?;&Y+dIz8T}w(1pd+|X=DaQ>92#vtSTly2*CdV|yN
zbeiIz{X0s5{>;3kK8ZG)g?Ty5WIlm-IbHTM052a2N;$Dz_VU7g{ONRYFI?Im0l^k-
z_D`n;y^?_Omf>4jNUQr1;m<XT^l)EEO(IS1)u8D*x9(~c33d8Z!|;XniBk1`=&4om
zYP6JGrY2tvP|qXW)@lO{8Y`57>!uDs!F5vypyayz)C+Kv!`$R4seaKeUhSjgdRN0x
za=o)*AYV@JY8q;<cQp<Fr}CAr!oVD1z80`8&*_a%hI6wwJva}5N@%`->Nx^;t+ulS
z%X<MUblOq>p$gk!E6{}Ps1+zeptzn@S-Wppt<<-o9rYf{upLbs4tp)sG*Z_cLAX{z
zUT%3${v=mkE3<e3?s8hFX(-1gFZBZ0<+M=Sr5zj3(hFFZ(_AeF2I-`8Ug-N#YV(Eh
z9pSxJ&dF(8kAdoIG=rZ7gxnP^{G@tJJ9q(UcZls;fVDKbtyc&9_cZ#g7lAE}ZtE+_
zx8LZtUf={ett{%*>-RtsFM?m%V!P#(xdJxab9_^+;smHP=Fb9h@dy~Uh)`)mU4s^D
zbXl*@PCjj@2DMlt)ccBRVGec<DoaVpSA89hP+N<*mS*|{64=sAZOxioQ%g`<&Dhe!
z)I!TXDXJkEeo({dYI$XegTraAb+v&@{3A5iB7lV{%2QI)uMJ%Yme#)1spZvZrY^Ai
zd_-CDA90R)RaRvvJ^2FOIfT1f9np?g#8yk0T?yMwWp)MlEP`V`@YLFAae`=*1*l9A
znzewGxdOI)H+7s)v*jVf*MTUQ5HxE6;u6QzuY+#Td|uYj6`Idil3#{6^iW?>^#va4
zmBvXNn$x$ubK+=EFIY4|j=~aEf9arJFpc7DHJ;W}oTa8~Nko}AcWD6~6KARQj&Vv!
z0~`|qY%Qx28#cbg$q^YwAPrn*XG-c9qq;WL*MY8yzIq`TBLu`+$PjTQ_{boI#Ff-@
zXa1Z0M7p0VVrM7T;84q@AVW~C1)D#Pso@;i6UWr>#LG7{yzuHxjV~-hQ`-w~-WXN0
zkh3FBSK}Mort3i)U4}8d@+|f#gRtdEN%f|we~$h%^v}^7TD}WVmpF}&P5yy6^inTC
zT_TP;S1K#wXl6>Sg|e2f%DeKU2;UYQb+3et*T#!DY`k{n6|nW(yb;R&v=E;a%5A=o
zOeTZ~yOQdm)GZ({SHkbZ$RS?|ItahPm7s(0D_lu+5HvkO{MM7ATzujAgZpdxtryb$
zM9^=&kP;|jtJSODqBwyc2x`K4ZoZQ0{LWJ8govePtVXib3ZjQXNzE5fGZEU+h=7cc
z%?waX2!*wZf#->s>dQc1=#yUXQGFyRWnW}O!^IWBfQkh-Sj12>6Vp1>xrtdFYPg=t
zM#1JBnZtYmNfSbBEg)$kXpRF&6Cr!Na5ND{blU=SCY1Vo0Xh?caV@wPBV=4x4zQHy
zL7qi+9ZFCjtt+Yic0Jb7-=-0Ov@(L`_b440vcBPojgY#Aw>Cod_kbD<5o-RsAOGgL
zi?)5Letzb*K6O7zt9i`vISc*UfBoY>|L8y3=fC>j|M1r*xHsC5zy1JCdgv0qBjrV8
z#>@`?PAC$#&pLO6DP3A$wI@PJ7`odJ7k;_do_jNW-#o^ZDi{pF9kJQI-ehRVt|7;<
zfwtjG-XYNWc)uMt(7^2@#svc`cx&$r95a#wkaT;D?|Di22BWhJM?hi<a2hD+$Qk@0
zN8Sj=)^_>PaiGnR1>v7JA-KdVrD^PPV*uWvl(-W)gOAcVPDe_eFZTlU_w@a%6Hfc0
zUu%aSt)96)TVj4z%^b%*r~l6qZT;;2?cynN{x9o?-tTw)(9V3<kkZ9ZY_G@=$9Mhk
zrlHmk&3mn%^WUtW;$wc7&zn&3%krrO^=0|gY-#!E5Q+8j6kT<_P%RjNtltGA8s#qw
zhJl@Hk+|Sx`_OuMgUG+G7r4FN^&)>@-$0-Wl!f&&f4NrP3u~;Ecb$Ck;6Gp2iT`q;
zytWM&3YT^*md|PKvsylDr0@HU`TS$e-hKa}#R3w_5EElS2Ya2!1Nzr_AdmVnK6ZgG
z4+$9Y*}mmkHc^h0D?okdSLZ4~YJ@AOMF6_a5FI1vJi~bk2jyot58+|x<*xAOkJ<|7
z@f&I_oMt?<UWk4XiZPsr?*RY6m7vK~)whfm2gX$=Z$P3$-&3Hb!-*FIvO1hc?}T25
z^W+Wg`*0q-qyCytUl@T>!XdZ9l^A}J-J=-~*m;PA5y<oa1!I7A>XvH-B3D2-j^oK=
z8_t`ofL?Z5@SwvDm$Ms`xgpxcaJ*_NvifL*^JETFFdRFyjKwDfXts2+_!hDBub{Sh
z1o}m%H4N8};QDyV_6_F|9M*B@s}2J?NT-MZid!zd$pDLw<WoBBGfW=8k?P_K>Z^!g
zjVq|;PJLZM^oezNcuLanlT$yr1)MK8@4o6h5}UR+0#j1ZGDZ!Q)v@WAMrx4Q*peqr
zv|B`jWyHnik@|o#J(33z$G8v+BC-_3#)k<>3S#px4W$r(kvu8M?YL=UpP2=;H__u=
zh3YL8(ZNx1FBr5q;9ddRn>8Ss+6TwNO~f{i&9QkIRT}Y0m5685zJ7Hi^4G-1hC(b=
zh~x0!gt%vpu#SfUWWx0j#AE(|dm_YJh(NIrZQ+4;G?KM2Bh5nKOoXC^u$hQfdyT?_
zLm}A;uPQ>9$$fI777xws6L^zWg?f$LNhk0c#b;dJo|4q8;V8K2=SI$@*i^(w%M>Ii
z{AkSjx(lUwCDjY=unq@VBuev^vLE6cyprt4A~SivO^9x=w{mla5SkrMxDY_IBa>AK
zq}dzbFR^H=^@_}l6>1qrLlPHucnm{0&0bE$APHDWa)65}vm-fJ2$|Utym}=I<!o7D
zO1(kB2zL3gT59$QyS##2Qj2QvO7bHP;=x<KlP}uAE7+(~y09ZbS_pI5+wF+#LL^vA
zNqy&g!{Ki&w1Tsr;FVY6^%S-OeYDm)Kxm{z4cOsjk2O^dDn;ajy_E_P&tPwe@CyMb
zdxLuu_{m<$2yPMfFp?1jc?Uag5@IQ%OK&*XEmQa4;1qna=dDEuK-qDx5dabY<w;SE
zz}VEm3Nj6;bkyo<2uf;oHFTgDMO1ig`g$)^d>xlU*UHC(k`y4sH`u`&5K9=3j@*eM
zw!vQ<7I1ukRwCH4SDHp0C!Um4m$j)oyq?KN*!!ot5S1ObZ!xuDc|{jfI~MnNA=1H)
zyS`AB`&MUYbWm(F-qF>;BBr)$<roN25MDv<2s8oBB@AZo^T}duxn8;_p_CmA86hgb
z4jPRh5n#_0r7@L${0j0F2qbwW`3A)A*FOio5Vc>&b#Rc`ulLQlS{l{HTrCZ2W3HCw
zvs9Mo|2h)BJ~1bs40ok?{jOwXx&96fBW}K4m*`OpvkxS>5~j9eho+fBPpKK_S*jyf
zKp-L|7Zg;@9GaCncgNI*><8V|hP;4+EVF6k)4rkwK~1))ZMZHck6GOsMyVZY<;!HU
z?~>FQ3SQBXkT}Ha*R5x%HVkqe$0YxEx6Yo?56}VUxDxCWKt8SnTM@XBnB0oRS`@SC
z!(~uEgC6A${-YR2t>XYSXt{PUDaAO1PIMbtWXsTDWCgr}RAJ+2nsAI72c^=lLp!t(
zI9I?{p~1)q*a7s3!LZ?u#MmE6b?Vl4O%RmRaCH+0qv3LOKwAyhBNuz-C}yv=x(Q`9
zw)zQOHE8p`4ivHeTv7FXfAO-^gV`_+QLonpIm%;Tb3YwCV==V34aX?JCOe>Ix6HK$
z@8;0nHhMP)6>cvaTa2l;p#=xGKlsu@(8>-{wJRyZ3&d+NrrJ&&IHa<{-xg!4VVuZ_
zt^Dk6!>MZwRl~VU(8)epx;U|7!TcXXdz*}RF|fCj_5YU8vjJ^4sCox<oq(2CQj`7e
z>;Yvrq<jlg8KbLZD7%5p4`gP%-kd9{;qVJEaKSgEuE#A&RfDiFhCT;_SAK$D_98=!
z!Oag?X^f_amU=Vo^nue`&F=$IcGskj!SQ${*hZj%yb?4uv%qF}>1Uw<;2<a1W(V73
zn6~@CQO-gw<I>MUEkmgqKM7dDVfrLsnTN5IOVV`r)N`j?0o#SrHGMch;CUr%cUKA1
zwmCq3HL$He5|r+%u&pQJ1So`NA2<S<Zj?J*pJDnW0I2<upmZO)G=(?@+R{+qR}Itm
z0Ys@Gz-9-VYM7LNePF|u+N}xy%=|*J-po|fbu~z=W>0YZbxPO2t6Q=I#$mSr=<21R
z!g&7eP-0;`0Cy<5ko)&aY9T6U>5A%286VuU@LqkS1~9sBJ7N{WOfC031qor<!Q&g&
z`An$Q@_o<Jsm7D>6;#)CG`^zhJ5kwJQhn!F;7Y3N{0PjE1rC33jdc{O-!j(`L=r~k
zkd8o;D`BgpQeXPO4&yA0UkO}}gt!BH(fUU+2X@5Kgus|rQZ6rX0`|GG#0iDk6&qlO
znHe3wu5R|%5-;mDMEloa;D(t0It<_|VLMQ=y|(^SqTDY%@PqqM8S4`Ymdt=xke_@J
z171mf>Z7|F#s#9d0y~KQBY~P76yhOPz&=yyU0CLmg=%zt`E#{Olf6R6LJ-U=$Q30j
zzCL-x6BS<vQG1AquY=b=I(H>l{X;m+4qE>w1jM|enlmZw46KVTrHvzF5RTb#s*FAu
zQq?PbFTlyy^MTxx3kSL`?YyARK%jTaWsrz2uj3pYLSA;9wL|F34u<~d(#CaWf3Ad0
zLB(~bV<Z@eE?ay-zX^PKCAl@b7`FTRXt*wYyr8_mtJe|q8A4w6iVKa-ZMML(7$nF`
zQT7DD%8skl5IbH6wSJHsudkg2bqa?+@#1yF&xSCS9YMAsRAomXZZzSbdpV7wNzcNs
z6peZozNct}L3iZBh$iBXj*J;0TxCxW)|YESB;5#6?OjQ})#hx8=oP^%ujnqWwlz$E
zSH!E=%Lf-?(Ccv1MH9HA!<82VT6SF4hLDz5QX|+X-DgVSE*==gpLa#MOxse!I5LV*
zuWuX~MW=TqxlEfhE&|s-5|nCbNa1eizDB@EhgUV4;u`y|D%jXy)Q>jREYK}t+PjkK
zKDYM9eVh36I->idNi)OC98H=Tj_7EFfb@+h_#lH`-y;k75W&$M;?C>vg-4TS-q3JO
zX}3CVfJ0<@SCTJYAB7DKM<Trrn*C^<Y*D@Z_|du=2T-QztFZ6i>8Hl!LFih(Z{$vh
zhEKpQ6($b6jynrK@>K6qVSZ$P?^0oY4*8Ed*eo1Gcs=PZTr_wcgcvRsypFpVKk`&>
ze?CQh6n5z=2MOLS=Qa9~3%YKD{DhwA=zQp7Q;Am-CBh$73x2dwGwat!ur<K?mN}v^
zo)WE`1$d#09mU08*Fm6iCACdKv+rWC>r7DVhj+3a)GU5@C)+bonjhZDcH~mK5<a#D
zBuMlX)rc0GE=}iWsp(!rlwaEGFy{bPb_W8*MT6IoFW5zK*ONZqg{$ni6?Ne%JIM3B
zF4P`~s&~R!-~tvug2d{{Y<u7hlsEfHNxcAV=;9H&5|nB^@w%z|%n}<#h=U(fBNHo3
zdl%URUF>-sv`VgAx4o#Bo)o>+Hmb323%#ko@6W$v0)qg`&+D;9YQ+>a{;2xa)b7Um
z*R4|}a&%nTJ|(F|m{u^*2OdXF*Dmlt;6w+6!9y2Mo@h=Nq23kbD-9XOAkFg7)&;G-
z3pmmpY2BQeaC@OMTzq<0keyYI+wKP)4n6pw!{WH_faf@Q^{!xLks~Nu#YL*uk(%9u
zfQ_dkfxCyk3rO<rqSfn_1KvX>GJqydn!V0c@-Cje4y=hIXKn}B#6w>SAoyG~dmZF#
z9-_$Z$=&A4nA<_`=1Q5{K>_E;nA<D;tBXUg2OyoURJa|e6OXCq8oDe07;q;J8oeGP
z|BVp44&;f8LazgQ;-L#IU{74&w+`T@$LmxFExs$^ZpY6(V2<N~9&)P3tTFPAD{`sA
z90#Jrl^VALQQ~3xeXT)R-oTW2D8Eeys>DOz0K6y<or3W)ojGxPzHJwQ-qV5K^^o-q
zjPI4OanI6=KC4Ni@g4AYddL-4Yu+<4ZpXfHaqM;EkA4wsS5k<!0_^m{jyQl&9lPAc
zo!9XpaB}DM`c$~6^LnM%{&b7nc|SVvh3>MTk*M2+nYxndn{4QWn7b>#Wd{n~$*|Xf
zRCh7#bs$UJWmE%R;sD7#CCWj{)qSAs$i;UB`7T_#`DCg7Ri9HA5nl&5-^Ih%6Ta_a
z;p+hSyIA--f&g4#sg6Ja7Yknp>#Nttq;#E&gs(##x=8ps)vAkxuS2c6OK$_I;w}sN
z%q+3h`qxMDpqQIPJbfK-6?bWD;8k2aeZ2rH4*rU#B)OHu+}B}#xS0DoIOyG_q)$zu
zgR1YN=+Dj)p8;hl621=5ii?D=BjClw!q+P(=1CDIw{)dQ_&U%nE)u>Dc#DgKufu5c
zBI0`>s-@7?y5~}8YTL0CXoiEU-bK~-^izLl!_c1M>ARBboGAA?%wz}UUQa{&aS`fu
zz*by@dL0J4lTYsoasi4^&l+^zMk;!1rSe3mXF#_2rjj-wTU>m4RtF9zo!*m@>OVgS
z2KH~?1r9MBS$w-%N{zP#q;2>l`*t-1l_v&1Lxh~~t!hwcqR+E762l9<V>l6hfraDL
z=pf275VQM!f#d^|3k&-(gbBXjU~tX5sPn8reeH!(&MbHL6_k2b`dULYqAPo?;o$7T
zbQuoUPEeP%dMZNe42N^iq_u{_yDM+40qEi);xj;9T);1Dg;R4OzYJIxClQ|k>EeQZ
zT}i#+fl{p-;|+$v?cpNcv*uO85^?n0^hihV4W-)DBH6P-!MMO&1{917&1HbWxN_AR
zP%w`xRjmOA^O2x*AKEl!fwzwxZSYfhr4f7}s@LDt@WF7J8a^0KQ@hZ=ThY$ep*aQf
zGPvhlAbm>*o(tn;z`!^`UQdd$i$r-D052}`JuAeE3({o(yj%$z>d-e!o4rGqilpyK
z^1Uu+Q}tzb<*GF}NNl}hlx0n`HCi^iY}>Z&F59+^F59+k+paF#wr%uR{XFk`?iu6U
z^&@s>WMoES?LF3>v2rFJIO{|&#`SL%%Tp!iqH>l4Mtl9CYT^<%3Ynzu0Rnko^wP5R
z1LuVDHUwV(47t;^{Rsgd?CXQ^F-2RL;>Wy|^292>ugy;fY~I;}VOc{?=2lKo%4c_u
zK@O+2YEiXM+}7Ih-ruHWSBJ&5E2(JdJI3y-4;C8<jbXyy`=UULE(H;ZG?#Q}vDB>u
zr6edu2z>!eZmI=AH-Ivdq_@3;IS6{gsFl?EV^(LZi~9420^m+$g2psJhJ9W?Ol?|C
zk{!9ym4?*H1l{=p?kV{q)*>mm$uJtM1JjP27CU3bI~iK!1r(`;vT2om;MzWzjOsEG
zyl@3b6S;u>o_`RA9g~itrZ0L<p3jXL*+dE;!v1egOMt=F_$f>PhUhslI$3RctSkDO
zP$c>pN8Bo!G9#~c%%C}`i&Tt$4Xqu9fz1kNOcM?SYgMhS_FVnockP@(Nlkrqtx`JR
z<RQ>^#@g17_->85RxZVEUW&0vF{9Mo?DZg+j`;MtGC)C7iv4rLqwnW)_NF+#>E6PF
zz3B#^GWJ}9<eeXAmsx;XdxCBly(DnHDXU|@_Jtt7T+mv_VK^qWxZPBhHqX*ku`d!g
z7Aa-&r>kA!-Us~vm<lzW2zp^+QP7mLVa-a)vXWC#atLGC@CC6Yv|-&4(O|Pt3J1dg
znD}M1PH3^jIrjtD<iRN2z=t+zT$K!*P#a-xwUcWx@!BI8`E9*sF0FizTO9^45h!T)
zxPWs<Lay>F`6;U>YQbW|k-$uROIzpqG4UyRozRSXOIuHFttO}$v=GIZjsjSA(z`)&
zVaf6F>N5mru7%zmzW+(M)mN^ZYDv3+0d-K7IfqZw&{A>>d8pwrb^{9B=E3sv{<aWD
zLsCEL^~UHmrQJwTj?t>66Dsi*e>JG&)lr77&4fNO23UCYtscT||EUu^(INZRIU>sA
zH@Txm`qfD_W}EPGUtPF0^0Nbw%6T-Cb|nnn`~VO|ES^WmtO%OI1enrhr6VeL9|XTa
z>y=mfd*^B734I3pHYCoImVA^zI2K3}Z((c1?A*|lDSnqzUSH%ysw{KrZo-aW00u7>
zFQ?>lnnLT#)r-`W=?iPyj6RrBL`3d1fTcaqaAhn_OXQ0OaN|%y-L$WTJ>nC_Pa4``
zUf}W}P`rjP075jM3Eu<fgstqKzxsVv2h-#ly;WKhM?}_LNmhCMda4WCM-`k!JAA4s
zm7Nj+%l8aUm`+5|R>pnPUG%$P08r&BQv|x&ttWr?>%B+-{OXLToeoD`1_fubJ8h@v
zX!NsN9-20#N7EXm2@u%bTWbI+;98;2jz5S;THcDPoRkrKSwdNWjswbJAMvxiPIio4
zyWgR7NdN+0+8Sy!U0u#o$+L+v0s-ro6lpT;{oqP{vS}M;Td+CRAYy%B=+)^Sgam%R
zlahdqMOy${i9q6T0p$?Xk;g(W(cWRuWQT&{Ht`*9oiS|o#b_gB)!|$<66jrXA)J7D
zcvS5j_Jmbz1Oxl>U`s=Qps}|s2Tg)*=AmMb#G)(08_*wqmp9Fo>7WJyFwlzh0^^T#
zMTfBDRo4@<L%!ft4e;ISkX>?DxTie_IPUt6rTG%&xn||7n$J}WJ@}KNpygD>C|s~Z
z(plkL2U=t9(96#8P~}EESJerUxs+MrYgY%7O5FD8Lgqk|NVxC<^L?Pyn$E;~j}fc?
zOwcwxK~e7?frJCSeh4Ipp6Eb!;Uu_1IKM7y;*@KJ25*oBZvxEPlc+cC@ctrsUbM-i
zeXZHiYy069v>Vv=<H9e>P`$))?RVO}TMDqH&=`qsj`hZzv*P?uJMA|Yp+4sXJhPHy
zB;9SAW&biUes|}xHK+qu#@kge=+p?~Y5un>?JLUI?toaJ!0WA3|8Hzsb)U`hxKD=I
zYfK_Gfz}m8!C4D(J;)_M?5rBpSE19<QlpJPd&3J%t|%d6dS}AP{$8Eqn>x16`GkA+
zezm&90N$FsHAM(8uRfL=;V>7|TL(Y>8Px()67IVaU0p=Rb)DqEp3J+ePyx$Z3xqZz
z|3s*aIb$tS#`l)vdB`BrWS#)<O@VsTn|99x9#|bW+utQN5E(9UXBa>g+Jzp?=hs$X
zm@t7J&F)%OjO}d5=n{`GXz;WOJit35l^#bwWnt}+MX99{*do{yNoB%1P|zZ>cfW?#
zV?9Aqm}OCUDm1Ze>!a=G_wyH-Ho&wYN2{t!IZHp!*x|!fr=eyEHF${fgBm?VDFJNn
zyb)*Sj0BKo2rYPkb44yZf;$>Vur7_i$w8YRK`R%aK|DLy)W^rtck(xx#7vNF>mzY=
zBpI$TLeV?NFhGmJ<o0;RJI3(d$+z=&zZ@dGrtL=BVx$c>{B7*7F>EBC<sF>wvqV@m
zukd*5AJ%#EW|KtP<UUS6WqcG`N}nrtXf-!HgQa%7jWm{x9USg&#)|f`y<0uIzNRq!
zvd3g;4}K@*D)Fp45c{bZC4^2xt=10>em}HWG2CLr(!5)-!0df`A7BnNeWD`ekTe=c
zgiZrkuj21X2~2*(gM}xHFvI+Kp%NIFrRT-i9zt!B7%&}@ye|ZS1#Y-IWGjMcDSd;%
zPlgpvBk?!JBM^f@NcJ}J1P-YaIW`@2YK^(DwX3)w^z@O8uTa550pMjF{ebb()(rGf
zNz~DF@<AOY_`MSCM{t$_6!`nQ1K+nqlKUc5+?~3PL&cD=?SX1U7!61Z=E;0BW4(?<
zmuOp!p>bFhb>~oVH_f+jQJr#CtiTUl`910(vgn<iWoYP-p&@zMBC=^J!j$sEhnU~E
zWvI<`RHc1C*U6O2i4tsJ49<N7Xf@JxhDYU_>Z!`&<rXg40ZxbuYr|Vr@DHFvw+-Th
z`U3pQnZQWXC!p`D#E>bdPg~bqS?dm+rjwV-O-f=eY_4vzLj|VJ?}nioQ#VJ7G7exh
zy9k|W0P>BzE~o{4UWj=INe-Xykj!(Vyqwr`t9(qJE07k}(mh;T8=&1P;bj9ztCjo{
z1^{h_yFw1~V(iHqSf+7A(KOUty~v!YZ=+S*!|I>ywZ)5#WUR$kpKvZ|`1Vzoq+b@{
z!m)b3z9xaGzCVZ)VIacYyrV0YG~S6%-w%&0+l#Kw+echh*Pk3#$CV2ku@Ox$$Y~rc
zZ45Y49hR2sjHEfw&zoj4tLL`3RPz&tDSgRj#QM{r7)!h!o#~B^RbubqFvk(|%Kc^9
z?$2|Zq(QVU@tdSUwRz&P3l-r$qf5ao6*uoEiPXSprQhz(d!xq=+k{!XwtW-}gt)wG
z)5!>1p45suU2Xt@mbBIe#3ply)F%>kh5NL*5L{?imP%f!8kYj*7*kws08ZPCG=WEt
zJwEaQ)l>YXA039cQl_>9qSA6}oe>O+Gu@r-CXUxQtpE`}L)F}K!`g?3lTE`1O;*HZ
z+8*0sbfQbp%~cLkDEM^1uErCI=sEziE1q6m0%VyFr^fk1(u_*g>-CFY%w2%F|0;sh
zq!v&IqMd#hr06em?#_){=yHiDGIbiITGkq@)GNw%RpJUsw>>g)=cV4AI}<M+8&#vf
z&@U(cp#>%|30E}{2~QhOgx;Y*(*cv6n80}imGCA{@b{gDfv|k0h*Rn4Bl*<QPTG^7
zPlTtFnm79$lG5jv?zCrITUBgk2KIhVLQ&*f=&)z}sAF1P>_Mh6r!*-nh3RdMPEO~z
z`Mdchh`p!^W|qizfUj2PXbz)wcW7Q3URMP^zqr#2V@p~F%)JTgg>rZ`ZXurKo5?i)
z!j$8!o{Mpa7qB}#$)xt?c!NER9vgU~O<7*x;-GuWuHBB999;|n3H4q%Ka&A!&tfdx
z-1R2I4<+FT4Dw6zuP}>ZBY~>96O7FILI_;|F$Ri$Ujd~+<im{p_$<^S7))Y=&UdFl
zs$S%}hyHBj-IJ-_6bX!BD0C(Y!P8H0<SCsqtDCF{6msUvC13#H5K@uKo?`j%mG;2P
z#9mT9LaCvaZl0-i1!34q%+3m<5~PJsr}&aN4^TT0yNEY0>yoV`Y^7K<!jwgQ!>}83
za1<>}u>h#wEG7kb6KexHv5UE*GPzCeU*stncFGC)>6C{R#l)4|bP|gF?POdYCJuG5
zLIciqYk9%fl3Und8O|LJ)+$#@rUld5Q5)z+nt(wtVrvuw8-s1GZ>7ekeX`8SxEDfQ
z=`5{{au^v{RxsAI=ifvLoK^D_=9eqgKNbU53whD2A$16KxYXi}C4Wu=Ym$oKGh@6k
zQeYwE{>eZ-yO<;`;`CJX`+`9uqr-@z8Mu@TFBKN6*;eRkSia^&VA47$4CF+A|44=#
zCY^_9=oGVX?UL7*U&Ov>scdB>(OcDVH1NCB!{6>Cem^Y*%tEbV8lce%uU+Zg_X_{H
zM4t3ee<i+??NXKl*4^I_auyKoc!xR4NwMdz>Xd~n9~721x(oo;Ei1Vqk3?iYSyDl&
zSw*9+n^Xt{4ZLe#8L_^IY(Ew-|CT5aFf@EKG5p)oJ3O}1W#_UtiICYy+;1{@RG%3;
z{Cmq(?P_eFA<Ov-q$PZ_5x)9>x-A5Za4vG4i&`5=$7=)jR0L_B->IXpxPkBu<#6SV
z%dNq}&Ka)=`LYH{9V14cvK&w}1SeL!yYq{rCA2As3il6jiL&*aaQgRTFI+S}2oZTe
zp!0?}CZO{(ag#BPUy-HhB{OKk=om7ONNSJSy^+1;;GiY|OUD9!eE~kdYv~7WXQT>o
zvJoXymSCxfwe#UJ5G75;-37~7Jw%zko1MYvv+B1eLW`M{@Ma%YH!)_FV&Enqil?Ke
zO-SlwF#(;EK~3?IivXn5gSVvtslbn)N#=c~A?iGg_3&Q{Lpgt#Jeu`Ve;Uitz>B74
zF|J0^bLlr={B)5;iHs;ok!HpC2rdc@0_Rj^O+z%g-ReEbp(eQiG`PS%12(A4Mo-0y
z%&H#`A9GBy;#W{KjR(>fxss5mvd{tGx&$X>2zMeflyxKdv)!p09*&@Cn!-4^q~35y
zsSf)@G3aVgp_R^+>-^L*XXzmK+Q>-ODr*gsxx<+u`JK9e?#yi>^k~3uOj&=r`%wL1
z!T*u9hRlxWMtRY~f$wIa3Q#W>Ub_%*nLtSWI3yth8L34k8}l=0@HFqT6O9u7aw993
zJG-g_DG8hnO!g;k9@vjWG5j=G3{CbUkb^!cOh>}I8I%67QK1Y-GW-&uNCk7{A5yhQ
zvET_T4#NsUXkb$_to^Fi77D{_kgGzXzDSlKH``%NLRc^9ECDS{M<7cCg|7bRsp5hK
z1SFu9z|Txay^9Rl>Ga9q)84RyImmfmfU1BL0YG|LB@mV~_<L{~zyYXN2+eo_9P^dY
z_}oSeF#fe03v2kfaDJ}{xqEeeagmY=1pbFR5>>GNhxi@?BvVO*6A1#f*f=6s%6qSu
zh<W23jm*yODRA_HkIa2wfX;d-=z;SD=lE&7s*-A~yG{^k;JZp+X4VK4A*`>4c09)o
z09b({%TB`?Nyz$u0pR<{b-D=9T*koh@)8qtt&+0x$8wS~%OAK2-dCEKGvtpnuqu<D
zXj%cxiG&mNepo4qd7}B1wu`B0M(*(bm2|KtK&w>77rRlmm24njyz=4nz5v73uUrV1
z6vo)cAco70xB!McVzmPFOBsPg2KVey;CZT7=GI$D!p3g%NrXyZI&(>kkrZ~3jP20S
z7TDmu7wT>wgTMMbTNGodom<)E<WJe-`du@GjXJq%CAev&JMo2V$7OQ{4c*Il^3QDa
z--+jN9WFs7Cdqk}YSn*MxI(dpHQotYCfuA{%Kt6{1at?&eH`8qpNUBiO$a@O$CVQ-
z=AK(CG>=$@V1*Vsj9DUOXv`+kBIyr|kKzr>yOXd?Krc6iX7wu|Rpk&<l3~qzA~w6r
z^OrFw=AK>SP7QN~Dnk-bq(gy;F<1OPbnLmALQfmIs-gr6&1jLESEW{>VaaGiF14BT
zXLh5NjA|__WQ&8DWr7`5Of#$b+8s`S%ttQD$SNry`{(K!@yqXmDjA?!tu;)z8bxM1
zS#G~xR%H&v6|-eJpxTW!jiD*_AB8Se{iOF^EW{PpX!467D-op@z+-cR&KGqM^`uTZ
z+;FUU_xZCH)%oU)>AK>kvy4+{ek)F^^$>#|X?k=STnRc_a+)C83Etfh?Q--4sm~Po
z;k{btoGRMG%}Ih&E~lm5h{>>Q6=MD-EcKh#Nm-Wl754DX!fAy9mQclwW+|AkC+DNN
z(bOj*AgnsUYlJ|qX)_T==BA}!nxK8!t|So%-{>cuf!#9TW`5tA(9s`4Fjw_OX!L)z
z+ZUxl=1VQn#%NL7a04EQi5)QKK?*Ct!s~D@3&ySHGKk3&?a?&yC@|=k{+A-?mwOVc
zd$aZ_MO|i#F6wI$Gi&<h*Bw7*+yZVg7)xQH6vJ%3U})kPy3OBRF!nnj>L>(1GeS4?
zqipx=Qy8Lw_mQ2yAlB<?4YA=2bto_nI#lcL5aPHX<HZ7l*<}h~YcJbbHyeE(cY0Z)
zwyVoJA;&%$*4YHw=B>7a#<YXqNl9J(-iu$?A6>RtFSn~L7i8XB&M{F`5hx6xv$l&W
zf(D<ft$V?GpCwTU=Z7k-f$Bdd)^NGu&y<<$RAh~;kxV*#z2~(qIaPscjwLb1NuP@8
z)C2fRUD(n#?J$!FpF{<&mFqM3upWsjAv2Cgs^URbo0S>)n@=CCka!LSmsn>N`!=lp
z2vGB{3r{yUUatiH?BuSM0kD<=&I0&d0^SUm<Lo!&KLeFj>c^K%Sc(AflSjTb_jB#0
zaHdyU3X&N@qtUBSPas022AP_1dParZ4Qrh~B!FyK#tsK$_DCTPe@*K>g&f~{j{(H5
z@l{hk<2AQHx%{C6M)pjHG3XbJV8s^WHy;S9D0p7em|r$%ZBrN$V&KxSJC5*jaoV@I
z&))sbtWgp0NN%<m00u2+xv#H<psl&QMQx|E!Rg~SO{piQbb?%W;3s+m^;wTk$c9Mh
zAG*Q*9N=5I437$OuoOE%(sdfo6FMxDav{KMqk->lw$aEB0_HwOFYY@mb1sAswH{>z
zyQg^$e4?QGyA-hRWvQ7DdKL=;I-6s=T~2O0Ma=G-A*Z#eE2LxM$8HC3rfn6PfL(Ws
zi|Myyi)XpCxx5PKop6Qs*-k1C|3GEj=C;1i81<UJdHzT8<zwPK3pyOGMr6yq$S8G_
zQISz^D?%|hI+ec-C!h_5I@{eSDs`arm_Pk)soG}tv|T&%akWCdx=lv3Xk#Wp-j<aK
z8*GtM+;`cnp6vbpwO;B!X7hV-q2R~w)`mi#=CDZsiyjKTvil^3<ICf*-Mg`-+;Vpz
zO=<N34t=ccw@sgM4LM@Yy{_&T%gUmtEZGjU;>ozl@TInG@<EDyCGU?wbWS=M3zh9D
zLS}e93i?14kV}6P8`SB^^CYO>l75k~eCaL&wBCJB1_EtR6&CmNzlv4Vq6=3(*$p&|
z7X^``UEu}dFWWx8Zh@+D$E#B|(|0-14h-N$sapgIqzLuBy}Ar`2!GUo>k^tK#J1D{
ziJ8ZNHVmXa#2GgQxpW!9#Hv$MKI~N*z{GiV>W^S`M$Ra2_I(pqvlj9cFL@%A!2zVA
zA$o=4$+o*G(D_kF-Go^V?q_OPnjPI7S>lcpwM&rQ6U+GUv;UUyMtp^L;22%}@FUD_
z(V(b<)TcrnbGN+U$RV&IJN-sAu!2x50=rDHw9MI=9;fd$nnos&of8gR1hF_ATr{X`
z&+jPp4CjS67#VYPz-vU5CZB3t`q1s|YUNs_v4y(`=X$!!C4~UIJ-Vev%pbIn#;dQ`
zAFW$YU_d$l&7Y0Sz|=phhe6Wju`l?IyW-hn6wAJ1FFjfSt!?WJ<O-s;+84>0ctWY+
z%OfHa#**OV&yw!apaef#DwY_~re5OUmXRkryCQ)_W&k6~U92au=_rNI9pXW3z^{#S
z5_2=Z+z#mq1m!8j9ijt*Wq~Lt`88T_Cdz}~OA(+bnxjxZltPb=@CAl&FTg7XVrCQ}
zz(FZ@elI2baZ;!(uDunX+1;G!ARKppR#m9o!1<I?x{7`>vvCn~1Q^3{L)XmJss<D6
zw!zUV!{?i_7e}}=IA>3Q;ANnccVWYEWgnFx*vl9g6YNc^N<j;r*$1r&NTL!^GRd=K
zd42Qu=zQahpQ|amO3I?T%G}Q-<Ii%u$rha80KcXX&UBo~_K!iUMm8n_oy%ng)xl+d
zktSfxe12Q^|KY(9PLjxT#m*?RXbBaZO~CFi8058sD{<ED1b78Of<ip({tCxoj?cXj
zG57;@090b<;+z@bp_r)O0p669fHq6h7|_A*3fXA34e`gJ?6Q3|hQTby6t5v<)wvh5
zaGql;Z@Zuu2VD-GK=X!#YC^IF5P7w*si*!X;fYQ(@V1)2Ht<T^=Mg&@T-<haA#;{^
z)+5gW+q1X>3&Q;*q5zGsmt$;}U?&?JH%250xoov!=<|^tr^uv0Y^Go(TgX6x8si1d
z$X%#$jN>~(#-(_<bLJ|93L0TU8!YqBRH$jOxD6KYIEq27`vV40b4#5ToI1`Q9Q;B`
zOe0wmGnQ2W)5v>iI1<k032+&P0(KSv-9@h!0K9P%(Fdgt6<1NTMbiKyT?!|=e)~@p
zs3y#`C4$kGU9`1=)J@|8Mo>Ryu$haAdWpd#C<X}~2NNU9vgkL%f<ld=*LwkCCeGXG
z2MM|SGlBBsa3oxAHvD02XXF6RV4-N0btslJJ#&1iG+hVXVPET=Z!!h9tZ<l15;s03
z(-!iJIIi?+0FEaFbiye*oddoy6TX0W>?bz>Jsi#KU3+m`P2iSY$f8bzGfr~JH0c->
zLXD3Og|C@siY(Ix#roU*BJWH*iHmrr=eSQL8MLXGP9z0r(*r7y=at=Y?uVEcVSR%}
z!YhPdPi36tnCF$)dKEyLh$y1CzFz=kR=6>u{A~At-VtwJLrnBxbi%<tO_eUT;l|<e
z$4r)4v+-Ig4)@D~mz&%zB^Ot$c)C@Z;F(DeR(kxb(wNtGn$S!F;v5omv{MwswZus*
zK-izyg}x6L_zDXMM7~oy&qWGKH4uw`qa1EcsmMj2wn2+5K%kr0wPglVEFltsa&)7D
z<;;F`F!Lx1T<pC<BDfH*#|x1y4K@x>0)iZAkF9Jzv4UbQ)SGYs7orp<yU)i5%~#8c
zV*&8mOW+WfAlPn#>z5Cub|Ef0cZ0%AD?H<8sT;)pg+>_0!8kH=<Tg`FWIYj4i%J;9
z;a?PDW(db4RLKCYO%a@(#-3k4G83jemt=6#2xV1-KByj>B*@(`E}#-lkPE7ODqf3>
zs(1=f+wTvGZjk*-jz=x9mo{K(AL?>+V~MSomGv-++yqVu#{<rrKbL~f;~QR3rnEzN
zVxrSnfUr6-HU(2RiH$w=odl0{geYKuH9T3c+)CTCfJaq;0bn+92+eRICYmorm0m>e
z1ah5I7gAywX-B3FK(ka0)jO&gq8%i1tc~e^F2I731lJ1iM5gTodn6yFyeGsBVmId1
zR}8XjfzcJ;6|{^^=nq=CF~o%%1f$GkR#oL6L3I8ieP07zxeschZOjHx$tfR-@W!cb
zpuUOe2c6Bu!+}g57CuVwxjR6+y(I@%auQ@76{8a<Cgs#b@{%PVdF3&c0bM@GYRV4M
zTIFQ_X6a5deE*T3^*R`55$kf)1`Xxj;e3(M&*EAa12rVd7q770Xy<E(Y>?%C8`aN}
zCBO!C>;$$<UfaT1LDVV=xZDPpFCUt8<kp3dU-Sy1@>}&P&d7AkWLSsgfa+PiTt0Pg
z2n}laLfdz01pW#!sXM*f?GP)!<kepS(j~p-jVF;Vem05FEJpiRXxb4ytl%JX$ScBL
z5srk6L)$!0K7VsL#*Ss)8nmy3!hOmjlDTMR_DDo_EVveU8o4;-J!6$%w>1uO9{uEk
z0i-rXzZZZM`5>-iZJ_@FgIxH}R1?ZA&Y;PXYrjHP<=0VUlU*S3cqA8)MN`G1{*MGM
zP4JQvaW!)OIp!__Sg5v|N0!xRWqH6f^OR0hC3_Y(0W_P0<??K$74Q(efE02?UzXdx
z@1+-Xq7NAeM8NvKtG$ao{CtXu46$Q7iPM0l(qOhY4It0!JNjUt=8G{+SqKEv1|;M|
zF^|}ZpcI`9rVR_})%)GtF$jY>bWDTC5Qg=YcJPlP6$j0rD)15~$!i*;(d7u_THrLM
zJ<EPd4i%RMtA6JG5s2#*oL|Cf%t_qo#MP0C4y^*j3?DcWfravDml5!O;8FzZ5X!dc
z0x}jUx$OERK9eg-6gPpplZ`cWanH&M=3eHERuuwa6l<&_>T3^ST05yPVf&x~kub?V
z?woCs0PiC^m{~%6q5hW76UetfBXa__P0=GO1h!2&@Xf%TjB>29PPjt0^oD{;wM6BT
z`c!BbWbH0<ZX@4^pq|@FA-n(d5{PeVm)tyI#%3b2&>5wu+Q%h0NPObV$NqCC=}BCo
zrrxKw3*t4!NzP7?(}4S!N`Bz9)Yl6++k-6|nh%X<Pl1#LM(d3bbfN*btTO970rRXn
z3z~LQi=Z6~$p)k9q-Wx80nrxh9B2Z=*b|-GuA0&Zaf1Ho_r2dWI@DRSSdA_g^2!(o
zO^?7Jb(v%}DSv8v!R$x*lCdVUA0;^(!LJ6mVVTAm9HM-4(S#=KrYStga?T=){mAiQ
zGsZ07nqM&xROB|)F@Z%uRck6`Mb*tydh5dW!;&1nNd{3|E3C6lb1?NX%)9oY{IDJs
zT?(-Uewhs5tE8C6q=HqVNb<mNFM@+LL}j)!#lcj1HDiLbWIlPN2Vy^~_8Q^v@vdp5
zl%o0@MFCb5Og7CQDQw#IC3(@~H{6Z!Wacr^K4+PQ1X3aGyTSU;a3#FAh|0!mhTrpv
z7>%&RW2BQDfW3n8mo0to5hh28(Dg)x&&x6Cm)px}OBLDgiAw9#Jr6B6_}ho)s{ya1
zW8qkLb{R33{lAY}P+osU!O{RmMjEk9WXr=Ju=KU~QB^i7SXJzby&nv?Y(oK$B<od8
zM4@fF2!d37i!;*7qgV-!?iR8D4z`u2GvHnpsuj?fh7f0oY)Og?<n4=#4CBYkPY}+f
z#9>$8stsJ3-YNl#BT)`1-vyTMI?|<lIe~29i+9@U?&Tu9h*_*K_GlCmFJ&<RM18je
zDqq&7L}`PZ(7_Tfj}&gk%U>GiDR~`qS)HE=k6^KvU5;_IEfYQhkR!@n4VWULYLs{n
z*sn=G^-A8-lSh6GJmoJWKQ#h-QH5`YCR|ioft~6?>;zkDiX7(^%M$?jpaBAY%9L*b
zTW>17fN3-xTfze8c~pGJjTzOEQGAbx;ZS>){3#=jm+H~ydkD<LbTU#QT=q+q)R#OU
z3SL1U-Rgs+PFfzmz+&(WupIhZ$EYpbgK5<6>%|gIgVnU99gBYVlPR|VC_ZNI$Y&Kw
z+=p0f6({d8FG{-JV30?Q{thsET!sBVQlN7sT#Oe=vH3+Ec(f5Q&I_QknJ_+vc;I4(
z>lpBC92Lp3F^Qs*)>>emWE0IvyA-&#RivLY|2~dYLQO0-eC~_Ke_oZVxSU39gCU1^
z-E2~66YFwTm`5{Oy5Wowf-N9Z7nm!h>U&~9(yQ=~fnom20#-iFhsxQTBL}A7SKo?1
zRp>{+w*bxlsdy4B0*-9YZd?!j7J68%C`(>?8E(YNiq<5Gz3G_9E`?La8-#kWwZ_eY
z>3Cz}n`Y8@5>c9pLlAY{0peSpq_w?$e6zB5ivWL2sIp%HK1~dvy^=~bmX)o=&I5Pd
zR_ag=y_^CpqG}GnUYIrYr^KG686t#QNUd?+Zm$`<ZJfiFOAjt@eHR-=MlfqDzrDcU
zSXR^2m;l3Me3NR)QgUg~PDT@J3iU4`8fl(PK8Bi*s#{wNJ)2OL%%k2V%e0McVB&;i
zYjRh{5vS9jE&+s?L<F<+=C8si^74Pnb1&f_4^PATfw?UMeb~XcRVYQ?vp!YH-cAhT
zI@=)%Jo+;>?POSPS}vf8M-TtxA74P$ndMwQr3&hfxgtW3AnAo+QB2XFH}zm}g3bA{
z@Rn%?$zU?AO}syZqWvDye&rkE2t2Zu)UuQoQ$*f~Y7&fs8{lhuTC(Y6rqNt20hpT*
z0loI-ElL=&60FQ^If-%Dy)?Cy*?1N;B8}{>qJDpc#T!~oXiAwf{C<NQ$X-@?yJUS@
z-?oB9gFhd!-1Q>vZOM%10P>);e~3$JU-eW;8ng6HZN~nN+S%fs#M~LP0;R>n|BVfq
zp*Y&sgw%q`xV)8qnmct7Y0S%?wJJ5wS;pjPz8*Dd<T*6oy5@|FXwqCIT?dtWzULWE
zG-g|OV@a)H;Dj?f>vfy%;cMHltb*e^*Q5*&^!sY)aW|*uV}G$b^VhHE99>K=aF)zI
zOhRJ<^rLH^$HV32RsF3RkFS?MH5cD|q8=rCzCL|^nV)OLbcS=%mAt9d)I99l*7UqR
zK7U^o^?1L$KhNoWKB`~ehOT}7R9t^uj`VbV9gUo?aP70i>jX`q-t!i{dwn)^f6Q<D
zyk4tzD|&oB^Z9tP&{3Pwq!exYn73B@<!U@fK|M#(zQ^_VyoCJvlXLC!QKR5gK&|QB
zY2gL<)zz$dpR<sdhfqX82<|O9>jeBzm;dMPxhFB-hjT$rOe52`vPS!66YhDh<bfNG
z=JT|7yZE})>*WSg1U`!KYXafr(ADr`@44r7GNqtiRKO0o(cR<mF=V$!fa90OacRge
zrL@R(TZLC;z4yDG<s8)TlpN~?#+$P+k4wou-327m=~kWXOBmk)=$F%)r>^q?Z{^h*
zs_^st`>`_=`FYT}*@ttC^Px*kUf#Y>cFos*@9|-JPCSziOTI6ojy8cm?3&u-CsZ3w
z#b0ePcHAk|kMnqaKEq<U@a-)}V^o_Xmsm|KUgPX$_FkEYDFe0`&e|XLqITKaj8C63
zEd3_l-6B}FYIk8V_7fd7UXfppykOXIJxw=9kblHz4zR!uJ#ksQQekO_bFA(-zVun$
zY&`47lGa035mIAy36Ni36!8esICRyMzPGpu;0vG5vky^!*4n#q-5Du@bi+67{=6A;
znLi&8TQ!5ES~tY}=BBZSd;x9VL;fJih*r&RUaOA!_?&Op8UK8xt3CcG7@mBkiNbnH
zHeShjcV}eChQT-SN<B0_;l+6SaO9gV`1Qy_3&guTf9!HtGV+%4P1lPiyS-3awBH(o
z*^HocI95zfg=Yc`el*s+*0KOrVl3BO*HgrL)3ovjO69AK&aS_HM76tjTJ09&{@FaU
z6cLXV&NNo8xp_<DdC>|2;MPcyxh<w%hCS?OGeycfo{6UOOg~-k16fZmWVwN^y0y<R
zn3;e03$x8y3o~5dG+BmPE}qHzKF#$<G0yeHFbz+=v*-HUFBU9X%?D7Y`=@W0w2a-1
z;6BMXH|W&yjWMi&>~C)4FXC^y-E~~>P0dj^s$W7(pT7bd!CEA3%e%vPt&B8(&9I33
z<hz&1u--%aY;@!CHpDu=47n>l$~@>pGs&Le!TGYyl4*GO1CFpYJtz*K>?&@LoD;p(
ze$#G)T&v^#E%UmKexjkt$}uYoxV<U9$~YNF_Gm-&o~9ThTT6@irh3hKXSy7moa$(f
zIT>()>wNVbe<OVpmb&*^{raGMNW0tuz`NC66??cH{X`;uEf9HU)BP%ZpghB?`2#$`
zU}6qsY-8l;<Y26C{WoQ6U;)K~Pmlli6CWR+g@c`)>A!lW|LD27{}$1SxH*X_I_WzZ
z<NvGptJA0d&fwDt3E(r}(;4c2OJ3f;#{Wt>QCl0Q|7C4LLr+7G&-&f0!heju?f%mV
z#{Y4KPp9N=XN*txQ{U7Wp9G)bALl>y9gM%*V)$=eIvHalbA3TuH+;=+75#U|Iq(@6
z>FM#c|1lT(cKmJch|l~#6~r8Do$dZtXa05akM?hs?~6|H+qHwfjicRPXNK<oRZHMI
zIXD~tHz)LMC2Z_sZfL9^CiqwRpRp<!JK8!s7#cg`|D87lsQ+(hY~T66^ZR$Eq>XJ%
zoy_pr|EF7`=2lL|4)}DUR^Kx#Y;0(2^pB_i7&73qF>|o~ZR<Zv=9YP>=IMqk(p+<<
zxX81~!!ys521%Soj1*4*SrZrt0GNm<oE?D=h_q2FU?7|b4RME{t|Nu-8*DmrgGqw#
zU(ZmFfO~#+_d`g<6>@7F1r6n=6H&bmG8<`<rw0&i$Ft*~uI<n6brxmqnrhCPw=6{=
zaspwZ2#DC;!ZM_iUoRg^d`JdW1j3kn=1-LX?$o>~v8AGdrQ~T}Ckq%nCUOLWA=dTJ
zvt&m}UROF9F^{T{40LinMh11eI9|cAC&zU)$3_?Q%~VAzK6vXC2_;kM??y!o=<95?
z+8=|B5=f97voWzQPnZcMvYA|2NxzwDKT(^3=X1P_Jai9h)U2Nw2)r2M#KTJUNIId)
zl*O$^$9(Yb;1~MPBqNQmZOtxZCxVBAhbPFX#-K>mB}gKfrvqD$sPYBvz5h%mIB@0_
zrs^c3N=n(oo&&5BGDxPn?@AxcPm~htD%2q_JBVm#1W_l*LFn(lawPsFKfnUeCk=Wv
z2ntjd%fA4R7k6&ZcWdIJ`-310_eg8Ty%i~J#B8!zJBH3n+LH^sc@4&v0Od)d&P|qT
zy$k0LheS6cwpBEcUh!0$CS(!9oV6}=@yR=AfQQIx4L+t2HXQpjVWr8~pxR9LI?!Mm
z)a$;kL04x`NR=%OLDHZ$M9H#mI1tWem5iZ~O3kW5r3`ubp#;n~E6veoRXk8pa38Gd
zd5<foF}c*@fwqyq-gqjynl@6C2ScmdJ!|IUGKoAgX_-vMMu>23lb$8wr4zr9XJ{b{
z#OiVMaFV(qpu+2)nrxTyK`X;7!W>#dhMmFvRW+jP`MkL-+LJmmeTjI!VPk(e-V<&M
z?ALyk2HtGN5j%(YnmFoE*psPC#%V4VFC_1<BGf<Cl)ZSV+`|R<(cStq`UtC;!^*SF
zXbwKc$g`@BJD#Y}5NaHM0OvwcwN~#;_0??i=~upY1kV?mp>$Xv+{GTymTh8qCeSco
zP)v?8J|z7{oh6o2JiS)mEfr}9t&V6vubk%>E~G%Sw?wT?G<aFRF=(wO8?Zu`l6RUu
zKj&=in^!?P`|9vgCB<ja4pUP6n;+ZeXh~-M2QzXV5uw2*Y6XpLhfT!$i+zQ5^(4Yt
zaFXR=zTGS@a>B2o)M(9Dm8@Tjw9v3*PTHg!1QmM1mX|Q|;;asld263*;)b1^IvM#i
zY^WILurZ>s5LsN#DOWaP-tlA7TeA0OI;NFWOIeZ%X5q+sfZ12#iUAto*?ZC~oNb(K
zz$$d{LXL&f$zz_DJdfE^TcXue%UR}|LW0c1LHL7$+{7V?v4*~!;@>ZLIKzIE8*($I
zM<;(D8pj$QlQ2TLj}2cAZ(;aYHwC2X=b5N1C{;MNW>`J4A+qE(qP48$ilJUcJD<Wa
z9?7Vh_73V?&^@buTJEHJsyx+I-F0Pg&U2o>Xu+c(4%HUnQp{my@JTVLV&2^7a}aF0
z#K%BL$0hN=BTDv@x!yIq8e1WKM3mLmmrVR%<6+2=6W+OO-Y@UHm4u41!I$DGf{9YT
zmN@JTb!vfHx!_4^895|h11^M-UlH9H?v9Igvs?mh)m<~|sxu^5HN!<;1et0(PmLpg
zC75;6<iT>n;u%TubELUy{g`FAQSE4+)55jxYEA7aH@+sxtl@Ots+m#BGnr;qM{j+V
z)HthIbX`POzsH0t2}eWi-m;fnm4ye@YolcN>~tm$d{Ne;_e97s5A8bdLCNt^+K_x>
z1iWnEAy%G$cowJ(09V)>CAWLH4D^lMFr6WVmYH=P_P35kkrLK523nK~5wLTv<QU};
z-tQcgh>_Fm`@LFruk3DuY;L)Eb51IYwv{{9DionYeTBwUfpK~8Dw)y%I)nsdM(Tt3
zq9`MV0)oLD1lLs9lnlCpKpSQgV+GC1*B%nMAA-*8p}@vwk7wEl;e-~13}qA~l*O0|
zB^B$+O$b&W63y{OPtM~_?a7v*lrqO|rkckgkbe4BymjIxqg3Zmbxvwm<;pRX>5=1G
z#|#-UY$m(a5CkJwQ!8f8zmyi9$iq<QY>;=yL!eFHt?VLfzz2SWxUAmY<q3Ji(M6mc
zg?!>xTumlpsx;OZ{WwOPSPMx_ig_17q&vmB3y|y;IXtAbY!Z#}u*?cRyE!8w0dJc&
z4N$dN-*VfCVbj26j{KbWvVFC?C#PD!6J5s-PddOxi=T_Ts_;Hai>g^%g7f+;YuV1b
zo*kI0P7Ygd=}{+{{6p|zF;;k9yI!mhHdl*aeiP5m$df4Or9|Ugxznvm&Ua8KwuX1N
zz^VGa?-f6Aj6XmU;~C2bR5%j%&Pv~9r8D3}1ay`6@O3-CKX7|Jq8oGkDe-Gf_w4!{
zZ={19BO0bDf;CFIV7}12+uYt_7bY>Cjsobb%S+s`H(1vRT2eR>N^?bPzmkvraA6=}
z>zCFBLW!BjeTh<8l1p_d_dz^q<ga_B7~FSG=e({m(Sj5H+u2*0_h;({_w-edu$-O&
zG^>Z$DC=(g;Vf7N-uWlcN!K@jO-;izOadYb1;I1WS;5_YP)U(<(6x{$6skc9dqL`w
z`xgj#s_M{bVHzAkLvw5#1rppJ>w_-02vzy;hHDtJxB7{;Nf#m-ABC>uU~n9pXL(QE
zi&tx{G7N+J7#mv@Tn5(>V&V1mHo_lw#tSv>cN#~2`GF#kyCD1=BAEqr`G%OcStm_D
z$I5sc*;?=J+MVgv+YZ}!Yo_^xG&H9tesxXf2`Pwf9_K9UC*zW5lShYNGvH*Ybz+s}
z8EKr8um^d_k>rHDVaSdZ#YjlomB!~sNk~hh=bl1_O^8XFW85dd{a(YXU&+&}YT~33
zm`B=2zT?jvC}Qu#0V`TH&Ck1Kw7|>JBt+TPVe08RYKzjYu0fbe6jz_g3oca9Ku<qg
z{%GG`g^kLO*cw_@y{vd#eCK=wfXsE3n4f!)mB-kE(JeV?3~U^H;P+6Fv?x<4PvMk;
zjft9xC$_AIlcnzkwV@{fGa!Kbpw^L@6u-{-ig*Y*jhI_544JPfX%T}+7x1<=UBJo`
zM=G7BBHPCBGTMQhI-Nz5qpiej^Yl_*9l(0S+jhU_8^-g@KR6g9slZ#sT6_N(`9;1u
z{dO%SH9igvE92nok!LmTcW}Vw=l~@OkB8z^Vx?7oxfsa$M?QcxHG0KZKNIaTmOASu
zs(O)9{lfmGX=_35N`Sd;6TqLhPT)_nfT$M-Z`uRDff9#5G_vTXefzp}L$S?v-S%|_
z658xnb!fzg*1h8L^!LuZiu7N!w4v~3Wa$R;c9@166me?z=Rea2_83*E)sOTTriddP
zS$q3P0PZZ6j}ph=3d2vE3G)BEl06Sx*>S;a%0vNM(Ny0{CQ6hOX-MvyN9!oaZ4EG}
zwa36aMJC}UnMgUlD42uNxmv}ta`C2kF_vm2?c<B?Vwy>MitlF~%1X*DB|IlOCQ2Xk
zpcBAYL?C3s3n6Aq;3*&7oK7j%hVzl7P#sQ5u29-4!}Z!GBH0PPy1wwYLFv|3d`P{L
zdQJZ!b*0GkYZr~1B~Buhr+R(pm}C8|vG;w3({lVLE#I;N>7+TvoR@@0O_66t^-o!9
zjKjkChgh+#QNrva7Vr`%PORc4i9y~p#Kuzl^HC4t$f(x%dHQbScINV;H*GF{ocfZY
zl&+(7wTXcQu)+a>dWn39J-*>hf`J19-f*<r(+|#+vZ~#K7E4Rx>upTy335@7@>tw3
zbR&E6Y)m}_07C#kZAeF`2<5YdP+b@LlJQRZPK}Y={?Nc5vg`4fZ+R)<<Tnn$<u@*B
zqp}5Wvg>hzWLZvxLgIk#krM<|VLxQJ5~3TK9tw$0Kd0WK>>C4lMRJ0T7izuPWc;n1
zEXSIcCjiyOl@3B3k7Zk=clwT`er{)WX$G3l)`e2H;BQR|U&sjA&PBcCH!85yF(aTn
zVdy(|UBH7ck<}!rzPl8Py%#{Z8GhgZ7vpt?m1o-Ig!F8aFEk^x00u?3>Jvc&?H`UR
z6UJM)3JF=*_YV$+`Rx&lLJ^gue-0$&)7*48w~W@sCG7Tvd|A4NJ`XKImJ}a!F+ENy
zhPYgD)!MH|ACGjt9!$)G=ExsAB1m(09~Id8_Ze<BQ2zeaWWStw%5+@fw1EflQFoNq
z#hQasTA)8#l4Av3G(0#g;K>ITOzcoTfmQ`8y3&yxS1T+nlb_y`1?kW^nM*fqa+kNR
zC8*iC{IaBp_zSb`c+>2I;b32P)}jZaPX_Zh=J@cf{qOk;b6zeR_sD*T2>m+h=y%h&
z)jP#HrhSvwl-Rjck~*oq<QLb3O?%XGx=_*d`Gkk|jIRcC<g^*a)5{}7x3ID7mxdIn
zU-m9n^RTa~Wv(+q412@bJf250P2R;en4BdBy}eAE4b@*?$6O^N5k0~m8XRYBgnNdH
z;y&aglBA+#34sNNwR|2W7%s`qYUjE*PA)$`86f3-#3du4^IwT<Q;2wh3R-$97!In4
zoEvq@Lp)SQ&W$?Fmx#rKPM&SJc!;}TyGdHTovk9!;_LH^%2C!^YI>y?5i`U(9hWv+
zj&9}1(U$p8X!bC1MD|6kg1bX>J#I(i&~!PeCo5!5$-5DC`P9g}zs61X#z#Tnx|~5;
z{3->zRYYDSNimG{$X9UNB$EapwFk1BAS)DIjhbDHo$lThK5S5IliZq|$cBv9WM`h%
zScO`wS?22fKHy0Gn-e4i$P6R+464U)6lN}kH?w`A;#I0v+Z-p;wYi3-NGv7JbLhgG
zB9<=^*lf3u*(!o7wcCw8-$<mECCMmL=xR2!+B+Sza!qEju6zCr=cn_BBpe>s=<w+J
z#LH$j8I4g-6vFQMuKfAU4w)dj#|2n(!mnjSU|wW+BFvfc6<?hoD~Se#1Dxi^>!+H)
z+1R}HCnc8N+ZT2B#b0w@o;~}0|3!`u`MH&!>J+sdR`ErJGwc-S4K8~8&z@9od_j;1
z5}s%gj3K+=+MkFnZoZ{TP22quTojJavJn)DtUoho&SKg`Hq?*en|`jbe|~+92sw(=
z^fg3m*}$&~y6RVebeQVNsg)Cqk1DP>MlKOdI1P1cA8>L+Fr_4Lt_(onh}PGo#NKNW
zvYFwo##kOG&`l0$vg#A9`aA(t80R#2%tcHZJywQJ7Ovj>z#DPZp9(^X2lsX*EGt4A
zlXgJw_O)XFePvARfOw`4-{#*zuhkQsm_W&hXMQ_pZj{HY>jB^?d+VVPW{w%XT#%G4
zat1eFbb#%So5~z$Rd5_z!+D3J4&^>42ohpd26D<5WVyKioMc2w^ntw?8p~;jrx4@G
zgH5rYN5zLGv3#32N#<TCDf(PZyieOa=rU{AD6b>ee?a|#ZPFX!gdt_pv5KIuMG8nx
zc-ZPv^ckfkcua8Zl5Sf=JE<??1pn%fLIJ<OMrIXlH~l#WJSq>#5$+ysMJVTe%1ACG
zc{%H*Py=I#@xoJ`OU+*mnFhvT1hsUO;9VH(6a=LZO(pV@<av92Gfs1XbkLT`OXV$g
zwyP8W{XRBJA`7ncIxw!1(G-7vp;T{WvcFJ7g;2pg@HH~A^W~k~q;DBW`B<rip-ygd
zld}@9N0q<DRZVbiK{{vx-)mW)T)PVfFD2j4O~#Wg%?dcmcC`251H(ldeYPj~b~Z*6
zTaC$p7c31WoK$9x+BvPX4b!4m@tkU6f8V*lH5o{>A-avvZj!L*P}m$EzPqE#=Slc<
zu~w)B=t16FYh7VU<ML3kUIaEiGt5iM*2O>1WMDLn!tKK0?p$|ajp1IQ*Vd^ihFP@*
z2ecF3t3^ws=%R3r@T()3V=(R@X=7an^ykvWx9}3MIw^7uk`5ZbNo@C9o-{P+RrP2`
zI?tALo(;02Uk!<2%o}HwFlUo7@`=SRe}|giF%bi)O9Iy`1ipHLG<r>pW*|)mBArjc
zLL?Q$)@%i~GGr8g=6D8nppOz|jTs4x!RU=bH#4Wog%7h;B%uar{6d&H2<iddeWz|!
z2i$Jk(F9}z`A|jZw(rxW+VMc>)^UgbqtV+0^->OmnXyABb5rC?_tv`zc+=)PUBC1D
zkl{lTRBJdaWu&)Aj_IX{^o1Fi7xAXfH$wf!l+H^D5DmoZ#P5$5z;R6PFNha_l3%p|
zQ!Fq?$Ef@RdhG8d>^>^JIeR-XKwD@x*}i-br8T}x&X6CGzU?4xY|ygM>}?Z!WS@3~
zn9<Peq&v?*Tc|h5zT1#)ioLd=*eG_wz538_Nno!8fKA{rHyVK8@W^)oVmmv8E<0=j
zKDqP@P~d_WYyvBEJ5f-jh&S!N7JxmdwKeEEj(ruL0UwJ7D;*;P&tUp7;5q{Ny5|0y
zKsu<kQoXY9N{}nJ@e$Xf{wZ2F1`L7rlC40^&@0W0V=a&?XMr>shA+tmD_Z7vlMFx2
z`=K$p>GTwX`q&^#>Gg<w8tZ^qD_w74&1<(n&(rlT(}}#Qd|3{Iye1LV8bXu!&<+lR
ze&QNTgYK#WR;W7fSAbTYfl<XxCOz}7LS?16>j%M&*BQDqB<2@N2GmaY>q4rv5AI2U
zQrGF#`HBFcLP0crIrIU2NdZEm_A(98^G%N&gYTLH-h)gy_hFMwEbUMLHl*vBAaSpP
zFs19Y`<erN$@C&g+_d^qECKKu!*G-8-2u5FW03&iBL1Y-i}wuymA(KLk)iK{3<ARa
zL9fFv&^-*Dj;|X4USRkVpiVE_tG3~O0Wf;shi-AlaJdUe7m15HBnFLMH1G)|`ZaMt
z1o|-%hzJzCKWYa!5S;F%h71$M_VN=c7@c0N*Bgbt6zB?t{^!|maMnIwBD-lj2*?w<
zovRM+4;#9T#p%iGJN}+-uxm66XCYnSH;7S`nU0i{XB&SV9+|CiXdXwWt@%J~91mjt
zW<d2#=WLSP4!AT7&S_?Rp%5Ew<*muUYD%Xu|EVnhPDchO$>$qc0r6*k4U5>4P2e(t
z6Z8dlF*Xoqal}~a+yJcj*lA*TkZ^)J$RDvmfd-*$y)i!?phGSFR{#+LqR;^^Bl2)0
z%d>pVKFB%2yns4^@<H6}{Kb5OIyHcMwE(UR>>%kgXEzXb23M!dW<bqIOM$T2Ckgm(
z{k33Vz%ev@;cL-A@_WXLs`+K`fy`)Vbe^a$KYr~J{8<P27$^Jc0ZfcZXaB#r_Fs_o
zzqmFtJ>!3oW{&?0$1?ndkpID?>Hh!l*#8Z`YR8Y;1kfXhJb#6&7e|DK085YrDivX&
zdY3lh0X)SLq8MV-?_6{3hbfdnrw+VqRm6oHY;d#LXc4%>H<;T8={vFRFzN;foZK>U
zCLQXDHEeb7txIRALZ+=-tJ_;_&{vfE9|XXquvpc4);q?)LjlCM=rKfI0d>?kQdK>j
zeZtG0sE8|T2Mqb`>2Us8lYx+6zQ&R|-fzDgdn$R^;1<N~VZs=jKt<cefXV8}EuU))
zwm`QCn)>1zhc`F{zuyE^K1?n&mlRRvjF1j`BlkY=A^7y?K#^4^%4EXBBT^*bh0F<!
z5Hg}%m@dj;k~)fGlG=@br57$1^qx(TuMw%?P<#+sc+S60`_^}fb_Sa!V=zzWl88A*
zCwoo4YILS|X&jaGqq%iZbW3i%dW#)l0#%WHq1)4S#?9`2Zr?VTs(SeVW)c^}|KBzH
zXC?l#XiQ8j|6MbNzrg>0G4y|t`@gXTVPi)_2Xi|oTZg|u{6FCaS$*s8*ny0+hO)W{
zm9VjezKXNrH>CeR<)Zr5=2q_b<o_1o|1G2Vx6n%8^c%Zp{2xoff1?XD4D^ij_%zI{
zjQ9*}98BL)1}4V;L>VNU^sUSd1#C>MjPdFJsVCrQ_%}?!!N~qk_HY0G=4lwehw`_F
zLi%>%#^&GDYX3Czk4n+W*jfdj{one3Gvfcv{J%QRsHZ^~io);wioPsvF_~>y3)`D+
zGclTIrp9O781w~}!V=@J_uO^}jE#l_4wshRd)k*Tfo2Fhrjijs=n@4&D8p>{?vCHJ
z!zUkL7L+NcJ|tD@V9d457+clLJh4pzUXs(jkRHJF)6HB#{EAr@fEK36@Dou}+!vK;
z1UK@R+0}UkN)rm2#pM=ietND$&90q5M|gU<2U1l;B+ECgn(HWT$JMY`6q1)NHysi$
z!Z@ON+sDbM?Sr!!Ca>TL`W|9EM4zDGbnpofsr)PqksL;QO}B7E8x!U7?tC^o$`gUG
z%|FIE67=e@B+=z$Z?@bWx1dMkZDMT6#8jv$rZ~>)`mneIkb|1p<dB<fH7#v6@m61g
z{?(=|Rs{3LtA*rJ@>s?&x|Hgc%Nx!o-9cLt*uc4E0`HfZE3uox3C*?C>&K@1fHN@*
z`2WFBmQb-h^P1N4ITB6>D;kXpj*Yvg0qz0s^)=j4k<R1D0zFOBkmni?B?{V)Q?VSx
zsdxs%_2aZu=ij2Wj8T_<T*QZQk%&6|)i%NEwvG$Fo8OdjMVrK?EKzjIxnE#U#U8bF
WzVIY4v9-&tj-;FiqtW{HG57;=iu(Zo

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..643e9787e7f41d39d88fbbd0a53b6714c8021ab4
GIT binary patch
literal 67633
zcmV)mK%T!PP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^b9?kEb|8_u!_35~YZk
z8fX|W;DPNsGdyUxVFSj=L3Izh`|W#+Tx(G~zs!^OW}#43DSk&gB#M$K{w&(Z`TC!~
z+3WvUJI{~*{{8ru<NVgf`P?5r{{R2{??3+S|8ai&&;R?dkN@ZOzyIO&zyIs_umA1!
z2j|ECdD!{!A3y%(!{R6N|Gs|C{o8%o#~A0g{`&vlKfHgtUq42|=f{8f_)o_#yY>F9
zzyA8wt$lm^5h1(%YNY?y|NQuOe?RV=-2Ktox8~<;<JEnB^ER&AKK}mw__zP#Z|C3E
zNB{mmj(_tv`!@c!zyGh}fB*Ye4EW_hZGIcu?4tSg-28dIO~0!X3BT!fw{O?>DYSpn
zX^wCAXj?B3e$&nG;JVmP!av9U=i7aC@2{^8`}SPFVE>;p-+TLJ=RP|Selt58-|Ts|
zZXkT!?InKiqD;bXy4^-mMmG?C(`|YRRxUs`|4{n-yuOWJNdNh-k^b)2yC{?Jo4NJ#
zO_b68O(*N`qD;cq-P$uL%Gr&C-*mfQhug4P022PGC3wxN*=6_Zt9So){(J{~oPWLm
zZT5FjCgC@;^Z72yB>bk^Ye&C{G6}!wW^F$sv-x!wdj<t7*-yehy937U{UuuV+N$$c
z?Ely70K4utQAYbWvzzuV$|U@z+w1?oi82Yl>DF$FGP;5An{H+lEi3^Df4Bq8{9F6^
zA@uRDxC0)4mt?fRp4)Z3%Q4ztcbexe#nJlBJ=1@<=lef!Hns_Q!m%?;oc?L4f9=le
z7efE9QhJ_u>3#kI+1>O&66~vk>a`&jud15}uN(fKJqN~XoIYOn#m9JEqy8&J<d0bL
z+V5i<CYoQ)?RAv(7sINP2w!%y*SWd=bM-6A*BxJSu=e}bQIxMc`bg!wI*RfK%V7S}
z0_W>Ac)nhTKUf8u?FTU{%GXo8o*x9QC|`Gc=G(%v{bi^2Qd!=Yz9?UJe4V53YhRQ<
zSc&#JBl`2(9r0&3V|(d<@8VXJuO~U*pNQW-it=^GJM_n`9|>P~dtS=w`L-IOeA%&^
zzpXvnf3OnW&TsSX<MFRn;*V6s-t7lrE6Uf?dp-8vg{>%GcYHlA-&ejUUw3>xiQZSf
zC|`Gc?)Q}!;ZN4$d3`IDl`q%g&#unb8}nV*it^<Y*PGVg4&kDF-O-=uuwT8TeBE)*
zVBXeIl&?G9eeV>lKUfEUoxt|{J@H3M<MaF=Xhr#QYRj<mCTJpj-L3Z@R=p@+cYJkt
zU-hDV-SPF-e_!>Y{E6x`Ubo@=?Vk8E-RY&K{vc>Y`Hg75>!I&D=I6(cKm3nOIi~x!
zHSzV%$$7T>wbOF;KTi4oTl3wH@%HV!+r2K-mkL;>#((qwiZ6DK`);qV&X=xmuFt==
z)r+@37u470X-gBy7g)3=Sh6gC@iw?<%PWfGA+sniu|9&7k3EoHlvFuDdHw4}d21P7
zl|fl=k{9JAv&RplHb7WUjq8jbe<Rdz*EHIEqU-0!v6Eb%T3Xklqy?`icu@!8^`91@
zCK=;eq?+VQcwUq%zVJ?|X^++3{yo>XI6;qx7cC-185>`E7+dlL2W9c@MR~F1*eSj-
zrpF7<V?ar1BM8N+AkeZEoU-6l|3)U5!_K2mC#4miEcnzmKE2p;1W9~)wXAp)E%L`;
zOFHpj4N6QV_R~Sqn$7EgAXkb)uH*;WxW$8f#x2Si`k`3Xaf=I<D>g34x8)MND5ep`
z5{$V%${z}jzeuhT1;<|$(};qdV~97F>>DF_1X7I1#UBg4Eed&b=8hX(JjxxgDB{tX
zY#U8HI>DnR9-ZJ(<AyrHqFjXoq!^G%a!#<w#I$9QcpYeB*$D=n-}tkyp&vmojX2oj
z+?b29<j-qc<{vMLX}s%SFE#((dIfi06m+{%C>90Xt_Oz33sQRJ>AeX3$*uPyt&;<<
zg(L)Td~zZ1I178_;135Ue6sbLqtjZr2*HLI1>1R1;=?qaElSMVxh6{id42C#q{h*P
zNWkQgl$>-|uN#x@>~v$!IEz6FmN%|s8VnZ!3;81C6loJ&l$@f)QXWBwCKmF#G0Brl
za@|;3tp2MVQ#`jWwobg(pRG^KsB87FJ6c@AE2q<WATPrDNWW_dV|f>aOPCIU*01Um
zlj*d%ElO<ej&(nR6l>IL;ZuoO6fXRgTe(lR)&liWJ&tJd&nHGd*ovQX2}*uyQ79-g
zcU|`b%^Y~&y5zw7)+NWS4gaDn#`oOsM^a)-^|tj&#_Qs}@~T-B3Rm9si?W342uiS8
z7w<JN-gE2JVWzLY>9FLd{2hxFd~6TJb|fp?UA>}3iFFwNbzr|J*V=aNQjg^8qExS7
zU%R$m!M--PUU^2fxpm9Y&8=GwPukDr(P9t!CSqO(NHGOhkB;H_)+>jnyZGv0US7rr
zNWs0nb<5%Pty?T+Yx)?JvzB}QNK!gfYS%*}YPNOD5$Vvspop|Q^zlO>aP8c><%rI$
zTQW=<88p0RkFJ;tH@rRShRfTYty_%9N-%IQ+g($`oohG630JONTd!b|m2lwhd{G*X
zI9!xg!hw6yro<bUpiO=Xcb-X8yViwv1f@C!H>@s%^VQO2FmW%LPKJqF$XpluOcm!v
zLMyq@w=T&9soG1gjnVgPg&S-_KIbjZ82>zP1(Uw^BIFmPv&|b{O-<-XQhwI9Zuwbw
zSYL!_;OLzfCVTRbPrdoYvGZY%w23VOu7!yM`+Rtt;ECBz=>#)1wPTU+Gx49<VdjTV
zsdy9T?<t{}IB?HP8+qb<JtY-0&xJ*)ZXsPKrDBCVEbg8u6-Sa5drwIPH2Fn=RJ<rT
zN&ZGou%u$(0zIV@&J?0WA^YLfIlER32jkhb2FrN3+J-0AbWD;8{mj?wB5(yfT4ZJi
zGj(>%&Q&yUzsE<UEzXW_==Ol)cu~lc9xc3QW}auSztK*~Bg+)NvM3|kWJt<0zuA&w
z;fy6ITI7V`6Ve*t^|9xYTv>b~B=7*ChsRh?gPD5KvdEJiC!EM7Bq#jLQ}fGtFGn-y
zmj;(|JugZdL7<T2zIjnrYdopv*`tTUh+VV@nB&Ovbx|<K@qkI4a~x1V7YRQc{~3H-
zuc_$JxOU?PoAjy}H^$y{W{n$+;veM5b)JkopBIH=y|BQhv0nLXvqzfdxG;QZns}nE
zHpiO*7j{bv$wymIXjd3{sxK0F`=YFIyeQdv{Y#QE^6p<0j%?%$-foFXzUW>Q9TvmU
zO;^as?YJoXtfy$bNNBDlzX$f>aQx`tUL5eM--7};a<|(ZpF2Pb=HGl!jC{Yp2+?Zz
z4V@DMo9os&F&YP^r+>Z~4K|r1<mmLg7}!%cpO*t$>JA;?04an8kMpF&50@wyez-*8
z#1E$=97)PGq$r$N!IR%U<zD*?YjlQCFo<MPLLThWqr<T~F5N7iw~k#>NIfn~dp!ZL
zbA8=8tIZ46A^URlJ6@)Scf+FORb-cr4Foe;YW@dE!KzF0;;GNRDA{`bOHUAooL>?a
z$4@O1qy<k|yJRTxiLvQH>I2awx@&yo<gDy_J}@>NBp%kNMHtzPf9F~#fTc+eJhfqi
zE}E1an@maW7@KY%MZTC`xrlVIOV5`VCC4TslXvh<x{CK#OXrHWcvCFOKzl^1v6(A+
zq7~u^Rc%oq_t4FbB!zfRDYTxWu_=WXZ|X&%l%5FDxus@#YNCro*}+vYrOx!cCatWF
zJ+FdUuiU==y9BA<2o4HC>K9rAtsJ^87QBOPcHM-1V(hvpI>ct`rs%n&ZRjZNm~ool
z@`o_xp$&y6r43nC+XKqnC^4cDA+Sdf41bbq)-b~{(TWv(9n<`;v4%spYrE36XE@1|
z^y1-gN=b_c!y*j+LA1d044+v9DpxJv>^5j(b-XMW1;W}=1y~d?sig|AC<Z%m8{njP
z+XgtP?SluW4JmHT!L~-dqhX6-Ft}b`=WX6Mt%GNJ1>*6!DCAR*N6w-^9@}dxl_{{{
zE*VnoS_2pK62ME;(mI$kG(?$6<7>D(T-&T+2fZi*?O1bv_>gPRwEWQ;=CjSpfY?&6
z@>}COqlK~AgR{={ez4ru<`PlEwcrv_JX05CpdGyTOFGeul*5<F(IADcTfndreey`K
z5JFG=WJ$W=4saPM3_4F*C2fLl)FKSJjmv6bGevZfAiS>^YJPZdS#5xGx+?H)U6g@#
zEVb8L)g0f_MPWF@U3&nbw5AZXMTsTpG&dQd06iYC29a{99@g*~>7dr|8C@P`*wAI|
zG{cm#3lw$N#bG#WU8)FPuZzM13(waVX|>KLmPf*VK3E+I`$@@=j(XluAN@o#<f4qD
zC*-2bxp9U?a}oHf(0qGdH)l$ab%{CNsEfkih@){4a6X(fT6tccBkiizb*-E!3yXq<
zI&qJ8Ncouttks6poVcL-)CGO!S!ZQmJ)xj>J(12HEePX@1;-_m6pU`7nIjvTu3=<)
zWyfoDwK-c{G`)N;cz#-!i02b@5pt*<FVIC9XorY&9{Wef6LgVsw2PAK=g~@yu~So8
zgg8%R++CD>t@e)L_6HiG?7fSUKa;Fp?PNafzx|n*VyZJq$r*B^EK2g88|6ibR?GR}
z^64}N^$ZwXV>57Rk#c^xIQru`Mcx~WkW(~$1?NE6lyhvjZMx}GJ!W|7J5bvgvfm%r
z1v>4G$0DVipZbzv$xd+!%9u>kFG{q?lM`otd&K@T7nO$UMTj{!z83nOI#y%0$|A&J
zk*dc5Qp~zh#q0O2K<R;YaH`!9s6~mb-EaXNFA{{I<xhklH15;Y4mLI3MjfwElSO<{
z@-5K#Dp{nKzmqe(hdObF1ALpBV(LqaqAB85Xj4<fJGV_t(bb7l^k^AI+i@PYNlCan
z*gy2;4*qk?clh<K4SkrWL>u^WQzw4ea?yr94kfh>eH&^;b3RsjhWITCzYQI{xxRg>
zSA6=ygR{{Zb1V`&HU3SmH0?9}qI7i5JKS&9czbsG(iRD;eNj5-DOi;31Zln~Av#R(
z@U-+L93W*U@BuL()~IxL_=SRkpMjFlGJayoDqK9)nnvRgEFC%U&jjV<->?^j{$d6}
z&KsI&(<zj%%OK!4VAyChE%bD296{n>8hddprd}M2=~Fn+GXP}~aCLMz5v-kBC}^7P
z)OhkTX(tzIKI#Mq-6F9U)@nZN1(C&r(Hfqki@-i9Hpe1mr}*zMu9=Rzndd-Ia%?l-
zGDZVQpSZA1PMHpyxS38x7{C{WgB$u52A2|Xn9*RrNaz(UNP`?Z9Wg3F!RR0jcGIfT
zVRts8KC>w7Hqd4#EG^B*hTOR$NFxZ?{<EnQwjd3|cB8fa{?b?t+s`fy7LN|o@f-OX
z(Z)}vC)_O6ram6^fG>NI;%u;sQaEsR7=4(1-0Ft0((-DT1e3N_)0sU|cQigS79oy2
zL%zo%#4(Ad!{XDJ?1VYcLW-o*)n*@Xd!#8UD3}6O2RhAOlxRRO5c9GqICJoteo?aZ
z`qv=q2d@d!6+la;4bFt=L%I_X{9?w}&!VhON05SG>cpv-Izi51q_n|_VE>yOzl)Ue
zIJ7(`ge$uE1Hq#Eug61nwXra1Z9I~cGxS@Xa)xPcl*6#&nHrS*s^bm00>uvyQc9fr
z*e?hPFQ@KUZw4fE=XyIHWs8z4POo)$uDI?mJSZ0hE9&v9@h|84F|MUMGy`Q<cJEjV
zY0I?lStkcN*H8Mhvc|fYz-8B+=s4$1x1t-5sxCGdR!kSA!}M&hWp?Lg?iAzB?JT!i
z@7&J1O*^-9kJb(D>TX38OHh&(9VX=<<zPDe9|mt-?|AH6BP%-edy~fB;fh=&@B*(S
zLw4k9hji0))H@I9oiZ>!o>`rzG(E|^^N`lP-aEL(M|kfI+-ll6h%pZmW`PHuF~_>+
zTf^j}?zAp~awG{nj6XObos4u@lw{vVi5AwNJ(N&7Hy0_{S(IBDiddBfThAM1S=<&S
z*9pqH$)n!WxcJsiMoD>TQ@N3d7wt4C8ci09V)!;GBN-))hsHxtjwB_c(qr43i&bos
zQCR-QUAR-i>SHEVsx>j9C@lvA34tQ^PDux(Ndbdmvr+8fq;eC|mbMX?Ga8JdZAWRO
zk^6G)J!q*Z!mTx;wg9tBjpMw;OAP;<VqH-<HfsLo5cj|s`2IJ3o~{8F1<cFwb!uou
zATP1hXV;uaX(f0mA7`WB;jDshf0H~KQ{E^NyyWL;C3s-^SsN~;{;d6mjd7k^tI?RE
z&9x{JDw4MS7Q9;&aw@m+qJUE*q{4ROQLvgkyz=yDG@fjfsk1AOoEBMjIFt?$-Vd|(
zjQubJg=bla)gtgH>*>2}Fqi1uY;f7*a0P|efn!Q=^pbJ}iPu4Xs?}|PDYUu`Jb#$V
z4jl*Wfhg!!Y0s(CpNnvcfn0=B3<S^b)NhWw;#O1lWDbU=58a%N#t)+xsohjxJIqAw
z#vbI2ya*i^Ihb`*f92KQZtlwTMjngM$F2{&D4V{}?jbD$jH0Q7ddG`EwIs*o>H#L*
zn>K@iQJZnJ=D90JixSQhDNqf06QyJ|xYwzO1;L<okt0UVyI5jU3$xQHrI0f|r4@3<
zr?kQ}A2u2>q>nb*Fr>7$>rpQVLPi;<*4r+`>y}#FE~+{-!n6y)A5^c~MMZ}S_>1xZ
z1wBVb#V2+6c1?A_`d;&+o&hU;g@2!`nZc?1Yhq=u@Ew5lyLcu~v|7GjuzVMncj}0^
zxW<z+>Fk8XqLo4qr*?6LC*}gps9s-<Mhd>rg2GOi5LMTyl{qOEQ%l2_DQ8eGQ!LKp
zD}~R_Mae#J^0fJ=6J{{$WjfI2yA%_cxBA4fb3~2|J7EFlrEXY&$%jg|@JP8e*oiO|
zJ?Iw+J;?Am*o&j3LUd!aLtStut}Ge!!67+aeK=U2(6<KLv(tk{r#%Iy-Gm8~wi0B~
zlr@D}G-YvN5)G^}IX1&)q3tHJX=w1l;7r{(I9$$QB8uFaw3MFWB@Ns#Gev4m_Tcaa
z4cs(VElMcgG--WCY7M)Ackut0Wo%LSEeIx@{ReDpAaxk#z(Cq5WU6b32q<%2gPr0i
zlV78$LUzGMQ-y4Y%+V?HB64)r59PE{B50q?^c-3>@f(l`**RBw4mxr1;O3XXG$?5}
zZW>EtFAfFoBiLq-BxNt%oCB6^-II*8k{P%SQ>T$(A(6uagELp_R5zR>Na87@G?RE_
zxITh3%Cz0QOxxfEEg3M7w=`tPfZiN2A!TK6jFM`)S{#a;to4l{QL^Z-be)@C00^#6
zbsK26v3U*}W1i$)h^(Gd9*6@Z`Z4(N@_q2*<@?~b%lk2sQ@%M%8qFJc?Ik6BA3C+2
zz7L(!-srKq$Z#AT^6xapDai@6l6bDM`H2=G*ZN}cU?lpSbTu)_N4_W|`INVcSw8e<
zMT$?@{N(alq~yNN&W^X2d}k|(Cl`S3wbpSO%LUgujNCdL`vvyXlh@#?UX;8QX)$RJ
z{n0Pd<{OM0pYWN|f4C^=sic!}CH7pS+>kAu%E#uaT%`2J>-g%3$3YTJ5XR;aZ8V>x
z*EEMl@44|y^quQi>hzuK;R63JeYi&^0KtjNZy`8Ze&B}w=_?LG3WvPOi-1{5gYOUy
zIi({bD2Ag$rk`+AbM^61=%qTt51an+#^^5j&l`;{a<acDa>1`upp<=i>04t61s(Z~
z0bX4PMT2soh=7(RmtzYWi1eVb2Np0pC<6~xE8+vDhKlg53|=@uO71hdq2VB^2#7`l
zOrIJsT<E#QkEEnXL8-!lT;Ui@4XTihmE)7cL0Cs?JSY_Q(QrLgWJqKNoqO~MvwkYz
zB$9qI0z;dvF?>R5N6RG73~X7g3~yrOOM@B5PwDZBt&;wr*eYoYhMU9L${-%ouijAQ
z6}Qvu-r{;16xEFTS*`ql-t17B5j=E&gis;<NG`pCkX{4?C`H0g1pUB9-1ty2*S5g(
zr=p%3o=_DTwI~d^g3#up??8xEQWSvI@B*$7t%j#{g>f~!;SuU}fRvxnTM4!a#f-fO
z2q$Z4%&BOzW;_;L4;aH^Q&DRx$0viH^cbQ2P0??W85B2#Uz!{x1|ok#&rqCQL%bCu
z@m3qre0+hOuoo$$Z&7l2B=9FRQbh$aTL_VZ`9sh?7+$yt^Q`#8)$WKk<mjNFDvI$~
znL!a1%4FC`9@>H-kvdfIl1v?{n94{UicPGb%XTs%RI2dFh*0UhCye-v?`$wJ9)_P)
zG$<#C7#)R>u1ukf2$i*nM#rH%<Hm5VA-m2B=Tbl`a*HbFwWSGCQL&L-l=G7v<b;_@
z;kApBfu*kbL3>ezZsZ)riLM}CCLL9zZzLW0tytjIPR1>HUkOF`U?A}U3Zst)+KfF;
zo<vsB*dvw~B|~c=sE5*uOwa>HtEA$iSKdvAmQ(eQyqgHkhMs>Y@dnY@@kb0TcYU9s
z<vC)^FrvLz)=Ox#6%M{gaojUrJQ86loP4Fej4j|il4D|2H$7g9ltb5KZbp?;5nPlU
zIiJjn(h)fi)BPfa5DKn?IW-k<A2~G<^M9h1@&0(ZE<(x^;`vv)%!9wUG2>L}ln}58
zV@nw@n*R!pWRYTumudJo!j+(~C^1DPF)T{#)JrLt2E-VoLj(nuBxX!7Ifv;Kt39@C
z3!~*w85za^DWz=~FjgwH!+>g1=^v($DdmV5Fg_}g1nE0lvWX##>Y8W_W~m$?B=4vJ
zF_owCT?}v)l@nvYqCnov0aC84Hr5SoQu#MV8>LcoBI_qUrZ_yinAyYUg)#O@2|)%(
zg-ROYPa>!2NJ{(;vW`|eGpi(604}KHB@Vt4oDR$QETuq^2}+zY00>lWl>suK@~?us
zdxn-}`hR6{8RNAg@5^WcWm?!G#NR7(Y*CnS24P_AmQv6{nqnZ(6&7J2gUv1^KUCJ6
zF^o%@af_0(y)|;EtxCGH%r!r@96fF_B=RL?OY~y`5R(IAFRu@0`rrXl<W$z$z)q$-
zM1#?^aup4^;F-%9N6NumM-Y(es9`ZtQ>XYu6tVIu7v&n2b!kZQuEfkm$>H-(WG+!9
zcrHo~-*vW3CTtG0GOLoe-=d5y%{0#I{CjSw$q2&-HtZK=OJ_COZI$x6D9oIN*wB(&
zxwD3}?MkmT8h4d~yKbc9ljLB+3I5zQL&P+LkvRO72)rn5Y?;DFld!UhZNjL7l;fmC
zk~Xz4Q<C<nMP!n;X%S-sMc(s)cBK0&H`<h?tqVd~+SIY));^VjeIzBnq^&(2DdF1N
z%G0Ld&LU4+*TKYdyHds%DbvASoXJe>fq!R~c8LnJw1=)hn6Rm%eo9qQ2E3(FyK>|g
zA?Jq!;0RJ+C!Cj9nP5~($X|ryrId~dAPFV*9|2{3CKSNHpX3a0$(Y3qAF&^}O#&EL
zlt67D2EigEXu~P)1Aj?a1~!Qpak3KuBNQTP5e3-f@?Y)vw0!7`l4uo8s|Iu<x`vl3
z3wR?rYz^Uq3Gc94`DMaCEXvpbA}o`>4<Jaa=3=$nhlWVQLZMh1X?~N2S3@2+kSq?6
z5~_mM6C1z|5+nvyTcKvyAZo;92y7_CesAa-2KRsvIt=OJ1>#{D)L1wlM=0O%Gk0|w
zG8be!$0F@>T*(RMXf8rrUxiHaA_=<WGj#r7gWydp10@Rq#gJSMl#~OcA)89JV<d7>
zAZ@V#Sr#FfBG8s&y-%8gs@Ll!k!PB^<Pj#1fMuHch9DD9p1@|4ao+}EdwlDbz%#ye
zOPCkmdL_u4%<k(ImdG<h-5kss>gGAbxpfLLC=i}_-)%TO20u$-`2^*(4eux3jWNKB
zk5Yp(rhtRidou@E5&<lWRuTd5o(HB>8wBrpwoVC^^K6|Gnu(Xmz)>o2q$A$O&$A&Y
z8T>v3Sz3e*gNdo0h0_$2IMD^>#AkVvS=SKmTA)yiGB((#)ee64&ako|#dsa9K#}sT
zM}kPz`Op9&l><k1e*s__kN^rH3r2_p&@$ix6u_1t;uauW2S}rUy3*9~+#8q|jUU4M
zG9c6yB-jxozlj@$Kgz-1?1kf9=wpWH-a;p{agzBoc80}feM~rKLGfEaXoiU3f=V+u
z*8rz>fE3dL;F=8r<<(h$YeEJ~T9btAb_6LQ;-qwrv*6*DMJi?_1UYkJ;xSrfQ36?u
zKy);06<D1)u!w|b7sjyouG9tq`W*#~w@5k1$<}Ebt{zNm1--WjIb{X5n-djJ%kMkr
zU)b{E8#HtqJdOn(2z%eLK@5gbFuwF`-EtM5ty@AOYNZ{Jl0-Z-e6=tUX@4x##Gs5F
zS<wI$0r<rOq{Rx_<d}wBAdZG97trIPBw}P|<YIP_2H?0qWlb}<Rtt905H{XqI<tUJ
zJU0AF14u<-Tn6RbaWD-oT7YGeLO9I>gk+6$I|l||8OLB026!hZ!I_&lVvCX!)r)YW
zJQ_}LYo3zNJW+@^8b35q07K@VjY9qa(@(IbG;T9$13wf@BtB{pq{?TcJuy}dGG8#P
zpd1@iD-G*~<{Ff9M|>^HpycG0dK7YOkTz^twq*zODLh(A4k;Js7b{n$!HrUkN-)}c
zV-zVHqY|I?E=DEc*%%f0w6!rsxHa6c^A-Lt{S*Ze9F)a7f(Y+~VoNyP3XPbgL@PF=
zJ`|d9QM@K8NaTY}DLyD=QMk&Y+`T@j5JI*F0`c^@dv4qzW#h&g@~v06D1zJ2<nMcv
zBvLkxEgs&_#xW28YR0vA&W#};Y+|q$^s!wGK%pUwlJVFk20>`sL_@%yw#fl0_b#^?
z5o_;)`_w)g(W+fGBFwe~CyuSh>5bQpdj7J<o^6lC#(efI7W?@bJFk+o@3SbGvv0FF
zCZ20QTtMk~HS@fAuI+FMM%){-LaLs7V-_jNtQXU-2(&ic4Iw1YvmM6kzpe1?I*duF
z!#G5$mwf~$_KFOz(|9drKW#gW*KAhId7Z|wbc<BC)%wbcX0O|7{bVm=2X3NX1`kKN
z%p%owb;pRtc3s^uqOo09cZ_Ik*VU6Fn%i}M#)#&2yIYLt+HUvc(Y4*~%WS+TWYG<V
z+}mZI47s<<d<|{oCv>SFagZ<4)PRB^c5WI=x7v-V)kM~Vh8Mip3>46hy4lt(m{BH*
zHIgz<09U0eP90j=5u}Ssqs6D|#*1^LD>|DBU{{hC6~tBCL`p)Q`yCO?R5ZIHkEx7y
z#Sv3s?Ti9GK2oU-N@=+{>-nx4cdIAp87=A2$+2GMh|~kS!dt1LFAASsC+2wT8I_9u
zu}FMJotPuL<P2rX#Dk(M)RT{n-p;h0<jbNfMw3sMuJB7fZ@MBY`2y-qXr6o~Ez;Xl
zsy7|Pcx`osH}XZcDADQ2H`_`Lsy?wqib3SluQ#oIz6^VFJ)<lwCyP|Qat^Lu4ResI
z0?*WrAV0igds-j%cWxw2sZY*es?W&GtFb?)`(}KA8?SHHhlWMCwr;ryoADu9WkZP5
zBMlD+Nx|>u-H6cNEDs?qZ<dFU7+4<4UeRTGfJvjj86IK-Y=(zq?q+;&i2P=K$eXeg
zDTG#-zS$n~;O(33VeQ?O0|-|-%ssvLt<RNzQeAR%WqxoB&&y<(Z<Ix1w}Ij5845F2
z?`57G7++n@X%JJ^<fn{gky)v3F~qrjD^|B(dTx!G`I_f$yz9MAgE(v=?enC;FUN9k
zoyHM_>XXcRwoWmUXX}&9(sO5Ak)cX{=iT1Dq#@3*MNo$vh)WvQYpuI&J;F}J1llC6
zad@jP!4NM|z=gS4BXB)>2}3etQ7GWJ49g^e*WXGM=0?KJ=B1~>HoZvPf62s^j?8Wk
zIKjgq?<A*&e!xl|Y0f+xp5Vk(j}Q!(!VNoo_iO8sssmE4KV{KpR`#c?{=G~W@C@`a
zU4-wT2i7Eg3HkA7>ysas{~BJ3?msv(I!r^yC!8HYVW+(N`_Od}9+N)kJ&Df_X$TXj
zT7AfQ4ZjTkpy8v^@Y1!@%YcFRGLrQVkV4i6?N#}J?ur?rpQ#VY27FN+CsX*9aEK~K
zh+eHeBpdPYUeE;e2;sy;IFKA?i@+80z&j{kTu5@6Jm8%JXu_u)cmP&7K*|})d<9Qn
zuc#q-3;UqIF*&J2BcAq0P{{j%59!pvW4{mHBk9@fL)QqN|9vPVnjX?VrSYc|wWIPV
zy{yE#_>>nGfEclZ;HzCEGA7T=MFC@QAe9jXZs9(gM2s(jDUTN%%zbvW@;kC=&-iZ=
z6&y9Q*94(>mq{i3;H-2_KY4(Y4E{(QDzgLyp@Dts@c@r}pNxfo)4tEC`9VpYGIplx
zzgHO`h6nViD+VD1fNA+eBvY>lECeO=S<X;IF7&BWBuyTD5)F|d5sQMszzDJ^j73?R
zmqMu!bU}2RPex`W0?uIcMjX-?MS<}g$08v}1RBq!g-3mZere$&)@ijl64c(lbY-9%
z1HpijlE0#deT1U~o{%C~Vrf~f>QGQizhwMG;7h+47!%TdNp(Q%Odufbu{B4+B;iZB
zXD*%s0jRXFmpJ2zk;r(4FrP)ChaI6n{nDc`f`t+X>Qm7~owc7CaMZ6_WklumtCkt^
z|CiXNepUPoE=|QYrHLTHul6Xae(NQHP^*6Hf<QP{zokIjrz$LdGJxv{Y%WtwSFrn*
zg$JQv{pO<*(PBga`&4|@5l~?#Ng)fjPJ)O`TWtoN<x}I9a3Hd6Q5dI!@V7uQ!}xGt
z-2<(hGHpNzvs(m4yLFrtx2}+g*9*)wM!SWu-#Qf#@YiqIgkTv2nA;vWNW`~KMHem#
zd54SUrj-amiv7-C9UL3|<cM_aWfF{7NFvpJGSrJ;cAtu;48%LUtup2^NE|=zjEd00
z-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNxa@|h?
z4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz6cH_a
zEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb#@^>6
zGjKu`wVmCRkbtP|033ab?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp;P*Ty
z{JcIYjD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z82<o}
z<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@=C<H-
zxrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix3uOZ1
zc2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^q;MC|
zfqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;6Dd)P
z0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUgh3AcK
z$Vc-^SZ|PpjLym*%8)^?ta4a52`~Ps3^}h9a-f<AC^^moq}q99j0ZG&qMPShA<Ak|
zG8r!=%9Z?mG?+MDVO&fW^h(=CLgAuRnqqv((TK@;s{~4{UaJI3ET4k9m=Ec#vM6J%
zk3f>gjBuYco!-c_T$HwDV+Mi4eTZStWY1iuN~y$k(<WNEM#`x~#;8{gb&sHHhn1E|
zr>l*jBQe!wxkdJBfc7&_HaB@wg(v2~dgV+bPu44E8o9LIxDh(n{bC#fgR53m0Vc|J
zOp$q*$n1?m1o)I=maqUG$PiwHiwVQIib9w`ma%VH(jzCOJk1Vlci)ntC&XDv(GzPX
zbclXM-34+gj{)yABr>nsw=C&A2Ykztj=6dl?gMO_Eb(xBD$U!sH0gXoM`;Lj%j?a%
z_G5=O(xKfk<Z2O^M!y~{tIZ^Oh)9ngKvMfEW)2y1WHGve>5v`Ig6E$~p!Z6eMv}cN
zY1(lv^vZ@qvc7jdRhZDfC`1Y9U?)AC3lw0r@<)NE@0COiSOFJ^I3uvU7brvO@!pk0
z=TNA;3rz?>2VSYw>9}`hSHlnPy?_~}x-fwopbOrA1ZG%OK=^U!5xsyJZuF{D)Bu54
zgn<^j@Y}cvIulbP_mZ_nJ{hESL_rebhEO<^vI;kw%gRsKi$!_E#>gKcl8LDsu`wVb
zI%NRE;c^ZTtK)EC;seiP5df^x(Mh*0awVOq-s!VJC6>euaYz-9AvjySa=+7+;yw5R
z56LR@0*N2UNp|Ii0|jLfIF6}a1MU2XGG~$W=$)o%g0e(O8T<+qgZ`kEJ#=QlIpF=#
z0^J;&pm1R4cZFaQYsNb*nZ%=66fO{|cX;Kb!vG(Yl$iv-i9$LM8Gz%sLOB7Ta|8)s
zJ*Hkn>oN7pzrcA>x$LlX2L*Rd8n(T%+hN9L?VnFV2d(-*XhjF<E7LhNB1-_Ah$V(T
ziC^SSODr*t+@;b01t}^O;i`ri*cEyTfTf^7z7vCqMUXxP(X=R*;dI1tayp0z^%RAa
z@WXghxK3M`Exlq|2`jZoL^^uZEw@2{Q>`WkjH|*0V{xI#jJpoxFs4RPs9YwPGFc|-
zQ(#)|0=fX+R#1pRmYUxp#aK`c)#cD4vX@uVKhVDxC0*tK2=hV#0EC#!3r3tV_t5te
zhK$9rK8aFxBnh8!_8<%yE(h1S50hq4@R`)N4p+P{Vb<Jr8(dekfH?+5!3!S_yFDQZ
zl1<p|z5~Ri=;>jU*33oV1Rh9L-X6!NpyynX#)PMHm9Zg&T~KmTFfKYAe+QB9ywDGT
zmFJ3ACZL`R58>w0>ScBV(~0HMK84-q&iKm2_lp{9nCH#4)q4(BzQg5rWDuY`G2{R>
z=&t+g9;)T`DX2ovz_<e>cFCWZSSj6ZfJpQLZ2*j-GYtC>)}lMDC}~yn!gW9rr@Nk(
zH#f5G#2aDPt76@!kRiRGAnx47x-oC=V!coSH|bv5J1{BTd9MPt(hE-_?St;RXi*8o
zT~T!e#B{lA37Y9dp#ZF=yB-Bk&w_n9+JxaeRKxF6V4YsT6#(>nr*sS#u$y^CAFK}e
zDKt@c8JvJP>IH!TRML0Kog0}UxWqekIh~1#`c6syNoPo0RrkA?4xQcwxCeYzcd8W+
z9(*nYKBQujawHI}yGot_DE6H)G2YzB1e|p_$pK1x{6M<#?eS6AwtGA0^A3;ejOQ;5
zT^CviadzJ+<P-sNot#2UIq`hmi6KbL-**Zb1H{}ZM&$KCd|_7-12Kr-DOY~{2KR1F
zixil%-Boshrn5H+mog=3!79JCG&&sa0A}8Pqn%nNe7cz!S`;$$hCC!t^fo78Nf&DX
zZ1+YW^N6AC+=x4g?88a{dg+})hGKmaL;Kh%Q_~`>HdUjY@+N$=xvci_LCo(>S`jd|
zQ?%hA^{w_>?u>%~<lAOxKkhgnneUWdTMP+>1V}Fu0o3aRAj*235&&Y~2@NkNoi+q?
zcl<{C;m9H?{5xgvm^(fSO1{oQ!p*xPX^2U$6O^#^JY)|++t;znc(6LG84p$`I>W(q
z;vYiV=cPa>e%&O*>)&o0V*1yG1l<3lE-lstsH={(1L`_tfq}X(S%l!o8<j;0>Jnxl
zgSx0$?Lb#K<GGyqCZCMxDwTi{U8Od#)B=jj2Bk~;$Rmr^4FN>4sza$Pto%?aP4`lA
zk~6+ce$t9qTB1}ZmY*o~iX|#a1M5_YN=-wli&EuS4MW-<qqk7^78ELtcr3B-M(L4R
znuCfaD|eJC+G)&?x*7#Qa%^P6qfXe8<CNwJMhxmbs#rCE%~mQl>Xo>V!C2CyRCSg;
zkv7keEq6Ke7_?O{0t9UZB|G(cSl~;&9u}izH5u1Cfs=5(6R?^ihMWJwU#m{Y0036K
zl30I64=EO?skauwvFbU-IyXT%KwuvZ{$d}j$e@1PwIbASJE8hmnWvtZtlm@aP*(V<
zw<^m3@iBX-P*6R1GXP6(Vg+E;yO{x4^|nR@qvL~5@=ujHs%Lu^LaKK?YbDj&pY@bH
z?4qo}l#-{q0JEzX2k7d>0lIp@?8h2VvS6@8R9QJ#M=FgVEHhO`5|pA!0}TWk^{QZP
z0fpTlz8O$OlMM@F!Kib9#6B3?%`P0;txjYn&DswkE>Om+>`<)qRmLio11p0T!mi5Z
zg|MsLFviMbWj#Z6vNEu-fLR*gSl|o>x~yK7=R7l@JM9#*^Rbp1ErBSuR;EIPU~T3^
z)@v)1Ba6DFNs>k1%3{gFaB0-cfk6%wOU(*%G>x(bT^UbVr%v|OBP-dJ0hYz?%1X<E
zcxB1Wl6ht7MNz%o9*oj^o6$IfvdXN?@_l7`W{E$Trw@?QtgIV}b_`m%Sxm4D;Vd{v
zQ~80Cgszl(mMtuMJ4+juO&-+`%WRJVi3g4QAa$7g`E5EmaOB_gaJarr4~O%ih@y_0
zH)0iiEN=yiLY7B^Wh2Y$fzpzPJR>YWS$-3is4U+K%UG8G1%)m*9}TKumLG=&Gt1S(
z5UX+rW!cU07agq1SzaZU?o6)}OM8}AiXm0yw?a(SA>S5@h?e&Ybw<lU#!{r^L}Rs5
zc-jt-a?x}cKK4=Gx)m6etlaCS(p{Gu`Z2O!2i=ng$5u!c*Tz;%71xGbk}ULkl-rWk
zV9T}1im~#3qNc3eqpCU!7wQ30ADf$%<!j3myQ<sLRr{&xxANwqK<=@5d|5@eyuz%s
z>&gPkTD;|3X0=}UpL1-G1v#lZk}~PW?pYYP+}x}iT&{2x7fxR}s}Gkio%M-bQ06FM
zT>f}eIX=o~&r-<c)^}i9mFqvtCs%L)3oIjm;P|L2%oSyTGR<2g0!uk(r~(T=S0n?9
zLmykX17psz()>qOnI2n&1glV27zLxtBGBUaP&Mly<ZgAwS1CGUmA|gw4OGWQfX9al
zXdhb?2&-&YqzKD!S2PK$c~=mM%6(U)3TuK_G>a?ziT6C~j8|9;ijf~%><q)U6kg+5
z&8h-$7>`v^Iw*|JNS<I9Y91-thXvMMfJ-dGULis((#|lVLxtQc%!sw#8Jfgu@UC(w
z45_LJCzO>xwlFAGp07wLR;O1W6${u`uoZvtsE8~_&6SGUauigl$Sy~*lnVcHltMWw
zJ}mfB@nen>CJZoJ%+6?~u4zInsz#url4%9Axlt@6*ouVWE#v^q_9~yZNVzoeBkin^
zJI`Vs6_kfas4a5O8<1@(yf38r+(Q5<@f9ZMD5g=dgxE{R7I5f5ugZYL)p7(hVsuS0
zj~rfCyyNl7BcNg;y)kT)wnT4?+f<$V21`2wFb|zj6{Q&m+qp+_I>4<E?im!uZNf8<
zM`*@vLf7QEn^C3S7_vDz!>OoM&Ja)q6}Y-c2wdeXuPyS`v%~|UV?h{<pFKcG9_T!0
z;Fbb$<JLTl(Ym1Apdja(7j%XF#w|Yf&|u#5h#y`Q<eDPJ_y8$`U>V;T>Ps++FHWav
zk@3t_h#B&nx_3rXPj#Az1?R2Gr$U8S#{(mRsbMn7M@o{ksrw$tz1~hM!d<c6-Wlu7
zfbjL&%d{j#jK{MwhR0Vm-=_*Y=Yy7k>2%R&<oW^1Joo5!KEW#jp3ioK$%B&N?57sb
zBX?QR_Ao0{K)!ot#D2CEu#Y)ABEl>3pT?BR4WLm*=>xRjWO@OOKAC-RfD(x&%21#Q
zs<If|hg9%rF;{{E9~{`!=!eoJIC@BraxQ2oti%l1ACF4jpcylBI~=*4mHV;mt4I#X
z7I@~m@?a~hBoi8zD-DG<>`GOk^_)+sBS~Y+fq|c+(q!m|sazU&X6Tr{^l*YY-@Q_F
zD5Ol$0eGb^yaQzYI8sBA7j%FWzo6tH2g+3?7<t+om6ha(onqRO4@8;7BRb~;jJV2l
za_013eEmCe_?0o`46mxRDhCLj@~)iO_ZQ#k&U}02YWZOH*{Eq|`k9W|!Su8IQODRM
z8pCsJ(i{eoh${JPkuq;g(!u<8rLg&6wwZ4IG03c@c@K2cQL|FcnO^5iCszudGkg3J
z45b5+t8)1kB}9tpem(&7GNqUfB;O!G@JLeZnOUokq%>t3I#a@@1OgJz?8GBTnfj?)
z8K%|Bb9AJ-(omO_Omn2U$H$&J>4Q0$IzE`$trW~fi4@Gi!9mz7wbLgvFll#Rls2{$
z(M8D7rd?#UGnZ0U5NDS5)P>3{ZKbO^47iofx+uw*j@H<-VVzmoN||-ktgp0MpU7fU
zF0M}?YFEathYh%LdL5r&)~~}RTxr4n8qt<F?8>*60;hayq#rxdt@UD=$a7N;^WiWe
zSE92k#ag=9#J!^QX%DW`q@V5FG|a+wC0OemP=d8?4J>aZdoN0;pG*jM<ye;_Fvq$?
z0ZG;_KHxSQn=DM^tCuVwXKs`%K)qoeyu+qVx66^F<Y3!+B?G0I%<F@qfgP=UeV?f0
zSXup!fW3~fL!%NVfCJpEa047Wv=ba>k?z7CaOPkOo?uZD?m_wnj)G2){vw1ipnwoO
z&yT`NaG2T)Pr>K2;Vn2K1Odu$fRtaJ)dgS1vy@5N@-{kZO$Z?32vWjKKrXIx1DJ4T
zYzu_K^H2p)1qkteFEk6sQCx@@&ctqct^6X=17!jpfTPeg960ucz~P8s6iCM+Bo}P!
zlw44W3y0@GXdsJ_e2{i};jEEQ#etgFohUSZ0R%$0B#zj~!Y*;<kqh2rQDQuVK*=9U
ze3pCb76THL%Ay2+gtp>HKNlj)`XQuK60;>JIU?O0%t)8TKPb;#@G$v9Iij(3OT?J5
zbqk!9v3)BMV`z9k{Bj}MtUrJfEz}#oh_@q~0}6W-c+R4v!qFufP__lZvnV;bw)Kk9
zwd#|DGueaUze}mS07TIx6a?Fmec&S4&bf6;VW&BHQN{*d<j}MV;Al~<Q4mNDU(W`U
zv`7gAr3cA{V^vs74lS?nm>ik;u<;&A31-Tq>(CYp{K-+igy2xCodcG6)|t{Ti0eg3
zFsPwU!Cm20`E_kLR(=6;yuhv;&Z$DgT9ky|>RY!Qf8TngFbI8Xk#YiXb1XuFZxO<4
zQG(@d>yzWB*VhR!pc<=w-5Z*iBfhr~#~hBbLM2<2KrV^uv#XWZXnIf}BDkQ>JRS}S
zjON5DAaL3dq(nxmV<2w|t5bl8cX~}+gtw#hCLs@w4eiY@Lfpw>gHU7v#s%SdHcYui
zX@jtH2Pm;VRu@D;+)-2lUkLbi(HcewJWx`jv08Ql+|{xJ->w#&_;y-!;@hdZ-6F*<
z60)D)fGHC4pTh@P=zu}-dxsG8tc+7IgNu+$dv3jw6DM11FoH5%lqDI;at^{8iXage
zB{p8!_y`bj(h70s2sW@qN1%5BGCENt1lkys7>+jmZ3KSI3F2Zca~%Av1tIB(A1|26
zMOkb)1qbWIrVw7G<Aq+BmJWYy;a+;;R|pyN2to`;njYT%g|X=<D^xg~4%iDpbuL0;
z90|}9qz&}b5d>erpbpE!q71YXTl6V@wGC>NE%FJd@q#N|l*AsT-yy*_j)FZUX@f>}
zm_!Ob)w6C=0j!Fk;=PNK;Iq1=Z=l{2%(Vz|g25LKP}p3^23%R`aH8mqe>Y&wj<=R+
zuyINhel18F#;pToq;PPHV#TX?kr$pWNrk!V@ZA?K?@s9&?n0wwUAQ-jI1^yB!U*0e
zLthGUxo^U873tdM9ug$f;+;|x4XI**siP>;j_$r8CufVM(f{)CpN_T9&)2WMrg*jS
zBEL?z^Sb?YxPJWSfB*3>ANFy+{wM$MfB*jaLZYtYjQ$>%UdU>@b<Ksjr^)g^Ss+d>
zk#700suGOLl)ad26|)NTYC9DGiV{txn31e;c}^~es+>z-Yz-yC6Uzc6oD{TXP_66|
zh@r{>6__h>dRGeZ24wjpnlS-iPvOWCUTK86sI$}?UQ!p~)m!=yU3G6-W2P$0C*O$v
z<pUNs+;THamb2^_l~2a^T?}B9o`(uH@Oge_^hRO})jRwG%uXHn1MdLrw6M%a?nq29
z#mC2eH-CwZ_h(@xyoP?-GwtWn^E6?7e_zs=qSGbO7i$^m9)~%PAXuO2G07sf+EHh|
zxvWAs@M1P&pb*{*b}IY=sT9W|F`qCb*P0+cQjxb_2rMk~DfG-R2ix6Hk4m*>Q%Yht
zD!f;fFm7ON19DWwc~D96$Y{}&BcvZ80x1Ni$+w0K8Hck{N_xBK8+Hkboec0s@UDN`
zQ-1ozOjO5THr<OIHUe(b&#(lJ4cknQlz!{30lw172i208pPVSqE)&n#(BOaGA%v)@
zLyM%iuR1_wqns_tn?Fe2FFH~{yE>BceAyA${1lh(dK#8w|Gc9%z^RU;%r85R_O?&H
z%lunA=NBEh!A^A~Wq#QazEp0*?}|{XjrsGAtb~qu@b4d@=sNgm$0dCGHvb;3)%T76
z^DpvzXqP(j#OPmjq?H@T$oDu~-_Dg^bmQsM&`pH<t8U%i&ZzG)!qlnti;g_praFRR
zU+%reTNg**cd68MDE|D5I6Mud>b~nZU0?j7V@q6B9<kpe<N58({YAGtne9?H9M%2H
zZW->z^ZR=sg}fc;Kkvq4zo{Dt_m|zy^X+o@u1#Cl#V<Nm@o07=<^HN8%cHI_qVVng
z%i-asx}NysytRHQi#AO++4prVZTH$QI=IUIeaA&OzwCh0-@F~a2bbRO%b$1DwW{HX
z@_hZpYrB2FCj|I*8~@^Kys}SpVtanwX}j0I3y@kD{V%#f9dLC^LOZ|gCYMi#yvAX^
zQGVGGwy|-tqbT#sj>2F}o#cDgntjt!e$kQ0o{u_Gy%}G1T&QQe&hx#%yQBsEyrYyQ
zS4W2IeR*jt+@4*h`W^!Ju4Vnaqm(gMM^O6tWygy!8OCEkAOZH}`2knE!_@!%LlpO~
zI`;G0RKoA^y4Y33pLe1j>Fkv4aemb)indYN{2pGXUHSY)r_@kgouWO?FFQpD_+op%
znc4A+Ka6aHxYZ*o=-2AQwX4J56}>6__~+fg7ep_9FSXjg?AGDZeaI^&)Rgl5i;kBt
zHqj9jKfmOdkGZMx-|6kX&M%ef)c@h#{I2&v|FYB7-X00x(>(q5Z1_b-zAlD3f}#|w
zU#Rf*_6S)j{PmALOHge1dDM~bnXz?z>5=Dp0>2)<Hkak(^^fs-XkYUmc>za@v9Z8c
zXcsTqqR3?Vq+#)>np`Bc3RZbwk5sWQQKk%zPg*e#mKrNk6)5wxpj8dCBA^jBVc~NZ
zX>0=y+lfl6?UcrO2d9zicD$2nPGR^HE_qR8O?*;0j}mgOA4*ayCWoPNwr$#^ocdOn
zH(Ao|cq0`nmX&MDs8xh67Kim!CH6o$wmN(c7~G~X5R_bJ^}eLUn^Oh;NI9ws;ES|X
z33LE_pp+mfqiw|ocM5}19~5h@s1H~}tFmEGV!#R?f70oI3W@xoSR0j5bOdBpsl`PJ
zz7JV;L{YheAjOE}l-(#`7>a%lx$6No%<_>3NN3w>OgeIdst%<CwYZ8``psIP58)U5
zW--u5251zSu5gXaLu!iFKwxPTSiupbGb?V={><{A+I@lb(sV`ot=gcnu&`dWmpvZ^
zLbU;J0FFR$zZM7`Td!b`lBpe$tw&WW4XccDnf+$TP(@!L^0ig;#eL_jyW)6mRt#0#
z{*C&e-eB=Z9c<;_24yShy4vB3W7XFn!~)pXC8n(CtiRe7m)*M$i6>3zeQf@KSk^u^
zf54T+eSdHVAeryjJPlC}SiT9R<;mfpn!@svRM^1{$lNMTEVqpU59rzHw)M&>?yjqd
zds3NXIidOw-mF9kl`|_RwL7z7PVG@RBz$R6+8OPbR#U<aTy#+%S{|?%a=R5;4i8~#
z3P`$5=&GM`F$MywoR=})R!$J$!?iZIZaLt&bqgl9T3#F)ZESAbJc=uE3x3>1QMYK(
zuYuE`$q$Ki)J0*20sPL3RNZoXZR<7?J6G=Q9Isj-5S3vCKYFWlD!AHTlxU#}{aau`
z$a6buWT@8r7E2K8`W8zNE30UN;F`*?`2~EVR%ufgitHK#9-3YHbJWhYiX~z-dNe|D
zXg0SVBP|CNz41iJd$wXgWBdCMGaGcY$RTBnDhbw@vN;fUvM8Ja%1)ZIm8I?b)+O1}
zw=N;@*3pXfv07pj6t!0ThjqhfE>G6fA`gtB7CCjMW)(q#`2JRL1lPbw&aGRH=G?jk
zOU_5VkTA@5b&`TFl|zI_<Z_!`d(c!9Vmkt>7J|H7)hIO5&Z~OG8VNAoQ44la*eNfT
z#AQD~S(0*UpCfu~QL57j^moR5pqjh_4i3hy5m`R}DDCMLSOn|Q$@mg@Y|n}>X%N&?
zy5<$W>a(j$i0RoC#FBpXvuz#nyRAZB{^IR|qF=v@1N)Ru{DSt(A3lOK0P>%IkW5fI
z1OgmasQ``zI_9Ztx9g-lD0B^HZ^c5uf7{LqT|48;(s<!Ru%{g42`ZVD6EK5Qr4>FE
zE6S+p6wp<SVTuy$iuw!>BTm=9Si>PH%RH;#2t?N}LPf{k(dSZDVaCwDNDOU-jsB_7
z*0df!3R#;e<cpGgJC@rt90`hz0D`AgYy_f&7lmQS7d|C7JwuIOBsB9wI)V_kZ;y^3
z6p>>6i=^a-8aEM8Nf(98n>i;%O90B$9_HRNBHLIZ1TovJ*pYuRg1^$8fstyDGz$Qg
zEQ-PaA{dI*K|V9?d@X)uUd=pm7NsKGN0c1-RBXH5w^TU<z}sEo;nCvsU`W3!3Oade
z_w|i&_i?6L1z#Y+Ad0RG{!DP`R<Ik&tl7<Aw|ruv;>!U_u<6!yg;!@(lEDwBx@D@g
z<48oX%#%7m3VFU2?0(|oQX>J(YqxS^CLGiF(!oRx)b{ygGDi@Y{`2G<DmmuC6tvO<
zZw|XFIp)C{C^;tekyX$rTk#v0u9|^3jO)>EMAbvPWT8OvjBQy@@K#+?Fz~*$>(Vtl
zCc0Hl(?mDLHlXaJsYsQ>^?-Pg1Ej@^ORpr9z+?%mq~tF<IhtNx!?hT>J9!S+CBp>}
zomjOiDI?lUsDk%SRn*~=J@z;V)Zeryyw2PxyQG4QIFam9q|_LyQg-A=VrN{s7EpB5
z%C-dTY`aWf#eTc8)l=A)!vP%V$u;F)qVlShF$xcUn+kA7)|t&mmL&SKx74YWY}-<&
za%xsqt&x{r)~pNew`eq`)~&Hk1-`;SU}f<_rbqZeFgC!Q+tl%Z%E2~uJfQqAYyEvH
zJ8)6RIlMSbCGS=`p((X0GeTCI%^aKJVo?kl#SagVl5v%W39tXuBL>intj3s>99x|*
zfK6o;$fSgnPF*iZ9f<;yCn?G926p?!Dwdxgz|VWN(a7m2-*;j*I($48Ih5x-K+3Vp
z%I4T%Q$`vfw?&ar484PL*ZlI$W@SSIE?AUxJxN&`rV^z*J-3zCylz!vwo@i?yqajl
z2|aicAhkN{B!2>x$tv%t&qGD2KM81LL#kE47nxig1S^XA+4ze*V~m-spF|bP%HoK$
z11khO8i+ukbWvhU7kF(T03jNW>Evmhurg1<J8r;v^hCFeHqs3h=pm-V@L)pQ1cr`P
z+EPDNeEu_Y=ws6ea&nP!-rAz=!L+qQftF)JRt|KWb+ni(AHFdf5DFl&AYN^>a;Q7J
zK(DwJ;t8DiBZ5Sv(0c(4tY0_53livHQF0sy!4MXS2oX5jiAqj51q<9i;w`K=Mvl#K
zKa@QVZYFbW>4s~?^_qZj!zw?j#rb`h>mEVkgb7G*QF030=?%J&K=X(=V~+UgBqh6b
zyEICS!g5h_$jZ0}Od0b!6dGc8TnY&69*aVx2pqqz?E<)6>y?ygczXzFZc*ZE!j)T;
zi2R^=-kxX>IR%QSsis5Vm#i;WA{GE;tZT;^B&}D3W^9_ny3|y=GVm0?!N67tJ)$eD
zOXvaP@}eZf48piNvpf?4#=4Sw0TyFjFCK$xqMWURcrQlCH6qiPqG26b7Zp{L@GjQ%
z=r$OIO?h38I3eqWIfEmnlD)E=SWq}?z_6JLwK!^)S!H`62G_bAX@+x0;Ail~9wzX!
zg`JYzDEOp&mRK+Nq|`=CSZ73BIZVddw3b*e_#`|mdqF5sA__x^5@Ez;!lO~>W{#S4
z)(b&tD*BD!NE0JIwe0|uZIy5a_!JYM*@8ofAya>c0mTSsb|hlT`sK<>17eCb?VdBu
zLsofeC!(|-Jwh0<SGHpSro1R<#c<1#eC7&SlNItr^ztGN5JE<qt`#6|SyRURUt)wE
zWf`rj=9$BkVZAV^&S(+M4EBkBqLrVe=CLTLEQ%?>E;HE932jy^A^e#&!Bhex?L|4z
z9AE%H1HG#Wy&F($rffgpwIxpov<8(+34r~<&7<Ib;=-9y0tp?5;7Op#MU!8`p|Qch
z;mp`z;BaVcKyW?PsU{?5Bz`Okf$UP#G#UFBWkee>%?}j*rbMI;U$+4W4)@0f1cwMj
zAx6SkYDh%v4`AS|2{JN`7>hvcL>v~a5F>F|2pF!zhH+Rc$jB%DfRKi_x(u|F(*+lK
zL-segNa*GAOLUZ;Sh0}&GSrgBlz=<65~9fgAO@X?+KB6;3DGz6O04aOktw`9G>=8f
zUQHjzyRr!~5{hao$VfaQQSL7wVZ!<)pGePW#@6)dt}dK5bkrtf-aCauDhDB9tQCr+
zsS~94rhrfh34BoW>inTo-3VZLvKw02MX0+-E?g93Wzdk>1hEUZ&Z6X>Kx<VtXorW!
z8j&Ue3S+6wBueVVUT8%R)0u=MS+j>D!C4_kP``lSw@Cbx2)7k7B`hUo4+k>z9b(uH
z^a-G6<Vu?fw-U~Sprm|V2<laR0a!!~r7xG9B8z;H2qoLui&(Nvy@(~-)G2r80U%$q
z{EneV0qjBwi0cQaV3RKkXu?O3AUcS+G1I{ZBZtZ1Md)HP9fh)Jn_ze6!)_m+!bmoy
z+7d@ODEQeuzvTcWHlloED>iFwUlZ&)&CW*uNT;3I27TIr{Ssdnj5;mE0t^HkjG54J
zY5rx(ZUV%_8Ds=ar)gK7xDFeInQMfuPVnG#z@V7ibsaVeGdzwK`pasNzfB#;UO3?_
z9DJ|l>t8x6fe~X$9qvf2S`=mzL3glD>tF|j%_4E^r@Dc=2>da*4Ljm~ECUFSPr|>L
z?V#zo`pi@Aw4a8ru_NTitnkt=N@fA3^AzA2JTCRZoJJb2Dnp=07~pCH@*PG}Au1C3
z#Z0Gk*g{r27XrX9reeiMr<Ku~rsGPEAOt*=1Jg+kE22?j?gPcd%mfiUpcfLtu@5f1
zPWyo;r<vxME$DlJ^@1*(qp1sl?(-X*F_cE8(naia++8NvVduINC$c-&T|mUnWv1@l
zSy{&fCfS{9E#!7sMixaC7;>eR`Ua!iVS=FSKGh4t>RepfX*;cNCYa*{lgl5%>}h>7
z-bc<YEX;T37Ctq3?qDI{bmtb1I}0HGm2=Vo+7}djIc396!Ne1c#fXyGfhlN8neQ+W
zY*~Mf6Iw``9W_%U4{(5B7!EiAP((YWw0E4pZ<Juo`ABQPW8F?^_8p4ZM#01W)IEy#
zc~EfJ^chXoj2U8AQNXTf;aM+O0KlglK>~-72(uAz_X;rdCn=MFSUKKF6VoO?^L`dL
zn-+y_E(yX8qb?430AcJ<)3znBZ{vry76~^F&5hfdoLT@T%br>QQ1DW-6PnHOqExHn
z)w!)09+^Akl5AoP1Bvu_qfD^@+k%F`jWRTAENmM3jyF==r&#LN^)K$BszEh>Ldl~l
zyWrZb7Kei`p(^`MY2q+N6X*Ii3q-VRb2ocyoj-E)M7Y2^iDH%OkpI})xA=*LJZ}jW
zH{f||PLK%NS>7mbf(4*zQI5pCI3=?2M^oFsDC9$qZ(y0!%=@eM$vGs7%t&@|t|&YU
zaH5^g7HhDPnK=G|9A2m5*(9AJkhgJ^9zg<kvG-3CdvQJ>R^**R?!s6Yz!`O}pC@j5
zq2iyX?hoWLKk4<-ZPC)Ga%@*h1KPU@F1gYVmAZ}ilKe6&>upyKtMBb!f@5s^(4|W`
zq>QEi;s(qBVAcn$OOZtc>*j1vYErygS$MGS--Fc&%~S&S8R8bQ&!4(&k>~x?b(^=~
z!E%Wv-~pCYEIk5s7dK^N)nzPY1a%vaO=DqcM>AE^ecGnuw8!4{p!S$Lz~0oJQ+f~?
zb4m{)Ytph}8EevRK9{Jm9SwoerPj5Z&n22q18xIaTk<8~HnN>e$$}HdrerpRgqSt7
z-qq3o<2X}81`A+DDMax`Gm5D=I?X6jk^#?AdURAFMW>Nd<XcJg({DbORM7W!<<|ln
z!c*hNXFHdWhL{Er-Fhj!DDke~{F+`qoL|!uMiaDp!{AG%Hw;$wHojpv!BcM-1mHK?
zOB7Vu?vuT+h}WZDnAG*C)17B=qs>GJ^GyC<?>$V6Ruch4HJVNMWIWn+sTbyzxwL|}
zZwM_lz)m&9jhZ0w7iAntzzn9ka0Wx2uqqd~c@_B`FdAD``E@?sIRV$xJ-6HCZ!h;x
z<`Lm>e}KZL{J`(_AB+SIk&C7h0u8{qi$YkHi_avL=e-QwRErnDibn9Sm3_ocur0KU
zIpV0bd!6b7mNEd)R7oBIAZ7bFUZjsQj;sWx37ZQBH(^IL6~&zwL|yf53A7RBoFv4*
zIgY6g9LLm;f>Cou3kZyV1rGs~txSLoNVZ`m#80HI+;Z3`yJJnK@WfT!bna$!g((tz
zWhCWSs)BiL(8H9UsH}S(n6zlLDqw!<Q;^FEqj#gS$4sU&%QBIv47X8g9_C++htXhZ
z|2;sOu;wOfkmqiyU9wV_vR6kdJE#=-V8kS=pS&n(yhi`29s}((uIm6Avn=F|h4ada
z-Wc5_OFMI(V2%%p%Noz`qO__Brmz7K+m!g(ka=#6^}z?Ws=Nmc=8e}X<{tpZNGHOe
z&r3zV2Yp^cA2xOp;}KlgSg^5Wd{a6|FoTm`7qqg6cKQI4ez{?q)7ni(&7zFWl@r-f
zaMa|C8K{&GqXVS0c55fo08+R%3{+~`$%qUIhg57t2cm>(Od|@!lz7s7st<(SH{Tc(
z51-LY{yY6*bmBLsc+ln6oZ>;ZTyrl^CAdqAN#h?R_xU_(S*Ef4gU#vrkk-$Hs&G7F
zLh1T=G#xytyL4Ni*@kN~wf=@kj78$A0p~(zn3va-Un;LDwEpHe*5#RgQPOjrT{^v{
zI-)u}rz-CSK%FDK<md*gi?W^?tuCq~);c}u(!V;&(Jj&dA$|W+r8-o2dHPqTSTd)h
zm3%2R2)MSUdTMRiWKeAlsbw3QOhYJy^{!8N`a3&RkjD5e1vfNgesAby=x&|o1dJ<v
z(A~*QG82Yw!$b`g@EQZPy7v5!uvSOwr~2SSr#g}OxU7{`$NVo-EkNXd9YMmpu?-2L
zmX!SIYx|r0>HP1hW%sJ3o-tI4pJ_CmD8^<bcHM}&f%G(l4)z>au>R2xFwW)C4{$ZK
zr2r~x9xuv<mGHAh)fJk=pUu?~;PcAyVyF^-6-H`jD<8YA3;r)bQEdx~;?IUL%(YWm
zuBYc24-I5RWAPUl4W%u>Xegy-ws8F!p|g*Mz$cedk6K!$va!qyGi8M~20y7-ZA%y2
z5v0PsOIAX$Hb&Y>kIrZ)Q#R_#7c(!JXEc<;?ua!*OsS;g@=>B04;A5kkwTW^VpKSC
z$btgCK_NF~+_v;)nTka>c&Y+ihVX2R!n`zNMqxtN#3RUvv%$nN#9JO9<q9!^rP2DP
z$jwDzI3*+_T``8s^$1GDgK})p<o(guOkt!0ZN`vdY;=6OZWo&H#wp%G!i0O@U}v$R
zyW~VhsSOz>U=6b&jTiPj6XZVg(Fz<4`Dn+YU;~^tqH9n6MMlfQGt~eRV}lAOlF_Vk
z%^NL$gTA;1bgM<dCSZV-(%2WJ<8P?P&=xrK{yZUj%7<?Nk+7k&{)G4qXVfxt)NB;~
zAZ)fna(==}uR!ItOoT%(wX>%wT8aOE#V|xpTKo-v6|vClv@*7W@G!W-XqB6^<wc4X
z0=U@=@hg+-YXGNRQQ~-280}}O(y=HVlv|Vx`=+geSy>UWo_sgPE=?|up|DlOzOR(4
zIK>nnZwz0Wf-f*Y)>iEOO3N~pJh7)UR6m5t0>IYh#J`gX^IO)fVuF@Ua@QUvHxzsE
z(3_W-*(wuZfKj*_CZDMW><?2J7^7WIrD6;a7&h->lqpSOVt&x`CY=R~5_5dSg2*SD
zc}&<tx95Dw1n38s<N;U-Cdg9*?12fZ!~kk=nBZm%_yl%IXl`6R7w<%5fMu$RlQN=>
z?Hn0lk>A3{sxg}CO3lzvmUgu-5^{KoZ!!i~DeuNmjH}XhRti`SuWJga!l=Aa<c%Fc
z-~=Gh_%PI$3+5fBjM*i~S;k(aMd<)3GJK}^g!}3e;OOnba>PpCO!CP=A4$qNUi>=b
z|GM;b&qOS+07*W#K8zaIcHR0iuC(jc3U#G;LB<ke!LCQ2$%E*y>(RGhle|xT4BOy7
z^(|w*nP!>y+-v;|%}i^<{7ji}T(C;0<BAd2HUFK$em6-0lj&G+-e|tOb!Y(#fD`|$
zgtx_EY!U{2-MkutW6_OQg9XHYtYyv@iTP{2p^O?T2`o}fF%#`gV9{JlyCoZ_j6ejo
zCGCtAyRZ0zsoY5p1TUjofVD`oGlE$M1$my-#hGVks-R~`cIWp0RG!`I7(px3h6_OX
z!pZ%d8cix=&#A#cwja}AAli?hV3>$!j}{;4=yAScouKUtX55f{p1HN_^=y%SUfH)i
zAu2<6QF0QxkC1AfS-zHu=Es%?YyilrTw&(#RX*{e<cD-SUARmmF*yjPtYpqHO+iX-
zW|H5caEhh`=!_{d1i=YVo=36?blxsp91jhpNCh<g=Tx(wTT_HV>A5w<G&DXs7f>Py
zO2=nhGWnH<p*u!+@P{ryWDiC@I{1R>MT^3pNoazTVQPjdNGtChjG37#52j22X`IwG
z<I?oZz=tre@Vp}kU<wS-i<0O2ype)0X_+@55F{=00<@Rv9Ppy2j+d025rgP#0u$rp
zV~L512Q|vi#P1Yr8S@rHE5(3;fN@STd;;lV7Q-hn4(8SiK=0%?P%l(S!T<!;;CDZg
zl)wVgQ04$fZ!FUYSOFa$6A%}QA%J3*@D*Gr0xaw1Kn=4dkFTN5S(9hhSPQK&pvofO
zyvY$tMX||=X=&(hj5`bE@@xc*PhNFmeW+6h-bd5o0)5m<Cf?A)nVs3JZ(RaCMVALW
z3Qb-s%WU?<J5i_bzcjg*4AtnGoJWTI_IMVf8&EL<d4)Nj&8D<b#921EY7F`AiSDvm
zIg(2sL1hU!RpJ!@JQ*|-y5&|E0AiRl)d@%pV=D*o)VNHjHq|BZicYi=3+UWFlJGj`
z)*}wo#MePa>W04)Pn^*<jGjfg1~7b>uS$%cBS~We0b1<@{poC-LJ|Tc0hIdIBjl?f
zi3|>zCiergU<=mBGN-?wj}~FZ`Jns;8;M9Xwmvzyxpm3`&aF>!ZR*`Lh)Q%-x3u@A
za3Z#~H3`4~jF=Ko76k}T_tq^Dl<uwD2>WAo%JDv1pB(SQ%M5|Dv}1y@epiW5hGLw{
zK#J`@E<k1(-KvIKi;I*8z`!xBl&?h@(Z(@@VvLIdCnocbTbFW(7~R%c9N@z6=nsEU
zWF-EK$9ZD5bVmoA>z##@06W~eGzECY8f?Rc;-{+(qeB=05<5*@a_oA(j)|e`CK!1W
zbUq*k(s7zH7-^AcDn9q3g#8{@)EHpB)B;#ETEF$COH78QN_Ykkgm5u{D*#Ojvu!48
z(?OB#1W<DAbr@Hc?}KuY_hyp`c2Qz!TuVN1$13I3;2dl+yROvm=2QWI0}<{V%+CQO
z*h{pW7<ycBKrnf&I&evyiw;aCl~X(n5!TIX*>Q<^RWNbPS~@^h>0OSn#vjhJ*;N|_
z2Cb&FYJ+RD$=3O^q8IRMH>F-1&>foBL6LBKDo<&M=58toV}oUUWD+&NLWbuM?PSKS
z9e`WNWygTyw0Y^0h!YPtrpCOOp?rJ;vc#f18elME7-Pc>9@wT5qPBi@$gVYTn+@Fp
z0Ij6A7nHd6N7WHY)YajV9Nc=t#Vx=>4Hvf%1<+KDH7uy%#J)A0#N@2KUX-EX1h<CV
zv^34OQEQGXb<}Q8Fw{|-onWYUajQsE15B2xOK|hq_(w|dFYm;%Laz0nb)w_yp49I|
zs3RV@gA=*8JAs_Sbw6cGf|I;Wz5h3gIF&lV?A%gnPklNTa(3~F6sr6OE$D4Z=NE;)
znqawgofl<lxFh*gH##s{=Pb@7*l+PA+peJ{mhM$|1xfeDg^-tdYb%lR6c<8%P)qjM
zNM$J;P>57Cswiz6;1V(-+#E&mZ8#xgmv0PC%KhWd+}lK#>2^h^Rj2s&Z9k6hwtZ2a
zy|zy-cELD_GKvu)G56TyAt`hFPDtJj7u2zlu5G<TVDGDzG70-6L+o$P^4Li_Gcvf6
zyD?g$_F2YfYA*)mkwaA5Qy^eF<$m6__(NOVMvye%V0i4u)8lE|k+T-<Y1`Qm3-a`8
z9SVKjj;*I}het@}<J;jI^8EOA_NKz{IC-08u-;D9VT#{<r@SA=2m~gxVh;m;PG|Zv
zH&!L(DpoD|dG=HG&ROo~YzRl$TX@Ah`!Smo_6RX}>IpS~d#(#}v1bKc*JZtyHNvoU
zUoLhm%Eg;F#3G`^b%nMOgu3F_7<<`Pa8<5&^t$20KhS}1$P2v-Sur7Yx}X=S1T4zX
zc;}fFBy}{W;PlhUT$D>beY^7SGb>Tnm4A;!fZwkC#mfMN*NC4OU_6{hkK6#R1&S-5
zQ-9r4BKmo;8KbDZ-IHteWJ2-fvz|;SC4ZKO2Oi5#=*~qLkwwA9Ky~IapunZsWk5Mt
zAf+opUKL7C)h`Q%RMk7wZ10K`f2oK^G^tbu1FWuA6m+(>DXYN)YrC?#rfl2Qikc_Z
zOI_{p;l63BS?{%U)tIt*b(vW<*0(-6W8Zp(6qt-@(A&G!k^_;er?CVtfo^kqcH|`I
z_Ugz<UO&7#dS(;zxs#K;>e&&?YIUv;OsZbX?=|I)ZIy0LoQqU%Ess{sIfwgfbI$E-
z&o=28Z(3Ej9_`$^#8}(8^@y=HJBs~TE?Ke=<!)qDA*-7nOb?1OldngnJ{42Xto2+>
z4K}yFJ>_!Py?B}@%w|@}0^Gj!iSwg*^$9T%`~x4Wy^VUz4GfoV;@5+>3#HlsvfmXm
zY0$&F;I3`J+!och_3BTyUR$?h>$P=D&fZ(E6*AG={bnkNg5l~D$5wlGd&G&d<7_|q
z7t&}@Zo8jbr`U%5RHqnRuM+~LwHYmV1nC;c@yovm#`QWRZe<BZD+ktjC4^k}4CkY*
zC#13WtxvE`#ue5b>Gh3VQz8o;9{`XG5<3NtHUkTaU~d){)V!931?gzLkF8UVWp164
zOH-Y4EOYA<@|CfRw6^7FE||?xnObpmVMC0cDN{SDPWM}VLR`B5tPFwROoIg_e&$i9
zWJ{UaEi-GO+u&`rNVKzOooB_tg%x(Kv6rDeN;tboKSgGKciTDz6TEGmf(K=EfepFK
z@Io7NFUt!eO}h83*HET%wu1>?ruO)~?!FtqLri@)wdc17TETtat?c<--5f8<I>LOS
zksp=5kOu#*_%lOJK`#poAQQS@@|2=RN*89HDuj6z8jZ`*c_ZL$*#*^i&{@(29Y}{t
zFIx(nF5REa;S&q3cfv&GV^>)X1AK5Fbj#s19VH#PSNbUFU}3Ue{Ev#Y<IP(ZKjUcS
zPn7TMjuttIgs?u!ah5uBAAFz%jA&P^6<vRQl;bSV&z?v30a9>jOgSBcM-@v2H)L0J
z7CI^yg-=<$j{D%<4~ORhfS^d?02sRa;W+JsmhuD6)jsH0&F|=9zp&d?k;VZ0P4tRS
z`go6kxM=h*$9JY)dO(Qnv+5t`PF`>to6C6_@cJ~lspC^qI~<PdKDEPvSld;whyHH>
zeH<W-zyZmB$0E%t@(i`T>@EoK>64MGb|KcgtH6*UeX38K{(z$CQ#Q6txmr*sTiif&
zDJ=krT3x|nz{l@pi9vE#pVAjEY)7OaA#5Qhp`Cwa{VlA>z+iRwBXp=&B-oW;F@56j
zM@53w#?U5sU2z&Yq&_Q71KLJm^)k4q&ytvY#P&-916`s5zfj8oxH>t-*w9zW3pVtn
z7bCLv`b9hZl~?~IjWDe^N01nFfn9qw4G;JF#m5865eC{2+OZ<Jcn3)NE7A%9@zgJ!
z|0p!v5!97CuVT7RJU3L|n6TRYQdkCxr1UL>E3eKif-5e{>pIX#PV1~kcvQb635Z(i
zmn7lN3U9Yg8x*(cmt1Us7VlTK(o5AZ9UO@7>X!}<27wX#>XU(D0gt5^u=rIKp=YdF
z-(t5M3OQo8P<E|sZ$KC$bl0Z>-})BNmG@A_b1_;j*7Vjva^v2)^?*PeUKg%91E~5<
z#Gb#_;|`d3^nw%uO1|Gs%)$MI(nH6m!m4_Ohan?*QOKPe6XR<oiyigb(HL38z41Th
z&}9Ea;U<EzeJZ+=z->thCv_JpJ>xXHkn0UquKKO35AmLX8|S37tRc_CFJeZ!0?Z8M
z#Cpb;Axx_SiQiC(tqZFk@vTQf<0(=$7esGYM9TJCD(nLbP{o@)2({`JaE8dOuHplW
z662Q_DB^niqj;hx7~LOX(Jo2|mCTulFYXUdC>RR+)6j}3K8=4ra40;oc03b*qYDgJ
zj*G&-!4v3_SN{RdBk>wPBQz@iNN-NyBJ_th4U2bFZAp~($Xf3VO@~VGC}Rg`5M4oB
ztS+)B{2N52^+)Lkh<0+742fW;GbtID@AwPi3Lw&H5r%@|pCllZKRLVz$WMSVZlQp>
zDC@rkbZB0vtSsZIt&+uO1VNe^0V6<6nVgV<>59i{X@on3eVU|>Kf?HKOp&cSCdf=~
z*yI4ZdVthpiptmm0EnMT#{%@lLUUz)NXn^aM#2G7&QW=o8RxVJOklBqmaY7dHiR|%
z$q1%nE3?ZGrbS^sNCS5(S0yW?o|UT7zh#@5sL1kn;SDjYiIBRVD$(RbeQ7Y%Ibc<e
zW)y};qoXubwn`rSUN|3!a&lpK94pMp1<%0(R4$y2MOpvNjjdQjp<e*Y&rM+>4XA)#
zxD|+da>1H4q>sDM(OTN*h<tn`CBNJ>x_orFpdbt)R7ej%ZggTh9EykX!fmhzU#DK&
zkeTj6(`(2@Ck*sw)+Ni|=39zUP)_*22!ry1GiWU*MUii?)Og_#v>d1x4gpMdUZ4ZO
zFL#v-YYo6wZk2E7n1W;)In%({PQuy)RvC%;3E*-w<uF9gZv9Mt)oDdtgk&FGY7J@1
zj>NblNm&E9QXO;cvcnDTKH~R{Sy!$i0-_d)%as2LOmlR@X`rCC29w;PKx{f}JuX0k
zo`-=@OIJu!Frp9$fIsc6vUyXU1DX8*A^6ZLnK#$Fzy$#M<w9?5fCY0v2`pB@Sm#Z7
zi(#yD;l?r&$^{$H^Jw-a!Ov{kBSGph8q~rTux;xjTFl)Ip(<Q}KEPdhZX-M@M(fd<
zIX!I>ghqLx0Kjm!DCGW?ny4!>Z;|3)s-*vZ<$`GE099^LkTneXXhVm5zcIfdK4l9$
zdN9Gt<fZs1leYtbYmt!ej#|}~(9f#omC}#HqEh+|3%I59N7-*xbZoHYdAsU6`LmVb
z&!4??IHMeZ3v;@`Oz4Uv+<%#w_6@wd(Sl&y`cg}7GupHPme2(?-e3`Q*~y!Gw3sxA
zwAQFWfhppSYP__N#_9@ATtQdC+=no?&4)UHmy|dmTp>}_6~EX}Q>DtvFU*2uo&d}n
z;2<3a`Id#(g$B>~D(^fL9ELGh-Oxn}Zg(L@Ij$fU8)fxd7he6M#52xe)^C|n>Xq|9
zawc9W|A-awO8G}r1*(e>!y>yC3JDIWUMM7{Zt-pWSAG~ZS6%U#4gO&7f=_}U*Hs~a
zm5N<n1ynOWvZ@Nc+|{k%KiG}%9}tl)^pO;i!wWAUjgTItWg8q&uHerG6Qm1HAVV;n
z=ijG-xE2Y!CWE+wLQY)lMLt~Wgm-F#JH}NTmu08D7a9qaltLjutgoZSZv4=rZXD2~
zZXD2~ZWs}q7>+aeNK$r_Y5=pNtCU4UP`7uUXow461Zpw}@N&3a7~Zwo#PDhAbn#Ev
zr7(QLa_Id+GkfUFL+HPE9dWQRE(*AXLg$`W!T}Pyfm=vN^@37>CEYs{$tT6)DrWKA
z$Q~4mTf?JJ=v<sUGHwm;O4E)P2E)A6Ex(+KYe6#1TVJ~P7wo}%HDkiO)AP)jFjt9{
zHYpH7NP)?EQ8r+y+;og)XqmdS2!y^e^&<3@sneCO30RiB(}2}39t%2#VMX+Wg+S7m
ztIkZjkVfn-jR^(gydWK5t#uT&ZdYogt`zrcstZA1U=ei2ATI(saj<xVxK7Ut8iw<~
zhY`f(KVuY}yUtP=1)arx8Y=QF0+GgYDGpajpg?MiKjHY3gNs5$JLsb-EEJG%(MCRN
zgEiC(lmbxvi$VxH>|*a|g>cBVw;=3R?4G;MXk=(Qp)DFraIV5gEsc9FcVM9D1zS3F
zT-YsL<&^@D@64Yqguaj!c@f*4KT3!`)F=)TK0MTgpnY>yG|PYGr6w0-gB{H?7(B;y
zK~AKLB4OECItoF7?$S+fu6aG_ZZ5hot8T8kE)N(ET~*;1g}o4)*kC5~!t!`dbps!s
zTz9<{A1=Gp;4};#K_Xx!*L|RsOQ<U;4QlSXk&sdEt{mA#%0;9y{c!i{)<UYL7qZCX
z*}}-+{&g3~7VrZWC4ZE=UANrB-7W?F!G0gw-LTOG35<h%N&qI$1aEaUJ{Nd91o!cT
zdZ(!V29w>QkdwH)69?tNDXmsq8>>2B0kj5V^;URrM7yrq2X+KOsdU))+zEovQEbPV
zUa*4xQoL!3>}k+*B@V0*zvSekpQ0njQly}uSN<&Q2+j!hMRAO-C^!dIX$G~PU7q$1
zgWfyk#<wS?8G>}YQ^*{E?GEt<gelel$Q;3dpd`1hY=SYDSVibvSduo%EnYof459(w
zNx`cqGjVeFMk^t2orp9YxU{bHi(|#?<;Y3uFm1W&^>v`0zEg6j3_UnHEKo&SlpGjG
z3dqWLN^(CtTs%wJ%z>zm5ll{Rgq%=xz)QVaxU=;+*oZa)H>d{PxF3sh@nY2U8~0yP
zxc|gPR4d#mPp!rQLW&XBr=MC3h+aRn7^L98=OnxF=-Nq`B(?!E*xo6S65+e&o9Wm|
z+;kT(-otLQwa5a(ySrF`$4c+61;_61F0SB!=!0Cz)4J1A1Im#kGAhrRKE)^;PJN0|
zq+HnoSFU1|feV*}m=x|e6||ydCihe4{W)nW=p9ew+K)Z8CT-&Ws1t+*<qC9K9I9zh
zCko0QY^M+nF?DtUJFHH;gB2CFa}iY+-YGnq@>6|3dcAWK>d5x44p_8hFHt}f!l(AD
z!d*uhl$!2CXBn2nhmL)4JJR1a*?>AB;W)Bb#j}fo*P-(Nv-USV*X=m67&u?Q;tcB!
zs#>BxNKFmc2HFF|cJ-*y6C1t_G_nT1hT-<V_ZAruYiHg%&pG+##Q`#3@!4AXSXv@Q
z1%qsSX^r8%VuJ7%`S!lv85;O{Yt!HT8=Z;o*Ap5t;3`+N|K|N14VhDaG~|Uc^c?VU
z1F2xY=9=!4cfKp+<kh+WRDDe?0~}rrKftS1Ho*Y2|Fs}S0`6ZMV*nNp!=w_cz?Vzo
zWvuZpGI&sC9qcq~stO=zV{ubZ!lE^0_+iDtPa+d;&{sk$Z>+_asFX%)%kaZ`THF*C
zN(YuL$H><%cCNAb-kITO!8%48A^V*p4B7AX`-96vTH*!Fg7waKdQ_=~1DNMjNa#Sc
z+w&e3#>RWEghzbo-${=qjx*3W8>(Pvk#18h^naUbVUdCsV2UMhY^nm`^u`{lh7k<a
z;s~Z{aR3vCLy(LPx<hn09CU{e={b@&Vv6K&07dv7OUK?kSSYCx9U?m34$x!F$zY>F
zhsZQ_m<|!e{|-7tbow5fn!c;cw6>YEXv^SM(jxdo<O@K;u#~XRM@^y6-dG9tHk~BG
z*Ai$olX(*P&E|X))=@(!*N_8zF%>I~ENWAkcZZv5p>MB$M132qgoD`dp<3+R`0}bC
zG2H8h89wE_sd=mPa?h7L2RN(O<8uY_6CM79z9hU^->gLC1B#>91I2uKua|1L({076
za#YgAAJg)se+<u&hm75MJ!I@ob`F1oi(2`3fMc6OSwH=JIoycNn&VBCcT|HPqr;Gt
zw{JvKHN1?VgH6V7(7)!|;R6mfS)0*S3j>a>S{QK{D^W=UAvKl8m<XwIrvi8Nx?4xk
zze@cYgG)iDxuAblrb<lJ!c+&{tFlC5@!~^PMzU$q^IYY+_Mln=_-PKQvB0r?2+nau
zti{IRsgnbJApOKgf|A26k5Ln6GN$Gm_NLtX1MsgYM&S!(YVhXQ)=R9{9LkOtP%wjm
zQscBNVQn9-4?4OsL23>f-Z228zHUK)hk9>H#^LJF4o@G>5F!q!s4J=2J@mdSN8O?O
zUHkWerNR8m36gqvVFUs1syINX8(lmN;JDt)sZsHsy1gROYKqo+(5)ld>v8sPQ-Ll_
zw>w9pmnW0*X2Zz%d0=Pgx^5h7Ey|~MxV1EtYO#Oi9EO%L?SuzskFOlVIC?0!=Slzu
zI4I&Ov?gRC*z>&#oyfT}m2?@az=DAX%&|PbvM$#;5YPG*)J3Nfog>vyUgfrQVrBN`
zQ@6Vl)eQH@wov3{Z@uJ1ap6w8zSV?r)l~6ZG#hVoX=TqgvsBYWT-P-23A6DscRwfw
zZr|B^7$LfRzmmGqUg|vTkh;Ww{vy!Ud(l6MMiUkwF<a++;RT4wn!v$4NE4n9nws&_
zG7N8<Nvbt%XvAC`L!$;M;Z&mENdQ`s6CqdnR62<SN);rex(c?enQTeV1XWhzN@|us
zJ3N*9cJ_j=@Bsjf@FIJ5A%u>eL4?rJGhkQ>D>LCo5}aoCnNXVtx$RpadRQNCQ?Zki
z;4!6=CHiRgcXf6`gIv`J4f3yQ^=Qu$aY0*y@!X`k7Gi~XPKAsTcr=w^Wr7uJb{@ny
zlxKG6qlt98Qz>6K7gO=8S5nhP1n{iXz?hF*=!VZ<G-4Bhol~h<`7$TtY3CPu>{h;W
zg@nmdIejMbl)Rv`DfAexUuL4mcsQ7bD;=TRu7r@d8aC2~Ok`A=NE1RB-Cwla=S$K?
z#LrYL@<i^Bsq9n4_)M|CO%TP;-f7Ox3Jaaet~ISn=-U#Okmc%pQ{NUBJE0wf=1c`+
z=PpI0Bl?C_r(AZ^=&le`9&t5Oi5|JBCKeN~w$@$?z1hG%Qo{>iIZ?>oH|OxMpNR8s
zf|lzAkwOtYUqI7I2%CVY)MzhOl}a!Ht&0+%QT0_o`_4v>z(kq}Zq0xBjYyHZePe`)
z3z-@GpJObKWy1-T*3U<fB?4247NHrLsO3dT9SB=fXJPh<H-UEVI7ihG9((i-i4%Jf
z*?9ywkp>56hRE)v-yj%8#GyD`Jt@L_z?p1_@Pa2f+DL!N17m|^NKz53Nv**XuORHW
zDIQ|$xOcNd6s)|79pnIc=w&F=vfde76N$A)_Yuz@TJMvAAcv=iiF~v}6ejcojewN`
zZ_<chZ&!t+RI@v6ZMZz>m83EL7rEO;@OVO>-3S>Pli?qm;AZ+0M`-0v#(!)L5U)OD
zOH77;EHYEgS&<s(I$}RqsGezuo^SLAdmjv+ka;i}{xQ`3gPv(ao{avGiLhFp%jz;>
zuEyA!g(3rM@XEnY!~<YSYK~}MKNGIVjO(eMfWl=2eHIf;DkErAPq3AYKxEkz(MU8D
zbJ;in;gjSaE-Qh=9<E*TvUIp$DU&Q5&a?X@pN8|OK1rA1cmM*qT+Pl>G{d!+ieYWI
z))FZaT$>;{5nP4=C=i~E2t(70fn{tf`3hVHC+P`%sU-w9`Fsb7$R?2`O?XA&eks9y
z?!>?A3DVNV5AdXj?~4(8?^1Xp_ORX%zdA(SJ}Z9zxe~57hU`&^G7{gL#>kMprZJ}D
zES+N<;>rHMiw9x#ib9<0=(#oI3UNhrBLo#txV1$yLVnXlG<U^WqHBnFeIqZgq{1i#
zFrR><!IKC{g;Da9gVb(s$mfJl_A4%QRzkQpcJvA=c9b?DoU}vv3+5i>J*}6vNkOB)
z*2zG1gudSL`U;Jm;I4h+XD2{zh_S5^P6gRw;W98i19c~ubrHu4NzDln;8#*1tEQ<2
z3CQjo9%BD?*YN85P~h?0432GdUtLkXLs(@sTVv}40_Nhej)sU2MxoNrEC%GU4&NBm
z#R|PKgl>uCZX)T!SlUW9%(i=haEnkLOM6MJh_Q6w*kIXMvZp{5Jr>EkujGzsZA}Yk
zHI`HmNT`Q$hfKJvGv>WU2qujsV+uj>bWKepk>F)bNf>&MY01I8YXv%JN#iIY{#`1J
zh?mh{(7-1}oXS%}w69t<#C)ov;mId684Rx+wO3LzNoe!L<}g<KszrVR%s;l2v6NqU
zdgmQo7HWi3I*0M`lQ{9o`1mQ?#XACMr?wJg-W;O5ypn8MV1emXs)i9QKb;Qk$#8jH
zPfq0g9JpG%<s7jtWv`@~MKsQnqH0$sOL+Qu&w3>TbP#f4l<$8CMfO}tQBlmVTE)Hb
z)+sIu`7C^Zih}mJ!{>W1s9B3V81xlRWZxJ>GEPR`&;C`ZLXDMMYeF54+22|<7dqZK
znK9Z|rJ9Py0|hXjV;t226_Ij|O{6>+x{jE*vKV!bzy}ri3ZoPz!pFx5l*j^uuL9Un
z;20n&8!3J26PCmf%y}Y<LxLq#1&lN(6=%<S`-N>xN#rJj{zpxlCxn9yARu~7{Te8X
zA;0p3r8MM5p14;TnU`;p4?sZviIgN`n0$~<@}PP^(FpP9fnIb?IH-f(cgrwZ<v^TH
z>Y(;js~DHgSG8hXdS7mUap`>3BInXut2meBk|GfS^G;6KsKb;QY~r40n19vE4_f}w
zgyW9a7m6VLq2Qfo!ayF3_?bw#GHiX-B7qe@L@<t+KKZ~7I7|uwNZ%`2C|l8Ky>*H!
zY<yKIQY+jjOr(n*isG8Ml)5-B?0aAg7|JwzB{c*^{ZAxz8P>n5)fi+ikaIy%Z&y-7
zNc;0CNe)6P0CWVy+E=AwpraNjqK4Ny8QkBy3`d-YhWPETB<b7qxd%v6I-il_Da6|Y
zQ4Xlf-vVlaOE-s=hP*aInU*I`YokJ4ABc*9ZhciN0=o58tr+NdC@m@p<+pw&ZuG7Q
zs|Jb2M}Jp9ktucU`2icXkFQF##rN@5s|IRXH=}3*>)$VtAeIbBD|(mNSJ#Q7zwaJw
ziv4}}P*8H<fsJ7x$K6$i$?-Z~cU`<}ihPaWa(bO}A$~=a(y(o^3j<27$u11o)J=cC
zZ@&3gjbfVg_Z7~>lk)X}d#33$2}i(SqK`@X4dnuvQBJYZ)>oyRqt~H^WJL*y#pqzn
zH-7YR)-)x3p1{YCW^da?x!J$k_M!-Vo32UeBxRepxE-y1wOupQ)OO8_j)t)krOX{*
zfi(IYEd!9ZADL(1$GDJaEQ1B2THO{@`la6<JE4V;pM@zK&J1wLzuvr8!qO^cSbfh6
zw6r?#gSzCx#*g}2B(z(-t+KJNt41hGtVAhU>g&!CzMm!7^v}C7L*d&Q|H3C1Deb#4
z7bpL*ujz&0o!n$KK8oRcMg41{A}6AMO>g8p^uH=eF9&d4cG}lO6{WEhbL=c}nyQ3J
zLPi2`q&$Bu;v^xZjq+Q)5}4e80GM2a&nwb>Pn2nG%D(kV<i&|fq97KQ5<Ch%DM_xK
z*H<Tref2n3)a#B5ut=J`SO3#*|HIRNyZ`;C|8M1Q{nS{F!yn+IxLx{B|Lbr6@wqCz
zeLDWP|Np7}U;XRzDS!U^=gRHY*Kg~Fc-ZH8{kMPpx99)yAOE@ibNjUQumAD+fB)0J
z{)ayOpZ?ST@xT6u|IfevKcD~lU!SW#SA>0@x%=7eKKyee-rIlsAOG9m{<lxP`|$eT
z|K;DF&&1|ztepRU6PMS*`?y2<lfAu>dGn{<{?mW|KmYIl;a~rM)yu%6hTHnI|JnPS
z$NVU@f47@fkPG(GfCl`9Uf#2x|Jcj_*MIllsF(9j<-Aik&Ly?@D6#gL)&B2x@){yb
zbN6q8?|%34Kd%I9Rh5vg`sYfc<3|&fP(JPNosYVX`EiZ?H~(R+fBHZE@|WN4%xIY%
zF0;PxoBRA@&E9?gyHhiv+BizYeE+Ez`0qZi6xjlA{O5tC&MEkvd1JLvUf0`?>c*fO
z_U~EmAH_S{zRU6=qyGKH^v@sNtJU=PkMG`Se~qs1-(M4`GEezhRf&Q>s8%-QTPtuG
z{9`3RLf=}Od?P<r!=9t*r{M3K{*M9T<Hq6UEr$Qj^#A(g6Z7<rP9UfsN7u`ad8>6A
zdOuYgpqN*+apF%bW#0F^)pP;$W3@f;9fGrP{@uI1R)6~3e`oc#e`NJD6yP13Vr_mL
zTX8SEwaCTrW2HX+dMQ)zb2S6xOw}m(gKD5Q)C-{C?^9(TdG{WX7EJs1zkuJ`ufG5U
z<A05Ak3X@L4FMBxHAPVTSPhIGZ#7YT{8%kdtZyY8V1KH@)Yh7Q3jW?N;G=&pJ7p%{
z{JrV_N4|hwZZ8cE<v$o5co^PV%DnSqHADx$)f6uLV>RTOd#fq=+>h0e(cparN^$T@
zUqHXGsegYH`t2Xk0RVewZ~}k)G&c9YUdQf#Vj1VnnX2se$BKUZjh-KWVs9*Rp?BNa
z?{fOPSN$c|`JF}o4;ek@uUGH+6KnU&4y2&}v{8Wz{jDYey<LCDjNF^Jxjy>hxAjq@
z^Y;vqUz(CkRsD7o#UIB85Yt;pf*-4OWDI%hy^^0R0-*L)QIel4A_VTMq9niY8v2bC
z+MnIv{QMq%;Vm#<>sL=D`FV&48TqOx$<GxtkI`2(lz*(0*>3;p)xVOTD}wUstD+>o
z@Fp@(>-obk;@31IlN^5aRg#|vx&Qiz_;0_xlAkL^+K*rLDEPS=LJhv^N%CXGboGB#
zWBC`}MDh;ASZDt9CVt68L;(DEKPCBjcr*THvAvR?D*~GGRZ)_kE8>>ttD+=7S1fP!
zS3L@T<y~A1XBjI$zKdT|ow!o^QiPKHI7Ej2e0x$T`MKh(d(&^#OUcg_ce!)FDoXNm
z#Teg}vh)k@A@6|y_?!48qw$=-S!l21$Dv)v&R;Dw34X2y4!o~=lKfl|Ak(jklKfn8
z``^6vSMn>S(*=L+Kl~<s&30P2o%`ymB!959|Jn}yYa8<~zy0lle|MwHSJC^seWXuK
zg1^ta`OH+gyLx7*`yGeN{FSYo9R<YxZsmE4BFP_((DEMmtDXT`^mDa#>NKKi?fh`O
zWwmzpU$+LqA627=6K|n?dpQ68m(cFL-0xU6;~#hlZ66$rHN1U()~BclnDSS}#mlgt
zD}t@=tD^Ypey)fN@?RB|Q~u|Q2n>7QMPI*Q@PECG8)5c4FT?(km(e;7*&1Q%KOM7C
z@kDTdRgZ!{sD?x}Z#AEPrZq59yw#MA`NwLYCE{CP`4?Zpxd_kSy9D|5cW@9|{SHpC
z);|so;dE~`1xx-|4Ix!;HN{x{R4tH7Le)aKC4Q_XH*mdy_!TekjV&y*GX4vDf!RxN
zdc1?%`_Bw+jjt+e{L#;oz3Huh?07#`vHexS_8<Kmj$+L9m!J6WpXnPA`d`r7h#vak
z#TW)f!OsJ809xK^!PtZ!tAVlgt>*pDw1(V|Z?zSFrZu3LIsYvG;v4WwCHFgT;2+rW
zeegPsgBw3yr?DE+!@kv+FZSnZZT?MbZT^YYHYh$-je<X@Rv2Nu0hWL94eX0M{hi(B
zA25LS9)B~q{o_R(t0Cw8TWz(k(fw|<zcqRHpR#y2k{`U)lnvp>YKTA98&Ev*uf2hb
z-29zy;2$~%e0gRl`SHLM1?Bvz_)31^RCvMibwKa^zp&S;gNx#;t6!o&@a6v1)S&n)
zj_Mn!wQ+0pqbKNBHnN)pr!LsOyucFup@;Nu7QmP2R~*5YEACH?^p}<^z`)<@^%ec>
z*jshp_^$eje#N<WBZm5)8R`BNzY>^WzPkG*`U79a{wtruzy0<~e#LoqL*@U}IOCW6
zX9c_b?(Hl316Nr5?PB;6{nD-8{FgQUco+H=bB_+B@6NuWKk%OattR=KP5Upu{bx`A
zGvm%N|MMOFy@#){#*I#>m;JZH{=e?1zpml;znrk><5T;__ed%I)Bj)7^Ajxf-gf_=
zzpGaQku#}Q?qaxtblo6kC7cj9M7D?5=^^U3h)zTp%9Yd%Bj_ZY0VGj@4B@2r01I0<
zqY5*g<VgWqteb@JVn{%`&~OHv6h~V)0nf;nc?F1d1lBm5tWF4`xB}D}=oa~zDt~1-
zZ55KXg);^%Dt_+@Ruy|r6eH3Qau5#JSprFK={E3WdFNaaBahI5D?pno3uta(YAetc
zp!{&9Rl<oRn7$Qg`CG=2Rt<@m6JW<f9*{uPT`0mn3ThQjwhi#WT|s%F!fWz*7zdkw
z_)xzblMjbwQN@K~@Wb(X890j+qT!61DJc7s60{naTY|`wJtLf9*b$gpL~ej?BV2J-
z5g1uEa4;&OcnWeKPOyI*jDbg$;-Gs<k~4D}rk|nu!2O3908T?E+FRwI3VL-qI?}3e
zJFyARK%l`DRIiX?AU4AVDmdXu3EHd?#b!|7sX}emr*`d+pbEL7Hu)PX9^y$!?ghwD
zaLZ_~&iNt|0JYsmP=)HQlSTy|o7kY@`E2~L83P82yDLEFCi+A75Ge0rD_hrj-6wcp
z^@lNI2quZmkaBS1T>)A}vW3_TB?guwl<oT54=y&tjeuhdvK5^ATBG9gpOWNj-Swp+
zQNk_O#(*%H*aWSfUEKyP@4@(D^TRxjZWo3$QzpbFC(d#7h{0*c(WSvKvg7Cy5ll$O
z8oQ!oPSjFk94kVGLSV$oy6~g~tp+?*{A`g&H8$gFkVQ2%qhHU#@~{e;1c%TqquG-K
zqiY<n>UeXjH>j&k;*DN}Mo)_JQ|~!)61nvTjkFnsb0q`6!SAuG8h5M?&c9Il_{#Kf
z%j`(`apKK6-=LP(A@O;yxUnl?)6h(dbV^rJ&bz~wYSX&{HZ?w@6F);ozKAQ~5TVSL
zQen4R30K00fZQckpm;mx>c&Jjh@<O>CWys+?X4;xVyGjB?MGC9L>Cyc-y5{iQYvL+
znuxX4YNdC-61KX~aekk@)pz-kpp+|SDIxid6wERxkvfu7ToIco9eyQ9Qr)1W#0hZ#
z%s?~0CDpn4KB)B6B0tp?1Zwd)&{S)xyMgZ3ZuXR@`aJQ2`_Q3=p{W-0WrOZ8#5Hjx
z88#M6S+<daH$*?tE92}HbgZ?5F%Fb+>s`jZvm^BLiqP`GD_0Ki-m-*7k&ZURUePNZ
z?UN!jo1}5Kj4aO`T5vIBvLi+9l~lWxlQvdoP-q8vUC2<slInlggFCw4^kC?^#Te+`
ztHjYj+bw+f;Mxnhv96>RtrBQ=M1#g^YPgi%RMPEUlny~MjoxdIyaIgqm0kD>)`N0(
zb%q`?tAvS#GMu3&KpW0L=Zj}1lrN+sqB)cSq$8hgh<T$UP9lWzzmj@|Amq4$l_kyz
z^qq1LTuHt_<skT+-aaMejrbI68bR055yKtg{qKdn2(tY5o*E4ai8@2YL!|i~{*@p{
zey^mqp(ITmoR}d#`;I)sQCuDmM7e0hU*Ew$8Dy*P2z9>#jt**TR#f9tqWq?n80$(_
zma*F*RdJ93q$BJ;l=<sQEMH-Mp?2G3l6A09hWOh%(%Hr|lxl`)uy*U5Guo^j3<4oy
z_A5E4hT$8umU6%K%0u(S>}ncXYx3_kt4&QqhlzE)gWWP_)6Cn*BDNC4aVy!=Z;AI)
zd}N)z#?cdb{1O>SM@F1bp1qFTwJ{D#b<GueDs);V_^V#6Eb)oZY2qXApu!9ho_CPs
zUI|-;;TMC&>^g5JI_N2aDGxi6H(vo8hLU@eDRyxDhB7W*Nj;bCLeUM{#~t~dgG}R3
z2i<UpY5YoRL|bEYj7VQ+(QAfS#jgOfzcebSJ`#&}WC;opi+7}{y%PRnWeLuL4yxuW
z!qx(A&QRvgjwr?$Q!PXHjmd4kk`IN*TRNgzu4JKH3u9`CP<~^oX|S-xpk3X^NBs>N
z)g5@<5Yc!C2}_6~ybqk;hG{dbgtMW<tsU20AySwtsqWQ%=`Ghfr6K(Efnv?<fF=_`
zcpuPZA_(um7>3AX`k*cYLwLtEtuo;D>UK(M9~uMW>1w((Sq=Sxq^1&T71@(wka?sJ
z9Ng@vbG%;02mYk!cE)5H<Bf+xlsZ;LFi~*_l~0JE=1T6CYWn7ps5JzexspI7wzRXv
zRthQ^Mn2gN^3*Vy)A)MASffVcYPIy6l0ElIrTU}@eRuR-A2jkAgvlHprQ}T3Fj6sG
z2|NZJ+gDxA_sU%wCi@svtXIOWK*5P5=St8yS;$CL8n)DQDmYu}Ee>ZGO}*MM(KU7u
zNrmXZJF;h_q~@`bc8AHLh7O6$Ti#2@+>S}l&Yq>(bD*`tWEf|D($H05N0ySXp$S9Y
z?MSNdj^rm{<mKwfH5$y>-b*WovbuL><_;10bYyI~61EJjX#9vf62XLW%J+}v59_kX
zkzVGC&@xVTA~NsDTNB~}>d1C;B}guNMY#xMJtNIdm~7=TcfuN5npjw}mT5IzQT?QT
z&#psPcA3E-vJJ8cbtFN$g3Y<d8L%Hdvw$MxoaxBX6e2|L$e<OXAbL7z-=fQUhGm%&
zOn++2F8diQxL2}JPTxp~x2Pj!R)|ZzBgI;D8QDmt6<tR5gqJzQrQQLyPYEV7RiD_@
zJM8-CTm6IPyYc4_1l1d<WiatwNquy)^j_a;26~TtNKcA#VfLlAq5Aq#+Xs^lMUAu0
zEn_2ENQDz*QR+A}g*e%J9;>3$yWGL4dnIUj;pErfLpJzwqYqWXxlX~sJ)5C_nKw-#
z^7YQ-=+S9w<IH*m>>ON|eV|kwv9}G(w!K}0?(3$eOZRnC%W!da+U*M-PEtBODXQ@p
zevo^BDBSy+S;7_xPeO>ky_dJ)DG}xor?}qKGbq9?3mfi_5NUg-k0d%-hC19RA4!%z
zYOu)!Ur>W$i0W|4L_73!c5rn@J8BoYupPBqx=;-79mKrRs)FPDY0}xNzNBdIJ6}N#
zugO$jd0-R){4MAEYqih7@fA&0cv1ESS>QVmRncUGuTq^NfqyzO!e0@-Y;gF7Ad4L-
z;-hV~1l8F#o61vvh$g<nAs9_IIGlzd;`k27Vl?`t`vyJw6`}F+Pll+lIuffzqg9T?
z^U-9LZ)n)Iu+bnB{S~0?T@~1F#|UMU?^LpFvJD<Rn+)&`9Sd@;UYx(tWLkqTH=4|A
zB(9Gpr*#L<?iKO5P@!$$xg-D0enWq@p}r&G;}x-GXwXK#bq4?=#Fl?0xfEof!?pfI
zgNeQ;7MQ8=(x^@99&EwUWVUbU%qBM1E2?jb7I$4MM3Vy>7Z1_oz{br)kjwu`QN1JC
z+@M#!5<EB+Vv`3OjLd%I!LBrNPm0*MX9*j?u9Ko4+TY;tb&-(uy4nG#@_{5Hw2waT
z9cWqR^e*M+=z2chkG#|Sl)ZIDL%+Fy^h0yHn05Wgng+A3Cu>>vQfYp+>{GAv+!bMb
zUOMec(DJ>^%QBkvhOWaRe^PXEQqunRIw<*(0bY6Qu7Iu7)_x^y1vHCSgbe{4xPD|j
z->c3l*POYbEAy*Ppbj0WxKs5*I{l7o*N+6H?3{Eh$kMN*KJL2MeNw`fiJX<y?N#5E
zf}#7&5*w}NuLL*pS5#|>R<;wMD>K_?y;2$3l|wHjn*D|Ms?QFrwO4{KzOKkW61kv#
zVfA!6N<dM2C2VYG317Ewj6gOuIBBnh?d;Ojeq?4NH{X?Dl)J_xGaDSV4qB=1jsZ38
z5dbM%5!-ewRGH&`^`VE1aW4n&m2iaRLA?^}BS1r3Ni|(AEe~1a9zZ|K(Drhjx$;+Z
z069ElY6I)x$Y{|MDdHg;8c-4sF~oLIxn2<;d(b&~s-w0p2cK0hmeyOW-aZ{*mMg+U
z0nOqeOB{F>50c1q09st!cb^A!j6mjj)O){@h4MfpYz=^=c*v}dN(1Df4;{!9kM&in
zI!L=Z#-|{Q8HAu7uf+`LipSJb>pS$2QyXl19#c=n{7#}zIym}VTzwsX^w4fl^{)V%
z5C||mU}--c<dz;XwIgfPzjCn$tz$4EddRB{2+BwDpm={Te|2m$Cu=x1nv*dco+UmI
zG~yQ=RmGYtIjfN=#Y4{OfD#K?(}hs+X!6E_OwluCM+f@EUB+@Qbyo_Hj*r1z-s(h@
zJXeBJ_ChGA4$4O-{Y<Yf*FC<TP*f+OZsGfP(Ij^45$<wNA1F1~_m^9ZyI>g|NR=z9
zwt-Y}mvIcJiYqrr2UO)sXfGFF#RaPBAj@>8DGWG@yKLc8B|a4R92bh}iUz9isi_HF
zR`7u)beX}R_Pi1}`VSPL%MLzJguqkXa&}%;Fz_qxw1l4y0E@d!;lsENxu>B^-Dw_w
zG_4C_)k_mUDZ-y?iMo8#(CAmf5i^`b_H!X!oV4;KspTQ}^jR38%x4%O?y`nqr?|fk
z>yIJhE>rkG@wsea*gozsg%5O`QmFJ(DIHRR$%d9w_)7<*<x1ER)SS|+^aIBAD_Rh&
zEMYeQ^2MFj^KlGE{_1SC>EaHIZ|<_DPhht7`2(inTV^nTDh}k;Q=*lEw^DXx%UcaA
z+Bd9agYE5`-fC-g1L%TW84P&ebXOa!eBX3eU&(#<n;z>c$kWLcp(!Y^O%vO|N9;RL
zssXtg?l~T%mNFn*oXK4b=NK12%Yaq!z15RZrB)q<)7AG@6=<)$QOda&r=j7fcO@J@
zRM%FHsVh3DHZhS<U3;nRQeAtg<%yYHD3w{er<#UtBMi#`fw_W>NnBZCqYJ&CcSRVE
z*e)2B;q30pCvzp$iJ@+7yxzeSgoZqtzU}Kl)e~daJPYhry%FE0u7P0tir6$1pU_nX
z*M}=rjg@!AcUQyCmDSmDU}bf+4&A79HU`9t3#Da=dhx9cgjSfAkErpv2V-b@?!i(i
z%h)P%-FH)OPi=m#j5h{?^DC*xcIZQ4u&hHLuCjV90V}=)VKyLEe9;AMK&<$p3)+x5
z(O0NtsKbI~JrLa`s6;vjr{0w;l=Iy$x}Xh?z$<~yF?b4ng&H>ul0N7wsV=)71Pw^|
zmZfj>&K0d(g9G(S*gvSZwf}{6syF(+;gr3Sx*M}TvxHp+xD{VZU4wd4#vVgH&MRTN
zvmA;p%$C7vd?jppV#*gs1ogI-T3<Ecle)~{!M-B4j-%h=!P+|X*&6EeMh^#_1y+C+
zUqc;)Mq5K2ghpF~9fU%IBl%-#T~RH*fgjvw(g}UbHQ%PbL7y#CyOAXz6|LjUwv3HJ
z!3mLdB{dpDsX|P<TE&r0NrwzqEmy*^K_xDl-G(%`uB1a&h?l2C^+K$UXbO_Jg6a!h
z(1r`Aj|8O*TvbLi!<Cg2TxAB;Hji3?YMXRI8}7m!bU9Cn>cMQctPEF$9F6c;2B?hB
zV7uUgzY;c_lkQ4>WWdI_k{=ncF)o;vAwkIF;sP+Fdc6`pXk>3)^9Hpj5Z0AckDV@+
zE2=JU4FYO$ZVsZf;@oN)S`ld@?-~V)#)Z~0+~B&>Eg6tBKDUN-AG_2rGSmB9Y`HYE
z&!wiJK7sl&B&5D&wp-`NxuiCLrMV)uyD`M6ws(z@Y8=<;PGH!Rq8j2v)1Lq4BcV=}
z;K=}*NlD{x%GV=KNJDm;E5Spn_d~;hCv*-?Ba~@j!XAifG1EP5fYDqD8&7RIO)cZJ
zISnmC2VDW%u1D4$VWmlD{}&dkU;5k!)M%xYdP;I@&?{|7HgqNE#DJ2Vw4)91m@BF0
zJ_a0#Pk5!RkS0FqmNuYcTxqBb=olYIjU&v#g%7);KsB~rcFvWcDI6rnQCoSC9P(8g
zAUQ6`n1Qw2hYaZfB{^!;AN4m}ZSrt8TvG}CH>ijKhH(M847erFTvxZ0^El+GzM`DS
zu{B)izOmJG>AoRVJ)rskUU^DX0rwj}$ZvSa`2NU!$nXXZ#s%oQk}|l4jAnq(eDG@<
zP<lf~Gv>mF3};N(<Ab>AE83{WS%K;sGfVdY`W^wkyOP`LlaiX|p=P1>#!$0ReM9DW
zp=GWBuyzAn#s%rJ0o6BXdjlHdL-uz<V|>W^9soS}koAql>w<I{mb?!c+p}Q|w6&40
z?eQVgdX|C|Wa|p5!(9)Cf*f>A8`5L=X!I6bQ4NCjcWwr^h%o^;<3M#8P&2p8mOJ$Q
zXlfcq#338K_8d1^=o2nbqdo_6<_drkF+gXoh(F1tU`K7&>$ws(U7M<d81=3R?7S{?
znB~^&M&Gqz^LCSojvd|&CVHWOpA@jA(xC!_8L%^Mvd57<@JiTHsnF+&*c5cAIhtDe
zZ;r4Iu1>s|0bb+g(iH&MxNS8I9cr@jO98vd$Oi$eTN(M!We)GCgRKLJ7u{r`PtOwe
z8o*+%gf)2HG+O7gw4cfFp3r`RgBffhx2Xq1`IS}jKvXYr^1-S6Y-;uci$&)940NA<
z?9UkM2W%MLS5l}MY{@I&Q%glAM$8h~;$}Sa0NLUu8ym=$k0eW_)Qo;?gCXrgZCyzn
zc}x~{#Y4DtJrp|4>d!d!8C}`7py8~^X|tf?1mn7rm1Q;zN2sN}jiZV8qle<0NEDZ?
zc?<QgdhLQ;T}d|ALqEQ)by>)j9r{TTI{^LGLj#9;>#~}0q;uh}tWJH;OZs9s8D0t6
z#>uYBt_C^Vm9TN>ysiXfwsscraRboeofb3jEUr9sR(KZgTMwmL6jaNQ=JrbX;QWrS
zfFpuh>@u1c)ncd7jD)(bY<7n1)DEbYt$G5Rg<kBh#f+rA-eoZZ`QplecO^AOeXNCr
zxq`dUpOWNa>@b<(3%O-B4n?V?c?KlRl>oYD>2-0Ty$ryYE5TN?Tb5S+8=aTMT*<BP
z9O+Xn7m|0G#~UiK%Rt^xi6EphKw55@ULW|XoKP-HkjpKy87Ra~7q$W9;+-z+=Zb16
zcQp-_*kNoJ62^t^G9Y2RcQ$NrO)A5m0SM#0scpj;Ws$>y=v@|h1#dnn!bY@lL=-EI
z0m$Nld07EjyvdRVkmd1q)M+TVM&lZ8RBzI?du0jR3jDBF!o3Q<+ACs1&}U7a?Oht^
zO3+TZk*)w2nTEXA-l_()S(9hGQeIyH2Z+;OlaanR4io}^8L=+PL}&!N2(@JZyR`jP
zsobSa4sT?v{zy>DRn}x>!>#WEXc=7pUhd@wqChpaR6k%NaGth>QcbL^^a=-mQsn#%
z>9N>sX}l&Yo%onGQL3Kn#>t3vX>w*G7~X}pGUSZ*CSSI9v}_39xRPvH_OwIsHCfaS
z<=13T<F?6(w|Y`kU6en&Ff+>5XvEAkTG)ilG<mam5#~+0nvj_$qZ_c9CYzg(m_~D&
zh?v%hm9z_qLBdDF)!r@hk*PVG3}@UJ?jy^&k~lvlYW&e%`dj&@3}g@cz;rG$h<#)^
z0}Qjzk%|BsW*@n?k-~Y48_$4`xe~U$v&420kZ?r{g8Qa!nJw3Mb0wU$4YD<v(sfb1
zkB}i(QbUv}ja(mF2`aCo20&Zc@1JD?*IoFNB6c^>J9xU0F?kE=Ww>|WB)+w}nBNu6
z|3H$7M3m&xfPC3U&TbH)Y-PW(B1=gL@3Rsha|LYs;N8=h2GC$1xw@l$N`zWlG>%Xj
zJQ_wQa~q(ReWZK=YT1H+StbD9XQ*pP_q&hW+{o^`4~=JJ^W8@p8Bmyy1f^?H?jt`p
zU@%w0z8Pj)e(s_Uz5=#eJIJ$-_JA1ZzoAqUE6;W&z1_;#X-H_hPk+ZZFdBXBz|~yB
zKUSNf0K_H{D@*Lg;_S<-4R)4~1f@@fkc|z9&?Y#`kX&?!kky97pgZK$MjFp6VZ*sL
zuYk?g^8H9q%3*H7w+w)qD?!V3)Vl(X&9lTtOCjzE#?KfKG+Tf!!@qXO&W@;_Nu5TZ
zXJu(We^JWPD|(+(y^{kw0^OrI9`$GT^<d^hIvKOGL$)|(aEEMhU~P8D7_T?+?2s`I
zw9O9M;=tN$;kyi2n;o#lfwbA72uDk(%?=_+48WQlvb_PU*}{C?e6l@P$Lp^?9fN}L
zUAV;^a#;h~xCQ1iz#n(WWnB=-Cq*2Ap~tYd6IruE9%~?LcF6t)vS!EYu?DnehdkEU
z33kXNugzkIEOP88I}Bb3Kx=l$WesS}CVVWD{GtvvnwuK<Q-*1MaM;{}iy8LA9W<_M
zOWh%}8N2S4uxn6<q2Of$Ze~Z*gP{+Dj_k9uz>byuw_RTBgRJG-rM(XnqF`eND9x2%
z8-y0S61I#u`zu1z1#Y|oHlK=cyVN&;(^rB$2qkzlPN2U!f&(b?k)Q-RQ}zqGPl>mz
ztcRyW7$B6N%he4#<Rd{TXWF-VRa0>#JSH6IKBpl*TFX*>@Hc06&EiI>W{^(pktW%b
zlA7fKxXcz7Y=Cim`&2DxIik3b1N@fZI2f=_x6@^f)ZtfxQqCE@)&n;1mEf6!Q#RBS
zs5BoMAJm%DYdtdf;g;Df)S3%jJ%EteZft5|jhI@RH6T+%6Kh21>d~MJ1??K`R_T1`
zLT9@ky3pDBBr_%ZXIphz&R0-<?e7yY({xu~Np-$y=0KWuMQFNIpI}@A$eQi#U-*OS
zdQ;QTecovK4&Z9GH?{rIe*381TDV(CumKd!l`ND~V_yN=$y4E0N`V0o&6Ti~GI+O;
zV51JWdkZ}>a0uQzG(;%O9cUZMafezuRl>`lcHFLJpdGhsK&2gfJErwi>hX$DykwT`
zC{T42@}^|<J^;K)3DyFjHz~pr1NJ6G{EQNRlM*x!2S$o8U%h;uACZ<s@9cMbAJy4$
z-bh?gbzX0{cl2Fg`2j#piV80}$}?0VcHXk1LdOsImr}&$O5>%7-(pAh#U?Xsz<HG-
z%wH<V6ma@VL#7CQDixU$c45@;l<a-L*Y**)TAO$gg|2@fL#JF5v)CzKCyWBrqy)<a
zfSMHHx@G`Uld=Uty)Kztqi+;3xYCcA;scSY12~+Nv9(=OPLpdOUN%Jwf?%bblX?)w
zhV#=vAZ|+71IN&&23roI6s>xYa~wq054g5JqM<$o-T|>e0}k>O;T~fEQ<E}u>hQG;
zb?R_-O}#ptTzg;MVNZF08gSsJ2)(dYMfBVnr`&L<e?^#aT2uoU1s@UJoC9|WDS~z^
zm`+NdrUyVcDXZ}Tgp(3{+5pvjL`}Ukc1!eY13~m9Yy8<{O+L)nuZCjw31{V}MD-qI
zVGSF24KlH=sCw@D)B(sz5jU5F<fMe{53EIJomz>qu?DWBQUscdfs3n>Va{hQMGv(<
z@q#^2te5L_YCgjj2ZH;LD_K?MoGo_H)#t@dI*Msae#$&@4FGCVga>c*Z>z@}>-06l
z42R8>u>+gK*y_OMP<Zwl=C`=iJ|Z|$h7LH^!)vjDv?fLDfnz=RQU|c%r3^a}Xg@xp
zshYul@-kx>itOW2r)19AVXtV<8Fi@;_g92Y)e&o0shAX~EiO|Yv&Nu06;gi;s#B*c
zbqvIam8|h+s|4u5XdGM}wXOiKfJdz{dKGCGjgF7fP0e?XRvW{h+I)>Uz#B?b=fg2d
zZ+cS~sW)HiZBTF0d>d4nt~j_cs5Kpjt}&oBod>T0v`1!iVmHCB-pY#OqjIy@M?FAl
z<wnbHP>~AJKL!=)J~%iHFbY)$DRg1xcwgHNh@KR&HLBkoJY)_aZ$2^^XM>7#^YUVh
zT}5nOgNk&!woec_r3~{_dUU(`NIkk8Mf7lMgBjGKd#i1#QDvtY18P(u00VHJ6hY4b
z?~@|z1B1#o0|CaMrd1@s$fQ#W0~iJHc}m8nf-hTN{GjR;u73dUl_EZ@-d~D15UO6`
z`^TW_-BXXJ=G{8<4PaHT?3U+MyGp1rCe`jH{9sI~-K}Haq}r|M^anDmTb=wS^sd4O
z2H-zel*P_PYtn*~nwil9V^T9KgkU86Cj}Th@IEPm=WooaQ~%_!c)4;#7#0r&6DoOk
z4FL3$DdP~RlDF*rNtL{1?@y{^Mhsj@y~CzKP$TcAVNfe?nG%y)dFzxwluydo2WVvl
z7YyKhQiLu{tdMoohl%|i@daa+T3)pDC$+NT0<Ne!iNJs{p>dZO%&!QI%dVfBt!u-W
z)VRy_aBAEOFQ`X(m9Y5(&66U|2Nmwp>0nafF7Z4Lut=ti9dJx8VhA$vY_8(9)nH(B
zTMB0eN2enKpxT*Yj}@tL83QmT&ZcW>YoFAni!pa&QJb#vpN>Ucx@6d|#vV-W?W=Kq
z2{syw%2dGuSA_Ycr*%}Np###QI#u|<6=6Dg99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_
zt_UwihW(<3g)&`Krh@$skjbWq-K08ID8N`$r-^dnv#Ou^rWds-9z$Ka2wu7(yn@D<
zy0NHCmyQRkl<8_}esXB~pcj>C#t>BIk?i3-Y7Gb3se{1cL3ZjOuy~H0N1O1X23F+2
zSQ~@E`=_>@p=X!6WuU;5lIpc$1;(PzouPqH<tlz)EUMhP2^b6dcDjZ}eLHy&SX8%)
zFc^#KcKSOs>Rg2xjD_d0@xZ#Bj$*A31sIHlSmczUb)JwFWH1&^$Wx~U&{?O5Z6EHz
zQ&vK;VyA>FiE3K024hi8GuB}2RwW+YHg)jSDPU6vE0SPr>R^Quj7=4cUA;s#76K>6
zrV2(h!Pr#7Q^$!-9XzM@yiF~v$b+#<3oG#83h>@|#@L;2?cHBCPr_42gALWIpn<V@
z7*^cC*wnlegzRJ2A$Q8`-&CnnX8)#2on6nSN}c`f6c4%xGZ-5Rb;=pMsZgg55L+2j
z-vdMiWPU_VU09q>92dZ?p8`I-^e!R|KA+BpQbpRsv8hpq4E#-v%AkR<udW=Sf$DHN
zq`kMJ?Li>Z6|EBR!PJx^^k5!M6<RPhmFJMdc2j*0eefIVbLdR40jf$F9v@gHLpJ}e
zC)Yn~M#tvQsWgX(C5KaMX1KtpL)WJy3*D(Q6*DlLDs$9c`jo8J@Q~r|)R{wuyQ3Dq
ze5cAB3q@G}3OyK36*^?sJ9X%gUGLDLiar=T=Uy4gcz-h5y^gFyCc9IiD!yPi73z3R
zb{|#dm<9(Sd)=vH$3PKdFtt7EMj>VO%{%m~A`XUAzbfcpICZRo4u(&SRL*^;jva<#
zK3P`0Q@=6_VK|SkqZ6GloGMq53B##%hpc^v)*Z47oLaYn6CTL0K4{s)8I%$Zm`ZoZ
zv<D$Xis&Nn(!7d47*55j2!!EOybM7YPQ7dA9U&Djf)K7C2csZ_;nci}LKsffYp?&`
zse4WSf2Zm-o(epwggwQnc@c;345#unIscu<U&SU2<V;EtXCOFS*ZqxC{VG6VI8U}F
zli%r6R(!#TRz(`yLCvc8f)UiL2r#&U`Y27e0Rbgy0#jX4y>nY?jC#~`ArRD~3QZV6
zHEJNV8{m&g38pHjM;V_mf_l_+B@kJh<cb(UpR+-+2lcG!*bqFanymleNwoqF9>`Wn
zuq_4ks*SHl;YIOC5LBV|9spu;dbMN3WIuHP2;~pgbwEIinu3Q1P$(%wi}Wg+4h}(G
zYb;`PT^@!gRcks);8rI^crd-n3U3&}gQ>lqf80iu4AbdsU!MP<#?2sx5v6Sz!|<e}
zX1B}U2eVX)I3rZIU5@{ty6vyyKcH{BP5{BvYG<WdZ(W}Mphp=A2cDAEcoiNo0zYBv
z^dI*?v0h@A?hks88TD`_7=(=d15Mp!*B@%?F5CVz`s=%+j2_FlKh)9;h8U+;i49Rn
z_bnB8=qK*7><<;Sq9MkiqE<Y_I8f9T55Z^E`eZ=FI6UhrB4Ql6oV#uU4mElg5^J1N
z>0Kv)LzS+`hyjG+N2C+Lp$aEQLCG*g><b6_S#b{IP(OE>@`w64?`$84&~@Dx9I9u8
zK#Wrgy6d*!P(k;hqr{<#?z%2G)X-gLf<q0hP>FG%q3bI9fe32__XTJ1UFp8yEDTt<
zkVBPScj@&c>THEfj6>bqW$_;>Uxho2165nW4G%=<mF^4<b#2EX;84+a9Rdy&ZEti|
z@F{GInzre};84{nN@66cIR${^jYCb_U>_XnSw%^VLp94ViE-$QMgpIwWI0-ePFzWK
zv+3Y*c*t$^GTii}=%&!pv+)e8@Q2x;Ya8zjW}~WA0K{xmwaqb4vlvNJQd4y$=$501
zE^W0%H4CiGQ?hymilmqgMK(@fa>H?CHoB4-NAaW#L)-XCt;)94I?lWbu9%Gn+{UBF
zGaEIwf+=R>@wH8Lak5W5H(U`qB@EbXRK1P&0kcu{X57SVP`hoYo7B2(ypu$|+jzd1
zje55Y^?<s!4RyU#FPWA~f`vIy#IiJXfZDm?fH51jGiLQES-pQ#^E@3l(_rauR?Ni&
z5%NbQywGe^>kPcOl2v66geqG>6<36=>##5zb#~*;z--jn48E8R8oM=3CN*{wr{8Q;
z+X}*%jcU6!b%I)3p&7HC-wwhua-zyExFR%PZt5#w^QG7iqB15BR!3nOv*B*?9G)d+
zZdo4zjtIAW$8Z#MF%j2w5OXnm{hM>uJ37W2g9!@pqhN{&7}Ythhj#SM3k5R^LUj~w
zF@c~u$JNz(`{(fNFrgXF;nCrlP#;Hu857LvM{yam=+{%SP!7~#<KxL9TOJrA?+qq2
z?m0_UCVB_kf2Q6(M|TDjagOIqb)+=vm0(8zV(Ln;ZvilMC3VqxB?GnCn}zx1eZhp~
zawVLGRTDf25}7cR4r44PB1?~AEM`KZ&M`f9V+i`pJ8p!ph?N`@UZwl<uJHxh>>6L7
z(XR1DHcAtIBE7;#f>O;{Qx^hr##oBk;pIK2so_)Wys6!Th0Zg;gc*M_oMOVzKOvT&
z`8f!jpshb~QaC|Vf8scCgyx&z6*@tieHuKDC!}KQ_;LiwyMlpQd`?Z^m7udY20bU}
z#h*AUeI!}B|I#-J0MrRs^b_c(176a*9)Ny23b2>}KOIF_%)&pNa5ZWeAwSAz0_t=a
zPB8&=Itr<n33ED%r<g!FT?rckE7lRZZ`#ZfzI~e*(b5<vhP2r3ME4crctzQNeYQ5y
z|D|S1OP*M2YGFWA+c6IPCnnokIijf%E{v$G_X+R9iK&(Wi#jpYbnP!kAs4eyQ7485
zxv@3|8{QbCJoOX&4kt{tJbOore1ae1C{$v?M{^J=F_D+(mf4j+%e1p6Ku#yRo?DCh
zMAvhJ@3G^-^=D23)LKX%1MrlR#^2n|D;Lxi<Od&RlF!jFZTh%@K03-LK1a_IzSQy+
zJ}F`qXe|aj%yLa0WelHiUmn+&3vAMr0AF)OR<-!t!bTnsJ{S7P>5;#ZoHZs6e^OKf
zkcB-)me_KcYsZ~WEtBpjwfG!$0z3)An~4`X%o0Aq26Tj(o4^m9jBuEM4jn}}JQHs7
zqY#G)zxwf|d4(eKrQt&n2`-lp%86ZSdSPO#Ya5d~HFPK{pK5v6k^3lz_)PTC5!`M9
zS#&Z?V&a10xD4dF#5gYZ*#xHOC{AMH^5ZBfVj|(*QC!3vf$k2J^0<72pSz;`8W|;V
z1uKhe1^P`v5))TJ$4zH|0VU_Mih(#fLeI^*PdeV!G;|zdDV~(n;_GT1TF<*$hvrk#
z@i|+T@P$rTw}){O6Ck21z*E8Db(EHT;$H12RALtI*Qpzz2a@csVk0K9N}f%#7l|j2
zvXM_@r#yhvJ#$uptw8fBQepx^bQCFZCAn;Os9j{SJIqQx3ubhLuA8_9JqVPTKp34J
zY8r}g2Yo0L0Hd=*Z4Zo4x*F*{j}UruPV~>;se*3XG<|1L(Otn?t2!vd7uV2dZ%!37
z+m_`EUc9rpQzWwJY+1fQ7M;D+@WQELFEw3%JbS5Ws5Yc4p9MZTg4s=6+g}NM1Gw71
z61Kf-h*M2F1|*Xj+=U02yQf6e8QH>s3mu{5W}$_y0NV+$LRXR<d{R_ziuN)nfR2)r
z*8pT2&x5|0ngIdq*`|h4yKU1v9L%q=mGTcA<tM+A8c>;~3+itZIe#TN8oJ6S;4g>i
z%O@Z*hXA?H@Bj@uTUxY`K}Vpr30%<Gbdpa%e?AhF(r8#mJ%RRHGMhm%dX$}f0#S4&
z*ei;xv>wE!N0!(u4rJ?~lppkxl?_DEDNM*yk{sQVm0ftEvt(ogEOb_&lplhSaFaAc
zSHx$Oj=B;)WMzrHhR#$<^DC*ozMnEOhM%?75|rkm1-(jTE*a1ZDszcZa{@7Rl+}DL
z=*=Y)8Ze@>WJV{7=qwr0Yjcpaq5&Z~YpHRlR;4<h01zFa=w?BP&Jst^1Yqc_skXdE
zMH?DZeUuD+f{yqAQg_R_zGNQ*-guS_WMr&AOm#ki0y>NC?}@DU&lN2Qva>_IhvHmA
zGY7@FhMI=re3P9|totL_-28kOXUWLMcXJkuY<yW~(dT_7IY7F+uVAAJzWxm*xnx9d
zD9OdId*43DtvxqX;A-j!R3MU+PatxS5O5P{pR<61e`bMw&T8ri6yT&!djjfn=F#|}
z0+pnEZbT~`LE<L1;WKG^1K51#QCpw0-wd^bv)_z&j5z!WA2&CYoideA0D6vKZ8Npe
zEoV=j6y$VIIjy18t^}QfZc}3N3BdVD0NdP%!9G(S>kZvDw>k&iHs!9~rQ4<)*1NWY
z=P-Zy+|YJ{u3bruXrq*0_ms0bAwsuI8y7akQO@%TIMA7LRD&$&Oqtst3p!KRQxnji
zGi7kYoVpS|2>NfzZ4I;RBSGmdcBMC;2$VR)p-qIuo+*<Y5f^95UyZPg=S*4Yg(5mr
zMmj)5CzGI0;D?TYY!m3AlSbYHNsUitx>pUhisPbkr%xErN3gc(fU=w^iyVn4uB1lj
zbzW3v^ed>Y%HDQp%=tQ~9V&CmKkYa$PTJ(3^T?U9$8lacN{&8#aGA;=2Ttfp*fg}}
zlv}z`LTAWA2T16-BD4%osFJ8p5D^`K;wIohXUIxVgwPqH3z|6VogpJVo2505!{ZS^
zZsLG>2F!6}WjQ0>2h@J0r0ElQpOj$sp)!X&)y|{la6C9Q=8&Tr;GZ+(s0Q}u2o*Ph
z{W(Lh_KAb~8M4>wEPsZ~b)>;L1Ab~G$~nrR{>+NYJA~Lx&$A_Rp-%vHjxcc(-i$No
zr7m~J=j}~(1G-O%&L{jPM|igh9M6^T!3c=FqIz<){5xg<7@jlaqK<||AhSIEIcK~l
z^1zvK(Bg(u=nQ$ND-iSync$%1IK;YrHg#lzI!bMRCAC;s%1M-$8jiCw<fSGP$zjs+
zSrN8JsIysNxL1Nw&6(WP$ZvH<d&dVoH{_;{nI*OgJvU^51BLUEpi~=-$>1)B<T2UX
za9SSI*N8ypqx9tyvCz*UQf$V~zq1AuoXJ*(qxMSJGw3)IhtGt+_gJ8mJ=50*0-j^^
zNyCSHO!jpkq4_Zx*ns66laZasoTCiq6S$lsjM)SR=h)`<4hYUMS=0r<xdJwX6QJ^<
zPe5=EAZAaAylSzjz@TJN2lS%Rphj%}Q6BVXW^%kEB-upzykqi82Q;C{D-BG}G1=1x
zxm%CXqArlmQ7ZI_`;P;#*~A6OEu(4NqFf30VqCRc5!ybticD@?)f{F_pMd8algVA^
zoF_&6$wnPE+%X<m*tk+UrjPrSwlqblPf&MV5u1X#G#J^qt2#=NKF_EUrUbXz$K==s
z_U4!z+sHzBOpa}2syqh2cENLwDeLM4Jm(OeHUZ8#Cf7EwImeoso)}L#(4G=){D_aK
z0coEAc;<9j*@c}sf}za=z|-mScmp|eI?e994?W6mK5=7ux@>CPs$K~l-ne_cB0d+I
zt<&Ru>QlV}jvJZ{3C^Dq)fi-)pVDnzPH%Afola96w0}n_(4U#N)F;tqvoJ4*nan2;
zFQ?0X2H@o*K`AG;%U)i%k3XF*?uASHBOutq&Hm}MpjQ$w-ZFeE3u$#fBK)~#ksj_V
zsY#^Cy&5!K=cl_`MM9lE)i8XaeWFyoA9`w)yc#Vfm#N8D1Jv^fx3$_pgT@M_;JT>;
zP;lMU0VugHKlK9K<S;jRN~&M9i&y(7x!%<<lw9v@7|55?yPAgD>s?L5|EYZCt1vJ}
zn6CwF%X50;li}R#O%Kikpc0xdpn8tLU90UZ!SY_f3Y~V;f2hKC*a|dZJ8A`r5Gbx^
zRo3oXRx7nvw4>fb8MdQo!(p$5nnvonBM8?@$jdG7$)DuPYh@NMz+FxYH4Ww1<fUE!
zyPOtkyR>8DS$YBMa+<5<z#yG;&I^4%N^QO{z9YQX$~if0>oHJ$jb`w(fRMYQg`ZT9
zX$LPL?GCYB3$T_(xAp3P|DHy_^&+sP(QSPt`Su&#)(f0Kr<Fy$di@?q;zjUFTWq(S
zGFQNcdya3aRh$5o#{5}8E*=5H77;3KsB6$-jV|l;`I1i?szEK*2=%_AT9|{KgUV7;
z@>RRT5o&7@*V0T|Ab~B-)Yh!YHMIn#)r>7oOf9tRlcE}u;RiLGu9jDpI5?c<T2~vm
z#6LoFEdp4WqC6!v{raE_!P44SomyUvX6gdF&qtIc|1Hi@uga<nr6*s&JBM&rt0UU+
zir8u?vnye{sm!hb+afsT15d3lElv<^vH+C{LbDc-GFQNs??)Xc)NFakusaY16M|+f
zKwRRu`gPC^n$OD`x<d2$N^)n2Ll5;8RbSwtUTK`fp*elaJ136z^nyhb<R~mr^_LFn
z1=A?bR^w?s#aU{)mPC|^bC(v-F>#h!?--|)G{7+-z}B)Vv0>v&oE(v11k%7|cBZ6$
zF{*1*eI4kU=&KikF+xDBg$xl_f=vb~B(9{MJM-V{C(`{~5j#7v28UWM1sQ^BE!g~V
zObzGAo;aq4Ctkjx;e}UkYJ6c4n%Z7?^Tw!}g`6F6x*Fg3Y`Pw_(PbFJE6-w|G6-9q
zlvHn;`se6RL;oDTq2;>(b&1pX*yJCGLof9L)FtAmbEUE(j%KFRS}1Gzs=O;tim<of
zsCy-Bygs~$!^Z2&yaKkKA8&-RKP|*(g>suOB$Ejt!mgxxD0K_S%aw3{7&+uCK?mVC
zxDs>_euXQk4uYm9h~Iirl#4Gse{g?Izx6`8p9uP`7g7R6Y_)pzTNEeo13^tV&&^j-
zo!?n1oe;6qjMYe%T0!(sD5?1ZY9>NoG$J4)WHSR46GCCFV&Hiqrus6_7y6_Zd{iF^
zO4%0~(Qt7^FrZ?=4Hhxf%*3<~b#7u-hZ?S@vQe-(N9HhJK+=Q|TMI~<2%6&n(nQD}
zFC0yT5#6=`oe8BrUx3bpU|b9C#RwVKl>;m#dXQ(4U564BNb5?fzg>@Y^tWjQAgzp`
z`8`SphOBRRVk4xk;jN93{XL)tLxh_D({KO7a~Ey<RQ>$SZGGx~lveYY<8v1JAOG9m
z{<q)yZ|(D6{qO(sZ%^>ss5SO)zkw<}-W<+Idl8EV&<;OOC<eMuOi?HZtFQVtLIFPA
z?KeL>3-<c<{N;RZnJ!=lmQ!ZmY?W%Vn0ApB>?_L{$Q#^96Aw-w$FU*v5`d@kDAms)
z8>_-~aNa2X%!+R@2KsyvmJY^gza&Vw$S&T7?9^~ZfxO|>!64i6>M&SDaR4uh*aVHf
zg4{!1a2jA9b-BM0>T^T{FhM?-p5p(^=VRZ;oH+DPE@WML-p{ty(OjR8V}91p9LM_p
z{KH#6yZ^Y15Zd}Kqpi&BT1Ir~yvvAZoOc-+O=vA6oYQI%@uaUsq!cSyM9i+mHKcpv
zcM-km!nlZ(;7+TE4DkmHMf)XF{9ZETyVH_U@ZGy&>}$0=xm*|`ujQgJbuAZtO<$`;
zzQ(?RL_L4AT;we!Ea>}syRISyS<sT{)KgkB@-Mw-WBanqN;mK~wPrrYyU(KeES0|R
zrt|s7n!Wq}b87}~F@!7)Xl3WAJ)o1l7DLpJ@kQa?1OcVkr$czs+Q&ZvzItr+SAYh4
zZa!Cl2Fn|B1^Gy*Xz^}`p+h{Bf7DixEBo`HfiCg#8fq{2Nf%l<oF{GInL}98LOeey
zsRaX6bO=fc<a9XB+KH?V=Rq4p_TkFQ46^$WkTg~n&>|G9<Gw1OU!7N01tWjLd1Hkw
zJcJ=lCfaZuuLFuz&`|K%Mj}I_Lf*o8iiVXI&Mg3jT#y<2x5Da&5T8Kve+1XLf^-O1
zfuT20l+Hsm2z*0W&&cDVfSxo;KayKIc;~#ZDyudK@;vSSJO5EHTOdtDP&`49=BZCT
zgwcdWADahcSpBhiK1PCq*oVjRgOi|8nsssrVKfm!5=3Ys$mEvMDtKeB1kK_QxTzIR
z6>85shHm3N>XfAwNXhi1<i3&3%cxW4T5Mhh<A@fUXJ=#}h|QBTv!2Ap$r%ATv3Ybx
zo|M4merEm?&!3ok9+;nlqu}O&8A>BI4Gx@Nub>*7H3<5+&aA^~0GfGl2;AIXaY&BM
z!!pj$v1#($WCp1N@#TGM#fBf$`=**iHk;TuZ6mTOHcfYW39bY`@M;51;;^`>&ET#G
zp*#^d7F&T42ri3V=j@C<y9Epr2gS`}HsaS}(|%&Ypb+2_IfbqOjYcg}YLF9n|8>GX
zfi<d>a3}EkskzGoRDzlb91k~7*T};Zn}_Rzu)ZL?^P@hi8)QShg6ao#WQWu2N?4^j
zBA$dRs;)FXwtf$Txj_*vo~%1ubFq%vrKPiu8iqC!0JK-UW-K18ub^zG!-k=dNZ(bW
zJH!=gyf)HUp~i7$Ts&BJgtT58ANNijfv;a?e=B9RT>XQ#TCNV(GK__T^|f?rZLO{T
zq<&gkkHsNzZS@9+#I@DZRS|2enS~kNoCll}MPS$))Y#f6)!Z(+39cwdv(zfgQPLZB
zxY1)VAfv-OA0#eJ^52?n9;7?Mx?|0+TGjYODcc<yKbT>zh+TmW6Jud-P-2TG>5hwv
zSVJwR8e0lR?zrvvh)~MUc9~j+TU6AA9f9#F!8{gO>y@x!_(~W5Uhj(P_G9R0DYvg{
z_1Bx~)D<09NU^AIdr}D8G6n*cfe@o%N20}8{Cn*;tLbzBt+*N+F0J^UHjwi%M1t6R
z{k~B39T#&~!bS~?s-bk>o6wmZSA<uBW!aGeB<9gj$`va9!j8lOflk2-I(2OBP<vCU
z8apm7V}_cZS>p6Tv!MZ~HGw&=B&}Lf6!uJC8i~rh|IWD<tKgO7T$59<e-3{kI>Fw-
zQ5ND8>>wKn(Ft~>XAL1TJ9tY%WP-hTO`Z^!U<dh0kV^1#bg1t@=ar6Ju`!n#hw^$E
z2d`+QpfpFvZF<bf=R!S+MzGhNd<eDK>)QTF(OCRVy_%^Zz-KASz>Y)%L8N9!o`EL>
z)x4tWajDx|URh#0&|`CG0PuTG<(Rpm8WTNZ-5Lf3&)5~@nDi|J7;z>1LD^iBe(i41
zc9UwiBja%hzS-^eq^ntIyV>Em=}4*^lg^Zm%*z2X!Va`Zh>WlUb`k_`J}JuXOIO1w
za3y>$6d8yJyN&!e`-z<}h7_?u&kZSJgPI%C!&WaU0Ltuz-idK&nsj&yVjN8p^xmL@
zyBm&aLwXocq8I{acjVp<p*1^l4+PMf9mxk`gl1}GsZ^8|m@|OE>_At=kVXaqE67dQ
zlNjvF=K}69NFIoCxe0OE!9jK<*n$kIa7ZZwcou`q<GlcEF_zlGNllc69ZYF4mL3dE
zM{MSkqMA8s=Hz9&MNT#p-I$teC_BM7yYW;f!oqIQcEWF7NzU)oplWjuqBpOgUfGnz
z1x#Tip<xH)FvMrrN6Qi#MJ9nOL8BvM8-ifYTdvXYz<eb&npETkwTxkU094x$xmX8g
zGek#tCDlvQQ*r7W)yw-YDe+<acDgzabtpJ!2mN7)hOmPpF~maHi$?JY;XykfsWIyB
z@FWQj+G`$SG&KyBIg}EvWAZ|Lgni(=CxB-M=VS=rc_nu}B9i(kNiIl}ejYgG*+D5^
zmLQ>5l53HO&?~raPoU5%$k!)OXa{L$2o&1K&Jx?it)SuEL7fT_dL=a!YVZMVDn#g&
z<k*~XPklgn3IN)H#0~*KI{@AxbZ3WO^h!p-gnR8aAuMMHvuX&-c_q~!YVHE0-!l6b
zuyU<V(;Wcz5V*5rI}L$5J8<wJaA(g=Ic)MCxntiBLOVOQ_Auf|I=24+wzE$tN?|*n
zUOcs7WE{AH8lrUl#JSMu_UedD2$P<^`t2z}jT$O2gw*Wt)`#(A+`;V|LTdJjE95UX
z_$(7WguJ|xT2%T#=g1O1P6T;`$+O!L2oeNdb_9!rfR`Os%144yzD0eTbMP(d>x4BF
z*3@!c6$*ygLERt5^D>zG!<sfx1l2^63f@u<j;w+o$;uKN#d%Ml%{~`zpk#Yb9O%02
z=7|%XNdK;6W%;d>FRTl#eMR}kdZ3hVOK{8%#_k{~U<adjh!e1r_dB|)VH^rY6WGf<
z50M03L2gb7+Wg3Bp36vnAgTe<QlC(iA_=^bm1Q=IBVPhL`y>*k>q`bldkD1ILFpe|
z$6zq}e_ib@B4NbccSY3~ewZ0k7s73JMBRmOn|(peby0kEoZq7B%Un3=iSDmgcwdO@
zuY)c>fbo1%k_)cO2nX^0m9TZFLy`S;l-MwlFhqiOoRULO(2fAd0DE7r`~o3}=M_}f
zM9<Z6$PeN?JNy7wfDHl8g6OcH*UW#jn*_oL;@RPjxDqxDZP;~WMl@-38Q2Rz7_t0y
z#H0pD{`!J;6b!U4Xvp5wHZ){^KW=dQhgkmZwO)QSLV9+D=LXsOdIk9gA)HT2vNu9;
zc4WxV?I4n9L?h_BBhyASn#`4m<GV(#Lg79;@_BsKDE%iyXGdss6r%HiC?~VQ5U&91
z5XavYRNrZbFX%rZKCh%cq9$M2f&vr_v}a<I5D2uxe;B}kcDNX$33$@shYW&1J6x3^
z6lgC`W(Wh?5$qnsfIcazmnh?XR|yXVCPoO)4nJ%N<9Q`H_q=$zg6jQzpNam<CWn7F
znvC*I{n%)g7b!rrskU)eOd7xrR)G)=U<dU;GzC?4@DqfvqkWGou~jHk!bUqX14Waa
z&ip}<?0+5i$RQZ%mE^LJ!wqiw5Qwycxj))#%olfmG}-c??hjD`cF;NmMi2EV+-To9
z@4WEp8xGVa%N<FaLMYNJsZ}n^eJ>za^n)CXtOH!F1gQW!E?+`afE^b!@iGB+T;hbV
zs6B6ZqR9~lqK-%)YDbnVKfGt_8;BYginP~Vl^<S`b<l|T3Dqiv>co+D5R~|dw{Lfs
z@T0u}EGK?=H`Xg>Y)aTtsaPkv^nN;Z(DXwSAyb%Tne$SHj34YDyN;PI-oL(!eAvbN
z*9)2Qkx>1ELdM1D*MZ`3p+v7FTV6Wtdq>mjt5!9>zAzVGFrJ)bKl-dm$Kyh-^yKh&
zG5U2-_&Xq?9sK=%<Xv;av`x*v5A<Hn^}18`Bj36Ybbg{#9oKhG8Y4eCfa99lk8A;-
zS;Ch9s-%wurNn|9)6GF;rS?NJ0ND+%fZbf^mA+40-}^C?&?~voKq%$R>3dNVu5`W~
zd{nM%z8xSFf0Oxk<b!lk1a>5ibS3lcl~>Z0%C{r;<dwi!a>s|EuhtzS)N$J#OHGDA
zLL^+df4k#S(Bp7Kb>MZONjqruJ>Y8d{1iR()p~uc9wBqd>yIv+=#^yeLS})N+Vmi3
z=sw?-xVIPm*^?r6xAdlmzGGyMcaa5lWSIAmB~S_I9}faXI#4Yh_>ci=@z941REvi`
zWWZWd0*eU%LRU864l+3x?_USuoGY<!ujI1Mu+@@Ocl2>1MXe);Z$}ne7xiBUsKuGU
zx5s$0#8w90qc#A*T0Hdq1M%sh9Uzcd!@>O5!MN{A?|UT&mC*3SgiEj2pS*tgKvLrw
zYH4CbQslt2xQPBbP%R#c=jerNai#F>z_qxt_;#=?dKf#nvCujh>Ux4-T-ka%Fv1?v
z#lR7J=&T-|CANYzH_l|f9XyjR?!OK$%8vx48jVzOVPrhoJ3Od6kpXrrepjB~jxXfJ
z)Ajs<ROd-SZsftUJibE@-G2uZpv&3^hQ^)8`KK3(#+4hmgB;XFM%a-e{7Ud-<PrDG
z`Fl%OA-azDfYZ2020QRHPE1$_p2l6yH{fX=cNVi>I^F|L<Kh_X0MxkaBD@eaDWUEH
zq{fvHxSuMqS!mH@A?ye&aM!K)u^Jq8I{-5-;=z8P?3k#xe{`UWPOw8qx-WS$phvF=
zdmKP9?mD&u72`hj)Lco>gLerOFeXLN2H>{861Ki-8g*<x3sc04v4g947p-7FJ4<{h
zRGw1xc3@jv6oDP!mMf{dr?j73)PEh|6&Lqk2PwTf744}%WAiw0{9F<Kj7igZ8*xQ0
z=D&`}qbp&%rOCWWZ^7_%;>J2`Q&%3|4)$qB8r}|qY8N%&)04y6U0U`)Z3%RCCAq>k
zuec0|78lc>rGfsGq>$7g^mgUVHIUN#4n3#F>!SL*lDrdhaQ$6DVYsWmx17_z@%>#v
z^*7WqwAdDpz5&(ZBKorewfJ_m4867;4MVGK9=IRFA<LPE*KiDTCE~TuG0jC3XaK>u
zcmb{9Jm*Tedqp)O-g_Bh5eYiBI+VJAXNH5T@AZxlN=wXuh7+(0er7l&JK$&5R{ona
zi_hAHJ~Mz|T)cn=5R8i$&;W#SA<(RFFprBW@JebeOf(Fwx2J}@u@WYyc4LUT6*J@|
z@ICZg&k`rHwn8V7U`ne0gHLrVQ&VSgiW7670V?An4m3bzT-1Tqg3HwS<Wy^dk{LWo
zE-abB?c^d4G@xaCcj{CF`MmG0#-YWCI5Px0Ujf@nd-x-`g<d+0NHT-#&BY{WaL;)%
z30lEgTo^F}ti=l?_CS=2OC*6;l8Z}3fmf1mCu0c={z(^6pmn5ab78~`4DwgPw)2oD
zqQG0u8Cul@PH#)0SypHmU#@3DtBE<#I@Ff%Vb-CwK>GKjB<GYQe<=z4hC`m{%hr&g
zq!JN!OBeX#V)(m~>I?L#f!n}E@Mj%LOay;dlJq{lmRjEV1GWk+wy1Lr&Uh!ipTS%2
zODtkmbbWJhCCt-qY}>YN+uqntHnwd$+1R#iY;4=+#=P10hx=81_vVkzbWhLp;8dMD
z&ok45=dGuFDeyp>ok}Z6C&$JQtht>UV8nH_*>_~dd$(N~JD*ni4%0$FN5wzD8{VVh
z6LK%978D{q56Nf>FvRiu9VQL~{a4Pzz)(>wjJ~0^lTS)1hTbaypj%sl7tIb`w+M})
zbI(EHTgPEIm0M}k8I8^s7?B4$=#CNCPzg(`S^{^3IzZKmj8Z_c(rq~K3``k^4vAk#
z1vffmuD|+_D3G~dU#o(tDn;5zFcY&jRJXmNKwqmmAZ*!h?eC9*m&qp+aC$UNy$Q}4
z2op2I%ri_=)SuNPUABww<B#%dQXiDPLvhuUqPXUMT^wb=u%+lZTmaa9^w|`w<K&j&
zwZYvstWb;OYXZz0;O$|+u&J|hTLKm9mN{B~z$Q~0{lS*pbAX~XLDOHfEip<u+MZ=f
zyUK6@T<`fnv6|XPTp59|s$X@Y{J`|1$cb|S0rwqCca7hj^2T5=Fwg;W0fG1TzL>c+
z43TGa9eF60aMF)3$D+cRfRp+`DI3Q2P7c1_qF|p>VoyH3dr2uf(_mXk$g@<wuXN<F
zWJmW&&|&cdpA1UwoAnm8es2WJ{r5%y!+to5ruiG3;L?6yXv1S;&9Rh~@oC9q=7tkS
z2JcKYykqv$tPYA6{(!aE1#0Hdhm)6dKq$Os{$8#iJf4QZP$6z8I8)#&CG?ye|J*C;
zL0Afk?;;@O;ohGHA?5FMpzJDc)aYpwexnWnqcF9!=mj}|YlrmT@^i00b9F_-a9klC
zC>8UDPVSYDx^p}ciA{ydfd&?dN{P||)(suKb%G&jWa!-tqZ(P;G|bYuZye^E=U>>i
z#ZDygV9ON;rS3?0j{~7*?i4_;p129XttI85057D~7l<dTp72Yx-yMU29u1~tHbl|c
zVUq5Rg2!C#9dErmz}jKV-eCgf7!G~k45=9jjk57Fq=QJ`Wp*+dY<g9~Ev+jdVa4+p
zg3ak92b%N)a~7PUxy|Q00c9s^bs?OBal=C2oA4{KC!Deps)&hEsy=&!L%>R=w5!Qo
z3SvXwvDNlt9$-7&A(#MUYE~KMCg{v=3<3+Qp~kM3<=_bBZvdI*q3k<`>Draj|LHf)
z!D!B=hW7meaxB>%5wPxXa@rC=u8aQ!48c$G-xE+FmxF1%l$@o58h$Y-=efx)&IPXP
zxka07IUNRR5ymronp^R8OHknZK?#`p4Aq4VU=&g4Nf(lWi#t0&vU0H1a%_}>{O8wR
zBzxyL1dPBz+n`7t3E@&Wm<xFVhH44ksh(?o+4d%-thr|0d(r4BWbQz)E12LYFO-VB
ztv&#xmc?dCNT`()00H)WV^;ny%Y6Xms73aX7({LtI!S)bc1$cD3ovXQskg5JDw~&<
zJU>b$0AW?O;gke`<%X*&EEsCqoSR@_shrYLGlz$u%>BkVC;(suFxg3qnpqpvJ-GuM
zHjGR61rBvwJRHhBQ<LR9JkcX}P)(lRUeNj2dZ7Det#)fA;RGv6iLRj*+7rA4b;P*z
zndpiIg`E;yS5KkG?oF^7r~Q|Pn9MnDxHQ0E%?#1UbH8a39kBj<pUZlLv)0Q9Aa;H0
z&T*Vl3VQO(TtcSr$Ccmg7kY@yt57upw$x{`byQyi9!a?KXthW5Ai)7He^IbeS4KZQ
zuqlqWj>~|r44+GU2_&7jjw1oA41;<%fULLr*@D$ZKLsmg7ioJ1H*2NLP-Sv#nLzlh
zYz4bFz@n~ziZBvbXzMpoYiNk|0A$?KY2npk%42;WmSWRk2?5hfMeZ~`gmyGohWTVd
zkIw5WIimlTw@3MmEVY{*3^pMGisZSI2vTP{g8C_W#dK>zfvGd1TIOMD&i-pK80hHK
zyN;rZxE{Z)YiR1I6@m>(S$4E_Z9*pl_gah#kV?Qbt0iUCurSae^ZM{FWZ4(NN^Vhi
z`?5jd5a4Feun2H+^U)hGFESTc@~gYrveU<VMuWvlr4v)g7J@s&NXJr1poECui`q2d
zVe~8PDVFvuyrdG|6cg#TAD+&%P6xzvVtzuQ$LBJR#|KKz+}#aiIB`~scS@#m^W@96
zZ`fBXlL5Mm9Y_cAfzx-fpE?e{=|P$T1Odp!M3akh0t9qV=6zzZ)CoVaaxOu=3MHkH
z8Xv~MOQnXP)`4ItQX4}yMv7a^6}1ZgS=#Osv|xS7N+jPJf^r*Y{i!oOSg81m?`TF-
z_6(&Eaq9q|S_#rN$P+t_vQx2$>-sj`sr-8TF`f_9$t03z=1j>E|4gj5_xcZ&__riJ
zRHwOl`z;EK6ytr6HynH+#`2<^|2E=Xh;QG}0sm02%)Ig>U<+Kd@$zWTs%6&ZU5L@u
zILpVyfgWRmZy~j#p6y*q4QRBwhtATg{(S~R%tbkZS&*hhhS#6OM{UprewfS}t4ivD
zO^~f8HgnJU$rrp;u`*A>5lwOtEjZWzw`HWzjNgw{@s};wD0MBKfRKd{Ee@vf!O*vp
z1~HpK+5El{0QXfxES4P_Hhp6-p%hw-U#Kib_}&YEIEQGsdHz&Z_!>JyWX<rfb~n-1
z_K2D=Fb)f{e^6Cm`J8g!l-dAVtr%gk0O&Gg0&`%&W>R3w1*!eU(dKgj@fwC$%mq5N
zA=k5;D4Ns2YQh@Tth`LZ_chd^YJV5p@A1`e^CAkV^}3*oQFwN)T=F56>D_Ew-@*Cl
z=6^MdDjE~4toQq2*3x2QFaXz^M9R$o-Au{y2~s<aqh;j+7BqcbFIDR=r);oYy-{B|
zm@-PbCMFG9`*8@=Lu7VV23R4j00Ma;f{Xd^iyQyQGV<K|#qMed{D^$57^x&pC8a}>
z+6+CT6Jl=Y3SN&dtItWmxX=$IRN7b9%1I!2slG<A^w|J&9PGINT@+Bl%(vMj7=i^w
z=%lvWSE%j9o=CohL3aymuNSR?Dy25ExD7aFr}Ei}7Elqs1-1oC#g8Cx3smGl5xBAG
z-$m1J?UTfjHf1Q@x<$xSmv$e$s2b%)vAY?5$CD1BU+Psibluvii7Gm$wqpq;ir-Yv
z69xpat=y}VVWV7nRY2*(UhgX<2ynGVGdk78u3YFt2w-<qgdala6tuyW9%kU6`$hm$
zP9RB@IXq$T_nit>a2Gb&n-}ZMG1(!DL9E<V!dp%ukhxV`IBp*09!&JLL1)64_y_;A
zHwe?f-gepm%&WJT0=e*#P$X*_nr*%<Ge3AU`6nnZZ|06#L1F_c$YD<Ajz*1Qy>WTV
z5OPs48O`Z~iJHpjga#5Z7grAoCU6cXnM9vF2$R%c8$^s4mvx92tRbMgvuK_Bl_nSY
zTgm>!PkgNNXJI~?aRdlX+%CTaxsvs%Xx{rBH98{-7Bi713=8;lq#(^P6OCyJH6#9-
z+Vs*o&a0|5lVv&XkqU09AK3!u!*5z@G4RZlV>y$fW&)<=CZjRx!beO+#<j}8=6-HM
z&}Rji1B{UY_RtACN}J2}0Rf^avhm7j+k~WWrOF(vG0DbHa5CF9E2VE`8||CR-;$1d
z5|i(w^)?mdUUuq_>Ac$p>=;4Tx+}moc+GU9F?^6}GEiqTq1=SF2Ii;PK^X0BiQ%W2
zb^AT75T(o-TFM77wVRZr0OCcruPj*PQL*|%-7#SrM&J&UFj7+v;@Cb>EAJ>g;ah2#
zYJ)%$h5-xjFc8y2y+?}u?T2A7#6>#oMZJ<Jf{toBLw|xDuVAAf%T_50M6p94f^M+a
z!6K1xpa5}jU0`k^a^dh5o_yPsD6U2actn0JEDmPUvj>&TUsOiPx@i@p18DXSUUZ12
zl&!3!`EXrKQX;6YweDHeMM633(jcf<-?%hs<r@s~#AEa#9TUbmnv<1u`~_@g29k48
z{{WS8mi~HT3lW&A?6}-#<-SgYm~HC>wIaWl6QJBFn6B(72OcoJmqlnb#S?trOd$rw
zaK6QIAeorGh4>ZpWWvpCA}(fn{g1&VDc9WueL;UY<@}7EGewsNF9XwXa$DI{PR)?y
z2m&V3z4=5e&YWx<_0*Wv$Q#1>DVWqVB*DnH3nG_@3`9xvD~9Gmx+|$5GxlUt>2fE7
z{74#G=jCl67Ds!y%|a4vK1?gj2shrs%~kI|qIya<N56GDr<!7vx0x#Q--gFj2ajki
zi%>^U^%R=T^)N8%X?Vv<SQuhHDPf~F7rCnCnMwWpf98%`t%`?+UWSvQb+W1zlXS84
zc~Finl8X$ORnb=DfHeMk$1{h>Qy}6Ym%?0?UBaJ^NwN0=GNK>1h}1kBm6imCE*4S$
z@zhKAhb8yQ|CEFL2S!?qqg1%RGhc}l#>N^suJJ{-P9YF7@(!jdx*oRl;1fq%6Mq$%
zSDROuF)QJ)cX;k`Kes~T5q4gVlo%<RC$h(@p{=&Oo|iXE&ecXm$ia(_shPHL+(ndh
z;Gi*@@0Jb5HfaIaYJ+<^ihifT+{L8a6dqpr#7?Ci69r(lT=)%^OKUQk0H}yDB_d0$
z2UB8TI$|(6Ki9Xk@Wb5sf#c2Gf1ae=>EEu*<P>y5Ro#s_n=F>b+8R*q+gSL76aO#?
zQEhmhfv8;)w+>OQ{1Q+F$wQhCHjM5p1iYVw?0{YSz#7+DHzH)?=;U^@w-5zDz1QvE
zJfF`O`3ulRbb+1tBBIPzYynhxI|_h%Nx90O=?Ie0MW&2}VK4tEgLN<=-8ad&R(FT|
z1cF{<GHk&3I0G?MaGGCpNe9^n+usd_l3|r~4sa5pOMa}&KTw&;st1e*uM>um7>}R0
zlekbV{7N6^8T)}lMZ}2lvIWAjZB3dccb6$9+Kwma(Z>Z5>Unfopb(s}gan6*+#G&H
z-UAPAE_ecPMOYwKrJeL_oy&3WS%JlYTqM%T*2gs-3OQf2jlX$99l9eOIe(<e3^|{h
zuN^oW+*W3ykB3gf7DO%xuakw5TnOI32RSeFI|b%hGl|s}hjJ4thoI+-q3hlw!ct(N
zGEwt!CSb{$;}pQJ3tazN607OezPQmVk@sAk9g$}V))fSNnA|#0zvmgB-Jow>A`E^N
zUM>uN4PGt?UIXD<ToB0l#gd{z+z|fh1HB=9>tpW?wE`#a1-Aw#?+%3n!4)zKw9r?(
z4Npa{$MLEoZjZO`^)&CX>+^)+&APz@hM%TWFzR=SvoV)jfoq$~KyD$vKNy6G-AVL>
z5|Q{B;4-3AMh<Gg-8kY$dXHcc3rN@{a-xG!$Q~UWdxk644ZI|O<buQl7<y$2L@)`^
zC?1|m+7^Tca=If(h~+2z#3=YK8ns$rl9se47yy97#Rme&VZ*n<u_sk$EC`TN;0H>m
zPG~_3(3eLn!U6tguR7*CRaR(cY#$WS&pxBt{NI`gR{LI-qK#EEb!dZ{%hoW(s^J`9
zz*KG8?%x}L95`cF;a86)qIDeTX@{!xSWB?-s`MtJb^AdJ(7gAig<$1<s)-VmO)HG3
zGjA<RfD47+QR_7L)zZ5!6=H*!mE*2b`(T9_@c?%SrVnASL)349P<05Y57?MO><2oV
zo(+Ho@)Msc9c;F}6VL^bH~E8Miq235++fv&Cn~W7Y55jN{SQK$B~ln_+>%&M_92nJ
z6E`*H7H{T!b7{nbJm4n*&G^q=FvZnq*B7mjyk!f0gp@<BT2bEjdT22DDVwHBaC;3n
z5Vo-KdxBa)^%Q9TXg-dPIabV4eo`Z&Ad}#{Cc#1HRlu+WJtAJ1xbu2o1gjnqfil6t
zWaI$Y>;@gaPBw@EC*j&z3L1J4VE0lH9NB={$Yk?C3L0?`Y!L%@BK3x-YUOSSwy=H&
zv06c#6!rkvJqE)SEW@KD01O6G^oj?gR7NeCVxT#89uX$gu|nIv(QPMR+3g?JH*wJv
z&1?YucZw@W_rj*V1Yj+x{eYNUM8f(vQPF8FY&WitkqWSnz7Nsr*6o-$L6-BYh6v?{
zrTW17o8sxf`PsZ+$_7Z~vgl#n?s^GZdZr(^XuX|o8Wi*(89Ze3uzh3%>WEg>NdAYG
z`pU~Q4s5lff%ToRR(H7*49#rVrLt<l-{#_qe#zXFX@A*sqIGhT@xI<-`*BY)mh_;5
zJH}c_j^?))br)GP7;Q%!+Q0-6>o&|45=-j2s!6fGMW=`8Siv4+LK(cu=n)vZJgNR8
z`?==hD<*emYxIbdP&y>C`0OoEEhHVAVEBwdJ9juML?<3atB(V2{X_(xKS>Pal`g@Z
zO_C5j&UR@$^xI{K#HHi#eMg0xbn+k>4+NK>iNEFezvtshja9wdeoKMLs(w=Kg$Bc!
zBNg;vhg5`mu*Ajod$!)vK1;_hB+~3q3*1jsrTELA7BBhwxLlWqegL`;O>VpejWtZ3
zG$0~UVXMv_{<lXA6<0MaUb$`i8@6Fj5(GB(Rf{x=*McE0l|K<G!Ql8)9~$AO>Kdk2
zkm(DZ72?7IS}j)CVVQp9$o_gZu&7lCbpS11EGpP?+>d%uw`RwQ>k?IwpPaN-im~li
z@aTP5a?sqISg-j2?ph&JH<h(v3*Xm}u*z+5QP3D$yH%`^O%VfZy@zx}rnFLho;y{D
zF4~?Ueh^WL-WNXkSAofM;;#_7jlK1v)iw0Y-$+)K0`08rNj}ZJ7yud{2I)r<c#^_%
ze#_H>E23dtF9%ok(PJw@bli2htDAeqTG5kEiMCqMlTLLZbSF6pzXR3>L~{4+<k&tm
zK?4sAYeW<>SBJ>l`wQ?NuvsVxPjji&5Q%=&dLY79O-S~>^4Zb!-d+*_e~N73CH3ii
zL8S2_F>!KDcm?TvTqO+eNc+XuDD;d~HSg}dDBFUa3EETYyeka95_uQJ!%4)Lk!nmz
ztY{&*MFF~<S|zq5^kRrSa%*5^8@Mz>#MvLmocj{UO+nY1NZ!Zt`j9+-jIQtjwt8XF
z0CqcA)E<mx@WFzmSW3Eeo;t0N8or4bb26&mUC`2lNdw(Hh`f<NQ9oCc%1uTz{*?Uv
zqf|#)=*oG{QeNn)s6hCRCfdBi11f`Pi)rafk*QM~7mMxfg)nY>0PUVSH*_GyX?v>J
z0FU;(JBx#vBz7)h_Gfs(eHrxdLEp>ilm2KRv+$GZ>zJ;lgY`{fnCIPjKu+(5GB^M~
zWIH)LfDe)r;?L!beci*Q`MyAUMO!Z)Bs)~wWqF|Ly-OR#9w5+-2V_xz+?*ioXO3sd
zUS9XU9rD-(n6`6r`GrZ^y~Os8yrb~>yV#pV4(~hS;GCcxWr%C?>5+)4^Acr6JoM(@
z>WMY}y<Sx8Zz+Nr^ArGS@<l1UkP|mSH;KJo-6U<K3^^=t?<7n)WVl$r<g2at-NX2<
zk7Won2jctX10KE;v+s9$ZCOSiAO7));g%n{tFv=!O$z%U9?L;rBOcC~)-EGw%=SU^
zVH+Nw?3Xv}+@N_U8O}Lw@Em+rUe%O0e0LWDCU|$Z%tzdvRz}W(p!bCV$D}z-+$9J!
zp>n-g^%X}z2`y1JwOo1tBsy){&Gj)UUOO!*%4B;75vNtw5)1{UhcrF>5h6flOVpzO
zM0MC$M|wCLf4_Ef6vXROu({t}9<&NCq&_A)&<8%A)U|uVFU@Jmv7#@@4{OWz*DMG&
z?l5n6*Q?}%1&5`6q%h7as2qc(RsWUju&|QQz9sGclLLWSnHs+~{jTc<Y)eJc8k`GX
zOC;K}j-Q00iD?Zr;v(6h-p;P;4l{hY??Fm*&v{TyD)_G)gBm)w%a;k>dw`B{k)($X
zJxq)kJh#Rz3b?%@8R1O}Q97@76M=hGrCO+F_oN<zb;3w2)9=_KGm}g&K3Dt7%F_B~
zM1!>EX!ShK$`!dEWHx+B%Y5M2w@{X+ch52mUpXgkP-dssjX0F807Jub_U<{S0O`we
z`p(vnIv3w6kxZw&AG4IlsthB~U}r1(``)D5esH+y!9z;D9o_@(`V}tq&uNC#xQrF`
zbFWI!RheW~A@QM!OST8{@Ngug^N>(DA2+sN)72?HmmJM;f#K4i%frHrsnXH5arLQc
z^pv{yd|ykCY(G>a^?j!<6rO%havVyz53}ssQWt7#G_)N_vmA9fOV`${h0uzt(39S`
zr1OpO9IzbQ@3$9@ldfo`&~MYeWb@%8`4NDbAbs9ognhVo22w<Q7`+>|9CtT-)2%#O
z!W^={M|v2w+nO~>1jV%{bbz$7ja<HM)yl+Dn910jt2a^Q5+AR9&`*1MWr5#{-cg#B
z+onqy3S(QYCOPxiuhO}|(d&4Mv6Jgw<QDAn1YfJMV@R9I7MjIcIc5%;z2DY|xB>am
zgs48Smv7JmT6D3%rynGW1c8fFl^Nt9ZdjFRz0{%eV9N%SmRWWQ7FCs576O=Ph{JUy
zqFlDtbuEjm<|!_1Nk*X25jdCZSa#c9C20?fduy!JDa78N@6gE2p+?CM1Aa<Xa`Akm
zeTYM!jD?n5w%OM@2Fbnk>X&ghv67JfYhtMz^g|^*0ir2MnT)6UT$yqcH?xY?VBB9Y
zm3SEKLEqwI&CdhwL9B^(0GFl$<z@O;AHC$Kqu06wrw)g@Dr5<?ZOD&^hhqYDllf1$
zu-B^J`r=`QnVN&oQHghhcEBNQ*Vhz+vBeV)uRKY29d?C+GK#>s+rN~2&~2VMvLi;$
z^)(L*VXxp%GMo%tZc3CYdBJ@xrPoY{TiTPbL-qr8=U@loLzoUj>quE!2`(-vuLbyD
z46H`+w(|~81o+zwtR!K{KImd-%Sfq5pr3RSend~_Qx4|@S|<w&OsM2h-em`pCOcHx
z#T7OmXjBb5$drZlqI_HTksT8{j<0^?)&mSPDq1dr(GTEgs455Xj<{Z{Wa`)!t58i;
za|_tRz#{wE-w;j3-#ritmU)u@rkh%zYtT?|RdV77=cNkWX_Ewk2ZX9>k6Ha4l_4*e
z<9f8AGUX!fuu0qJat$y<7`O%)RUm$CuISo(8~CBH%la(O*}8_9!Was$j;PETihzw$
zhEp7ZjUxK&h#;W!vWeRnPYlk8b&-Grbc%%v*hua{?Dr^QW@AmGTguV6h6v6q`sFw{
zCX?`mgUF^V(lfvfW=3`15r~>B>=&hwT}E>am##uI-T|&1)$A903dK8+fshP{0E$VK
zoW6<J%93I2(0Fh~rH;PCR;1Lx4WUrBaPi%O>EcQ;AIoxR^P!fi?$E~`lLsr1yb06_
zbK97?5z~(}nNZt0L4}H=CXhH;=IBaa!h}Mm1YMXad1F&BPAd3%GeK1^lD8d<J5XS$
z?EWf7y?yjsx^?_5r*&%dd36at9x-=x5Len#b#(;VCll`D1XaM$`pi@@Ic;7IwMY&9
zah|EdLrSvr326p~8A_=&h+0CcI~3CiesUI(lOm0NIubHHjB=f!Y&dlT7pW>&b-86y
zKHYI`V_obYW*Hv?zm8uxPbv3)RH4xud6zTsb!8}O4!R^^3ynL4tyX!Aivq`qj68;j
zNRmOk&XpxK5Az&bE|(z<+djlwutdmfR9^kgyiuxh<$|x%FRlTON~KfG%vS8AIkhr6
zr(CsUn!3^|RnzP`=l*rMLfit9fx#hv%9Mh*>m|)q8%zxKnxda8I3^cb7iG<-GkgaO
zGG{^wUnn7yS_We$DSGUzkoIi|>`kf$)dDGYBK37a_%=`k_9VdxV{R0wsJegym4N#&
zmg-1&1C-R)+e*T_NpuX$x;k6*TACfX;P=Y9T7Yjjt&9@T7Tq;_+NZeuY6bRDqO$H7
zkf4Gbh8y8ShX`;>s-|DzLt6WN7F;o$qQJj{mr#A}pc1}Dh^|O=*goJTbKLSXH2N1E
zH-?LO`&I3_3a^sIGVYNT(PjI<HAj|SOG}~WH!Hr^xRPS!>~MwE-jU70Kt<aT*xpFG
zB8DJNsdIGSsc+5+h}ykawsE0V&yHW<x`CGTTFhMq+1a?j#{rl|Mv~ntz2CLeNTqL<
z<|i$k<Wan))WD&aZe=l(+6;p2mQy<i(w}%NO<Xi2sOll1P;Q~m)P1g>O4gbclg)Eo
zLS8$6LVw&)Q45JfBHJ>5W9a$qGo5PzwEgHQZPZE!ZbE5Y3QJIQY6_DF8N>2xjf3?2
z>+v#lY-X6!Q`%#5kE9zk@DG%PMLQO7fra#n9dHq(&n{;g8bzM(8k1c|98|%%^H*GP
zAagav+(nTbwb?V*d4s=#paZUPA#ER#Xm&pBZlFE&&uAp^$XC!g8(lM0hR0m$q7$o_
z^Bk5-_zJi(i?#3HBylpV;;N-6ij(ouRI<>xUIoO_)VNLsDrwr_n-q~_M?b$JX<SE|
zG?}R16!Wt!jr%yRj+MTnxVlkRXFSpBMVz>B*Z?(z*}#GCcQ(N`qB~I4y`iaG4?6rg
z>~Om0*HWBaz_BVMk)F&jP9n<T<PaN;y6AA^(4x|>4m3)FN;}`dAO$}1V2o07V%59(
zEjcvqTxcpiH2%O^K9~xfMxtR2Z3%Ln7u<kF)~Dil6Q$(EOrNb7VRe*?S=4IUeG|+Z
zAHDg;#3xGZxUqaJYlb|M>_Zh)t>)&3bhGbveEJQ_p#hXpv}?@`oSZQMB#1N?h`hBG
z7X$k4WV!>r+vsSq{xXNQ`OKeoG)!>U{n4)tN=lJzxOw|RK1%3#<A3Ml!zH#7h7vx3
zs7-|WwuJco8{}gNS>1J9$2(F=k9G!Rg^~RY?cVNO+5zYc<MWY1k#<$fJX4jF2GvVK
zT4@F+XH5x*1ssz?RM64RUukq1cOwU7)k+$s#{j&OJN5g$p6C8n&=mtDHy3B_SU`l)
ziQ6uwK4xxB6<ZO=4P1Oa<y{-xq#P9}SKEGh-RYsIixPKd*xrmZbGS!&s-?@6g-jKw
zC)zT_IVrJ(MHKqUJ`4|U7ywzPW?Bo+Ktacr!VVG`an+T|&g(5sBV}VYaoyF<gNHo{
zzKp$kPNaq6y)&+amEtffU6DMJ=t~MgSBstLP24=L?(>rGs_u{DB4KB?MFvqr#~J@S
zs3Z@ln?amo$U}F-tprtFNc(&W1j=qrKhpU83Q$8;)4D|<<46<@S~>Mb$!bj&Gvc8i
z&@&-QDop@CDTY*_<3j4)Ex|=LNi~5Kg&itP^vNwO0f!Z+9&Ix1d?f1@fTHp`%^^kp
z1mES8)`D)1YQbXb>&83p4~{A&HF0!FRRZ;*Xwmi}NyRS$k>sJM(F!0+DJ<r{2vXK-
z`r##wLHmM02vL^*E$@|st_Vt&Yof4IphmFE6;8>{EHvxqfo0(R*dqW`#0+LfC}Wf7
ztOPOVDWm96WXV<;djg0g7Zrwnr|lDpBs#|VVR{Xam!E1a$<BMf5u$MD7>gV)gnVBw
z5Vosh`UQ}8tbh-gCv}3y%H=-x!7C>~(SHGE!9gy60*D2N+zyV(MjpFne;F+uz8Z*v
zO==21QD?0CNE=2aR0aL)P9^Y(_P}v>(nVTDwJEa)<VVH&mXcJ@&d+Wm8T%Lw2gHwR
z#!k0GzJFmO_;i!v)9fi>2Op=XEK=7i7B^OjXS^J?)kNxypk{baYq2?%s_CzJfjFad
zP~D5B0Uyw>=vz`RFd-F*N3cN?yb5d82aSDW6bjE^lVYwj8<jz;Um>w4m#wBPu~&U?
zHd~l!6sfRb>rKgGtFlr=8nR4RGiP0vyjsLtu2loplPqm5;}lvn=OA?nNgF<5U)6o7
zB`E+m<CgMU3lM9X>P{6U*etvaHLSiTo6!XrCp(#k9-M=RI#kmJLEF$qG(!N|z$G?C
z{gnIWsg$s26i@%Ya?sx$x;?PdIP&eF^p6`()=@6W3M3U`zf#<$-*UfF+NNJwE7gR}
z10vdyl&-iqcAm7NGqB5<lKLiqnVCPSPh;sD!33ziS^O=kD|&4XLF0VNPK`B=H6V63
zW2h|b_DTE<+7+>MylbEwnRK4(KHCZPeJAXh<-_(Tg+*E5c7u|A3ouAdu!8;UeKwV{
z-pF^xQheDfjfh{^>_B{#3nBi>%VWyc;HFn)bx@s_09Uvtu{d(g=DBl|+cbYOL>N`6
zbnx=0nj34)*$VK~19+QJHrnhowx=w4x*O5jcLN1wEuvHb=X*&0?0zprOOVi-jmk>M
z1@02AEQ(_Qq^~cEvjNm=C^~7MCI4s&d5xP%+m2}|3{k$_$fw}?8H|^40zA2GE;MDx
z(ZT@pf#gVShhDGxrT-;uXMvtH!_)vR#lg>Rt(fEo-<ca+un=fIciK+?MGafBNV=uU
zGHn{(jCxbAEjkL-YCtFY8@7Rpm7OVFrUC6U2<#=AZAZBMcV2`GlTN;ZD0e>IH*_82
zPZUhGv(S!`P8(<ZlXkVd8K2tqqPJ;>sD{eUz7-{z)~>Bpq!9`jgznHfqPu7V$qIHU
zWs#_gYG<vZ_+lo1pJu2B)&qhbw0AQ<Sjy|F63G*I2DysLuAzf$pUy_oqN3DVt3DYu
zl1iXUBVQ48qY|B{8JG49Z?^yAI93mTdF1mN|MSnj5J@5Qw1RQ2uBPwv<cMu7@5{9K
zBLCNy_(RW&1J79O*JmwXwIL)gUK4vcw@bh)eGmWVYYTrSe`f4(_xt1X@^!bD@5}oY
zyzl$u)7RtSb!^Xv!^H>XBZy~b3-w4_&ei^H&daU5@6+vetjF8wN6**o+ddHBVf$I}
z`4c{R_qM=H*PB={_3ngLaL?O_?^n)s&$}9R`wdNoE03lZj>%Np242Y&{(KTAS`noZ
zhPT*kgzCNStnW*xo}}V7@R=t8t*hMH2o@*4k>^Kgc1RG*-26?|K68YPkMZXq%JbqA
z;`Ya_YtP#X)lW1Mvp&|xQoc{b&$Oid5$CB#hQcwDbDzYqSa4nZFVFWw;oVmUQCs-f
zcyoGOD4!(>s|p*wt@Uhxw}JQAo+f;4`pb$jA00&y>Xn+xO-;IB`jvE_F2n8Q?uGrs
z(>F_RCf~B*g4cCRvlxDB*nph!C5plpy9AQ=w$xhTx~Z3a`aYjNY5kz?)GJEU?YB?=
zoI54OsN^Tq+otED{BHc78VJ5W(nFr!%8}n7_I5Ci0{;us<Lw1C{r)E@Jusg(J#UiQ
zatGerhrmPjCxmSUA=7I^x=>M16&TuhLpsx7Pt}n%!VPWh`)Fz{C(}N4$K1n<Yg{d4
zPL^_Rd`nhf&uGJ%clZ5O#iHHeV`VXStLq{fl0qpKD8C|XkXN@qX~5?+BNv`?wR_bM
z)t8t3ik<!UcWib2IX-T3%ggnt;4T%)?3MK#HLpA~&>(CNtwVbdZ`IZj`H#-MqMwyD
zZ)O>;)A3vQls;b7zV88Te78SDveF%Vy_V}BV{^?|+aS8Cz{uVk(o1i@2j9Kcpjl~a
z0jok2^M%5Cu57D+>^fc3>91G2FF%8morQe8Ykh1N`dsPKg%{JU3A?;GZQ1_iqh?JY
z5?ro$gS?1<mSL+;A@f+WC2;8XGG_A!8YUO8eXqeWzpUpH=Wc_qV(4YAqek`3G11j4
zafsWdKr+^{r7P`TuL`Wjw9B7a59{s4R^Qj@c?|1W^w{s%Uo_!7OEBzRfF3m`;q4gP
zB?GXTX6`#jHS)t3;v5}_wuj<_=zVkI@_S;Q;4Sjzx_7;z?Tz=>=NU8hYII`<eR+4-
z*5ge`%gE2gk`rX!P0Wx#86K}?rxEhWHGdu`J=T?hA-|f=l<&i{uORyEy`|+x$UV-U
z37+$>B2TR4cLnY>l@sLe9l3w&Y%fed{PGDXy)VC1zHiO}OzllAr_YzaZ>&zfEOE`7
zPV@Aaeo-^Y$$w&gqK`Y6X1m<>ejl2DQ|#gUgomXs$b>SnF?MuvFfp+HTe3B@gkmLN
zAo%;AfPjFNlaq<zKX&GS+j)5YR?&;PIf*Mf8912`{LApyX29^R5YP(?5-<|b8yS2{
zKEA)s|C01#wl+@x!`qaWftG=Q?Ymp0e>;8q{d*8h{|!b!ui|cJLO`!zU}i!<O2GI}
za0LSglkdJ5|I?OU*2LJtK*-jOK<nGY@OR(@j7$s+1Umn?3x5ax_ID&;`ELVp2U};m
z|1p?<1^LJNx5@V(z4CWx2Ll^NyT8GV-2Y>iBye(YHu;Yx{Ou)T;$mTBq9iW#*ZA+b
zDw#OiIy)GdI1>C_Hzlb5J2m!i{qOqzT`3t88#5<!0*?O<OU%N`$;5$xUd-xyWkpPk
zY>oek^lwK-0(KTow!eM-d&}H1FV#KWP(+(+&XgB<H+gyId4EBY{31b4AcU+53IYI3
zLKMl4BmhL-s1-C6NrHyBL(tHbCh!X}o4LUvB?zcztVh5*Kf6N`R&|Bk8b?J(Rd6D%
z*F|9`OZM~tqU(5a{Oa2N=w4_2p;J@MRr8vqEKETtLL3PZ*IQVIT;luuzQm7gSVbs;
z#c%Og3E)n{ml{_pCR9rC>+@s*lh;(9a4^)m{%Mx{DB0^uHzW2z4U&;w-pAOmZWq@p
zB<|$6uIAYIf}xqZXvGJAoiedxD*es4h!JC*y;kRauu&2jl5;jT&gBs+u|zJDJ1cpN
zx%LCC8F)U&%h*HjutwebiILEYDPAJHRG+jHs_ch^)$dUsf;;$yK6I%lV;o!a3%QAq
z;gI183hGfPG7U-6D3<A<)+6eCA$#wy$wUXPyuviyBs3{$d)RY;RU$^IH1}PZgZYV4
z5<R6llw}7|P0e7MM0p5<{TI$81&RY~00Xk%7sKG7AL98J;0Y4W4F+ya-1J`va&QlH
z<~&<bBE~GHo3*1Dd}KYjz?;`#?1@mGq#8WrY1X@N0dUClGvZrC1L+lywZDWdLs_!c
zg)ct%1`Y8M*{s1wmBNSP9w)4{m>SfY>0bsK%z}H}*EQ+u3=65VWgti!)Q6~8_l*W3
z*sW49mC|U~RH=VJUcRdU^Uum~_E{AVR22LPQS<zRC!{&K)Z&4@k-y$}Dz^G-q$UrB
zPOp2`+{a}SWn}Va3OPFw!nsX)mZ+C*!a|;rr5q5O$I<;s+J>MiUqD)lUFtiXEQ=^h
zSPeN&2G3{Jh@R)u=CW8%+Q{@J;`xS+{pEO1ge|at`_(V-W-HFPImDNw-wuU6nR?`0
z7UBuQiViEn{ZmcZ-!IAZa09+~w?6)UfYr)j<6UO503T)IUDd!FPf}_KGf6mrbD^wS
zt9PdUY_|FEFW)<Y=MT$JIV=$A;s|WZHZ?jEY#1;sra&DZl6j@c63;1~UaRkxjxvJQ
zK(wF#k>?*FtVFxFM59AIcv-(OXss?6xI&+rcbYyw=WOklS3x%W;_zH0&2QNbQ&K!8
zfMavCB)g8pf>K9JWVne|L2KJ#6Z!URU!hYyiLe%u{PQs1Zk7)v(YGiqM(ag2%Xg6u
z8kXEihirqeLSN+PCCt18n?qFI+Q*uNQ74yfMm{Y&8s<4{tXLdG7PoWim5sP}!l=xa
z+@CXDvr6ivEGZ@P2o!z5>?;Z7K+TBkJsDQ6Hm){cRr&;B$3mHuQO}>e57|>&V%5~k
zSr(hZLM$Y~1cO36B%w)hMt)op*j6yku;1Afd6?2;Qil5}*dk&RN2vC3;LG7HjUMWz
zfYkgwlYR(E7mltORgY|lE_sb;FKfGEYLwB<r*e)*F{%A}19dLwp4B)lcTzk3G1XPw
zb!B<Zd!D~&$*Uv*)fVYe%xP};K{=^v(cI{B5Ms8(&qzeiEqTu?My|k8@0wkWqm(`(
z#%AkBE^)ANKjg>-?_4(TpZC^EO3l>ZNBJ1ZOr=;$5`Km@wLtTu;8A)RB{W|XE|f_?
z8N&qbj+<_?ToP{8T`TLVGc-gk!^J=pg?c+roil$Wgl*FF{^x|{6SCCDNORTtG3#)n
z`q4a>rEA^Qn)+jILQS%H!|A+LGn2Gu3hk_}{`xAJNmjGix~QH(k12ODuBQ5*pS>Jv
zth{Jm8zsYMr!(>3i*g>lC&G?-=+}AoDvl2_Mid((;AI2%af$-Nvp{74cp~1Yx!uEM
zpsy50>5Qp#ENt_z-`rJ^3idT7dbBDruyd}|DAf@DSPp9B$Z7VUy;=^h>~6wr9{G6-
zE^5oRl{>a7RN+DcrN%VDaYgVd+0sCIghUi3nuCO*Xk*3#!oeH_*EHDF4Ell~8x~U&
zC9TSr9#S|YA!m*-U=#C)GaZBoB1<C1GD=daVl1VSiuE5&2v+Zs%?ZYj&f`t(DL=!g
zWRKm<w2ng|{SB=6>Lg5mQ=dcCIjLWj|A?hZj~d@PX3U6XH{Gp<ARNJ-S}||-RatnX
z2uGW<LD?M-g*JP$vWv6<A3zFqS-rc<6ZVFqk32gH{lKfZnoPk`ZLBdyI!2sW3r$Oo
zeG^5bKgGTal<E~dJf!>CBo^!OGb`lm=8TvWylvVnP|aq2%WWf;T@#Nb>SNx^_QmcG
z1@-!!*g8Q(@&OKd!d(1Sh4;~~=$gePIIoYgmhHUj*@3z0l<@VI9u3mTFT!`r(ZciE
z^<o3CxmpB^n*<If-XtL}6<X)Yoo+P>{)0mCHT=5;F15FPuY`ePf&tQ4&p3Xd!jbql
zHij-M-2o?JpsT$5&)fO^f!pg5z1ZUqN#8ZSv+HyGkq!#X7?`F=wrH7x`9h0s3wz65
zn51-iN}$g!FA2xq5IrYoDUl>7trhM4N`8*Rg@ME^U+oQq5_69~B`RgfF4d(x2MJ_R
zzJF9=@!q(c^Sa8!3Qh!WXK!WSo~*x*C#`yf=kyGqTiwS+TXz!-XTdV^%|C)py1oWz
zX&L>(A|$3%5;_B&7253wl@dJ%T??H;r5=>D7osWo^9-R#T^%+pLW?V8WPyXLM2h!)
z4c6rrp(-EVXbp4r)*#6?`9f6lz0j2c432a2Ebp;<@oKGAmT_<&b7PB=+weM4Jfgnd
zM&$j@WTD3WPV>k=KS&gE7es(lG_!y{-w5kA>!e9xw2ZHjz4h*{-I;#9?XZonW}07E
zQ)_y{w`)32SV?U2IA_@)1&<<|A|~RR5jRV{6T2+WSo55eBiKWpG$-^GQ*N{<R#L{U
zG$B7)Qbq<N_Y^XGLR`uM^H0j_*cyKQN}hgI6Bn)EJn}xuoj~S55l1I3SkbCke%>vU
zC4P<;5$d)sb5GY%TeMDf4Z>8CgvR%4oP|o780lxr@9o>Gu+jOETSKdAmlY3-Z(I)m
zkh!js^K<udikMq4dL<`~L5+j=0v<|ImSw8tsa(>qvC%ULBtPrn<QRHEZ5Rl_3<=@h
zX>?^LC9ZQmBkzMxBj=V2L+5KsTErpJ1--4!7O=A<kV~hj$+t1RjCUZXPG^zj=_;|>
zJiRnl2e4o9x848n595309~=ylR^YE<uf4sG_)@G+zg|mAkB>vc$~riE<XMgT9~`hd
zIzWlR<D)v2SZUW^E(WoEDF(8o#jKbZWTIcj(PZ63S1(d&T-ZN1Z7s-O39{5}0tE2Y
z34Wyrig|JJ{kj)0RN)MOMiJYzZ(o;bD7M+I+rF+qMxXtx4vT!({-eA+o!tdjk?u=J
z7Y1)mo^CjAhh?-u8L$55Tp@j6k4cS2<4B)ziX_sJt+$U9;O^&-qoh%|!idvm!u+on
z@~43-J8qaw*=S%Z+Uh@2Ns{Hnno|1~F}h0fTLX;h?XmDqQOS7U=L{X6l`KH%U9IBS
zxcO4Om`b&i_X)&yvCO4BCHAup<)q}75}%SBlVpy0F$iHSBM~y;g%L9*zEl3*oKF3y
zjo>Fwr9PaJTA{N20oQArgls4D;`%Jm2BlY9@h<&B<~99A=1Q6A-!2wEOOi~cNd0o(
zF~>Hhx%d4<)N;ZH9sjZt*`x*LoR_3WO_66twSpWC=3!yNeVq8#Z=&oYR`3!iF6`na
z$w9tfh>fN8=f6EjqM}<9<{7$8+F8nrUUj$yaO+EoQoD}U)h7lL!3qZi>m~Cc_V|Z4
z2?q`c`6AG7Pv5yx%c^z{T7LdCx!%UIo}du(D38Mn$1t|1$i~t~05Ado)PZz_iu`f5
z5T@tCP%_@h(5X3++aDH$B)6V`^_rI&L2=^%Tz=!C{#&l#Rc<|Ah&;=QNLT{UJ!*oG
zIvh!sJ29q_`M!|&^keER+P*P}Pc$dQWTDoZT{ghV>E~$k@&urUgvvpf<FQ<e%ue5t
zw8C~~msXI)Y+V>l3&GZ;$c3!1?OgP8exnj=9SZ{LBc_3K*9AQI5_wIs+M7$E_*(&l
zo6$Qia4~*oczLExPH4|I#X>Ve3t(_es{t`I(Ej1?A4CaOuEN5W_Wgr{;r@FhVo<~-
z=^q2h`Ls73&Mm*|;uClKLO*}HhCK}}LY5RCbTL0nDu=pUao5_f#~hDzz8p-<gXSn6
zJ0i&NbRQMi2J{(iHc*ZEHrX#{o-!YoIBnoVyw@H5>SD`5EiEwkU6Nx3T{Jv6Ea=G(
z7DD1sK7n2ZE4I>+5??DKBb%SzlLhI}Ihjj8ZF-ltt}Ue1x%|AOh3JdbcD!l+&Umn|
zH*490*(ZxNhBZEXYd<!BVZq03;~v!y5ou6I6Z2*kzj~)!$GmU)k{UOcMp`Gmm-6hI
zxM`18P9G+gKA(8sp7Gg$f%0pH>Gbjl(Jg#5`?(=i+SlIYY997Qt;}^sm~n47o7eMb
zrpde528*l2u(y|av!VL)^O(D2B(g{3U6b>yjcCtES;B{cREkWjEHS9yu$JGW1k)wO
zS^ZoO*U3fUgAr2EM?xwJI{$^(HkFtUsGy~%g7Kh=*tt=+Jk&#V<lMN^Vu?f|_~glk
zo0p^uwwtuo+u14-J)u6os2p{@rKVSA5ivu&({X9D<>*$P0)3eum39vcS9D*@Dx^D9
z&*S!YJh~ni&18k_DMdG;9=|$8_vg6T-uQ1&xGraq7XM12ZdK7|DKboBeTo&lHmT$R
zNS%S~Cddk9SL0^aVyC+|rFR=t+hn&UC-NbaHMyC`H8$ZEYu34X|93dDfaXL=L2{!=
ze#7cfT&0;yk<DyBs07uj)i%e;bRF)YDbk;k=Q;EdO_9r&2<*07DC`v>mEWo4KVC_t
zm!-(5Qt4|pwA(u!v~x{ov9Ei+hV#<}LK6><Yjk<_d=lg`n~X<kCJJG9{Z_ulI3N?n
z_P7CSP6V`#2`!3@PDHp;KNG4G<)qMoaDjjM^ZBbKay2%ueWk`Rc>AI4J_l&+D{^GN
z?LW)&qdc_=P@kf;!zw?ka)qDbzQV<ff9*;4CKLpVBIAn{!5DD}t$jsy@$fHIYT53O
z;GuGUl#QTLW_`_|JB#ZO+t55nZ2G&#effTl2s=v9_BBLq*}$&~xf)b}beQSOtCtgw
z|5jdcj9Ma`a2o2?IpE@qWKK=wS{Z=A6|1jHjr*fb#BPqa8vFA=iGFfOi_L&|)#nkQ
z!X&4`V=i*i_@OdvvT*eV34g@ZU@90n0o>b_sH_NmRK@|L+s}$)?8=1B0rAWL{`-L@
z2JN1hq(mwve2d#T3*$T%Jr4j+xmypVa0{%M<$~mF(KERDq5~Xvyfl^|tAgXW8m>EB
z4Jh|HA&^k3GLTdL;Gc{8Pszq)#P2wZVR2kW_)4*!yf~EmdDQ&qlFPSAljQD&Qescl
zB>QyDgD$g1jf%SR{RcGfIHtX!PMFfB9jgdRTV#L~M2D>|MIX`HLdS&HF6p*4bdv_6
zPVg@QsFd*gYvfijcGDkoz`qqCIV0R-tcc{jPnjr$r7maPlxkp%FrRs=b7=&sA%B5!
z8bd7|C3+WzI0Zu~#ZZerCwtyr-;C2<ARn}4@=<$>pY7@<$VsiRCb8nltOMhz7*7f0
z7fSb5rUVE_RtOjT0lr2dalX8hpY$sODIYDhG}6s&ZgN)P^Qa22ys8PwEl3AV<bNsa
zlW%vy<fGzO*kn4{(yD-?YDa$?J}_FeF<^g$Z)ayRwbh&qe8$#P!A)b~tew;TwP9BD
zB9T)~65ux%v?dFQK19Fq(M=j269${Z%YS!t`7{ZiF5U{Y06oZeYpo|DWl|m{-iyG_
zZ;o|I)w=lgL=HyVDAFzx;m&;*-WcH(c5R)OYLr!5a6mWVy;`(Hh9L&$2){alH45Vn
z@@ur~fZ<%G_!eFgRyS3?LCQgMjMR3&<xx|MK~0}-r1NY^_sK9j=EaBv#-edn1#311
zGoM8KaxBc^j+q2VLkhTFDd@!$q|s~QcLwrw5c2sHEJSiaT+LQcD`Q6SM~-Ju2gYyW
ztWjeTaTxvI(9JAq@)5)A70GD9n!X4#2f;m{yKgkD8i3nvJ6eG3An$4j-S&NY)H@ys
z-Ma4ZUz)v5P|xK+SQ$I?vNuJ3^sl{(fH!S^)Ac)Jhm7x1pxVRXsUy8b^32agWX~+X
ze26!7evukCX7pYvfaoAzC;ngB0LQVtz7Wp<CBC%)Q>-vY$7lir`W$a196qYOIeR;?
zKwIcH*?#;Gr8R!c&XDg>e(fM`?9g)19BmVO<R5lKSTWEXWIInlTWB{ae%p|4%DuLr
zIH-0ay#~;5$zU&pfKA}BH=2Op@F;hI;yXJ;E<5akKDi7FP~bur?1C%wJJC?3h&Szi
zmViBIwKW*Jj(ruLf$xikD;*;PPhbY$*tuZ7o<+bWkS<!Sbgvw|3gpUdLge-DfK=@p
zL&hL`saBw7=#}Qh(H6*+vmn|GqvsUE6>W>VNk#>WerPNndVS^KK6c1b27O|m#yTLj
zO4nOhi`p&F^K|{obYib6Ki0!wuSrDphOlIQ^n=4-1w6xP&|M9{3N`2b3ed_kFzWcp
z<R^husH{|XgJ8JvIwN<+r2Imuz}krbJxKNT!98hEnmYYDKT#kwD2S#{hd!WBX+UVS
zUgjYN{^^lp@LdbQKOhs%eK_P3OFNW+4e9!($ULhc%<1~=eilHVvc1TXH?4k@O8|T(
zFg#@XcR+66BqI<Wq5_S6f?p`8%muKhEJGh;Fc2ORgRX#J_b_xifnFeZfzflI27_F$
z`iA=j!0$hO7?yX8m%D)UQFv%W;?NjH10O(QpA!efpzjkwh(ICxzwH1ALejm|QDCCk
zpB0cpFc{Q(y-^uTfv!*)6wb!L+4}s5?WXM@AW!Ibt~z+$ZRj@^rzfxP1bVu`uF)->
zh4p}6A%3IIbfl&}*#zkF%5IHA^Ex_h%?IJ&dXNY-18QtKXOrf3!2QDHnr0yo4z<zw
zu{9Y~P31HiFqIY1>B#6L^>iaADDfnqX&G0t30x+4g0bK(&JN-%ffz@V8;G3{H%$T$
z5<yr8i4+$cWEjTY8;f)g9riO|1rQ-H8Uye$G7nd(Jj>7goq`L@3#bz)AH>ZrK-@35
zQxmvX8{o>&4w4~rb^~E&aCORj2GpFa6bOf7l2G6_KpW=!fTgA%d@VXie$Qx8wSX)E
zkU1@_?jz0RyYDXH*E-1iIQeG}U{Y*4$N$E)|AMUl!L?Z!nErz_bN+8Qmhmry{0}Bg
z|Np{c|0n#alQ3=*$bcaF^ckU192pi0EJ+%qQiP4>UD}8b@EAvgYJ^$8bIrXUu2cq{
zHt@Vv5g&T6!NYE&P3R8aU|}C@;Ka7Wq!%c7a?8Y(e5fzpu+_b{E|aAO`D@);!`^a(
zp`twCAP_E<)vDIB-Z2&)3Lv3HpE2qRsH4V_y6W-l177Y#RpN(E;E?~GF4xzZEQBP>
zHMaEee*5L<W6ARdj}TrDGv??78u~USOjbv3`CMa&C5C12)F<~iyx}SMpH0vohbe^?
zQldY&B4vVKDZCGS2tNWiQROs<Gnw)6iIoZYAalYZg^j5eri*fzrH|s7rFRov7(|MN
zyk}DtYeZ`}mG4Ctp7O7MecQXlIz!A-Fj=N^NyQywQoJT#G&|F~G>=O9(cL;IyQQ{X
zyv2{OfU3wpG3@C(<7an2wr?BE)VzEEGf9f!|M#B#vlIW`G-hVj|Lhs#U*P{g82Z1E
z`@h_Rh>4?-gN2=wt;1g+{vWzQ&cOPcJCK#p{GlOAEn;G6pz5sr4e9^4Ud+JS!pfb1
z;$Kw+f9oj!RcU2l_Kn>${nu0IU+e-cBLfoy0WAv~69FSTC-XPUz|8b-mO;|Vz{<i%
z(8kQlgn;3nc7l#Ze`yL%CXRp9zvKI>(=vTe<?jfE4eTULEX>TmnT+pl{xK;#nOLh5
zaQv(NUq#|S%HJ7&e;iGi2>vn%|C3SpOQHPl)%aI;&W29^&?hS2oW<Xj`o}6{;Arv>
z8T0>J8H@i@m-)3O3`0@;y`Lg4W6D62)ZA3xhB_D<Y&eF`#XoIc5=kqJefr&-SZ&lb
z6x!1?Y3@1c%g;CMye@rLfcNrrFJuHTX}MW2B<`4{MQCAc#l~x6pKW70A<Vos+qQ0y
z(&U0xalhrjPtPF-_TP!<2%p{`fmEf5WW@%myVk{JUch+ioU(MkK~B5~=Mml8v7gkJ
zF*uvx;uU6szK2*3(I-^!4DbmdlKZxXNDiZaP2afN7!&1+>3lO=suO{*)fr<Q33~Nd
zlIU}?Pw%$J4br2*rZnC$F%oKoOB~c~dzg(8$e~*K@=%*iGjhHf#;DJc{<X&01;M<*
zVkWtiypRP3T_||s@{#jlf6@yH?BLwI#O%8&SR9scLUR}D_2YN@j59IG`1xRHORm_S
zMGZ73Gw5Kp)3}&m@vk&a#wQxykV%OKs9}9l4b&7ZN;Mn~jZQUHU<hxt0+*il13A6^
z7Jyu!(`i4=Z~JK}dgHae#NF)!7yL56JE|4^Bv#I$=~VN$!Cvhiy$!jDB(U^ts4i#;
LkUcysKVGswZtkSr

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..aa24b385b403d604fb3737e340d118a4ded0f878
GIT binary patch
literal 67431
zcmV)#K##vAP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_MozZ5~YZk
zHefVhz=Q6tnc;!aMmNydIVgKz`|Z6&uC=J0_vXpEU!hP{DSk&gB#M$K{w&(p`Tn1O
zviJY7cAj7V_2=;~$N8g;^SQr%{r~^@KYsoD|Kt4n@BjB<U;oehfB%>F|Nf8TfBWCx
ze{g>NpNE}a|LfPkd|CWt{@?e{x&OFN`x@i?(cl07=a=^%_xs04czyksum5!Xwp;H%
z`unfn-P(`G9}%+K??(E6{r9i`@XyDcle@oK`_cTIZM?hBAKu1w+t)w;JpTQE`=|4t
z)<^&Oza9VXpX|r@pZ@uO9RKq_f5(8|4%Ft4vCS@;-_OmT=g0KBI+5^)Zg=}}ZJ$E>
z51r=tagVn30^twc{0^>*{UrQj?0<gTSNHz@>aZWr^&9s8b>@3-KkVFR2f`m_XXA%G
z&(;lu@4LOl?^BdX_(QkbD9Y#t!XLU#Pr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>Z7+
z{rnJRwExh_`ll$9@O`)TOp0=LBjFF-?)Tv~tQLTTe`pEb^J;e4{r>9Rf1H1R2Yj7>
zeF56+pQ22{A7<zCQ<O>gL$~*i{t#sn{?N_Zenw{V`!4nj3Rbe8gnx7gjNAKLwCufA
z=kM76Z`lEM-5;Wi_8(?9?NgLV_(Qk%|NjtW68_Mw-4tbX1K|(d%qUt|0ucV<4lwf{
z?e8B#U;l<X;PFpMM*I7@UDu}^qy2rSdG1mitv}o|{g->b|0~YMHX%<qc4mpwKP>g{
z-Ff{+=>JVh&+{q0&%Z);H$9L9`|hB6Z-~XK>L$YbhW|&;f$<)vkN17?HQv{#|4tG4
zODuWs_puEV&2Q)SKFa!=Vbw{5Z@bz1++6>;`W5B-j&C_w`+e&u%J&_8r1D)IMfnTM
zVE)zu=le8xzF&vGunIQYFJe}d@27Y@zX)1UzVG<VkA-LZ+fMDRvV1OmQNHi^K1V;-
zz9@fTCEELp=+7T_#9zA^+gk_x6t|*$Kgs#|MEv<xl<zy<p+9c@Ncg_n^Hx^RkJS+6
z+m7A*W9`}g3oFs>{4wu79{+A7{*sE=yZs_;MfrYu@5kP!uodO|j_=3i=gJr5`;PA?
z(dWt+<@=7${kifY{FSwM-rq`P<=eIRYggy{jrl2TMfrA$>rLw)hj3B8@90l-*soqv
zzVA3^FmLN9%J&`bzITe&Uswl!pTPF#J@J>6#^?D((2DZy)RtlAL(oL{zFY6Vta?$t
z@A&TUx#~svzT^9?|GDZ#`75f^c;ANek9*>;=}vDo^%p@a${$4gQxE;rF<)Q5{_wwM
z$}!!4S`%OIoSbL7-#aa5|Lc_hzct_O7;it$yWQ(TeXD?FYW#QqulQo;xbOD<>U`@8
z=lcA6TfKSv_XYL6dD_xM@&y*H36?C&U%U-2+VYCxc*rcuTda>D<zo+|HzidLP~QJ~
zQ$AXTS7lJvo8(P-%k1$BsSOa;Q{y`0$3F-)+%=6hpXmDfI(CxlQ%mbwl(gU#1uyC#
zy#Lc8)FfkEi&T?*3(uQ!#TPy)HSMw5+rQ`f7ANTO@S;VeC}ZPG4`WN7;Gitty(w?D
z96QA~#`JjMc?>8iZ3LlM6$Dzgf>Rcp>OaT?bJ%(G>7=yclLepJ#-}%Xjv$Fo@0Jyh
zqDB4~Y)K~`tU-y%#C|$RTC;f{5adcx$d&v+8@G6n&$vYyLq8PDI&N{na>d3a`L<kw
zH^nrfSb{OvNBKj+@i)meqTu+OVj5Afa}4pul6_+&k3fnMx%gwjw?!e3&fIaMi$}Qw
z7DYTdlWn7kM<;mH#G?~DYTQsKSd^=9fD{8VNzMrtnV7Z=67K^|EIYxV^9O(SJ@g|8
zrV$5woEvjdmi&2b%lzX-F^zZq>#gSBTd&~Gn}Tjv3dN$J+x5WEctJ|9JiQm8Ke_eZ
zq;+!OwUC71jZZEF9%o^%9Q@(ngip5Kb97n@7a`d2reHfSN_?2cvqgznJJ)0>An)%T
zi_|#U5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?JaxoFZ+4i;`2cSjr;^(ZoVt
zHzs*<Nv<19i`9R(V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P
z(E3%KVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wpp
zEeZu?=C130pqT^jTbCSo-@4?uwc+2C#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi
z9YG0J>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgp-<yzaWUFwm1
zU6kq->}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8
z%*)I804ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1
zw;a*AbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5
zoo`CR5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2l*3?}X+)5$P#3z_R;
zpQ+-!NoXY(`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpE-h}+3bhdfptEmYcNy^XK
z)-68^59^x{4II7m!emb#@~Jn!Id(qmkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT4i
zJIws>DHU(x{5>TU69?{jX(LaZucxG9=DDya)h(p!q*SbshsE79rQ%4^V(%%bfF{2v
zkcu}YC&}N)36@k0T%f0P!kI#}C}cmJI%n6a;b1(w)?gVASKIK!nvO|Qp`ZDhT?DRx
zM~lqtV5ZKF*|~}a?)UhJw8h!+4c#7a94`ua(xZj<%*^xb{Wsbvd1RTwR~BVNn+!>L
z<~Lh%ES#|<MT?v;d_r0yygv3^k}Hc(gajTS^zaz#X)seSS{8Y-<Af8rgye*ud1`(+
z@8xLb{L<i3uIEK*BM20d+&6E^YK<rLJbUzT7_o~M0dpLAzAg&pI36&mbB+V*=OW>U
z<3EFs>opY}8rN>zV3S@I<Hp#V&a82RQT&4(xz3Z3=kua)tQQv8G}bGhZT3jh92bTU
zO%qSF)#i9J;KFWcA^B(v3hfFbPxVCtZ{L(PjyEM+?|(^BM&A94!jX-9!P_lS$rs(5
zqQhc1y6FlTxg8gUpY;^2Hwn$P<oCc{9F89y+=~NV^?OhNNA7mJ<8uc{!Tg&KijnX4
zHz8ULzoBztU~}C%Cr0DI^z_d+qroPVgdClo7Xy3h=JRr3OWmOZ93X|T;BlUm_~8--
z!w;7zocQ6Cgd<70h7^SpD|qtTr`&6=utsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+
zwD%JLJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bo06^fzw`ug
z$oVB<as1RGL0a&XwM&K~pBS4Sq&^T`qPxaNPR`1{=L2KYLE>SJT7;3!_;;>_0$7^l
zz*8GG=%Pu<vB{L=j<M<XQRIv1m5WFRyYzf{Q*vxFGI<Bzq^o#;w{)&}i#Nrh475kI
z8k@PICt4w%P}LR%au40?NK%OBltSw{8k<sR@uprBO6iFZom*;_rzW~clpS0ZQ|e65
zYtqW<*z+ow^~&w*ze|w%jo_dVq<*0_(8{6fV!=DuX4g&FC&sRuqC;$^Zi=2e+J=tO
zjv1%<Eq@489@<cNQreJJwLPHBjS?do5dwPz!SE-!W(_kO6RlXm_c6`?8f!RoyS6KB
zdxn!dNpBtwr<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7
zw*gLyw{3uv+CF%2+K}Sb9BgaUI~uka27~M6ectAM(>i#jS0Emri$Xs2c;qY!<gvZC
zQkeo9?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>zL(2h0thYz_1P0JsxVLsce
z42UiDD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNjZF(91T+Fx&;h7
z(I<}t3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn+q2`ANm(>P1r>g?*
z)<qd;$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%E
zh7DcTPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+lUD0|VtFL&=Y!Reu%DC+>8R%o_0dl>
zLoUiVdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)
zval#vs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe
z=^93+S9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV
z7&|qkMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixl!Jf
zXtkUlE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5
zA^ZJ-U7*w6cq~%N`Kd1%mh2R#pp3~h{iZ~VJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}
zt1Lns7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@g_kSTK+@`LgPMN?O;>mZPf7!
zHCe<LCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSR
zo0NpRgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SA
zo9o-Bdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{
z5~9Nd4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk
z=r3jv<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4
zg@UHpPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8dQF<C^KXn|Tfd
zCC4`NEn_s0^oa}G<do^KiJR$EgaLd}IJlv2VQ?uChZzm_i-ca$f;7mn(-ET*6pRki
zU^lHQ9d>6k>NAVNZUb$0!qU==Y{;EEf;57F?LV73VGGhQY&Tl#?=Owju>I`PVDacM
z9lw#U5pDcrdcw_8ZR+Du5BRbdDb5DFD1`%8htY@G$E|J{D=n{fNib<^HJ#Zbbw}eP
zV-e!WGvs?LLL8HLIxIeo$xfI9Eu=^~U2XOOw?~?yf`Tbfb)eJiO^F5s12Hd)f-?uN
z={F@??|%)le(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p
z@w-SVk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZ
zA*IB*kNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vk;xALClOLo-lz
zW%rJ?khV<wo^^7dbN!@0D{HKa30!vFiH>vLbSt{?sOn;aVa0S&I!w<7TV{7|=1wv0
z+|F{V_0H|A+q82#_h{YVuI^Suu>>Vq(P2^!QVyoW|6%af^^V8BHL{{Zzc*?89j?el
z0x$4NGGs@tc1Sl(N4@iq-YEm)<C)cYO4F0vI}d5y>%D_pe1!Mjz^$g8gBbH5VHSAc
z8FQ?AzBNov>Q3t-C`XdO!}x;}(#c4dMM?H;lxSfM+CvGYb90fBokh8op@>y!u=RXU
zmc?yRa-E>8n>^}0jf)@cWR#SbHkBKRc+pOSqS0irD28v7GLli!cxXHX<w#O8Dm}Kn
zxmd+E8HMF<+=V+OtUhK^rCJjsiqdj0kPs+hpOkb!niMc7HXFqrPAWGcZD|{UIitZS
z+IEyi8o4j$-h-B!BHUUdY6~#C)Hu#dyu|R&Db^K*W25GO4sj2Rf$x9g=jj??QNX+$
zU#Esv1o9F~eRj=>lvaY5@^Ll_9?mNG_BY9+G3A3I!ApLgR)PnnpS9sq>d)G5*cj)z
zwHl2n+FXkwp(1J9Z^64oA*XU1FA6wCLMm)W9tEq(!z)jZM&rpwnL4}j$Z3&fhePQA
z;qx$S&)5$$P<WPwSS<pNvYx)n26Ktd%?6h}4p&fk9XO^0M=vQyka!*Br&`?xm_n=D
z!1ITx?9g%09*BZ&mG+!E{kaII7|2C9#X#`<PW|S{D{eJ)Pv&4~`q0hUX#6mGk=jl5
zwZlx*ZtOwc$cxZ%k%L(`^;cf)?dGmbZ{)EEeeC+co3iN(?H<xHz$ltJsCT>xR7-MP
zt{!00y=gNT7_}KkYo5Duv?$?Bkpk6_H&IGfgL|EdSP%?a7dc|&yo)6!wJ<xKQVKca
zQ(7Tsd`c@!^I@YAL;7f=4MR$6yB_s|AY_zrYQ613yl$z*?V_qfBTTyx{6Y1)T~u_a
zfWIkUP|$N^RD4p0Z`V`@tnW3y>KU-oSNQk2ni-tBzb01p3f}=(zl&$`M62cd1<QAF
zd8dwui)%bNlg>_9ELth_aB3G<cw#QljOz8(Xr$l^Ehy}S2~l;OTA7n#F|{;&nQ{j8
zGR5LdzEb$?T$JnsCr_J?I$;L0UZw+WzDqHId8<zxJ4fWmuoD(wUh0Mgn0%;Y3y+jr
zgPjOd(Sv@G(1Q%0gS|LfDnvI%JJbbt;>wai9~_d?)rW)S34Lp@Jv%*UblOvJ+D(`+
zX)8e%O<7ZzMN<|RCegqulVdY%7TRtin}!A-49?VzgTv(<CZfo#NlWP|Uedq~GgGA2
zWDgE+(7;V&)uM#*O_SCuQft@^yo3M0EMtqpZ$U8O>_1>*1F6F>2L{qkAyZvLL_nGI
z8tfEDnfw|}6|xI9nkr;FWR6am7m=g0ekiAv5<&Z9rsvSAiQj-k$j-UabI^&42RFYA
zra?)=ano2DdvPduAHg<zBq@98<{YqW>z-t!mCV3xm^zIN3yB;a7@WCUr@G-BK@v|H
zrJ2Md!}SrQQKs$YW!eTWXvu(qyrm&S2K45L2`MXkW0X|W)#6a(WUX%uiIPQsrR&`E
z0zhzms@p)jjm>k=81p3WLS*%v@<1FQ(T~B8m+ylgFW(2hUEYt8obt_C(rDhmYcDD3
z`_QTF^nK`*_C}A@MTX<(kbkE!PDxInmBe$6%}=xlxz-nh2P4tvq^pTZKJrB&$)~(k
z%<`c>D^h&I<|mieA|>~Ac6PkI<U3nQJh=dLueFZTST4BMVdU1~*e|f3p1cNE^`hjh
zNQ+5(=#PGrHs4_6_=L}t{=-E{PbHm<E3xMq<%VqOR6aIW<szj&UdLBQJPwj*f-p9Z
zXruWgy{0)dde4ntqVHVCQm5}+4;T1<>BBuT0SHc9ehb0T@&h;YPhW8mQaI#IUIffi
z8hnRv$SEBeK`|U1GW~>`nyZh8LNC=Be%SPnH%52Kf8J<xk(2#RkqdsM0;TNBOWztp
zDCo#<4DjkYC>oRtMFg}oxg1;2K%@taJ+Oe;K^b_kS`i;GHB^LeW$?lQQgWZs4GjlT
zML;wfVEWX6;X=<Xek3JD3Q83Y<O;`NYEXr2tQ?;l4#GNG<3XXYkA~~1B10lG=-i`6
znDtWuCz14%5g6KRjo}kgJ6a}rW?;)|Wq1=KUmDCfeoBv5Y?br}#a2mMFx(u@RtE8y
ze)WbbuehCN_ZHXFpr~ft&uZld^k#?3jNqXIB!mj-M{?;Eg!CpLKq(S_BIpM;;>L%H
zxwZwKKNa=V@Pw+!s6}DO6@)e)eFs9UlA-{th8J*!Xf-^oD~zk*4UbT-1El<n-b%1d
zC}!+UKsZ@TV@^ezHRG}1dcYVSn~GXnIX)Tmq{j&DZ;F14%%Hd_{L<toF%bC^dWPcc
z8se=OiMQH_=Hm<OguO^1eT$OIBY{7mkt!;X*+PgM%pZdG!SKRGm}kWwu69SXAx8%V
zRZ)z`$_$FAP$t7h^3WCxiPWKrmt^Wt#Z*S>P;6oaUAB`Ep;CoUMubZ5Jz>OWd}o7+
z@i6?XqCq)9#ONr5bY%)<M5wGqG&&CD88?P=4cT>8IF|xiky}(TuPsfGii(ZwqMV=X
zAScXJ3a?$13@mlc588_&bR*{|PILwFGU=!yeIx0}Z^Z(yb~0|s`${Of2Lp)@P#AqY
z&}Qs$@+7i~#vZY}C>dG{K|PdKWP%<rS|t@9z4C4{w4ADc<lRJQHuU^Mi8qMGjz3~(
zx$FB3Ezc2Sh7s+(vR*=?t#I%~isPQ~;*khb;p8jzWo!ZGksK4Fy6N#+q#U{?b2F-(
zir}K;$oXVml#a-GnC=%TgivrD%&Dn>`^c$@nEw;4jQ7XObrDjY5YNBTWgh&+jTxs(
zr-Xn-7+cDK(fn6%B#RVNyiCK#5v~M<MTsdYiD6M<r(R0IG$6(x9U>^OBr#)x$vI4?
zSnaW8TNo{e%E&MVNGWZ@fU#1k9R^gBO8+p0Oesgifbmg@BuL-cl1&U@RM$jfFiYhC
zA$dm)h^ai4?_z+fsGJxB76tNV4v=zXwXtq!lghs_+9;Kx6Inm;F~#B8#mpW)FO0EQ
zN(eGQDpb-Ce-b%GM^fT<kae`$nOP;l0&qbkFLCgd;B;8VXDJ1WOi<#K0YIQ~s|=6<
zm46l7-7~Z-)Bh`r%NVZ}d0$2oDAU3gA^u*OV~fIsGYA7?x0Hew(i8)MuCNFL8EkeT
z`JuAjjA2~Lj9ZkP?X8hRZB^2pWv=<L<>+yfA(1aBTcRHmfS4Q@dwG30(+3ZbBB!#}
z26i&#AsURPm8)pT1<zc@I8qMgI)Z>yM-7XKnmWZNqKK7OxhU7DtV=_ZcO_;nN)DfQ
zB6Eo<!E;e^_^z{MGGTL|m06X%{T5|xX{K>r=ihTfO-2|#uwlO`TRN-JZmX2nMPcSF
z#D<pK%AGZ&ZC84&(YUJ=+;t-*pCktpPVnch86u_`jKtxuMBqhfW6KmanuL{2Y!gNu
zq#P$DlC-IXnUb_mEh3Y&O^X;CDDs{Uv?JYLxzVO9ZCwz`(x#3TxAv(N>?0}pC2j5L
zND0^8R-QHucNTftx(+6u+m$lDNSO}q;!I|05Bxi`v`bW&r9E^7!h}s7^(9qB8Ss`y
z?aGl~gq$A^fFnqOop4@aWr9&DA%78)mr^<=fFzXIe*~2EnNR=&f08r2C1Vyde8hg>
zHVI&0Q3ADr7zB%upbe+E5Bw!z8Q3IZ#K}$sj8KTEMHFC@%YU`w)AFG&N}^RXts2mc
z=o((CEZ~jgur-7aCcMLH<(CQnuqa~#h_FohK7b&xnv2zP9~vSJ3x#57r1?!6UJZHR
zK(aVMN~j82Piz1?NRSv*ZH1a)gQyXcA+Vtk`@NxW7~BIw=rE*<7l?;tP-EeI9HD&2
z&)n5%$Xt-^9E-HiaV001qqzuieHAjvn<VIxSLpn~2Em(H21*tJiXpiiC@BX>LpGIc
z$4KO&K-yvfvMfR{MW8LmdY?1}Rj=1eBF{8+$s<f20n0S?4M8TJJb}$7<Gu~T_W0H<
zfoFW{mM|~A^-7R8ncdebERko1x;dCN)Xj5<bL$jhP#`?<zT0qm41Siv@(Idm8{SX6
z8)JYMAEgFoOaTY2_ht^TBm!6#tt0~AJr7K&HVEGHY@HG+=h-?XG!rkAfumI5NJqSl
zpJzi*GWdN6va|>r1`|^~3#Tb4aiR;%iO=#Tv#ufBwLqa3Wo)ofs~!C8ond7`it##H
zfg<Hwj|7pb^PvGmDhH12{sO=<AORFY7K{)Hpk=@XD1a?P#4SL$4v<Cxb)~7}xi>H`
z8b5^hWk9GaNU$SFeiJtgf0Tp2*$c<J(8mnXy@gI@<0SKG><o*|`j~Leg5tM;&<qj5
z1(jxSt^rQ%04b&gz%?5L%B!;g*Mtm~v?dAJ?Fdpr#7XHKXTifQi&V@=2y*7c#ACF|
zq6D%Qf#_)1DzG|pU=az=E{tLEU8xNK^g9X|Z;^72ldaP>Ts@fB3VLr5a>@#9Hzz8d
zmfv^Kzp&-SH)!ZKcpM8n5ca-fgBT2>V0`J>y5%Z9TepNn)Ji)bC5d=w_-bJy(*9Ve
zi9s1VvZ4Vh0`Q9mNQ)J;$uSMNKpYKIE}+LnNyNy`$i?g;4Zv}K%9>_ytrqO0A#A+K
zbY=mccx?EU29S!vxD3j<<6s(Gv;fN_g>ae&2+11hb`A`_GLFG04De1+f-^U9#1<td
zsu$r#c{H5h);uMjd7=<;G=6BJ0EWyz8-@G<rk`L<Y20Si27V}*NPN^HNR`h>dt$5_
zWWHcnK{+<4RvOj|%{3_Jj`&)XLCMK0^(f@nAZ^&PY|9SlQ+TwL98xaMFIKKhgBzt7
zm0+~@#wb!YMkPM&U5rY?voR|0X=`JOaBH|>=PUeQ`Y8$`I4FyE1QFf|#g=fo6&f)~
ziB@b#eJC{JqIgYGkjMv{QhZR#qHvW(xqE$5A%tuV1mfv)_uRNc%EpZ~<Xf+BQ3SW4
z$=~-TNu+EXTRgm<jbk7H)QoHKoEt+x*u-Eh=wrJWfI>qUCF8M841&<MiH3kZZIc61
z?p<y(BGx_y_o;n0qE)+WM3`*}P8?g0(;KfH_595qd$v6m8}r$>SnTI#?7T|SzR#j$
z&c4m!n0T)JZ~>*`)y(texwgY47;$gR3aNVTjaj55v))X<BGB4&H-wNp&vqEE|F*)n
z>o6vz4&xB1UiJ~3*ef!;PUE$h{j}{gUb9&-=XDy#(k)WmR_iM(n!RqT^^?7f9k_{l
z89W^6GK*B#)g2=m+jVuvh{kqZ-7%uET~|+zXl~d286%q8?QSumYrEZ(N7r_{FSGHY
zkVQ8ba&MP;GUVPa^EI@UpU|a##6iADQv(Wy*tuye-D)?cRufqd8eZ^XGf+T3>SkNF
zU`ClJ)=0`c0bG@?ICW@cN02TmjTWD-8!yh0uIOwkfL%#mR1jBj6DbLK?sr5mQ_<{-
zJf<?*6-P{kwKEF%_)4WVD5d4*tmmg{+^wFVXSAe8C&zl3BT^6S3U8%~z9@WlotWdT
zXH+Ws$0G3^bz+X}k~5Sk6Ay~6P)|NOdOOp0k}r#{7)?H1y23B{yy=Rp<O`@bp?UI|
zv`8OMsor!D<F(Zl-pCi(qC}@7-)t*2sQSbbDF%^GzuvU=`7-Ry^^CH#oGeoH$~m}t
zHOxV-3OrLgg8cA~?P-13-?@=Ar9L@>sXik!ug3nI?wj!eZoIx(9~u_n+PdW;Y{rLZ
zl?@?Ik2E|SBn7{pPa{JAusnpcd{`brVqkeFdqtP&0Va+9VR(oQuo)hbxtsC9A@ZB`
zA#ch~q!3zR`eu8`gST(ChqZTC4j^3VF!%J{w?0??Np;E5mHELjJTH@BzEKv5-3ErI
zXDG~Ay_b1%V0?8or$J0vlP?*~BC}H6Vu*A5R;+Hn^xPUV^EJ=ic-MQK265O#+UH4w
zUykM8I*lU;)hC(tY@K2x&(<fIrRUDLB14t@&bz&PNkg1ri=YlU5SKKp*IIYmdW4;b
z3A9OC<M38pf+1d_fD3c8M&Nq%5{6{PqENtb8J0-`ufLTj%#DPb%}Y;%ZF-To|B{I-
z9hu!8aDs<J-bqdk{eYD`(wuoXJi&>n9w8Vmg&TJG?$_2MRR^S8zhu#8R`yF)|6ZmG
zcm{fzF2Z-v18b7Lg#7rk^~sORe+@51_g@?t9j2k<1!qT4*eUP+K6G7#$D|K>PvWyf
z8o~ssRv&U+!!N@>X!xi!ymamKGGO4njAZ=-q>%MNdsRN5yJCjuXX-<;0bf+d$rOGi
z9HNR5qF1XA$woZ97c>DqLO3xI4kX9fB5=h#@D9os7m{2i4|wMQn(&eX55NisNI659
zuiy#n6*UBJVITB2CMR`h#MAx=3VA>9A)Oj{?DxTYBt4sb=o-QEzYm2((?i;)H2!p=
zc2pjvmz7u-FL_}Bh!HyozS>11WAe;g6fgz{QW;U;7Vfi2#P}kZ@_50)+-FBCzayLW
zjQ=K4!BI1NO%RHAnN-3L&PvzxlLt7-;E%+iGD}bp8rY{E5AewM$yf+D?faaXAC%N7
zV`sYldzArVctD@JVh}<An3fkJnR-QFAt<5Ga)u&up--J6Y4YfkXow7nSQHEfMvz5e
zEXvZn6iS7l3!>Y+7@3g>ID^p}aY$bj1;%q6i-aH%Xgrq|9`z0SrG<}Jr`6_2P<#8*
zm4R{$1OrM+{)!&<5snggLW*FCrDeIQLqRS5lJOIPFa2U*Oi24B)d8_Hfq=Bf)*K0w
zgfHcuxp)c$pwhx#;*2LoBI6mtd=`Zsc7y`;OOM6~7D^nbm!gR}Yd<sKs9&|ph|23%
zEi>f*Z(^JJRq->pG!@&FCV~XN+M}rYt(OEst@^DC0^wNwmI85~s<8NC0M`-NT&9?=
zVD~Kx4?@BE%||7o#fSp-Qhe1BP+=!YAq%%of{098Z3dm?Q{$F!AhK;y7^i~pw?Hw&
z_;6p{1Ff7gZ9oXKTLebCb(|Epu8@e=3(Pe}yM?gdIu#J`*KgT`U>O9M+a5Sb#J88C
z3m1jF!$ot`N`xTAe&??aj*WhDL^}2|2}Ud=k?LLy^&*(vOYxL}c!#%D##{!8<Hwy*
z5n7mAf8<9&P}rh~|JVR!Nkow7qA*+%_MnGKD`HI-As?a$N9{5!B4l;p1yX|I2B<);
z`$>SoJtX!>5JJov$8;GHF_8c_%n2dzc0nW-C3w^yT^k4$3v|YZlpMcq0E7ZBl*gPR
zqJ@tIY<ZEgI(eDb5O(aR_7*~uy~2$UD78R1$#O(E2T~^nokkMEc~+EkKz=$Y6O_r=
z`+Q^uPN<@`vzrnU5VakEqaTsoUU5bY|8`mB5F;Kari|=fZ}rvg`ipA__%vegdo&UJ
zp67(0*H?wHFC5jz|D4R^Mq)JlqQE81SSpuAk0JH0pd?1!`&s!113akwVubHIFh>;Q
z9{{qP-vAFD%`h&Qz?@BeK9dQYp-V_M@URLp86f~`m7WkRFy-%_xOfPCTWJq&%5B5k
z7JM$(Fz4p793sc!5XNpLVz?>&AXHLMNRCM4@WRbNs)t*nSTY;L3%mjbPA^~zq?LG~
zOkmt@Dvihd6bBjvQdpvWkq~@Sf~&PeF2-k3*uo260XZ~YcnTPk7ghq2aTby?Q(ll1
z?gBb6&)U5BkSB+Rrsw#~)bt#mnKixKTTc7{;FtvxG;($zTrz5|<R!OD6U=0XMZtO^
zC2CQ?q6?Ez>J7507K$~021(q6x>jyh{1JZV#*CEuiS#b7M0xznP1g%^$rcISkZZQ^
zywMH$XkH2H4YH8YS@}a5GU%064htvY#b3&h^GYEHs(FBt<19d`oma+qK%*zRd9D?r
ztQIAc@lv8($=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2klreb
zGS>PCBzepT_es;~jZDi$X<IgC5IEe281_u|%yp`iN?bQ>qLpi;oJwSjdgV~}2)cGy
zX_<7o+88<#Q(cx@WUmHjKl5aBlQ&g(Vh*fV&NT95y>h0JOY4mrp>y3Y#vw4cYE>0r
zqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0JoRt(k
zv1USt=vUNTAgA&e@J>S_^QwKzlFoC$w=C(Ht9Ri(z_!T}564Ss-oB+t=My?gL!et;
zZ{D>ZJG7Aw?T#T=i@-Gc^=MgbCecGgdi(&A+E+1i$e1IG(G^UG?06PDe<^|9D`^@@
z_O7I9$GOle8xG0(-uYBvLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+845`O^
zR}!5=q4F*?ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$Dv2`0%o|;t5Q(|
z1Y!{eTI|Aa<0j}#OpV-2)*5*+Nb87#B*YD&a42OJZZ?;dpRgB;@_~(!KSU%GQ#WE`
zKty!P0EWZm93WQ5;ljiRp2s2pSf!(rZd>F^I#a#VXM;*Ci5udODjq{{ws_@!rz^#K
z@C6={Rp<p0Kai8`$_)n!$|7(aQ@sY-`4MH#BI(gPP16KriIOt-6(|P%K`VRc%z|^k
z`=bTAIW|Gzz|QXq!6ep<cUm%uN3$qgAXM-0%1MU-J}4<O34RlWbRaSS$8m*n0zl^o
z62N*)y@=Lh>Xm<i^P+OuVd)ME?wmAidu6x7jLq6VFG2^c`aoz!2k9%*IW!_m0Gx;=
zhF-)ka;GJh7)S0>X@G(hm5Ojx!wl>SJq5s0P$1ul!Nej+FF`adie)$*ah#kEB0@by
zAtn4U-W0CW7G_JYm{!6{EfSHA9(BuY5a3j+$pPc4aKTtyC^F-&138STQ4}hd38qYz
ziFyf4%UwVhz}pH6G00N$Tcj8Zs-e0ZT158pO8N)-*P^7$8~|ZnC;)&Eb9uptGv*%p
zUc!*EIM$0OWk-_m8D|f|kl}K0o%=9p1_hr<ed}<=`x0i&UAMt?MGKf?P!zoI;jr5i
zk|5cH?e053T#B9^MrqAl1Ww?ARORh)yaYYxiZmuXovVxuA?$*ZlY(*4;rKg<gy)5R
z0IWP$yfOjxTzCjKmsT&c8<<Wkm-Z5NpF86#6W=dttYMxv*H-U2Sosc@-;qIp?!=G-
z)S$cWuY0JL+e=V|o`G=(NbHh7F|ks*-2jp31=;`@MQ0fHA*@ArT2a!f=!NTmBu;ld
zEpKjQ-HA8Cu2;pnmyjX7pdjwt#kw(X?qa=A0XOMh+B+~Q-FdG9w$ckvBJG3jx@b`e
z#9dK!1jKZ?Yzdm_M4<qzrn?>mPtSsVIogEbJXFK)C9qB};0geGeo{Jy3)sy(qYqXG
zd<jj|T?Qv0j(S000G0HUa_2^72rltXT~23WqJC16f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E+#jOpG@-G682@PI7?K9>0)oe0zKqw(Z`|`Fz6TI^+2Z
zL)V2CLY&=C3OPl9TqmaxQ%*czcVY+<^Y@cN#sD#QiV=A|5MS7p#6S$<Ps)`azrnp*
z(;@}tY<HDipy}*`!lg_}TCmC=EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NZ^K$UI_bJ2&D^BKxpXfL{8fkfB)L#Lzx=%G9(7t4-Btr+f$>Z7!>Qd=c||lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3jawNJm!wCf|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR8ObU8NE*qN~&fmRdk@*`Rc3A9-Zax*>olR&^+qg_R#lrRiQu
zPIAVV$xm7lOG}jM#PSoRUa>?)X<(fyQK@Mtby2Dut6@mnWAqm4-hx7<5sxJn-Y7jX
zOLI`sWaW-hMLUfdQdgq@NREw6c+?47a-7mU!H7Y<M-{6Eu-Qt*M!gajG8jvml&a3M
zC(`B_vgIy^9)q^(MS!5Kpk$|B4-0&$*TZ78tR~}nCvXz3cLG*(#BlRp_-oY(834el
zR}$;b=pn@dHTBj)I95H!Sm!1v2MFxL!C&ly6&ciTyH<qyZ6{P8EA!M7lhu3b9m)zn
z^;TsWAU<Xf6$+{cZw6rLO{@T{dN(rwtKQbAV03)(N&Zrqqk6VyA*6cOvsO~Q{aH`R
z!!F7iOeuM)3oyHSae%H~9H6Tg%zmr^B?|^iM3t3;b)?b=!ZK53Bta>vG|)hxQLhTt
z7Ess?;+p|gG}*8)7K}OvNbG~L-R#1l-ReYU(yaXu;sRy7$_~X!UuCRfIj}NlA?&Jb
zUI@F|4P&f4R@O6ACo2OR3z($=js?zOpv&rIdCoHfy3<Y}J0EMQ(GrMaYh@}#2-ap!
zWWBaBIkKo*nj~5Dtt^%-43|dD92n$4vDB<EN7E>4(3SC&b?RhaJ+hKr8DLrLuB@~y
zh*y@}ESXoPUKG{a?ZGI$w;7EyD67oMEZ<kAXO{SbdHMh;&C0rwXvd(Ho5cjn5YB>w
zG?gDHN$5(sXW7ECx3jci+2m3Eu*~)-ka*Cz4^oG@pWmjF14sT%4~Og9^l&&IiYV&1
zc_UWQ$MRONC}epwST?e}9w;q&$TPz7ljS#IiOTY=u#9E-Ur^|B^U<IhX8CbgFtc1e
z46!PAP?p^+f6>9JoaI$w>CW^zv9xD-r5I9Gek;UO9rA6lh-i7gP-nCpWGqEmPBd04
zg{SQRDHlzL;bULrty_Un$;!QMD&2Ltp&ujrb<jO|aBPKCacykHRB>&{CCNgsN4YIo
z4YpjHtQafrCu+*dJ*uj+aG@R`^|85GS-!SBv8%c*U9~S&zm+!^1#*wg<I5_#<rQY7
zT~`)R*5WPSGOP8%|D0okEXYaSk(5a{cF)4V<>qGH;BtklxN!Q)S$(*C>8wxef-*-5
z<MPL&%JES?dzL~jx4r|@s$BnBKDmMeSYR0e1jkoZVXi0xlxf}~5m?GOLls!~xgr@*
z9QxS89T;<#mFB;)%JkSGBv^&I!YCMB7J(MWm#SF@A$O}YzDm&<tNe8ZZ=gCh0zAG{
zK>OIDKv-qFB1Kq+yP`>0&AWn7RPMVXRag_eqFG$wPrT<@XS~8<P>lT8VrLk(rSKZh
zYE~71!+5NU(m`Q#M)Cx^Q1eL9J}j{A0$gGd_6iYVk#>d=9V+BrVMeU=&d?-QgLjof
zVMtX)IH9ckv4ugg@_a=~u{ym1saU|ig01+AM@3{gYOYk&mZP9bMRqxgrBwKrqZG<f
z@nON2iXU^7Fkyh%Vs=I=bxjjuQ8fY`l}sy`&5dFq!B!*`Zy^U@wpaPQMard#A8BWW
z+<6xBsGvMVLT!<I-hgaV;e8>^=N<w`iLWq0M=_0xCB$AjwtzzidQ}D_u9hR95u<C0
zdF1fA;vJ6{kARAa^v1AF+7i7nZc}yc8!YV%z&vz9Rg`8NZ08=y=>WGvxMxrpw+YWc
z9-$ex30;%tZbp@QW60*@45y-2IYU4dRN(3&A#jzmytc?!&k_%ajs;;be)a$%d7$&0
zfm;g1ja&0HM(cudgMyrEUeFcx8@Kq_LxXwKBYt>MkZXz<;{&7&f@OSXs4u}NzBrwx
zMaDBzA!f*P>fRYmJ=JL<7M!;#p9&RT9S@8MriRHRA1O)FrtW(n_j)_62zSMLduOaS
z1H#v9FVm6~F&@v#7#?5Me4i@poDW(Crqe~Ak?RL2^W3A``2?>Bcs|<^CJ#!6v!7Z#
zkKAQN+rz9-0r~Eo5&PLvz&_^ehzPI9e;QLNH-JVNr4P`8lj#LC`egRO0ZJsAC_{lJ
zsLEn+A5y`i#asyvd~je>qaR9_;OHSe%DJGWuo5$1e>^IAgJ#Uk?QrCFR_@2LuOc}l
zTi}`N%7d-2l1yk=t~3<duq#!C)^k3kjwFpO2L^tQN|T`<rgCZAnW1C)(!&YreD_Mx
zp^!2~2jG>y@D7mm<46rfUeEzj{DP8)94J?nVB~3UR92EBc8Y0BJ`iORkLa8aFyboH
z$(hrC@%8V>;aA3#GrX$OsvIDA%DZxA-(P&EJM-<8tL1~)XQQT>>1R4-2h-2;M;&96
zXbjJ>Npl!TBC6!GMasM}NeA=WmBQwO*=D-+#~`zs<~`6&N6kt(XL_A8om?q+&g}6^
zFq95NuFB<Gln^PV`}qLS%amd|kbHv#!6QkrXJ)NFlG2oE=u8Qp5(r2<vlEXXW$LGH
zWtdhg&(V?UN<&>zGR=|Z9v^$^qz~p~>iA%0w^A?{B~ma42M1xV)J~twz@*)MQQFv2
zL>D1Pn|6`a&Rj}aL7Z9IQx__;w3V*vFyK}?>!KuMI$C4ThIM9TD`nPEv%b=5eIkoZ
zxwt-os9hPm9yZ|0>2-X9S-%dOaHR$Ndqi8_uq)qM3Y_w-k$&t*x7LegBF{}Z%!k8>
zT#3%E6l>{X6ZeYJr#-k%lYX{y(=ZF$m0+!NKnd2mHL$#u?7b+Velj84m1A9!z#Qum
z1teL!_<-AJY_c$suU@i%oVii50QH7>@D7_c-7ZIxl7nsQl?;?-GOsU+26nXa^?jm}
zV`cR_0`@w_4vk8f01j}s!VPfj&`xliMY;=nz?p+Bc!EVqxCiMQI0`yF`il_8fC57B
zJU<F6!C`7IJO!W6hPU8|5Cka00aAW>Ru_C3&r&97%iHLvH6ehABS;A|0lB!&4Pe5V
zu`Lh^&qEbJ6(Gd>z0fQiM{yxuI1{_&wepKd50nXb0FFY}aNyV%0*51lQ6L?QkX*2>
zQ*uEiE*zc%p@A$y@<H0^g|kLJ6$ffwccRev1rP|~k~m@`3%kUbM=p4iMTzkc0wsSa
z@mcPzTMS50DvJ{Q5!#9){alDF>xYm|Nz9g@<cM^0Fe6<S|DZf~!NcSa<%q`CEfHhJ
z)-7;a#`dj5jG^KE@XLj0v;F`|v`}ySBHoT{4k+wV;5mzu3P+b{K-m@q&!Xh$+SV&Z
z*Q!qr&SVdY|1PES0uV))P!McK_JNCFJLlFZg`MW)MHw4-kweoefTKmZMnNDsd_5aX
z(jp}glpZ7(j#XhTIkddOV{&BX!^V3gC73Cbu0vZa@Fz$45`sgmb`DtPS!YVWAg&iB
z!JvjZ1$Tv0<=3_0SosCW@dCSYIHw8`Yf%z<t8d+M{C(?{!XWgmMal`l&9MjxzC{SH
zMG2O-txt}hUSB7`fNHGzb#G{5j`-d}9CJ9z3YBb80=Xor&#qQtqv=6`h~R=g^LRKU
zFq#vqfWT=-kP;cKj)A->tWE(U-sv@Q5#Em0n}j?#Hncat2yrKi4MLFx7#D=+*)Zi6
zr47Q)9iYVeSX~eWaYs=Jd?Dc5MQa!#@IXn8#%kFKa97I?e7jn7;@fG_iEpRsc8e6d
zNXUME1ExsGe-0mHp#uiR?;S$WvocP>3@$=0?YZ?zPMmD5!3fH5QI=#V%Q*;ZD1t;>
zl-PJ><0C-CNh`#iBiO(e9f95j$mm3o5NKmiVmR9Lw-NX;Cy0x+%yICu7KEfDe!O5N
z7iF>K6dbG*n?iV%ju(1iS~~o-g?s6VUm;}7BM31ZX?l437sjTetWe=_I$$pZ)wu|X
zaU?)bkT%dyM-Y4ggE}k^i!#toY|*Fq)i$V6w#X--#tW`=Q4)KUeuo6#I12WZqzxL?
zVG=3$RL{Ce1+XfDiuW!`g3s!fzJYpAFxMi;2?k#{Kw)zs8*pW%!-=9d{@s8zJ3d;b
z!Nw_3__ZKy7`G0Tk;1_(iWRToMP7KiBo*ea!*^e}ygQ|9xC@Pzb>TiJ;!J?i3L|)@
z41FoY<-Q5WRita1dq|K_i+4&*G^C0JrjDXWJG%RZoSZG1M*qv#e>&DaKi|Llp5oQU
zoBTfA&g=H~;rjKT|Kr!ceA(Ce{-6B6|MlllqsSxfXWV-6O@-7sj2rEIWWhq|C!8yA
z5UhVLOhvkeQAoNg?hCI_)q!V_ugS~vUQ>TJD-A1Z>Q+^FC^A;{6I7H?AcR$li{MnM
z;UW-Cg3X%<X)0|6Tq6WbqaDc*(A8CU(I8Wd#&`u11u-v}kj;GatbC=+tPHkG&YaAA
zQ*5>~r=ud1T#12n6VZ1YHw>x*FVDCvcWF91rLkE2aMwMNCdHGHnkhm)?z{P0bl#s@
zcnRl^>$GRuZzQNog4S1lQYmOkor*W{lVyak9T1*v65fN3sVaQA1SmwRf?i-vvZlBU
zWZ|3CfFq8h^+%?(H$dQ9Q+^`KdRwKh;`p~R&jiv{46>@Wu;fsok%KY>{U*$Cp2>#*
zSp^1{2Gk*R<{KUhWoDg-s6SD0HOHCB?MyhUkV!-q5x1p+*qt%7JarJ6c2v;VlA(-%
zVAUrE5G{8UP8~v?PH846{&uWatW?U>C<X-S?}*CztEj;DLCSACLdIbGUL7fQ{o9WD
z{-G%T)cq*g{7pAVu(2Bn*SFme%t<-_DPu%Q{%<;BgCMHn=eA|~w;d5c&3*JUoC}{j
z>o*;-0rT;+I%-SyZ#y>o*rq?j3H!Nmf76ls+tiVi>${GOwBj-FGvbFn4~E}#<oR)`
zBPsLSj`RFDW_~K3who@(bmY-<sUuIUZ{>77lJ{fmXIddX4z}NP<oS29qbT#cj?5Y4
zDfu&#=RVHO-*n_0Pjw_^e%o<eAE)ro%=i8{m;Zi89^ZJ+{@f1q{%uE?9(c<COt_Sf
zbN@FTc|CM?6y^D@qak39x5&>dW%zNg{QWQL`Wfm7%Czq~8jOIvq<*sc>vnDZrXz2+
zu8yQU-*z1H;}ZOtAhsXZ;%_=u!9H{p<@vTFi%sB?{h7+y$F=*Lj`)3;)qigHwSV8S
ze_Y}}h3;S1`frDtf7aEpYKVN>@!52QpCJgl&hQ(Krecvna6b$A-M{NZDCD8#yFS&C
z-*ki0($o!v``d0X(?GTPS(u8{b^d-gYD7)lK)Ao_R$z8ZZ~9r_YS5#8(}~K~M5if4
zw%>Qc(LjalXMpwWl;3tlm>rTPe}0M5+qWI(^`Y?n40wc374YwOq^5`g{@irO@m<F~
z^ElO#Fd%)Xn7`>rO?0RuD8s((*sl+T^=CMLK2_Mi-%*-wS4UF5U5-w`i`0jIZW$6#
zkbl#S86M7VO#eB*>E_I_ZoIA?kLpstf720Kx?So>z5QDSfg$Wv=6?z>sMP!4bmS|*
z)e-3r=lN|%mdn6n;b(?Yd^{h1(~+-?p^gMOwr@KUN;}^oKR1Wg^W9?L4YQnF=mr8^
zhrj7I^w9Y!)8Kc{9=(iW-PEcF_j9fn_xqh~a~W&i{}^to#{9qX!L8>}8FNwK^MVIQ
z?XuLeO!DP4tL4@S7#3K}vMA`K_zV){QUiEzi@d7igQCb=B*YL}W~ZDQU0C>VEQJLP
zB-K1yl(5jKEZR<~NsTJ47R^J|*OCwxOI2tq%C${emEQE_@E^2_wL#ubn{(p?DUBZw
zyX%y*BtcQyEN4kkiZh`sRIJUNXMAI<&DN$b?nXh?**9K=#cuYESET%6ZJcz8l`*iQ
zX+*KjiW-tM?H4QRJU65C%sPIjSP0vz$`i_Bs}hE?^N!8<8pdZ<K9os$?6%ifK9x_D
z<ys{cW!+xUTOStjv0G=u9Jm{2V;w4jhSqpQ&>Wi)e~dCr2a{DdGW-ClD=D{uYER<y
zIJN?n@;(e_>$I(;C43qxc`3I?tEv+8ja2Q-bf}=*Cfdn3+x#HOI4d(Y%FL>^XLx*`
zXDbLwA5awyrRPY6MdOFI%A?BwaX^m043rjT?bH1I=J#frjA?sq)C6O1er+DNRPL|M
z;}+8nY=Cg5WocF4&7I8!AWNrQmS?34ugbT=%U2~{=?UD7<6#*(c5COw60Q}}zzVK?
z>y<pJkOp{UTSdFDu4{!f+~7*vdM#n7SQnOXRb5s3kef1<)5F|c$1!}+&9%(%Q?s5g
zz1UUpm!57SRKDa54;0I6C&r~5`7xP(6HAc}_eCmCew-3relqy&Rp^+WeHzt|7ybW1
zs$Q|<`>bAV2oE#~IeeNd4#XpDm77<*LR5A}7nmx$wlg9gTGw{ISiw{oqKuu$64Mb`
zkszt+5UiIaD=6`!J>C6yJ$A*&UZ`!Ue9Sjxwc=l>jjl9H&o})MB>wpTmn*VqV2tP1
zZA82J#5h~I$}Uz*ufV3%_6dBOl#q#5c4HPx7bJLu;fyRsuDF~f)a}|jg%q?3XvkXW
zSM|snx>Yy>Yo*VvPq4Dh>XoCba0XzK1@f>$nsRh>mO?#hl`#n1y4HN_G@=cq2<1})
z7g>E;)~v5C$vkcUo;B|A_sHRGt@eK2yG?r^H)^H!A&9Is+xp}>DhuPnW!TQGSB~V|
zdL^S2(FA|EsV-`e*6&z}gUPs~UL#PiE1)h0WB1l2&Y3N^1=q_K-C~KieKOWCU3(SY
z7Qy|^W=Sfp1=Ce<;VP(Xyen<Q%iWc&w7!q6M}&R^#yDa}bMkKrS~-6m29w4u-+GK_
zD{>U&!L4tdmRuNdIULGulU3I7ifTsm3<q3fQ+3J+D2;E+iw^9DrVKe~#l(b<c;xho
zRzBR{I_{u3hhaq_v>^+X%QjIyyZpr{W7JM5ax+R}pZC@$_^-H@dC4WBplj5xKDGKV
z%M;)Kr5NF5!=d*Y^=(g;9g1M%=%%>%)Y{(!G=k-)ZUVeW+gXdxbM@49Fb5{d2i1&2
zR8?6cz&hsW;xA6jv+GuzBbpVr9pZf|h+;Y>sN_j_rK2o_BElo$y;T+(&`DN(39bN6
zzlxSYIQpU}ggs)5mMyxX*z;q$DgfHrPK8w<IQ~sRYkg-q>L&xj^H>Yt{lkF#a9TVS
zBb~Fcim5@=zhztve<*C^j}j^Hbg@V3KT-r(MkFcuvA8~tq>Oi4mj@m<_UQ6J?toRK
z&0Jqec}ZpUu%`qj*|R8|VIDd5=mkzE#-or(q+T5MC?paOCae6tOyRH!x<L-YqA*h=
z`MM}L<;Ro7SDe`<$&$*lxiQ|#vbix{W!l`SHZKYXmwFm&zr2+Fvg*TdbXN|yQg3pn
zAFL|#Qu2*e#@@K1#nI(5tim-PSwD7{D2!B;?5>=e)a~r9oEo_Q?#ijjJ-a9ng|xd{
z<>2A@W|e}6xC*Pt9b`Khqel*<O+^u+hnZKwn_Fta$o*v%-V>=<tIbvDjAhZ0FyIco
zbtJ$U!g@?EC5y3S(~CK0M-+Zy8keD)qNw0avAfpOk{h+0`M5jmt_3~eHj=i8yt!2X
z>!rjxyNLhuOZ3M9l4Tc#h(MGs-86XmvG&$WIfzl83+HFz%e^UR#3Cp=52$d9z-&Xv
zR;A|=In63R4?Y~L{5)9BtrGMSM9nHa4<SW|T{0`sT~D)|=V5>XYA?Z-*`*+Ryem<N
zjftf>YaK4gtFSWfxo5REj4drgb}1#pfnvluaxX<Ay(wtr(3t9voQp-MRNNd|SE>)t
zxmX7;DLFKqKHjpH9)@noHYqCkPCcSRABT^ahO#NTVPW;E!Q<7g%Ju~Ohh0qfbV?$g
zwRp~&vH$^NWt9a8&?=jCdjX`%$`A=eDw}%l_9qJ|<{T4l$|haF0WNi@IAaoGhEp$J
z<Z|1T$aTcNm0>cWppGD6(n#T01t|GPI4ft|RVbuklS&FQGf=rRli?9TP)4<e%OL7=
zI(^}Tk8<FB+Ss!HLurfJzBw?w!=nE0NlHjqWuPgBurmH(E43lb3oxcuIcUf!uu&QQ
z>v_ns%&)IsV#^MYGHy`HSaXc0FaWS^%J>Et1{(rHcfhl<j&)GN6AKB-90VJTN{^a2
zS#SGApooL6+gG4T#DWZ6#Xy`eMJqZo5?E#YB^;K+#s|K|XsU3Ylw?D}TR;b?j5kEM
z94yiP3Yd+U0e6W#F@qET4$&|3AKrH?TYn@eCg6qfl8+B7qoCme5TI^gi;ScI)0C(z
zR%vp0_ZdN$--IusmxMH0<;z(ba}N{VX+WjK$O_ygjR7WD(!gGck?Bc+H(+@CFM_ay
zP<p|=#J6{}muwf-OY%)c+5<8szFb%@9eh*7z2S^@p}#=81}0`O2@xS)=r191Uf3@<
zlfAHCAaqL5I~FNF?)ZcJuzU=LBe+bM21P(&t&6hGIhU$(;(%ot14lZ93Ft9UP~uBc
zPJx1Qm|z`ObZs0+PVMx(F{Q#Rg8tw;W>GGrDQf@3;i%dceo`U|vxq@sg;_KZh5YE*
zcBa}`S$-$Z)vh-V07y*ug^sFv*4YZXfOS22&bWLRfp||HVMrABlfiK^l;as_{gPyz
zEe9vl`H8iyq`(vF+a>nrnctoaMnCa_sVqU1Ml{(~J5naBZ~&i25!<k|E>a9fIJ7`g
zw?h4UaAE-UucMlyDYLL=#m6H^h<43n3M-I5<WejOK+n>~Ysx<i%(Er4-3wc7?P2Rq
zWHso1ol1E`5k46mMs&4bBb6igFz4MhJW7P(;U8Co{M6sXan>8=?ME~?X*?JTc<<?$
zVnZwTWC8CzdHZzLI_XHYFyih#4U1^{ih(D>Bn=RkcN_oC8><U{l(B@eA9p<W7G<Cv
zOU`Z9@%UR5>_y_Wyh&(fh#%GeHziuYl)Is%D2Z}WQX47&J`_V;6oMqCj5OjkbQF59
z0^~y-*29FzholWFNIsN!wI%@b8|Ow7@c0d(NOkD|X?^_0zeBE+tl3eoc2PLV)Yq*r
z`tGzTTVeFwj4&mzHeBb6Kmf|HDO(c?D15(`F-QkU*-H@EceV;;GggPza{{ec6D;+;
zwqp|lH8RtzF#C`ZXTt33h+!}!jdr{dtqpBQqz@Vm@T~W20`UX*iZyL~c(e@ARxiM>
z#QbQV?bpR#1fj)ivI)@{KB1tTd3arv1tB_Llm$mC<v@o6!zvpAn=hdHSQFqUTqlc?
zf8y!`{)flI=p7)^iZ#Ki1=LFRL2LcJ&Kmd^j481JbQ_By<j*TW1Pw(SJNy8v%`up|
zU=)Ur6#j0?bfQDUIB!kR%JK3t1~qor*{v0>@}n*T?HChn6djf4gOXB(g7qdS!oVqx
zcA*q!pOZcT0<Bmp5ala66@>DoPT&vFCKd&b?Lb}*0uxlGIwgnZP#+F%pbG~#@_1NT
zPLLQ_eS?C*Ir5-5I4r-sEd-=ql)|izCK>lPxihfkn!p%|d>tRgz5x`98M2Bx4YSH&
zCdPJr8ozAn1m8kW6RXmk1B~U_bHV1RKI9aWzc}8LoKj&9Ac>o)#Kwrn31J}vjyxEp
z#413Rn^ol#+B!|AIW3!llU#T!>;}0TmwLhcu}JJjaCaz}CL~sxB~9mk#*Y{<D38Q}
zM<)(?s1qUG9bx`}heiO2nJ$L0bO-sxh)!?J0S^Fs^Z>(0SL(tmVOFw3LcKRc;j7dF
zaP-ZDC5`u}8A~m|ekjk|0m%L&fkme}4Ybh*i{X#DU@`J-c_b;PhxqJBd&oV4Is|4_
zNg>V!tEvewWZ2BY23+DQqQE8owPb>sF136E8Y&GRNntN0^G)@_q+u;I)=c1v4^0~7
z>dmT*0++n1CUDVtH#!$tN-+Ta4--BpD_NKgw37Y0Ju{kQ5wOrePO;43KS0V;fU31~
zKkI&_Mb3n$?YW_;d>^dlVWvB{b3+4io5nVyM}&1lOu(fbB^gbQ*4}UR0;l?|UdgEr
zy-%nEi;~Yw6LL3D(aog$BXj6Yi5A=krpq1=6ifWqEa<|lR{?(G`C)`n?fKX+xq(>(
zMwA1EV$7s6;9(IIj1~`nQ{4w(cpKnZRk5ZBFeJ&}%t|<B(mVj9{YmK<9n9`;QZ$j)
z`-m+fkSo}nf0MV_8`XDty5FSLiho`FMYQtgl==wO_LGv<Ut<hKPt|oN;2|d<+TQSL
z`=A5{t{J2Ad*k)IQ}Ty%IU8?h5uln`Q^gsCZG#k)e5wfpmtZBIloP|78HCtVrx7VB
zOsa+$*rRzCh4YNZeYaafjuG3X5o6yW-)p0sP}bS!%qX#HU%!49XcM25u@4?_6QCR*
zIcJz`0N%t-aq;e9F043(V;Oi8wJIksz#{C6dh-6;Dd_?&@i^^Q5jw3zD8=mL(O48<
z6K?W)o?t|^O%fka6uE)W;<k>RawHN3j+ER_EkV{l3Eb;>;<e}2UWe6hflX*%1}Ok3
zu-RiXzX{y=UoT-%d{V$A6?uM!j=(%-h(=+;a{(H~PRRS`;9*5DiaOtjMNwxUu_)@C
zOf(9#5B|yXkstna{jlk0?BjT9%tB4>9U$3$%rzQLHeQ%kimWg#6d+OpkOBkBpE<QG
znCJayRWMID$7`O)!k^$ugg7t4b{BnR5ldY~xeoWGbwDEgeR27s=<3arl~-WY&%{*<
z-rSQ40|e_HQW#K2{T|X6z#7^=bZa--KXkJ%%8)M5Zm0h5VoaC1K*n@k{dp9$yX)!)
zUvSV?S?{|^86aPH(yDgr&4k>67Bw$2!AfBx8%`-~*i5v5NQHY-vXv~j9_erJ#<h!g
zCu)UXH?=oT`67yj%D6_nZV+<D7lNotZEe@3PMC5A$(Hupt|`46OAlbMqjc(q0M*jF
z8^Fs-H*XP5YDOz@qqW0k&C=BgOPdA{y&M`X9;Tw?G<eu#)J40v`YOtLarK4tz>HbF
zblOEV>0<s#gFjlYrIv`Z^`2^%>5;~1Sv}Ie5}_gWQWZ?S&U)Bk4rjdv^LOW?haILc
zA8JM_bP7loGu1hrRH#(L6yD`U$tlcy2g3u}CUq*ldfU9z1B)=PuX;MSIn^WOYU-#L
z+R5Zme`~B%k{^wgO7f$zqTr3p0gICINdra{`$n()i!L-7uouv>u#+4hu@m{*)Q$Y5
z>GMRZjm==QGF@_PZL5fm4&1kyQ!C3*q`stu^%N^lb<*HY_QKd0?WJH`rpJ^q>sK(7
zC_8>eGuH$;)z%oZ6V>9;14}Z}fQFN6piYN1rUXP?df3z;?&FRYrZ*rvDiP8U)@4~o
z<VaGQ{_q1+T{sH7rJ72rkD1m)3<AaPOvOwZ!T_wPdiqEMBu9ZKa-$;1#G0^#;<RUI
zR#T~T24X3fvJLoEn)Dz58^I)-Kh)HXqiN~}nS>i(*58$1bEPF0CbmU^wHp7OHfIRn
zIBBRR7tUV{)sc@AuN_&lnUGTkZzkl(DxNtxes7lZ=E%<|>v~J83C-_~Mw6yW<4#+u
z;A{Ls7wTM2W2){SC!&U~8z9n`L!o6wOu8J7NW{rbx=MV=ZNYC3cH*?XoE_<$W3rC5
z3xAONLq)e&^i<PHPoqjxp=@}#4^u`$bBYIxT04b9=eScibZ9$nnO1eC5f9a9cx))7
z5Y8uz?vy)<>qt9#uID-vIt}Se#%QRvw<wrKrpKBxI3hbIM)>GP1puuz8i^ZYl{zz)
z-;`*jeDsTMJbi{?N&-o3u(d2oax2};rkoV!>Vy*#ePBfE%w1TiICNC<Q{xA`o#;aZ
z5aV~CXLO!IM?*1P>rG!ubBz41O!ha`L~E$kW<r;Z6rR{QO5<NSJSITeNZ|?Rt=?Z9
z0@3wez!(+<Q=~6e@0p&ySn2eFG>Oxr!|2u-$k93~DZ<4KQcD*%_DrKUmMStWI9&=c
z>Y-TH)H^`RMU*m|9@9l2UK<Q?^6dYLytPCX9?*(CD3~|ZuTSr$p%`L=mokDJFuqA4
zQ(5;0OFM%l8cKszJVhbIXe;4xJXV+nc4?!4(2Lv}-SkpU-e-3Of2<@Pgq7q3p@aIV
zA7G5msUOG~okA#Mj1G4Qs|=YCshQVfDjwPz!*ooHgB?M!GtD0U5FL9=+Nmg<$jOP%
zOIVE|H+sVx9NQHF)D*KtTW3?qmZQ}Xn*>foyq1D58npWgR%*r&9oJ7XM28mb2Kzk1
zqK>2t#6>|A@#L!Ts+G87Du&F&or=+FhLFe#<7#-~GR~{vX>G3C22b>g7HhBuSOK#$
znWw_ekjzt&X$>)3dKM^VD~B#&plmB#OWM3bwj}LH?5P;LW=vgBAl@P+=N^qMj|+b!
z9A~srE@=gfc)(*dGgMTvenQDmKq1qBBI+<l27ud&OgtLu$=T2aaKc=r5XVRkI+H@+
zJcyfOC6AURtBgG=)G|_no=3r$tL+HA#A*U$!z#CWCH&;zwKD*pSYe`#2FjsR`uv*+
z)JP0M*eVClcvA`X8OEzY-Rndw=|m&NbLi=P!bUL))({3L<+?8lqj#~7Px@8Iy^|0E
zoKr&jPCz!9C^>B&f<`!8;yS%DeFuM(oG_U6Z1#<kG1ji1Mnt*Ip&#ney78rC#1t~)
z)1sBLHX7pK!#|S5=;?t!31OP~d$=|yw$mbH95tW9i;^m~YQ5N9;o?9eMG;e*nl8Y!
z?4q``GF0+CdGYW!1~XmU5Q{RRed{kGt${BzV`x*>G6;Cm8@qwUahT^~S3@h~`yu{@
zKqtF+>f6n@?Tb1L6JhM?8b5Z))irCTM|2H;MhlsHz<e^52Qr!iFS_;YW@-eVD~poD
z%fZ6;xN;mCDa?%E@GCKbqi14-06TAw7B-<JqRFCg<gf)_5~iDZ5tn$++=!H=K&#5!
zh>M(uu6Ny%6=p^-e!voR!Y&4t8EX>Tb!*uXNO5V`0ouW?N1QX|*Wlv@msRB7yqjBY
zj%DpDyH9-;=e=@#j7CbP0Ub)qv0E^wKvJ)KBIftJr-4@H_)tN%>tQYveI=Y|<uX}d
z6JS+d;?`QVY-N&=)9=U}ol2@QfCyCLRW6g=G{PE+3M>lZc>WI5D{|r&WuToYXOlx4
z+ENKRobTqFF&iPt@e8!t87gKOOUSKMo7EsUdg1S-ifu?O=ehDy`i<R>_zus+qa{VI
zjXkQ0Y&3B`IzW*4Z79&k3>==FuS~#M!zC1V=Hz7RWYc(Xu0BoUVe({0D-$RA#(7hY
zXmYT4%|2c0g|k;k<90E5(lJ(8O&>i*3^nB|<I-qIRaT}=W=hha&67LQI){FUnVwk4
z`9uqgh-7PIkG_=FQwgRvk(O9lsD>gym8r^9pGC=^fp10$uQri7S>k|Xph}#LWT2R~
z#39lAGWj+xz_V@1xi)dcR|c;E#7KF+ru=BrjF2DA>|sMqCuA7s-~c{xHcTiE{YX^C
zd;l|{WadT557B^jEK-ixwMKx9P$D&wmqMq)oE^VB&<gffy0*b~94Xz--^kSKp@r@E
z4z+!o#K<}sth7j(<UPfSz<M|(4S;$$OB$FCt$=((PINn&VP!~(j*NJ;uS}39^MH<Y
z@+LS8$W2ta^N(Vgo~>8HCrJC4En4Ix(n1#r*wneho0<4;LJp{2gbv^WSRw~BLK`ef
z;ubWm!71DV_5#XJc(n~V(@oyfMF}(rsTK1SUIG^_5qjiSG~`e>c?1nc^`ps`XM<o3
z)FsA)S&yw(&RRO>AXvkM{mBNv8fbf@a@^#8dQ;-jTVL@H`0#;1wkGG;{+Vm+U!l9I
zzH(Kc#Kgc(6yCkGkC8Y*cB{t?OpKe0F#;7xPMX8u189obT$Gl7Q+<NjiYZ+gf=zA_
z8xZ-Xuv#Pywq|G~a*Ay|MjAHs=ZT!sa!h%+DJ0ntaoJ?>e^ZvhCH@6;2nA6iK`~HQ
z$SOd~hV7l{icN*x4e^^zR&*vXHZ1AP^KV&_staLd*ah$rQOn+th29ifZy5mE+N@#W
zs0;(OMM1u00;|8zL0#Jya!|G6g9E#_Zbai@H=^<ANizt>qZ?+#VSBXpY`qec>D+oH
zD$}|3N>C=AEAYd#t{OU)bwpdYty2g#t+fVEO_OPMy{KcvFr6-)1dr@RLa#(A?0xH$
z1LifeC^=x-sTL(KjqY2w9I|iSV#L1n$`RA&&-xcfL+TPUL20Z`N)C9c6N-xTsXhtO
zG<9VF%B^+1Lc(g%y6zeHo?4gEF@Sv6Rha~~k433oIRm{p;IV21&$Rf7M+YMz>y!^i
zW6N?w;1o_LSCcu@05;HMyrj+MXl`4tLfy}H0+aD4Vm4lzKW`mxwQq<<*Cm=J>^1dD
zmkzi{FgocQ1HoBM>5(=FN9Po=JkOe|gu@^j-H@=rK^tDHlRur1bX@m>q~p)#6sMMu
zm~@x)tN~EET6lueU0bi5wDgN{rXw$V_(QNctvZ6Nn{(Cu0VtnVK23hjweFwAFAkE{
zm$%9)0eUoOel~a^8;ov-LYZx}tw+Mw$ixP8>?V7f!E@P$-UzT@Hks2FCAZ?xQxK)3
zn=;I43vEMsAmYZGGSw}eqU(qBCO}ehQ|$tpS({3?8cMe;XF5a+D-ej5T_Z|%&;V;d
zL0lBqh(aue^g1AD1U9~DL~WpA&PVgs_!3%FFF<&5+caiE7+^RM^8iW$hqmHIhD`9Y
zE65`Lg~CBo4srvAN1NJikkK}^-8KqYk}3jT0>=l1905|`)Yd|2junzZh7@J6z1~r6
zYIk7|wW&jOqYRC2MEln05@QxhAaVrSlpSZIJQ{8+>3qb*qVVj3Gk_sMpOj)v90!E7
zD1z<GS}T9q#;lg8y~UXjg{z4(+3p(~!jjumt(yt)D-Nrv*OHaXw}~fZY|EWn@S5AC
zLZGgz#+MOl<cuN#x4%Z+`eUQiUi`J<PEjtj*8Iy@<Eg<%#jcZ-VB>vjP^8H6=BckO
z%Gle_siWDUEeh>ur%-;<e7XWb+xUe5k7&A=R(xsAC)+jSkkT}<RBM}HiuyxC8cQfV
zzD=2wnsRI^0aB52tl-?@LR^K<&=Qd%+ZnE}MJYB!EN>IW7D-KZ6nM-c1ex*_t*6A~
zf%SBggGVk3ir+565gFYjOQe)|#?q~5>k`kFB?GrDH?q#4NzB)O>*v11BA7SA!L`BH
ze_S!+wd)o)x{%xG?d#{h@783FMXG(bM!P6=0<DkqbKiJ(jM29f=gtw0?Z|mzL}R<e
z&XHvw>k_jV(cCUE%Mo4MEfy@gwmU3YbpLXP_4D5Du;hmTVB<E7EP}ehl0lEIur<&w
ztU=zoD;J^euoYw3t#%x%pPt*Lzy7t#cQ*cTaKfxqn`k|y#RMCyb|9*2TkSy>L+#XA
z;;Xd>p~ZBo%daY-o}-kbZgurlE!2zJQSiWqo=whDsAKDuQy$eT<l&=ESx$KpH+QLo
zouRW*8N0FpsaAG`vqJCec75umN7NsYnu!_Sn{pcKt_aakf=3p?tzI+hy*^vFoaCct
z396bh3X{I#-s+K&y8O}G{>lguZ}rIdr5GC?NmU7$52@ao)Y?#1RZh5S1NN;?jJMSj
z6V<s@y7=J3uj(7~ahM52FTEbSLiG5;tTM`YmL6N}WjtQ9K=Y#qZWeGJe5mG#=hi1j
zyuB<shJ0<^lE+eihDWMa<NG{>rqyzzzFcqho<tFc_EfLrZ@nq~N0z_ls^!U+CA4WP
zh|%_Q>l1_R=hiEj*=w!S;(?Ohw5$X_6#&LcJBs!q)>IcP$D#y(5zKYGWTEMb-Lec<
z%`)ZcmP72@w}PK2cOE}9Ga(RNP{O;@y43c1>V}Znu6U|2S*^50S+inLbL)_Unp=ku
z!hWHZJiFB6%9Eydd9nuTa(A|3JynRFp#)uVRbj>p#zU}Bep@B)4e8X2QeBcYB?Y*i
z{FJ+Ipuo1vc`;B@dowKH?%C`LxL8~$C=6^^r0NzU^0svg-Ux1eSzdEQ3I_>e?BWe!
z+YQmyT|rTXhg|m(gOvQ0zYDDv2I%g)**ezA^?03Uqy@vzfb-hr{hqm5x{vArPUu*e
zID36=y^;|+7}6?#WUjNiB`0tdz_{Pb;(%8rQ>v2^qUv{sGKL=^v$9Y674pl^)+Lvq
z92$lXD<Cyo8tdC*b7{mbQGAgBDYg$eHRAYIBoPXh9YLZ`1IP6!p9aom0kIj1XY^4%
zjac=gkMe0`c-+dR&sOkzlurZ4?kJ~58Z~;FHc@Cc6Z%g&z(VMUWFrB7vk<LZV(p`(
z=tN8%!317g`C6(8z!D}TK~i!o(g^2>)+{Gqtn;|g%5muQ2y}~H#ds0Gvnce~06Do2
z-Xe2Gqg;(STU{W)GVDVN!%QtEz#a||@-yZ6O3kL1fdt_}eU_Z0uCpjtgbfl~aiLR?
zBhce#NeT|LS(1XoY{J!>uo>hCj;yIu1c^C)Hq9_J;mIQe9%TS@93aKQRMgab1OxI)
zul17@PVT{1s7g-wn))mu!KpKMr+J*hQ%`sVF7?2V1XN~c;?GOI`L0qp^xv~+=Aszz
zRbC1R=u<EL3>Y{Prv*QOa_=hL!^nd^<-9<6La%tN3+e5>0<tpLsZU)qh>hsP{ABn<
zK-1u7I-zSAgAuH~7-bugPwUH<WCC#-{i<k~czO4W(IH_@=~qR=U<+Ro0+dD|j?YVQ
zuKm)ZJ&P_JLE@*Ob}%X>nW88uL_YP3l0t=vevO)9C=r)TXUP0p6#VRkU%Aj40gm($
za&rW!Vs7#m^fW;5P8alU1ow<a_@*QT&mI{Nk?hz7`O8SCMd7C)=(iq)7hX|O0Vcv$
z@IbnGA>eNbVwIFw(_3#sgh=(9K@SIGr25SqB}1{Bels(GAyQqHi5Vi*Z(ah2v1-^Y
zB>}~R`mGI)x<&o2sJVuDag$e_#EP2h3t9|+eeH!74X9rPCVMIFswa{)1LBeoa!6y0
z{oZ5bk_{Cj=U_uUCID)^NDS8-#9zziHH6TXgdAN3$iamfSa0Cc!07avym7&loetCM
z6*I-@^$MDTt*{G(JOaJe6ds9DhI$2-T{N%w_ca)784~muTCwPlbj}-Qn@2G;H@3uM
z8vBhqT0rcEsV)kqjFbP-L2<)6@yI=L1OJ+EfJw^f$olZG5};friOSc@0vJ<WZA|j9
zz&31*n9UgvMbPG)sZKnQ^9rwe5FOOZ5{Sq#0xu>d`649(6YFIOe0YF9_eP5C@kkU9
zZMEPo!A(S4Eed-f*D;VZMOxoq6n_5!MHzR9hh7xMY6H7`k#7Cbj6cd)Z4{O~k+;2q
zsiJkUd1d>_7{rz+oqiJchy@*7#yG}OxuTC62JJG&MGe$7Sy!117MyU|=NL=1D4d~V
z&eYG3h+>Z!<hKWA_b^yK(OVw|%E#c9B^JOQZi08Ls;WwPfkkmqIMB4U29hk|=2@Hd
z$)jAIPURn<&-Uq@xLc(l<kqWiM|wes#`f{NnD&pSuHlM>YG<~{v#kBKC`^Tj1!IjB
zm7g``ydn@QAb4Z%MljY$ijrXRP3D3{S(GQnrra`vcom98jKT><aiG$R7obK)XC<ug
zLrQ*Ico6uc7r29=@{ku$0}w>Ka2OJE!V4|IJV22-$J|J6qvq)NkYEe|zTkyXfFJNE
z%G1)i=>;ROV7t5k0)RK*f+K6d81u^XM_`sKtsmyjV^PSa3vzJjm#_Ttr60b*H)Y@4
z_>u}zEK+`|(r-}ewUXr<r9ml~jneQaceYU)9(Btb#GCSGT8fibDme<y11kIgDSlh!
zpjdv&D@z-&m0nre4TWv<69-5m2+T3dBhV`k8`;BNdDuu7c9yg{6d+X<Y*&C3@zh@#
zAQe9=2?mI~3ple8Y2KSsZ5j&rW;!)&nckFfhIB)(>}ljAdM5fEAcYV#WkiN<>TOSm
zOa?1a8Yz;C0w)#oD7{riB&$R#4K1@Vy;7rL<Map@i;T{kp)fZ(_P!#>GAVSm2U@uv
zx;PL(<xK%ajG$WJ{n#8CK;?~QpT>f}iacYTItN#emoi~p!Dv+)TgjO)cY0+$0|L!6
z^ErPA`@bm*spA5Yc{zisTmfti7}73l^TDVpS4>+~+!h8z)^_$Srx{nqmeUN#6ju>E
zhEe&J*_;FOEwMTGwpU^^QnI}Z(*c-vzNI$fp6JFTdmIdkjcdphT@=b_riLyGGu`u^
zS`;RR=ljMxTe0B;AKkni(PXZ9<DdUf4*TMzEa5ChS+&X=00zBRiX2Rzt_VC<zFZVc
zFzi*U&G|W43CCx~Uxh$a?z2N66t>r3{&bnx8!|ebaePMxTs<n*{X)EzS3)#g*j^dY
z@D+P6^n?ovpQ8U79I@Va_=H@y9X%lzd&5tNRjaEI-bP2nV1t{`D``3-uUsL73-2LU
zno&zf8x#<s^}vVb0%LE30-}RsP(Y}49&MPqePUQRvEbWi>P3u^hE9Q~FnSax;eCNX
zN|jV+HCyk>K^&e1PV(RSbId;@PLCjA1S3nNp!a|bvX#FsD4a2)g^$B_6-8Ijf2s%n
zB*j&CH!Pee<?<2&isyz0-U)gouW$5FW-WXU&cMnB2g4$8IUbHp8UcdFy|T*@(9YU4
zFJZ!XFO-{;94nX`=#b7>hp6Gax~bMdgH2vl?AvTvHiwu&O+E0R_4mTy$rc9I_4gbY
zfY^eBf%z)vlmE(<uY~sL_yAAFIkFy5@+%F{N05lTGt`5~J2P4ZV#IF<#3)49O)H6d
zIxg=Jp^;WOBQozoHyx&^jp&J=dc0J5+$+-_=1UezdI`$OEB78%Az5GPNYXk0ST=)|
z(p|NIvzEFm?zI7X+be<pLfMNT<?;l6x4Seh0DODp_+M%1ih5CK$9bDa`~gxN)2?G0
z7Slz+aJzcpytukL5e6ay%RGSs5L6bGtx~XH9`%9_Km}TN9_yL2cLW9eMj<WM%z6c2
z8G8-1Q(lBPa9!B~BFn|4rz&`H<%Oejapk2Q!nWx?(28I4f-JbW?0O_!Ty~+wU0C%E
zEH0z`f|Q>|RckMx1Jurr`eV^H$ckQCcP@Lu^W0o_TKyZ!ox5U}Ta;e+!b?CFr_<ed
zB+_0mCKT73i>?dl=AsK?;l`TlhRQt7BS^WZH`iSt3^&(Zx7f`+FWU*K^&KuxX9Nu9
z=)?zZbG;!^4Z>O2harL}9Cv`^7!bh%Z*W{`_pnBKR3cxk>>*YAM&%fH7HNnu!t6qU
zc({dmZNdWQE@&cH7Y{EaiO0ZX-L0@CI=r{5{a`r6(d03GX;(kEqFtBp!^4?(F!J`j
zKq{UAh9>1mQpa#0IB73reZN-*4q|*@-!s85{`Wf%`E25Sr`qrhnU^dgn3QCKRDkDB
zNmDV722-LdNWP&CjSE!cdBB&AkX%t5Vn5Gp#^gE@Ek7v}!_D<rL4qfSTa-`+UFaPh
z_Q8#SC!F6v*KOpHuykP^^g^~rs-?Rsmz*6!RTLLLbEP}1oS+;ak)e4)bQ%@K;zi+z
zioy{QA|JJrit8PK8e(!sw&e$b>msgiix5GDzjFN{`#_-Kt(b0;d$35C*u`!o5~P$&
z;Op(A60(!H=s>_WY=ez}0TL0r)|0$ywV+^VtMx3(*d)I<mz)RT=*`7W;%d7lMGBA9
z8!bqAv?jM^4r=Nc$lco8taBjw*seMUMA?pk10<dUVA`#7peQ^z0i?~77KEcWowO9p
zRS{@Aw>l~aZIpiM9K{|WNLHPR9q)CXnmym<dy|JMHYg&>aPTH7degZI>FG_!Dk)w3
z1TuXWJ7F5>s6AD8L&w{-?vI|>T{~fjoj{510OrbTspC0W*H)+PL|0pnj5JqpQ13d6
z>A&fn=P`>u^h*~%mZV?0__+i(FMeD&z4JJpT7g?PfBx>Hdmk+KQ=dk7P}CT}$5EKz
ztZ(ON-1O}njGI0Ud2qx6>)YP`=G#p=2Tl*~n@-Z5>#9(R?p+!PHodzv5G<^_G!U$#
zV_{Q`iUJcux+50Ohjd3QoDb@bSUKk{JGgaxN_8Y>rc_6==8_(WRf!Ei<+5`>yH}YC
zn8~E0c3e@V$aaKem#*70!|N!07)3t5N@r#vkW{KsC!}<477~G8et<;vUj<31{bSC<
ze$oG_?C0M%p6x0?F`7DHe#_k9Dm6iChaM_@bUhg0X79uGV!-4E7oL`^KCtk7G_eW{
z%lRHJMR&Op8WG*)3O`)YTe<M4`7pTbT{F^6s1gszt9FJpvf53(Cs`4v-kcrLneRpH
zXy%)h>jT@U3s8SNdd70}5BfyvWD?jZ#xc3&i9pil|Igan^jx>&+Cu&LD|YkT#wil#
z!%i0okf4EpLkrR2ii?EmG`I)>|DF|lj4@XgXFt2@t*b3nJ@LCT^D#3s9B0_(7q2vV
zyQxmSfrsga=2WgKgf*CxrCM4fdoZg}O7K`CNYLU+3fG*xQUQr8tq&+JSQ6OXp(@-L
z_GBF_m`%v;>MixJ>dC4KO`X-r7k1~dm#jVblq-hEoa8x?v2`U_2z#p%EIy;ciO3){
z5Q1dRrmi_FW$870v2TIC$vQRmYxrX4j;gVD2S((h-oa~iibi~CS~9ZL)Pa2Vn%%C1
z#yosj-d_tKJ}n0X4C%MtUmGAER2TFx5|Yc6W<*Suo9fhT`Ct`xhNkgAseZ3qP+k%9
zW#~-qR~c6MNE*ro^oX5aw%1H02lFj=!HmBy>n(_1Uk2XcTXitkzEK7HffM)N%$`mY
zx$-F`FYL8R52t-x$&ws5Z9}#P^1;&jz4#+m!#Crvg&dP`R0(d6!)YVG{~o+Qp^0V$
z&Ewkm1J@_YJ;Vt9Qx5+Fv9;#V?jE#`D{oNHIzCY<<Mo>WC}<nk9v$Po=qO$os$jf9
z`}k0^gKJ;=F9=p22}-rFl!%0elcCMEoG9~l2j|1!^@(;<q;9y9n(E-%(9Q{_)EshH
z%nX^U?yK;ogR4V3W7O*Cnp>_8@+qD{Ys;H?l*X3IJsP+>X&NJ}XhUiHiuG0ZcAVdX
z`B$30)3Stxd~jx0Jc}#YxI+wPg>AY-tgop2H|Lvw^k55l(~r^=L(i9I9Ds^xcRGd}
zP3)G)GcuKY6lAFRCLcWrRq@`Gj`H)Ibj%rW^PHxQ=S*GqvL%>r@*GxUT)NrK5-x3(
zQSK~V^`e=jn_kXbxz-{BJS24iFa7&qvB*0q^YZ3{wci}xw#lXGig2r)B`g&=K@H@$
zd2iN}EOzRy9Rmc)ys1MEQ0C1YO7a(P{wKL#I7dGvT3-Z$TduBA<(u#py^@-l*|3#}
zsPIgL>wM`96Xb?!*F<)x&StXbZw^JV*wV0UN~k@=#i*&AG}PFeJ)3Kx{(XrO@>C}4
znxn4KEwMy6I_wG7)U~2}5%ixax)(30rs!S=<0ILNXr7EUFkSdq*d1n9TKHBcM+Gjr
zf?{3K5SAP^&~rEkyoFbKjLb6*Dp0-o*_$%VSMKtn6DdbFsA5+FHJ)6tsen(H>IKdc
z`$rzun+v`wV2B+_rKTcHO_8vco?+rf<=lyZwe-*d){-1W=S#|}1vitFMOU*a1{SVQ
z_`}&N<2&+_PUWqe$WAzwhKN0!O6+vGTI}7QHR#zz4w#6RHJNpbe65MJVVGV{3?%ic
z2ti5LA~lbLgBseq28fkH#K{#>Z|JaG=bm289Ptr3;3GaFSH%&x5K9Yde)gtSftcIO
zc3+a5xkiO|(n6@<ZJ*Dp*6Bg1HqypYQ9*$UWNdNq|G7SIkUTMM*aATNd>|q>6w`*i
zgx}tuYrmQCMJXi#>q=mnyrP_KaZ@J@kF5+Qvp8Z6w>a2MZyDR6VV%xK<!~Z@#FWcA
zIZ?B5zn(}Ak*wQANuAK;4nIi~Q^Y{RQSOBpCDv5a-di~aiyF*V;-UugwZOR1c=0-E
zqim*`;B6lwAx>mmn62~em9E<AkT}5rt1)NFbRx>1OIs`A^D9VahND*xRgwr<k_O3;
zq};AV#h$P#7G|da?y{tOL*Kr7!JkvlFSa-e>-l1r<8%St1cK!AAI;q$NnSHG>MKsY
z2ybeTB`>rBO(XRyNs{w_$OGU(?iq(CW|As~!lIHvk@_Ac1%4rinjgs#&j=n?C!$&n
z#QiAl!z~$$>Bw+Upc6w4@gXxIb=w*>xCkStiqYyY6g-x8ilLw-4@m^fPhUSOe-N5y
zX<DI*ekG%PIWU${KBBQvns5lIbqOodU}W4fHD%A1dJk{Jim&@XL{AlV9}e6>8`(to
z{`6)+@3GoqFe1b(@757Ry<c*s!E7)3(x6nm(~6pM^)L+qKGUHU1rzh@*#m3w>-=*q
z<azjG$6WqGTqy8)rb`j87e+KSjHn!NHoD3cBW}oh2^T`c1q>Ax!;dB|<Vl5w5D#{E
z{E32c=z3QeoIm_sVW(WH-UWt$5bm^IOa^>#YV#BE$m9n$8N0!;%fr4pd`a;`2)5y*
z8%#LaUJ1s8JkeLemJCjI+@PPyFbqy|`efJzm;SNno2LZ;>+6*a_6XafQ+=2V&UsQE
z5P9%QYMm{*=h3ZvE|7zVg0#;v(54YekE!X<egcQwu@7euZc#g=5moeq9bb>7tK<9J
za&?Ta=jKA%ya=0&QLuSOG{J)#igz^`kYH<jK<)sV3-dwvUKD$OA}r?E?+dK&WiJ$}
zcT+FH>4+%=X4HVK?|;#=R{ABw1Z<pu7$jg1=^ZP+{ATA0^xm`}Uf)`5d363)NV6*`
zcf~D4fwS@0LKM3C%M*B399B3BS2@?`Zshz=1dV;2j<4iSl>CyfAX{2M6Z-MXx%rtD
z)An_Mp7i5iGyzN`lamkitX{ot*0b1tPx)e3U+A^3n02$l_LejEgoiV{y&<VqHg7bq
z$d~REN>Jk=hR8o(7()O2rB54?i^q}{w*h5q{)ta1*L0nz@z%%Ec2H52pA=y^Bi8a*
z#0!LD9!vUKF0Qe(Vi3`JEYog}70F4Ox+KaH+|#vE5L<en2NSO8O7k~i%^!>2N3(pg
z$I><d^ZsB~mAUbKGZey;q6)E~(=pxe6;olB`@KjblkWH83rxA+>y~{Ya5tknOvLtn
z<3CK~*?5CQOt2^sNaBHLeZ`uX^vTzq<fKo&E)yqx@)_3RvosuyPt^kU>Vj^9jLGmB
zDOg|eHRcA7=?%g$Yoi?EI!;9N8}nTmj5lI>*$jTAyQR4qZ^Tfl&>sD(3S*7DH7c}6
z-q=lg^6O$|ZpIlAj%;{%=9S8%Z@>7ylNmvWn8R0e<G}ErD-2A0Rk))c@%8hH0uwS9
zc&nH%RfBH-O2IX8*D^?7p7i|J#maQhD26UguBZag#9ON(zxY=z#-L%P4lSIw9+Oc6
z##XJ4?(DBx6^3TNl`0C&64p9&@3FpWdBxaKC5Gr>OI8tj@OuUspf|w;NA?Z#b0xVz
z$M~vMb2Z*d)i;wG&CmqODR(7ap@~$f`X<Ho#ww7BeO8i|hh!B<&JmlXBsFicX)v4t
zQ}|s$g=13B7(MEI)v4%FGFUi+N5xl572HaEwCOl<np9ONe8XgsC?0SIp+Yg|Qf^7l
zbOw;xUv;X3<WWrIkr{HUnvN5QEj>8L_lDM*cd~7&0(3Xyb<o7!S_bgKjMs_9-ZKoe
z+&2=~l~i=D@l`8dzO1&6ecB2bABeIoGR`NGlng~jpN#hK+G>4gi8VG5Qt{U(f;<cb
zX}^*jLPMeA*y%jt8zJ3}@Ug;0bUv@5xy4t73Rx#Zlp_e$Yie~c4n}{!d1#ScpZr$H
zIxZ++g97eP#HDzK(oavM=^1@#aa2ghzP@VZD^gzWl$?sphg-W@K`xMcJWHzr^Kq>p
zc;jmx1uuN`_su(^6TWXAXF^#&87QO60^*3%*xwf)*be*q<`GS!OAW!*>gcSJV;0CD
zlg{YveT@v;c=TErw(;n#Fh(O^C1W%O{njTE7>yQRl`3$f_IyBK(|HtkyhCX+o)l$w
zq;?=Z(B*&fRh}&I6+lOSO^D1fbVYmz2pIC(5cOF0t-@l;c;QvjG_jR;dj~wXcY9|e
z+TMZLxUzXllwmVX%Mj=GW*RVTR;|ASR;*DzHxC=5^{-i|fTiyoRQa8NdS$w-K{S=i
zX0DsR3G;&~vCKp^rz>gdZb_t7)RlV%WnIQGR^(TICsUH4{@p3Dv%lu^{&gk1h58cJ
zghs2Fv(>w32>z;X`b&bz3>f4yo^8!0(pbGQZ@(p&99U}<I+udS6kOwqZbacj=92_6
zLm=UnDYD0x<Y6)AMVjN61TzKBf*lzlz9isHPS~65G|f~A;(X1`DxU;(Zhgf%o&mM(
z4Tubp93o1RizfVQ&?VU{-I)wgJ6_RzyOv8R#@CB12?6SV`0c-Y`fvBY|M<WC*1>&S
zFl`M`q~LD<AOF|i{=;*J-98Wd>;L~$|Ih#B`IJBZ{c}|Oq4nFkAx`Y`y#Cw2{Oj|d
z{fB>U|J*)p{mXxN{-=NXmw(r%|I>f`zy8;M_doy3fBpOy|MJ`gv?A>D%-zp!_u-!-
z%ijLmfB#?o_J4fp-G|rz{`-G@7*}>B)8St;2GpIZg%CJ*Xn$jGubbTbski_1-~KQE
z=fC@x|Gjz{c+_xPpY}grLi3m(tok>*iS)+oC3C(1LN7=8vi{J^|M9>1FV)L=r*hsY
z9LM_p{Ne30tNq{XBtyZnmjm8q-@W|*R{}>um7ul%TnXy)$^b?GDs_4x?$6&bA9bVh
z;~M)f|J_>u^nd;N&%fQ7(K0(+W_{l`_xWSZ-aoqBzcn?y`{F3?ebc+_e(vzU`Mgqi
z7g9}p9#~%|1-~<ItOnN7?MHP(G^W32y?;(Pv+cVqF9+@4UQGY|!9cC1zkhsJYy28r
z-@m^mP-Vj1N0lh}gK8Cd>#Y?~_I|9iOJ99!Z7Q%oR>Pj7>8IfDoBj_Z`?#dUYnng)
zJJbK`lTY^8J37(HejFV%^tYN+_MfT^go#%*3jUxP*nV%d=wD0ucdPA*?-21N=ij~C
zYxQT8#NS!{?H^hF1J_gU*yIlL<Jc;W#aoMUEq<(otk`d@KK_QKOodR@UJdcbYS8@j
z0x0<VpzI^>-Xl^uY5(>Y@LT)!7ho_=zoXmZZ&=C(x7W9t{9u2q1`^_1O{~Npt0f2L
ztprNWPgOcdftr2_{@yR(gTFV1WkzWGz3Kl)z5qm*)ZjWVRDT>@B}n|Lwfo<&ly9>7
zzgWr?{6RIu$9bzMV9t-#z-W43fhbPD^ab?G2>Z7;q2K-i3^?;ISMr&E!$O8(MwQ(E
zhGm>NkW^*2KL+~oS2#cZhP}}?))Tg!{Vu1!d(~e;(C;kze@N*$f4O?k->`PS^gs&w
zPa733QQvA3kZ<vK%*egmo9pJ(Sob3B_Y{#|nvyhSz1>9d$FZHV<-V09__12=Wzl)-
zy^^0RB52iDMM-|H2v@+bijw@oYv|YiaesD$^YeT7g}1;!>t8*U<mVy6M)g%ulAkMH
z#@lx_lz*&bNaXTXdnG?tgkQl|MM-|)O=POm^M_x=uOXwsHTbKqlKec#{g+3?fBo&1
z{9Li<QeX8b__-P)!G6_~<j0C-zkjQ-{0na)ZRs)AnLoXWUs4e>W657Ewpa4=@Zf9v
zRZ)_kD}rC}RZ)_kD}pokRZ)_kE1vkvH!s1jyo*coEM?`#ckye`iIAjUKq$$NL%e6&
z`4^k;EBU!17<}K*OUcg_ku2e>q9i|8jPYG5OTX|Q@|xq1zlmQ`8sUfY)k{f!9NMbH
z*>61wey)bQ`mcJD{9F-vN4_db@^eKboA|0I$*-tRH&ERE!*Al(bf<+N^k03I<PVni
zU+STMsbl{6x4(Yy?{0MYDtdpnkF=>t@b{@VpP4FiSI=x(zhiKjzp|CHqocS^cPr1E
z4N3lJgqBx`U-b-kia%GYfHz;&7$Ez{YOU_q-fE2(Za-I}g%fX~eOoyH{+G}$0sVJ0
zoAD34ga+o+*YNiF8Bb9WxxBtAuJv_6_4^eOa^S0?f)M;%5ixDQDk{qD&lM3Q`+XM*
zyZwtV<GRTG&dacW<YlyuL$*fP`cKDfR6G$JVAZ4G532e6%jPKfgK8kjzSVaB$xzK|
z2qna~a1>hTmtMlT?9t!51o`!Ma1ays9h{Qg|2Q~gSbVD~<>HUk;PClYQwq_as>LZb
zuc}e-2i0T-t~U_BVg>$;tCd<A|B0=@>?N4@@8Cqm|8a0@d{xQRVn6=;M$!1HFwPIx
zpQvK{t3tY1|M+tliZRz;cH+N(rY|q+KcTe|J@mtiF${`=p9kh}eR`|O7wX4qh!*lz
z^ZvKAw&Jf^Tk*HF268m#pXFbC1Aarf{mvWs2X=fPyiVib#*f!&tk#`_L$&T-qx;=z
zaQ1ww$@}xCY8yc|RgHo_s0Iol-vG<M_y+dn_599m^A9LMdyl^w-2U+*j@97y^;TQ$
zYjnR`?XOkd{Wod68wnrYYRUldV>RSf(Hm&ztFgcT4O|cV-}wgqp>x2OWrmU;4@_Wq
zeN}uVzi=wN^xQh2_x_*QYSj^%<EyJ*qCc?Z{>9Xw_$!9$>wL3uYxScg=vOwfoA{+J
z*uJd568)it^sg4cm*`gv!Jh-j`I|=iOUtzt^YnYYzM`KEd+_V}uKJ38#khC<kow;;
z()}xTrPgpq`WlvA(I40{_Fvc>{`I$4@+-!(8=~xQ8fW~H{j7M#-@ScBe_#rWzg`Sq
zqF=hzn}1s4k9VP8QTJ#-`tIy2`UC6vUn9w1ZQ6hS?f>`mzh&Gx=6}AUzxVJp*0}!Y
z^|JqZ*#GYx_1880{?iGIK0dW?Y&3z=Km9+No}Xx`_qO~0{#{%Nu&)zV?qUdsod^uv
zkS98lU53}`A?mkq7DrI|aN1MKSw01I>_Q&QaQXwmxjvlUiqVsP9!}R0+$01X+mRA8
zoL*~@eo!Gl_b`k}PHf1K8BR|V<lGFWQ$Y-Li%}FJdEVjFRf?PZqy*h6r=@_?dz4G+
zEuvfHp%f0&SrSPDiC3R2@0=_8SVvhw!|AsWD+_3DVQR}y3DNFv5l*-`kpy$R#=^wX
z!=d6igp+d;8v~#Pq++@~DXG&ZQhA1w&mzi1I3s+7*W~js4rX|i_t;aCntT{6E7xZ@
zonH{|BAgzVNd6hlm~|2C7m4%{m|J>HMC9bsTP6Z?3l}+r;=g6Yd5^%zvVnt9k;PMC
zJVJSUL7ESx_O0M?Pf2oSPQ&!mfez8)!s&8x8amP5DhE~2E5s@JNUCr<u}RN3)p%?=
zd?L($Z2IL?s?8@QXtPEXo31*i3bk1yn#xB|g<Mga(JzmcQ^}R&UVw}NvFXxt>YTrM
zIz>>IkDv<GU7XXN-(ax`Mkn}e{ITf(Qn@@+fX+?yhvp%;XT;w0Ks>Mc1P`qK(D(Dy
z0XQ}TSRxZaY_jDJlF7!Vrx>^#u^E#n6Pw1SlL>fiS5R%%*BXqqnv#62yS`N9F$jf8
zI2!{aY4z;tHbToCj4w7n%;V^GaY%1sgDjwfjvmo{0s((w%l+^;x<m#O;^YNlDpVST
z*bMZGpm`xO;(@bfY&y5V-zPRdTVz~~%{adB5sFR6>2t6=tOD<ygQ=!B%sDwQn#Mt^
zj!jZ<Z-6TWWVjM^48E;BM^3k=4u`1Nba}gyf#2ZwSXPZY))m#dYI<h9p{9<M9VeC&
z1tSqdFs8$kqC2ZgS;iZXY0(F#BRo{B!<K5(y8<>fKBHTqb}A0nm2ijvv!xv9tyaR7
z@FBCX@FPO;cFfg{iEfZb*WpcYCFodHK&*z|07n@lq9Zm}EV|@%c-n=+Ms&mrjHRT%
znf3Nb30qz0IKR)1n1UY(O1WZ|a#d$wv8Zd92ZCHQO9`$Kb1)Qoq9cY`D9}Vla@bh&
zeNf@lqKkKjo8p!5IY6p4)!jgMYd3pJRDGWK!F{OGc{d={f&ipITfbjfN2c8?V7rJ3
zb46?zfVGsIxD{e8C4WXB!!iqZ<e>dD%DuBAOYaq-<%3tQw8*_>35{0P-jtxxj)2f1
z_5X@imXYfjuBNf*o8A#e?@FrOUO2ZDSLsTs?^M*Ur260W;EwJ$Js4QGk~?&#zE_E(
z0opBm_=qGJGGkpyEm|e}u9%BYir8?0-c+V}L}3g@>F7wldj<ILEB)>jR0eG@-(!Xz
zGOL7%1sE#%N=L5TK%SRd&TmJ_Iyw^NhB9#U4zyEDj}AYH5X=8c>J=i)N6%Q2p+pq7
zoG(yeKRPn;hH^@LPH&&mW;BIQv8EAO5;_v@hO!{^;$8%^IrW~1hU@{oBjjEvdq9VM
zB^VK;R}{yXQ$qt}&8eZ4Q*un@Z|w*V8guHwfmxe;Fi=Y=#yS%8#+#I^BLZY72!GG;
zrJ;EHx10dMNckN>QLg~cwTmuyl=+3)ZPWN;pq8@8T}i!vL#bw1N#m_^&Zx6?1cMBv
zyz5Bc8wxw$5gsxWm*h%r#)VL_y^iPuG5PN`t4&P<!<66eN@{sG&Ag2)Vk<!ugvdxH
z9r=dug%lrIr!R#z>Bi%i@*Q@=`Dz?>w2mz?4oY>+rA+V!Ov`MI)vJ{yJ`tEULj44;
zjnMP}*OW!_N@|N3EN0hvJ8=cM!Wg^#T0?V%DX<CcqcNN@qdH<9UlChQq#Lew0d#}<
z@s;H3Wk~m@8;)y=hH@n}qOCDHMx?K^Qt*T#xOa2T{?e!bePeM{Kt6>~xsn<JK5I+p
z8;iz*E2t4r5$;Ij6Jx1qoYTfs%fP<MZ1a>PU!=Z#c(q)~Lb(>k)DQuFW2)&>F&<)2
zukPame}hVO2VXaoW%f#{Z$mY3etWat_KLX@%8c7_-4)87+Xui6`E@%I_1-dKoAiNV
z%`7tY#^7yYM@pekr1cJt;gzr%V%g|ur;uz&nXYc9r1l}C>J8;2?iHyfMtcXy>tw*{
z0JaUrwdx3*AIh}cb-j!a{7KR6jAF@jyz!8WQpc(Y22Sq-XEl>{JTj*D72umkw%ibH
zrXx9YD1CGvJ4<Y(sFIOU(;rB3auqhc<LmiIP^!_mS}lB2^6NejBR3c%y(5Cs72tzL
zI*2f-!xbGVOxiGlo<;?<c_89VeU-9d>Bj^3W=mZGz?l@}N|W)V2%7>TNClIYr=%Xt
z-r{hE(bTIAQ>2tD%Ee@i|JRWmBupxG<qrvk(&@mE$Sm!>Fy?klI6HfmYR>^`g@Wqz
zOt2EVD(r~B6&1bsfvCDVP^w-sdSFM4)nF8!UZ@-<wYZYZJSk$kKt+>ojN~;}f*oc8
z6&1Rte~>?{OCv`ToiJ*~2ul{$)ii+9x>^Q!T4%V8UI|u1f!RCK357{lE_LS$(9*=h
zlD15(>5A$n^?P<5SgF|V9ci4d1kVIiR?wgaqT-1hKC_4-j91nX6)yTw-+`8$7UZWR
zm|Q6OdxvHjT^e-io}utV9cjIyLw}wKH57^l-;wa_O4znzkW#XdV>1-9s83j#uZYzE
zg<T4AYVFatdI#j|Tm1v_^^GF}9Ja53{R8lIYR#1#D-<-oBSrY-&L9j=N6gpgOKk)C
z`cm5mlMbN9S?89q5!Hd{Ns;k4HRH4{_dHfbr*-+3Ym8FS7fyctJ!CIHUmvQ5bDf-n
zdp1M+GH;qfvE@5MG)AYcjWcT~z*5JV_THaVsXAhB8<=f-y9Vs*rlt$~6q6}g!Z~r&
z+YxdyaMZjn09n31BK#ot00pS;Yi0>sBrFNhrJ<L#;VBX35vMrCpTClN8`7|0{)pbb
zYL#)gGYn~m8Ra9%(gy~cRPY5DY|_DDl!*!h^+1#pt#I{Mk`t}iP`!e}Mw6P3z_8J(
zg5&#X!t7OFQZTH2M`+SeEU7D5S!S~^aJJfKVE76}mg*G}H5!$0Fsh<S310=BjSBbE
z5o$FQda5J*YlyPg5ui2NR!e}+w%Jsk`lCq)he7a4*nPlf)5i|OVl>*N`$piRP_+DB
z_Q`0{$`KMa8ntp{L5n7>d;?({vY&LMMY{sDy{iJ-?HHkS@|_^tCfnfAQ?atr9XiJY
z1-xRtMw4odP_NOXUL(|NG#RZsqP>QK@uyE<_I2R7BmZW<fuD-Y-z(AllOnbZ1XZa1
z4gy9rspz`^v`IsUY5fVr?(c|Ke9LUS5LHpTI)WTWliI$4nXT&xv;mrp8h2eQgyME}
zTs&L}I|D>)`23#~)jN{TjYzClf(IucD%w{^99BQFU~eSzx*|62S;7Xe>!f%kc&39?
zDPwhA?SNGIK$0HXN1r!BTKkbYy$k#tUC+n+k#%|_dD9gQ{pSATm7pu98kRP_586!w
zH9~JYlSY@QCjnFzYDDaI<wCfUm1Q)GAm5HFoICXhQ~D9*59*-gM+$hw4!;7nQd_$#
zNLjCdq)&>lA$aMLexy9#tIjIdoFOczD`?r31nSU`iaS+5j8E8c?dqAYq1T<PA7L$m
zemcXP^}5)7Qo@$WoR!w?Ro{>FZl76Vqt(2h!5jH2s<lKd+ey%sn(eb*sg&#r&6yI-
z{=$3JXNO>%SAs9TuE;+UnV=D9^GaYSLGrsRVPiW>__`4v(~op&gv7iOwzCVV{YcIB
zjX_b*u8{ez>=PaFEgfN{I)YjHQLe=flEM|SZO1~DI-X%EJ*12yqW_g}gk?d!66_;j
zLpU;6bcBk$WsW+)ewL!`Wjgbaq75R4hg5BFJv^XlCsV{jIy9&x9?BklMb$Z3suAhW
zmHVP2d7mSmRj=TB{-(m{AhTQ%CJJm8S8|LFK8pu~$aD}|t|S2b$meiHY`ot4l`ND8
zDq(8?EyY7>b@Ec4l;A@LGv!L&TGc`7)iFK=Y0NS3N?wf_)RimZQ|mjt5<Yd{y-ht8
z^E=5t>6JS0Ba-Hgf4max237wGunAQ^Qc{7rucT&As&-_J`YRWEP&-BvL08I+4hqUg
z@}PKsFMD-tG$(BsIZZsI42Nfl5A-_cUvg9xYqDgl4q%uf3tmZ0mbB?&sCX!Xe@B*<
zj|ioF`7UKSm%6)<5+8%RtkuaVd9DPd?1flRS5h7W)OqX6b&sznRH&0sxA6VD%RG%e
z!d>QRq%m~Y_m^9ZyJ#65Oci%3$6%_sOF0Hr<w~$Wf~s;Q)R&8};v!Y`;-h>dRE0rD
zahEQ9s>FwapW|Xtb%e@vmm-|G5#6N)A0VN!ja*6ff6>r?0E9|E(hq<Te5zZ{&Pxjh
zf5n}e@Y6wHaV03}hkhM0PXkNcsUClj)<v=Eg~U&a@XxhGUAAc;y1Q)ChwdcOpNr|@
zK4d%s*TqHEx)GOZgi@cOgt$u^hMwa78mvExjJs6f1K@M%!q9!(p$a2BtGggL`7BRK
zFxfykxxaK!TCRjG0p?r=>w_dTSF|8lS;B4r=8H2w%N5jcWUtOvn=bAU@y(U3<w|O{
z_4$LQ;#+Dkh$;@|)l;ICg11t3Wy@L(E!sD<WrObRo7QS;bpz<4Tp1L2-!xYnw0z$*
zS6|6}_nQ{$E6CHy6`?5r*rtkoB{ir(sRra~xaWABIAdVA_;x-M04IW$fve(st0$vM
ztvU*$tM9EUK(D<~%DGoeL&H(;N;rN%*Iv9!G=yBfqKSzFbnT_K3%d4F%M&xZP%5={
zPc;o}BMr+yf$>e9+uF(!8(rxAyeq<R#CFlJ3}<)WL%rJQ#89_3UT=MpPl>7{_Vu9Z
ziLq;*1$L|6$d#~bUPk~|!ka6q-tsdwm_DwgE&e7~R#(H$mDSmDU}bf+4s6_Atpgv$
z(z0Z|cv%u22<jC!KKEb@P0u}8Dy11)d9L3gdy7m2zNq$E2Out}y;qQ(69>zXqS29Q
z$C9w(OB7}UW5tzv$G}+eMHBRuWcQVf$2#C}1<e;$yp}6r(>VF9K+~n@_@W8gU<mX@
z6ZB)S6kZV<Hw=<C=qsr%yB-7tBz?<zrFip2E!SW`y%P2h@V54!Sf_fU?;A$hE2+CN
z>oZH(Wx!kUwbV7h+gfTD@V1uPon=sTakdOb<11m)6H~r8BEZ{PYJJs&Phy$Df_+77
z9Y?>#gS8<Usjs0vZ}d>fx~&K+u9QNC^aH+zItWB#k|D!|fWwgd(X_6p7T>@R?lWnG
zHe@fo67~&vwoL6tmcUdrB(A+8Gzx$dBkM|PG=@^Sn0B>_Bi-t16$iN0H8w!vqS}2W
z^@7@0t(<lj<I1d#XmXM;Bs}#+6SU#N=_5fY9aoPg9#>XQa+M*C#TBp>KpT@Hr6i{r
z;c}i5)q~k?X&J5xIU4b?3{)AP!FG}0<x1FaPP!|vl7SoJ%By7H#<*x&hCHf|D;B^N
zRd-zv8rfUdya5(P!ZHIaPNzx5kbKqW)*t|jb8`@digT-JpyJ$2C}m*LxY$~T8(dcs
zCj*nl=hm?9W0x96mSCTYEf+HTTxuHd3D%bx@N+J;Tj$5Q1RLPe_*`mtV~A62?;0av
z9M|biV%U?S8sbFLo`3U^fYT`;2WciHjlU^dk77bzQT2cDq1F4L;lL6)ho%u=ItNqn
z8fY}G{8I)RjZahKiKfa&W#G|V$wE0X$fv38dSvYpm1ovx{}YSVFMaMvd4DCA6dOx&
zhfi9iZ@HSJ9(^UXAgM<i=rLD<oQnn?iBDLit(Yc0X_hvyV|>soZD7avIBFbj4laI}
zA@$Lfu=Ub&oO!9PAm?!$wUr0SAzQV9lH;O`8KRc^kRpw&x;|>uANU)tHhH)kuBin6
zF=ds34C5kl8F)({2}(JSLzZeo&Z#TnaDjbetLehNA*ddJK9E<Q5|zXK#t-rv9#XzP
zavxH>!Gm!Tx~`-Yt|6rv<TD@q+6F*RnXwFW;X{fuChYM+-n1dZn2)Jh0rZWTrTYMV
zk09S&$!+yXNlo)mvw*!Z)GVNHNF6V>%oTvvZlKG!C|x!HeS^9;s4=d5T$a=rAJV=D
z2oFA_ePi*uC|!mn?@HQb$S8az)zU0%e69qKuC&4~%GMQBhr1pOfE+YT8`5KVW&3&{
zszFfy&duN!F(wda9IP$_Yvz{OatGdzrlxU39MaKi&vBE6K4Ahi;yIWzR{)lXfjV<V
z{7EhaJ8HXLk1NlZVN-PkM!jnSJFkl!X1O)H(ROXvyxpXtV~2Nxie4<>Ck1S&FjQnP
z19!$v`uGHdnyaOP(8tZy6fhJS&1|mxn<K1)tCKHgpx3y$umS`dx2=YOp(ZWA0N71R
zJ_5kHm6HG11cHioX2|F0CJlXhmax}=7IP)6!Skk3JD-JqN}F~Cxllz1Gw4KaQx69C
zl~(dVR4;Mz!3lm!wRX$3SfswsK=*0K{*1AHz=mOcWe7EcF6m0eW~FX=a>Oi|EpEm$
z511`ig3SudmX9P$1!_h+wn340v9_#I9X~0;7E%5XZe0%rrdj<nPJKpGwjnvPn{tX?
zQO%aV<CPd^O%1~knt9y}M-%Ty55+l=EG}E~7V58h?V?>7(jj{f{rI-lr6I40ov=$s
z#!<|b2hNZl*}Jr69O+!VE2~rA^9Fq}oD8o7ZR2F8+;N8BY*)g@fqC6|MQUqj5g#`Q
zE#9dygU{k!Ds%B!yl*{}uqdjQEx@Ak&siPBuYe;0EOsf)i?G<KG%uiH7X&Y$BB)xn
z>IrNXxY%Efc>x%^G-fbgyh~$70$~?Z%Zdwg1$Uu8CCSBz%y$M`$St#R0A-&VGmx@V
zwSFwEE-tp0f%tMI*lKpm(yG7Fd1=g*Rr$`5KGiZId6#;;0f}7-GO{&00#X?$Ew@ao
z4{TLVDwie6<rdit0I}1AZ6LW^2`&x|*`%+CO#>1;l<i`|xcFTLCXDyah7G34-qkh$
zu{X7C7^5_D7!X~#{fzmsT|BWX%Kj-Tj)BPHqIp>nS-eS;29f3QcGPJAT%&RgGpaXX
z?Os{JwgNlsm2j_ut@eu85b&(YvW-N=&Xj>xd5Tkji%dg~@{cHg05of|Z0|Y`HrD`g
z`fF0s_r`%j<S!%FrAfmk*+r}^1KFkRuS#VuRWd?D_TY~MrCeoAS~kr3E`pZ9^zUU}
zejo}|V@ve|HUi^mTPW4UN=x5J59s7<8C=G%fXx=-HEHSO$Fzx3^;|bjMy^YfF&obC
zF1FQ`)HKSL?Hw%}+&8RJ?Op-8f?T^-!oC3fniOi>HaYoLPl~FGvS$}(rb)vlXQolZ
zCS|6{n$3$aZ^CL)W}1|4&}N!+Zc<_z)oC(fnlkd)rNlI7)41BZWj->Ivq^Erjp07h
zoGVf7Q=-Nn-KD>kf65T-VIQc@6%1k@Y0e<S>~jPWV8d+XbTlNH-HMH8;Ky7E+um7X
zyKqRjq6NWyQ~Suaja%L;;jC>0TazkX7sdOC8DdEHx{p+8<oei0x-zn`Zj!;w?>|cg
zuDkFjMeJ^%cd&HVoqCqBCE(tDGw`j|#r!UB{s)pwBywcz2J>Yf8M_e(Wh?uQA(`hs
z?|oJhWUhd1AG~`i(;yn`BU5*@Pl;4(i^dTO!I4*Ti$G=|wd^DC1*v6={&giQ%j{Zo
zbVX+FD74#$%5!wQAt5rTFdqp@SEJlVc5cvMw(??LNzJzG+!Z?b3fL}ErtYIXAO`wx
zDAmNuvK=EwBfEAC45q*18yJngcJOL$z&}=-3IT{sB372zjm6oQRU6S+J`$8Z6+${T
zC_<a$tSiV~gqYP=l(QN#YDXd4m9XJln^(YQYx#a8DCID>=vxLt&6S|#I_g~k$L3jL
zqXmdNg8nlG2F(_s%kb9@>Ddw0Gr?&DdRChDQ=)}h?{lhmGGIrbdsN4x{+WF}nE4PU
zV|K0ty8~u$hjejpZFWc*uQ&1RkTMRo%?|3~;M#2Qy9`{L9ni(Ww7F$!l}WX^0<;Wb
z%?|0_Al7VgzHXw|o~z@vS0nf94k+KnTihX&HK>hSWG(~!afeLSMUi|`#1R;J41GJ9
zH9KUn2D4^|^lvb0cDxpAP-}L`VvU{PO4#<O^&pKL`^lA*6#~?nD`4Y@`$+oO6$I*F
zqd7DC3)TAIu(?GSGwg>~f@c&ShSX;4x;vycgO|HQ&dUbg%#Nl90}q3S?6b4Lj+Oqm
zT~_R3%{(b$(*Q)##+d1NyL4}$*mkMj2Y&Y3se7LyH*S|<yMS=J;2Xs0?NZ25f<@y5
z`l};2h%z4uN(g7legXTGcncY!pAun!06&+h8+yn`f>O@3Z}qCCV*A!H;Q;%biuh<P
zOZCAsqxDCEQq3TZ+9Or6CnYt@19X`!F4#cC@$FN!fO2GUjf&-R%P<@aXs6q0vL4W2
zKN6I3&S<q}((fz5GY6+^s3(9l9~vKE&1tnB>HKiZY!<NQVplUM`F3Md6KllO(yRfQ
z8k$%mVpop_EEKitCP&}i`Ot;Vc0F{Vv-L^d^4(UQn)4M@U;Fz+%rwo_S5lpCnmGhb
zyCO7Q&?g$#0JCO$`xAdqU2kd{*yoL!FEhw*Z)*F4e*381TDV(GumKj$l`NDKv9Eyb
z<f(8gr2y00UkO_&g?EbyHtK-8x7Z^Chv2<KLj+*%K-&Pv9ct-R2`_`_xLwTv9k**h
zg^s-)(|Rg+ydo5DFw1u2s5**yQ?hy=Al{?|YXQ`o6k&;hdy^u5M#;ZP37UriBSo06
zUN+B<NK2x3_Pf20>g+ggB(A7BuQ%K~`Yy8k0HG#D#TOlA87dJwZ`o0?;|J_ZDPnVl
zcq!ty*pYp)Nevq?UZn{0mjIapPG2EpiqNNm$ds@PqlOn+0<g7xM6T8*UPQ6$AIQ)t
z*TgJ#iq{FF2sJ6easi<xMYygRpwy&nK~S$tD%a>6MGUU+F;jfNQ+0rclQOopYs#r|
z4fxBZXh9IHlyg!K!q{+r8gRr-347oe+SFjnK$N0Y4|0x!%=!V-_D3|-r@%WPH)y~>
zo+8|13~*{vhE5&6mZ44^&aSCfhm&jX%RB5T4^RUJ{1l-V)~bk}TjP`)F7>YnGfs_a
z;G*CoqM38xE+Iug$D-+^1TZ~7!bw?;4<wwF;L`@F<|AtArLkKIzc%1RU$VxZP1fYY
zjQwgTW}k3Yeo9pDK^oSuf!81v>x!!9u1_6=oD^|$NlH#i*#5v;bk?brC>?9yN-9MN
zb1`snRWi)^tflCo_9tGj2a5G_okq=P*y2EN|8XU&%AB*s4!Zih*hxn*b;(beN3H=v
zO^Wc~js9)*cw?QuYM9}$nKE`@a~NA4*c=MaUc>wrm)eI1N6OFv$9i}*HUzCn5qscR
z55Cj^Y<MZdPK2-@AJJ6JU_W`8F$_ia@u*W$=j^ao)aQ&?D#ra4p;L9l8deaK0=30u
z%460Tgi|r~#~_?KO{rtRN33LxKU*b04@TqQ>Zo-Ecm+IajnS(}y=ZiNlx}LibF|tR
z24VA6=0I;KQJoLRDBSd>E)q9i?QIY@slE+@rppg*45Fsv&@~27(|Pb3V0&anCw3F@
z)mv$Cd{k~0`=|#<t=y>D4Fahc{bLYF_rbwwAfixZkU|$`j`!8=!01U4TO<7L;30E>
zdGnD;IU5Ah&C821b``OC4Fc(QZJ!9_lrqdy;pletkvO^?Mf7lMgBe88z122hRM~09
z0F257V1VwEBH#@8J}JUJFbKBk2rvebR-OPOlTOJEU=+dUDH)pzzHEK*gU~Bp{{Y`B
zMSNJjzZ7vGgkJIc#~}3XsmBv}w+?*+T-7VP<#}OO2{pzf>~7Kz#w6@+9s4F>x4hFI
z$gpm8@|(b2xepA`f37Htor~6lf|JNh?}0Ii%yJ<ZN&iU!1`obZieUL0v+C5J92PHE
zt_Z{8p<n`%ch>+Aelleo0wH-z-=Bo!Eq#9ylIbyUCG`%Q20=vLO~W86Z>bWKsJwMb
zAj>CZ>;q6)&IJQJpA?}B6DwpL^<iRvhkwDC1<Q+?{v;~PFW`!*lW+_e6NtMM!TgHQ
zxb*tD*}682NyJ^QhZAuxy`UcDRl?>EHcyH;9|YW`)4?R*F2#8qh$5LXcEB;Y@FB>=
zv$=}bR)c}jZ2`^<j!s7eP_;9~9xD=Y=>sq(&ZcW>YoA2ZMW4H|h^DLTr(+RImlXTe
z*n`QveKpQ6$wp%lOyw+aMVMb&T1QnHIv_2=soV#y2-C^qz~bR`={T@(cwKVN8;hsc
zCB$EZVYv-l5nhZG`$dEWm@a~;X#WGjWK+a$5>Dj`Fc#r7Sx$Ub^;6&UBAVhc#L`9b
z(iPzqH2TzyMKE1D9;^b>)ztjt(DXqsf@%5?ROXTF;XG;$2id8Ez~Vu6>L9Rqj-5xF
z@FD`sb6~8E!QlN9ZD;7&1-En*cv4cmmao8A#M~Jg2q9Pg17i_#>n30<;O%q`jd(kG
z5Lkp;c^HgExSjqEjhHJpgR$@&HXc~F(^0JTAqRu8;ES9xw9XT<oD9ao33=+YfN<6+
zV%vv%@RXKNQL$6Pl|-19ufbS^Y5E$B-KxZ++a?B2odPy7Se^u96NBYSFg76=yLyRg
zEF?~hO$dfJ!Po@hspG^Z2G6NIZxe;(c`$aNupAGr0Pl@wjNSRx-u-3sBs_IA*nnO+
z4UEmhu>1zbCh|@MWFNZ@xl?NYCZtZO{hN?FyPi!*o&D_;54vzO7#n~(WenZ~)Tsl+
zR>su#08tK^A5l{m7N--(1;o}*0Uutt3r~a3r?Ua7NP9Ro5p_tx-$Yb84UB!Ua)bt|
z!|4!uZ%5mMM5ZfRCE$aJlq2+D9!=$1FgC$+$Y8q(pF<z~27C^k2{uSoDZ}Ff%VbFB
z-}U7Bvu1Q`{+ysW6j*XNQ8V2IMjg67C28nR$du2(a6;y&z4R$rt>GcX-HDk)io2s0
zzI-QSj)fw$f4LqECxi~^^-c^O((4@<D({2AbMBR)jQ1y{-RsCYq_R5!RsIFT38>>$
z*?m-*V;UTU^mQl3j)5Y^U}}5RjY7)mn|I)=JPw8vU*&W#oER&ogW*#nm2uyRvBOZz
zCrgWW;w!xnhV%G3I@t-s3Ayr27*5n3()JywJERvlQMa5E9>}mhsM*69loAe@pgW}6
zBOpYIXd>`JUilvkC-BMxVK{-8E(pVkyLR3Y5_sW+a0NLSIUx)u^2!TgIHA{G`@a)=
zP4<5$^cqhE9#z7g;zVBfAw0tgz9!?p^Y|;@gn^t%DdG$ShwHk(al)@06o&I;Yf|~0
zHf8x2jA&J)vK>TL`4@~JvckdO3hJXY-3A0e)I_GbqI&1H)EIHpbRiJLQMo3JAdDIU
z+6}~yNeQMZh@<pR7(pC0T?s@MCu2p7pv~C;>_MD09UFotRg?A~JgJt$!2{VU3AUvm
zuG;u|6kZgM1VIS3_W%%+)2kgLCi|%aKq!B>t^)!nYH}VPV4<W8Ez+uNIyeNe)>y>o
zx-1M)P-{9#;8rI^crdNXa&H*HgQ>lif80iu4AbdsUzYzM;-(YBh(cTXFgz)#+3nKz
z5m_oloDsrpm*GDMxBWHz2k^G*1Q0x}c2=tO)@At*T9lD+;3-*+SMCub@DsL9`*9Bx
z>m_z!f6#hNuZJtaAf)UcAa$2se~8pwy8UUi*LO!5J(hBRh|+Y17^hc>4H2aK76cyJ
ziMurWL!g#7#5e?M`9q8Ype}z1KC9Lz9U{izSyvtr<Iv>XbrW!i=v_>#aSGDAP5_6H
zF3*SohT=!06Tl&aGe$wlFhuMN2ly;MhjEC{U8?*cKIfh70};Be`+`Gwh6}_v1<+l$
z1&09LhmI155Z!fMaEQ=dXM#h7maD`#K<K*4ejvhH!F|D5d{??JI12+7FXRxi>n^>X
zM9h}U#5ly>E{*>XeC6&i4xqN28y<+zE8Q6!Vr|DE;1FoL4grTi+Z&A)d<xql(l%Wf
z973(UBu28DQvgcdI7He8{ooL1<s~r=VU}(Z<Ion31U^s6a<p=txRUB-)4}8LklScw
zxampJO|hkC;~7@&53>Pl8}AHeBh<<PVm3l;bIjAMh@>g0sk#z$%TYv^w%Q`hf@|}X
ztX_dUDP}{FjnkIga2%P9reyk2JSoG_Hhxm8vMsfaGq0R0X5#_3@#yi)M#Ppg#cVvj
zwy7>o_KD|)D?+El0h^7`+jt)^8=*J-CT0WdwxMnkb=!C+iMZQ%zL<@;+lG2T>}^9`
zFX&~YrIKJ_4ivF0O&uUQHyki#BRXSNpOV%4H#N`GaWf5;_GbB9Oawyyh{P9~jj&F~
ziz``G=0FJ9a;mr@bX|vq*@)SVHv_W~v*~;>8xXrSO(qe$DW>0Sgl#!t%tqL5O`RZW
z%Qa)R^V@-2Mov`e1y_XT%S?R*Y`%c~z$;^dVRht|F&pkC&*52O=9cvl;D~U`cML~P
z7ZZM62R;|G*WaA0-qA7M7)*o^KXRs+pi!OUdT2-AyjU=^C{#!8784Arb6j1mw|@@L
z4im_54v!Ac1biGhW=up@Kl00%6@EP>3*|r^Ha?y#vgLs>^4?$qanD(*GSNHe{xfm=
z9NigA_&J_4)saHfE5VKc#?+Ny-vVLkO6sEXN(O4NHw*L2`+^D0<w`gWt0s7mBr>5W
z9r{>Ic$OadSj?nGonw0J#t`(GciaeH5i2<+yh``yUE>S1*)_gEqg~^RY?LbeM0$mf
z1f`m@rY;2LjJ_1J!^(S3Q^Tj$c~iRw3!P_x2{rztJH>>ee?n1$=I0=Ag1Y|1N#O)l
z{fXnm5u0x!uFwhU?9*UzJRyj!<I52#?+ONL@i{etSAx#s81$T=6@TKa^pRxg{-tjc
z1gI0x=qK1u2XRU7dI0<B$iZTQ{B-1DF^m6n!quo@g#0L<398efJH-Ui>ByyGCe7){
zpJIaLbR}#EQL&ELebZ)^@a@~gh?d4UF{H(IC%P{m$1BSI>$A0q{x3CCD0yP3sf7Ve
zZO1tDpO|cG<%p(6xG<v9-Y2XJC#G5kE$YNn)3v`Gxm?U*MV%NL<i^?<Y<OdkveZw+
zcQ|3H<=H!G<P-5Bj$9=sY%~Y15)*leZkb&Pv`jsFg5-3f>$$b4Pjo#u_#QhRT>s2T
z0IY@Z7=)*kH2&sxUb&#IAV2shm3)qdY179I_R&#3@i}^y@THcm@JSJ?0JZ4wFv~P~
zlren5e0f}7F1Sfo0)EXES=HimiyL`7_*~$T(;|N*IcrQD{-me|APswrEV1QM*N!`%
zS}NU9YVkSh1bC8!H<K@Pm?eB78qg7EZh}8_(!*hbI&|dW@JyJ^k6auk?CQst<`qEX
zOTz~ci7uB9%86ZSdSPO#Ya5d~HFN-#Pqn=3$bFPUd?x$oh;BE*EIR2XF>yh0Tnchs
zVjP$GY=TpC<R>w4`EleGF_CcZ$S-1!Kz9d9d0al?&s|Y|jr5YZf|W(K0(_H`#Kcw5
zanl)K0OVX+F&IZj?73O@NyodI2FAgc;z>y@zOL4RdfwGKkWWd+=WJQR7doNc9{Nd4
zkch4TPelx`qqO7`_i9J360_odow@;fAj$s9H)0~I<k?hvk$Cbb8~H?b$^%N>GiMdp
z3Xo5p5)%}nBTtDd$z{7k?IMfaVOH{4G@~PS-NZHMfuqC(!|3c#(*VL9w4qE8jLr_V
zJupIHHPU+?G4$q~=%2q+1#H_?eP@NDyMnh?bx?{guA$G~oGKvOmgbANcxQ8`NM_O5
z(tN=zI(w<%g;T{|YP$aM?4_mwZAe!>i+prMvzxfKzY^F6aJ7FWY<t%br<!&QNGdgA
z7anl#o)T4Oqzi*Cbi|gM#TL2(Y$xCfT}gKENm0Ei>dOcLbd;RD1|Z#d9`wc33<AKO
zZE7gdZJXxdV1A9Qlzr$ZKlzo^fJ!Z0fWJ-V{FUTrXeytezZ|A7pP<Mb668L^12yPu
zp=dFKj!112yr8pbB%h%Ed?YBP(y)$t0`yx_n-OI6C_DKCqv%SoS5&aldJvl)Sz@y|
zkgbDKe$Y!=HW)>xI3Z6-a&${tcJYbMl9COw&{=^}eh6a1O@<k|B0i%q>Pq;Kl_mBX
zn5mTJS5kd_KV@VLKWnQcfaanGy$Ujy6zB!WT#BeU!5BKqYCacmb4i5;jp!_?(a9n@
zOG@<G93-`9P>9Z2Y8=q2ROb@}q9YdFEDF(CiV-wH7&>dJEw52ghsIPNB}1PGM|?o3
zyX9P8(vLxJJWC2PGS(laI-g(xokjEaMArM~iWUUf*`eM8IM>k30XWxC(*Vvl+4;n}
zKcdae&v$W_lx%!AXF<uvmvt6x-dB<Xq{;gVHmcz3-vG%aC3*uS7r*X(`yjLS+<?H<
z)Db`+l9W#{a*r5r6KtQez=D5fk$ui;>IeXE(xyE@^*Qrs{D43uDW4nON=KBqiEa2y
zs@@<rpLx{Q=j=B_?cnS;;~gUof8xi@4X{(D@(DuE5v^?|8r^dC<VitJ_mt5Zpmrtb
z9I#D^$tMWsCkbqG!w36JS*$m(ZEkfA*fwRZ-i2*b2J2nh!E>0ud~TqfsB2eJBibnC
z*F9ydPKwYiQ^$o)ag_6Xf(~@14Alr0bf(m81PeM-*HaVJpEIR!L!G)3J_z_XWwwS|
z_K~1;7rWA%PdG{(^3Wz+V$YOH4v&j7Wv_-?#&f2$^kNa6DJ2~wqLWF`C-_50M79a`
z&`BllfuzPKHQlQQTg7ovxzi^U=p$O&bWmB&ltzw36jxFs^g1spGx`-&SEX+|5Ocl;
zY6oOa*{2-`#z~$0a~?TU`Z&%jN6FEr4=z(F<lqTi37ZCLPMM{PC3J=~bdZFeD?-b#
zger;pL?EIAQrrYR=nQG;$q+h2;esa4dS^&U&t|EO<M4PykefJQo&j|nSy|4A_W`wE
zDQWry-zO!QeL&`rrP_Ja9F7MkVh$OqLH;>IhH7wsj#zOM+@CW<Yo9o%pCNs{&hlqS
zT}K+6GhnAiqMV}~>d!2{yhDoJ^gLT47y1NI=ZF(GVa+&$R_Zc$eBRzvH-LRgbUtA>
zIpVub@OZ9-4~9eJ71fiY<-cPFz~MPVChBNd1X9b>o^!@~A`hGy2Q_XOh0c(Lx*S2z
zkP42l9EV)D&!&z{P)DiFucQ_WOF4<MQp0d|hOE?#L~@w4e3pmp5$kN08}5~$RC6XX
zHS$}X(cbX^=Z4JGF|)*0fpbF|I9NCz2}-rWm=x|ZNFI~E4Ws2TeT{H*K1yFc;S2p7
zGR0=>{CCy>z?pPq7;3MCJp;y>V)#thdyfT5*)x582*7iUHfh+9k4e7{Bs4!J1sk-S
zV^Xq{nRArke1eyA#4(%T;2hiB-a)}RCXKoXI9I@iZ~|0b^a%>i0mbYokykA?6&RE>
z>Hsbp6>9kQALT)RW+ulwVv<dy&pRfobN~rWR%vi@j!B<B$lZF38g-F$j#8md+<zR9
z%_c5LZW&GE7UfE~7vrksiqQ7CRitv`s^&0b`UE}am{jg!=R7ImPd4hX;g0c0!^V};
zF@4;p(9-0kJ`uX>ir5t3(x7DHuIea7`aGjbm=fG-ACqAl+?!)EY$FThF&Vazsqz@?
z+C|SfrmU+I^qfO_+5|c0m`vN?<{WEkdSX0fKzmBG@gqK_2Bdug<eAf@Wfynmh=w)~
z2v4WW;tl4^=~TP(KJ+NN`NWOs>C&ljt9m6gc;oK%iuhb0Tc^eQ)Tep{95;{+3C^Dq
z)fl9lpTf2-qc>vuolaF8VgHU&pg%KjsZX-aW^rB)Gnr2?UQU<(48qGtf>KUwm%hAk
zAAdSc+zXfXM?|oNoBh+NL9YzJc+0S@ETq-_i15!fi?ncGNlhYE?$v;FouBS%<q38A
zRKu`^_K8yUe(0%H@@lj|E>n}Q2CC-~Z)>%I28|U8;JT>;0Jv`I06?zGPQ5@kIm}I-
zlIj=r;?+JN*Si`9$o0;K!F)Nrt7*Vq?`j(MPvt9L#eq5Ed@XQWp3@tj4C7{RdT<^9
zmC$^F)pJDdT5V?un)d=%=(MB$0}9(=D?q|_)CzzQEUsr&*6v$YE45d&quv7y+tIY)
zu-8IOBX!*og=;0{<(Bv4Pjcn8Qi~VpE~kZ>1~@iZsTasDr-j-sbZk6JFK}H>bF~~8
zq%)lJLf?;4n=g#-i0`#>PEOl;44|)34Sp6Fa#ytQlj<?`;031LA-8LR*3xLUULEw`
z(`dI|B(^k~t*<2CexuoXAtumirBSb5zXy|ek^IsY+byHa6|mu+<C|&~CqSh!e-@aF
zN5rs2hDsai8c?j!WW7FL@@Ydgh+>UY?<=Z>IoLTsmXeaM+8vHqTZ_DwX4(QtY-y&p
zW=*cCC4g2lwlp!dK-ninH6+6iYB*gjuPkwJIL)=LHgJi5#O7KgurNh=N^1J`K^KFi
zwXZt0yc*Tih3GyXQI`C-I7huItumCJe1Y#A;$5u{Z^tWQs|99P!gdqPt^nI2V$27g
zT3=e6AlqbtDifq;Eih%SfGyvTI!>tBvXEhSAPXi$&03(i#BufOpc_=5mo;>S>hqQ4
z&Jc$d>MN?gz(T!JIf+Ac`j&T29QEl1jV2hQute2g8mJdkqc~fQr}h+Qsp(o0Q7X<|
zT42Y-S!%swoC0Z(V?u<jWmRIs#+NubBEtxTz@>Jkq<%4~Yg2t4=$gV;FF0d_h*%35
zBCZ6R3{ps3Nj-Pw-|Q#S{ag_{JFy0bS}uSLQMDFy{y3(Fb7W5(Q^ON4-_Y>Ft2Z^i
zun0|UFT8o9SIt7sjyPS7Z+tdg58CK5l;M?Uu}>KRTb`6uZ<_k&=uboc9KE6DyFhh`
z)A-noKM;pj>IJGx#8Kx8vLcRVreH0UwR~0Hl_y2mTX5995;k5RUc_PJ^<`cGThEU-
zLfM}d{If#2%@>l%gcxC0Qau#hg7R`D+#f~``AX11*bS}(9fV!sN~(hh(-Y)xJt@k?
z7oI=3zoy-KA>B^|?bZt^fg-kAz4#Ut6ZnCkCY<NyE2+-!EEOh1EHz^_lBHJQJrqi6
zzQCG^&=(C4$O!4oAjO1OSgRuNJP}iU8R!db(hD}Kj|8Rci<D@XxFYCKv0w&^7;0u>
zT8BC}F{?uj*HhUjqB%$AFkfKOgcw^3OqvL);~>&RNFOgAO@xu%wm_W;r9NMv&V*=O
z3+BZLDc6+)EG2r7XOUe82#Tb2CDq@q$2$7kGy(*zjG+2G3IjvhH!QIcf@@f7Bcy*1
zz+fn#=Kt{9fA`!)+dfr4KXY53x*yPL9&>!oLjV1L_1pjPTmP+n{;U7}_y78U8Wu2R
z{_AfDl^$E^ypi@I7S9+RcAk($wogn^$lTCZeH$UIyu1D82UgHtpPs)#ds}7;s0c)N
zG?{&~ArEE_*^m~@VfQt}Zg5l9kXm`(7zQ6&!#+6e*<mDBg^a;jBZEdVOdXwkDyr?E
zd-i_4;&Fjp(HOFK!|DAo6i6)ST&q+%6DQjASrAoxlY>jbQtHOyn2FyZvkQ_2e_fn8
za_U?YFbzjA_{eqcJ>+~NbLka@B(;R*`g|AjvvlS-*7xTRZ~fEyAFZI<?q95++M~W#
zP)+)~g0KO9Eg&UF*8)0UiwE`J)w90VjxvFCxcB>CtsA8;(#la*DlHvGg-0O4Obmcz
zMO-}E0p7(UT>WYBz`5gV@hCjNyLc3P@_X^nO+$-^n=aQ*$cl}%qiYMU9bI{StsUON
zXzl3IPHX4;ILx&})#Y6~wccy>e9m~E<?~rIeczqu^T(RKe`e!vT0H?Ib{_8oIIM8m
z(X&v)Lv+h0oF{v{obcKMu$|vxbu!YN5@MM~8C=5U$Ax&DSAs?ghn;s{2<v$TtBQ$x
zipCu{BnDZiVHgA7_Xpj=$xs6phI2awTn2(}f0hiW(BV9igDxE+ohF|;#5hIx`ViqX
z;BOI*BYD)%(Vtq8;XIBbg+hpI3jHE*|M;Y&W|pV(;+Nktnp~J!?D^oR-!fW72&zaf
zDsl#dsHhpxHk_X*0^^3`*dC78r2LUk`NGL7D^`CvPw3$Nhx3Gv+zG*`+rLGyOZ*fN
z?)M|8!hIeO=Mk7?p3kAYUICaBfupBrq|kvwEYi}F!+Bu_J^CZ4LJg@A7Xee@^y)xn
zixA25v@BF}r{TS|D%93|cn-rcBgiAIV@PbC&*6^}n-~I@l@LkvAPQ}WB#IOuL5k?9
zztOpx*DF8=YwE9Hlwtpr9W@kL`;=-IB8Q$-{zBByQ|e)C+?XB2Vvo%mGn^4)^S%rz
z5MuMb`b>0;NA-il<RyhZRnA6v0zWt;N>e&GC2m}3;Se1ndmcDM2gsf`*FhH0gBLh4
z?uD1buNt{-V$0G7&#O=j#)I?ZCW{<~hL4~MHIw|TPu={5qBFvj5t~>G-?UIrMYykB
zK@Br%$qeG;2}~_N%oA8MqYAlxH&yyF?WCZdclh$C(Zee*6dw_ud$IZ1rfXkpezVBP
z6kG1l2j@gaN9?U(;-r(bIyY{qxeeH)0E$nCMJ+Zp{tl~KDCl8F>Z&WL_u9+vG8EnL
z3KDBV;SD=1g2Cv9y=;b|*oGZu#XxAo4!dKl!<)5U*2xsHdqAFb)b<B@mUMDt4+{oJ
z><zCm6d<v~1vU^LvBOLDmN~#&3Rl2pOTmn#s3%vHFHzwVuViI;p|tVud}{qG`^}T#
zB5rp05QhRF_6C$%I+-A|TOcChEoWEvJ86Ka1snNCRYT{gAYDoIeW_`H)mprc>}iF+
z0=A3;<ywE@WAnRNgybtJy?C)@WS5P#)U?+!m}=Rv45kJRqpCtK_DX_q1-Omu$bt|G
zx!7@s5sN3XJT!&kD0bYHTuE&WPsepiD3W4_+x(UAxxhDuR_x_|9}2A4%SHc=(ljW*
z+@is~BO_uctm2i_QnvS8ktJ+}_n1*@8OOnn%c>AZv}dpaw19{Qq2P+W*G=NrIR%L#
zzs|lL__w$zTuJqm0DdJ2)`4!`Mw*V(0KkRQfA0Xm)zm5ga3S4hiRv9UHCq_CsC;)s
zpNOeFrP3P2<d)KrSuEz!aA0(uym9M&W(i+i2P#hO7#*-U14odKi`QVp#gt@kCw7cp
z&^hC6q?Y64j`4H^0*M)F8~8b0ZNtXOV2eEyvBsoge#^<yz9Rl0SM1cT@;T4ObWIxI
zQb83vGRvl<@T?<2Z72}pl~hNxAzbI)EaU6xfK9lCd^EuhgGNkj2)OnS#YODJ3`hYc
z5>Ptz`IBLAMQjR)I`#b{1wtSuVn_OenELvW{vamftzJnDX{zxA)j8BOtgmyZ9iS?F
zb?zVy=Qo8u>`0j$Q(v<6Ea59gOrn@n%DW-nTugq+NZlM$Uor?Mp~#3Gq?DM{&O3-J
zPt2~S0kgBK`NG+$UBG~|v$Jsk?Hd%aBi7SLgi?*LspXL+HVObmG{h8?32@S3q=RS_
z3WwN{m^&qyNkHT{U$ttd8P(8dAS2WX9O_1>BLGarO6=fT#R%FsuP8s>5o)(EbA*}&
zWR5BUFBK#a=A9=+Y#M+${L2Qkviw>V^Nq?Tgf!|g{GE3o=8z6xI0cF>+ChN(vQB~|
zcO}F_1Z|6<4;GQ#Lg5s9Mt_STGZq5G1zDp{imHo5a0B`ceXv&Wr^ty{kn2l<6R)Jc
zX%R^~c#0t+X$O@t$Rq8eWdYv<5)^zSi5COVr>KfOQxk-OD&BHUC2@KH4;3!)O6q7g
z^sx?{?G*X2k1AoQz=9OABz64TNAjRpt4p6`1zL<D(1i&s6y30c)*A3deoACji|yb*
zH#$o7@#vGp$b)eX`xyLo1iYWg3xzoB2wEA*DZQoaxI!8B0W@NIiW03904D~HbP7J$
z5x_IZDD7isfjvM3&=95cigE%)DZP^Hm?95eNp()(Id<Lfh*o+f`O%VA+6QhCMJw%~
zYKK^*9dzz6m%f~Q?=V3q!lj07J{Pzq4r#BrtAUt=y&|(dDF7-D+z={CVJ}L1h(X$s
zTp+|C?cl&aK?-RffHegu?4Z(z0d$jUA7Yf=a=jrrWL;5y)S{GLNexk7^~CYfgu=DC
zhbd|MmE?*9r}UO{O^Q?60TE%0bkG4IVf?V4K6_fl*)YzVqLB8C@EhQd_6b}Rf3zb|
z@Dq$|*nyd0Qptg<U)J}6-Y}lhJK#B9j%f#?2N<QdT%9+yJ+j2X;jn3@R(RSJ$Fw6J
zbC{0Ul?x!m4((85LhR6vQ~*y{)B6BeTGK?~?h$;^K3D$Dt^zHMvC29;f3AcL11<Ye
z!vM>E)NX+#D5p<Ja^ZFy+@VH>7^hc~%a)AOE67#bkD5*^RP<2GK*z3g`UE(3p*w<!
zhd8Kx!qgumq4v_Hqw81>bvwi_?NG_1yB-YqWR#l{RhM<8lkh1D>MiHWOb%+FK+ewl
zvp&HExFR+TH0@gr7n=610Rc@(X6<mFi>_G89dYL)*{mJsqv*U|>kDAnbuv%?zYuY?
zmxth!BH+z}<us|Qy<7~V3&3%z46#x>;`&Ed0JDzh|Iw$O3VcoKYR|uf;0xH=h2hKi
zHhJZKMYTkS+6ChFq0xY^(}ncRaS%y^?KrDP*Kxc~^Fb19U-K5~FZ7DU)hj`-x_(`2
zOlM~Jx<(g#FC70mZ_fL|@vk@8kl;oeB(8QO4G0leuVkYZ#}CAXHQ;`cYiAMr3w(ux
zSAQMu#37<;FNfm*Pqi<g;n(GMnz3+KiS!?T`L8+Sji|p05nH@#0i>BGEgLS`A+~8R
zD_t~UIt+PH2A`{u!q68@pbleTG=cg8CN>?4)20}rquz3@helA}0K6tp-vxLepZ0wl
zB@V+r8X$~5C8|ajf1gbXh&O<%=`@V%?r6f{O}lBMZ%2pse@bd?Re*pHkF+C(Ks4Ym
zVhlvxWIhnpU9*4~(F#IW<$Zs!tO<uV&U6j9yLqH*0^Tx^M;m(Pz}ph;B20gXdD<&Z
z{}m8r5vTu(I3S!18*mrK`&(wyfI1RSpT6s%Y!_hH1iQFEh}Jca0K3-J?&26b8ZN98
z8MWgsBpT1oxGjk$@ZP|>rnp5NQ8uCpyfYBTEn}lYsE!b$wIf$nz({|W{;q?cAE7gD
zdtAKLUN=O3j-FHBk{^QcXR7LZ^FuVoMU)?*F=ClGdUuh|j}G1y3*|}C)=!ema)iyu
zQ07P2j3j1$2+f)3EXzbPWJ7aRSlLk>yz3gzkDwcA1pM%Bx-$W<i|cwt)fK^PC6G%A
z_6+aUm#s?m(jPzc8tJ(8{76uWoFg5m9i^H>+^{;hs85ON4GMTO7r-sEiTVgW5|nCI
zb+~o_*%w!&?u-3QJ#%0Zg}Oe_aeeH#b^eTw-dr8`(oQZ>_n8GYGcg<iZ)K}a2{(C!
zVRBJcuOxXVqOA5xdhJJ=w@)ll<0kJ5Z`IWL!V<-nfO~%zWAzd+oC$-wLpk!Jj~j_2
zuY^CzZU~Q&q|%iIxVxhp3aM~K)emXi?)X%obth@!me?=H8x<Zq**hXcbwmJjkySfl
z^t;Ha9Rc}00MbbD>G9r=dE%!lWAGK^m_$tNh>YgS^4pOz-pdj4PJgAH_mIjA7K?`r
z(MYlC0XsBkEiMjf58UWGNvIv9K@X|SAQrlE0(V4+bL9l?89&b7guop!=3G?Nj>vRZ
zf|d#hTq%KjQC$2@2;4z(anVsbSemXhz8%b!j|8Qfa2d8LsQ!~8_GO?iGHfBv{*|D2
zv-+aX6TkgP9u#YCr5U3|4{63xJAx}MaF3NGHj3Ls7ZJ6C;o`|W?O?ZfNChr>i!1AI
z2fxLO|5IJtc!e^LC5h!z#^2RVS*SrN_K-C!{HdadZZ+q!g(2poi-gt@m(rE#w+ASu
z9}$XPY&kXy&?5u2g9qcHpmyZ6_E5;)j!%NDyPjkiS8%}&HjD?&++f4JB+pL1x4S-M
ze0uKskc$xGic#1RH`EoUuw!R<T&%E;{lk?2xaW@J9$%HRe~Lla!G3WMp7{@;Q1q~V
z0EHeXW#5FjAjr5v5cXooJSk$!^?F?lu?~)mlOfhm74QPVlKDsy7qN@G>#&^r{4KLl
zAffAE437s_Lg1$(#;uDbb|uvfvd8<GS;Eo+M7m-U_JhNn*TMnJx<U~4qRF@mf5DS+
zg&^z*h422Jgey9*yS{k@!uO<x-BNz?;)Zo-70&d(S5W(@!W8z89^x)IhA!h7kg$UZ
z<BCVv5n|b0DK~pYVRi))?BK$<A_;b=UhYKJQ~%5!Ky`D`zdGXEyZB!neoC%Lf*qbr
zSHhMnV3)hV_W-&WY_Jz^CIxK$;FG`y3)+moS$%sFXWWIo(4C!pFauA<m8;jFgS!F;
zK31{6U7RpOd~g>h%n;+=H<_D;P~)!1fmf3Ka)b`FJZHE92O5qdE@qhFxZ<LQ8ICl*
z#pg7fdt8A7t<FWhT}=b+w!e(x>@JVUkAYm{+tqksgDbPIwUIRB+L8>!8An*bTds3~
z!U`H38Nay8IAXf8^;!c!ig|V=H#muldUhq%|HbzPklfU_4FntC{MN6e`u|d#TXFC?
zKtST2d@4{;>@ce%zbkLAH8|8?5eK>Prl$t5(cPf|Z1k5*eI_w*<>@t~I`BO(pPqlS
z6+q=4>OP=y57NL4Mi3YK%wQ;S($B1HDYwkE0kqtPW)bB53fMN#a+}%)SZ>pp6E2mp
z*TApwGIKl-)w}O#>0n55fj}&KSGHb*k;-?Y>Skrgx)Lt;gAq_Gw~lk+27?~fFc)df
zdgI3kIJYFv_?E{8l7aXlmRkp&E@HWX`hO+RPYt{q2anBqLF(cG+(5eVb=WY@mFuW!
z+)VlkwGBjF+F;;V?_#nU;^JRP0pOLCLLyq4^@08o(XDtizFf6%f?TdXm!A3fa&{Wf
zD!Q8WnWez|0$SHrGdM3UT~iyZ$5+IL0JvnU8DizT*lLDY`5#G^R^6WaT57t$b}h9G
zFeP+-19;`Xvv+N7?bB{;+qP}n*m`ShZQIz|wryi;+uFDL!~fp<-23+XoM|$d%p{Za
zw4KkH1bIRq=TT&xZ4d8;D24}V!=%xznw6ODhD8OIte-_;)J`y>mP$hodfHV?4r(p9
z8KW~e?FV%YG%nbZoBU4+=1BCb)+fKOpb2zJ<u0^==WpKyw}-m@z}7MKbP#3MwfVj4
zIFT1ms)Hd+nmh9>Ydg?tMGPAVi8|?4D<*tX3cPqI%5-B{4TEpDcNA6_FT%pXOaY_p
z8v3Toc9nsVpiBd>OjpL*?etVx5psE*exSEcaJ*P<<U}be!;0@zQPGBeSQq5pl)e7@
zEJfj<rp*V=4&892n;E$DeH$g=;18I#a(L9$T9ch^nh@GyP^S88PtGhnHAA5|rV!m3
z+}>KeNx~?gy9bi!qb-=l%S8~qky8~(ex-)V8aife!zRI0cG-sM*n&G;&n6V5$WWc|
zhceeA<Gi61J1JN<rL8GO5H}G49H#mp&7Z|aUpd^RiYKs1>I;(63j}ze!!eF|RwN~3
zMo{3P!|8`)xC|=&HQ#ZLWmee~C-cC^)S_>QV&;}l`hna-I5#S-CB_hpk>Qf2BU#rg
z3k|?mD0XL(WpvfvIGC)w7O$-G*4!3GtYNk%d68H<Wi2H}!OK>>7Ei25W?rl;5z2hB
z-%|-cI>U9peV#24tSEcWZpkqfk9Pa!2N3(po936ayOWPa&O*zX>Sw!0mpMK-PE-zb
z-%rvO=S2`usBO0sx5DrIi|&%AfA6-3Cg(_vS9@anj{TE>aiHogci-LQUgGTG5~L$;
zYINJG?qwwCr{jjMYzw_`eawXL+H-e@@LqXzB9>kr_3j3|a1C?t7IXz<>_QouLycVq
zsF}0cmil8ELw76;MJ{cF61XZ@+s3~4raFq#5ZDjei+p9ax2_DF0_R3J+8?QL;K;*f
zXXQ;`n(D5(W|(J{&2sep6!1D)%Y+A&@8uTSmL-s%L|&Z>alQ?EI~FSA@DFJ1#pi`s
zj6kGV)t_MB#nwbN^b#+HARG)yIDr<*K{Q`jHqwrTg-69AcvB|xRw`8e%GtR#1B^a%
zy-}bx)h{uZi@R2WBV!yqu>`MqXBP9B>5r}B*_@tWZhc#c6bhjkp;hulHr&>4CsQ}x
z5pKEl3j(&f$$TW0V-<>zq#`_*<a140y$L&Kn}k;IZo`^t-;%TCY=XddhXIQAIBlv%
zh0#RA*>I`CW{?Yid9L*&Y~VNw@!Z1iyO`=Z=}J?9u&ry#Q>TzmKglNDics#r1XEG1
zj!Y(F$VkdI<q~QSg(i0Tho%D{z^})4Q~j!S48W>NbTbnUcN&_%tYEv**cw~mw3B2l
z!FSCYs*wu_d3iNa0%uAeg;j6b>M%u5Z`tb5kO`+=q5ta3GysFIM^}qm8`?Iw`Ap2V
zuVn(ZozYwmY`QXP`N9h8(l3+7G0C<Go(&atIqGJGmC7>~*|l6EWE=<??FvlU?xl_Y
z3Lyr#ge+XsF==f87vsO2@97D3C~RTDz12>&g(nk8Hfr&X3fpv<u!iMd0xi^z)&YVW
zj9@~n^kdkS46rK4h3#n51ka;@tz6JpX;Ze%DAv)ihc~+zN(En1edpprh*5G}qbl8m
zvFZ7F&DK=mr@1R_V>R&8fuxaz-b(uy9Q-(T2+Al=^k>7Ul~vAS^X#f-8izKAjSVmy
zmyIRt2&4`nyiF5z#Y>yVAfh{HM?%A*KJ1O8=4(NYWe)6T2Y+nr5|&Es`bGz^Ge%Dv
zFh<9MyauAh<}WkYp)8fc^$?bkR7JUd8oM2^6Z)RFn+xoKs=f>G{4CcVhqSl$Tcxf2
z#vO59tL<SojA{R`yP5oLY7nma;l2$ItA*XZ*Q8KEg?EwAz;e164C67s2MkI*C5;!*
zi-DF&IhPZS55*zt&NaI8Ho22oR$4}EkTJ%GZIH3Xx6jTd?&q~R;hX$OMoR72G2>5&
zNK;}@iD*BGe|LCGH^}>vYnb?xY-b7~LMN4WE+JDan`K9|Uu7PDKronCC4Yb@2&}nL
zk}DRi<TB0DHGeEv6*)!|xq+yEIQu7oWj6?3!}Q@W2&TgM{GD!JwHvu-U2a8yK{Jjk
z4xzd11kU0)8yr5{yBz@G0n@B4>KNt^m4@Ogeo!mLjVw2YB)mB=#~2v<NP0F-f1}G?
z0qL(fqBGTBa9kaxj<lHu0ZDHelr8t8_7OxLtl(<!5<$VbU81K$Iw69>e1Ks^qTU10
zY-1Ay${aYpJ%_^3SfUz?vp`dnxKME#PZZS|5vHX~)%SkR`*P5Z->Z6BHL+5bZG&6^
zXB_`2<Y!wOjrz+l-Mas7VuiB(DfD~!?69o(SO><s#sL#7Rbww?8i6SDEEcn75<NnH
z{Fb4Kj)cqid}TZzP?}$}J_P;-Ga!v6n!(#DTJ6-JOeWbuvn9IF2mA~xL>d|j(v9q@
z5Wyqp1EWZNr|!EfDk)VoX^DhimeD6h^XzR2utJS;oG#s&APzKh+)@d%YXLPk!bM;*
zOFvx0jqfpssa{jC#l!*EKYuP$Y54)e?<L6GBo6FxonbGGD!$+LzMgpWz9_wOwRKJ}
zEOkeS-@hKY!B9@2ql|SwtmqqR%=k5ys7I^Rx1!b@3zpGPCi(T(iVQHusDHAvA>Gke
z>@B=-#;HMrOhO{Ya;mKv>LO5+Xe^V^B27YM%k?YHrorVL>c4gGMabW`rBERX!@5}d
zgsuIg_1VcOZ^eoVm;_-2g?U3y97FQ5h#zqQUs2kC75lY{9y>;#%e7}}opO)oFWsI-
zLz%qaww5bIyLmy{aLVx0m&P{PZ?0D8!5FM)i*Q@S_@zQUAR7|PgIs?gZ8LYyW>&s&
zStl4NP3w%73&3bM+XmO4fG4Q1r?QD<F->`XgWfiVRAv(LMPFN?V<0yPGN~|PU|IDW
zl10s}_0{rcK5{6;clo)BT{}_cjXW<bMdizB_Z0V^P2_qIwWH{zWBjTsJ1#3`OyB!L
zu~<*>bj0Y-j(nc;Uqs#7S-N{w>ji{xU+^v`ecA8QwdsT~UuY_q689obePJ7~q8?A6
zs~d&1K&x+qXN_2V^G@4nS4UOptA1BClpi<Hu$A4uQ*F{?6<mKy<g*MDj?wq^H4RMh
z{X(1o2Nm}8YOPk$FnKK7m7csttmvq7>DJcXbiQAkoLq&lI;x!p7tq9rLDrX3F<yv-
z-k%69Q-#k??+Hg;N_0t)S%onBSfl*wL7MYm$9V-ihOsKFMZXlg<`(BJjx3=Q&UJNa
z;JFs<-h@^*nGST$q_Q*)C@FkR6e4a^Td5P64uk91gk>vz_Kh?6#&oy~!3W}vs##m;
z;@6i(i4{64UnvV8ECh1tA3j*5<w}%}Nw+I488dM#-TOC}Ps`TsioY49!^rl#ekyn>
znBi1}QahzeR_5-htBZ7h-oo3Y%5f#1vBr(QNcPLo<r$$lfjWh7JLL-mQ%Uv|2?uh3
z=!<ry2%2tXr9V*eY0|5&6lI`}1?6wMM1=MN@ns{8)SYlp?aFlU-RVv3rZ5P7+C4F*
z?cO96IChdRrcfwm8`mmm>m~Y1BjDNPHTv6!JG`?s%HUc>li}I9mO$KQM}9zZ$3L*3
zsFnN;RePLyp+<I}*UMn4ogBmL09E57Se<^IjKvR`a6=sjd#GEEHQNOW^iNdL;H7Vr
z@lIZC*-Oq%+lNCHu+c$&NejSDuJ>XY{!%Oo^*?Zklr4nf`@=@sj>wZ#X8SeqoMk|D
z4<o&!>wC&A4=i#K@hD@{D6rUREDX=711gzkf=&!A41cJy>^YAB0<+PR4$HPhIqRqw
z0^(BA7_ro;EP4Ynb*<F8!`k9li9LBW(#qLuQb|<}tG_79)u$__rLkjS(wg*&r6wBR
zrpO;lyPLMvEIby3gk`JD<@S<UaVkHLq&bqz*antFPb50ch*W~Cc2G$?vc5aCH1EfM
z)uGHwCrmWJW0$e&R?ME)1;0*TEq_I&ERI9~!>JhY+kQ3EHc<!hk#1+2u9nRrMP1P%
zxfb;>+9)A*kXF5{U<zZBH^g77$Y9Id(aa?QC55+#Mok$iu!t3)A+@>J<@c9>?KpET
z7c4TOKM)i)D2&l#J^FZ<Oy1lRs%q*KA7{X=kVDZ$joK=P7LsP0w*%Lvk3dN?(TFph
z&A~7!$t==<NRv*z3d74jVG-#aTrm3Ly_gda!+L;wC#ggtPFY~lO;1_M#zG$1c2@*}
zmxyXh;GEDC=XVxIDl9dW6yT?<1h3^|flWUz4^VA4_)Rb4eI-zGlK^{491^By4ncAZ
z8zub#0xB@1f?**P4WU3Pg9)2colV-fB~z?}xQ2_LRA(bvxXk8{U_lO4v7Zw2Q?%u5
zVJ`q76+c|GG&e`7QoY?Bl!sI%2O0;8(INm;K0^WpTgf(n52CUL)A(U7kQC7`iMa=|
zjcVk^PF2+i)LDPFpA>O&%xG>|UwEakrUyn*<Y!af7u-23YkEV<mV47c<=E2+s8anU
zEs9y=G<f{pR|}y4wq3F5Y5nfy(%c@X+RuZ{#IY>|J=w(WNrNGry!=18FyV(*=JZ5W
z&CjNRy0Nztp?P_$>Bz!|q;q3u{6*%UYNe4+;awez{<us6gN%$N-U;}tX_$tcyqAYG
zHky5;dD>BTZ-J?$GLQ_Z3@C)MOuj#|*I@x<vmB9(Ghud~0<d)&a}D)Q6{=PRIg8rL
zQ%=rqSTl9mwX}$~sCgpuDT9H2O64JnZ7~Sl*L7J@-A&4%8v)oh{B#gHvUSPBg^aYl
z_zYmsHc}aTz%h$j>NXG*tA#%(*hMM%1oV0-jAvZw<W)f%E;%4OY%L>)r)~5kQJ4el
ztW=15C^*f9SfN~NAE}ZA!U~}|82e0xbY3zaTAeLgqR$`2z2|4s&ayFfKNINKfo+@*
z3)FIf1%sXk{ruL(ukKJqVpcLnL>D(QMk&yTlrmUJu*LRjck4)ZS!;Bk%?y6HUusUh
z)d_kNe!W7dx=y`U(?5Hm`;AIFkcB^Q-^w{mfChyV?})bP-2cf&y`t8qa$vDDwtDAs
zV`9_HxzAmbZ2V&6mw$4fbH`nji=`0jF)E62g@P^@82nPsaqTY7GnoO9+3esT{LEcE
z=r*V5UIhT6mmJ3d0K`bR<~m-PBkKGb4_qvWU#=;ZYF*Rx^r2mO=WBouNvOq~m^9ML
z95~VOdH)7KUk$@*R!sV6TnGq-jJJ0xo04=0{~rB6T$q&*(O>~%I-ccnX>-nm;yM9i
zF_RxBc`rB!_yrWumnP|NSmB^yQkW0w@(o&r$OBeiH$;1G&C9@rOfo^M1-g?S%HcsC
zrfqCkF{z@1jT^rqE(FxnT1^-r?ay4;bBHv!;z3mRsIN3cFp*O3XbxeaWJB-n18&+D
zaYYUI5aHC3eWQRW*h^SebH!7ge;fHTNqxLu(MI<0udtZ<qB<{l)0BYpXeO5|>sOyC
z5rECqTGi6q2Xok%FM>I5lp28g(thcJ2Wh3UPI>aO5E_&KJop(WR(<FBQMt2+gUPS9
zI$9{<<`M+eU1221Nboa?*Y3N!O+6+*qYd?Ev_WRrg$7kx@Fz}OOZQ^|_&LfGC3>e!
zZ+U`&4I}P1a8Q&mkZ76H()id4*iJJ3r3EZ9hEGyFM)y(RHA{Iyyu%6VC(-Xh_(8nW
z8a28`yx012Mm>y1vPFu_#_>$1v4P7rnDNWti(h1&zXTMkjy^MRPtgbGk8Y8LF8%UK
z+cXU6;D*NgpWt0Krv_B-tTwr;#H4HAJyA0-4&)4L-CkLLj1<u%L(3;opVf4`gTck8
zSi@kEGOQ#O;e8gRX!qpm;hBDn6g;jGlM7KjP-?O0t}~i^Hl?vk>({b>G=`3l#^o+B
zdZd=YQw!Ew<W)nB<lL_bg5a1oLUqL@G>AO0h`@$lQ8jka<k=1Ss%ebcWQ{k7+_9+1
zgm%v+HHZK;E)g3b`?=6}s}fdEf-e(+?CSf{?AT?(mq2P1S}kjWtu670hYQ>xN|$IJ
z`jKmO>zz_&J%!f+H->f=N%R`R*`yIui_UNo=$GrS)=$-ijudtHib%8KeW?|pUMTf5
z@>g0-)96>6W7bEOs<2>f2rcI3(l6gu7K5~Qcy6(JG+;=$5a^Aj8JyK&@*7asgoLsN
z&S+~SKnHG(uQmzqsYgItHl*Kp-aAR=RMNLni!-r8YqQ!iK+Y)iuxkEAA%iJcli)6$
zDn0HkFCT&&1x;(!2!s~Pd_4n~_d1&&01M<!-17jP>w@3Iit*D0(8KDd)!NjECGbdL
zz6_V^LfgYi-)VJefU<jA;%^f?#a?coSdj)bU}uA}^%?`pc3K8Lq|;Tx$MJr&XR~5j
zzuxlD47|V@rJpXp!P2xm$de=cJ=um<$Msy)npXE#+y7j%?LyOUeQ-agl4N)yr`0N|
z2KwdQWi6`?-U{5YEiDP1u<176`DOc!STkTf1=e|jyU~eI?5431`q$?_$ugLiB8Ro`
zZWo%4dzm@W6(bbAbzs&uPNkYKjg2kJ@X%UoQdJ!zr2|WqB11CjmzvJ&;HQeU4IS(i
zL9!J#z4sLhLGaC;EI*b5tt1vSZO9Me>yxT~OmaHu<G8NXfFozxk(T3awyrF&=4#B=
zH$qQxy6fX?|BQzW?pS7a;6)8Igr3G%@&?Ufspf~lhs?#)3Q$|wKJ1s<CeoNh?>E3_
ztp-9kt?zM>UMO_l?DprU#?piZsWCRE3GH*)+4iR)sFKA4GsNd)NB2UsVGCB772tz5
zvRSweIP$V;Me0|Ep43EAy2Kb2BP^LDR;Qm{$OVJ-r&KYG1}Bh({Gi4>+)?)jC(_B3
zs@5+k4}gZCwMx57gW&C>L4=y*Ow$)29$X1D>W1yoYoG#j+M$U7k}@j5{hmm(SN*r$
zPZ88$^A2g0<)WRPd;EXd%#G^XQ?!CvR@FyH-ew~4;G}{ITv=aJLSNzt60dY)t+Bcs
z@LR7n;sVBZ4pd<Mt=H1J!4w)}rIEBtZHZCbxY*a4rH>+WR?*FlHbcuI=`SOJR*D=q
z?c;#Ego>DDLhU+`0c&2K=<CMAKGIhx$X#p&7n&^BgXGN<FJ`S3T-rDRJA-(FcG|AC
z0m|TZ{A;Yr>@$t<=#$OO4wzS>KW#=p?nQHKXdz)N(#zfQES(ZXlx-Fc=f0XPXcuyn
zLt^qJIi>@hN7gv$FsRz4&p0s=|6(2jvV+UeI*g~XwKX*G{CdLbU&oebdrFyI<FpId
zj_h%o18l=zt=qPAAGK^a`)#j7-EKln$|MVM$@UdYTuow8vgvfKVp2Bs+S_%{FY3yo
zm52srlmVX9(Vg%hiP)iV$DU`A!MCP7%Y2Hcf~t^nmlTk2dTf9pIX*w&s2x*B)Yz&J
zDU7T|g3&3eeCP_NLl)V4in_?4pW&1-&q<2<olRLGlfdKG5J>VR4uWM!cX$9=u5HvW
zZhueUs5x_Fln<5gP<?(Mj_%zQP9LTi$ggu7*MlK%r*6AKCTocj=+<tBpx`)^1(Wde
z5&B!fai0Bd3)5x6m5%T%^CVp&J(94TY*4DmgR$#9)nVIV*#UZJ2BWOogvqbCC~-ir
zuatAbtn56aLUV1{SM;wOQHG+<Xc4gfQ9nrJy!<NTrVcqRI?G>j1Vpm}G|_S=I*rOW
zRT*IK+f=T~g5AoOgD$<wQ&f(SdIp5L<Vv4lWr~k~ytcKrrR&<ct&o%Mr9cqG<3q8v
zU>~LM@}U=aY@CcM+MDTy(z{6?KcAkM$yaSscbLEw`kSC>VJxz%t42eYzAYL;a|VV-
z6%J;8q2;tdQ*fAJFkl{(!5iw0yDURAdyO($uSqQ{J8BiL%HOsS?74?GqD$1KKwnje
zFJ$z9pQvdeItqm|k~5*&j+m(Fj+a66?A#wgY#kco2%rm?bSFJZ+2zS!`|9|4ZqzU5
zNU{*TFrcAc{|;T2;_E1Kp2oUmzZ3JX(>>#1=UdlgD;169XV*GBiQr2|XghEoL$YSp
zmFFDIDm5-`+^QUg>G;ZQk>N0IaHW=C(y3fGF}N>0Zv6YSn{HdJ$Z0^2V=1JYqH{Y#
zWAOURmbGiSlFkfXKhH6*Q1tK|N|?A&odMeP&NuI_91e;yDK|QPlNc->>aCsXVoQWg
z*^ns|R)u;(M2=q8JaIbm0!wu6NO}{*Zb1-<RmVoCcEdy+>6lIEq^;cMSXQm^N36uP
z$5k$mDXYY(+<_fA;jG-}L`T<|%Zr)6sL3b-6zb4L<`q-?oQMM+Rb0K-^p8}*I(xRd
zZt7Nm-ouA|(-b##PwNj5Kr{T{fKn#p(H=^3m51w)Ub%}qI&87WH+<$;Tol6P8v^kP
z-8pQK^eKcEihy^cYi7+k+cA8vnU`|m2}Np|hpqueZvC?16iwvJ+*=ckJf>`;zsE?u
z!kMC+3yOk3q*B0Gx%BQ?1GcCyA2cb~Y@o&J?At4l3!_tUvHS>~m2H0pA5^L8Y7OA2
z$or~skD{&RUmhi!;k+PfZo@z8;$$%-@FR>w8saOZGgYhS7^)@+>%QP2Zu`TzEIdx!
zN^fy%`Vyy(v_XYhbTk$v7(06d{2>VfI_LZLG-CJ&?#d6Bm!6sltaj-QyyUUqN@dr}
zRKrp<w1IW;#KZL<r%>nt)Tzyy7Efu+Rx8-2n(-#<XN1FouUXJ9Ko)66d0%~bN;mMO
zS_ZxAj3^$#ng%>u1y>spHkIVp76m+EEY>*H<@~}I@DhqsgmPjNienlpjEs0oY)+Tk
z_#m7|SGV{eK63cAMjMCfPcZJj_p13(fPov8;Rrcjagrv14F}X#6x$n!e<}<3OPT!j
zY@<tcjv<VVfIlaCl1?a@gBBztCBW8`gIu2QvkXc}Y<sHj+>g3$+TyPXxxsu;;qT{2
zG=(R%;497vvq!9Ts!u;)own&qfkL#7C*@w;2`{T8eQ&qNpNzwnZYji=UOMcCK&uoJ
zeh6R;qBVLXV#EW@_d!aH`cb&J#(|!s4Mm2Z6;OdHpWZT>z_J&4#!HRjMV=$?TEX=s
zLD-s!h`Sq_D~s4WTXR*a0z6UFqsociDF!$|3izE;oBgByP@We?XZ~WuA}rSrG@%F+
zlfBYt1d*B9BVtq`ONE|ec@5G~BK8z_FQ1CP@^&0sh{<dk$jJNzu2TPK(HSzAUYD4Y
zpu5KpLGP{r^W;LGd|-MH>qVG>9YkBViXEb~Axh4L8uZx1<YZH#8m@NFYyQC!PTIEz
z7sg>NsxXYCkynNzm=kC9rKZ~U2#&$+XgWRzo2Z(jKi6p8gLD&%tT9>0m^0Y42?djF
z-m08$X#1lvKn*pZZbbqLM|=0-nY&jAu>wmlwEaLIGRUeD#u4cWDk_#inAPbjwvR;)
z+=4^<R+&D%uR-#Bn=iyEkCO-Gs28OsQ}J2VyHr{9Tc<KL{bYl-P6~=)HHZFj4ImM|
zfcSzoMHKsK`~=RT=anDx@b*0Sxkg;llL#bqG(_D3;n(x@#6AKLBE=Y|Jg>b&%hc=x
zr$r-Pca{?tEYlC9stLk$g4WS>0oGQ*u=*_H{21Jd083QEE)H`MfxPqpWmLL%4LU^y
z@$ZX06fh%GoZ=$C(j<*W(LOW}d%Yn9S~P}Q!eY9A9?pb+>T=-x+Hb{`1ji=S-uU@8
zU&2TCGv%h&iS9!FsM873<)}tmJn45D<!*^xD8?Z>JZ|ghy4t>eZofdy9xij9ebGsq
zRgKk#x$((5`zvmx(?AsH>@UGR7+^tTcCiE`!#)n8AL5J|YFF3IrfK$kJrbdJ2kfq>
zL>(L{LWJ&`kPhT$4eQ`L@|blQwk0@ocoDhuhIE)hguxjY21k-8QV?L0`-|~(sI$#3
z>rr0@mA_+nR(zxRSt42WpgzmiLm4VW$eSL(hMH5SV}X@gM9?j8J&)_06N6q60EhY|
z|2}BoJ_oZx4S+wJ#{(fo+8G#xZ60ZbhLA?9`pujv&|wt*IhcMa00o**{!~2`>Uib_
zggMORKz$u*W)hbQ0KAxbndFn-secjZ;<(a|;8X;SIMI-blsI1V4MjgL)44-bCXTI=
z3GR5D6FpFno3TnHA1V3_bJRVkU;j+oKnEX`Pex0*nV&L(OS$cf+Yg*8i>eNaX%9h=
zrl`KAAweHx%GHWEPw(EM6^atR9<6zA9LiE?_u~pMW_xeGs}+ve&4@3B+NbQ>xI9m<
z)Jm=;T#I}{pEOB4f4++@rPjj5M$({$g_E_=k%6_fv7mbcS|{&9WTR!azxFVG_B*O-
zWIi4Dm*(YUe9dcp44QlO(bqyzAnCdNLxkttqjfLJG#P!9hdb+OYe9^3uD}QojC9Y6
z>1^WQ#|{NX26v&cXZ0hg?FQ(C+!55)<#nY7idK58R#}CxXAEhMU}t|uFl51{6apz#
zi4-^x+3k{>QesvGLF@*EL7Af>$DyKeBZ0EcP#|{t{m9KNe8nm?AY34tAIly<btML;
z4I`-U4Gn>jB}aIrH!4686+e$a^v_&_n5}sxKXQnz@lez2ncslW49l=nfSLnm^1!U<
z)K8eK8ekJLV)QElVo`K}aHB@+)!uPgEX4~i73=RY6MJ2|^A2c$5RL>x?yT|DJcB<e
zcSdvS{=BG1BLawQfvA8xcuaiOpYF4DE@!*J%_dn~9RiLkiNV(OkAr+>;ms`ApZSZn
zkq|Kwoak^6HR=LE3)2s<Fu(AH7NQ~b@zS>mWwfSjZkk;ZHfrMWAHBwu5r{}3pvj1x
zP6v7<Kn<Df?ROT}@rg5x1oR-l57pJbB#B;Pi$Z8X38bzuZw${r;|OI@dJ!iR+C~w9
zro|4$WjpYz-e8uUBidUEayI6xlxbcA<&)YfMNK~1ITu_>P&R@-k`GNx^4TvruInJu
zdbJkbIZ@vqaAt?|Utg2~Kn7k_(U8e@Hgiu?xZ|m@!ZT4Tc!Di)nzA(2U6b{o<wp{l
zV=9R_#P9(qJW0|#%k!9k=-}bXpwSS03GwNNl-a^TSuXobSLTNm1(?bi!9qujDis9b
zZ#L!Te-Uak)^Dq^{&i%L&?7(trwk@A0@_+0<^q5QYe))))+Mj`zAEM#)*wHdQpWD?
zMrE9SXB$G5N;%m9NOC6ulC{{3*6EHz(E2uWr2#{dy5q6|0ZHkvg`P2}bL_YHfB|tt
z*BF#OtNEeG97=4n&7p*fJck1wfVMMr$-TE(nP`{;s8Bjo9%$=muGKswRP>B?G`J{h
z<#+hIVDrh9i4y$VzAa@m?Ez47m)I9TY!Oy*Vt{nopv8MLjS?odc!A%~3qY)BS?lgW
zT5+WoLBTAu(nwHNtBrRITYlR@bm5X*8OA2RNX>9m;ri0HeKuSZHzcEEwClRC=z2Qu
za4E8ab&R4A&nB>B<enQO1xuCZ9Hcu-E1NeEK~#_lC{7P6j!4<BisRJE=P%%%kQyvs
z&hQ>zYF$cS$iKK~s*AdG%V=~OQQ~goMZ)W!Cn;WvAB-nSUjjLqDiu9S&P~>`W>Nvx
ziGD=pjap0GBA9=%k+_Y*`EFxziy&>)cp<`<6ltx3+I%zQOA9CX-k{Xw>g(85xWyHh
z^oQ~v@S!Kn!eY8g+d?CZW4PKQy6elf2zj@w!Mx+t3TrLpMI)H6GsOHv+`0L=yV2@(
zdKFpo*v*49)T@Afdr>hq7fqtqRBqmP`mI2;^V2o#(ygV(T-{kKU+(cXm<C2U+t~_C
zTc=qxedlWP$A0)3VlhXz_V3ovo8z-{)#diR)>rZ}iI9<Qp3sPqYQ9vg$~6z>xTC@!
zNTP(x?k%^HdHX^-QM-Y{%9NL01%1rwUVhI_;$C53yjcHoh_~JIHmyj2cF0}Hysx%F
z=n7-~h|sEZdqA_fT*J<IjiDkX@qj;9T8Qc?R@KE?YB&^w7Q=nnEz$74;~r_)Xiag2
zK(Ez^>IRuYg9FpvcVgFmuGz(28T-OhJzV1=@lq2ZeH+Wdddc%V>|v*c(Ev|9i;F@T
z>XJcYvY`->NMo>JG^`4Fu;c=_awPnYZJJufP~=91V_czdNW~O+4H80MCG)&)betF@
z%dVR;0y_kYl9tv-mwCopbR*4Vi<4?N!qRL#dWaCC`oNmVT~=dz-3E~a)kN$pMnhz4
zafCoEdNHxWYEI+nTDcv)*KoFR?dn~w6`f(P<7A_iYADiez5J?b1Eg7CgD2Erj}J+}
z?%&Rq9c#;G+XHu{@%i_ds<|6AHCA=8)XeYaF+SbL<l8O2x5MPN#l%Y-*xcFfQi~gc
z@3;F+OUDT3BQLwZeQJN-KQ6_8|9CBb-<M6SI8-p3D2R5Nd425a`Z#Iovh1>yGuZn5
z@Uo=m^?Ph>iSFZSXzT4}tMhl;sa<E6>?O`&1uskU=W!m+*;77?$v!V@bid#Cxa6vS
zzejKBv5^xzX7XG<>e*%;cg~>6op;XsYERx53h}u{{Qbe#_4d&<IumKOa<WTtjWxNt
zYTNX?pg7at{0<f4)oXAD_5OKz#^?D}Z%l!YZhk7f{^-%`L;c*n=~3>*f?bz{4_@ui
zdvK<YJA!Wx?ECu|!}sf<t@n#D2aO8AGR%eh=E?2QRk6Zk_Cre)?yyOmUf0O}q2J@@
z)qNj#x$F+^LUViWC@vTKNy8(0SEQ51wme(s%)WJ{A9H%=YL(FsDrQ|5<ZjM~@e3n}
znxk`7W<R0lv^t}J?{}?90$!6Mlc&8>Di)rD)EWmt;R(#jgT8x%7x29zN6jB=^1UOU
znR$T?FL$WPB~SZk^M$Uqo6PSI5t!Y5?0)I+QTnkB-DNWG_ZZDY<mKfJn|c4XH^iR1
zti~()n}Y!K`txJeXxHDBh44Y-JC{m*5$pV@UPno9&O%nY<=jouBTD$jgU5iM(NaG4
z#Kb>ua~3Upz1;%Pb9t%Arr{B&B7|`2u6THsZ>ZH7>|Z8EvI%;p*zA(W*4kv!ywKwm
zI6Z?m7C8TolNgFW)P1b9uzo$(y(;wnfVCbzX{Tg6Y*Mye)=E<5eZ4w#&pn|E7;yEm
z72lGxejSaW{6g@-ji_|0vul2TxOulC@pRnyv2Rv?A5=F|h6+!hW-Z|Inkd7#PGAaJ
zv7ab|{hPovplF$DZFx%(8*|d@x3td<YzEi(E|uQ4S;P};lTsI@*`rp%?Sl0(ji<@n
z!%E1CJ^6E@OmPC=D60d#+)9z`iFXP-hQ}3bJMGicJjQUiQYYi;TLknp7~8c9$B%~Z
z>Mb+s9L6~372otG9(E}%--@s<14YNE(uK8n$Ae{1y@8?ey)Ixg@PexD{Iby?+d<GZ
zE}}^T)uG+So@(#9ybN72b=O3n;(yD_{3akgzldpdYk4t!sg8Sm=_wbuL0RB(sZG_p
z+I{hUO!fP@#qRmr@qXgY0DkIo!7YL8isa_+w0m*3l;`AF)Xoe$o0gJ~`_hVHN`B`I
zbf)qu%;isVUD%Z#zX{9WDF?8*Zb=g?q87VuI*s1^@W@g!ePmm3@+ry!;C6VvGJ2~|
z`8m1RX>3Vnmsrr!uVoVi@iJ}TG;i!}tRx@rCcTo0-{cFty6S!G9p9Juw0|JNi-}Xh
znAjRSIXjvd*!(Hk8Ct@y0O$dKz5@UN77jKB_J8?I|M0oF|1{BwxH*d{IU6{e0RCqD
z;Th0>RseKD0ssa8osq#O<>mb&{5Pc&wX=2pZ_=Mhxis_u)=#yH{|J4`{WA#0{}=<%
zDZAU706y;?GBW{?02ux<E^pvy@~MmA-@bG*CdL*9f_82Itxp#H=fF7t42<;j0G+?Y
zg+2{`$~ys=|I<Ot(ay#GzYXSZBY$!Kbou<EQ~EURXkhDP|Hqh-`@d`nfU~2E$-gzB
zPbp!OZx%)-ieiF)nE%XG(ZtEl#nH&b3Gl~niZK5*HMY<CAOHUGl(dPhnX@^7{XfGJ
zwXk+JaRktbT7P<0*u==r_%BQU2r>ZJm^oPg==x{L+%nG9J>5`68mmr}7I-#zc;<Lg
zp@~z8QQ`=ps{#XofD@2~v%&$uDC^Y%hQbN3P&Y^#x>5k&V6*8fY!ZNfEki95{^`lh
z7a>(w=*=-S3^aM?ueG|UY@~^v9w4-Bk50ckw%$9}SX6YXDmklOGL?kL35CCgL&bC#
zl%f>-JiRUQp%_*W3S;wGJp2T5r{+zLDG?PcAy54{n#bZXl_TsAv8jEWAv;L)y3kFJ
zzE^{0pp*M<Y*_OP&nr0Q=&+{h(D;nLk*aX{JHZ-7eDP%3t8pO%<{DeI&Rc)I1PV0A
zOmxh*2kiJ_*$l4C#8IZ|cl1Wkxoj_E554^=b(=>9LNCTx@gF7nB<(PzD&p3|Bi{ix
zi1R%dk`czZcIIcY<H3W$gX82>BQT^I5+o7KQ-RF~RC$69-oGc}9XWFgQgjp0C8ZqT
zPk~m57$j5Ne@XAnjh7JXDb}DaIf`g%22sb$K^g2mb0o-<@8JL$kOn;)1_i2!<()ys
ziM!MpxHWLm{YH{SxTiJe-i#17W;WfZ9>L@#?aBe&xP)Mfhw&uQ;3iA4`Gw$*fI>Gd
zwprMhR{l_(Dr6bLoVg}+_RiaHNPx_0139AjV=(4n+**sVPOXvdxv$PFsM~!_ldi_F
zfGSHGilk0`fRbg`s4tAoItfcLg_>2BN(K7-O&OGLMw+9?x~Q)_|2A07^A=xFb7HZ{
z17kgJt^QbaC3UDO7mil1bH@Dpw+Ymt39BSBHX@``+q6s(FWtELTq8?a5LS<ayQ7qK
z0aafAlqCD)H(D8H5$4b;GTe0TkBT8Z&&Q1=(XN!Csn4S`)@>cm$GXDoK>b=TQXw0y
zIbvp!pA&{13%WA&$T%&;;)E0&mxX#K8?qM8Rl2x<-#VKghVS9EvRQeS7%d=27<pDS
z@W&Dq>q1T9_7J{NRIJvzP<=GozWbH!93b+ArYrB~3wN*wv}BnYoe0$R85WVFjSWb@
zP-lu|7fr3!c1lGU!D=8o%&Fx1g$XIr>?~62eC<E4UGKM1mkn5^OU^w`o11m9@y#tK
zoq2YAs*vKdY=tW>8s*2eJy?`k`@;O0ct>QofnH8y*Jd03`s7fqQ#paO8k}ggpJzYA
ziyH4!m=dM+teWYwKnn{`=Bz`yPFSulY;_JdC(h~^k-Pf7DsI%yshgfh!-kG^3Lh;R
z1C`0;l6+w+<{dX8y(xQpqHFe(YB5t%(L4-QA2{nmTq!^^ENe%ag|mgT1yq$TPROZ1
zI%&kyiswFSa#OUDYAMrVLr9RBI0(=$$W0uQ5M$)aDUM?e=K}8%@{^k}Eh=fSmz*^$
zI(~?97Z<S%(bDL?W)eir&oe<qP^w^L)u?i4U1ZT~NP9`!6-%R(b}pG?EP_!j^%dMD
zzjH?8xXfAYSY@)Kvg5+?l;<>W!IDQ&9Hu4wTM>u3;XB2Iszqb{_q|}VMLq^1IxdMj
z9#JxR=33XRN?gUXAyHO4Uo!E%^}7KlPDGc|IltW3W)dpKI$w&1a3)HHYT_R!=#%r*
zD)|pmOQ<1vng}6`{7RT62sd1`8)Xs*EACpE7wsXzYU$q$L{O==a@9HVmV;R*Oz*75
zEgw-N--jA2)(%+)>(vkDI4xakE>_haa^k8I&FhZmtQ#4nJd<c<boJL(NKG;uMb||1
z47yCY67e+EZ>_r7)mV7Yz1E8dPmZT!As1vlx{rjMaxpG*@06YHrH#nfhagM)?qU@9
z2WLP^f$)XB(Q-NmOTk~rjnWvBX_;B);74^e3zcy$u`nW4zk<5tNRChr5R7J{g%2HP
z-R@Mgdu4SJW^v2SS#VNWwk+SUR-g$L7%0}K2#hH}R>+hD&>_X6GE(ow6-F8}<P-L1
zBe|x)C#Tcp2ih{5nkZ`heC{Ga_#)`S9tvt=et)8a6h>r8#865>LRo~ZSX{oQ(tu?B
zCeavY{NOUy(3)fwN-1;bW~Ox*0_|sD&08aGI!tv6Q{$|DQKk}2nHDj&dB~6+&1U+m
z5{hsLXL8xR(MNgyf&2&htS#!Vu@G3ZS8MxlTgbjIA>USRZgPdZ5$M8C4np4X%P%I9
zuvP1;jK3TrkFSQLBu2lAAk!V=+yqE=i|p^yS~ZA9dst-#pIn`MC4p?2G7C_%UE6e9
zk7m=vXO4KE^Rj!kza^(yyAfRjgeC6bV#LkHUX*(uq()XPEFyTlmo{zXUe5H*Rwn&e
zYwFS<nfOikW;s%DTD?|e05MyQWN{V8&d8G>=%q~K@^iaWjht_<Kx~!ZW}Z{+b=NDd
z?-0;O673no2U0K;`^rk+VXfQe{1xOP_wM6*Zny9Ha!4=w@Lj@ZRqy2Tlwhch94iX0
zA)GZ*I)ARfqSL~`@)uk}8XX15M~9cVQ+KeQGpwX=0*uzO_U=zU_Wk+3_)Q<}b);f*
zkK1D9(!_6-CER;)q!B*1%F+0*oG!T?rK0&q{MR$rGOv#|b?#{^9zU|X`Y^2TVj^ui
z0fU+F47_s>;1jMd{#sf_sn~>HDHH`yz-I)1^@2-^oPw{0OrlZsOE?Hp7vDZXDNt30
zP6^ZC2^v}8;wh5ge_8AQc8ye#hiJ5lHFIr{V3&9%qWM<fN)Ca*v2l|7(7AB2+APD+
zzl*iLNx@}!87>x9TWc%)c4IPM<$j}i;FlLD0{sh&pF<=gpDxb``#STeL4Kr^x1O!}
z=BCw!Zmng%g|}*oPe@a1YTTz|DpyERbmK64$sh@zJc~Rk?2-X5Q@tIhG}l=3l!QIV
zLyjan<ONH1q%c}S+P)+%FH%BU8Z+k@`p3AKqy^S((#z;7LG5y`enkT(jldkrF6s?`
zMqeR&J03*gidkOnHKQd#wiXfEmM&9Q$3aV^PGuF+WP-THbZ&5gq9$hA$<kZv)(U)N
zUijv~irRVk{lY8fJrHz`tHj*wovZ@ZCY)aJQGH;2{~f=FqNHW1YFRR;6nu2#bR4l&
zErKk4H@Gc5A%r0z!W*@&%!K%5_DA?#&~f<eQbEXERdJITRGNUdjoCa-rZ`H;6cyPP
zmY4B1^yKjjiX81v>=sWijg>x}7lJMKTfRX8&%C|8ev)#66`a-Aw;><$m8q9YDXFnB
zSa=yn7mr-)F~7Y%HYZ0IQA7eX=VEK^+Vh1#*53*Nte?rVCI%T8=P}foSCN$qlp1Fa
zPYs*%au)*3H5)+wyfp&9lLSP)ICxX<_zjgg{9#c=Hym2mr0a@ow`#U7%TX|9J}N`Q
z-?VR)mZq{g5X#ehXlX+c&B@XX=j^eK)+u7uZ%^gZ`gR!As5K7s877ItomjhjNPupv
zR1OkG5DLPM8wvA%Ka)N7UD$KMZOBA|TGLeCN+w8@ebtoQwTRMHl-ulMP;ZS!bdE^G
zPc)TsdQ!9ir*pNAVddgY_F^p2PTU2E{=znw^c3IC+?SP<Ta159a7vIq<iR9_vkXVd
zKomkwA16>bxH_IxsSe{KOQzbNlw78?Q$gsqOF*#~e0F`}Z-LRPE`O7HCiR;7P3lUK
z;nyk}J42jEszCL8*EY*Ks<{JD^;(L1r{!BxB%QFpn)Q<Ks4DbKuauXi#@a84yNeOq
z945*-V1X=#;lwFwkm%=4MXoP#I34yNj)-iIo1^bEX=N@ee9__J$Ez(aOzt>XQy=e(
zhbZV1sFlcr+Tk1AAne;C<PF2PK7Qj&F0J^r*JNd7a=C?VGfpn*Q5J*$1Jl@nJPTVN
z3CIWtSO?k(CS2uYK2+};eeqa3eY@sRPH$-77umHq?3di+F!C!$(6Xy<>cg`6FS2W~
zf@GP_L_*@g?h)gJR6oARaK%T}Gu;(@J$|2jjdZ9F<Q2&dHkq&XW|Q%^cD5R6Tp9<~
z5Ley{bvl%7lHTq)kdoiZ=+FwZn5hY+ZUSsh2%pIa+08~i<<%>))G#BVJzyEQbethV
zE|OIxs=a<I5PQvsax;3v11%zG|527<n;p`%MLyq%)C3$9)okz;7G!sSScNFg+Eqx%
z(xJD%|A*fWu_(;f;<V2M#XOp;HkYR1n%MYXJs}@fuAz?u3(&<ydmT*o6G|c9F1V^c
z0ja~G_UFCvIq+<SLnkC@?#_dJJO3V|jXKIvp9Y7ejAN$5V&`=NsJEJf)DG5cw32*-
z;o@v-*uug7K><%bh+tyJvT=+Gc+usyq}Xa<X_>sVu1sjh_K6(2Dbt(WHElty_NAvq
zEo2|;mctG6H-^1ky&20ctR5NcQS7n7YlqRfGYeiWTla`wsBnWC>Zn(<*p(Zl8m3*-
z=j52#6p|XLount%_zeg2GP+RFw7K}Z*7T1$Ow`nA#^dt?WVat9Sx<GzQa%pfF6Q8$
z)k<Bbg&1}Qvv@oYrW?GAY_U0u4ZFLUHtH%rJ`TBxhr+vr-!wT+T8MUxl*GT2lSq<^
zmc|F>?^pAA6k~l$a#26k!*l*7|IPrd@LgOo0ygjYt6lO}UXc8zu5yOGimxv9x@93A
zszay7?G}r~;z37`wp={K9q^qb&E787;TUnXd4*+YYfV+%(hJDxV(m_g8%+n-a^x6G
zd}uT~*mxqlqSnEkA$lIy!?758oYWKLGRNed$a;M0<eeX5W;<iU;0PTqU`>8M1v^zm
zo+L@JjP=Qv@mnMl`=E9DvKpYvm0XP*U5lJ=UKQVL(d-i48l1@nOjc#5A68j~nrv8R
zYyI93Nc|h*B?QQf!ubp<NAMJ<&xJR#d|~2LD^^;ZCen1c1|~_YBu=yG!WzPt&XL&c
zHc{EigMaF@8o$4gNG(Z{Q6|$>t!uZoJ8I{c&fr{j{T|Fq;}417KdjQ_(fb}Jo6%rA
zLOosp|I2sz_b5Abyyy-WaMcmNwlSeaq0x~rXYxl}WxT8;1_&N#svobPT0Ccc<Ld9^
z7<zAC^j}Z@TDuDDS+BcKa(t+d&HPly=&kTdPpX_hj`3a)qQ-vjNOi~M2Z^8%h!(;b
zu?w#L4)5URTl}eIw>yN7#_?V{ghrA1dm6(<Oy{dD^}YCppKHu-pN}CSCvlpdy6{a~
z#1%nTgL1GoGkrPrGQzQ8rDdmxMZ$6Cfli%0PL6P<<ao~IJ}5lV+M48;TWumXbNrQP
zt35@!i2*HEgRd*!AArhDvg<r%!zYaIe}+yJtXzE|7;-h33_^*6^mZjGEyNg+cEs%T
zwPqi^FrjrsJ~2RS@o%Ho?utr?r(`6sxSq8z&Slo~0P>W*_E7v`fgQD!pO__bf-qOO
zhwF}?!W?Lwe;8B6d4s0`<31}07GhlrcFY%KwXpk`XiWO`4R;|lhSP{ZG1`*{mtr@U
ziVs6#={jM8%)LNT^s$n7m$vcq7CobS1zow`J?b}H)9w&wEGg5r6(q$?QebkT{pN3l
z?~&SqhlH2k((I~eCk#ZK5ug3hC=hp7$*iO7r`~5lhZUeX!rY^*iR8SG8Oent&u82e
ztKf{Vo_H#AsQD|QQz1BvVHOYKy$gb!gJ2Y+s6?I;J+CjX#%Rt^_F6J{sl3Hbe(A=2
z-eJL#z=AKm28yq2JjtI|Al3ad$zLeETqyq*^b(cW<@`o&!nYKxY^21}NH?dk!9|(Z
zqr%_vqAEBiKMg#d@42)`uJs!hFD0M+2IJADRyhJ?E5_^Kp3#D>0owy&D;uM!o#sTq
z6ON`bUJ5fu^{jU4x>@0~cy=YRzwd0|sth#70Nwg~C&`bfQ21;fzMF&d#|gwVv1XWg
z*nZw?8$Dr3ld@2;ZX`B7bL?}<=7rynWDqp<!mYw#?p!xN>chN3FKtqijWVnA_h`qx
zR|*$NF+~xa5Lbq<N8sGSQb#)W=uf4Kt`Q~Rb(7`lBpo$JN$hr;9yGP+)%0nH+D{gB
z9}Tmjo{fm%Eb3>Jv1gL7@`%OGM?)=cn213%BtdHx1D`#?>b=H?(@~}ZQBEh}p%U|B
zsx||g8Pbd1vpoabFo(Zpju;Dz!RZgfHZrHkg$=TmC!z;w`XEj31$BY{dZljG0N!fZ
z)&gb&ds9Q|bm-Be+V()|)OAPvt=ZiG^Hc_coxV*cb5-a|_tL!peAVJRRl7a9&+sM*
zu08l8d8oTkj_Ik8^obdi7x}8jH(cY&jLu6L7z51f$nUo{&|!4957ZM-u}?M7Bn#ZZ
zAv%AbKKpAi`*+pu?49jskWGxMEMGpTk}6*&7wESL-&Qa;Hdt9$_LlJ-vUhtT>?l}v
z((Ol(P4ufI-z{i2rEWWLTr_*(ZUb0^M2KfX;0DO(D@|ZXMAVxAvF&Z5Z`*7F-*f2a
zVIT$1*aVj8wj*Imkgr;OErGkxtE(_|oqEbW1Kt)4m)nN=9w7{(A$0}v^ep^0Ky=Zo
zrMhJim7$lf<H9e8{gbt?3>g9)B%47RVV4^hMw+0PPXcMujh>PWm$fZ!CK%)`dSS7-
z>GYL?df1>#==HyTude}N{porQZ&AGoewwC#p7zzN!k1+~$ZG;wy)HD74`XjXNFLvC
z3jCJ_aJibxZaMhR69}r<iNr_#6`0IqcY`2=u^J<HhJ?HV$$;u{e?4gR*8UwSaOxWU
z8eb6*bQq|H562#m4=G?+^lqjBdcLWlL&#qiz_(!IE<Lzp<BQuAz;$W*rYPJiU`%QH
zt-cl@A2Qu25?9T>6pKK-CUD%O`ZpkMs5m4b_{j3q`f<J?;L>NHA~N(n&_N*hU+8uD
z1v&>|(*Sw_koiVW0UGqO-RkS^XF$WZJ(!j^4ClXq=_2sa2gG183;W(dL_fy&zJkAv
z2O@(6?+)7o_XVeUsiVS0vOUS81Y^>xcYCAJmw;TL(aWEVLbCSwezl*nhk`z$+rDVy
zezT=pUznP>yy5Tagt)}8bP>`6eSsQAn{G=^ezf)1<&oJOgXM8@-kb}>#q%KMZv@uZ
zaLFRcX+ucG;+$dz2!+_{sBBIIR#G~T_)li~w>vR7OFmx73Wz`QYg)z>Z-ABx9AVD8
zi?M;Zh$F{P=LF!y#Y_<+f`t**K!1q|3N#F5>yG|%2ODbTzYL5N5QzzV9-fOQS(fQ*
z{zlFT;RVtTk_YBy?=R*X)UFBItqpWxXb(-FF|&@e-M=zvJ`HY8S^|R0K0(NT?XL|7
z2Z^QWi&%{Tme(~>SjjH~05PYb(S4vkfAjf8_<IfPZH(-r3pgP<?XRfy|BP$@39|kh
z*Jh??{5R6f@xQ~d41Yq%f5oKf{;zoKe-FRv#Esbo&?AXFeuQZhg@=ZKN{|F97vi9M
zm(&vgJ;V^98DZ6KUvlmKP%MQ_>3iBNj}6&d=Vr6jCUi%vvv3G9aAw_R)C&+ex@P1|
z+}9VY+w9y~lg?CwPF=InaIjpbFE8`|OmRtOv99*4b&5uW0g7wVXNb4}X{&Ogs(3hg
zN0dEM6<5&-81UQC<@~)W10}(Hi6eEm+j>6oQ2eycEr{R6gf%jbj<JOWm)Vw6Hd`NT
ziD?-$`N1`YXm|{Hy8*7UpHyHWDWbv|E*<nj?!EV&@ZFySO;+P;1``3nS0zGT=<LvN
zA!Ew<slsd~se@Q1sb6u=^uk4g-ZRMxRU%a!N_Qgjk9n7=pZpHd_F%IlEas^k5;3Q!
zB(I5Q&Gxho&4c1z47WClPRY$@Z?OYxkP5O7Ob5F5*qLANTi11FYF^)gGl+{2|18P>
zT(iGc;-5uhVq*Ds%^3a!{{M}k{~fvigDnV~I2k!w*gM-f{t3kY1vkhV*nDCKGSZqV
z8X{D}CYA=OE=r#v{r|L!8rWD^y93DoZUX#iqxieg+Q95HcF*`9Nx{F-1sVo=MtT4Z
zGb<y2fsKRd6J=mx{0C)_a5k{EFcPpevo-<H|J6^x$><ME!NJJ>SM|^M{?ut0Kd16%
zghB@P;wBbm=ATH$r<%W5O3o%WssQ%C`~Rtk|6BPp!_Vz#!U*_-ApCbk;SYrJzrFFd
zIu}Fdzu*()Pt4+vr~cv!8aSE!1;+gUJY(VL<Sb-v;P|ftqz(S5Gcf)Q!2C~l1O8f&
zzkgyxY(GH@3tKY)otlNMfUT3ozl^^ut63O3n>&4?G)xSCX7PVNOsw?(w6ij?0{(xm
zPw42g_5arJhs(nD2g&;TVP*NZ%*Os-c3D5S7aP-`z4U)StW1CKqE9;v|Mvb{j*;!Z
zbkGBsKPS)fxhMXN=MUEN2YveFe7^nypFTk(I~7}tKS&PX&wI^(U%3ChjsKurfA3By
z3*$e2`U8ahzp~6_H(?lvqWgS>H>g3C(y@sL!<L7{3PiuaN=e8jMy`>nemye|k2rXj
ztBD-Xz2hv-@rkjn47~;{Ne(&L!MmSpMf51IZ0ntnh13NdF+YcJS$+|aBen7Na&D{N
z!ue*}M}0-~FSM>(GtA4^O9e`SQHFvpL4Sh!0GJLpeUZQioLgDSzH6ez@d$S`_o7~Z
z{#0imWSPNp39@CTMJ;*_(J1N=FVWpK0(m8EH_{9nlW6q7CMB9)7`{Ie4RL1ZN04eD
zX_`lxM*UW&(U4>5y9kT%w;)Om_o&Xi*Uf?F=1~{CrRnyO3x2o%C+-zr5=ZCAbnbaS
bV7sm+Z(}Zc5@>yh-NiXznN22}{WiM+_yxK2

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..cfa0646aa7a315504cbd4f24d74b949788b8922b
GIT binary patch
literal 79390
zcmV)RK(oIkP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz00oVOp+wF=Tn^JXi+(g2oGMi
z0|*TW&|-ROCukvzFar$Ew`gf0>FvdEH!}}rCwZ#>Mxm-sSkgbnjdAgddHGte|NO07
z|5NI^e*M?a@-NH!tM>IgzJCAzfBvVh|M-8bU;q98Udq@1bN%;!x&He<mjCU4zaCh>
z{?DbXU;pdZzkC({$@t&v=gfW`Yx(MZ{nf7j|9n~dbzDD2;QQ;peEsL;QLMFJ?RxqW
ztG`Y=1%%jBP5-a|{`H^!z8ulG<Ez$R)z+={OMLrfweLsy`uk`3kN@p&>)*yp|Nh^W
z|M0i+tN%}b{~yc${P(vGc&upIe)Xw!UVLwxo#(I3juayBgV<4j?bEAJ{y}K#zm8rf
zDF8o++2Ose?kDhX>;CiCu{UeiTYLF+?hoDn*E`=@{Z-bvbpU>7UFpBdc}`*g-o>uz
zcc01xeh@nfr!vF<{2;bjOsp7yDE`IS-?sf%f0+I2zi0M0+wW7Ezz=O}>uoBd{DV+w
z_o+<aU96rPr*eo9_(ANr7Pnq<00{h>hTv*fEqghxw;t`+`sXj;YyIm3P`7rU$^?FB
zoo)B2OyCEx>x;fkWdc8ll{&AHQG6FEXXnI<?kDhX{Q~-7?V4KU`c${4?*I3E0cAgK
zQyJwSTDO(^R3`9)*!BOnsZ8Jpv3hVSLkz$VVx@3uVF&>H#V?=~`&IwE2z~uK_JGsw
zGa2Rgw(a|U9;5s&w5{_j_R<ggO#5x0Z~wsBSU1ckEIV6Hr+@RTzrN1>VbcG*4n606
z_MZR1+?~#W1j^e&b$t+{uTo6FwZs2g*MWZ3)B3eveD!M^wWou~U+R+Ud+$><QG9LN
zwUo81!%|4Vt5~_#&GFAEm&m)|H4n!3J_!nW7qlLS?-UgB7lxtObqd_B)!=*|hrcii
zWvjnUvqavTxSzjGv_#$o&+RtwEWZlX>&S8+`b6FZuXXf3_KEz3k*L=i(as;gh`+Wo
z*6R#-pKgh~H*&jQ5kFsvybB(Few^e8yo;UJVRgNYhLBgmR_r$REdPa(Xl4Di9j%}C
zHWGj7h}c^BZL%fu-n{Fwcb{yDybE5J%lpVD@-BE?iS8qx$h+Wq+(%x(Um1(@dRH7)
zUdQ6EZJpO0^FG-Ud2Qmj)7otjPUKzCP8XQBULx;;+vc4&2?}`^JlZVerN1x^cCEnW
z=WpUK9U9N`w~3a>Ytx2e=Qhy<yo<H=+o&h<E_eytM?H~u!RxMnAN553%F(G`yW#fZ
zH}TibPS-K@w~3a>4^#Vo4!xf-zrTL};eVvb-rT>9hL3wrw6h-9mlm!6y~+RIXz#R)
z*I(;VkFlX%N5E7y{)hip{ZiI`9QAtZcAXX0@%rnty88Cd6ZQId>NttS4a`d$x@2hn
z{BE#QmzRj)A~TR{S}zX8We?DW#E}EY_1A^mN(Hw{N5-AxLasTx{07wyU|co!)qng3
zWOYX~>UO&5_t!E*rdN$q*FZvpmk4gu4qX2<fNZ4KYe3n^Yw}#k?r*pw+3Y^b)8E^8
z7aM4P@uEf~kv{cHb7f1c;6O&-UC7lf%Z%96G0ksy<`oL0b_cSn9H3^)d#ZR(wO{On
zV$k#G)q&LPr{euor+&J+XK_gVbd^f>k(by%1-hga7gk5SG5$R*ghp$w1%kbj2zw=7
zQ2U`ih-=(Hde;y6u=Yc}P-4XTuK8VJ2ri_kMm_|68!zP#d5>R^sYc%87gAIs@6O)U
zHzm5S_vj-)UL#Zg6z{izu#eXG;(Ajb#TPIT_0byL)~otxMITl5(TYB*{Ge8JQH;U@
z$SYJdb5?XwQKt=s#I>NQ%T{#I`inn%Ref=wsK(ws#t(BKWByrwmhtdFit0Q5x{mqB
zB;~zxArRYRQVaxQ`w2zkj#;|L>OFvV#;12dW97hYApq|i+c*%ooVmWT^M}1BY-8za
zqfuKp0Plti!RI^>e=(J31MyZH$7CEpuJ<his;sR~38*{*iAFa`9cXl;(1A8%Ee7OW
zUOAGXFdP5|@&clX)CmqGnpk`&7YDqEf!q%?a^;Zh2Zk1-f0ez7>m*XfidWk?$#{#J
zMt?uN#39_HIgJbQ0LDw&kwfUiI}i?G7zAqDQ^*_BsB;^Lf7}h@zBuG#)N<hC5Hk=C
z{2rfj+gKU{)Ot!RUgYB&YTsG%pEFIAc-25SQMUN%nk^_s#oHtj6>pPB)LS3?g^Z4G
z@x3pB_$SrsBo!U6jdzc&W+0qgvDXh|Os>Td?`mzldq;iONvJ_hpU*UC@?-uj1M+^X
zC#P+XuB=B&d5JUDp#0Z@eIfh!?CLIw=+}Xyly_g<Cn@i~x=m8CM%8T+i`s3ISX57^
zpWVDf3EC#ST?-&@f=QyGdNxT#^|Tl74V@R8@dC(uuT5f6y*7#YVAiUa;c!;tn_mJ7
zgGzq&I1$w{iA9aH=<hg))L8WKLq6f^I*CP%)=4ZnOeZp&@M<}=#q8MO%PBEz-sPOc
zyhbG_2KME0WYe(cmV?s?TW;AWDet0^lLLF_g;XqY*eFX*4(y9%)AYtBST?>2dtT8=
zZ66!j;z$a4Z<O2+)~lq=V8gytv@&eig^Foo-{OdKK`2Epv`Hj7K}YRzuJzitD7hJI
z!~EP1S;qKy><UHawF`(h>ddwscx#-5mVn~5WfF_m!oqq1Ucl13?P%=EMLy2WSC6eH
zB|;}Q0Bj2z7VP!pZh|XjU3Dhd;-t0=2tVWhOo1(4yy}RzVf|e-DK;#)>#h%Z!}_{v
zR&22@3?#*TcCDNh!{uT0?i#aV321chs#$@P{6H`(E+iVs--rh0tmxQ4SDgvBm_!3%
z_rs{OHjNq<#<gh-hVpQf3$9q3p^-e$Z*iL)07t;Q#LjH!OsyST<0uyNe)E^;w750A
zL%RnI#{*%XG%w*kv&DLLJ)<urmaHQ8m4S3GvqNG&^PM$%%#E>xyu_X;c!f@lu=<p9
z*SsqJ3ZH=sfaVrsT@AK47Y&U(yJLkBIVZ^qJM*UYMZ1Tgne7XOOPZbsQo943B=Ox`
z$SCzQ&Uxk3#i9FGGyt@*$ND-Dw6UM)q{cRO96twyANGGnKaSg!3sjC>KhRCORrCXO
zuUfPEfsWz>QFE;)J=W)eu&z4>xTvmsT-(a2lV;yheVjCLMH^+-Hykd?p;Jg)+8m)?
zp~tE|AoT5pjCx#1l&-%tQ+n+E17Xd2+~CWhsS-E33(;cH4Px3tdVG!p;cG3X)&-$B
zhWzOG7Q5j`JHN#atNPJ70egJy<?z=nfV}e$UMPCp-!H&R6~Cc%qT}N_v`+NOis|Yf
zcg6ypOaM_kT`xMmse{+cj!)|FGr$7KCkrm;f%p&SR4Dl2oC+&`IA+2UP>dm`!io`G
z`R-NbwQtu(hYJOrNCx8bq3pVJ7`~2OJB!7xQ+6Fl%{R+(T><dr+SqeOnH#KO?#s|`
zxS1B*8wL_vQQ5U@z?rGU$$tUlUA1ezSe$1sBudv`x`G(y`L4-g_^AP5w%{sTb}5Q%
zL)~;CwGQtR?KRe;aV7P8)=@VtB<9+v0rV*P-!T?)V5yo17N_BYvuGeuH>r}$P&e&9
z@_Z?}<-*gU?7F^ONYqVACTr+7omH$|C9Nw~{Z28Ej&k=>Widu{Maicpj%owJyvNyW
z3CO4CrUR`-ZOWztE$-9<;VfO@qI2k&WpNT65a$lIicQCv7TaV=tz(O=V9Q%>8~?6}
z)DAcY`9x|vN*$%Bx;7TvgUi;m6SfU?*G|zeZ8q%`Exzc|wUjorIMi?PLuhi>2ZbwT
z>C&p!6Ua6pUZd_Vu!{o)kHnZ&w6Jd|`3PRiH2>Aduxod%d+7EGR`P(ZKJ3O>QvJd(
zfX)ZJggy`VnE~){RpZWHI#sNOo8>?-S!)~t27*qiaReAhfu6W_^rZT>cJ!n^A6z&~
z*TJnCx~=luQSphPGT2_O^)~jK+R$gZ1>*8K5cX5^OU^(rAM5ogr7EyuFX=kk)rwxw
zO#nC1657FNVS$&KPJ9)6hv_q`_<}B^qwHgDCoggpCoMZQhH-5xsX(l8uChb*TfKz3
zl@n{7>HbjSvo5A7TCgpcrYNqd1L-Jx-`lP;(FH~IrE)Bog{EDg;7hcPOG5EUXmLIn
zGreFBFexbt&OD)&EF1cbr-*{HjY(@!wwR&=!sNYfsPW>?VJ#g!r>z3_)`4`CeW)$(
zs>SdwZ4?D-xak{!D{YaB+CY3r8r4k&UV!Eo*n%l#I(n3f*XRsdDqf?_qZEA5sqHKU
zO$rel)J+>l!CGrNis1G-5H47_zFyEMt)~x<Ci{9~bTrvl&J3MV*8|5#TT%3Rk;>5(
z^P<VPvARZc0Q^;)d|PZcYs{e1G|h2G9SDEJm&O5LeONay#d^8+(5sfFZDozQFc1vX
zihaCcman0}8fDCy6&rNhv_Y@2)|J$+t~j7JU6I!2B}~Q@1CC855Y%o%F>2P;+=80v
zmhHFEQD$qg(X_O^;QCpbrg&UI2M|?lxPcC&qwG_paoJxQuAl>o+72Yf&%6{T#>SJ<
z0DL`>a(5tcTWt;1Z6{8M()SJ|ekQtll%w;h|83`nCdP3lkZ2)4lz~Lw^Fz51FV$!t
zHlIdiPz#5_QMZC#8c?(k8%H}Wn#g@)0MW#vw_qJ`opRI-yG<*4Rr40EdJm3mblGnw
z^a73g#$`Y;&sV*vV8~YW6b@rjO<#zY*e5I2{CcYU*BDePst4e0uDmU@BhFZr(JBM*
z#UhR#3m|WG<q@wPha9Cl%HC7;z=Rrzf7%rr&~ibT3^jhjCqm_SI?CQnmAg^HEwo4@
zK9INzRNhJkRO5G|g-4eVTiDTWo0=HsrGco4*cIxgCgPr3H#E^C#3q`T3ToT19@dRB
z;b`dot~WRIKR@{fyMC!%FXk#yJKkI+#5b21w62%qkXpOmjblYMURGMT_zi^b#u>bt
z-n~l7U%lhPS*eX#21KFCXJVwOpJ_X1M`OF){8lP=&qiC?fH2xSX9q0>0|_C_=AAP{
ziwQ2CC2R=`pb$bozz3vM9y%NBLXO~Pa7d`(KQZPiOgyDl)y6QfwB*1(<H*WqD8)&?
zGlC%6jgx5ADipU%2k;wEY*eZiT9`E!hgg|PDb}S(ighV^6&CbxKp6nGjs_z_sjCJG
zC(XL5KCzk9l>@b%5`uwlK$OB*Z6~ELWpQCF71z-LP$s6$GN2Ihe}{6dXt~>B9dIP-
zw#8khP(ji*Y}iFcnFgJBDOwew03Qe|*Yz$`E@s413KjMPf|Qpq8)VpN@KJFDwZm*E
z2em2<dgoGjo*4+mI?5En&{B<D5IeUx)E&U*zf}q06Qp9e94L+Fch$Av^DDb5i%Un*
z^6T*$UdB&`CA^e4Hno0A0=Db{`Pxu+&ccqZqtJ%g`XMpYm73SGYhqH@TC`^OI6D?z
zG6vvFUO~La0DPIm)nW8g-zbDOP(zBK(@~}jdb@`z$`LeyM+X|sF2oC%81Q)+2-Y0j
zrY|H)*I%7o-?>c`Z2{DDmd=(id`No&oL@@e?PnlEXmQAaA|W=VNC@*BO3KpN5Pbhd
zhTj3jeC!&Y6_d+F?8L;P`LFp!c9bzNp>13OiWb@-p=e>K8)YzTxTZQ1Z#CQ@hokrc
zAZCg2JGLE@gqu?{j5i$;nsK}hm$HGxh|_A_j3ci73m3|PU_{M-)&DY%AN^XI;bfrb
z%4Q8?q0=(;d!?}l8pluPXGM)QbpnT7d!k{TFWMEYaH(qQhJq2(Mrlwz7w9sZ@ndeB
z#*Lq|%xbOibJlL!_&GN(9q3){t?*)TB)XzOrR-2trosMEV6AHnm;F-N6%FV6q7#3E
zDRMyQ3*3?lq9aGyXE#+xt#Of_k&gOt&1zhwX-RI4i?sIj*3etLgtu1FTUB2Ue9Rp}
zD{#RpjInNU*C;YlH)<DwECHbp{ecy;lb$XEiSC;aFJTPo$r(!H=76F*6FC&2h*7D~
z_1uu5aT`dC6AtS|7WEd&#alT#N{5%aDK--RqKyj0LY2ip3f@hmM@Q+zL**fmC7|f2
zu-LY0>MEAmQ5gQpuW&|O>r;x3Qnjih5~)!c%n%&J?noFQiw<Bo*i1+{*{JvksY{yx
z#*BJLQMaQoQjdLEX9;R*5;!zQJS{-&lJ!`3^(CsmZtA*3ST~;h*RI|}$H4YK_2+7;
zU?S+es9)m=Edll=hI(yk6Ooz|FXqQuIq|So!L~omJStOeh$de2=UQ^&q0`s=;9}OV
z`Mu%8Sl6jksZ7zwH4sfILeux=eK!#HRD8w*K~E8g1KScy!6<U^iq)f1c`_lJ)~;A`
zsz=#jQCa}p7qfcyc`*aRwalm00JxO3uw7QDOSEoQnC!8*0^xRGXc7#)L>7m*9mK0@
z?gnT=&E3G_hk4kc;h>(F3ffibxoY+2Agt;@4#KJqM4umVzFA_68%6DtQ5mW}v~yM}
zKMJi#_2BWfK}}Q-e1qJP2hgyQqq7d4U%9o{gI{G>BbNcRKA#6JWI8X@qwAD`j-slA
z=Z*{Du_Wqcl0YXN(`g13<7viF+Sd7SG!QqY=m1p_H<5>|3iCP-Vh$9Xy4WLyJ#Xrg
zqGMqQtvVF4#j8$*Z1Jj7VW<x)l^8mYR_ZWxXs!DxDNKa$GLBPk-QlmB$Kty4s6!=8
z-QoPf<8|G6(BT36LcVZ7kDBq|6KD9kZxX=x?%P*h14j4?pO4WD=hXQ&F``#^55V~C
zT$4AHYTREid^?AC(-N_Bj5oHVQ3!)YErl*lb>|3gXbVn8dHbqVQt*c62!+rf9$hz$
z%*tu8X=r#eWef6Viow}<OX0P1ARz-IPu)%lp#@vsOgqZFm!bjNAsJtG7LSpk5C&k|
zC58dmcu|QGE-8m9yTMIG7y1D~f*rnfO0l*)5FMy(mk9R65hVi|ERvf^hLz<CeW<c6
zgiaJ1^(k2GHmESED?t=ZYEu|RlNuKW(LgH`bu0K-sJroK8Y+BHxgs%E4x6*9h&;9?
zG^MNhk_v99nLM;6Bv`#p1viyd1M$N*Ra)O3T0=4P9qj+985;=Sg^3Ac{{kHwpa#Vp
zI*@t_sp={`0#cn<p{H0<<yWbykY2D-RUzFWV{}rzh!~ymL(#055!6pccn-Ci_zlbm
z={ZMu4um*(F!M`c>PRS#tLjoI#j4<b1l{ZsP)KR#?9gm$pQNXi)WEeD3H5Lb@faQ`
zoH<&n#ITMah$ofO4C0aEdU2?yYP(vhw$T^VWI#b)Ly;i`dNufjq?WzXOR8#XF&yNi
zt*>;6l16`o>m0NKVB*>)v5s=>ljWe&=SkKDkLp=vfmi_1j=`6w?Sn5*+XvsB){h=N
zWs|X_QoVuOULaxn(5h{;eQ1@oN{iLb4#(0V`%a~wl8itjh-dGUooE0t);paCJ<w;R
zsfj^8vPB`tC#_YC@}WJ;LwsE4CzIEJqW86SHr%~rI~zefF#t5L)rQqrCb-(5<ksTY
zc62{2c@?JWfyAyzjY&OekG`PEHs~=vZZoC*a3Eo+q>*t1_Ut{)kTs0T%Veq?P}t+O
zd^PyvAc)3+K3PO7)hA&!jjGXlUic>3&b2Hx+Rk-xf&G^@+$92lV8rFS;2bSGaD{x>
ziXDi_A#3sg&`O=)8zzU0(jF1y)zKo;R+y<d`nV{xJUYV;8}{)^?=IQTE0r!XvR{Zy
z@FNr`=Dw`-wbF%xhWttgucn2f;&364fEp^7WpWzu@Sr|B7BD&}91ljx{R1{t74BQ%
zys!X@-lum%#X^)G5S0p;wyDA}p~ok_1QJsUhbk<{>5jqBpmf<7F+NcpxOLRZg+gv0
z728vKhInMqI(v^W>L(peJm@DpF!Zrix=-lXQ6tDR99u>y+?(k6QlZANRp)s5R_Xj8
z-zuFJ3U&@-DV%tUe)YgnUVb~Z9Ft#9#X&Xvenu%?pgTK`%y1rB0KrvAKN3SPC!`C2
zgOUgQxYG}G#FZD7V)`s_{YkH<iYrulMh%26SD3VM>097p6^I<LDsI5(qE&IVPB*TK
zJ3L&y7C`YD-Ibu5kk8l!z@4myGAF&wYT>eAy1*1%Hs!T8Vtm5sNtY4o-{k$~kwLyw
z*sjKL#$d{?IA_SuuEO7no_M1SZ$93@R_Kf5(l?M89!>ZaCsKI@GFk|pgYiQ+ebBvd
z0Na}Whoju!ZOGc;fGRJ>Wkd$KS15yFJ$PtxhD7L4`b#o&D19nDbjUwqIbGJ39-%r4
zuk;Ajxp##UpZ=W{D#oSYXXOpb2Es>2E~Fz;C_F-?Euzw~E6%vmovTZ)Gu*l4(2Cfi
z^m(nJf|OURM;Ar=qz74{rjmQ@K*F)q)IOYE<e}>^N4}!ViI+h~>FMi1M|Q{;c$A~#
z#(W<EMMtM2@dAY2#~o$*9!H;eR8gNjmIo59wV0@j!itKh2MV>4@{b;IH{n{&qrb=9
zxNA1f`HKQ?;EnAM(Y4(4e!7-NjnP8)_8w6$exglx@B#U9Pk(U_gh_Yu5&F_6hjR~(
z@md|Ucnv73uErenD(69PAW?H(nFrF~IS<wSfP4~)u7fc(>2U8cHSY7jq7?rAxVa7>
z<`ew+N4U(1Cl0hYj&uqL7(kyw1`5@GNk=juZ{l85eJtS$P#B0eQ9%p?@h^2(2xb9e
z48kECfhLI&6AaE_IK?RUDcYh?bEt@nLI){@Z4_{<WN1eLt4W4`6uC?(Mx=n_BLhhg
zzB2`z6u43C8w#CKDhq(<JDz|T%9HUf1#}e|6H~xNfw-9kP>ifTtOKV>#orX_C>5gP
zQ9u4N`QeqFkv+U#6#8B%AgF*+A%lkalZYu=0`cEL)X^wMWR)fshzl}!iIvX)r=^5{
zmO`M|2@0GlAP~sdsshS@jKA{Uog=hLg#Tw0SE0X_$9)y5Kp7S`0DoSQV*_Ep872dL
zw-kcrv&k!hv%&y6BG}4~;D?NQD|F*hWZXcawTEhsW2=JhO2nEkQ;Z%zG6eDkG6niE
z0EoeX{w<FeNBH0Z$YUyVY@jDo9AbgeG-DMDV!<Pp(U+8kv5o)`>ZoclP*bb;1}|d8
zRSsnD8Fg6@<eh<;1BvQ$Ph>1n26zr6s&86bHU?~Vlp?B<yWc?i6lUt{bv(}xYNLnY
z2_5!@OyR7BdRv9O4up}jm^RepX6$T1*mj237AkiYf;)Dk=qJsC4My<u$QHt<86Anm
zUxB~_seOtRE>sCCnz(FG>LBDe5D(JkDXb_+d(|K^NV{kd{R8s2=LKaC_g8FmQIxhe
z2t{f0jODxbsu1iYka&|m?adGpu5Vj$+Em;XkJHw6u;IF$A>#vzaBx%4M5K1d-w~yq
zQ-x95U0Wbj*gT_t>!_j#_!3I(jFBHev=0lw;*fJEth>50$fy*MKY-{<9Xd7;Nhq*?
zaVqOIr~o=1i54E3W5ru|s{6s)B!Yo~IBNqr2nG<O4Xb(|{7d38C>t3gRtk|YLN21k
zy#T9B{-f-#mJNL%!B$Z<YG5~_X?PrEL2o33ZGrn>&^wG$yqWY51L+e%M2Vp91q>3S
zIJ#Qq!vaskWT6-*(s(BouLW`7V6s>M1yu#LC#8csNR${n+KM%!bh1Wlbb<8)u^kip
zMuB-i3>^jG;z{CB!l^NNJ{CWG`_CLH)TJ(na@0kq&%Q@bFh+9#zI`P#$pwkJ<lE2u
z-VLHRDd8xY3@8P`<zPu!0Cnk9qU<%1i2`AZNyst)?-Y@?EaQGs<y1XxFTp%hB@#=R
zECMCM)F%cRzw$UYo0R*dleWhuu^^tYNi1kyY?2C+H>usnEi9O4y2K2f)g@+8#cdMu
zX^<p5e!rV|dJ60;$>rn7S|+|9zc+dXcV0>hj4??ZH13;G!JHA`vZy&DK;Cmgm0CK<
zd(KHHsB+FpD5#mZnRG0rB1c;MZhW2-gHnOrha^h_m^hdi>X|%Ej`)f$GACZktJJy$
z?ygA+HIP2hMvb!fXKQpTbI9v!C^?IiO%g#OmFq(ViBwb^(fvt)Rlo$03|UY@1c6oo
zFF+D(6?oi&glhrRlc+0H9p^ETc~SWxzOMp?x}*eK9I}JFVR$Gie^3g`yV%DHynB<K
ztn`(gPi3cTY{tvPbLNO0B0?+h2u`ZB0^=I!)D}SAED)}hPNKYA3$RT{VM%S0nB5kK
zf+9|b&b}r++|WpQi^L#TjGTD%RvCyhYmtbKimfE8D+Vqi@!7dD%-^eH0|@<=B*q(1
zv~go;EfcRERBTDTH-Koe9NUYL6;H!&GwGk}^86iCbQf40lROamzGb2qbfuub>72x3
z6wgU4C=oT%21-dX9u~YcIT5LUOx8q4`pm3YKotS{#Rbsl3hLw-hMXjh1x-$($AJW6
zWTWR|i0A}h*gvIBD=@7l?PP)5c$Mm`IDO(W@mCg*R3yixBkRnASzw|CStb$EX)XYw
zYjn0VaPXya3`${;cLMRAImjb6kZ7oGgcEYAI^J8`s`(i!3K>WJhc+a@kospr*gxR(
z6Rjzg+w|JN4|yk&A2k6T<-^mS9IFL$K51BiEE82L73<07>c~1Xz9!N+b7D(fk~!9)
ziCcD*$v?}PLS#qD2P!my%WqJ2OpwnWQ^yc#s$9^~9=ziSIj4?sKHB^cLAND#-x=Xm
z!f;R`NAL_}t9=THYdDdHQXFRXHnqv;NUGPar7IbaqoiXE5><dTd6}Uj*V|1Vf-Lo%
zB>uKzoBATEbmUirIv=`Z3pwWg8Erp~X`Tdg*l|n~#XIphryc{4{WFH*T&K?g0C#7O
zUusS`>SxJj1yHAE`Q$k(iBe`L8|qW=Y*RytXl8pUznHO3owx60^vwCMzK(PHI{cG5
z=a0i(km@;qAO3NkTaKH5z32SF_y>OO^RfVhdQ7eq=RPe9-s)rO8lN!dF-?CWAU(R4
zE_abGTGf60&vRNv$G;87>s&^O<TC1$w54VPYwhsq&UJJQU0chvj*f8}-r~8Ax^8Dc
zxzCKZ3_tYTXU0#qR8wFNX{o9(1iB0;H=4t1)TfQ+@EY}LqdB}recEWwsL?iU)T`HM
zoA%}6HQJ|rIr?ay_T{1Q9SFPVK!+UDHXI#tOxy6N+K4P@Iym?eJfKY#@(wBMbk=Ak
zzqB}yc)WtD=Y27$7I3m@rA%Vp8L3<tHA%$+7*U!$%yFJt9NKx@EB@--t9*%Q@~h_2
zttmW<N4t@hMB96;;0?aVJR&yv4D%S-<N?g1W~2Y^@)gHXNAi3ct={g3+E()NxOzz^
z;OMcIii9}9H94m8a6J%Sm{zp$&;=-t=*xgM9rdG)6p0o}35lyflanT|3$3o9^@uw`
zlXoRA9ZimtyqGlkMDp&^s(3hg!5Pr)64a`eUEGtJ920q$8i)%maoZX}Jt^ZuB=139
z+FI4v$DOWK(*>x6&SO9+6>Ts{RkT4y23#;3-1Be)ZJ{@qZ>S#bB$;TzCYc^FQ+>V&
zw@GaP16-T*1{H&_Phv3$liI*bdHeU(BUA<pA@A?=e*JGZoq^Amo6f*z40HymX=qX!
zKpD|)Dg*xjCY3>S?xZ#_O!-M~5ZhuS#|QN%ZPFUV!rLaT!T5GZ^d5}hP}H>6CYe1R
zNs*{sDh>?QvsCuQ?P5R_>!_YCkWfIimWsuW`iWH)sw~AjeoNiuF_9AUDsI!ee01Bc
zi&Ebr(sG^EZms2N;ERn1Y_3$*MO}_bs4otrOmx;c33*M<NhUf=XRf|`Y$^LY_V#8u
z8+;8LfCQo<rr9v=S<T8M;Tj%>z6LbvVKqg(LoBBPHq1$nfbG$8GDK$#gcBT_VJZ`F
zZyO=L{E)D-1@j+&$a}$3u^62=0*NVhq9?dG#GYh4eJ{{&dw?<*htqpvlY~zU(^(oC
z^k(}c5l06EOMgoj&v@!@>FZl69iY>1sdR9ye{+^dS^?ta=Ohy^m*pAug=W8*AR3f9
z%Qwsvj!-D}{?@f!xUHjg+CBWWT_=PMd|0i^><o(vAE<b#PIzIIX{ma^O&4MI3m~8C
zotmb&`Zjs{&_dL@<_4@t4J(sdgs_OpyNC9u)-^Z$$~;H~Xv@Kh2}d58yavD#GiNGD
zE1J*bR93*Q2D*c9nchH&umFk{O7R36UQ2%;*!fzgr7(I@i-upy7f0Cl9WT<Vfopo}
z+(*JD*}Aq7T-;liGc#?QZPSTA%%2T8Lunr+OU1YBr=YU%F9=rF0kLCZ%^V0i1`ATE
zKVZ;pTh$cfjbM|l3Z~(<HI(8#(nfFoZ<;DtYPOaQ#KAk2A#TBDj%r%ComQmtM|@G)
za-zVguWh<Kz?R-N-oasRZ`-E!;gGsXO&Lb}mI-`l*l(M*7#ROSu<{Kbq?W!@a3^S6
znla&X&^E0iq0ML;c?{{yFc4G*`i+6mi)5U<<OBtG3G&i>)2AZ1YdZZde39Nc73hhv
z3<&NWIPvTncw{DMy9VC9lt!5~LDuYDTLuy-kj5vF_!V8_-I2tZfaH7PLrb;GB6pOw
zOKl04mA2ER#b^7jqXWENoV#fDidll-2ycpSX6Gv4R7it0i7nnx6M4kJL1!Sejl+qj
z?YcC&n@=z}eajE1F>5njh1#B@41c<|=P+ab|0}Pgwx{O{HcfdYg^D0(t7iYFcIYMn
zC#iO5gMcGdJ9L0JR^>+grt8(>tXf6hSl-=-oEhN6)ec@N;pavEu5WopEl%>a67so_
z+A{Yk8)dqS#Z}|b<bY4wK<Hrt$2I34L;bK{9UY};GIc<3kQ)H~)EZWbLtBV@+BsVq
z{nUK2A6gaQs@D$bgy78w8n)Txk6dlv@(UaY`wkn;K`jy73)>OD+F3VRxZ$JNQr+iX
zjO3X6rjr(F=)UC%>0EWVTZOlzL##jcjP$KS+uA7$2;8{_qW;GRaOy+?_s)UP(GmKf
zlZRG#i4GtxqHrW_QX|6IbTIvK2Kf$<E?CDI)PS=y>k{;VXf>AUR2iZnPD>aKg3Ih6
zH%!F)sGZt2;N<1JiYJk%zjgpP@eY2*Xd?W4mqAIn6B$C5>NPkF+p2F1PQ{jvLU3^!
z^qK5(_$E8YCMq3D5)yHyf3uTy8j%giMz8s}WIDsA{H;Swp#<=^cB;^uPqw9p5FNKo
zS~+-kJO3zsvd3M0l$)N|yC_TDYrc6AZtJm5*t&nE1NvY<t^DWcOnyl8V;>0A)%1cg
zY4qp}Z*nK1zr3v(IndDu85s=6djngDyz`y<mF?^3gHtW^4aV7G<2)Z>07j=HgbA2y
z1sO)*RI>^!@GdBdyj`*JkhC@f7OW^L4Q(65w;aQ0n@Mws=!iw^xEVrWMS%l;B()&Z
z@DL13#tQ^#SgD+rjN`DRoq&SVl2QTzA(s3QsJ9g*wPR$7fyV*CCtltOc)uw$wbbAo
z#%qz1!jc&Q(Jz)v2&j`K%K^e@1_v^ORS?c?q9`a9S#|LuiyrD~p5Zl{nrC>;md%TA
z%NY3&1~TVxMzjqkmz0_#?8wTl21b~|Kro&NW*P{(Xh&ldG=q4k!9UHPLHIREsufk`
z58-zXv`9gl2+Xn!amQa)w7oD2Y(Nl0l-OY6h8QBrEJMvJ=0f;Y#SewEpJhBaG@K*`
z|5j|9W$-un$em6cYXO4fEMvW$)I4~}W31pGHIN9Siy37K+g>VEoF)e>hWS|rTq6{4
zAQ@ojZ!#3TaaJ?*5u;Z#^bx}+cPvISTFv-JAM3?A;L#%NCsnIAVk8Grr#MOnSlyHC
z^9<9BamrvwY&Ug7DaJ_AkcjoPjDBwJE^W}#GF)_&QFVlrnl!hFJ9WB!M!3dDUX`1P
z(W{ox&WLcejCMv8tW|ypjpM%4gMe;PBOd@mTpOCm2uj4{dI|x&%Fs$^02jpe4q#`f
zZ;Yb2ArK#IQ+#ueMk&IwftB5+aOMruS>enZ#!S2pZTE}`?5S7=tWlB3h-jPQn`0fY
zDZbg;YE6s{&}}j~!}6^FZJPp|;|lFb9UvCln>Brp4X2TY(;c0q2EYLLacLQ4hQDKq
zH2(pFqmMM?m}7?cLz5dE;@X+2{9B>#mf_9_k2i%o8`g!Eacl^)x5ldqL-7Z~`2L3O
zq=j>Y^N&*eD46gq!=FJ2V50w~@07KqQ;2iCHHE(!4pi2}0|bf!%b@5m${XXN;qPHB
zDHS$}F!UO93D$n6R2ca?_;Q>hT2d+;kjfxZr*9ZQM~NbQH+F)?kW!DDWR{R`x>qfp
zN`#CboE!=^g_+Hy<tJgqKyIuS@k8VwDH0>A1*V8r84zfgj00rZSWIm8VB#16C{Y@O
zwA&)e(HNv1HXGzn3C0h@tl}~RV~b_fc9>GEdB4CyGE%f)#&<*$o1(hGUorsJW0O=z
zIbNceSA;8CqiULTDxM4mzk-87J5dS=tywS*SUWX92kRyh8|e8>&XZ(`u|`cMnPdjS
z0Ycsl%V=^a;2nuM6SOs+0tZtDv^FLuOi<q}4uNK;NQyi=MN;tu){Bfnho;*R>^Y&>
zwv0=M8k<>rzDfEsGW($90y?j3#;TDM0<=O*4)jgtAv0=X$xdXZBMtbAJjW2WYN&xt
zPNSekas=}`*pryP=v(AU11aGMM+PRNfrunco&pI!j5~#CwT0T!(i@e8Py-@I(J8U`
z44hVK6j@<x6($0T9qD1rv>>}O)zdk}FhP~c1W(_h!7>v?1(>oNA$wSy{08K8K^{|+
zL5rMRmf`x~?HWj!%t7sC8NUzmFOwCF3}I$|-U|XTrnUMezt|EGUSpIXffzOi)4C6p
zrXzSwoVON}r!EQ7%(NTqyO+QghJ%77vm3tlAQOmg!sl)?wOdR*U5rATIRG}`#H@<l
zWBC?ooXJO+#B!ztG$fyMBpL<fqQUUDki*WBw*V}6CQoBh;hC5W4i2quW(U}qnCR?V
ztb1nk{0e41&yI$69voZU=b+_VOm;{5_nDFX4J3hP+P{vjENtH*8MN?%TL4iceqzH&
zX?Fv;p(Wh{2oQ}9)QeaW&8S5Qt)e9(1Hv!ObhSMAA!|=O;4nRM&3%j0(UQdBh_6^X
z=E1L6H&hTsn&s&oY?5Z&S3x*w$pjJlK{IW%$l+mh|6W98X)@W8?$XE~0YXeOT?)<?
zsrI6_L7=%P``))`HZ3V9K*f1S8mbGz%vhrr=Jop)52%?GPT&f)B(DIU=p8xYL#8t=
znMzGYXR?{zk?2328G;ejNUHTM)>J@1qW^fTIC0@Kapxh3lE@Miu4YPB0*co=vZ225
zA(JZBWF!Zj?D89Q;NATzS!w5TwC7H2YxKlV_FEIr2N`nj2z!duw#J@<H#nJi&B*>o
zw%$9!jse&0rjCg1fy}_B@B^|3-;q6DexUabHH!$;*=9<ZK-Jj|;ZVj*8idHVl4^&=
z9hAz`Z`4)8gjd(14o!p|3ZGO^JWp)`3v_l3DCuqhJCE$w#t(6Z*nJo&kS5&`b|}U-
z*sqrv+0-l&V)JM;Be%&%oy#aMUu5f^W-A=VW<(zxW_``?ExwF})Zx>|Qh)#Az(GDE
zEk7}Y0+QN1AyS{`3P67JTqQuEJ_8juC#^Q5VmJIo{cXu2pZgu@T;`UqB!SPhkVNq&
zPa3kxYXv3YJQvwTr1ZJ$(jP1rYx;xbicWVht@w*L^0_IHL|;1znf9mMhHU(~A%U@f
z$xVxl{<+nW^*^^mrUu9jlj#GN*io5YAU9#AAjplHc?z_Z)1S*2De_H^t~?UZqbrXM
zOp<`Ku#PmHK4QtDc0<%o%*T*N7UpcoBTchB<V4TdQ2FUp#H0{;bYkL&JYF%mM4rGJ
zk3@M)Lz0R-$}x|HPJ8s;LdIGkJT&66#FQC%j*O%lJZLiKMjk~Ql^Hs&dg_j-8$02Y
z5I)Ji>g0)z=sfo**Hj0qS{|{HX~e|o#bhLTRA<5xo#yGXWhR3jowo8u0H-ZSLa61%
z0&i-0vFJ7Oz?kj{Y=r5afYIz;-S`VnE5k<zbyePym^nrlDW;amyB6HB@;b&0HI6I*
zD8tI{l);E}o^P8*gy-8vl0D|s$tx!F?&Lj`xq0%g$^<^V%q~jtlNa7_z|x&q4p@0_
zrUO>qt&w|Z`QnxQTM3Ht+8!y4@?Os@M|t;WCM0vcD6=QU%oC&k)+EIWnxt4klN8i`
z%-$po29rCbmV+6fLJ7hIQK=+B5~)zoU_v9)6tpcsD2C}94pmgyFr^igItw7mpl%06
zShYh!>`bb)Pezm>0axmwn4>F|RZQfS3N5%@rOpd(SF>V_Im1$WhP+~_U}NgBP{1)Y
z85DGpcP!R<#x6JNDWvCP7Bp%CktQuwg>b=|)QQZrmMTZ4V+)le)3v3>k}2InsTmc+
zJdiInbHh<J%ItBeJY|MC=~tJ?L6-_xrm0IUEmPU0CO4AZrK%U{@Me85lIBfH<8aDK
zwK5a$rRtf<`JkR&0EJpvI}-I6)N(ToU@F3yDv+x31<3?W!SYNvnEG}mB}|<>@)oAr
z9;po%D)#|3sQdYD8ac4!AGC0o-c1XK@uG-yjFUBDq-#uT1=BgEMS}?+)9Qhwkc%uM
zOdOeZ6DF5T+X@p<ru_veDkmEa@>r%Fhp8^p)I%4mGzUe(%(NFR%%_=FB_`brs}qxQ
zrd5hARcW_^Pt_vZ7Sn&G^$Qt7(?G@~qG?29o>5rZ7C<p*S`5$fmDal97!_SPXFR33
zE<Wh9u=};pow0CCDNwO(OleTDZOA0a6s=2|Et$tPO`FX1D(fe*!OA?Ue6cX0E`VB}
z%&bg2o0iy-mzJj5Z{@9(H5aLEm&xMG{I_WpW{zA_6i{T*P1`c_?85#Wb;Deck-8x$
zlV<D|DSgw-&5XZk3Rha-u$41!aN5$DS=dBEj^x8>k4JvuC2jUhVw`4u0~=ME{v+{m
zItMT{G8_n&ugssEUIs|8Jb5B833IqAFlBRkG9az<GPyg@=PYu>e?@-iK6ywme{{N0
z(7VhXEtW6kp>`m?R-=EFyfa4P>U7>fUTZjbd@1$yGI@b8KX!VGFoAY@lQ0i=I-w|0
zcY3NYn|FG%nB1SZ&oe`Ky2T)k_%iv<&}~cZH5PfO(gBD5Sm~vMl;-s0@$N#lB6<5T
zHM)r^iRshRMTqIu=|;3D1$(*~F-tpLlbFZdl*oiGRq5e`gz(Gc2F0B5=_$p$@^YkN
z>iKlG;x8`gk;NqT>9xf?_vzVXNOO|zUxp+mOZta-zoh?|A^8X$%tmL2w^CCxF)cE?
zpCJcnI<r~fw9v$sClq%f1J$)<;=2LG(D;wkHC^s3(r~0x9z3BY&poT)q)GQapUvy+
z0>~MkZi0q180kxhZ)uqv4h_6h;gC2=28Tw}uFB_;)ob#1T)w#kq)(((x@}UIXqA4O
z%1~dSX{Q6`q7^E=G<{)PXHQN8Efw579iiVQECaEGhTkU6np}6otJEr8HaE6#lh-O+
zh-5SAxH=#>uCkT;<oRlmoB`gk06P6=7XZ-*TF>dYB}ZJ}HP=FKT_6V##9VWOPPbp*
z#ry0U%$*+o!vjIADSV6<K;Z;S|4u)?ct`QZX;dxJpP2_@x;)3(JG`kk32pEN=dQ}D
zLb_M`1;d@Gp)!d}N<jLk+w90a?oPwQUB2Gd=<7{~@NwIVuq1hm`?b=m$6Gb;r*b>z
zg_e%#G|`9W`T}HIXYY1i!P5ht*LJwc0||HbRfA_9yDV>es1?#7->lJNKT2}gN1F{E
z;pzELWlF{dP${GE0cvm}ynsrdh(1_=c%X?Q6sUsAC<e2xBe<6sE5V9)R%}!4yTT<{
zd(0liTu@V(ff>+0E*ZQ*HD<(i7-Bm!_G9Q*5gZaF^qFbPgRU@xOsH7SFcj*rGgO7z
zb6%yEfcg{z13O2C$<Pjyu{36k&?$P;$p&hDw+zwYBxQ&WXeVv(9U$t*5E_cOpaqcs
zf`W$({8SlWWT9_VRFc7WieXFE;br2N=x7hv-7?b27}LM=_HT&cSHzUjy(+`14D@x1
zyD~=K@4TlQ<LwozWu4JyJ)0TfXIf@E!_VSJ4RzDh=oWR;$)O{ND1*-i6mesk9gJ^R
z2%B|An`zhYot;(H?hY|6H6!Gl;dRDva)sa-qsMm<NE*1bGL~;3KBXA$XB|W@n+~QO
z!8ZsHTmtfMX3Nn>P?{nQjUnNiCIn_YqZ1d0BJ@+cGE}P>=V%CZrJ^p72y>*m$NC&P
zX`L~dT0R)rtq{zCcnD@^<uKVZw9__5U{dcsklLpZ(E&tlLoYJQ5lbm8h%rig(}v0@
zZH22E6u24AI*{m?hEkuSVU1DQ3Yj%zo6oRX+YrU3SX|q{g`E+*<~rbv={3B9QNISA
zaE1ljRii0x*c5NA1DxWm5q@k4x7LkiL!6spm=}W*IRl+dA=WyJZP-^7K5gFXROv@K
zJ{m@0n*yx04k*A{y9S0ggS`jh$4>@?n_{eUCNRc2rviekP5pq~s84fYL%e#<1;ott
zoC`SKFb>|J)27*F2`GB7PEyf<I+<+y7pDfkXvOQ>h8&C;)o*avYp6R;RN@3M(6l9Q
zfZ+>mB*z)hk=z5u7;MoK3?%3tbl$*H&}h*gfGY!%2*G0gNUj8fsy+D>Y&$2u1%rnm
zNEsGD@#ZZ>@Mc^~8Kf<1qajO#2qG4Tf@T8qVqYhM31h^zNGL28RS;DG@cVnRSs0e$
zWV|p2cFSsIJDDChCtv|sl3l~VK%Wd81`kG&bPOPRp-e*23rbF5upEdDWB}0*I-TxV
zYh+U~Fyb{M3ytj{fe<f=!8bCwON?>kqBj|c*M}4+@k7DSa!g`gAyKIe#QR5VD~9lM
zF|v#wLO3NkTO5fRY3E=>x-|ZdoJZ2b#1BP{`Xm;NF?|wqo|ZnnD;Q&_cwcNcG1`m=
zaEKP`jqT*yk<I}rIg&hQAaUSmni@E4i-Kn$QM)=xdF^V-MCFR~LH_SLRPG?6Xqprx
z+mU`?C)v(A3B_cmI(Z;{A}=zWw36UxAbU>=B!jJIqDdN15JBlevSV2l*OK9smwZfy
z$b9H{mq5HTrP4K=7L)wRka&dTP@^0bmU`A0(l2uAfdm;;myq|ac&cpQCmt)?K^C55
zR|ex$GGYxRsJGfA7WHqFR7?i3Zw)9K05it`f_#e<UIXziuaivFpH^QZ!GN-(+I~!I
zVg~=-WE?XX%953AAkJLkd1FT@xY2Z>fJbmrpP64Af*8%nRY2mj#i3wE%Vi*Tiju1U
z8SiwP*hz0k?M+Y~EEC(C?WDMq#s;p)B8+q3JSR@Mfz(dgxdn)iPst4;DegE`oL>n1
zc3$d*6nH@5L{oCuNpP3L4t~2Fbn@G2(8+J7ymSNduSm>(c7Ucx%zp+OWU>P~V#iD&
zXpz$<X$A)nL%U8=(Gx36qcWm09LSg%igI>fR7I4C1Mv?pb$ld<SgD0Lq6QP$qQTKS
z2^ozn5+ZGM#H*u^{wO4Vj0R$3O?4dXtVtnh@E=c_$$^Y+0TbmCNRVTidK{V{aatPe
zwaI&F!CxU}%*6q(j!t^G`zObyAt6xma2jYYMAbQf;5ZVYC!mS+)8GW3#GnSv!$3O9
z!7X}be^pV9W{Ld-zIV};4kWloX?F<njfJ$Q2~E_f29-$Cr&?q@N`h4ZO1nFdV4Bq~
zeSoi?WUdLw2nJjDK)7*0L6bDGiRg}hR4~i-TdAnBzDgunEg&)42C}U)>un+>`^s<R
zNuEn+AlX;JJ)2)>B2CpDY_!bic0<%NPDU&G-x=w8lTR1&2rm<~Pi^-ZBtqgD$%gu@
zBC+w3h)zdGQ{)6oRE_?Zum8M^?|i*}^=jf?`vqUC+qxfiEv{ex{7+y1@>Rap>p$_o
z|Mhdd0l5~iXMC>TG>>)p#$WSjdz*F{^Nu*XMPw8gjT+?K`6>C&=S3O|`G~<gwUGNf
z$E|GP9$59yK1Jl-W;@8&O-kX|0!NT7-vS#!Z9I*Hb<BgV^JqGLWjglwd{xSAzmbfp
zW-1cfA~%c-7PyfNasuAQnS4bCBV1CQO#<^n8H#icR!SdfJ)x5rWGB?ic`HY@s%XOE
ziliQCuc!n<vZiC75sMULXgL^8l`hQ~OImhaTabb?6UEUbxa_IjWsX0ceVGBaY}&94
z`Msoaf~U~{@ENx5EO+R@hV-gK*+!GfXm;1VH+&d^WAi(F0?tD;sNZ3@{$id{H!eng
zTk1z}ekqpbTBL}VA0thGMP6&Pm@S#G*APYFX@})4;6K#lujxNxbko>988t3v!x-Wt
zQRNzUBKeuTL71zt%4_>zf^%y3-6v{PyU4Gh#ql<i*AE40{0=wJhUs0(Nq;{OUKXY2
zp=z!ug^&Apj^8QrPlhI{(1zZ?=(?05KWNYMPzo0l`ZO1v`5F_j7q0t_In7Ij#i+sW
zs_3jnPyX>tL>?fsrp{$8d_T&{y?pV*x&JQp0gWk*i~6Rp-S}N*(#_vpJ+`5^>6y_s
zr6~CFMACMpl^VNkkMbI^L8huQU=Sbe^iZVL6ln?$00YRlKOfdYkL{)67MM~{FN^^~
zpx4eWP^22O!f`Ux4F{5<`%ZOQ(4r(uh`Sy$3L#n%?_J3H0Y~r>x{(SCS*aPr9=eqx
zS0|>2DM<x^HAaqO3$yi<Bu>DcxJZehMB@x&410P}Bzia#j5R?l4h31$rCX}-s3;jI
zTJRAWzxPUNBXZq;M^?7=miQP68>iI5OuZ{E=rb<5%V2N??G;9()1#$?V;FfmlRT?1
z8Acpi%65<;r-TP!*-ktV1Efv8z*JXuxWX5|n%%N`4o<Pm*2v9dCJ@}P;qaL_P!F0h
zQtrh)VVROVD$n9B9!j6tQ|iK)E`wUDqwE{&n*6s+HMfeN-0y_dKgvvuHgn;|-kdz+
zTkH*Ej|WXykF12ZJY0T&u1e4W-s{>LN`6Rd8}b+`;ggteVK%H52{Vv@?w0ds)LTJI
z;`E=B&>-hQPfmX%=-Gk`9~l=j`7sQ`;{rjtS=w<|k=QC#fKtriLOjv%!)yvRDbTOS
zwI5aSd#=(*K?$0a>TU|Dnam2;!#1b<Dp1yy+cQm$%7vD|iA$Q?#)ZB`$)qe6>y7$g
zrKy8AKdFAnHY>WyjmGlMJ$Iyjp4nYP>#-#PChWJH*l0x-T4)Ag_Tk2y#Bkr9c{Jm9
zlbMn?TG`K+K?q6W#-tmB9|9Twz}b0<mNfpU<>v=4jNwg!M&qVOm(OocY3lAbV!c1%
zfu)p~<Fp!q^DD#cR};M)`Q7LVBwC&o%r`~!GNs6?EQr0_@v(?msmv~e&Rb<cZiUqy
z9<$;#Aocyk=+uhXm`JVzudFJfjfOZz>R~IqS{6Dfdk(QRJfF!T(?!&R1{)}2v`J?C
zK=6j(Eh0RxjBRNmGuljq6s8S2!i|z}2Zp8Tp`B5{$rP}OngQDrP7Fq}od~mMgdCXx
zb|E}y96}f^PPPvBbXZ)yK_Cv4m>x#sSOx;i!#H^OzNRR^qTpsZFT)=aQI#cw3mJM_
z^<oCm8XZ&^e|n%I@O5qs3d~?g2Ik2#yNR2Dq0L6(6NNb-kaG@gJCY3J>zfu$4<rkb
zelTn_gTfB7mSlJl!<HB(6tAH*il=vk%tU+zLRB)@;}BH<y+A_04&HsNbNGcq6%-M8
zbOaZ*DiOqiHRf}5Kd>II@4Vx5A-Haw@W+7@-*<Rp!_%7n!5g^3WX_L`d~zYidD}{w
z-k}q|IlzX`sr1W}^C-Rf(tVPONqHzrk;Aa%Rq8bc3a?THhbf2->+WF}wwuW>4|bWG
zlii(yRnBB5ZA2c62oE&)IAJF{aLr|A8y&`sNm3?fqzX?Ss;Rrl#U}kqe5X}@FGEJS
z$@hdr{aYpR)$CT04i8~Em(mjsA`Ef-4rBQmMtnN|ZaWONQiREbD={o%O~G}B)MBme
z`k}q%0YP>(n(JC3Fo@Ae0Qb4-mdfQjtsIrw5LpB!)i^8y)M3c7z}v$jZU3slAiMKQ
zdjyo)v%WeMyz`4Zner(u5LLcPE+)0`vHhm^uF6~=n!sydk82&g{<tPy*{(nK^}1D*
z2Sp&1d3#K=PilqJcMMwxn0vlupQsy8EDH=Hyib11@G&U`!JS=uT0~>bblNQ$wftUH
z`)slE<E*TH{<9|AL%6{WHoF{s*BrKkE~jzLsV!w9VQm_Cp_HxrG#6`V1?e#1%WbA3
z<|MCaZUcE#P5*nQEl(>`xC1RyvTfG^u8|#_szanM)fA%k<&-x8c*&M=U!>Dt7~9J!
zr6e>mgSJ^-ivGwUqY=C%%b^(Pi1-I}__y}KvU8C)xO0^BH$+%%DhU?`i<Vv9Rzc<F
zS3dY0$7ec@;#@H+ueu%Uuz&WR{3D*g2wiu8uh0Q{O}bX$io0=_iWLMMWm=5D<XUtt
zFr@V^I$T&7{o*zStsj(3rWC+*S}&GSG*Ah(+$5nA$`DVOZA$aI*OC!qLz96ptyory
z{2C$}&-EeLpA8yEMD~WkZE>X{!%<_+FBu%RL;qH}3a5Th2bm3FvqeEm;~3(dUYnPE
z#hf&Xpsp)b!OBP~R3d9vLmsN3Wg?Zq35}LwXF(f~+A2Ek6wvxEaWo5+md-MW+AKws
z0u9<FWnpj7p_U@^B%Ke6B3#^>KRp!c!BB9DQvg=zf(!5h4dEH@M`+wiF~y~>O`16n
zADvKN!UnVisgWz<#8-7v7fEeuMW|%a4pqTRUy2-mz|%GLYz>QfDdH>iaN!(`v98BF
z5!2s}qy?oWZ6BIdlL#*kS7V-p>Tr#DA;#UlX>LIgQ9ETs!UevEq39;HCdG6uGE}hX
zR!t*NNv={T<6RqwyI<^WrRCjkmExY4AjC?Ryp|y_X6Oj<Lp2Uf1;=uz5nV%ggqu`F
zTorRxemnQI53(iAGi(c;7g(G@nULHm+@V*~`b8dh*I7k%z#dgP%?AasmqmGZ$G)H(
zJi)H-uh#xNQ~_a+(T{+pj44n;#W0lJyD}LcCi4(fT(GW|L+RGS%f853S#Y#i#?L|9
z2*vxMq_sH1jaotN<LZ*Jmr>z}`bJYjvl3^HHFNYt7U;D}nMfO4rY?d(a6K6;RdAxM
zic4dLr>dwu-+<iUmwC*g%|lF=Cq+Xx>nYtH(lOUr^H?LXJXL7XxkCv7tyx?Nsw_~R
zip~!4>ZabTTBdM>CEPM|qHo}fe{xawFOttghq}#a*aK0n8Rn!u$4wuZqr<5~*-ez+
zR7rW^>ZJ29=YOM><(8vz)4StfeW=a23smSC!)q&*vp7bznz`m9JfSI_j*{j{#ksln
zB?`*v#_7Zhktw+m+;B{pW|X!|(^Q$Sq%A1W50W?KJ90jq$8V~{@OW23Kcy-<;8c2j
z0i?S4jubxYJ?{^kpm**MlO7SX_9(brX3h_|d``(;pk6(cmFs}h+^M8#5s|-4*+Otr
zX-W)y!qfazuAg)F%Rfs@u#tMK6<j-0@(i&5t+G$8(6g+f1XltCDSs=YaAyln#FdKb
zy)ZX}C>KG%R!&;yUG=Y6(C>*1UcXE2QKi}wmPxB*u53GlsJTK`GE=2?v583>d!QJn
zQ@wan1BpAAD3YT<!gA4SZbf{_M8G)I4s{f1Y2|`k;eBm#Q?5JNjJQedWOXY%^wfj&
zTcRU(ZN<b}E0)Z(j3(zSblP+&nuuS|P*8@_kesACeyu)0sZm?8u|TKkCp1zLCo<8#
z#sQc47m|tzN7=<JkAt956HyZ5NlpA6jSN$w;%KDwYGT)E$6ccbrLF14(2V?SVz&Up
z-psD!gMC7?*riBL)#4rmFeD`c)m75FY@!wseHUqclK2F!?$*Qx<vz^G0Wz)>#<@%4
z6Mht8{y9STEeGXBqE!(=fY3u~`dC`dW1>YEx1>5}ml*UB@kr7NKqHwxu&Xg9TX#yt
zH(N0(4#^>)zyKvKp<0glL)JqoHLf75oZN9L9D%_ZtsRS;B91_Y0V)i{98dNavYcEu
zKrb~#xyA(;j_1cdU7|ZvZ7~pZRcs}ciij&X6ukmEv$h}7L`G`WT`7pDMW4g+5CE28
zkkkh5lZIjMnPzbDz`al+$^nl_TYJVm!kM{KmkX5;6oy|OB*pNJjHE)`1LIM^0`6Nl
zlq>xnP~j>W-vKi;VT*mgMW`8K>n4|cbf)u<C={jEbfmBDwav$IAjs(k6-X;{L_+ri
z(d3a9+19BEh2d_^@RkjysP!u~T&d}S&wUNU-a^RT3KdI$H1|h3t+|%HGRNG|7XCpW
zSpJnhaK9msf>b1S2?9CFt02_a)He>n{+kB!;f+*OHVG0rUj-2r0Db0=Yj*|b!~3WP
zT`5LjdlN%&FO{Wu-A#S^{66?uQV_^qUj;GHxa-9WZ_3%n_rZ&kVgSxpF=}L?=#AIi
zRlkq#i^o<864_n_5tl+m@+W<T`+JW{1Faq<vi;Db{idk?gcARzx_%I(hPzQv$oVb^
zw+`sRKXQCe&G_RR{V@b0e!hhC{w`?JvwsvQQ0-+HsF>gUEhzPunPNBH{WRdx=D$xd
znBhN@8Q^#qY_o0P!|0JT7CcTc_!UzOHU@hatCQgYJwE|2Lmf|biUD9y;)7V3jT#?@
zHl>y0aS;5e>`Idp^_$o_SxmA=+ItnF`>Xl`W*2)C!m3DHO!UXyI`i25@t8>vh&bUM
z-gu;~Cpu&@{XBNQKT{xr;{GB+>kuqRQN0;?>5$M*9TX%|?Oo7r7OIcVGikGW5Tt3#
zC`hEP?}F`S0h_8So7j8jfUD~>8PoQ6!E&>(O;s)L#}0PRs)LTY%iaYM9<Ux$RcGX-
zbK<csK_I2P3Sz6Ef$*c4{WKXqypfj0DnTO0t6<+}1LQ}<2eL>$c1_qDPm0ly+26z%
zssQWeM{Wmc?|kf-cuXf9Ak-~A3PLxJBXtPQ$V*k@u_i$x=euCJ8D~Gv7;-n)J_ypP
zTO>$ie;4FntQd^G-L1ioT@z6vJH=>3Zf|0^rqQxIRa3U+_l`MCg6yjGRS>S8uw1)f
zy&;c+G<g>a3fbQUEe+!zzaCF^@&^&O+D4qxN2Yaq6{$CS`{#?98`1**AV@>KCN&X}
zEIkO8n?3&{-lw$iKXynwrmsQBdsT5kr@uf5-aQB&s~V535+w3|xoP{&9pUpu?(%d{
zcz7fH7_hB;zS6Uyy$Uv)-5oyEsHXqJV@3Tb9qRz><z1}ad?`MnrB3gP2SGYvR0$F}
zUIin&X83A+=nqHNjmJv*Gb=<;++IZB!bJ~|PcR=($m6@{_OVM4$kyK5W%4lj$Q3aB
zO&+TlkN7=^rS0Vn_2#wmk*YNPSRMrF?$RVk<a`x`*^*Y}j~I2+&iq)_c&tc}$omlz
zh86||eB`EGq~m*d<Ek(k3UVahFE()8pi@r>-ram2s~V4O6eQB?yI{FF4MFhcM)X|O
zH6n~C2&BL7d7+P%Q&I@t-IN}y8jn>85_vzgLfs9gCkW2SOI72sm4ZUHcfoq|sS3fn
zm(^oc!-+~Kdbwx4p6J_o-h8$~@b1O+Sk-uJlOPZ!y?A)zcJm1f!Mm5(V^taQ7J@?T
z^=8)SO%%rPkeh&)ipEooVg$}tv32%m3$dGn+hZl;sX{RV`<vLY-<;(_?(RPKSj}*U
zJ0(cJyZ$QZ=1w}}ePFLi=e);i_6T|mA$at?&&`8@#j$6SRg`XjkJa;sTp#h7d<9=N
z=LV7*`VW4TvLHPQAFCLTZ4v~cL;(+P>^J|!5WIUVK328Bu?&Jl+UqHa{F3y448glc
z<YQIiu_nQ;x$`Et9XJ2VPY`O}JT4#JI0bG)kjU{Wi1QxZH$O7#rbFjrRpT+9trK}Y
zTa&4AxQB*NI*UG55e}m+z|!_85bTO{ISrYc59(vZYIr(Q46dvFRjjLe*q$5w>e9pY
zK@d$ZJP@R7Y<m~1@|XRHDzZ3v)N>WxrF3@zy4yZ?c@X8w>+_?mQ|Sl#ShaX;lOR8$
z*MnR`uoN9pL-6kO`&d;*yF-wOvJN~5l1pI6b+jRvCY_2O1nGNh5(HA$S3z+V@Fd@G
zq$Be9M*2242@-id$qz&J>;e6eM@jlbKUOs!s}vM+ybG3_hxI3D25&ys4}x^f)>kX!
zconSVLoja3AO%dH?uR$h^}9%r$o?u=Suumfr?ubR!5^y{kI}-E$o?+KQERMf-G6gQ
zf2?Xewn~u5_9|HR-`j|UqCd8A{a0;V|DiVWZc=#78G?70`p2rqV}*hx$wpoU*PDa>
z$D_Gs<WaEc>!4uM*YPH}Za4q`k2`+cBLW@-88}cWDCBq-WUqFZgGQ_G5eE-~?88by
zA;-JmI>#@3$QPFZ4G&@rd#Ds6aJ-0BL{v^24sz-!T;fTPQ56k>iM(!c6<H7%dl7>7
zXpG0I#$!!_L|zRS&P6uGc6>zTmeC%MRgK4*1e2=gP4L)mu_K?z`hANgc@SjKNu!{U
z*UNDQiCK~LaX5wEqE(&*yB2#20(rMS)}7=#JaJTHLipjtkuft}f<WF+95t-q46XUl
zxhi9A9xJ*BzYoL!h-2qLtW9w{A=Q7J+z9sBB;@7yvm43Y7!mZ5FIL6~Jyx-BXMiAs
zi`uK;28%<be!haQI75)0tI9Js1Q}8Es-LeQmSI3s2;M`S9;+Iw=1D=tM!hci!_g@N
zratcGGzU;U2r*)6g-}LNJqz`H4#f(oTWr>21#3)0iUHVP#XwerIIkhs&l~b6xap2d
z!A*DESHV@C5XwbHwq#)0V^!JZ6eM!K3eqBmvuOz41J@p_8jqO-fwc8i(AcYV<YH`3
z2F5)IvJbVn5NWTjV-*=+$*>iIGxAbZscj(0h`m=2l@Ts6NAZQ=J+AMus-fXJCCGrl
z{wjzHF-kB5?{R~VRgK4Z3Qpwp6kMT_ViY0-C*-ZFYbY@(NaR%mR6%=!C`T7;H{|h+
z439Jkt{DsYA_zx*22nzALf)$Ck7?;3qD;*Xg5?&Z3Bg;~=5tlq6%b^+XL}Vy`nm`L
z4Y4^W^s$;jT6aQ-k)-`ah<6sF7geqGhCB)~E|p$XiM)DId912s^lAv+<5?f88jtC8
zDCGTg2!<C%2SRW{-m2=4Z4w01U$xB@Jf4WY4Y^x5?qfw`KJFA_6z`iq%<y=cLwi3#
zc6AH(eGo)Uu$>fClyH9+thdPF4@nAtvhilfagiXA_k;Sn-XfDf9%p-xRelg;NOO}Q
zkyi)qg6Kk;yCHasg?_H8KekB_$o4uM<)kx2kzn~P*7`vZ7Ku)KPX=kfT71gc6u3Qv
z&MA!hL12r@KwxuUl~;lF77Xq}zlDcCRSl0d2@-j|?>Z;snZf2C1$Jln`NJC-rM^iJ
z$o@WV$94;5|3t{@gggqu7`$;|%DDLcF6g&2#L9<QmS3vbgEbIB8~nvyh3N9cD-UU(
zGcNx@kWN-6K|1NZUa|_<yBX#G39`Wnd3+;OH~TI@5(d0lL<)$E52{DUUpHEThxdVe
zV3invSKVmY*_tgD`GS}wQ5HOi9coL62{>QH>_&eOwY(D|Ja$SvMn^p%=c|WbL4G3A
zD@0B2gbR-y6TISw1j*E3?}F<@-|%twyqV77K`1yMiiD#4>h@n~Z#=2>DM(pJ<ne7}
zl;{#H@X&tM`jp7TN8X93=Z%Qsu}f++hhi(~D&EAx)Jal{sO632;;~y$Cx{VvRWQ;y
zj*J-}UkL9U8V`b`+Gr9a@;<3S0Z&GbsOgQP<GEwvu}y+N%IiJ1AdevlKccF43XsRn
z3I6_5f(&?gb+Rl-2S`GZkMHSsijjvml8K~AkjQKNSV6EY2}`1?cM6lo&WXo12?DA0
zRS^89Bt-dyOX-9>3W7<c=x`uzmDdw*K_byA$CCnrjbvbX9FBO5k)w&cUOti&`oxud
zbk3dO<#9OTv5kU6#QE?b*k-<%=$jjX%;RAAQ>(-PyqZu7Vhce=^AWGI*l8XIBA((t
zDByJ;?1*5?ao=a)Wf1mg3dI7jAEsHkvFOC>?z}pW?~BJ)2@=`f1=kx(PmIEyx94%t
zSuqL{d39wi&=68n7$b4#1$rF#4HcsxkX~N}BbQ~64CPSt7mYTDy{`~K@kO8QP4C%@
zHZd7Jy+fMa52%lR=(*#@hlD|1XNIKbY30$iy97zC)LsQ`zws?$kk^@k>3LeAViY9u
z-YLk;8GKG5mgSdf#zQ@XP#*LwFG6-Bii&sLsiPj>7Fnwf3W{^;)n$Om8bCya7oHO{
z)${w#gJi9riO}lJMqNO(O_r+|^gHj><1~xMv=0y|@B0AMT}{q3RCkG2>v>7=$5uMQ
zB_Y?V`wr6PkU!@m60Y(Zb0}^vh8zlbjX0#oJQ=_~QVu02*yGm_k97$GsqYFJ@|{#J
z>B%?t_@zfagcAcE0xz@VoLS3aF}~55J+8%j7w1TJyi$NZc7#*SRNX53c0*ovn|Mq|
zej@GtR@uwUxE34gje_lQKdq7Vbkj;(BYo@-Thv777H5+izuV*4B%W#%Bk<<Iesuw#
z@H5wsk8g9uwoF6(c7y@>9FCC_@N$ZD?i#74NMiS{nd*Hewu@u(jp^?3lpIghJPZc#
zx;8>-OxC=Q)P>2T_jvP&$2JK9>8}QP*Zr=^$`=>GJ5S%^)id5G?S=^c-nARJXVCHX
z<0{t~c@!jFpuQO)@9QHD6C@S<NI{u2gOB&}c&tzN@?dc)?}BzCEew6doyPD{J>ri|
zRVDwS{Z!SN6!8;^(RHRtd=Mm?BK<xSc{R>^%A`}Ii=jH2Ss0%+NAXmr7=Zna4x@|&
z>U*Kc_T%Giu2}QPf%i(y43QscgOfAzQ5_kNtr8^iYWyqsT{2L9JnZ+*N%<g1>dMq<
z5qVenAg}eVvrObNOv=kg^|e1G?F)e8{pf@Y%ZH9!5xD)67_!e!l?>o`KW{OU@FAV)
zvHeEY`Dl2E$D}tE@~$~WYEM4)k(&2ML2`y>Re_wZOe>7cC$;FugZ%GgqYr}MBt3Rn
zO2|_Bt_BSSKAB6y3^V~RRv;fTY0m(huVI#MDmq1r`U&0gIq{@ESh>iiS}8{0bs0L#
zjdS(my5&0y>w_T4T1|omcEeZqzUwhP;wIFe1@?ROoGtNHV4Hbj{Vnx|JPKmzIY|nZ
zl(Vma5#$&l4Q-mglbH68g2`W7BuHfcNpPmQ4NLu<`1V1N{J2emM9z0X4ll3O72yL(
ztotBH{@t$O08(Br@|6jmf~NNiZW<HvBuIYW^^hPLf9)s1i3K<uN^Z2k4`M+cyq*#R
zoAB$bsrXe=41b)S=}tQQAV_XvITQ$aU3AA|Glg+D6WvLT9|XyLZ0b=Ub$u5+XNu&H
z>*Ht6<OeY_D{m63Vsd>KOZw$cWcQrtm>-0kpSEbOfW!HHroc^?#Lge5F}qVeKL~;m
zx@fY9Bl>-|;OY+I=<wvbF-iYfOnlRYVg&Xd#3okia5%itR6mH3%(`VIncnMNjCF$3
z8Ir3e2lj*Du0DVuk@oKLO-|*C`*{WH%nub65jVSqKzqBZGg~d`y2C5>PT>6@2%c|5
zgncIF?^o)C3O;O0$4}6K+q<zyJmNA>CA0XutEnF2(Dyn6k7BIW${r=~I?=-6Zcv$r
z<F<IsA07wuxi^S~7Z-24aifP9`<*TQL6D^CiXRg49%2DS6uH+wUyLnCHugUYinLuT
zGZA}Vnc;f|ZuhSUL70(8L6XAvsj80H`$7wHJW|I;w8WiE{y~tO^SpcsvDa%<jkM&V
zrvD^0eR~hC5~sbwxro@iQ@I|ahv>fDx$qyvSS@;pibDU@Llj;>?D&t<>d(ldAPD($
z@I}%8zVGc!he_hIkvi^9<o{<u^8L3%f@Jf5rCO_=`i_idpU5vdr3rWt@>~M#lu+ar
zcvY-b(4jNoz=&@vzoj5}5M-W9a)4y+g7@H+gS|=DjC!^k@+7EC2&)8%ygGw;i_XlK
z@bMJS_Y4XTf=slqN|4CAqwd*}k6}b%7UgDmcsQo6e**sZ3md8%_<Ck{_=JIPLLLM&
zEreo&g}lcGuXV~E@o@{^oK50EC{j*{=mq81llpilmQ;pOv{G)!qu`;n7=l7x12=|o
zZ%%vhadX%`5yqbdl`lhY6!QK?*!P%L<0AuKCfaxqWIm1}K_ah8i_8Yh&9c>ULmmYW
z%^1dZADS_*f~Qh`Fx0-^kS9UVk}z%W=PQx-7=7H7jC#=))XDZ9nxbSStHc1js$u8W
zfYgTBvhCF+F>|5N12U0!8l8IFQl@|sVnUt-m1|{{Ady$Dc(PZRyne`DVeei)nagFB
zAdy$EpN5<rhB%?dTgF?QkkZ5;PAJpHyu=BSz++mT%zn!*^JhUOp%GJBrlomb4sn2D
zu9{$2xo59=5QIvt9TH^Pn^*c<PxjF>7tY6RdbjL2PlC*D!{8Jl_Ik;0HVs4XO1tyt
zhjFclhwBf6-0LlI&qqm=GnLPSAT$1S2?F_Hpu^#SiGhO1=$0wyK@9nX7(T2-<?Byk
zbJn4c>~@)l=+A;mS0pwZA@6KBdaSE~`we*%WW}lkiM)DQ43poSG%47%?rD@B1UVmh
z_)g@Nb(kbv%ncL_V)ryne->0Wr&WSPUeB3>B`uRa1xMPP1nNO3G;gBXLguJ<ilDvE
z>7>4b0d7Vf1+nxgNkC?%YCj3i*{Xu&?w-Hu&w@&GCF(dL?bVdjJh`_hUW3B#mLBUt
z3`w-a@&e#J6ni|CskS~-s;w9I%FNHzL^8OdOa1{No#4;*TUxI_3#v*w!3%jm!5`2r
zRfZV2Ic`E8-^k=*s|1O>1~rTpO*zPdHS?B~>_Kdko*ZJE2J=m<tC~n?1aHYqdG;Vk
z(*u1_GgsQH52}-Z_DrA_%%}I1YJU{W%xfk=AoZ2iKrIsYi6Ji6-a{ym*)7aD5G3->
zQ@ujLRiJw}gdQs)+=Cd?#xdiGfH&Q{KV_L*?&Hbj?&;?KEXb^MGSOw8y4TNXJT@h-
z`-I^ofk!dqyjypQF$vyl608zV_GBXdc=yl9qaai2bqRL$@DGA>;=PYA9QRaw4}#3t
z$BitJSN=Ieq(2k;eSAf`r~3P|pfUok5+t&{3$C}sfuGoBCgf2NE;tH)%N&IEli+qL
zF`)~dH{?-}84bGxH;nA7TiErO@*X<(`;-OoLEzMu@<H0fR|i7ws3Vu+CzR?ZGb{dC
zK*<+Z7hvg;hm=RD;QRgPAjN!*4?^jU6GBY#_ybk`ocR%a{^y(v@<EU(Bb9=O$oZb=
z0H=K>mi*|rpQ$Dv1Q8K%i0WO)kEsr(#Fdef;g-qr&tl4V$pufqYaYIK-m+pwdW?IX
z%!l_Oo#wtvkO?+l)iQoLTQlos<kh(6;d~Hex=yW?M2`2hGAs_r>iHF!O(x(`49P&N
z!~h)cV*QpeG*Y+RbBI0&!u5Wmjz5!+z9%%Yea=W4$!TsWO8+dzM5dd>0{E$#=Pljo
zCz6{^$m9E%CpDA(00G6=OGT%2s*$s2&ae6;hAgbgEJk2|7pu2atshU!dQaZ^Acz&E
zD@B{KzP{eRM!n`#u#tD^o*ec;kU3;COAwIlJ!1m=v5{(aq?Ri8+_Mj2%uoxDyaZlT
z`GNPOW!4KMmTW&{y<h^|%zB}exbKT^KW=GqBaPXNJP9hlZkHgC{>r>$2+oZ(ypfA+
zPRsl7Hs<cF5Mucy^vo-CW`f_y?RHQ3`ydD}?siI$xq@FQQb)Ds1i~NB5PVN5{2<88
z!`Yia-g&G>Vzs?1KXD|?n}A2LSQn(D5%7Mp-HgePBN?DFAwN8hc#{=<?}g{n5t!$h
zP5I+_5%2kx9|W0(Ss7S}wD$}w+pcWQA5Sltxtsqip!Ck{fhfI<&wk4Q9dDVDmp36=
zOoB`%{i>S0CcsUoPwA!~-c+6Dm;&|3s)4Mh<sBU7gZ9H6T-mO52N&{w2S>UtCdK}I
zF^6xa$$k(-=+Jsfu&JuAf<;NUKb{&jQ*b{BM3(MNIY1+b@kIdfXe$+hhErW;_I?mV
z0NUClNaR%oX*jMl`9^zc-wAnnqsMZ~H#$>}zxpkX&W><ZUjY!&5Lw9|1UAI)?il0{
zcwS<V5;hYtB17*Fc^H`zU5V!iyyu<6w~NH-c-@S=yw4vyl%i5O*x!%VJ6Jc4lR0qD
z8F+i2Kec7PT?fuLU&S$PBjvj8*~fZA9tD{#UiWPw?{{t_%RQJV6gk7+lguMQ`OY+<
z%uGLpBd)*BwI4_Qy6V5J`(f7~-O31?`saW8`qw|H^z)gwJ`>W9AI;?O<OWHEw7nLQ
zJ<C_!X$J))r>;P}_O!kT;8K=};m7S{A+pYy+h?Sll=4XXok5E;a?NV~P<J2>g)H+1
zJIYREqKihRkw5RRUL5Lr$ltV`zt=`t0P(8rKzFiqb>=d^d82+J)44PI#*AeBeGKCK
zvV3ROc~a5&6dtTh8?N^W^r=P85wUS=T{Q8xKD8(i%NBWw(_wY$1yp{I9mffnf3JO;
zeln0cbyBpas+)ZJL`GY7ls6EGL$f($8bl&Fh|xe?%$BJ+jKCR)(;sas8W3sUHSXX?
zPbv&Y76;HE<n0_Tt!NM;@&?jb9u4dy*W$J?yk(E^@dPxQ*fsF`iLCd$I6DGbkLZT|
zz#}kDE&=&7-0KarWdp(N*vG${niyt_fv|~wv0NNtBg1pA_NGSeGi}KzIuBTHYU6><
zbb_1(Q1oV1lSUWSPLsUBBsma_5VB2GJs+!0rz81*YH*`qZDFt2`Fj`GnO)#DaDQxy
zf&R(V;4wmW=snS3J0<~dvUvwCg#1OjUNnwTRX&3TjabszI5HYYubf4TyY;EFLy9-s
zlrqi*$e8AjYciH_^_NieLz7TY`Jis$X;rOhc)&*%JV6T~@0h9)LN0G($-AjczZ(Bs
zreBT4)K-oA=H0YTzv=V9R+PN4a&533+)Vyuv0gsvjsNZ~Z8?0KmpFE@>J20o$S|uf
z9#FxdA|unTp+XMvwx?9Qben|6i<bdODoCVI^Z4*;%fXGsbs!yO7wIv6cVwlA@0LxY
z51tw^au39Nu)$eqaVWa6sT+;VSSjVpN6RS?@`H3Mg#3W!^Q7ez00myl4?7O2t+1yW
zYP{;BbjqH^A$}~NhHGm|d5vo>$U*K^&q>B>?13x`5U+7PBve7ic4$n<v!?OqBk@r$
z0gWcqU9AMaQ_U4QZjH5W>d`7XHJ4f(0+AUW@F^prHUraSRd%~^6Y~y6)%<X?1bsF{
zg3qwpFFp}{ppAJi=!4vxNlDj!p_^88L9W<1gNe0nAkjW-%{vY(6{H)BL(#f22}KKo
z?r7YdLx^q|1Bqc}K4ObQ)Z!3^Xgkp@tHekNsM)X`;=!ZT5i3<y#GS!us48g}HB<vh
zF>giTe87=xsmi=!h_0x#W)C2Km>#NBwpAs;abzustXzQjVCgn~Azq>c)?9H7K~Yte
z$;&n_poI=pCOSsaog1hjYSE4W7K?!tNv-}37R?i!5C_sx_LpmxfG8x1AE~z+2$~o(
zxfUJNaikoK-V`zno%Vi&)znCuwE&79*4_cF<Op4jm2ZnBtmrtu;Sy624|L7Z4GY$K
zQV5q?@oWyn2X{Ty&d~vNJ=8G`GwTL<^;R78HY```p?1f)w<^4OAVI;o$MW|rh4+9c
z7E8~nZ3QGN1K~8mLbJvZe{sYIe9eiK2&YMWxOLT9vyESk+Lt(t)>Z2aH2(u(?-uVB
z(|8m#nMVp(R6uGP?JHhnzpmgo)he@L!B{JQ1E=zpWJ<7kEDqs!Kwn;0O(`7GD|psM
zIqIf`2d8$Yoy8REC*Gx92nYFr#COh&l&21q9sJe^gkRzzr-eSxl=4Kp=OHO1sXTQk
z0pH6&xLd$FF(7ntC+{#a`dSBd^~o$67NkZ4zyTo`g_fWxk6s3~Rgs#=dJqija^GXm
z8Vn5VQBZ;pCcEe@q?I~#MTA?elN+Nlpu#^*J&FvBr^V?#AkY7E>MYX1t9@#2fnaPr
zgN7r21aw$SK%QCa)cgu+ticDtMj(?1^+3ktJ16Z7Ze;_FGJXW)`ls$8%w2PG;pxo_
z?8_PxbU>^KGL#;tYJv<LM@|5eW*>Ubn7pIBVs(IRX|Q*&gJY|8K97|`-Z2LwPzK`t
za_lJi_Byyd*xf~>*xzp5ji1cPu;M3kG9Wj6WC&XTd8Zt(3>t1&WGx9Kq!{Bu!}XwC
z;V8l-en6O3OhbA|`(p>*MYW?@{5x9g*(Mf8Fn>In3RE)R3SB7&{eu|FRSum)Y!gSj
ze?I~F<UMr3G+%Nr00p1OJNFjc+RCoICH(dmhxlfspS?Zguem+r4c>Kbu^_rv&G3Ef
zy4HZMvdCG2p+z8v4<M-dBh+kRAY9qC`xvr=>^j#VTD<I<FbL-<QVr6RVz8aFGfD5y
z@xn*7>tutQW=VCT@jKdiwL$1(*>Tuq%34x887!M+Z>lcY{#*7{iOMz2LjTTo-E$Dm
zRd#JlxUiPJN<)U|odMz9_)7MQQgpV?G|UgR)6okt7>h$i55<e<ZR8KFfpnDPHQbUK
zaue_Cf}&4trG_x3+1)h3a1}18uWb0nwnMuiJf_N~6{=yg*_dDfLAwLMW)s(8rO;R$
z@fK}bj~YIcZ4-j;WZO{k7H&{zy9?IP{*_JhsUc<3rWw_k5<|xs+-;qTO^6>v%BGD4
zIqr*CV+Z1G!l4(}%aV#hc<B$MU`o|EIh3yTy<%nS^sOPELlIRS-R}oMVw9qC9Rz^`
zVG@)mV~wI0g&|!Vxf}xtkvvjXbZ*xG)J#xAv91I!tUtEkzUl0SJ15An1F(1orFb=m
ztujLp)yfum<Cb8!UJ1pU_1RbC6BUV|^NRF26OYBUbomYHUdGgnU_g>hJK)ruSQkKV
z3bM`xP&7v>Yviv4jrg~_XGfD7O40pVCnCS&;t<=sqB(S7F;K`C(JLD6te!(CDjVc6
zP7;dtlry-I<9mhMaEW&moE@2q$qLiw;0nFC<8@SBdl#;=<UbC?R{`;4lN_fY0lNRt
zhJ;_I#E?DEv^xcP&;YOomCZ}&*YI6l9Ey%D*z!y>8QDag+7`XUOk+ChlyKG&|E)vu
z0J<^uA(JK@ch`aNJxDklsk#<Gk!DOcEU*L@g@hUceTxDpha<MXYeT^gZN*4=W^qj|
zrWK3nmaXeYafXtg4T+ToXEKUWGhOXLOk7MK0-~A8>HO^u+sJ?BCoK4H7n4m6&iMn0
z;aHJbFx9^+)*{1MdU3Dp7>}yo!Ii*t?m{rP=TwVPTyaTY?A_u}cc9~e0ud~@2vrye
zzU7tK<D^1dZSf-J?TUfdqK(8F#dIcTKIPCW<1#r?&2bvwHd#{DydodE7)=HexgmA4
zV`i*&&?E<c_M+Ih;fXzJ*SL>17~V^xwqPLsO*QSLh@Q!Wi4E7uLLKw~B3~Y7_dtBC
z8y9w0rxZmLHl&9sEh3y6E|R0%Ai#W!Jl-{2Brjw^k?%k?HZQOWm;#OV#(_i^b=9Kd
zb5Y>oVAu0L>Z*q+MJ4+PJ5GzYGE1Xz1j9$XG}CJuDvkqXKERi@-?CY@lZQ~{;v7&6
zjj4&T*R-Y<;?ybidc%Ek84zEFW2RK@7vd%KA}10J;|%mFt<qFDg1Vw}`3*Mamlpf<
zK$Hp77meXr9{nJ*>VTqmD@xI`{A}C7te8bF@+(z~uhvUT{Btz;*!2@=@3HA8(B1<Z
zhobTZ61USvHQ(@`_piUvRdpaS&9U9JxN{a+4;mA5wUwtAXWN7jdw~;bMH4ukxM&Oy
z_2{RS_P7>#%G#>hF?s8$+TpZPPu9*)CNfjFr@yyR%;Li_-P>4CRjw$pF21@0(`81y
z1noeB-$aqIqrsd$5L9LL0xH71WR)9p+hIg2mG{U2MRsN_O-$2OxmP!2Tq}w|Y&$#~
zTnul+`L`Y@dFNMd?~Td0D(OKQ?2AaCya0-f%B=7vA=VeiT^ydj5ldTSscCy>|8J@;
zR-{T58G{Fk%sGvDu_~>3EsSXKL#&TUjP+>}V|^NWOG{*2Jr~dT%o-ulTkWb5F1xZ8
zjez7BaIKMh39VYG(864Z7dQr-A|0ieQKq-9UW&;QVF8OH_~t<jU0`jx%KkS#XWSGW
zi8{mm#S=!yRf%!iOxr!mk>OdZ;I>OB>IvgYk$GyNZ~lPLhp?3}8+ITe#^d=wLP`eA
zwsnc&tJtt#)rL~TzoU;f&Wy@_GMr|s7GYdDi(E-B#7mea8z%+LrVaLj;@6hws1}Ll
z@rzJ>D7*SVYUHA4XLAvusbwHN<`pj=0}3fG;5t)_8pqV&MSaE$+=UmV2A`OM@Vr1M
z)={Pq29=6)+@Qu%+7C3Dx{eF+5~ereBOJkNc1gr*cK;hDqNeocTEO8AGmw}{R9Y(}
zn3VGaaW{|~ga`aLWNK_wPb(MLKwP45&F@fem%{sh!`-vUKsgZKlFEtZM4I_>s?%^c
z2`ZfhkoR;s*`k<2rSMFOlK+JTqVROuIu{7J9Jh``Z8_8$XtI<$q~X$7l!l~*M@{??
znnQ(e33bINdvkQkHOz`a=O?BP7zlSUk7>97{OzlI(Y}IA%#K9$L$h0;(;UUvc*F<W
zz^da2UJE^L*;V&&5^==KaVHyP9v}?geW4RT1Ko=w(Q{O>(k|S<&oY1#z66abRq@U?
zaOn&L-!>JUGAB3C{SCw~gx?+;5wk;El;O~TEYjbi&nZQlmLVs3i39)AsFy6f+cv5k
zi|zo3{wvD2*QjPJJoNj0XK?_l4+wUOxPTit_lg|l8!j^giSfhLWhq7594;$GsdE}G
zCq<TWW<ME7M>)EyYy6t&5w^kf5Zb^`R9B3~Pqb_N8op9y4H;1u2ikxEZTv{7)M^Mw
zy$~<KjU$WW2Wiv)|5<yRp51aJTWG$2MGm_MRoIU3*A$711Oo&VBgEvQ+eqm2fQznx
zf6wEHwU+mrUHN9_saBP$j^lm29rm`pm%}R}%&-Z6kz{p!soTbDyr-RrH&J!#ZvcvK
z32=YqC%*9&y#!&?tct^IEp5Ew7Z@V49tkE4&{s(Ey|$dV&sR|nrO-i!l6?yR^%+}$
z&K@avAmK>h6)^$*7fC)AFNk)^3hUn!qMV63vbD4rd=cc-B+t<R8?Gc{m32G^eZc+O
z7fH(}V~oqc8Nb3^S)*0A#s-3=vB7B7sh4*pSUj31%nM&>O*Lr$Rl<de30xaXG3d2w
z>0n4RI>Ji;L)B}_7w+v{AJ&q4yPBby>5GIr1Rp%|y<EWrSiY;Y+#Mq4O&RY(|MkKz
zu654uDlJM?Sh_g7NP($~cyBZzVfT8{l>}P~-ad#6UnRfV1xsZgIj>69zK9oDa0T^}
z6!jY01Z_`}JjdJQvn7B2d7L{2J_R}04e?8A<<X?^?=h?m<OE0_i1-<b!EMNyaK8*k
zGVo=%k{C(x;2JZg>zi{V{B&Ijzc2&(_8cY(PJ~Si6F+!u^DE7dVq>oK3aWJ5u5K?V
z=+Bp;so(iNj^zFI{Slrd>~{_|e)D|k!u^rsM@@s1y1c&O=;W7g_yZ9?;_TD?h@(&U
zBMy~m2ZH4JA!n3VFPK^W_5$pK4;G0Mw|Zigmb8MzSC}-&4o-}dk^wY@DS%`w7d#zz
z6#z(@^Be6tf^H{x?E(zLyFt9E3jmKKkMlx_49uG-ve86SmpZ{!x}-6`*z(9|s|l^<
zR9{tKmA%Rj_fns#TFUpG!GF<IKBS-u`&?87Gk9**$akB>0ATiPI2i^P#J9<}P1{eS
z-6l=~EtBz_LjrJiqs^w$oYcS+sG>_Y(AulAB{y)*aYo4p%_w4mBk1!z<+L=}=y*a8
zqIWYLw|P9&G(<LwX3#+-PJgxJ>=GMtRf4ghO;;_<sA;Ulp)`#H$C4(!+)dBQ0TZCM
zqSmpk<0u-ANT`H2i;PnDK>NTG>2>0zE0T`I;d*owY!wB=NxO7P5}>uJ_r?>to{FU7
zucwZ{hK+ya;T#|MCOZucvFWH3=XX33M=_n~>8Zps|0(z9WfW**stN`lfgi3BBm9(L
z2w}s6MzyB4hpMsdu4)}+T2I(`r<o@^=&Ham@?RNtT9{}|n%NgS72K8{+Ok5_WT?uO
zI-2TWE{!HT6*kzByU25_WNa$7k>(l#?Dw*xH4r7Qtu4~mrXB7<v7wyLl#Pb4y&=zE
zZ9ERNOolD<-;<6@urWfnjw_``{MC|uAPZwd?1`{Krfy;!wmgls%xoE!OFV;?8UmF@
z!eJ9S=_5;cgPpIOhteZq6)ejBGTP!H*Jzu!aZGSfo4%BtHrx2*b(-e%$?Kd60vSC$
z6R)|L86RrXhm?jI*_~U5!A_saUU9iAzk){go-Ew0SJq;eV6SN~c{G}9+9Y?Uk&M?E
zhmN@=u05W~uq*u@8tgR<_L?UgoLC9ditN0m&y_FM!caI6VWZLMp$}ACU7+!)%M3Km
z8A0P0(}Pz<KWIK^Cf9cEoE6%=X}Ph2QeK(S-Ulx!TmwCjpa#brZc_I`srkJL%0YM2
z^%e{R4OipUcyWCsyx;05=k;RM=mGy3?X8h$B`>O~-d#=sYZ^V?LpP2duc4c|z$2w;
zOZ37kzL%t;TK3BD;V^BA5x=*Z2{#}r$Pr;0lV7HL%!Zrpd)Eo)D&B{l(IT15v{xdM
zYc)sd>s2g0tL}AeGdMroE8b?jjCS>4#GNq~Aq_>kMQ(O)qX}t@v!<&h-A1#WdmGJm
zIBB|IgK^eiA2d@XK8Dk%YZN$(csukonv>)?)(jWUI%ya$oQE{Vnca9qFq(elp>~|B
zvMu3snx0JiPdZ>#h1oscRcYEWfpR1xuErmb0ReSMk24|VypaSY;(>$|2#ihRCA2Ut
z?iVlHqG4OCnbh}zC})5`Ya3YLTMxq7(s_^DXjjUWln)}`i2fuEpV#Wz7aER=F5pB$
zThdqZLBNU%X43$7sxlTgnvD<wy8(GsZ=}h5M3;UOzEHt%5n#cU#*yIF0n%Qg51gZ(
z5aBs6G%1jHtHBh)#sau~2}cd*g&-t7=}8rBXg%R<b7@Vjl5j+GZL1_44V3bL<FqPN
zvW@g<7wb$PVVwCv+=3)l-eq^S$`?KP<m4J@Hm8;763FOUb(m;G$1r_X`TI7Q?kWN>
zH6(|t%<UZM`l5q8T}7(A97>&OL`KsW4vthu!r^Wt>7kTsxEBpKh-h73FA&k>7JUR+
z<~RXg_Im)RBsTK<hO~jTlVKHZRl&m4RIlKpfTVbKymGmXc-0X$=5ifRIe3{m0u->A
zy6}F1<6f{RA&BAb{7w~oU^*{y8%b@Q*S`%BRcpGTM=wj7vb#Q1B`%M;5Ix+ks(jlU
za!Lk|6h<dn8@u3n!3HD0`6EdJrc+~bZe4A`zFHNd?D$gU=yg3AR}`Jr!;b`n+v7(S
zBRODvJc9hOHh4r_JxpIVfs<?(<Sa>?6}~Ka1AQbMgZ82rr%P3El2y(z69Obnu3u{d
zEt8$dt<w0YV0lMU!L&~GkK<EHDv@nPsMb2Fs^QXL@Q76p|7>uaE3AgY^;FNBDh0qe
zk`6|CuGUJX*ckc^tiOt^Q8(GlgF6ttk?NRw5cdADUXqrad55}{BznXS2<M|Sq~nej
zEC;iolx_~V)~@?H2*4|;h8^L7pofn^zQ9vX_XZyBD~V;3TrD~(RYp^JLInQ?%%#ZJ
zd)~$5SM2yIrMCr7>XjD8sqa`N)l3mzj-;grMs{bdDCECkW|%l+A3={xj>%6}_&SBQ
zT#-i-GiPcVtN{-cDmLVSf)9RO^xx@Hj1D|RUX?b=IiMbn8xt@q(mUtNnNkm*lsTnd
z!pS+MU0hjBE;&?rl!g3NXT2VqWmBE((Rw{KM?qd4m8Mbo79Gh~|08;1$&ZP?Sn1~U
zDLpS2sBpr{KXR!g;cZooS<d)X)c~E}8aId|N)NfF=hAJhsXJ9}Uu>zSa_C8c9dVgj
z%Ehp>H;@vyTvHvmY4JX+PLi$_y0?-lw={nycB{o}4mxMmMGRiSlw%(4lyrFFRfHnB
zzIzpMN3MTgx@MjA(NW6J|5|(=9oZOXs!lqx5oS~p>y}<{PF5`Y2a?zUw_fX{2WXLY
zLvD}Mj_#e6gj6oD$ia<ju-xvd@r6}?Yu^ZmE+iNKkxM%pH+2i-%x&rxF6%eZEw+dw
zz{{r7*V*86XQ8!s>-Eoc_v8VxPP%*Y_w;%-_OQwCl>>us>ejx2z<zZPwhQteuDPBc
zbR1*K?i8dStUewS)`30s=I~{}XYfZlkM$7TpXAu_dt4C{f*;tB<Odk9vCv^v-y6n%
zh+uX3X^C$*9*95>rD*68VJScT4@50%E!7Hdd<A8%2&&Z-`@AB!;sGJJG(Mtm^Dp|Q
zFdRe##)He6&`(OjWnL3wtbjD}lT8U8frW(3H`krLX2i}wVEKOF)D}MR_+lV7S9;CU
z#jPo_K5+oiUr1hF`GFkL&z=*7As@=nkRWJI;T{5BV=MZ=jDaDVG+_jk31zdp9lg`X
z0&!;pYde2~um>n*5S+5rnGW}OO&nmVBf-4M5UHP&0SXx&qVOnuL>V7KGY0{8KZg>O
zGA@O%$?yyefnOV(|7+D48e&E0%Ym3<H!Q`GWFs_M9Z8%D7~J9`$j}$4fH({ykyONC
zsE(f_3IoVBPl~eH{;HF~FS=ePLcWL%P?3bG;kx`uQO3g%)MW4l-P6{jcHRgi74gp$
zq~r-v#KX|nWFR;UuQcnZI<Nmo;2r8NRY(xocriz8-gJK!lB2A$p$DQrt?06>#$`oo
zMPG@5$ZyI|Uh@K@wfd?Py0*$`U(#-pzwhv!Z6ehkQ3UD1SEM4;aueH^r;irY-pUve
zX|Z`A%J?+eIv6;jIZ7GNMw>!sXc|`y;P?#LQyD@+ByIS2Hr<9)gnnqEh*wZ!k0ddC
zUb-}0T2us(Yr0MNNTQUDPK7Yy?-5?EiN{~Tugz5PKj<@>!ID%d72B^m8RBQ(F`F0@
zZ2~xLHhD>WBvIl3AR4E#RD~q8liNo{jEW|2k&wh=>#JISMVhLe!NC+~4$i6#S*cSH
z182gBeITqA8Cw-B;V|iX7&hVn9*@TQPcPR~ymd0Fl~zB3Uoe<g_`yD}XkT&6k8#lH
z;w71^lRcW!zh{R;Osxp3-)!DW*`cLMjt&VWbVeFm+P@HEqnVBdxIJq~;z#2}Gp+uP
zaAf!0gACvNzI@d3I{_Ra-fpD~@m61TGNxU<Z!)9%IQIiYB#cWH^)h4H-7UfMT1Lv|
zp0DJU6?cEl?dlTuKhy&OXyr^9k~2!~yj-rCFMxMVDTuis6DUngM*{5)!2qc{T+^FO
zo-ka!;sb`HWPCtQA&a{-PM?OTeR7zo8H^-E*wfR9#+$qpq_(uGhooeXM1GTSof&Zx
zeSN9+mSjxF!cxX!>})1`*zbF9h>m&RJHiz8yXx`9?DsXpYpwPBo)I^#-*;W#F)8U;
zeS=ogLfJSeQq(gXrhXFBvUd$IKC*IYuZT{0B)CMcd1KqUzTPn=_aznt*_3Ii<D=U7
zE$;y2O;)*zs4T5dy`+*oq*1zJT$=(6&;<On&KlWe9Sz|h-mY0LZNfn);3k0hap@ZJ
zutV2M#}18p)u-U4{psPTFYU97qrLQxE{^un|8#NKm%>Z=RMoCxjNxi8<x=8OF4-Wd
z7y^T~L8^6i0*fIOkGu0W^u_ixkF^L`@hVX@*zZAac_0e)>Aiad@wx`LZ3(n(V`(vJ
zFv`y>tZ;?X#SK0DmSD!=e&NP2hU5wEP~)RB67n5}jFf!GAlAaHuQ5nT+;vt2_c=tU
zI|wP!As$yB<XpWa`B{A`wwyNo)x(tZm-Z1cdR*P3yk0G52*JtAM2LdbcY7FNv+dPI
z#L;&BB3fQuz*VC0R`2v+&DRT{<SHB^k-?sxFQWZYI>vMDm(C&C<u!mk%3x?vP+v19
zUiGf8PQ-M$#+H}l>#S0oEKR&^?^$)mZ`*5DQF6O^NH$H@7R>qW?{!lm?E8D&?EdO;
zth7C3nR<!%MJPcj=GP!gu5Bfj`<B_XgD}^&Ebtvii_K*P;QK1)0Nqta$tE9(SBP!j
zWd=OG?=s7zAJ=dK_a%ej<avwqgWiJeZEE^F?MOICiNUSZS37~mtu&52QoR%zPZ0y-
zNVotpt%JRkJ3X;tca|dKR`FMt?V3c;WmA|yby--*VUswb*}rHa@B>YRe548aRacRz
zueG$9_pOC4^Yzw37oB)C*1WuW?(pi&i(B5~(ZF8j#$wmZfskZYxiTL{H!($@%*$b`
z<y9&Apa_-~5v8rxSDpA^SS8G5Zm%l*1E;woxof<}bJ}Y!3tG|<-L=<_KK9z9j_b$Q
z-P)@CYWuP3@5LA|My@N|OpG2x+!jne9oPkoZWGU2@^xRhX-T;3O<n~2RGYZ|4_CVd
zS)F*m#4+bBxrtC-k-Dtv5~ag7WpY#GO}deQP4r^&hpatQ(-dLA0*MaA6>sDXtWL|V
zylTZfYnm`XmzLBHK*=5sMBMDs>SNbT0$^)0lQ4-~V}(F7CQsvvAcFQXiy#+^$gh<N
z*W{F4lf3vCxvmv{r`G&cDaNh&t5T1$s>EDr@+`t(<R<mudBx-j&qEEo#eT#oDAgUZ
zbm6FEqF*9p)A3AGrBwGKYJ<A-RVPr9wTr0@!+S9`QhzFV15bp;fDb%0KH;{<qiHzt
z-NSdxR4ebJ>3OQv*I_oMht+$~&ttNQEJ(tES$iMZkHYpk1II`pLI@7}F&2s}k_U2A
zMsyz8!~OA#DS$4LvHH?pKsU<#QM@X<#xUgOF&ZY~H7Pw;S~DK`Z@z2jb+ghvPjw8<
zecQRWJZAIO>fud#>*To1SDl$Tzf>buxhbmR;aS|&Wwaa}*H_dSUkZ4qTTPB!GNPT)
zK6PAfRjEgjvmbe#yu7L$ErS9|gH|jM*Ij*|@&%4k>Y*fWH6y~B-#G%Ju)Pc=nHG-I
zDxs43wVK5!nO~zBzJN)LrHwKsqmm3%IQ^S45s)Neu00`#*O1QO!EbhEo1-CD4%$(I
zau*OHvy#hd29FsN5sb!O^ZBZk%H59xvMDME*|9lWe*I~-&ZhMt7)Z_K`&P-(7J9%z
z+3;b6fj{PW8cIO-r;~k3VxIJSOA;Rfk+E<g@X(<jq8M6HuXwd^Qxfvl!bHcywZ>z;
zy)G?6-)mhN$P9O_D<gN;uK6+YLt#m+dLW7s@48~c&e`u38xvaIJ2uZ?3c5|o_t>>P
z;ONdk4nKJ1WL-CC4*l=#3AU89xI7R=2Xtr~9UWjufQoE5CLUCU*NI_yJU_%CvM$3a
zI7DA1F+CaAu_8dbA>Q<lq!7jS)bHKe!0WtsYq{Oo$XSzDizhzEy=;s-Y8$$;$Nl7y
zaI}D$WvpRR$Z>C8K(Mi)s~14)AxrxJY##Sg7U|oDV8zHiW7vaIw)4KGjaNBL>c$A!
zwca4izrlL*<ZbX7mTRy<SW_FFJ=*A^Kmd6_hQGxCyj1+q=Mbsv(!FqfZ9_+pnRZJX
zI)Wepf+_n_T#^S^zeXLTR<NN>WdhU<erG1~8V?y@XU%S3md<1fTo~SwH^PPt?=zs)
z6u<z#%9P8hW*UnpgZ_xy5DR&N`49nvz7Qj9UX}(@1wxnS2MHE7wKIT&!DvN4#M7{8
zD8(o$+gHu(Bu~agDx`zNQ}xy-fW?%tHvX=wSfpC9>4HX}oiIq#4{=irJel!I<4h)t
zU6axrIHg{u7jrDmJ16kzo%-@jtfu*e!V~9-%jIHX!zlv<QXAP6jRzmfneF6BZ7S*u
zxmh*^E+!`V+-e3VrX|bmx~aZ7PM~esDx`LutJxDtEdL!^EPYc}?i-9o_Ja|#pA1>n
zNy|F#=L>TyYc<uvd|t9Jtp>!l^bG;g>*fWo@Y6jKywzn<BAF{cLyOTNNc^&eTRK!^
zI`@?10Qi06U%Mj4W%=BB8v~h>Jaz<G23B9X!(Ygct2BWOdVVAX58#*C(sv2;vIvZa
z4g=XPQGmceJQ7-x7m((9^B8S$e*yjM2srwQA(se2Yd#Sc@X{x<L&7Wz-;JgDw(tp9
z0<()Ka^DGu<*>C0A#C803{gZw`>jvX0>H9;8H0e5*Nh3}ZS$K1^=*@idS=3Inh9s;
zG@3Y98XUF&%z`oD63jMi1zTIy#<DpgQhu>Qwst0v;UX3#euE8vUj{P4+P)m*ifXzo
z-bg3DIqkq4J_42pen7+x^DHB9rX(BJb<@V&-18;LzE91~jTx}@zV}op(;vYl`zUoH
zqVmuAf+9vLTE=d5BB`>W+?!naRY?Q)avAtJF<fLVCFJm8s+QK26ZVxf_KIqkPM@1j
z1dA21J&d(pF2O#xn6E!d9pxcbazpZRN%#P@5vW!_%JwfWKehFe-2B`loV>0ha8E&c
z?80Q~ML``(j}qM%x++{r)==byGM*@MEJwbjOXWYuOD~tmpJ2wzCG+P22{D1`B$4mv
zGW;h-jovMIqL+<Qj=cP|(&G9=EMkuQLU-i-l21DVHj{tmcqY*ETIg636Rs8xC?;3E
zelPjC^Lia$av$=lpmX8q64m6SSuwdPzj4Sq#E8y6l$gjXD+IyEmDA`j&CbYIIjGkL
zb(?g_y~jmL3o_a{@}8j7bXPJyhu%o%<K&g!NG4}GlIw~TZ?GbnS3}4kXS^Z0FL{*@
zI>H0F*li85bR3l*dP*GuN2R0b>k8KO7))Wrj&Vh<dKzM%xL9#5gO<1g>ogc_ok76J
zVRM;-!C}kj<9y6QTXG1G7#oa6p5>UBH+o6sESemwjZP`#NaHM$M_A)5lIt{_^}GtP
zw}u&@pcaiYKn~3aWA8U&1p-<+!UjGe$<bndp`fCjZYpBop`y7$90u|1=+fx9mG1nH
zg4O>Bs#(uy_Rt@%vH|_mAJS!4rq5)=$)`W$fF|<gYBR#>|BxT1-w+M()pUix1oP|(
z5me26$ZrgWmRBu)<1oPT>Wl{3;8*TVS*0@JU#1s82l1Yj^Nwi){RUz{Of}{$cv93u
zaJ^x3ocynJq0PtAJrePenF--XP|wgweVLB?Zj_;lH9eK8;FEKMEWnpK5;I_5Hco`D
zwy^YXTm{40SJc=mNn>P6@;TRexMwN}sGHwCZ*m;&c(?iz8DjVN4Uz!I<0E;wYe&oa
z9KogA6}bTEG#}>1NKw|xXJC!DrGbexE(1OJYo6}I@=y<b6{7&*3;hNuuvl@f7zL!O
zIYJaXDav=C7zGvDyaYY-fn=AR)8U3J09VOhAqyImkvB37uP(l1gW=UpZk|pIA{r%9
zw>rXCleBiq3@(s!{VmC<?ItR2L*f8eHqIl7rJ}ot!&*D*iy1smIbJronNKFDMWq|9
zAx2AdO%mB$QN>AQb5kk%*wn|FEyEEM7sIY_=j64yDX<HYLm{)v15sAfu7W#MzflZu
zV|pZP`y3%oxuX;ZdpGSexTAE2Y;SqH=r<4o_*H%bA>c02O_%Hq4z(`+X~Q+2>$0W6
zVC#xG-@uD=^BW>1HX5Tbwc#$!O}kUalu2zJlkA3eaZWN}-z0dt-QX@A(@a<xmoIKN
zyh~>#&N6Up{f0~E_`oR6K?CF0m1v;BNi`&JR0e6;c|FwNnCf=p!YtL|FIXjCT=3ys
zIS|N)bGsp7wyH2}Pf;qPAIcj3xG9(mZ2B&yE;EvU{Y^er&bP3r#)I&VU{ZDE8g4MD
z`i;SW%#nUWFu(vG4`Mtcd@wR9!{GKH6oZ&ZZ%J3$r{{;FD!FncGwzZra|L5FxsqFu
z1;->)&ksd;a^nF4fuJHa6$WCW*V>T>-?Xgc3_0aDv;*8~Ljr|x&;Vz-Aup`!UM{F|
zu_ueQoZ+!twB`motKWzbun>D>3u)mH6&bx4Xbi^+*M<!bs#m+SzMF)b)~nHp2;1*g
z^9L9aQ0x3gt$^LtmDPk~JC7^I2a*_B(XSB$&2L-_WMn=Pgq-szFd!O&S-aA$G-RE2
zPc?d^NMnFEOq&}MV`AE5Ae#uNhH0ZDFAYZ3BYB0AL#<S5;uWx^r-gf@D=$og(G?B-
z2m&DMu$_e}?EAvLu4eEd&;{#}bSV3Z(FbMmI#+J}E>Fm|igZCO_^-ZeRXv&U4Xd8K
z5I!W`XZ=PGfnC)j%X))1tcwTV(k$vXxX6MZr0Y_+!Kmr3s0(2;btUs@uvZ>QP6{|S
zySLlNPE8bzu}d4w;gwbiHxvSG+^{7XJ@N_Bml%^Nfi4r%jbB<=5l=HWaOIgd4;#X=
ze>Jo*6>dAR>Rk{3PVd=DM&863!FAl;_@c{&puqy@uCM;C=y7WFL-9J_&#Cvxcuu`f
z)^qq|J*a8?FgX!pG%_`2w_w5a8}?<JhL2nFb|rU=lC;5FgM%!SJEkPHiSSIjb4tl3
z2lrQ|mHd&M&Cuj6Nlg^&j#fx_9lNp>1W3il++~N@_?#=_)gfHwX5wUSG&r}02rVb#
zcg3|XIOu<oI69EWaf9<JCBeC@(4WzKfy`VXmkW@Y%LrnHD^?M`3s-GE7Auy8e8)GG
zva`fk#W^N7Y%)IOF9~3p-?+(P1YmEU<X>_iF#tnqqPq#d-{pZZWA_)o4Q~<Oac&A$
z?kh9=W^3?s`X8QTewDw7vhiFGhZBhzC`r?s$Ae*lgXDn-Z=TOxdaEx9ULwY?ZncH;
zptZumz-vK_rmqroJxcBVOG^@G5^MHaT!yGocL9=D_f=xp4lu4QBbmG<U7H-<M%sS9
zl(9Ks43P~II}wAdb5FqlwV@7Rpxe-%LdjGga3V3}^0|Ag(d47O-4Ji^R}wUa4-NTu
zNGuz{?Y|V%GG;Q4+jkE%L$HIdBDS16iDh`dyStK)_f^903{nkLjUW1mU~I1**?s?*
zUpT?y`;-X^3|~nz%?6YPzPp$$H2mlzYsR_J2pcRz*11?+WaYiys&$Q9hDx{o^?f}-
zvisEwvvFS-Ix{&+D7k;t7tW_|g_poYN0~^%^a~;hs=G1L%8>(Xd~uCs+{0fk_%Xyr
zy!glfW8D>g#GFf+Aj^P5FIY2xv<v7+sq+lk_&}6c4buh4=)zjV*j@-~m|Oy>PtxiD
z1M|($Oe3so-X+2A<6O2yA07wzQtmV-03*6T64uJq<b+?!#FJF}JOE&&_|jRVqs)^C
zdqty*^5!6%D2_ZiTxq#A=FI_}JkCkzCSI}5QRK<-gokuBd2YfOgDA(`$UnrByGKVR
z$8n>{p2xAyL^~Alp-l%;K9t9BCF8+a3(tIhkp9NB%s+zOmS&fY(${mZ(c*Fw^nfm{
z<Fg?em@8JIft$)hcS`!}SZ<xBHW^CEeshIo4E9@;(VeL}9HONvID=W|dtUg#g7pG#
zJ!x;(oI%>#HF<#b_Ph)uHh|7dY1|Mq;96lUsg~DBa|mmBqju9>g4X8rs5a0f!~BB>
zW4pddF*CK6GrVX@a$X`$=4h&e=?-3-n^NR}*Cu<`6Cze)A83(P5{H3pT7Kf>x*bWz
z$9YRIsPI<2hB||{;<e=&qJX$!pFRd|Vu*5jf{B<mLK`#8hg1YRgYsvBP3WeOC^oW~
zf9BM<3FJ6ElyY-y*)cI22AmUJ#Bv*3)i4ne^xRE|ZI)jdO>L4%pcu0@udNmDdR|*A
z_Lo^@8%Fb!mpZ18;A}7s<2_E=TJ?oP=%8zvwg@!@+w}thD`7N1a&yyXFgzpu=I#VJ
z&Pn-ykl^tBldi{7+o8u&-`pOQ_-!Hr!x81XrMcy1{6x-1XU@+_a~zE;q`2ix!2=2F
z@I6tY&&yo8$bfQN*B@cjOi`|WrSHt>WUk20htq}&5R`a(gLl6`*SvQzhxc|bYl8QN
z>l;i(+Gm<Fz0p3?w%#HVMZ|+pW+l8s(B5=$#H^vbZTgWsxc7w=bC2FTE9NJ?_gc(g
z>WJV$BAnk`od|Q5*J*}y8h(>*(x!8hZmzs5z9~1sK)W}4k)+l0G3XBN_;no^lr~%<
z?lfH(Lh|{|vAJLcZrD^8Y`_Zf4%S<ywa1RN@&}m4i}%IKinDlMto&h%7slEwgDv*t
z?J8;kcPMY>;(f6W;hQ&vI_QJu_QYLpwgrNiD-i$5>FYN|CUX9|g8efwus3<xF?(>_
zUZYym1vhGOj@@j+oMWanvzzX`F`u{bIoV5i^Bw_S9GGqQO8#M*WnJ4d6Z5^=N3!O7
z`yaeE@B!FQgxB_)!4iJImr!6CFU@bd%FSzKZB&St_PEkY7y_mp3H8BF)wDD1nHnn7
zFbzvLDv@nY9p0DP=F}+~L43e&0?8d#L}q?`PB|$h1guU=lc*rUtlR5F7jYzWa(NX#
z9uFZ3JWM--B$Xo@&y{WF5bcskLnkLs!rK#~(2rz1SMI||guas|V`wW`M^nlHvev<|
zI-=~sP%mMFQu-q=$;P=4$%ebSghae9N6<_K?~0e@=``%j<#pI_*+bVufLE#@h{I~d
zEOH(m!d_{mVY>S-KS-j`{YgfQb43Ir9qve|D~v|fq%FQ%)%f6z9U{DL50}j=J+eV%
zyQDD^*SvDFA4w{PZ}1cU%(uk@W&Av51`mQxvsmRJFB$<`4nC8lrnwxJNjp0dytB%w
zQCLEa>|P})L4ME<_u)(A`wVK7*lACWqLu;(W-)ene_)t-;m6S7Oe_W>$z$<WP)<H3
zuPPs}q)RU8HeO^%ufJkTk~nq=m74FDa!D@PrDby2Tq36<(P(fzQ3f>>sL07(D?_?r
zrxELvd&6a~I)br-z4|~DBuWD8&%UI!`6Fp!F_JXEA4ztSC|Mg|P;j#YV2b5F@I%|E
z7tU+!*j{+=!!27I&JTSJxGSY32c}6KOgY6eh)+>;Tf{Sdzg%G=$>Q=-)C+vK6kL+L
zE+?P(hrYwExRs8uZC;8V4R_PM_2>>F_9g|N;3D__AHpYw;T!m?Hs&^?gjJRNr^ghw
z;=nW8lY_hYA-o05l4Ri6rZv|y{YY@sQOuUpsz!Vd{P05un1f2Pl-zKosN$i=cKItS
zBon{fCj^x~b_7e`;)P*|bKfb!{_EhH5rX~D+0&NB#xT5#9IyMEsn3mmq^}m(Cbk$<
zncNbK=(;?08$<7cAo7HSf&upnycn1bY;~!d5cNo~HjpdBmePgLv|$PtOkT$IJ2}=7
zQ_NvlSQ4+JoUR7TQOsd8>JC3R1vYjBX|rWg9swLy(|m``?1(Vmoi0IK$xeqLLn(Vg
zf3CC&J|RKNo`1)?!X-b?ML%TeJQ8fIFqq<e^+1#(t#200v$p6H?;y(YB$tvL7ZERL
zQNDgqG*sK<xsC>Jo12}+q@Ek4=%RuJol6@YQ-A!zyUOdo#S5tG<HgHJn@VKO>n~FT
zZ%-Os9IVj}X7$v^1o?~%Y4n~HWe<5Oa`-~q)V|<w0-9ZIg=hIp-w_Yb=;!4E=dk)7
z36>AS$Q=ovI^|TC(-2Wu9(dkCl)ifU!o=8{X2Zf$O)bL_bQ*8yoRLwcp_Grjvo>7}
z+5L@2@|57d>AhFge@y+EwhHfs_Mj}`5wvF?Nou9MP>yhE7BTl7kwXRz)6Os<gXUmW
z7(CT`NBBY;Q%%$TQ@EqU{ZktmBXo?|$QX-bOieAu-Wc555Jp1|t&V(T*W=aUt1YkC
zCq(I0N_5ST7;>(4#=jT>7>J-p!{zyAq>1}TFt3s7{yOqHBVG)iS3N^cjHZ@=-%a7)
z9Fh2J=+*cBazb_x53lR8BT}D@qEEGcq+JBT`)FcLNw|;;voaP$&kx(Di&%1fYlKI7
zkn4cf>D9f|MSNiT;`jnjnxgnQ!#VUjLGa1xcY<JL_B%ru@TpG}(^Y+F=-{r`wQ0bX
zZ(W-Pn3ER0e;~<*y2c8jkCdat5na%_CJmM=f`6PXtEZPgb-|}f`BIz#8@i*E11J31
zH=`Sv)Q1aqH>nR7J|=~6yie;oP$3CoMmI?H2SNt*`l_`vNCGAi$eq>&B_n>Zby*4=
zA&!rT4@vEGa)QUbxxP!doG@nlc|z1ORs?GyCXhmLI_9=1T&E+dqWL}Qq@%t;Sztcp
zIC88Qa~<#zhWaBxDZ`Q|THz7(46&gK(P7u@8Su?@d}6SYO@tHAun|w(U2+W4VHe~c
zXVeI>fsQ1@jNA&@u3|hMQ8sL^O4&4RRt~bOIW1I2l1(*%(}CbQUey}lDyV>`oK00V
z1>Z?tpPrWpFJ47)3CYeMv06vOoh=PBKFxmBiF1<z%J={{usavv(r$My050&x&avMk
z%*_K)2IbLyG8n2x`^muhMOSGK7O&kqFlX2b-EcW_;g~M3Jikacz>gz=P6hz-aU73z
z8{`P3a3csENdzl$6jBF!RZyIw2Lc2tVkx@OUKMgY+N*`o(C(j~U)9Lrx;5ajY>lOz
zL6}%$DN>Wv0>&{uAfq&uSCx!LR9=llAS|6a2Y9L0?i|4>plOOE&^YWEPAgy|W$bhW
z%y>+f0*;Id*5<2P2FtpYGE&!k)yc3|L$(J-)qwfl5sczfW+^Jjwuh_{rby_X!75H4
z`G5=;b}OV7njQ#cVe;ZSl2k(e6wVkN%~UPoq5YdG+8n^%Hd(8EB9Dd1Htk5DWU?|l
z@@klj%03n3?N$m$0Yjc>pEt%Ew#h)Krhxj+_#n!3?K4Z^DiuY<xzlHZ;X<ypIFpMQ
zvW`2zvnk=ZPefxjB~tecDN?7Zq#81P0gqc9QZ->`x_CZcYW3GsvsTx05&Q2xHe>(s
zto--{daXKUoLD85SG^9ByV1qfao1{<thSJ3AVmQN1R;r#h!_NfIH`AT;Cpkew9^=o
zkv5cx570H!;vU!Pof`Ng)jKsj2#s7kNM4m3$1G<L?!3UU^IB5lD%i?ajf|vH_Nz*0
zU)HNiESRFxETXNHrNKl73oE=LKz<&(hR})6o>GqZ%z&L7NJLmF3U~1qQ5RU&6z9_!
z$VHJr9mml_R;6_X?gTfas597$qK-Q9#ox%JM-qE(dF>0Z7%3cq!!N<g-3js}Q0_(m
zf%2d^ZrANv8WBdul<LNjLCmgM@dThLI&e(Hw*@OXCE4-vDxE)bFGOmCy|t+!>C0B$
zI7g_Oph&Bs)3b<&yVtKI>@)HzWDp2G=(O9EoX9g})Dfsd2<1CookDP5(5D>%bK2H<
z0@<mKq^R|j+?Sak<VcKTK7+CT1OE~pK#sMx?KLW?M0*VZC9u9rt@;`iO8T$Vx(k?+
z*CM8-T*SA`sWH>70Lo?Q%UC=iYG3NF^-_!yDmK&m0ZPqqj>tnQM`PVBo09w5keg%O
z*LEemc?9*NU8|=g_fw3tAM1XKDdD9+JSakH^N4oK90TMNSvu5HGKqx#=U@KEr~Y#O
z^Pm5ZUzoVIPrxu|PPlm8|M@@t@-NRZ)RfQTfBpZT>i_lMo=^GnpTDfkzt(^0=jFA}
z^Xe~u``72c`j@|yzm!i~fBTo`fBmPw{d4vCPyhM9{HK5Z-~RUBJ^#($p0j}aTJ7`9
zQTHh4;U9=Q#{A`f`fq>vzdrTO!}EXt_kWF`z^4;EUeUisysXpBj#qZN_6M~+-hBR@
zw*T}${Kx<Mpa1rMrj`qjvf28l{m+@V%;ldi=-*Ydr5T@E(t+|Pw6sis`;C_W%YXkL
zq@|ys^fQFETOFT&%<>u4`gfHi0-}}%9`{?ze_N^Lyig_cSNXRpfzjQ=BkEtp@a|aV
ze_}k+U-#QN_8<Pa_ka2?KYsjjMn=<YbDGt0-rVOO-Rp^B_V<Q{;cVDTvWWi33;es!
zOGMB?wEa9V?RZ@gD*x`du^MibjvlFo{GtEMeE;m$UdEZ0pYx{w{mJx~&vvcZ^ym9`
zE_`3TtK+xl1gbbb$g1S}LVsH=H^5tq8{)T>aF)NdWX%1x8ulCwzss2PXNLdt&6;*@
zt-=~Te`EN6e(-~wSl+!e+UUOR9Rk(dYL#Tx@2Umc=RK7v_?>FVL3*pL`kKnWS#3Dh
zA<W?Zr+0hJ{$uw4jji-A<sX^-v=83C$zb?x-_k|q*0S>ZQ`tbHxwXWr`L5c*mYB*&
z!?ee1D*t9R5JB|<DEM=qvX8vZlZyC2obvZqz%S+JU%>gIf0@b@{7&z1*LSP=_ybe9
zfsJ~riJtmxwG+tdRjIb$-6JD0s=xMs3jXX0_<Vm)^v)A&Zv58p|064)Chu6Cs|?5a
zZSO|?I+ZE-ooev>yw&6i`fWA1%iU^iy{7VSR)g8$z5>}Herg5O!`k}$o6s-+z&Bv~
z*O|Qi4@~4azs}=1|G+ek3mjD$<@Z1I_N(u_{eitPBPQK#XWZ%Zr)T|1Ch!}R{vQH8
z`|Ir8e_-yua3BTsyNwFTN^dm@$Qt<*BXX{ry`QWl{X_%*Eg<q!LlU7Nu9_%*+qa#@
zs9Q;bZ>v>=3cU5M<ok*(`M|G=l6+qg&Va9qlKjMLsK+sKe0GEV{d@R{w@`7D_|jC8
z@4JW?$ghf$d|&af%HP#c{<cy>s+?QxO1`g%AYQMElKjM*XhEy|-4*e3U&e-n2`^nG
z`M#6m>k;u^f4P$HD`q6>S3L^8ueS5z?^REdZ!20PaK6=8{)smcshyVf?ccqLpMr=6
zm#UYZl6>Di@U31ICHcN0k|ew;O7eY0F#lc^CHcPMUSHq51V8gGj-58a%D3<0=RTda
z|7x;b$+ul}WZ`*RQYiVpBJvErKfRQEUlA0rS4By_uej`8DM~-_9{jlO{r;NxDbR?#
zdM_;{`L=641J2%h5`13`9-*&#l6+qg%)nPgNxrWL3gD}vBtHY44vlL3?wa^H?9}0n
z_|jF9-<jH9ap+f!`Qw*gKlnE{x_A|}-t8l7Y7+c8c=H*lG<Vg=6!sei7yp^9oQhiB
zL!GTWZdD}ty&k5w-m4zn_r9-IcAiF5t?X}(x2#su^Wau1bVc~S8ZDf73*~L${PQoN
zto~capTF2Y@Dd96F|Y0^aqjp1>v<LSs@Qos_I*W!CV5p<u#)d9w)N{4+xkN-f?9Fk
zg}4?!`7#b`<TqYM`$t{|g809BSn7AjY*gIv6j8k`*O70lfgN$HP5&dUfwy_9jryIT
zn$^IS=UZU;Ctt!o-16VL1o`=Qun|7tc24mWzU^Eq>>R4K^6K4hRs((HRuiA(yJ`zw
z%Br@Mg!tQPG6UxuSU+P0KIu9WR<3_%D=@Vj<5!&<<BxQ%+p9{q-}`yQ%DEK~I_KLe
zZM-T3r|;XJ!%&Q|e%Xot{74_F*uSH-5gN|Ti!pSHg6}&vkq`V<Q-bhstIhhW)@J=9
zts!mPt)@J3-&RBPL5@GmKlujcXS3SB@do~Z9e*0H)7Uxt_BxH#;6Hn-DL2En)!+tu
ztI03+yJ`cmI#rE=->Ei}tjssS@=v~jah%?MW4HMS0MHortImyYFXC7&vn0Q&_44Z7
zZ&v#?<Q;zq@eUAoZ#6M_zpVzMq~3stlRx(cjyL>otbu>%9PqNtQ1b183GR=tidXUz
zr^3Vk%L96?|ISvc3ODGNsxQ&+*mA!N4T?Wws6LJ!1GiS+T7rINBa1vVal!Vo0!#F}
z7Sdl$fS2fJ48bP_>L2RqPfb@OYI@JtEBfBBhm6hds#o+g#=VpFq5hGcj-RnBA&9_B
z-IwThY#HN=&Ea2vxssnTo*k#|Kh)3lQ}(lDIlr~NqTexvtzS=um*}T%_582het#GG
z8MsFS(p%Xp`W@@}ufHU}+O&WC@^7C0NBSLo{>$n8xrfibuH#XkFZ<Ws{{K#|U)S*C
zuY0vs?Nj@BrR$^gPyerm=Q~>Jx$XXce)GGs5X(M3D`zsS2|E$efv!o48zR~tLHs>`
z3&MXU1`SD$FtUgqK_0tSx-zawb~7RbgrMLT#}oAk&|+fdHPeq}B}MEM6MbZ8{58pk
z2C;ZuH+%$RTazBQNC3Lzg^!pDYchCQMqOBwSY=uAwAZA2?Mmm3HIp%jgrG|v`p5@*
z1Pwpv_&wqlApPi?^qfPq{Us0n)uVt0I|etMXpkoKS(C(ioJo$L;TJiy^xIuMJ4MzB
z*xqX@Y!bp?tjQ=95hvpm^N9l*(?GE1=f4a@0?PTKw@gTKoOxD9PSG{V23-?6!koEg
zs%UC}<4*USwV*T^<{-i^<sU{oxFbNTD>~8WPJ-}oYr>lcc>>ntE{0GgAHgYXbc-CH
zj1%{S1ijd)HFM@7aNL@74?*0x6-k$aLcAtjMIYovJ(4`-?E-zcyC6^Mn)E5y6^o!`
z;Vgi$>63u$qiZn6;l?5x48fEcRM((;84{0v1X+mnyarv#B9zP;phjf?xlb|wolWsH
z2D8i>Q$Jq$Fb2BWSU8GxfW!l9&}9KmA8XJubP^GSQ3OFvb{g##V;}6iKv;u;$dKN2
zDVH~5(XBzAT%=fiLXcYk0@1C30INHRwren4#vW0KzvWZbP!QE%53E6t7Nj^>gGcZ^
zpdrF&fW){IQ(@=M^DGcWGZN4#<#w_s2AXct@ZDL1@yhl@2Ta2>(FLy1cmP>UI}N65
zWPm4-VNVe)BALb#B@r$~YtWr;W8o-*!`@Je=IxA^l!Dy#YAK(hQpT17Eok*Ul2jxe
zuq*thP8peK3xYi_C9p3g=QFLcH3L3<B+4*cDyCgg(^xl!yWf!*YIT%5>f}N{lI%}m
z%N1ixzpf|dS>I|meTY}z>R?{~9!c&1718%rS9a!tK>VxI-d`gS*HUDOT4?xNQZCQ&
zi?JqZ@hE8I6SjOrD5YXbQjYwzt1EGRp`}rYgG;6xI1;v+bNooqYOaDKsOWJ=|0YVY
zyt~|pYlQq;eW>010<Nws>m@&uA;Az0^hTkTk0`q|@PjicdYA44n$mbzVS7FjJ{1md
zt1BxrlHq<ND4mD81}z!WM?&Q%lvgT}ir|7r#Fo?daw#B2jc|h@V7vKZS47A-rJVF#
zd8acH-s<pxt>G1#hT!w>REv&|6@YeStc>T!xed$~m9!mU0GHtWk;Dq<^vybwoOW=W
zdqR}s%Dmi&Lb$qeMT2{~6k($x`R?lcXg){OLy&t%tw4UAiRvq`UoU!Yf<MIIs2_a1
zd?S=eMXbUj!O{a;Yx(ByPm8Xc=Lqb$6pf=+<exYqjzD_5EhmPp@Je2;^_w9MkAN*F
z9DI(bLl7hDON|2$`cmTnguc}Fd8pz#R0PR9qK<N`S4H`#$k@Al>Y-Rk4y=1#;7DzU
z)X#NyB-DRE-GP<>1r;9TNb*bXK)j!mN))gq!-;%3;qH;da`moufe*cFPevZ#g%~3>
zgP5Kob_N)NmosU41wvFJoFj>kz4+EglHGB2aG^tlzO`<sXR5W+$$cp}NzLGkOSwTR
zlEy40SE&u)j~O<OAQpq0wr1q=U6DPbMxcPDgj%PZx)I`5L>E{JZc<xJ(xygn6!XSL
zaTHThjEY3R%Nt5L&PqCVMA5gZRvUU!)eL~6a}^&+PPo+h>@&@xNJY6S33n?@yUU9n
zg7cVi+SP{iWh;{Jo#Ii=wuUH~hD*uyDw5|cC5@;ExV&sLR>2X)xGN<@jXb~0wi*W3
zG(I$Xr_2mBGx$Cs%3Z1fYbr!b&4|*=mU@hJtE`Gg5*^A(k5JZ285AnQT^|Wr3B;-J
zEfu+VmXaleDK?cQj;;vBy=>^Y6Uq)gH-V=TW!8-O{e+0>1A8jpW<~7qBf&O<z#>a&
z4k~j$FXk|)$n?CdtFbt$8P<9RIay3KP~on!ZmNNb$S4cx2C9|#H=0CX_+<=2R*^b)
zDbebYoV`H-W-3CoEM$GH$N;^R6}BQz?o#I1iqQ7Ul**@OoX%y$#ub4%7ZTZ4q`+Ou
zbXzS;d?xY+FL}isQC{T=EhDqQLOlM8=9c2|S0t8RipO6wSM5?b{tD;JrTo7YAwQQ1
zE$iC2Fe+h1N`-~&!__?gjjh3eHjPjj5q^$<?K<{Tg}kY{dERO`-u_a+{v(K)rJy(!
znJb<pf2NA87)!zQEAkp036`#nDDfe{lbMU^fhaU?1k_jpN5C!&=(|t~UFU5A_6r5q
zuUL&sk#;JQ!!AYFugHP27+t?IOZJgqV=^qcHc^Uq(T18{QDUn&-XY`nlcMa5AT?6f
zEJew$$aAxlaJ&X>V6`sPhBQ4(iOVa}nXXj*vth3$xQrcrDO`TVuKz4$ORxAeETvSh
zNIJ9>2B>DLqSXYKk>BVeiFb#TNUP~njW7YL5icXx(o)X&8bQC7V&y*-xu8Cx_%raQ
z0^`^Gye@{tuZUNA1bk%615*>qMu@VdNJA9~Dwo3IR|Ga&ig{m|nr$_r>_|SgnlLu}
zlU5VPM#i_L5cm~XX0^&V9~If{j);vXcx^>(!<N|y!~v34Qz-F@41x<mj;eE&7PTFR
zJO;_HiSa^!z08p-`iSx;iAxm^{|G{nD(H=T;;RaJJCJDx$$ub<#eq;r)o1*hdI6X!
zFj574URAjJ0PLd}Ey&ezqC=>p6XhXBQ33RiB$OBMM$prh;loog*cPikq@Z}ON)YX7
zqdNj@IXKQN0Qo0H@uI7cG*V_Qh1EZI6{#UUt{Keq6tU@aMB-YEv|o|Bd{rUo4kTKI
zq&twPLO0c@;j{r)9QhU_?N^)%mtr~9JUFf@ppC=jqKoinej$A0s*DhMBrR)UvqI3v
zr3g?*k{uxQ&iq|ZNZ5Eo2V#kTPS1z9ge{{3t14VnMZDA?H{nB%h^b3K{EviuC^Tzi
zL}9b)fU7l|LEev5t6BzDtpeX2P*nk@jwE|0INqJz6CQ`LV^sn0jzeM<0MFQ`M{p}e
z(9ES!R24BpSEK=`h$*^?zRHnnY$?cpMI6#2A=vJ~qeWo5&nU48EX1-=ijgk*UiS&O
zz!U%#@ljV1)b4paRIICtc%~l-N~!mxk@SdSr4&Kwo+0&C(b7e*(j~59MZnTk#(mI+
zGKA7S&xS=%8nH;1qF+^nB3;O7aV9!~k**>rjbNlpnF4AUC|6;^n~GSZs}NZa#3?-z
zG!9efDp>z8maf83d^OFft8_IC`)8W?9*Ck(gye`cx|DsOBGTxQbd<9Kbw}>2RRqf6
z>lc#3AEmNF<pVGl`3P!;5nVKtrX-es5h_Qd;Ui(=K(R%r9OS1XL1foDJc?`>E3p8!
z!z90y(x8UPekop99nKyKxQ`Cq^d&|N=2d9J9v?KS=wTHeJF8slH0~~r2rC)a8><L(
z53ahRr($RebJ!ly>HAc6gNhiOa|?8549>Z=yb)IONaDdyMOe)vVJFv%PgzIaFB}Qh
zFA~2U32W^96i#TrvsJ-oM5&xx=s6R^g@l8!q1hB}&#SNy<tWS&1?)4pM*B!mI>R~@
z=d9*M+!G=+i!hXPlbCxXhh({Bp+?Bbxdo?@XzuxlP_)phtD%a{bhT5_86j|7J01!5
z(V0cI($E{>@7d6!j#8>F#61&|h9utuf-TN1z>O$XQ~vlhqbY`j?O^TA2+LL@wcXsp
z+lZrhB)L~0MB)*!U5^sc_H-z2Y9bXn60Bgv3!Gbc8o>eQ<^p_b+>sx_t(2+=PUDV!
zZldYDmk$AlAYSAXA}m@2*PDt6R}nbxNZ8iMi6QiipmEO;p{<F*l^q*Qgo*G{70l67
zX4CVp`BdU|uo>nepq{y`jsRQN%){+mGG}Laiz5hapOD0>SG>6jvc_D3)ZlZ>C3ALi
zK0?w_J~L_wRD&=w6{hY;V#Jp~HNv~iB~;C%4s$VK!V#T4VKFdG1!rX<uvG<R<&@Dj
zNGnIe!2)e%E)qQII#q@muIQmm;3w^0lsihX4Ics4`>N;<k$MtQ4mF&QXwXy`988oW
zA$mlbjk$!w5j*cl@L-Dq70<;nmmv5;Eaa(FBNc>}xwPmPR-+P-R7CBY%s^5X@|@2l
zWS)PU3h-A!YdI1ubMR7*gq3n{`bZuWW6sG`jnpbrApk2P5za-xoP#=*W8|qA_>TyG
z&w&(R1~=tM*yDk56kuNSbWUg)gq67jmcdUs+^Q@k`@g7>nO#w8ftm!B5V4Vk<s*2F
zHE<+sXQ4BN39stnS}iDr?o%J&wX=jFPSAWLY-D2+Orh(Qe>@Uwr$}))C##&^h>KOh
zTbZ#-gjOJ~90^*^9VjGd8GF=`pyAlXCUd1cA&AL0we~@%pHmiYY`k*{hl92<Nz-~l
z6e<gcV@ID;7H#bMa}tIppCts;xW#TIuGSHxe!|?lA<~R6_fE(-r%?CC{mq<&-H1Ut
zm1Cvi>o&pKs`&QJDb$^x$2q$;D-dEPbFNenVy2wcD)=l@NmgnQT2fGQXGg@<Iqg*|
z=GX*=&M2*O%CNmVMpF=aBTDU@`U39(^@O4KfPPGKo6$6;vbR(aVvYn8YhZkZqCtt7
zQ#cx&n5iT$H31#nXr7eNv!>%0Ij^+JH`e1M(B3O_6V%=?6de)OUC>Ue8n|{&L2cmP
zBf)bMy-p=2I+Az;Lr5D0nK^{C0kNmZT1OIHU=HLTzqC@Km@PMOX667EZ=lRfC7n5v
zk1B&;yzv+@#p!AwyUejv32<~|D@O&Q?1pr0M*@`Hz-*agQjIizP7%3U0rre6Hm7u^
z+Za-z<=xp4W#?PTugH`KT+4)WN5JkI6erMbpu#*K5sEp0T@87Z*oLDoU2On(BHzN3
zqF4&U^^oMXOmesy4$4O`3V&j#6kE*`qK;bBw&RVvhN(kgkJ9-3i|e{2&E*LZnjKKq
z)GT1>Ae3&fIm}^dHDT#6esLP;FjI7{27|{OjZFcDj;5vph7M)|dm8vJN5qz}1VsXC
zCI8M=a4;NIeO&l<jmm}>^snksB3H4%jv&>qY6ie{R9?azQTC{)Eg;uX*wl_574;Cv
z6(q2hyqPBiY#P9IFu6yoT$1!JZLqG*4tU;>cJrBHf;Dhpj(;Dt3ku8>53C{S=j`iM
zC$^?T1dA@Fk#Y8=mH|7JV5lLI{gLpwxfDB4^%IhXTB$A$fSs_qAra^#(TlN<jsQEz
zvBiEyst>gcjM)dCn#gjB*ww&snZ2urSZ7@zxgo&kR8pdb<e!r%h+3Gnr*afE7`|sG
zOnw@y<443{01_2>tHI1ZJ7IE5OZ*YA>5*ID5ut6M(e7#;XtbL~0%%n9tyX80fFv8(
zFh|6OVy$&!D_CjW)XGGMEK138nY~GMz)WRBYT&)h-uTc3MTxW<5=eaJX|{3xSfw*?
zXRjKt4YjLU1?<ekXR(<g5Aqb*tK~J&RDPu+$X5}6ZUwJ_(ECWTcg$0HB-uMHU65X;
z5-v5cUZ!&u=Iz;Zpyiar#CM|PhHJQ)FRtbK65FdGr|I;?XW}kkDnZi`#jrY2@{z>*
zSIVZ=EJ|z?$2ynWLc=}e@x(<#0FR0z(DE+x2-plFB05m?XJvy3GerSw!Eu>B_*jRs
zLyyIx^r7dTu@~8^;j;Hg_)Hx7lpU(!&Ukv)$RWYe5uxcspx)Io5Gd$g4ZN3AX48P5
zF2LN7EdGetcHmEWKsT^sj%4z=v2;WLdm6|w6Pc+RuG&wTP2)i5`Z{MC*XcA|w}y*_
zsc4Z6;X0=qp1Yu}Y3u@#y4H1D(6*83cSNagQ%gXk-qa8fsW&u~fYb@GAI5u~WQ85U
zKoz!~3)AVT&Omh&39(u-Xr2&YR{@h`IstS`^2-$KtHI0rNN%N|G#pVX147KSt+ufe
zjc~bv9y7)BYM{?dyKp%eHq!){k=bc7uT}$V<_OSj@MfkmZ9NUdnJKPUOXAG5rMBtA
zzW883PZOv%e@-#~nM=f`>c>Jfp=_kZIufdmh^IEe-Z_%gR45ztmyZOcP*Nz{07^|D
z+wf&QBDM@rYWgr6K&euFH5*Z4tNE{w<UuhzC(sSD%rpUSkY%R$UJcIR(`4Ol==(GQ
zZ;a0*53E`KnQ8$~n((v{Peu;02BOOp3#@^fH_i0KnDr(|Z9tc1S24g#6Q<7jG|kj7
z)|UxVW1i0RM?c#!IE&MSsl7xAJ1rP8Q_05~7&24Tu;xIxCwKy@!GbB`SBnLE%1{M7
z&S}EJ&IMOs?`fVTDuzQJ2wtb0iU<jV?=nqD*pdAEh}dv~&9>Dpux8^|83dRkzy^ZN
z@kpQ<z-HTOJMJ6WR?Dz(wylP9Tb?9=Jt2zK(*&^{r@<zO?O3O6q1y;1q3mhR(+gsX
z2iEYZnN6S@AEP5-OF*%0s-=#-v;lR;XYZ8QN1#{|!5X;Ivk7y9Pd)SVm16}E+lHD>
z5Zi`YhB+09+Zw+8vvK`L9MBwbA@iV_PqD)qqQxHxHVvc#o{g~F0ZN-NH)t?Z46q}K
z_1%QI9jLSkbSM1E2jR(Bj!mE&to^CXa1G4<DH2!<=Km=Zc7rH08Bnc(CvyaNZZc(N
zaKKtL$<HU?>vJU70y@rgt)X;k3O{$8=bG?y$9XPO$~_RJN?P0?zsx55oB)0{;b&m{
zj|8RM;gyE2bwJW401f8LRN$ueIY^umTLu1X<v}q+u?SsvtS@r9TAqkz-BJ_R1vodH
z6^N772_u|8$Z#%#*Kn;l5<Ij=fhu+kc@?yV_s)^9SwPP!cn#9a6s4;r=>>6Q9!O#h
zSK@7OUS<{E&Wyja3UA{eJL|>U9j8GtzZ$44vkFdkTr`OI)snb!1jxYDkPdiO;b)xj
zj|2+hW})hX3WCc7%d4fCU{=9rIFwE0%xFkoJgd-iKYtf?M(*C346g^GR3A_o)R$9c
zGYKQBs}<ZWR96RKESchcH8|(ZDrh`V%H9ne@RY2t4J6z=B5W|Q8664sEu_nxh)C7a
z%yf#-7N)3KnIEjdTs5nJG0a)B3K=73?yOZ!2k?Z^=FA1;%$*hB8BCWc%2or@<w$Z*
z0nz0M*s|pwT8mo7%B)2#b8!lSr@e5B_r+k$&#c1Wa2}nN5Im?XQ&Dpo{8OiRUJdzh
zkA(Xb65<{ap9@4<2)Hx7_$jkb0Hx)AnqiKeB78NNY>$MkV~LifUg0=c0KuPzw6#;|
z4UgnBo~q$eL5U3;xGv&<HQKn32-^n?;U7tqjs}9xB)W*zbtI|5kd<M?5w8e6Bm3(|
zf>I8uz%xwuvj{wkD<eu*17D_eH4L;_I!dvyi;(o;!GOB;oRWfMK`UH}d?YBP4#Le7
z2faevJkzP*2%r-#UXBDxk>yf^o5^x10?rd&M^jX-c33V-)7Z#zDKt%!<WdBqC$MN~
zg6!nJ6k+L1Jvv3!YNWmt*{2bFV3ynzo)l#l^hKVGCnmUkxGY6r8@W7Z5!g<0%M&7W
z0pymV@9$*TG63$p0X#)D0&T?uX-KkpL~J{^_OS)HaoadV@M_47Irb*MtRWNT5p|Ro
zDzWtuC5~K9<|ARlnD0X@u!fu3BVn}(?X*0D+A_9q@=REHB+@PactojN{+W6$XhM{X
ztLU+XlJmOys3zMq?zG1iN=|mn*h0y;8Xp@d8Pu4uhi<{ZjTsD)+dz#ON{ZPcR?662
z4R3U&%k~5+%n<LZCGTZy0%_0*#+HRUgXE7bWW7p4nIWoITNMfmT7&6wB-sB}g~CME
zL47$z++((6zkEdcP=ow3#P(_k({dziJ3pOcD{p&Ce#h7{af1RfHqkd&B4g{D4}#1`
zf)e`J)UrW;S-F=*2ejzHeK`{BH_M<uI_RmFY}lZ=46(r)cr!=Br#ckFAs|J$Wbz07
z6*%xD(#(Mu{$5;_TK|U^^viPuY_(%lOO$d-jU@!0JeffbSX=WH@?Uw;H$?1e2*+|H
z{B_Q$C3Fp%)sawxTzStCvEzBh9SXS{$w)&nq3g9$v8l%M*f)Yg^FR_Kx`eJ*e&@#$
zyao?uEPb3;{vDgi0=s-H8nZ!hIRZX424^V$X#>sWNU(wI0{w@!)t&248BvcQJ0Li|
z3pzkJj#oQK_<EQrHbnW8{5{*vsWX<qIHuQ;u-(co3Xy{tGsO35$%{Dx>|Ef*j0J=a
zR?I1bFWtbG97`A-OqsD<jbk~A0LC=CN1~xJOe3w?<g|<>OumtIX$g}f49t-vYy<1%
z2sk<pb$Hy4I51-gk|PexSc2pmXOyvo$#;(uo9!5J0CMnXhge}PiMAoZSzvbzw-9*}
zXHI}lwmZ-p!Edl+28dzL4`r?!Q(s|xpN42&M-uu>IyWAPqZY5zkmlrwFfcRYjS5~P
z*YlYA5Q7GDB*@I$@J&7<ww}OsOu_3Q%bYStCvoeMpy`DXpV|%Z_5Vnsw9!Yhx?2)u
zj)2W(XUDwcl1z#{L<VaBGh-5y8vxHog3|dtQMr-vGDQ1gZtgK@(Kf{R8*}KP71|Dz
zLeoy4cmr!@OyY6_Yi5Y^We5^8W>?E;02-OvJRg)rHjA|w`-s7{U`zt{$W9(*{J>H#
ze^5%Dh|`ZGb+TI_6)>sfQDXa!uZ3t{hG;NjHa-KZZ8mk(F?>w}3Qyc27S|Dlu1yc_
zP`C2Iz@oG2!GNOY=<q<0`V(&3=ioGERU-q+7Cv)eiEu$$5MZ8==n<GwMUUZnEK)Wg
z<rrH-o9D)7h{AP58AmsPvw;9}%4}&xiLC&x4rOh(0>C<!9-3d^F_t<2ygC+|Nwhl1
zxqb|km?L6S0IVW;85l8R&``~go=1{xN8rzh30XGloDP19Rl|@FBt$vlwPXpeu!7ne
zGR!$Rn1u)v1~i!vVJ?Cw6C%8Ynimuw5sy=bpfe$2lgI;pM0|YCmk?n{YRsvS@ag$=
zsAcIb!x1k;=pIUJE1~2QGIp<_d*a(0ST!HfQq5dpA?gtHc+iqUMuqrF3^uY5Wvw)O
zhXAvz;)EG8D&QF3HT87m>)=u7h-Oa-+k?wj$S?t6APf<k>=^Pj)MCewE4};?#gMPA
z20Odc(VfBWbUiz;ZAcn_69<Wp$n~HB&0U%g4!KM5NyQzl!80Hvw)rFI?QHK1b(GnU
z$@gMvf9B^eWYl1?b0!TIyGL(T3%X89r~x7mgbXSyEJR@|17j!Bt5Au>+1jMTjwwaI
z)ss2BvKAG{4eTSTdeElkys<FwZbF2LAl`%ss<%QtVa7CEGlT>SJMSX$Sy7G(MJ?qI
zLj<jH-w`4<UOAx)!NQRZ*2KbZl|3m@Y#9H!)m+Q*2ljeWlpPcLvWDomMNE4`xSEe>
zNl$}Pb1~+ZB{e5R)QM|YP{|rs@nkV|n)G`%T!DowcOqPqg#>#F?$Sa;Egf?rAyle_
zXR~nxWG;!Iz~K25$)z_?ctV86LE#AzTkq(pkQP`wA!1_)0$#+Zw>CK6#i>6sbgr|-
znI#V5q|!Vy9Z^J(2pOL}sk!UX6Z@WERI+zMz^+Vgd(+jK#m?|{!*CNEA}WDc$VWsS
zR&IM2m*I{%L{NcCS1f%4C+8z-s<-j|6T{wcn;s%m#EpB1Is`q7(8vIaKQgU(gm?)N
zo{cy#A>y+uCu+sBD?c_DlNs0M1!h*+86KXFC`Y|Wg~si87CgOiG=<iJ)Dwc-V3Ldz
z$(vZtg_1=12eO<^q{^FNRf;NaV1;}{OZqqlax7kX9a+Be3&_l&<lu41g3uEJY>Z&^
zgeZ@b21-wesDop`FDe76Cq#TL9X+1By*6-bLWT}@OsFySbgssr;h$nWg-505NTB49
z-h)aGK6p?^t!bOoaiEx=3K8!OWS$UVuLPSXL>#rrUUaoT`K=gQ`i2Lw^@W{abQE*@
z5@Y{}dI~gNT!6#X_+n4B;*Ickn6xGY9;O}MOO~M?h&v&IicY{g48>d@gT_nq!u^z_
zd&|f+A;7NWT#w@2n{z#icYj0}{-*XThrgkSehJ5e6ci#fpP&9GL{y;VFW5MN?$Ea#
zM4%91vjK(YJV>8q*CG`jcdgO#s+mf40dhCa2NLSdJxkOPLD`Q8e}|S`=P)N4?wi&t
zbES9NY9DY|ynF+_Cq!tSV7M#Jj5*P82efx$;l89o|0^EN{&!5tF6Qr%<s$A=8VnRM
zkb}J?ndpen-#8*XA<2FS`#Zt0DEj6E$6eqbOyLlzZ-mF7@<&33EV5@r$6aRu(1B9K
zRYP>#bsBK4<ld#i;+w(&0o>{kz=CPXzz$LFQNix{lmYV*DJKNjSDc`i<o(Bz-t&<N
zz;^=Nu8(r(p|lIYcdSzo_Ma3jR!oh0<>(5)cOFx_0DR{$wJQpR1$8JS*n&DCEy?@V
ziE4Y(!+~l$OI$UA>YeA$PN?3E3TZiaqe2zMcxaIwtn-K}KE7f6Ley0cDi<|R#GAPj
z9>^M=&-RIWdqFYx2r>Ju6Y~1S@12;}h2MM6B6hA$j4QUk^<0qpJC1WMaNl`W6}{g&
zj;12>8+bq=;)8WuRT&yjbz)Fqg8M$R#D<7=eezP<z$OYATPNCef%{Ih>l4M8tk?ja
z6ro=P_noIyc>-9+DOH{T)_ElLL02;CJd=w3Z=eW$MEZVr0$Ue!&&@m}-1|C#t=RiE
z2y98;w}Cb5LhgfW_R#kqNIGj_iyAzXx^Vj_d<DYoBPuD3x(yyoov3~ATq>5o4Psx=
z{B02Vx<b_00Q430-@r49jG*jo!*UeY-$r8JAof359{dTrW?5t(j5-VG51v~+f&P;+
zXf34AghT~|e;a_zUT<4`MG7NlgP7R`^amlc3+WF+W-sbnLS|Q>8ym#Tj?=&(Vs@Pd
z1`#v82W;>(>vF)gfs-k69UACEA;5k#2#)C-U?cG{aN+rm4&q}I_8-K@ChR{5kWJ`+
z5Fne-e**Q8aF~dZP2hiU@tU@Zfdy<A{12W&jo^Rq5NZPdBQbFJ23Q`0J|%*Bo|Qs`
zonsLF+CVWEh<N-qxgJdreik0#Oc)+#w-gortfv5t!9IUPC}LP$pPEVZYc2(deoZhw
z-Md4AjcO9wn#Ww9wCNg23pP>YV;iQB`~Yn7AexQ<`Jh~l@&hm&!9&D;HFm^ML?4L!
z9|O-QWVx+O9BJhmV3T-R{sA_Lm*F7rqzqjZ^hdCrBZ}ey%O==A36_npf691lg8h?l
zS#Ab4iIz<!{K?g6f)5ixkwb<Z35=tUsOVuly~?4$=Ex!|4c;Qid%z}fF5L$VhNqBF
z^#MH_mi`<tp~!*2Cc&_L2y7Az%ZcEK;-xel26#;wGHAd<t-J_q@=yym0)tU61k_+<
zk(=n`8MX=cPXb~25!j?Hw+YvSbo3F)3&3WAVL1WV<QZ0O05-X};Rj%=WC02;-QqNX
z`o%+SlYxKnVB3W07Xfn<reD0pkw<|o0_FyozlfKc?g19@GMx%68B2H)RY<tpbThCB
zmm5w4i>q5+1xJKQPqzYFNSNJp8d$u;Y1$|jF?7>ufP9FM@$p2_bS|)!Kw7>9wuqwu
zia>S0n+^lZh(Vjo1dBkr={T?mq?;`I3plzpX@CgJA%hA^F0Mnv!g;r4DFJcg@nG?Q
zng;p@vRv~m8wMV3LjH?*xC!|$ns!^!#<hrvo1p*FstoAAxFY3tV2j7odZGW~@w5v1
zuRNeuf&WFoTeC>CTSbYm1-M&<{=r*H5r%7HB2|5z7uR3<4m>I9DY(@Jt5GAKMysIw
z;uTDt8g0;%jts?AQg-@H@LLJxH^FZm4AE<w=vRISwuyeLI1wAQu-Z3qEu9V?+eEf<
zJ2)bAM4X4s^(Ws0+c=!oi}p9KT;y+HOh{NN(f%gft%CcY|Ai=l)wV3LEdpS<AlN1V
zmJfn$;@^7V{w4sfg!>x^xC-rWBH#+NzX^ZqMf)4eQQi!;d5*0@`<v%jIWXAftxIip
zoH~^fp5FksazC(5cw2?$H{oq1l>)(fLPE6?@yg@CHkYMb4s7$NT8m5+duEw!@vvHf
z+c!_DRp0l`lPX;f9@_-FwWxi7-Llm@v2MZld=u)@>);7l&cY&7e%2AIVsq)rrQnE+
zm15_3LY7(<LHW(YD;*7N<LoLw1KT{h7NuzMLabc4S$LASQ<O@0Ayh8(1@@9qxrh_x
zg;==&?|UI!F2wsvTUx?Z!3&Xc$@ll9EaqhyYMzT+UJXYy@guZV**Ts2z3}uJZVX-$
z7?-Yx5EvI83cL^)mrjo<FGR<M=K?PT$EBl~D!T@e$hh!S@OU9KE-np-j0?{NUbuD(
zU5LH#q#BM7&ne?|nA*!@YB7x&PpR^KaP;ycYIm>+d+E90Wn_tM(~?`7I?p9ar-UbD
z(LN#k5up952XknvG~$^QZ#XpKp|n)#0E}C>C3qovrMH3?!dIqWJF=B!jx6oCa#(PX
zmbQEm9E)*pp!dhITKC>kJ8$PUToF9|h_*Zt9E*O-8^P(1wB?TApe^ma)OKQsBgszH
z5{2Br98r9ZB=$-NVQFt7b_ZW+%b&qPSK6EO9S^qBM=)t>bC8v`d>kBm?cP(3S7<x+
zoC<9R!<~7}A|KMA@6baU6iztri2Sqnkh&TCb;~`$@h#eNP;gL`j)X1cCv3}Q!TFs#
zq7FevC61M$N5JilaPC_^3|{?Ha&4B$U<whNag4WCG$==Vo0Q8I_m)?$hx_B+_Np{u
zq=?NO!GJbB54?^jP%&(BdpC{BfO16T4ji>NLAe8M?cLOJAhKu6JHY|l_HJx>Vz`@H
zpXeh?**~Rb@}MRi0o$EeLY2>4m|r}Td-9F;t|-L0V9P(j)8BUQBFz`{EYf^KQQqe{
zXhqKvv7HTV3re4d%3;Bg?cqqMdSc)sft!efhO|YkbHoGMi=M?EyrdAIT^uy_Vujoe
z7QwxPk+c^-{f-P5TjV@HUf8FMf2XSQ5I&;R73O-+Q`MGxg5&75*OXp46*dWYPl!?z
z0(i$sZ_|yzn?-?YVfo32;Yf1%t)ZqZbk|A;-DuN2!9h0KtLwR*>MQz&<7~V|!*j5N
z_HxzAFZTwU&cPDe3*h?+(Lg0?gY_og0*9?&FViRtC}{jNw2=xDcst?~>}6<sV02CT
z4h*iTX=J9`%hdM#l$zR|=prGwgFdw3o#5aO?bV3xJ;_5y!e%CBQ&THggd*5^W)j-;
zPIy9+9jfZ$LYFGqUYHyDIJcc8ypD~nO6~|ply9i0LmM3`YG$KL1<ma2k7#ucliOZ^
z>JGcyUIglnxF35Gs5?w~8%_>SilReGB7P(T)v(#X!nl<O++l{?VA(w>Ix5OL!C}zc
z@=tI?4BGTha4?Csl7BxQOrkA+1V?zFEr$e0e4ssr#?7L{RuDyTPa<&`gSRq>I}FA<
z$aM~j@}5JjT6SjWqXml5X3B5}!Dx#`=U@eGCH;2T);Ab(Pl~eT{;HO(ca)-KVQK3a
zM%Mr!?CVx0a7SvlEn=J_{o9_x(LpWR)79?4$ohj~4y#Z#NJV=JR^#R(BpApT<2_}7
zcTkA7{1-ga;(Y`tWOuZ{ZDCdrgIgfHEyo4N&CXU1aL4`67JJSS8){EsaDz|wrZ0o%
zEz*`NgX5;@NH}a8+6#VzT(qaI(;QKPjtH&$2dYle-`%<J2+y7Cj&%4Vi9QORBRtm@
zr_R9-+DZ)Wpa^ZS>fBrW8)gVcM4&wcslf%>%nt5g0&Vf+91+Sk92XwP#paglf@h?&
zkYJBPG_)h(00dIoN;U3DCVEm-_?sBXF`+&X=a_2Aqr_Gm{h7Cmz@UQ+8OKHR9zzeo
zG9)?9Gx_K#*EF^{5|r*CRP7x@D^%?r+6q;J__L8{+<iPzz+wmMXAdH3aDMg>qQ*u2
z9<Fv1Mm&4C8V;DTm3`bn3)rH?IXFN^f~F=qB){MzO8o`JL2cL~&UvUS91eEG9>U>{
zSY3M%h=XRal~vr6=d;C{a|C1DL%<u+fR2PH65)W3h;0Fy4kGX13+*A?4Z_eKEG2Fj
zWW#$eQ9`2~he75ccd&%EcySJ9&mQ-)8pNJ0PMjkq(2?9qxjq6ygWR*bAalpH#a0UO
zBMMczAalpjuM09~=I7l7nUNg&`G}&3V_z3!1~X`r_2%FO9RW6spaz{X5hOT2yJr)?
zoFcM0xIDX0Y3iw$Ky-)m$yN$+?;X17blh<c>;lmp=fF-79n_vvq`d+`W{-$%1C}bU
zxP$Jq#bWagSlWj+i6j8+-qkj6X(!l56rkM&w!#0|Oh5jFD3(hX+U_$-Y#EENclCOr
z2SVc=9w-~EH&4pW?gHA#5Wl;CHaI++sly!vo}IL=2cpysNW15ssb@~2-G#C-&vqBc
z?r_fDN<!|4eZ0GncE?$-18EPO^g5X>o?M?J;KvbMpDo&(W5MlSRjWcBuFd4$>|O-D
zM@7@Z#Dhx>m^e3zE%usYFWH@tnETD{!o=8=whI$u<JwM_K_3<+Hk&wR`#l1Km~%vE
z2msQz+DQQEOU>l_-M(%Ya}sQ^*&L*t?E=vQM?M#b##dlFW9m3K)!U~U>rui+0rJgu
zL1@snkA&^ul(}6vdH|O?VRRC9whKjrv9p84<{;~AAF_lX{?B$9v+<eUE?agmdbSTW
z3s}lb<&PsK{dOU3P;j;qje9b1w)kugByuFI1Pbp*gkowUTpbW-i?!weN!tag;Q_kc
zNsn|mCTth3hWElpf>I8(VD-RhkAyW(fcJ!iP3L*f=@IO3gWZvX+yN4|cxevO&Gshy
zf0AytXlIV-Kili8R*oYPazf=(PDLIEo<1U~f>WH*iaY#?x9boLX3lmZ<i~@Uvt1w=
zyqxU>$zbJd7f1#%XDb`IPh|DjBAa>ga<&(>4VY=04+hRuvT=tS(2=Aq`JAMp$e~K`
zwM|eOM4HV^;+`~`5Fk*DPascAEPcvHH4~D?$?!<1EO4g@Nhj~-(?#VMcLe(h2}XQG
z30oA7phwbCjyac^iXVu22-q%GnYd_<1N2tjaK{0An^xjHe-}cAr`(ZHk%fkVkin1H
zqMbQ?@U{^pXI!6c0?7!AuuUKtp%b<VBWG}heRGXFA~0-`&K!)IBSA|zwi$g!eSHw4
z(OuNZr`gIs?x53b(a;<mn61>|4%5#Td(6}I@(Izc)=>@WAs5n-U~J&mc_gXu$^sER
zI5OKBN~xOg?*hy;Vc-RrX;rP_hQX>@#SMe;TMR?o7Gum|t@}t&inVPboO>AjwiUH&
zm|e10FRnp-t(RvB1MM7p0qupeo)wg$D@rx)NsQT|l{sRt?53=yjz}%L31=gk%WeYN
zu%><_D4mB2WhcSr2~jS5&})u>4Fi=n2IldF71@^BO;r2rwouIOXpw^?vz0{LgCn!W
zBXh+6*-dFp9X{ws1mzN6Ds8xfBC|yia~RY&{6G&9$)H2K2{9us(QZV{NJ_Vx5HtMf
zx3Z6W@@$?EVG9YK%_*~O0LljTh=V<|m0#SGKyw7SHRBRwHvwdX9@xwk?#TFe1lWj>
z6>v9$Rb$7wt_dP<oa>q(GFUQ4g7F4PW{dsh8;kLXutVfU(Gjp|pwI@)jN7JDX4}A^
z?Sf`pTW!(4e1AY_lW7|4nB8QE-m&Bw%+T97ONFs<1-D5R^JKj2CbKi5j2#Id3T)X5
z2j8KpmhA@EYy{ampGmcWHLLLTMp%_y1+c-P*~%{NV9;z4#5@T!N5F=WQTvF{GLC*#
zs5|4l?JCrb44_*X$Q?;Scaq4mlX<q?N+9ka!fbKKJV`G{K>dI(>!gE`<C6J^pkOY>
zs&DMZVhpO-DWxhhJ8vkps{k`HwC*aveBMVDTn1@oGbg!&GPCPtf`Bpe5uuc0-PLTO
z&Dzx{E*C1vB0ZThPl$54_u#;M%J_H8lS;Gok)+;)*FBVS65e{jsj#{ph*M#u$-09W
zaU{7XcCaTt5|rX=##H1XNzJi0bg(pzAUBwfa6U)EhI45?N5qx`tyWXJK&z36yn`pR
z#T4sc$!y%<9|_KlwW(p85|wGZXQ<9y3DG;~FS{zdWk+)6BSMb?t15|j2iIkbGIk`X
zUe$APjlXM=#sI6e@VSXrYmvS{tI9>*3zumju<Qlvw5V~M`O4;VapY6_@g8)U4YF8I
z%F9Q$vZPzyDu^1^5!mNQhVv(}c*@dKV!jm-wtK;PEK9?%pc_~Ek)(1{O~om&DEU%H
zo4ZW3ghODV*}9V>qnzZO92rr+daz_pCx@B_J}m>!1w3WC@n8BOz>wnA$$u&G*6d*J
z?Lsql4|3lrqch<D9SOz_QHeJ)jrSxGJ|W00rIY?rI-AauWFbWFh>*OCt6|{VqBzu@
zoEc>w@8ryg0oH4l*f0QYaW+g_YH>9UkXuYm1LP_}c?Vl_ix1W-!d!0U7Vjj$6vFm?
z_%5YMHQYXwCiMVF3j<Mi5@3`|ykmpgDxJkq>TM#|cd610blY93TF!-7sv5>Z6ep}>
ztKKT*xC)W?LzpQ=jR1}+J9#HxM*Of2qRUcR@y<XzOWdy>)Rwik^hlG^+C<YGpUj0v
ztk1s|<E3<jd|#w^bwq_f0=AGC`bel){_RMz)u$&N=1ACTZXMV@K!sVG;JSkfv-V`e
zz^ZFcwY;NmQ|%^RS;|e`0cw_5U>(f(wFSvL2=qskO|_EB5|Vc?Tb6iVy;UeINPa}A
zF)?`uv|GFL!8H^nBJTi)YwHu8l$a+(*i(QhkA#iq<UJDhDlqNZuBLO*Jx7GL8(xa5
z^_JaCLw5(%Ufc8#3w2E!1mODGgzX)E9cvpN;;D#9v)n6|h+j`f#GSPX$vXn>tljin
z$A~vPw`07UhNW|^H;qe2545<$4`ywm@(z;B+7*u-7|E*7V{&8`sb9U#Pod!F6O)JF
zx+Ay9+C@J<PNi!XsgU2L|G%|w>D6Ufj+*zc*h70@sCQ*fkpKw>$Z#1UCRi8=`3^8b
z{C&R4jEL%W9?Qr3;v-$J%KdfMqr0lJq9P;BT#d*tmzk^o`E@hp8lT|0JZAK-XOdlx
zfpw>EdMv0r-P2=W<q1@qNgHosqio7YK3o0(YY3<<X2!ebT4H9pD{?rRQjH%|_JIEP
z>?NB^|9b*RI2LpOV8e4vSr-5a6W?nlW^pW0I=x$}A{|mg*vpxOh@&%Gs<xs(OVw6%
zNb@_HFlL0Sp9w0=#}xmb?w;9H)j8pe4)_EpWF`l^<1E8Wvm3M)Qy%dNT8oJeHj~I=
zCYKtDI**xrYAEV_EGWgoqa@-JOcx{bYXW0C1{~f^gnydJsYZ$@Gx^kgMv1jf40lJV
z=Sv`$8cZ3p#%d=<S{`+hWz3o?UFeEn@Cj;+iTO3bbTO;CY)6Uh#Jm)z>sZh_dDMNQ
zb#kctM)T-UC-22f4mA*6%ZR*eouR?RvnR0OW69e8(~rM>&TCsfmwtY=+x*n~*^ZTM
zqknvs|M+iz{I4JNNBR7h|ND1;ehjk%`NseJ11vXFK5=N>*`_~=B=)xHOd7~fw&{H3
zB(@DQ0EnZ;<jtNAi-DfvJ^sv2B(m_i+2VZloE|1UB4mp;5g*`Yn1}=wn@U@Xy{X7+
zY)SxI%lPy~dDgLIF&$u6B#tm8HLV5PZkvoysvwt}6h11PSL2yw#s1Nza>;-8!Zw`l
zc?I9thSHzY|B+xr&Fnm;)1eAgJ;Tw?Nu%BJPaAX^YfHb=bW~CS<{6JCDoByW{B_UA
z1Sd$b;<cx1LM*<5k7ok6E0zlrN?m*CMVbPIYlq_~M71J=n>Bb_6^Ap{_^fN5I9U^b
zUy(!16rou`?XgyQo3m3gWlgFBlc(kjR|oPXnBw{>^ju7NdMZx0P2p-4Pu&!GR+DCM
zZdCQ7@O%}8RcC$`O`F!ba<63y9IAOjZAHT66=WPMsvP_wQ@V``Zj)(4P$6Mv<z_G6
zNQ5QFyFw0b%jvB-Pq#u6D$cMrfWPx@ZKOzYuF@4;%q=<D3L@y1Fl+_Cb(>;5E7UBv
zMCEG+yl&}{R($U^sL2(d?k$dSwUck0isBV)_iaiJk31tA&_YE%gT1-KuaFGiTXc|$
z;J7Uz!HT`b-pUMma=1%%Pr245g4YT-rCSSHLuk`U(cW<r=Ke-P3gz0C5_~~wrX?r1
z)tVW+;~^>;^nwC9HlbVeqLz`KdrB6(;@h;viD}pkz0x)}CcGxuOL=ss5-~J<&0pDq
z0o)@aZ&)%@`9StPrAy_GsDYQfuV_qz&$PA3HKbsCWj5_dt|B#()|pCHSX0Xn>ej(%
zq;#B_1`}7|e0g^b#>jl51SX#bEtz+YM<nu-xIzQLZtH-mfw!@B#`B!ib5VO!HUlMx
zQ!1gEc@ULv7CErD&J-GDypUurO!1vP$=-72M1HPPZ>F|Pt#$fYl@0}ryyumYEE7g)
zS!-ZG?y6)Q3rPZn9V%_n%^;<`L&{aLk<RX>Y1+u#c+($kCXBk7N;b1Q-84eTcP2PQ
znN^e>2Zy2yyZ=b!0ZDa_d{35%SmJerpT0a&BpEZ$X!NmOEf<$pIUR1E51hp;Q|cV7
zmrMJI<}0#K;CcDZ!CFQvyJ1~k@>P3b{t3qVBg$}@qU#aR_}t6@9qFT%sO!D#l(WYr
z&>g?xs+CHICMd2~#EZVvk{NDo9D1lq|9A`aR%&-xQLuBB;wtxIy-F1I%GXjC;wtYq
zh&Svj(%2ZvDY^N^DCvEbi5ZnlF;U2WeAU{dqQ#P;MyFI03AtBaR8i-h8i1>-gPj@&
zOEO5%s(k4gGH`e*26<5DcnS-m%3_G%UHL)?u^~8pFrIW?-ASqNF)p0ic~^stp~FMr
z)06SMBy35#EeX&eD@JLEASZ=dS=6nC_^5?JyXlHf6^cORs6BmA+wP@`M6C>^KJE*W
zs9l}E!c157b5X+~#dsDa7GAP8RK^r};L7tflb-BmuzuV68Kp0-?2&X{q*egt2o*h2
zLL=ofUMeF}$B<A5!s!)YZWPRc5;>JG3ZxgPAwf}L9elkMBCZ$#MF2`fDtBk}v<_ps
zQ&UTaB3BwfK4^EU)|9CscM8i0ntuhElj&VL!k+W!vQU`>G4m0uycCj)Yqo-G^R%_#
zFp`+%4Ys{Oq>a&zTq*~?Sd6g5p%Xzd1z?(vc@ZATv`YVw0f(nzNZ3bkpl8e*j!_{C
z?vi*PKn0yEbVRsiXpWAqAujFvMnC4^=@v}`NuFIB>4;bgKG0_5P=?I#g2e!sD1qgn
ztQHZ-5?p!ZX&q2#^Cb=##O6+v10zbn^_E6&1UUqwelutw58jsOLBm9MCr=o}!xzCF
zM2V@ejmdaN$d4Y5c#?O?dX57>IiCYshA$qmxX1d?j0OIps5^@ULA_pL$6kKv6djX6
z{zwn$gKxG7nu-J3IKCdFGlI5fq8MhZLFa+PW%4Nubnjr6k*J8XeI*+QyNookWbcpy
z_NGZi)ucQn)dF-vV2&;wr(q{P;0wEEf*5mYF3Ce8!BgB5F|Qn_TJ4U!<2*?jdf$Wy
zl4JZu7?{YC=*kv53lO-khub?(u1P8Y4Y?Nm1fecpj$@NI#bZ+Z*hAG~VuSuZ4#c^8
zVYv9~6fVDlJp3{V6wJDLex$=M0M{<)_jO2vRr!4iQgzZ$arSTz4R)RYTzEd=RA;Ec
zgnZdW$wM686jA&IG6vd+!;=^I%Oeb>qj)2oao>azKhw|J`0@GU^O>pZ^T)>l|11Lk
z6q0zl_ytMKm+XZk=6rb}iQ`vDVm@dhiCpquP$KZcizNabJZNG%yAR>SKob*se1VCH
zE?zJ(AD_TP;Ve8YHAN7;!NkB903}wSj~7a`UqFeAdsJYF0VM)L6O@<^-vtsmG2Tcb
zP96v)5{)F1xPJpl1gJqIk$iU`iBEuw#0`lga^1a1Vl+f3B2SJkjA&%MUl@_k`voI@
zMG-kG-Y8;@+!HY3$4~_;0!56a?;?nFZ7zg}Ck_PhF-h261abTdLF_*+d{}i$z=ur;
z0}#Z|J1$gD03vrg7eM4D{|z8w#{~rOV-lJP08tN}0HP$CE`W$P?zspe&%rK$$n&QQ
zAjYT&JnUb=!_R9V2^)fkM){bF9r83#*r9+mVTTIXy4WE<Ko>g{oGt8-M>N6?y$Z|}
zc1RyX*rELjJ0#L`(Zk6_p_&J{h{gy$<i1MyA%gb>A1Y+NlB~FuKIX!QIzSM7D4<1v
zp^_{LFx-MR2pB5D_X37W1SrT5sdNPxip-aQp%6s@hRWJX$Z!eH1Z22`a9qgHe+3x=
zvcHI-@^A_<%zsBt^Ba^Vw2%_$1PiCqtO_nf7Gr^hN>A94P;(C@{uNlL%$x!X`>()4
zVS0%bK3g#<7c5kUM}dV(s0y%9nTdrJPW4h?;Se-PuuzyD!NPtaJz#}h5dH-Vnei1^
zp|UCpD~vSci4%TG;|omq1iDDH5jY{;J;8+H@7|R5iS{Kzcyl=mA{2fqh){{j0TI@l
zL>vfVZS;%;5#E&df(V%xQwX7QPYNJpMrWMM9as@iT;hX~(tNz}!Cm;$VL!LaE4gpx
z&5jNVBK(pcci21Cv|z$_F4#l~16Xvp@Jm}(L4+iFBtj?@GZDgf>RthaTY}g^2ygmI
zLWF$Rlq>S)7b`a<>I{9n0}yIOy8t28a4$Z1v%+0?kceKV_NruAUije6BlyAxc`w0(
z67j2uZ)3WvAHTo{0kQ}myqTN?58lj5Gq=*2*$B25K)8Q_5K<5D3qF{4zln`rS!{?9
zN`?9&gc5oF0uUyw)R9d}5#BF^P!QQ0AtY!hfKUpXV^CpsN~`u_gc6v%7$Ni=0TJfE
zUU+Z=LA>bT%>qDpP>=n>gMr0ecre$o=L<flR}A>zOMm?Z5ArvH2dB_q;e$hnq3}T|
z>0Wq{lD9$#k$CHk5Wdu#g%Ik2Uw}}erveCdAooHDCEtG$LOpPU>MfqO0KzJ9$rnT@
zMb`@vCWt6>@G2Dx9aP-c3m#ND4~MuWMpx({Y0GbP@MeOz@Zk70JV+Jf3l3g2LxF>g
z3n@M2{k~v>E-vLo1|?)iXz(JA4sNfGo-a74n#uNcg?kbkROWQxgHOPJKwpFqUL8Fk
zgsNTu;Z>pn=UxI(FO0DK5+mFS6%|G(C=M9m<H}_$kZ=goBS@$S-`*sQLtHR%!lJly
z0);w+zF;9W&x94KYC(lVLWRN#6>lu8P~saCIv8)LF!d_(ISgc03h@YFc!UZSsv@XR
zLD<r$P>AJZXu?z=B;Z1+>kuv+7lQ;`$RK!ug*P-#XrbcMgcd6PQ)nR}QDKEuf=xsV
zyCRy17Ip;y5;45Nv<!EoF7pKpFGRTCQKSM4Z>S~#Lq#?xUif?oPfWnDDK1H%;f?nr
zY$!=7%fL4UNfI`^!DoaG712rD@CILvFF{k!8#WXsD%emEwEGv3kg(y6kr8Z2#w<|7
zLSIU#VG(Eig&H#20)fZ((BtBUiZ^;;hkzf29SW=?c37xyb-_au;z;oDO(iFI*htk*
z>=3BX^TG}<`}u_(!UF729K#oOm~-WMV~3<B5<I-rQG$o$GZH-1leplaNYlR!9)5=O
z^P3-^cXAy9;^&V!YTfG(f`<iIA(v02lYQ|LLGh!%YBm0b&wzZjw&_QMwP{M^3R34W
zWM|>6nm9t1L1VTFru`bx1S6h0b$K8Zw=DSg?3O<E`2NQ|vl$Kj;#UDE#4*Gzd;HnS
z#XP-wjEZ&O%$iR9L92aXtjX)$e8}KX*<L&kg_fgHunxe;DdV2t((jdp>;M^hHi+4B
zH-eSLHaW>Q-xx30y7|z6l<IqD07y;pa~5FS1%wyItKTcKHjs{O$KQ~p02AX_@*go?
zJotbsa13}0fMe>^EmcAvlMWq-YepG5%%>Md4Px%*MgZuPZRt)%)^OVlA;1Bpk=+12
zRFeQ56jKd(TQi^eW73tw2GS%ghrH-UWjXjoCLOtmEwC*_(}5{&endRo0oy!t@nl??
z&Knb$dqeM;yVAJ5dSUa~4dfiKMSnQ+&fDVA9UMAaPG8iqCN0lGjI4y~5SL-pt&6w~
z!v9f>PA#nqDHQxM<losm&Tn|fMkfjA<SC=M`4&DwPR<5nvgmvP2(R+CMwp99h7Rkx
zCH3z(GZ;he^n9WXJiGIW0}7p3OtcCvgRl6T9lQq|Xfr-T+Pj9T^eN&w0|;J-*m2+t
zL9Z_0TgRB`gk)pf_<;myaSW*99;)y$BHC*mTqG{$#u@mENo)=~4U^Le7}b_M5k!HR
z(zYUJz&*6VN7o`{D>fh|={a}2sN6jQ&$h*=K6i9UaCAWg*Xs}n=QT@;&J~}3le%1m
z=VCfKuL-8x(uqbvm=^@-&W;{lfE4Izo=JWTDCF=K-4jPeI*)23x|92!Z3i==0xz;9
zK$|C8liusG<SCXkU~8)1+tjH~!8sAKwN`jYL90jSa$!A|#-HR0|2i*=fUoIlOUKce
zsV$g^({!RXqC`@788~1w9?0P=O$P&T=WH4qGSEMMt)F9x{%zGe(fW<sBGgNih8p3q
zHn;i$060vAKZ$oysaY#_y*8Hy60;P<h*OT1Ty`>iSCd-ZIaJKS#zIgLR{RcFfE$SX
zt0%d7G<T}`2osZ9UB!vIiHTMb1pPXx%w!oE2f;4oLG2u>8ew9fc2s!brYx=%nL=zf
z?!{{66EO+P#hGZ_h2G||#LR@$Tm{x)qKG^d@PJKzUn>IK-$$u9uA5@7SA<PYMiFGP
z6`MK-L_!vu^&Zg1P*F>xBCm_hs+!><<|g%lDLPqHGu%X~+Jz-M$$eF=JxYowsrizT
z=T|GvG$Yk&jf6I)JgXHsZ%iBGV~Mt3wYrM!RvagzVYvZ*A24U2<<Q)%a1NnpcUFmt
zfUTjqhi#p47hWL_aSWIwAaCj9I*zu{L`H{HgiQ{9k86rq*wA!@-h~ZK$chB6ChB>G
zXvRC<22LcCsD3soUyjW8`w;zsi7`8T0vW|6*tBxHH#B2`c^}Kpl|J?SkAYQT+6av}
zmWhklNl*uLg#T1zzp|07KmR!N@Zn8L!0uS`dGM27u@QYt8g><AT^szWi#ed<`U<x*
zNTRjD=VX@eG{r1?F$>^`4xKx<@I;5szkwwfX;@E1Add~6n${N8<X>o|;*Ro6>rGv#
zA~P_&21k@8&AZy*S}N0O1*~g>d;A(oJx0Fk6Na2tSP-E0V@k4GTaOanMI6AHva22o
zxEB>g#%nRmtD}EBf=@A{cSIL<bVI>{hpds^BYCS5G8kGgaAxwcpfrQdfj5=$Rz`8W
zV~M`KC?D`;k(ae1jh}U`7MbhMx<dz{LIcXWzV$#Zx<2e6cAHKK-XUvv9}uaj6s;Ax
z4#7TwC2w1GlXz5}r3@ujYS!A|2X{qfwT=FW(UF`I>so(W{`j%T%vvGR^<un$mvSuZ
zFkIEh%X&C64UCvmMF!u+0zi^XgC{C!yb5Kr8;#dMijp*5?d1tt4TJOGyGj?YLg3%J
zzSju`Nfqyu7p?(Na7@|s!7xB<310*r><RloDS9WCM~C2@NhhxY$2=C+4EMHcNq}^n
zDOqdnS;Fq3B4errHM}CHs!3?CBJt|w6;%ZFSeIkb8{dg0dXnQJwxgqWj6CbPo$O5m
zk3D6tM0_ebc1)}r{%x0Mfe|u+y7e=FZ_*PsQl^Bh75K1qma;oqIC}cB(%L(Qd^wf*
zsdmoT8>5LCtAzuvok?!5;$0;H3&5!<wd*lOXPDWweqMEx`d&qjVr#BS;ruoicdX}8
z*gIAf)HdaGJ(dU!6$K0Dtp=jR^9niDVghAL16Q_oc*r^steEcB2n<$cYd$8{js0xX
zR-s#z_=vHqZCe#%TibBZT0thUCg<f94vW_-<x85j5|9}+ELPD)XqdFivIFm~Ej@Zi
zCzoEY&@gEthjm88w#B-kYNGtG_4B2$pqNyAMc$M;?1hms=1Eibk1$}xhtQgqA$%yU
z$u)^jsfoMtRD5pVWIeduO^yjZ+Q)*o1#v2ezM7@j?>8+($ZufE23x@hvPRgU=3$RD
zp1f5Y!at-5l18XyCbGs`YYan9XSp>LVj?wdI0i%AZ`?A(5nj~88`{i4#FmtDeHDJ;
zF_0%0hjNFmh<6iIB$K4yvE&$Pc^Gi6$pCu7)Fx?<_)YeKAYp|(vo)fG6%>1`To0Z)
z;9XZP2xCWqeS~+d=xj{MDnDW*CDP@;f!Y6}UxMaf67Z`~%eJaXJK!YWv-diZvB^u|
zDOb%}1QonkodZWUb?be6MU&%^VD3oJuR=!ra6$1*AT@3h^{ctPv#MM&727|fW?uzE
z?oBDhL5D>8jwPF{O-Al$O^0h0n_jEp07Hb`>O?78LR7xyk?TX|Dooin?C%kkW=h^#
zXO9xzlnLKA&*dMOvZY;vlFlviu~ul^zsa%iY-{I;48TcMQUu6Na4Z}W%&RJqhKVzZ
zO2DtqB;C^2!AZ1Le(ERouoC5~NCEJs>ZUVG1-_>OtTCl>trN~{#g-ueACmxI1tetB
z->Z|pYSrwW`%MR)oIe2npkQIj*IJRK!BTwhfoXwN%$jrms%))w;v56|dlgvPDHCZ4
zxJ^9d_(`&kFD)8CtR(v0f(YyYzWWA^zGH}{Xy#6AG^NK^5qR`wJY%m}6zo}{^<m1#
zS_2?8#UsD981gYAmeb1C-g?2yja;mC!NV<@w~5=D60ufby>IR{juI)-cMRDfeO(u}
zq!F%iO6QjPbRzQKQhe`$DO<{I02rI5{Huoqo^72dMLPuyETrBs(R?bByqJ{tDsXv|
z`d$TeZ_2z{*N76mafHoU<Y7Ifd<gpZ2AR|(x>q6O^5&w0+jdO&_%67eMRR!JWTf!m
zt*#X%whE4BX}4wYH2L$K7Lwho$SGjV##%u%GbLjMasCMtn}&^|WcO+w2U!t*4>cRp
zKU1fJ$mhb5iKzAq9%j)-e_51RDg4PI$9y4uixtgj9F%Pd^Hs1^w#)klOZQUxSN`>E
zCuYA$&eyhm<sNj4+)!}}xT)fIq6ebH$%v!J%^=W<Bv)Gu+nT49?_dHDul=HeIP=_8
z=sSjBOiPfjg5|eeOni{*j|HL0$7HySm9^AB$x%QKu}yitiZo*gY=9*>=q{Na90G5N
z_|-fn-mWh;4w65XD1o%@Q?CNfqBmn<D^9Do6#Qx&XK(5EopQ!y@Du-3FpJ(n7b8kH
zP9yuLk32HKZEE+`OcM8mg%yKQ5B0uNj^62`kCXiE`tU<>VEg^>Zv+5H^Y2))i#H%-
zMi;e6AWC+-U_lTRwkuK#Ji3nsrD&Tz@q3|dI@H_97<Noo)+XC_qhL1L)=-*XL~lTQ
z_X?6}1-E0n){K`_4l6bVx3J#S@_<D7la>sd5n2fD*LHdK$$r@`*I;wT7on8k&}_&F
zo^tk3{=r7X10$y+8YhaZ7%uLXoM1($^Ol@oMf%8hbWV}{4<13%@}DhUQU&#AQ%<lN
z!*R6OfcvwJH_Zqi6U=NiimWw<@K{(YmIxDI7$o?2*idB$wd)7FbBixk!T)(n7d3Q{
zi%~LwcCttqvy}bA5h55s+qCU}DI&4zhAt}GY_<L+rYS#*+i+ZnJPL0OrH<Cq<A_M9
zC&Hlcyuj<(rsG18d$w}RRz!_%i3!$Z_vDSJ@-(A_>4LvL7L;O2n!FC&YG+!8CoQq4
zNR6;&w%aY4l#0v=TLBIglwHMfJz;8j6<?es;V2H=LJzw}VWEel*F6=KqK)*l)pq>N
zk=^JYw;&)DZH3d;WEG`E)r~^SK5A2v@64uZVa1!bO-m78*L_6_E8gjk38ieiRwK~D
zx6y&I{AZ3Ucr}V_1F>kEPAm{@yd`RQEZKBzQj&kP?Yb`@AZ_KUJyCVp9jrQ7ZMFmq
zBknF^>aw0(vYsztc9`qROk2H1iIr3dec=_xf_f~u8e`4fTPqIM<-NJ$BnxS8EjU=+
zH|2Gn2nmcuRH<z%$Vl%9z&tV9N^M(%kF=H8wk9Dd!v-Z)7V~t=34&zp#}cJ{skRc`
zR?y)0zWW?UjGc&r#}Zw-v4|aA+NuX3YmwTvI`+|fYa0{a_$Xsk(oH`W%t}YBr}*m?
z{HDDXOi)2_+Cd+znMVGGL`EcKG>qO37*Jc<MKv6uCoK7kg>jba5}c;J1x`3(;I@u8
z5VUnHlWK3-Qn@aUsItxDjU+y8$y!!0pEg3&;=S04=w#g+;hSA`BUp25e*+KqSO~T`
zrawh9kD=o#R&UWuttoK6_r`&RLsD{YoqeVYzqh3F;J0rbMj(vi9e<h{ca-(Q24gGt
zZ3FRXE3&FZiia&Jrc=)G=f7G8%PQ2a6f_;%of8?GgRkJzq&#gg78`WV_a!a1a|PLk
z4J@Z)K+GTZf*XQRE%{4(Nw6zb-k&d#wU}^=6TM}`%T_AfV~B<<&hv)7?6Vn1*09?>
z21fdh2-jsbjJ{P+Bev7~id8jmmTr_Uyl*AKZOK^L%7uFjG0#Ond>TkhTZ&f=68?Kh
z6b?wkl_Z=HEmTx*nfUHAU2ZFj@y1y~ht`jG#PU@47WzV1@>sGr(t=CY(-wEJfzkA_
zpcFG=ao!)xSr}fziSWjy4f_^X%$wxDvR8&y4+*^$L(?UPhaiCyJI$wOil%18>4+nI
z?MX{MiLMasnDaLR8@SnK(%c4QZLb?1?%BbPLQER56dPhRx3c3lh)8S(=rrg+9fKmn
zi^L-t`JEeYaT^=p$1Ngb14Ox(Li`#yR9jTW1`gF`F5MO|=U&{wGytJ{Rg`jJSXvms
zpo$=LR16>c6_%b(_R`7#0@bsXkN3vA6CP<5lfR&lVeE>$t=Nc91`D=8p|=!*8%R{|
zV0bv$Qws{9>?6Agz@mXfwV8gmC5LJ&`)&h=YJ<FZ$}t&5UThU4`#nu{r$c=#tQ#9`
zW$8VZ476vke$8$6vnNkDjwxF#WlqqnPDDRnk94d>U~HgSZE8}cDI1Ly1SG4ME&xtC
z_T&OmcZ!i>6d=mA=TyD$tmjn4vHQMyr8ueCAUHOh<(x8b(uTmJV?wpqd(Ww=bMHO*
z&)JcoH<01w%GcYfM~QDno*NwtUpDyFbD%_3Rcu)s*j1a!ds`lkK_&qP$3^i2<j&ek
z-`hfD?g<NCiiW+ja`iSG@NH2lTZ7Lm!epZW%uA2~PP20JHt?*ru878Jy}+sFvGC(1
z8HlSAoAY*RxoFrMQ!4uyCa!^k*)e4Yc#C|8u2e*i5*`&8R(oo(NP5&0S`xejp6{UN
z0Cv<d@T&0(0gCX2hs*Q8iS-r}vLS444=n~Q1#s~)gZp$PalzT&;z_n7LxswP^O|4i
zUVsd>Rhl8HOJ@x<r!9(PYjAvr<RU;G*h4C%NHDP@KW}SP{TNFlw$XO20ANRK(H*a5
zho*0EEOs6>KQLtLuHG;NFvgV7N1GG{h9O>&!EgT4Kqc8jU;Sj790PAly%2o#d%>vb
z!{2cfc1+a$zz%ij!ylZew|WTN+Lu5veA3Y+*8vXC4t`<-btwc#Pz~nAOM;|Hlmrj0
zBU0#?@YI5pv<Fei2IA7kf>Mqnk$?vF(jLSm8`w)*a&|50OIs;>8|X`0DSI2(OO!`>
z(v+`$)i}Y~eTg!UC{dXO&hC)NM<0C03Z76-FiGBkn6@P*+CX00(i3PPxb2L%%|2qY
zd9_=T(R2(Pf4H`t`Xb;fZITk7BNG#1FE7!Uk@7Em>~Lngb^xF!y(D5f&TY3yi4F48
zyI&a_>^VD2?W=AzHk=_+Luu=H9)0T}V!tU?Vgos8cTM@8_h6-lFYVQ@L9=(iYC3Rn
z`_jOri`yk<3^vkpOjyyuM%qjT+;Wt+_>ZBk6J1&;Wp}2&jCfL8*@BNH`@`eVHcFIG
zDd<R>gvgd`q$eyC=z$w7Qe*>zc8e6*l4HBOKKyvYpWTP*g3tR>^$8a@2#*b!7q%FW
z$C7RDe1aoOczT%7yGtYoQ+|u=*sw0_F8!WdJ5C2XiqY_^E7YYlG*M1fA${|Ms<c65
ze4?DMX4Pn5(u$?nzyyD(6@e|j$y9v8l*7tz`p7M6*B$^%`R-aRu-xyi6=NXGc#FT-
zz;oIX!EEu-*b@7_ic5u6Psl4>F(rJRc5_t@ceh=+r*wCla0Kw4Hn_M?nij5N?bxd}
z0S6#5UE!wSF>U1oKIMc1+ZC3A1FM9<4a}xv;nRl$+gNHT2L&+pShBfv`v+XwrbPqf
zsNJ+^3~W~+D;0gjWLBo(25)C8*Kh-|X)BR%1F>m?rTwHSnkZjk;?M_*Rq$Gs^`pU|
zI~F|s2@%FEI$^^l7=E~nyKxafRL(I_^(y_(Hb6&jP?Ff<4IWE2C8qQ2A)3Yd;9Dy3
zNSk2q@20sraWeDL+5$MMe8CNx7Q4wypB*?9xr1$D*VyDGqzcb&auN_pbu6qL8^@b4
zxPhd!o4)81r!7r_XGvSyP2Y3SmNsN;;t|5{Yy|8kCW##F$w`7QI@CR0l429gwoP^H
zV~N#Kd4b#9k-Y$O6I7-xvS0(1Y1f-~0Q=po^u7&yVrZAewt826s*w_7S53N!qr_b`
z>t_Do>ZQe_uPkM&gxx{TY1fP0K?8n^OW2atv_&Os03Wufgbl2w4JP3emKiE*SW`e)
z+DiP}7Dd(cU0zw@JuANUFR3;hl2lE|g$-Yo^S-d*tJ-_76w*8v^aw1bV~NKJ4%4pE
zLtAid>r~x1B&kzta*&;lZXBy_zfzKe>ss|4PRwj81@O}rW}b2YH$)Kc$N_vxJJsm!
zO|$h~LkWt)RubR_F4IfI4&dQd4q%GoX%`L!ovj?dZNV*-eo0GBt6eplA<r2(Hzt1)
z6R0*Vq@X-eKrb!X31N8)GqvhVz94!C@a;)cb^`fh0{7jus&4Efsjkuh9&aT!Y9vDK
zs_!^J=PjmUOCr=u-48^l4YFbb6>4Xo=L1uAlB)zT@?Et`EDL==Rtpff=nK9K`=_FX
zW5p^^T$2QQ(V`DH5dSMYNUl^-8bf70(M|wlsa=$3hh(Xu1&3rQgv35+N;N{B7aX!w
z(OJQUM_UY~n657YM8tY+>GwCXsl;`>`B-lD6`Z;hZ47p$a-vob5~C!pn1AENAT6qB
zF(EIiC|0>a`Qpei;sZxslrj!C@S>D(xRDoygu_q6!PhQYO&~T~w3y&TZ5N#gY-~=8
zy!y?pX3<W6!);Zz;07L(QUf>gn67{%cudbO0OZJGD)I-&VxmUcm97+^50#Y7lczN0
zfD5AAD@v>w+fSt&Za9IxT9zAusats%8rV-o>jK$NVmr2^G8Im7GMP%%Ndc)$Xx10C
z%*|Oxj{wp-Ta3lFjjySo`i*U65mFBdlX#4c6s8hLJ=jYtGyOa;oq=CY{0{u3C7NRk
z0#k^2qI7z8%6yZMOLURrsDwiD-ZS}PSSTTy9a|0rFB3RM#v!x}NgfwDjt!iNw~A;*
z<5|j<Yie6WoiEqKPHIwE@c6+@T4Fplkc^fKu`{FreXEr=sFmu}4>>fKW2!^LbGfEF
zRPUB6HC+P}X1Sb);K>{jRJ>`R+uUqRIn7=&sURaQkrNxJM@w|X2I|pr&E(K$1)>Ly
zszu&Hn(_y1*2KUKlycDY{RgLLiDTFdDbttB=}%74F>t6Cn$=OV7>uU7?v#7Q7aMG$
zmjWy#hn6UZ$FlGnj>bk~)1ktRvb93^kQsM5MSN2%e~EY4Kp<M;9X<^NqUHM3gG6){
zX~7{{;vF{g$a}@d3lh=ttDNh2k@SVeUmpufr)4jl+uRf^(`g%2xR+@TJ7sQ3Rc@&8
zSkQRSD==&hQRpL|n?r)JI0oJ|M(ZuGn*(|*cpez_m5i(hrg-T^{cE6=E>iz)Ixx-3
z&nvP-^J|W9)g_)^1C<BbzOcm0A*x>kx93<e4U*gQ91G?#$UO^mz=k=nlzg~>j=M+)
zY+&pzzVd0BAu7z86M|i03^q)~D?HphufSwUEzu`Ttaze}+?G3Kh_x*Tt$7*$J)X}H
zAc)N7OBpO0mYyXY;)WFI%d|nj8U{(^2d2C;D_-c}Kq)(?1p*YIV`0S*M_Q%@0wnXL
zgvKqI=_~RTH!#<)4s!$d=U8|y0`AX}rd|X2=U67nGfI4!3{9s8kl(E*EPR&?&6f)R
z{{E71Y0J;wGGTlO19%`49fo|*wP56DcTw)|$Wdoo>E!pI11*yvX$K!@NguT*Cnzks
zOSbkZQdhLLpcJ2s&11X{KG3n`<LQvsUz=Wjhg8xM`>z+MH7(Nr`l(|x&iF`a*SrFy
z=-W2cdY;Ht$)+E-BrMqB>@6t^_Vfprlm$Cn#wBUNj@Xyym~dw(cyF#Jy^PH7hnuDo
zyY}J*n6FzZB^_SyG38HYHbm0SU;-_&?>dM;@63US@Lr(b^<)A?xnoRLl-RKJS6`_H
z!3J7;(CO_U|12@|dXj(ERrQAA(XsH(8zVa?Hq$e3Ymt!`hJ4~kn}<!)lH^}679~7<
zoQ14?h0+bJm6$jPK*z$yQZ2px3*IIguK>ah`p?=*;|ND~D}^5TKT8Q^I|x7v^t>lc
z`9P}PX{gTcs(0GaM^4FFqJVmmC3O18Z+HhyXl<n~1W#yfX-9)5v^D|vo;0E7SWq)~
zLThW*f+w_=t1fuF(h2N=I;<rKuLGG_OVbp|Z`R^0tyy3#xeZ;*QHnKwt*a%U{?=N`
zyO{i+r8K-99H6!6n|E-4p0!xahHo`IU!q#%s`X$ArJ?XQr!OB<<pSS93kqBICg0#N
z;I#yl6{f}??YMWjH=?$_Yq16GCrs>W&c!g{R#c~V9fkBj?P{_6ps4C@{<?WKTp=92
zLJHle>e7KVe#sP&a6*`hu8ZC%HPx|XXKca??8qAyCN^QCGf2^Q4A~dc0u;2MFu-B!
zAOdA}Q|FD)mz%!8@E8<n(31-kmd-(^w7gu04mA0gP_%4P*9+(<;;lgNde~T%vm;&a
zWQy~@k|{XeCTr>k_O4;eRl8E^ULHgTq#mXTLv~DZ^$nO?*zn-MAPN(j018p$b3hZI
z$dsmRdCL|l<pXF&VM2d#1`#GUfr{}8H|PzaIALQGD*Fepp*N-uu%a3pI*3FE4GwoL
zTlrWU)7fs<kK(PA(D1QjU6L9;`6Vh6Q)q!{NQxk`e}_Uvn7S^^(Inr$H!%6agqI1-
zp<{|-+*WH&qd@;wuFf{u3o(B>=tW`Uc&B6iC7s4ZcW(k-CDPsTy}=>fr>uMkILQkW
zTfix=@POWS6!TAw{LR|I90t+}?oBB`2>o}^io(R&kuqaz)`CX#B?Aa2;B^)nZo|jw
zYE##9b+)PVwQ`Q4W^Pl`Vt5otClLl#?;J!WX6?-DAtm7sf%bQrl3w_-i?iQx3Ld6>
zX*#oXTu-5ME{VzCnGz{%SOt)&JWRY*z5vRK(kt7pOv*`7$~&Q)3)OWFf?1G;9H!2^
zAtLN|kdng0wG<qMu(38~;MfJlm;p-C(wVekDG}n$zvAjfM>mx8p!b1CAj1DK<s-<*
z=m)m!9aV&TkddOy&JA>KnL5Y(%**&41h*tia0Wm?IVKddZ<^g;u`ow<OhNEm!iHDA
zGa<-Q&SKD(!i3j^Q+Fx9ZSS1BYomz1-t;yrJFB_f7dyMCO4d6Qt|)D62NNl>;_%AN
zRw|iyXO@&T?>k^w=JPi!a7!D8&TJ#1`ZKjQWs0BPnP5h;!yOE+FNwPyBd&#@GfB%5
z8@G4nG7&kykAh;}dN3Q3B!)XQkB$k&l^+So3io6br6tD$6uEbrpuyR_nrh3<ZkSkG
zWwRTK7=3+|K|TsozQ-URJz-)4TK<BSH+Dj^A9SO4+9GfjpRnQH$igIA{;^;NY6Tdb
zZzPF*$Yk`S4G#(8k72@7f?{N3N<xJl&*+t1eVit}aw!e8e6pB}-_)0U&<~#a`i^vi
z=S|219#Pn^whm4<5$F3@S<J>QydHCt2^Gnh3Nkx2{wl^yMEXAH0!s?G54ylp68(M9
z2PSvE4?4kfsUyntL_n?&POZy_KQ=T=*{p_f+%zeNaqMowDQ6?DYdq+}PR%%`px1;O
zbYW+I-71%pNm^VVbYZ8yypt~MO>i}t;%M?jtxsm`nmSTDwj5}EXrZ<nCJZ$4#)Jvu
zHJNQ}-i<tXL}AOZ5B=XLvk6MrrSCH`+JuRlw@EKnlEQt`jfJLgpKxNODcnI)3KMrX
zlWC-;Hu=zFiacLzL*q-UUH;^RoQ07aeJZyY9Oubh?$oTExyzlJvfwbCJYxEgPI}J6
zRUaK-@#OntcCEo;HgYJQzt5RvtfG@1@X!Z&(gPm)AkUn~c)iaAoSes^&%Y9vv4|Gy
zgN%TbFyTuxvEv<>?32!~bcg%oes^%L&*Kh@FW;wJ;-Q&7=@JjXbCU_`h7!L)rzuRl
zG2G8rf;P^4Ne%bOo$Vm9H?gr5`Tkh2{{#L0SkMh^t-+QG6Q3ZRZPE1mj9-lVDmWk6
z&<N1kex;G4w>^gXOK*FSrPuQd5Ej1cbhky#?~CsC;1Pab*zo43<besDA^x|xlg&(a
zD{i5!_Tna%iJ$sHtW22jGA?dnMd0s?ezyqxeZlh{+G{T*799LyFM8TTaNkN#dkF1Y
zoasZE?vQ6POc<k&Q*w&&C%soG^Y%sWl`Qza=)86pLbN#X#D(vR6Hki0eR1dcO6<p-
zXXZOh%SQ4)Hh~+@E}VSPf$egj7yZ|Mzt4+KY}faBr4!rrbzXF0J0|T-8Mw8yBQ3|5
z{DV7R8WG_;Jnk^@=A4wrcYa{mxQtI}vwNJli`!k1;g1Quo40qy-f8c=()aE1suy>_
zed>)f_U}5{i!O54cYV=C?i0m^)QVXD7Tx0%kUi@t7)@bf103(5(v<Z@A6nG-zBwtW
zUz;{`d7y~iDwF0$nn*!uyRf%i8<NdUvWW8?)TBrXiSgZ>PF)}7oztl+X-D7Ox%R3W
zxpNiOy>D(@rOJC#NA}9KYGd;%wtL_7ZAEwQn;Tm3-TS7y+wXUI)8Q54z3-7lHh`HU
z$$0OZAaYXPV>`L&6^rxUH$7u&^!CjKK|;NKb45r{B-_OOY|~P*v8QeN!f$R?Nqp~{
z?sHQnp1xO>^9S^UMN#jYesIGK-k6#a%<X&g1J-mbwz(}8N4;-uOJ6BImAsRuXWPzR
zq6yC0be)@ayqli0$nJg9b8d3OnS|`vP>!Xc>DvroF-)kOd1#xa_@=j=Nk|{qa3}VR
z)3C`)-<*b0+3i-c2tlZB+{?Bk(;NdjCO{4Br!Zk;jgEGcl2<o4+O6Np*g4H#qoXY@
zeK$JVt!p(lI@*mNXG=%B$=5eJ+D)f*Mn}6f&1j>e-Lw-oE)Gr3zHxPZ1ymf((l+iv
zg8SmmVqtN24<x~Lad(2d1r6>l0TMj8LxQ`zdvFpQ{v~<ed*6HS_s^Uirk}3v>aMC8
z&Z%ck_n{|t15tfjvZ$~1ULB@G_lmk!+j7HIVUiulW1**JGDNR?5pt(^+*Vl3;_3tP
zn3io7=3IF1LH)}c)G@B;X*XF*H(j1y<lVU3O%add)qEBy`?8IW+{QKJW!v(^VtL$;
zV=24l1LoyD8+B=RPgR#R+siu6lY{u8J=w$>yUY4-b0<>1+K~^o3R>EV<iwlRs);)D
z4WDIx)f2nTZXCF6{%X<-T0W1JwSGWfd6#n9bv`9K(7wEvK3k~VGR})%(N5grbavZ(
zHnpFKmvZc`tA!o;*tqvlvDC3Zp+Sp1b5Y=#McJvGHU?%9O&WYL_psbxfuGt=3_40J
zP6>_3uD(YO#n-cAG$dmWA70J$X}rD{Ox1P(9zA9{wK5{Jn|VwVtuLw0MjOreCL``f
zYk71mCnjqS22Ku_EB<s6ABNop9}1@g@kWqnx|57>(y^cOo9h{FY(V9y&(Wf>bAB5*
zQHo5jy+00WD4S}JVew=R?RMv&F?wXr?FOlHwLW-^hGic6u+U4zOXQy@0rdoKk1sbO
z9AR9FiS=va?LE#YC*72RdOEl2l$MiRmr<r4SXVQN_l@Xx_C7#1cqH?jck9@X!RN(L
z^3@?UYA!y}<x<ORbJIN0-i|<?@ET2L7UUVJrv!C2lCnln`Ytz;<2khPUv&q!1%UZ=
zxRf&&*E#k-MTyNe(-+$2?y@}I(_gls>V9}VamTta7$bJ2&C!`Zc9*1dN)J~@gCl_A
ze?-|~PrWFhz>8T?unsHfoI)G``Ix)N=oFjQxv>m7O7LB&wSA-Q#QEz63VM_|avC={
zNrog;5L{si^66oJ19`CR!&`hZ$@yvb7kVq{fK2QZm~J{6KCLfn8L!{Vymh4EL8wiW
z?_?k5I(<Fi4@6nu=N7;oxqH2rE>Hd5Z`9?y)(Pre!g<^-tpy#6@!GH}<`3zXU#uPv
zeI*}DR>uV-y4!0ycaIkfDFoOKb*S$@Ub5mN`T|n69b!)rH*}X26N{TqsMj%=VS77D
zS>nd{=^}CiwSN|ApN+hUQ5dIO#<1^Ly7F$WS!c~$_fMRl!4eQzb^Q1PaZkIq%k8{o
zsR`*P>=H9#u8&{pwo=*=6vkjC^hqE&oEhUj+cyJ8usxb!xoX{=*7%Zt8Y58|vk2@E
zvs>R*R2uxuB3qK~G<Rg7YNI+5U9+PW#_3m`p}UV>ELY`1lxM9MDz>o|+i_52Yu2Qw
zdUp18OW_Bk@~(07ONU`F*_4z>y3`fW^*yco<*+dlPR;0-IbDTBeaNgrk5Hb2-+IXb
zc8$({h#5?7vTJCu_0i#9M^o%1U6hCFyT}w<!X#ZP=svvPW!!aMSJT-u8jl}RpOM5Q
zmYI8Oknn}9;HDE<1+AJ)oP@yEr1PO2Hi#A9-`a0{JMNxTbkC8~g-zFnuFAK=(+%q`
z8=8Do@`yagt<l*>y1H41u^m<$C3)Z^EVIw-v&;{28IFy*X=&-~T0H7jCg#um`H1P-
z+t9Shi>k#W-Ws3#$6@m@VVPMGYn}-EHyn{4(1X;Q8{A-VSV3KpuxPCK^}bv(^-X;b
zu#i;bu&sgo!Nxg;efd(Y4)ykc%@{v%tg|E586x+RtqxG@38xm1OF@HuH=2eU#2WX&
zK1_d+MGBsu-jA-DYC(({RNR-8K5v)^T99_lDUpUfvLgugpJ8g<^Sg|X-~x%PIXaw3
zFV$MsPS&_qZA-z*cq;t()swC<Z8c<Bb^t1R)p!LvpDM&z{i!-p*T{YZN`3Ilr_x|0
z+_zuH=z`bL{Y;cX9?khteymGnqsUcxgk=g7amDIh-a}iDN{*73sH_|9Vi=D(#a&2u
z<E#uI`6#deH{wS!tL=DSvVaCyzpjA8(QV_?;Ya4!P2S#&W~lF1H*4I(TC=Y@QXxg&
zu9VJ?OE<nmuDYE$fUZultM-H};TK~Eg$%3prq{0t3g*t#c+8J$pel#a*!SWKj#&OK
z&F4>fY63+BYabh_y`(4lx&rJhd*3YuE`#F4cG4|LVbM77YwSce8JW#}l#;;fc<`UA
z!A8?&6PX-LBNqFOd;v;3aSx=e!moSU-JFA^U&5NfvSzKxtfWNX@rV##EPs{r<KCf$
zkIo6qq)g`>V|FJ61U5GKj6x9()i0sjcX~}8^~I;L*(X#Y{3v2oi1t?d$$6KvU95a5
zx`Lcyz}mLf;XdP}(1P|@4+AfCpxhV$gK$}_LjeW*8Mx|}yO+|VL&vvkKYmJ(rlxXx
z?`46tC$o8E^n^je+O!8*7cG|6brouUQ1Y1AJ?Z8;ZV{?HS$@b(M0Wt6Rxm}sjq6N0
z{N?F5G&G04BPKv~=j8<{h0#s~I;`=Cm(30Bn3xm&O|(FhpyUcp`E{I|ANCq}zJ=EG
zt9+fC-`aNU5h>Nv_Y_g>0h$SZd!i%hf~#<&7F(-Q)ghiwmmw6y<*5QhS#U9A!mWqz
zankzT+kDX8YvsIe<ne(e^z*jx?ds`d{kg&}m2g@l5_h0+n)iG?--g{CRG&R&h5rQk
z64nnY5!grqtLEhL)6o=>kD<6X&Q7VfeYelb1EXQk=<J2L1n<}P(x>fNYzE)`pSI&R
zNOOE4uLRB5_UPdJ04JdSIW7Ws>zfr)gW85#H|fZXB{+K{0VHn>X5J*ppB=n<@D=#3
zEk+ll@{ug=qS<cHZB+>_h@XTFMPt@bl%WwYcbzQ`g}_Pl8#bavPWXu@8hMRV(}E%9
zM>ra6qW#YFhtXTXjX^Gm=7y}g%h2yq<kj8$aCV%qMac}zc!OP}$LhUMSfIKGi(Qcb
zK{wR+PlRiMH`Ii_e(1ldauNim(%9G`TNeb)&xzX*njWVY3qe+s{8<tsq+y`My$-cG
zSZt0&MWEm7Ckt!10PZY+h98mykpTQ|GN?t-_cVB?-J}OJ8dE}GIo=7~j8-uY<$jP>
zO6x!I!fX|QOoU#K)pGr}b^?GqDQYWaY)f>wqH=|%Lbv}oA08Kp5@%|ta*EM}qG%{)
z?K#8N=>@$vcNF1HH6*<k*PJ>3#>LvFcm~T}DJB>kvJ5Qsi}CvACLPz>rFxzIBRU7s
zzSRrG18RDZqVQJ%!yVP0VHP>kd#KStI)B8<79E%t@PsTv>nQ<Vc_*_%QIcBBRYHE1
zxOOP~i5tDCz2BgV0s+Xr(W}o&!yQ@bg*B@HBS)jx>Aj&}-*z4u`e}m~+khE$)ZjOM
z5{)Ku@*d)<mb)=2igu`IQ?Fm`1<2@Q{kldiV3#_p{1lrBO23!{3|5#D>uqs)sDv-k
zG|8@&t1<rKSp*kV2J79@(~?XANhF43FUjPi*?5D%!}Jc!YwgkDs@!j!+)Z+_F-A;O
z8ol;-06K*DvvwWx4zC{&#P9`DedgOqC539E-q{~?VO@;7%wB4S(jEtRZLn8Wooe+z
z5U+DK5qQHgGbhuZ_+`5@2YGjNIx<|Kt5jwbv_k`DX@>YQ_cv5_yeDeyamz-dwm+4U
z5)T?YyojyvLPDD3`FYhjkMb)KV|WIje*=gx02p6`!&UjPeQ@2Rzmqh>xgmDNwW7XU
zN|7LqT^nJb=H6i6T8oe3sZ2a$mB3si#m9B<TiQ0Fj9zo)y~4H#qnlEEkngP}Mwx#T
zvW}rr({j<>wjVF2=VoxR7dK0a#OE}Q6tg`ASqh<RskLH}`v)Pvm)qDE9h@%c>cn_a
zo;b_x4Gc1Iz5v}mGU{TTAD#X-jc&J>bB)c{L7O#IS3Yh#P_R0+omen1#gT=E;CHS^
z-~7eioB54Exvu9SMF)Y}h^j4M3$2p{e%iba2t+xePewnMu}ze}c7=jDXAQ#8%p}q1
ziZ4o1H&jG?bY>>;AX#*7I{tMgRT#yOhV_$mU=1pC;2Qx+j!Gj^AS@c=Nm_S*wnvNA
z%Ru3uRT9W6=CjlYP6ITN{E^s79>lN&8|;P!{+wi}W#3n-Cf&%BXatN*Nu9<K5DC;+
zOO~L!66BfO{8(L>v9~Y6(h4pR8&p}l)}YLZle{RPe|St<BfcF-?}C$3DQwvXN8#A6
zTvml7MSv!$2sFhm5bw;1e1Fgr%a41Ax&WkGS$HZf(t8QR<c0BE>2zl5&fHq^6w#a3
znTsrT76UNGcz(WU9xOU}g^sLK+C(*qr6bYppO0V{w?@9kM>;9NyC~Q7gp@YPP($`U
z+lVyUm^X9A;t)M49^`!xKenZq?sl5mVsQ~&lTHWu0(rq5mmCpYUo6&*fIC@{39cu*
zMR%7>ffj$!zDIM4!HHunqww21GCDn0-j#JsVj<dESTnnoS{LaeCA)<t@xgTsHbJrD
zP9W?lfg_tkHHK7t#1p8)oG;1ie2tS-96l`}gVt_gC~(}F`7>cLtKuMBw4&}oQ?FwN
z<W)k}Th;3b<j@JK>S;W#T4U$S+l)b091+Zdb4Nsy(R-EIDa?mgN3dernr#=_%y6`_
z&MEhqaF;PL3$!Pvx9!f~X32`M=C?AXKInefgG9pP;f4hhdXXb}-r75L&d80ZEj0lh
zL&0AX3>8G%ZrlMqEQF75e;xgj92#A#bjfopGukANMDOdK4{WI#>vzb1vVNvaKV#{J
z9<NZaPgcz~Vo13BwXIR0M(_p2;zgBx-d1}J1y9`>qcn66UBwbCb#A}p12JTx^5vq~
z#))8meZfxC^8xQpxYT|ow@1zf1wB~~p6y^OOlh`Gq4Nc2td_SQVa?)PbT(SCgUFIS
zPB=S-Aj^~~#m2O7|AaxeqEQkK^w>(&4%Cb#KTk2Tr<D+m@lS;Hg;%u4`vH)|7D$S=
zI*)K>9uLe@G76<PTtTLc6Hjpq2--><M;L{B(a$i%9~iV1x1Fhy<0yNfR2df?tQ&+d
z#hx2s?^HO=pDVZhZJK6ieuHQzqo$<vvg4&UV^NbmnySLX$mnhrgm)H+pu{$<PDOFM
zj+ZEm!|(XQqCMRak@)$T*$+impi7etdQfWrjVQiBo?!2UgPJwXASKWwfPbG7ONotH
z7%yQYfwkucEl;Xmk)FvKonBGt_i&li17L^7YsB4LDqN+r@Xt=<gMmiTfc6K@6$*S^
z`wf<huIt=z&^U#Wt10DPDTg=noJ~@$>z1k7R;Mh2nmwY~mmj+7YHL?<`~*pmJ8*T6
z*7{b`2=;EcyN^OjLje=+EgCjz7=8{sC+|QsNy50eH7Md89LL8G@8H5dHuD5x2W%@1
ztZ`!KmW=hL7&GCLVJK85qSRByTNieH=~Jkiz%I%dGGM}OB7`7fAaL9lYQFU<2|Co)
z3h;izheWV6Bi0)7`NzgX_U-7&bM4cD?Th5b!}(%Pt7DIA_cunAm`a%8kzSp23Y=)x
zic0UCCRMiTCj0O+rt>-sMR@#g-n|N$v5gXE#iN~H2|tC$4z#E2S=Xp0ib-N=12*2L
zZn@K4iz2wMAde2~{CJv2k$QO-6mEdwWCVweMM2BAE-}?tC1PT0YTaLzb7KITs=U%*
zWL|8mlm8%IADn(SogfI<w(rvBevM8iU<tczPg~r_x@k|j9sJRO=Oa#c4_`(qs9S<B
z!+s~KpnEjk4~~Skbrt#eV|WNpyeCdlxZ?`mYA!XIpkZl~?621muqo0zieCu#@>?Py
z;Ev+k;uz}{6&H`bopX8-0luVCtLo(U#IznV;V0oX8Lz3{8)chO(u~X@FC-!fg;@J=
zJLm5A+?yTCwi8uv2Pb~k2~}it!G@!9YQQ(ZPbCPysNv@Z5=}?pH}Bm=HwednIF0NR
z!6rOQ0HcIQy=OkN?-TOs!dd40!YqP0R4e00WSsYMB<X2{X>EoKn_O~bM1neFERMqh
zK{+-sa;gg%u+2Wn2wnRPtqcx^S8=E-wKI#Ba2=Vx&l;K`-7jKj%ixlThS}XOJ<_oQ
zJ1ikp2enkzTY=tma$AS`MPC8Dfaond7J^xxnV}ylY|yZE=~?6J7xK{}c6-rDA6LdQ
zMM=QF$Rq_!0Rg=nuSbs2UTF1puMx#DG-Op)Ze$5gP{KHlEpm)W^Ae~ecqqVqM;2wk
z_C3>}W!)SzVAVGBM7aIb5j3CAeuICTFNmBXM!T~Cmu6+aIuhhbUQ@(J*EFfID`uA#
z0(bypyE%xl4}4y!(q})~vIDTK^yp+jwJ8pLn|Di4IoX-B@|NjX?vcsp*iww^#Ac?X
zqHqx7=}<V6d)n_^75dqGb3*>q8<U27XbB%&LFGo=HuQA8>U;m-WcyaA{%QN^N$0WR
z@zQG``|0t!&lJGb+twwig1dg2-1qk40{HZ3H?W$ZY~p)+x7&U{o&DGp{h<DI?fZDA
z|1>N7(7dbvw9oq`ExYPr$@#7R_LBGK(WfKwr?b_^YyIrQk!8rH;K!rNg&nV>N}hJf
zap9;4s@;4mJ6Y(_S6^LMJa+rutwJ^%e@cDvYN_mmTlkgF%u=<@Wla8!HjB-gRB0g#
zM!#=SF2&`gxA@aV`xD4=j|Y}-M8wt3#rtt?o3rjGXmNi1S7|2c4G}~xl=a}Lhw0Sr
z(PO0jR`}@@Ls%*PCmzpgK-0)4pU0HV3)S*fTh6ZLxvlZG7Ti_PjZ^pS=95r+8^eYV
z6Ax$h$37%eqDM_C2a@RrciUZf9<T6KA4^}(%Q2t&s`gbCX29-8lNQx!%>|476aAE`
z&5A<;g~taIWT_TbD!#KL6Po2?Pt9C%2;@$iR}3JX&Gtm1$Zqz%qquBeqfn7On-;7B
zwx5vmh*h9|Bf5PQGv91sP0$*-!tV<9)cpj`JpsbmyJrW-4rO~0m^EMXW8_2jf`whY
zQ^)wa{!|`{j`4Q3QD?>u*zNzbRYB}%RS%(Vy;b3|+YU&)|9H+&c^{8K(I?$r!#JJo
zi?F+NYqfiOO_ka0dZ$M_9byM$3Wp>sQTn@9bxo0SCQXXMn(TlzT?<5{Roe69E__0>
zQ@SjIJLiivYtlD2bOtKat(o}}kdK(tA6)u>JWY)T7CQo=Y_=EW7d&(^n}Dm2_n**~
zs>+YDk5-mH3hgb}wI2#U2Do{{s;L#%iPW9&)v?smTyap9-XEESsWl`s*sm`R7Cq$E
zS@;%kpSJTpg6i*;1^vC9LB6}l_wY<YPK>J~;nL?ey9cJb_L|ETD-XveVGHfa43SUG
zgDEg_$;%lkt9o_VLu=RuH+0z|1&KGA(>p+WKRikV+g%*7Q=8omtJdW3z1t&`c4zll
z^7HrjI7cTY1Co#t^d*+i<t(KNU%`#+_d*Ecc5`xj5Oej^35i$^d<AMn;ll-Kv$$uC
zkhfR4e)jOzQ?IgCVd<mI!QiD0-Qgn#7yYBel~VTY2fAzTr^j!j%*Ii?Jhp23MRuNj
zQ>`cR75j7^9;#Y*&pRKtmh*h_X|I^Qv{9z9y=%Hm^T{igM(~&so|ycJEtohoXmbqd
zRT*)rLSKF09Qz^ix?Olm`7YH*74u+v!Rody8~bH(g}i=I_MSyf??bj;u+R79bQy~a
z+aIsIpLQM(<j*4{@5p`b502f-+Pxpi&w9QYp_tejJ2^X=7}`AF*%?`)yaKQRp8o;>
z01!Jj2=q73`4=uA@LUCyeD5r+=4|L}0{8<wV}@*y0sts33Sb8S!G@5lkkGU6pDR$x
z&er)K(xxnIENlR7NVlqg2|?uk8U)9`lmUQm-0e*OKovtX695f>{kL)zLq`)xU+jOk
z1uB{tTNsMjy$5JRAU41&US0q@2OAqe_qVt>L@`9(3BdKQ2GWjpF82Qz%pWDc(dQ<R
z1E>a3?PzH0WdE!T?EW__3vhOHG5NbB4v~^DakT)Os7i}HgMZCc)x^op#Sv`c1bDWa
zD$2j727;8I?fYyg1ru8{XLA70zlJ4cVeM?<2mnf1Lo6#{0=6^$t?4g8b^wTrm;1S|
zzg+e{<4D8vJ&t5u#ev$i;Ig3Lq+lvCbt*M>90hVkP!JS!0+vKp1OOU)sZ!KPA^{cY
z98*(I9^e;ZHg-xx0|=;Quf`-hJUD+T{>}|~We^u1SH+pCS`P<Ao9O8Q!`gi1^whfg
z(6;#Mt!_m*U&U>vnm9d$1XTo5Y)3%}cCqjE{fscS(H9B{B4LYPpP}5Dg_2`GNr`=;
zPkr2*A`~=LrsxT^slFPg+e!2~)=Q81sgBGJRQ548s#+)Y3W?p@t*Y2H{=rtqR5<5D
zzQ_<?Jd$>2T*ywa2&&Y*@2Qo=M&=!liFN%&6kn{A!JnBpz*+f#R|h+p?Pcttzg?kW
zbHz^K#qm)l{F4Dq3rfjb8SB1&AHX@rR42Y%q%nz|`46R`knbVihv=F5QD`+~X(G8s
zgBo_2^28jxpN8Wd`Em<V^b+vo<Q-ldLd{dM%cZ!lD{M^;eWKP^t-_ggl+@A+W{y`z
zGTgl3O;DlVB8D=g4Zbl74tgt{_X9Cb#-+ya{a1eA6Q&aSPgZk*l}HI=F4N`8egYxd
z_8i#d69iB^iYJYx09}gBI(h&)HgHUOrLa4#>{n%~xMe6;=A!tI2caG#ax88e#D3NA
z@3FszthG66)a!sZ-8E*x9qx--z$&8xrYr>{ni`F7jITDq-5)^KNrb8?%-rvo-Xb5}
zzkwAVSK#fmF6u7JzX(zHydV?P8lI{5z+cK+tlgKIPwlP9MPt=(8#niH9meS$wo0M{
zQDPq2re#Wc>BUXuf-RL`xIK0*_fnQb-w6ezB-tn5vnp~)a)njUk)#Vee(BZsyjq@>
zYES7MJ;FL%vUNBbZ2w>f>)&*oidbjO8#{q@lhEf_(4L`B$7dlOC;r-TPP}X6Yu5D9
z+jf5F`?iK(eLr7lXLAeAa#$eta|q6Bk_{%P)`XeFZK1m|d|9Y=VS22yeef^c*ufAE
zOMkPSFVV^q*qCJsJ`k<xHY%dW9sH(n%bY2lT{OB--6kIiM%Bb}n0%Y-|3O@pWn+d}
zm#XKeda1`oLn&|$n4G(xHaX#9<Cj}TJAUJM{Y75bvI(uYXh4L-c4tO$@g)~d6&0n?
zGF};rU9)Y(-L*rRZuv0gLP(<3cAovX5Kg>rVM?_2&AUwBX;#!1bk4f8OB7`W5>`iO
zlQP_nk+};G3o_sqKE3oj77!lc;follSfosTm*itxY45mxg%zcX13k0POf#8ss^%YX
z44|`)Wz+(-K4fhuyy9!*YlM9Vj1zY%P)O?cv=aQ8HL@aA&NQ28u`DjeMI8+25fh*e
zO^5~i@yQTdqq)3r3H>a<krtiwy^EgvLri=x<0c74DTXEZXVnOdy1!?_TQT{9{snM(
z?~>$<SFg^jjvJw73F~As?_eZ{dg>j#OMct9=6<QO`u^LI*7DY4%R|A#ylG28RT-4V
z2-hNBbE5}_;dd5wwLV)RW;4R<lt6yjOF=0*6|QQxta1|7v|cH0J3l&^t)<IvPJ9?H
zC6oTScMUX595sFnzalspUsqCxAK;BlF~80KB|nQ3nx};x$|0ggV1j<m&$?VHi$3qJ
zoq6068ls-=YAA`rw3@5In>QE2J#2ajNy%Sf%RThgeOcUn^}SYOXOhp-t?GC|<5x~x
zMWT7l{-kvshrDMJ%ebDw;ykTMW}Vccq`qOhDSslVmd1ru2aozIK|HUe;_nChV;>Qx
zl{`B3#GP{SPjWBcIQ>)r(=YWRmULgnz83jD4pRa}CgF{n)Aqdt{+1q`#-7Z|#Xb3A
zKu@di4e<#fe$+cESeG2Re#UR)1KGF{z57`g8<jj>S#1<q0?LyXd`y;&bLZS&aK#G@
zRclj32VWz8QT!AL#Ei$`VBU%=j521=r|8MXbW3@WoDR$nvgI;0QPuu@(@ul_Qp|-X
z4A#W_=YcNf2TDsy_7Vmf#v&rs;<ClJUooxkW$WUMf4K~PZA!8VV^rLIZ>GH)itKM_
zEmS3A+Q)Q=Qsu01T>3VKF)ea%WtTlY24uQkjzrN*JThlq=lf>r7kxP1ge}hcU?{5D
zowa?0En@e}P}lkM^IUOnbYR56PUr(!+3|1^(Yx9T<CnWwLkpoPi7|JQSipVa^FX-{
z$?a`ctFKZq9#)wl2d4*AG>DC(W`XLqi!1M!VnAACT#*lxUUoP37xYYv=TeJ+4~bhO
z_;C{-kITGwQll!SXVASKO6pg0PsY0^%9Fwu>)SPHhMy?zE&B@&D;J9l5hf}zEl%Tj
zI0O^Kyxy?5d|qo)rx)HTkX|4^pW;)$+w_X--UW2i#CXOE!xZ#>yyIqTwbtu)rh+-n
zy?i{I-0VI(>D7<feUSBC&_6giB=2peCyYk>8o?c<kUv>q(PrUbxsH~Q24sMFZ1s|H
z>Il(yMwOFDK+&Gl+59Zbvpv-vzv8R2gjsCvaZ&uHB+<3}lfYISZKUtTn;5b?K9}6q
z5~=(>k+bnL#k(t;8uzq$kMQjFZhY&@*eIJe!1v4->_U^j;D_CA1GKflsYDc1460%W
z@Z)0ZUGQ>}hwuxbBe+aGvJPU*#TVB|ubIljMj>0xh=DCgNL6XbUM}{yo?(8;!vHT3
zj-MGO*d_ju)VeQlqenpJT|UVD)i!;+(4ffPvq`wL!oY8I5+VJey4qIa{@i4$!u?!p
z$3HJf5_ug?gjX^nAD9OwI?LSqs?uK~R10c2KW}mYE;epA3RR2>i)(3*4*9l@=8CII
zE$?Q}8YYp^XVFK0IAJHv)Mz0t$u-tGq~QtnP^QTay(LuYFN~2@u>Ta77bUBpK#;SK
z96ls1XF+(8bUUy>UOks<@Z~EXi|8cwCeFD?Mt31k3n@b3yjfoE8HXi#wl*d1svc*1
z>rP{oZg~afNP>*!SZ+vxsun@o!R&q0>imnSyoi-=^Xf-sKd0~benKJVxXDgVTq?aL
zTtU+>-m49&?YR{3P?fVRc~_duC;uWQYAlZ0sv2F1tpnbcjRL`l0{xy@PjOi0B>OSq
zGI&2?VzwZ3vZA<N8YxZG+s15)I8z4u(<l?&DxsJ08uG~gIJPqDXQD<=FU|RG;#=}n
z_Y2|g<eqt3TRk*o<nzP}clW)%^z);)C-U-xgQzbQ9bG(ftq1+Lwm?pfC{h^YxX#7a
zI@L$hLEKNT1G!V8=S&PU@Q-4dGf$(+rx`VWI9z{SnNmI$<*HhS3J|IieM%CQ^5PXr
zy%aHe!yAB#Bem?%w5U*1WV>3mdQygsKmJ%A7ICk0p*B03)rwx0=F7?&hG9;ZW;AI}
z1YTnJsBv+qlGeS!q0X$iW57N_9pS{?(Mbb!ZuNF2p&z~A!+sq_-qQ`;Rrj$yKiaZl
z6s$E%`Gs79Y$=tN+@?jeo~rUnH@ikt42E-LB3YuTywkO+1w7ErI+mMXDA|kSlTP9$
zKx&=HT+UNwGjm%>PI)H&D#0m1VONlV0?jf4GXp~$D}9Lk?at}`$lJ;f!gR?@+aq#w
zjCOC)JM0p$?Zs}~u0<MA^efBm<!@-cMxSWi7&82uq&|*QC(^!Vy18tg;2zN00KD^>
zjeB4fo>iqCwjiAFlJ%%4^h_^TQDP?CE{MB~m0szi%-VT{Sd79)T=Z48M<^8wvRdn5
zp9ghhR72b(TboG}S83s`F24wAb#Y;G>&~LaP<K2+LAPkNY#!2v@b_hk?kx(T5BO*M
z_k77EU)Hzkt*lH=R*7te=%qYLW68n^j2-B+hzu~Hz);Y-$WAB`Zx5!z^j+DC2V2-$
zw0d*8!h&8ZEyfYu<|cojKXrsHJ$2RSQ_8<pTKp(Rm+4F?E(7fzIYhw}{!)=YKDw6k
zvVdy;VdO5#p*BcJGCRa%s?r;z7+~#e)n7L|1g$CaW-H8TSE*iMt#e0SWi_K!JIG?Z
zDvY@vure(1Ls8srBI-J?R`pdC7bfm6LPM9<9~g);bQOu}cdiA}clk)~!S|%FMdU5v
zr5U!_q3x^mQ+1g2(819ShE%99o7;VFDdVi&#KkQgx_WxT{WqwkP^gO29=a3rSWcT=
z>ieob#;<pVK3chjU45HIE-u<?<@`CU7V3J;U+J(Iz1!Pzvo$mcpZ$8*2~$C!Z71I@
zpcA}Y!#Lpk)nPVcpL4g^d5Ik9zG^46l{*{vQ@&weake#T;rE{JqMpJCA=HkgL-=1_
zNX<1TeXNvFP|Qnf&qQ`?8O{NYnx5w_>WFE#%wErEWBC#_?k<}{7I@jzAGd5L>{KKg
zAR7FB<}fh%!$OGP);+QdDZ;RdIr`4*<NUc=73ZeuO>*o+3Qd*#M$)xg{IUaHDKJbb
zZ8H9{DgCjA04H^fWB+Ie>wS2C)^$y?ysv}n@#Kpe^%A!+arTYxS%RKBV_&_CY>D`a
zjXF9wmut!&A9wkSdn4K<?zMOi8YwrxYBE0bG;*|3CGkP|+m*r|#e}X&E*gjWq|UA?
z5A4XVePrY!QS)x7?2@U3VDjtR%h<QRP`T9Vm4<q}>pe7Xv6!Kj3EsQ1<rk!GebGkK
z;O$}^fge|$S6GU>SYOehFpZTi-QqN}T)%UsOpiY+jLWh?L@K!{WgXHMs_${u_Yq&8
zk9oLEai6{oOJ7)nzU^_)Y-6ww9=+8CuHOH%Slc_vYdKm%V*~m*vPQYYZe-o=tgpyr
zYHr4LZbi=LcdGZcxOR!}zdF->Gg(j?`?bI=UT^biqT2r+oi?B@URIP293gB}-cPDJ
zb|kT!<%bgY?#q0m({P$D|F;nuE7`+r;D@gfvqzX9yA>QzS;%MICgX=&8u?i{I>uyR
z#ga}_i=$4C={WI8`_uQlG?CEw?cEAJL4BV%rHrq}{merJFV_9$o(6c3<E1wEp)2-8
zbc`u13c-64e94b-<?%{#_%Nifss2L#>hXNFbqi0)v25Occ<a{z+MBO=vhFsom4$Jx
z8bp}(@tR(!UBBZC-zU9Aj~;y5knf1g50=CxmnuX9^N1}xMYIYC&wSRl+w3L7<$WmW
z#bwBR8pC&y)}^v#{wcHU?-u*y``9b)B*W5K6R~28F)!w3SO(W@W}vK5N-@}{Hs=&M
zLoww1txb1}k2iudIi7E>8;Mk^x+*#LLWdG$PBtH7wWSIi{-(`sNHy>C3#!Z{yT)T8
zV%YfS=dj^|`O}x=y>5mh!Ps$#-fom7h4}pnjs$If);t5pCajKF2Zk7p0nKbW?a>MG
zj2z?^XA>62xm@}lP@YO>9;)FMMA5VPiCK~d=#zz8B<^G>TtU|PyRj8~=cJk_?h|5g
zq1GjE`@+Fi)0<a`#<W!TB-3HBd|-0b7*9bGhRs|iVSL%yvxH$f_X0Vot8(g1*18_o
zad7QxJ>{+~=6e#;j!<VpdDG^3Ow|=yXnM-+2G_!eC>^m~iWAo~y9(A}LrG_hn*dw}
zjLii)>uCGYhY8re*T}pd+@q~2mA&^l=*8uZ#^0+}pn(am1<P}oMaq#=5qOPJW_IGe
z3qqWOQB<RuB(D=a&rVJUS$<$|HD(Agc}pLx>%}R_&Am!^MW(O_OZLWiL?o|3zT<OJ
zfOtfic>V?K2@bW((Yf-lUkO}k|0heZUQXRtmp4KlUji(TD?)Pe)8ONUZ%R6qn_LNn
z7==}qIrdhx%g`B{@bA8Ffv0T^LBBAXKpduaTEl_Y#9D7iQ@D65Cv;Mm%nEO0vdgIh
z{2-t6C?ey311>$Z(S%2by~q|6KHoXI8pcSIZa|qr?GZY&(U*`jDGihEzyt}K6CE)&
zOg~-GA+Xd+G)a7L=RXgx{ooaLVv~{#&aBMeVjc3HFPxzzkV1FDnC~U(M{|czX{}pq
zhYCe!7_u+)l9g-Z9JK~$>^AFvX=$^m8?g4a9L(rl8D&M^fT__eYRBIYjVBT2QA-~U
zgjt+(Qp0G<!B(pV-FU*)dJXlZV~+-5ACA00O3aU~SP5!iPcM4N_6%w!=%dQ)H<pk_
zGw4ID<4RHf@Euf^h!?Eoi#fIx+z!8f$K0R^z1p~@4Gn_3SI2B~=+tLg^T2G=bH{kn
z>iCLsT?#{#z6Ml0E%XE4c1%N`Hu{ZLuMKRo-^;=4d=F3V?I={{ye_1@=7JT%I<4}H
z&^$E*dcA?hhx6L=f6{^4jp^`3x`rzDt%MqRg|@ScC(>=eb63pc^R6R%V=V?|1^+b5
zPZ;S_g&(I2@_nRV6Wn_csuC(s<Io1(gFPitG%646+7-+S-f5EGD)M`^4m)@fTziQQ
zLsaxcgc}OzuZS_HTF{6XIOl=VYipFQYamgd9JVPGM6n+r(K+B+6v`*8(<VPl=ytry
z3IaW+&N9!y`)Q-O=HBir1j86aJ<&XUi-2VqJ-kZ!4ke5?$a80L5hr~C$vUS->_HB4
z4KQ`6b9K}G^~iGvK`iOu>m;K&9gFi}b`^^*R3ZVOfm(1U2>BD60hLc}6%6-hx3d=(
zl`HUvX$D7WR9;{FUTp_^4P$B4ge3~&Z*2#wkQt4_uWLe=sk>~J!GAtLVEQ<mcqKBA
zl9}vo7>qtx1$Jjo$SaTwtQ-o^N7iWS*^q~4t}>|dlZ3%TLHhdW*a`C}4~>e~!TF6%
zc(ivHaoqy?0&d8qlZ0+)W{m;5Ce6SUTVNiJGtHpM&jRLAu>)K7w84*I21>{TO@P+m
z9OgX^F%1kEmI|{$oL?xs!Vg$UMYc}lU>LHOY<eQ1ZQoJT0Q!N5`QYn7O*W+tjV1RV
zP<<Dj1eWLQN9)kQNHV-{(x?Q5-48HQk3(Bj@b^POSTG@*efH4ZA!%M3IA~FzYZdGe
z0yd2fZ(O!dFvqxTDhC6I+?{?@_M`Sl$a}!G<7R<-Tj0|4=<vz8NP8Q?3BIL^xIXMH
zQXlSEb8_;PZGfJj;>sYZpp)~;WDp6d2en8YwC1u)7EMkwdMY8`C>KCH)K>TH%5YFQ
zqjP`2NM=Bb6T7qA)v1!G%$10iWo+>>Y>DU|!IZl+2+l<YE0#GYkT@<DvO_xD2Z}1>
zm$AV?Mq!|in3tERVO9Zi(3pWy1kgtjxukNXnSSQ?^n3_jFfA~7aPRE{r2T?hv|u}Q
zppK2~k=ZiFmoV3Q=10uO;LT}2!I1C_Q;3`e=%Aq?5^DKjRN}+swf7g6izotM%vo6U
zelZ{2`>s<wEyCRo(ml3AC&Z-j{BK_SIm!B0Ui%dn8^_<7X5Rlz$Fe`Ckbmc-f&W)N
z_Mhoj-MB&9KsHRttH%$TMG;}4u(C8kZwiU=yg${FL;Z@S#03*pubuF3hO3sKrgUGg
zlzj}{S`q-+>QK02)L1wK8#;5Zap(t%?wxV)C2ku?*Q~T{EGlHGBd0FfXgXLfv6Ynu
zYz3kxzp}3MtaggQK!J*@H(-xEhH0*FV*2vy-~mHv@14wB-N0}D8+v?C3yMgxTqnfx
zyPHi%{lAK@mjuMf+BpgPhw$)M3DGi}b4n*_Lo5j_gGV0u2QiHH5igeE-)<)rSjb7f
z<%>`VzNPox@}YPL;Kfzaq{`qVC#O=Q5JJulix4+voEk06=9J(0$SJ=bcf%%8B<4My
z{JKK2f>-TQa_TDYBo%_UO0|TTB@uFs=FmtxMJIU;-)Oa@wQB7Ycj3QpW@wXJx$&0X
zA%gir_ekIXZ2368{;+yhW2Wxq1D!!#gz>*V`|XLpoW{xd>TjR1KPUeG&Y}Ow+&^;*
z5++VyM+<vrJICil{BOEJ$<PME9VjYjz15Utk}$C}eCMJDN$LNqUdqtM!rC1`|ECJ@
zT*vUI(%R4rlDp^lm!#Mqc7cVRje`xq!o|%2U<dJXLRbb)j=xw2S!Y9Q3$UoInY9Uk
z?RPs-C-5^(!OOw(yZAi5=Q0ZiWGc@i6gRY&F|jZ+hcFqCZhk{*&L%eR06c%%KNn>F
zE<Dc=5{@PufM*8bpNzsYh4R1F_|u(>k@Ii*<PC(gc(&AURLs!H<Tn}f|FevRqm#3^
zxuN6V22e2ktIW>vhk*G{a|3=m<j)f$X$v7OENsmHKy?dSQClaAzk%PH)h&#j&7B}D
z4JZ5aEdKA4lbh|YdTvf`!2j<Dp^hN6|9211=qu1OllAB1e)ab~i09vWxgp^N;(U&!
z|NG?TeCCTFdf5MN{YQ=i^zS~{09=sCzk<ZX^LU=Qo@e$6f<S)1$tMVjWcSwA;+e?-
zJilxH>A3$5<7bxZPjt##7(d(TnFv$;7meleOnUu;OJe^gPp0B%XY2xout)S@LkmYc
z06Q!DD^|!9>CK&;?fHNZLJoqOIU3rVTY#Nd?HtV*{)D<Xg#B~2u(OqTCiCbe_&C@&
zIM{eNc-YuExH!3(*f{9e*ckq)^xsV2-{hRQAtd(g%znH0_Z0r3=Kjrky>~P*MPUQ5
zbD^;P>i|I9!ubkd3iyLTT*Cu-Nk1O|+rKe(UN*=a{|kG5@ct8nl%AdR-*Vg#i~lFa
z!^s74-hW~okf{D|48;8$p#Lcc;^u<5_dhWnwpaf>77z~`2ojk8CCBrB$nk>y(Vw%U
zA>`?H{LKrhS$LQ{+v@oxp=xIbar(2(|2$x_wx$r@{*H@3OrW8o^Ka{dAg1C(p`npf
HmO}Y|mkAnx

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..3a16edf0b390d7664d6e3f452cbadbd0e8df0ae2
GIT binary patch
literal 76832
zcmV)LK)JsqP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-klby^<WZuU~PN^5V9NpH;OL
zU<_cu3ytp1@WPNG0Yaa}*bCeL-iMhHk*vONv8CtEVCH=oeOM%uELJj^8JS-D=YRi}
zKL0P}eSiJu_x5kw{*~K)ov)w&{nvka{rmr8fBo10drPnX=ktI6%jf_8+xEZx@1Gy+
zum5vP`|E#w{o5<qBmMt>9#`sD-}9@r{j2Qh^?sH7bu^W~U;pX#A0J!%zy9m%Km2_=
zy_4rFU0?kuwVa>o<*Vd&oay!V_xA7q%is3DjW+-OU$%euxB5T*{l9Jh^WRs)c<g2A
zU#Iu7eD&)R;N5(zmJ0`mY5;zzwqHXOQOnEgO7-fWaYQAQf2nk4v}FH9@egHR&-Qg3
ze=Ym+=d!Q;x)03DzYMH3`*G9)@JqFtztXK5fM2TR^G9m{eyNrkTXXTF{HO9y=U0AM
z`}v=c|DJvf4#0YF<vhPqJ);_dU#cCS|K6$r_@!D;KUxFuOSO8iHJbsJ|8NG%XY=Y0
zZ$SF<87QCsrq6$4Z~%T8T;A=!Q4PQ^)%N2@YXH{O@>TAw5%{Ir`T0n+*#BAnADV&B
zxb}3U^YgE>eC>Zd1F!whXCU|f)!MX?6ZmCtpRdt=s|MhgYUTRT8h~G_<^H2J0KZgA
z`71sFUiwq%e>Sl8*E`VbpIHC59r^d&IDNiD)Az!Qzf?J<g*ytr{JfoCwa%Ra@JqE?
zzpfhlJ<ES6?ey8Ku7|b$Pwe-pq#uI=@XO%R!NH*#fM2TZ^+#&}*43{4>%6Az9_4kV
z<M=99Z1yPrq4YodRDD?L|AeyB%Y9rZ|E4c;T+|n*fjxgQzs@%A@?QRJXZk90C6s@e
zD>h_OzousX$CrHmIv-a2Kcn5p8H7Ndl!yP$UY5_t^|R*FNB;e@gdfy^Kj~&YP0G<t
z0coY2_H3W+s3u@p?PzwgiE09t)lUCJMKuA-YH9ZqQPd0M4<_NdzRK^D@Fy?m*v|Ib
z00UW%@Ut+cgYBmtfpxXd$Kh5B<#naccPQU#5m;9{=4IlgKM;QE=jTQJRr-JOZ5ki(
zyATPi2liPH<6|<_6SAzBQ?Wls#X!~-KRVZSYcY^@#k%|E9TkQA!Cd6eet!Hu7k{Fa
z<yP(cGWAr*dWhXmfKx>w>xyTx&)`&1$hzXy>^wJB6tb*X_Up$O1NozG!$$`_OS|f7
zHva5{^7#hexA{QUL&O(<swiY#vF$%Un?lwVKSRHN$O2hcJkB3`Zy<j%8%O=h<=5Hx
zqZ7-OetbOxSq`y|6>=M5AnS_h`tbn`WL>e8xssLE6>7il!2<qZ4u)av`h5=m<Xchu
ze*1E=ydK<G6SrCf*455=kMPp6LWA)vDh0Bx_&HnOKV^aZf&5$gwEDaJ|3p)2`TFtg
z3}ijTu_o?A6tb?^`j2fskafjl|FO*nvaWd6AD^;7{$w^jr^)jBZ2S{v938^$N1pH3
z&yoE1^xOLUx6%90DoWnjeCDs(?UeSj-~Zp}_Vg|M=tJk{1OC}?KD&4vqW|6htKp@+
zoo9ZH6V=uC(R}Tn|2h78g!mTZ<DvyZ2+g@4#7b^O^HPTuyBuby*bL$i+;)-2*~gBn
z0~rd(K%yFvghr0>>+zr##ZRf?JZ{LI9NE(iDN{qk4tLlId%GiU7#V<_zK=3J#*sWd
zW(<8Gqc__PnVvIF^&ez<4v<}vXeLTmxbPrCZs0Y<%JE<?7j>qZIQdcm8KR=)robLE
z5Xp}~mw<~&bpL8U$|;0ZOrZNT0z>)*d(=QaTl)Y`4I6+p<YP=`=e^Vt%UQsX<_Aa;
zf+OeD&gXBNLD5n&gYr3z$=2!ziN!}m>&8mCZBvQO`tc(7L(K-l#n64J_Ct%;kj)@A
z>)PKy*sNc28nUM!2-m#n03Y4{h|;i*N6WOAN6SJq0$Z3L#MZ<eik4}KkCts2_O6*G
z(tL1$48W3NF`Bl8+1nTYZcFY{E*d~_K{c)2?yK&DM8m$ssuuHvXaLy+RW<V+YpSYo
zmZNcBQkAQ&WBF8HSu<3o`S<lxqHQZ_2CT$sZ`l1l5a+#NxfC|rur!K<FN7r<ZT1b&
zAzKNVl2@6cZ&(Mh9W_ikx1-G<8(fy~1KBkIpY<f+H=E@YP5WN+LAtu{^PIlgk1|Ey
zFv%%o;4_*+^v$=8U6OB@!CjIMq-y{^r@M7~17u^`ry1}m+_nC_A&S4^72l)u8DP8g
z-uX%#2!v35!ae{ez?bGgI04n>=mQkaV#U4HCHedE9SG&m%dXh>s?SKXZEyPlbq%3e
zx#=<XDz@15{JWXmhGoma-;9BTAjTB5V;Z;#yv0`M3XUNfx$n#En1*fwZ?V-?D{<KV
zb`6BXE|73{;RCYnbxnVPjJt+iT*jel@M_Svo()j-M`P_3h&VRCV$uusq(FMw=?eC(
z7Mopx^qNNP3dBH)o|FB-G4S!PZ9p+{7iiUlyTxH3F>se>)ie|<eMarF$`D^DM;X!!
z<tRgXRm1j6%I34RIl`OOQ_pef6^bJ3Hn!_Az8cFHf6+E8MqhmCX$Q=ZUD0<pLv{rv
zliRcbW-P=U-EgtR7MLNV*aEYaI2noWb!>kLV$14Bg4mK~Be{^0Cc{sd+km>B<3dVW
zhY3;&EiOSyNfY9Kvj;_oTvAEPBSBRA)FBtuKJ^HzDs;O9@$6HNd{xD^m>{s&7QGRB
z5ZA~K5rqc0yNK$gHR3%nL=SQq)k{6{z73@5K_;VmsYgQ-wXz;#@8JjebY}x(5~|nK
zACpHtr~ZuPQ_rb8wtA}Xmm45!{G7UD;;6A@?q2eTbRX|PAe(;Sgi=p-23l~g2Rk#=
zU~BteZ=e`wxyKB|-sAx_J*Zi^=rJyeW9pBsjCxG{DQJAh#?UW}yifhHl~McD9~VWB
z{#c1!Iq~AuuHKwj1JWp=ln;cxIWcf)l&+?a2Q@C{0a@Eky*X{*IvDm718-A*eBezQ
zZa*>dHuc8`uDuu5aYOuN?>N}js*g@Tt%&bH$Dy=p-^D4wke$C7`$L7=>4$>NfTE}P
z7^!#SlrVs#hxi~XO1{R6G;bUl26XTlK0a;3I7JMEzwps<AKpHY7a<~?W2*E}oHPc)
zDf1%;EJqGt4zp$qhl!dcB|8|@tQo_>plWOG(E4kZcGSDSwc4FKH2A9BxkEdzEcpPF
z=8M{QrMB9kSyw5m9olt;vWnx&C{r#_fosyP(;Eh$eHmw(ajitjK&7qw)EytdF6%>w
za$0w-A1J34r|=GC^i$^gfwEb5YHm0O4TLiX)w1p^!S#u6z3GQV8+5PG;>)E;gE}bp
zsNx5u0dUr!4wh@`+ZfL_AS~``f9H%ruPYZz)`Yg|?h0JtR=o|xcE=*!7N@I$uw$mL
zl~eulB|Z@L%U1bj5SLRy=g+BgHW`J@*hG}rx_#9f0?oTattzp1yAoAm=Z3~qqz>bl
zHjvT1%^|M@p+Q3`hx!JEs2nJHPh->0zQ+%U6PVCl*#bJWnbOr2*JetWp!~(y286yq
zQ7N&LyP`4>u72n#B{p(sC8bGc>j?snz1+U<rQzTHh}dm+EWpZ_cQ+%=04Qu<@B^W=
z@zpMLbSmwF7_<R5ey0m}U_Z!>GKSdjO)ix~Y!}2JO8|~`1K|)GzQKjta=ZMMp||D$
zyvNv;anc)Qd`lZYuSGj^!{@aWF5VAv_;ay7aP<2iD0yeIz8G+#Ge}SM&T60bv!DTb
zs`u9Y7PkTHcrd#QV{Va|6UW7Yu($qAEZVr+fv-kk(Yq@n1I~_y=&9aYY1z%~ip5mx
z4TyIadwDzT-|Q*AZ$&#hj*<gmPdh%>C8@9YoE26XZEBat!Ezv2whhK9b42lObt`c_
z;uBP~q2qv<vkVN)Z68_tb8G(X84!o>Kj2KkB#~iK#bI%jIedH)^5t70pxqnh`0cxp
zwO_ZYuJJwak3gn9Vk<a64v5{yc|V_g4RFBE+Qb{q?pd37gH7Hb0@gbz;C7<4^3EzI
z{H#sgkCX;*O%(PHCGVN+xec3omXV`jPtON?pV>3*@;GJ=gx$9te3Vi0o=IVEeum9Q
zNFPVmEIUZc>K*r?q~1~f34#mD2o9bD;t-OYmbrkEbx$9MhI3@b$6+%l`)?Y4;oZ~6
zqIt7iwKxf8ekl9^x*5U&?dlm9lpjDp2uk*v=cX4Qn|_Y(M#E_>)B4hIR?AJ(v3tqe
zs23&>cISH8n>fmt3>-rZX{^(%oLR-^PuEX4g&KmTRk4?=icg*lH}%Bi>63;d=s<iZ
z_2kmhk)q-Vly#)2*t#>$6!1_S<*JrkL{;i@Js~6+e5|XLQ&X`^XB|4K@6uVHyvkiV
z>zh~Y?kUS0gafG|J1b@X2}X!xM=r8X;qYk?%e()C^Me}-xxf}2KL-M(x8e|y^-;v>
zGiQAjD~=3V2N;|_bI#hoaQYk&M};#%*0&Pp&w*fAI27c}HOS+qL1>;Ed;Vgjgr{)g
zp#Nu?rQo)12sR2FKnKK;R&|HVlUung_Z24J%*Wcw$XS-G3hh1Xyo3X&As9C|Zhdtt
zv>k)cHX|Zr?yB6n@gc4-pk|rBD$J!h#fmNJPf_da4+oyr9}b+mb=(}_;Q4`AvWMuK
zjbrCPIB*ysvutR7?A#2(j6>(nGOAT>&N{r|=s6Hdg4V$-1)wH%h|4{xLtF((9m4Jc
z<vGV?EDoOrp+mbm#1{ajxV)oef=Rlptvf7DNk_wqJvmAFsIaIdUUyXN$Vtjbb+vml
z$UB3>=0G3|95)R?+1~P`10~Ly11Zp33wGipE1(}O2ax%ggvVf&6z?0P;-^a=Bi@aI
zJvQl9rI?v1=^%=uqai*e#g*f9Qmw<maUhUFfi9e+<`nF*>EseAa3)Bn_QP_hH<Sa^
z-z3$iz~GZ~q%E-cq*EJ3!CsqAiUvDvl7fU2qao-b_S$sH>|eSI1Alh;OJnkr;Q%Nr
zT%;zcP(1Yw$d^p<8_J}MqXIiil1^1%R7tu@D%d~M5wgM-nsk~jFqkB%S_NBZIwUJ-
z!zr{c93lq<S>X~bNgXRyL#M1Nhn}D`;mDYi6tn`PM(Pq6_QxcnE6#(4G&~4fWRl8;
z^WQ)qLu`;qT3mrTn`o-tO2O4n(y1ROzJc&Xgh?Vn)hpQkk_@^f`%ybd-NWI{5cCh*
z-wol=Aye*tNh)E1IU&iMfD@V_=yB4>DOBI@$Ai3R;c%2MG|?n2(t`jDK<{z4Kx8w>
z1uj!FPGkdtz`4)KVo_jTNKFFIms*FwGxs@}s55uE8DU!$dPv5;CM^}mFhhJ8ICUA~
zea@%a3dB{)L}eCdtgHy=f+Lk7J_-3`<Cuetqkjs0H*+&<DEX?EzKg@q9dQ}Ub%W<0
zgD@zZ+LP`#^KmP26Qk0c-3Xnk%&0iU00P36vAtwyhe>)h&M5=o_JW{JK!!B6-cUy4
z*ne_U+nPypkx06H&D_Uig33)z2f~&)k(J*qnyE6ku?gr99cQ+p=_s>l8n1B%FbINx
z-Zvr8`;ra=(C|M9N`5p@u~`rY=N$+08<PDeTnNzZQe0|4CpQQ};nt<&MdsEuBfjeF
z#IZTT*0EqR8|UiCYMe+?+j_B+8s`$iK|9Humy;R~gpK<OvIn7guBoKvy??tJXW3sg
zIVI+uFZB$uX)d!}O$UOOxyp8yOycQMLs)cB>Fx;I@kN&|HIv=>F<op1t1ex)(y3Ok
z+dyTyBTz(jcuS|ADj;F*u_)7_CkKKrPC*fUMJam}HdbXiZY5lIB^?C)leztX{E2b~
z{d|(<Qj3Q`fGui3`S7iIAihAc8QuUFkZiMw?<kS&19=e=EPQ4FssRCJ{X~HK>LlIG
zrCq%ZBuDIe*<DkPQbEtThwfA;^@P2D-J0E-ei6v6?|XHV%?(i<m&gt)<AmULNn+f~
z7sb4xT<(*zXH^LVq57E7Jx3*6*X(dViDj{;c#e?cw%GRc^|S0pa$lS~j&mqcr_svZ
zslv?2^nPpxB)(RVEA<t=X!*MI;6RS~?cD}41EXB<n%NdG05&9m?fABlFP*w(=$Ln-
z0sJhp9pAtP!iI1l91xrGoiJaAhBP7Ax*N*;YOvh4X-6IaTMi`M_WFVBx4k}Ju))SB
zVnFwg#z5G1hdBFJ`%z}&zD@_i#*apTUrPwH#m7>JK9;^t8IKpA-GQ_pWww1mc8%L^
z0N5m|6?wX1i7Lqs!A&{|#8jmhLX{j)fmX#;h@(~2qMMWwAfc4_hi4!sv>U9$BBhjz
zuBdUYvZA&f*#?wnjcowbNx7uTt(4VpLmA)ass)tQa3Io2A(<RHDa4R*(IZv%1KmnV
zEn{gUDx_QoNeU^xHv^I$4k0A9%$1O&7INZ~R8m|u<V!~_lz6J*RQr}RmwC+LJi~w$
zr;!2iQ023DUO$dG1Gyh_2I3dhIvovYK0l2zPdS*jGfq^PlQT|K_<jut#~e=6Np*#%
zzJc&ag?TySNabp%A?Pz^=8Q8Hrs2Gobim@IoCm&xJnRkxrUR5{HNfk49y-fo4$ebn
z0~`ScM7sgz;OsIRU=F&h29$W0)nFi-L+uqtf>GvCo^#M;Ht@$b84WlCvK4j7yUAce
zc{f=NDDS3`AAGWPD=a7jO6V~q+%#}XxN6{(u)m&L*mMRonSHEG!xWbFS!I`^M7e(*
z2rU`(NwQ0!gC*=z=pZ++LlWc$cF?_TKr~EIh_n?Ql3|fyiZU#(u)mFnGJKy83NXte
zM``7++0Zx295!VIjS|Z$%OXm_@mO_AP~5*x35usG)Au(=8tj-9R0@MA`j)~Vdhy8#
zhD`ILb%+L03W^)pDM9VBh*D6yETVRnaEP{F{G#9~6xB}aFlDu?H;~mqw-ec+2Xwe8
z8`3#0%mHoL1DTB7qv%thTl@jh8V^Yv+~#Ol&j+_TH@%PYiN}~=HiLLM0684o<Y?v}
z2=4|CK8IHWaM&6Uy8}@$U{Kc%nGt|?Es+_fr)!IR&}&k68;mc+1qcwod)z4-*vNH_
zk`Xnw#a&Bg{Fm-yGUK;&X_Fa<rHh@6kf|+he;CiG3!=>MCS4+B#wqEdDKqBCPy8Do
z?~qr4xhW^ff|rp=qJUPXYq5Ob>lJrrnL#%>Nf>ZQ)Fm8)D|t<q85rYM4ewo5e>m={
z{%}=P^@jt8#^+ayd=UG?MNrY7jFR^y>*b&qN!Gw&D~g-Y%ovcIHE=i#>PmGWysPEF
z8NY#>Sq6K?-EBU28<{omqW)mQc^RpLeP&RF?vgV@D0JbR86TlbX$Fnr;+hZAUG~Ll
zyvxpP-Y+C|emZy|Ss3k-8Nh(M_I%J+L<gNCeNFfEj4O>B{ejqBfNuRWV+Z6H@IfZW
z0fwE1Zvnzi;eN0I>F`M4#L+cGnmV2P<>-*<-0!Xs9^snsn69Sihk^Bp*i?C4Fg7(D
zGqy~(e0gse;$9{w(NhIOqQAXdL_B=e{Y+Gejw%>Y_eWqa>L=vnjw+*kxEBgM+8D_i
zt}cvZl{X9nS>Z851g<J4mI2-0&Fv=B(OqsijBgFs9mcoHy(f35qVfRBbYz!@kj1;c
z=t0C-SNRwjlI4c90il->mK*)l<;^r=P}w=o4L4{-HZTS@e5V)#8~#<<{m`@2FM6HR
zOKUSIhaVRMV#Cji0kPo=hJe_Y{Kc}nl)JwehtSkJ4x!Pz4JEm)q3k_7^}_T<*EaT^
zySFqT`i{ecF4K2hPIenZX2TON(^Z_#dYRth^5^py+Hm=^7}^Woh<N4U8!pd53!<&=
zkVxrsKfg4Bg7_kNDQ3Ea!;dk;AzY4*7HJEgMZVtUOTLmDfC67g4ggj@`CMkYX-f-0
zq^!Gb`ci<lE7#6}<k|bvB4^#<6r~+*tP}!c%;aI3<%6v+HGQy?WRU1_3K`fA9e%D^
z?$-JQ%iUU^V0l~9rxvlb@VWhzw#g&cf@-gGa@u8>Z8-Ka%r=~V4KdRY9E3AGy7d*6
zS9exVv4hJG*#d9zSlk2|WL+&@nmnB?4EH)GXJ|w0k+L+li*CHKBqB7Ij@P3+J7!y4
zE*^XE2L(^14ue45@Bueu&y%0{2buiHEl3w$?Y@gLYB$``Eo%3=CYN<X@Ko$N%`ByI
zd}kc5`^IlXTAuvpGrhUJUAkDyU?CT4eK*|2dYjz%8L=C#{*2m<Z~#LPjDRs7j41G)
z(eGNH3He>?!_csMD|&%Jy$EsOgS^KFN<Ltn$~~f2Q4|d5Wt;^NU#~~>WeV1?nBVK1
z;yDblzA|1fgX|oEAsZoUiB%Y&!k)ocq39C^1xJWVHlJ^gP+`}aB2=P#h){{{y&_sB
z(+iv~Pk^kU3#G$Dc-S-O?u^$#6!9x!dJOT%AodHYydr}bRUFYnxhYmCy5>hQ1tBre
z*n^ZZeZ&>S#HeEhI%PVIdo0uj2!T#t{D}us>gd*>{nuT6gR2cAvm!V-!nX{uwvtvp
zP6Rbg9rO@8?ByOz?4!Wm-SFj6z?mU<@WG#SJeMzGR!|*^J_7C5?rg5mxJ-BRsxwc+
z`N4f1H$Zs~!^?C)SD+pPpCgzrw>(ArS=6(A_!SXoko`#aNzK1!HFjg1IcjXi2`0A6
z-53@hg)cHvS`m(!9_v-d5QI+WS~nDZest=f3wzb>n-t+mIVHtvX7^~{rf5!stWg~%
z+Rpe+P8Pn3;+xJO?As!=lyTP)ewyj}t`Jp5Vk3@~h?z7M>^h)4$HOu-J0fN?-Q#PU
zI^@IdQkN^vM2gR4{C33fGJZSad~<bs6`Zj*NBn)0skY)ntAJvLct_CjKp4He$Af(I
z$J8N)FGq*+90hHG;Fmv#W~|ES<zwoQk6t@C9rG2H&0ujwZhH{7PrXc+)sJTi0ne2o
z&C<XTQ66FB8~@2a`H$vs^i2PLMXYCf_$#U%jbeOyOrFEz+0zK1&kO=kkUa-DMdA-B
zxHPm^SH?MOt7f!-!u~1Ei5tK~KExpc0Zu}Y3>dQKiHLx6H?b8A$oV$*sYgzPp#8bx
zo<r0KTqhHMf-NTNQJQ+>L<lm1Rj4l_YtX6;Mu!hHQ9f`X2P=dj)*Efn3~FduCpc$x
z3<?T+X{>uPOjVp&MPtEtjZ7CFcJEI)^%R#@L5buV(G#+3_%2wxYZ_wY$c&Q!We0bK
zAoVb0_lF$(iL*t>f9nJ3oBplsC-_Bdi?XiC<WpO)l3e_aSs9vCUxr?Y?8K1j&pGuR
z7n}CrN{gtNRSbFs`3m>h;AgSD*gB{km=PQ;OfuN8MFukfu)3Ujj7zUiBX{XRMYbK?
z#TR>Pdj)X~zb3(LV_%%>d<FjvzCqgyEIEX%bGo{!pdFGCgs~$nw$%#bwitW(1q@mr
z`$#r_a@T|W!5nrl3h|z?2Bi>|9u&nEJ0>`W&S~Vn7EkiU%}@;8MSM;pcM)IH$X&#+
zK-hy`AYif|kakF#Z6)oH%ng;SL%i{*1qV3MK>-3^6cm=AlgbQ_>9H+BN%hn5Mrd@u
z$G!-?RpeGPa_T`XD6(8HbILWDAfR-KYAZAHMr>R&qF>k$Md>vlBjZXT1!vxpbpiTc
zP>0Qkc0jnKiG+-bWDu2okcr5QCA6B!rWTuDCY##5B;jX~t7SgJCo4RPs@sCZ+BN}{
zJXCa%z8O+anXtaM36lQF&?7R;QTGlKx*5?gwpZ}jks~9x?rzA%-;h{u*9iP5-($PW
zBG!wxopi0KZJT8IJp=$F15O+?dCo|mn)Ye$(;WD$cimY|5T_l+Gcgz55DwuL?1!I{
zF)Z3YlSmoaW*}T?Ni>bzdXhL9dEGTZY!hC<J@&akxcB&p2egsf4Z+0Y2-MH1aUxuG
zV2u)c<u*g7M&V29oEmpTXZni66zMbpY%daS`sq}RoKrbk@g;UmtvJc(9!H2I2GJy0
z5n(g7<c@u6h{(}6L|cTSDh(t}&mHUVh#gBnRrlPhNVKV$5pzeH9&9V~h%G9RSS4;D
zI`aJNA>c#X5KfUto|c3oC7wf0*=;IvO~Kz=ytILYY6OGq5vmc7r|1QareesQk!Z-4
z>d~f#9O<#<{X~28sg?n<iZO2Rh%*(C6L#O~WC!#iiHDr>$z;oCnSSEPZP3GYaX?eG
zF{rc6QaNvf1|qqbC{IO@2h`{3Ib-kfQoQjtnP<OG@8-@`^Ez=PRu_<XkgcwB-a6d7
z?>wiM)t2cwZ50G!V;HObJf{Z(plOuv%sFohj!c_?y?W<0^_WP!izdr?V<7TlBe?cy
z1VZ3I?EA^JPw#7kbKtZ;UGug;B;HlOS-8^lvf4&>&HI9FkJr305V`HUS6rS<kY4Ap
zQm=WRFks#$Y@uFx9wDLW`!b|?%^L@i*pqCrUei|M8qGEDCAL_v!cX2cX*2G=Dn-B+
z>Q(L^(M?{j)0g&|l^G(TMA<^U>ikK+!d-WQ@~kRcu{jBdc5VG#HNIxhK(1MpA#!O1
zw&1QdDN(+>TD0wf_E-C<MO|%Dn}|#rn+<!`UEIui&B}|fpFXKgzFhj$m@SW4bpg;r
zUOw}EYRhN-xR)j!$!9%wn6i11`n9{Qx0~909n;~!XZ4tlB|fW%e2oO1)A7LOE%XxD
zy|44@c3ik7tt6m0hxn|W({aFO?V64QO_2jA`&yk3WIk#0fy^guK9KngO$RcM__=-_
z$SfX0=NBSz@EE@~L|ry_35%;xpU13N>;(_K9-E<K=osBV?#Iv(&7qga&#DIL<UIa`
z2#_BL&&i)@8ATuV#-lU?P5d{b=SAo9YF(ALl%3BldPSWzfe+|@%pXXczPoicPsjXz
z`Ge!2KU|y#ayL7S_?o2dxOmGn=+nAera{~FzlZ4zpxK`}(+#4O!5@Z|vR9U@V>B>r
zFvScc3{1s3HXE2+j<bQu<v1IdY=;?8SeX35H~W$WE+uu>WjPy|T$WAORWN1^C@f4z
z^N=V#$0aw}mt1g)U8ZfV?B>o>yM<VVxzEMcXX{=)5r&1bbpqUt4w>M3Sod5?v4M3+
zDJ)AJD-N3&O_Kwl_&cO@Onq@F#a7lKlGw_+DU$=446eIB=WcKv@n_K;7nAN->%sUm
zALD_SRTr!<{SJh}KOm~mwGIgD40ZCrq6%f}fVkoec0gRQ-yIOwHTTHH!(-V2;apRH
zd<ki{J0LA?b{j46CGGfu2`24RS4=R8*QhY~Tc{u2#MAYL0W|<7nWSq}TrLdc;7`Vq
zN%D@ty+}z=N&OC^q%cLf;0KcVh-Ss;hRGu(^}-hD0HPZ<{*<B{hd(5`;Q~;}2A^X;
zJ~8~vZumE90PM(x;q!Rovse_cxZy6UBx!ONMjzXxE7~O$lzi~9MS|tGD2fhOXC)%y
za7$AdxaJpdB|^|}X;UJ043{<~m8l~>VB0ovg;OFv3m1kZBCY&RXETTwrMr(eoK$uU
zc)l$40neAE=89j^d|lem{QbIg1jX`BdB-Hrx1~1jCJPd7W=ooHOMT#RS(>aAH_AH@
z-jpT|Q#v8;j!Fd7;O?lTaCk{r*>ZSE9H#bM+$I&qz2L^XL`VxRmx=;d{N5Z<$h^_^
zF&-@0_`=~Od+Bz0Um}>KWsWc0U9wN3?D}vNC=nR~X95eZrW3%I*SW%#z(=Ru*IgDA
zqYcEyr|VL9J`@kx;DdZjr`#ocsfL3~!K~3e5l$CHu@@UXGe+3?x30BH#8ANDqliO@
zP9Y^CBwFEK6J9My-Ww4Sa6l<3+*%3-5MC|C#Z)}F0T*H=A{lTYRus43zA`1k7H~mU
zJVt?TJT|BZNieEL5CgD`hQj5hqoEV-t?vIb2naZD(9<Hi06s)uEf|1T2sb6$NDG4o
zaG_@82=aEyO>7C@x?w93Ab=Y-&@RkAR3+T~;b;Z=1_w<1;o1*>tpY#(ZMbulaN=*!
zg>rbfKo`p4;o_=Kc<eX0u9a}m$Gu#U?>(;NO8DNxgKZ#pFE>jf+4LOmt`6hv5Vgkl
zi>`DfT<vjhS8_GGGA`{(c-Dg#wdB~mp=g9>J)Hjv{OIu@A3(Sm9=<ff#}Jx?+~z^`
zS|+!7@WGaFn+Ihq`Aoif`B%bE9<GW;i?Z`4wj-4AjfX#`(Y6R_R%VCswal@lUYLW<
zk73`9UxrS~_|Q#0;yc7kpFwkAEt9)9JY37<?~Sih_<JX#%V8r4jc6x?E3R|w(1Ev!
zm*-m^zh&~u_K!h0WoL+0?jPMLn#$y0ja^y3)7X<I=jrTE4c}?(zc=sc7def-{U&Yn
ztn4g}krXMHPOL4er0=*`Gdd-B_zvx*OwQM?zLd%P+Ad88K#AaZUUr>PaMcEKr*B@X
z4Q{A#Lbo+DIbho+IeA|rCc4PCy5gbQy>N+Uh#dS)_Jum9yW)fHiq84Aq>DU4>{4y8
zX0dNL9u{qHhzTfkx!!cIRwfVYj^5D08vEDeV(t4^QJhle{#B@(THJ&2fHhWOUm~Ew
z`%+M{eYQkA5@Ik)cwHk-qlDKrZr=<+Lx=aRXy3u@+kiOJ$Cv+v-NzxQXpi)i3P!A^
zhE5-$_DNjEm2k~QkV^^IYy`oSaL?}Wsw(o&#s!^mzwNBm@SF(SvG=OfIcx_6atzx!
z@f42A+g1FLzf>|W_*I<&Xyf7}&f!NSyK}_FG>0Gg97=1(g`V-~@$JT0plG8-ycFs8
zz7<n75XOi>*Dp<PBVw~kIFuuP%gFzBR_k~W;~!m*hlBa{t$V)`9_B}KN<m-Vh&3|=
z?If2KweKTQR5H<8OdF{SzjZ6<#D?FBf-B*GjyO56A#Q+NR8-Ira7PZsZ^h)1XYpG%
zi38CHGv-d;Aw&R{a9u}~AW0p+6-ij&&Autzu!K81A`%Tj^W311TU=ua5BEdcvp#5u
zk0dqaw_+$uIK3mzl7yDu5sXRJ%Wp+&7I%Y3L}v*%c-(FpQu!NSMG@zO*imEPMBC6~
z!&e?Ls3m;m5vS@ro+d4B<Ff4>P5t4(oBG3nH}&U)M>jIy8Pxb7_J;$9Vp>$PheVt=
z9B;{0>X7#)BE36$qf-hZic9$7^V*iQs19{Jh+)X+%N)*($50g9yDtUe9f$gJ%+b^(
zT=<Ve-QjA7Vp*<O?J!W)IkcPnu#VU&4mW><hm%#-5nByKp8tq5FEv8DVN9wK*^Q05
zMr1bv_zR;05cXaoIsk$3hM+sxoFiTU0rsVm(VtQHrAA=4DW_HUmk8u1C9fl6>#GR`
z|AJMiD(CJc?*-@s$ou<EhJjLfECUBY@r&LKkpF^=2-ttC{3JkjP#B&7I)qZ?{CeW9
zn>5AWB32-m@wdnqieebR&rqsPc;Il@$cg+dqK8s-g#j`MGAVzHFrs+m0|+I+y-bb?
z6NA(!kW!S0hA^juQh92GPeQ4>2|1k*jI__+WW#U-T`MAr{uZ0YKpM&}0MVY2l!JWJ
z-(v0{AN9A`JxZl!1_F=*ue9x3EFmPe{uYx+sXC&9ZG?2#-(n;wwV-6<(*YKoCS=rh
z#FnG(mO+F<8t!kArEI10*bBFd60sd%T_K<Mw}@FvM0<d|1uWnjAQwatEsQS&sf8el
zA(i;IsALLbL^kow6a|SGAx){$6v0^o)^Z>xIy@ovA&bZo@Z*sF+!2>}MaiWt-4aAR
zpin2tj>}x?=IM%T)lnUuAw>Zy=jl}K=si4X?~uz|hFK5~l`8%8<VGl4?FmlU!cdp<
zRKs^7BofJgzetvJN3!>yIue{oNJ#$;XOdE>>cW+zRH?e4aw4n!up+>_Bp^~kl^XO^
zJ10Q&R68c2p=3*53Npy4?udzhW~cHcAM8|#OFr1CaC*NXJ_qzjxVZbtpaBjpWB?!s
z7g{F|88<(v;+L0#W6WQ+8S&#vZK54x!*|xPQgxqrLAAUgY?$+Sl^1gye9PhFj%4pV
zNXNL@N!Pz{oqvbeGN-kuWlk%1yFl;;F)zb6-A?X+H{Vh6G3y8cr;{=TJi+OtRGlo~
zbW$P&3Qi|?#9H>l2PpM?)#*H9lzOG|I07G(8^D&iI*^yHRGnC^uBIpC^6qhYbTu7_
zH_d(Z>S~;8rmOXaGDq!YZgsM&IrHK617gcThS+|T*)W;x4mGS*hMUMLU%Ts6>w$3C
zSZb%*MgWYtrZ8)W|Kj)wupKVEOYH=rQF7&7YAFzZFxTD1mICmW4(Au;wsoN7LlHOp
z?h4vm_H9CW-u9gzqks}0O0rz|jocA`u&>FoW3xGUtfJot^0Neo=?&mheVu{|HGqwD
zsilfqAMPA?1eLDy6|Af?QmJE##ee4;J0ob^d)L11CH}kx?QA3P3L4r{l}=zk)zv_}
z4oGH`XPCPq<+?p3Q74^|d}|tayxSehQ~y()|E&jN=(s=?vWX#h5@Kq6VgThnH>pJ>
z|I`k$;%S0Yk19eM78}@}yPg5yxUDPaRGyX|nCqs+nGOvn5Iz(h^Sn5m*1hw=O>av&
z)we+K<d=A+Hx;kxO$A5w9Vpx+AizuC5%A`a4m<V@Qf5y`-lx3>w|aNL4KCc#$lQGc
z*oyChWB|V-+_yW4+>^c;Sgn3%7uzz~$nQv-_WSKy7j?1U^P-L)39_R{Ijd!|k>fVv
zhOlWY(45tDApB}z$&yR!4zY18QgFxX6N`JfTbXTho#yftAM$T9*iYYjUc=oHX$ZS{
zUh(2BbPZm--4T38P?~iYT(E6Fpc4uumSV2bOo_mrC1naZ1ZItki3aY-q_;6yL1=c!
zX8>RW!nV1ry4vO{>QagWp;Fu;nS!)al-W4fNN3{#ux(!=+eiixN;9wS?g$&^@;KBk
zmctRcDX0ICZW;)6Q%*mQ1{mO}mUj;Dq+ZII=UJ?w#B&%Yn)_Ac!#KI#BOk{3<21xX
zAaRI7t`Hrwm`()eunmyTYAEw0#wm-F*o5FXhj@BsJmJZa7kzQK<h@=TKzXkhhg9TW
znNPB~#=8S-+^4O0vzVVkD^z5%C`pH5Oj1cYk77y+_q&P`?GBg{UgE{+pO<)HB4F~H
zJCbKh19RwXvPJMlPWFlyGx3B?gV}n*?!lBkhHL;5x=ewWu(_beC2TI}Uy;G5Fym3t
z*dgB{qYGtRUttmAJy{ry{F-bwEb&&%?M}?06m}`zfQ9XfmtL@MF&C3eUXUhtJ2Ls>
zQY&m}Ob$hR+xD$1tP+{VOOx%7k2%~nNLf-vQbOC(XUiayTZQ!y7f-S;@|r0Okbcbs
z6XgbgQlKPxEK><)SjvsZGNr^VI+iJ4UpZukrQ8nLVIemfp_IT6w>(=IczLN4R$$)g
z&`!)doUkM#9U6?y%!gL+6iVv+nk?45iV2(cK-?y-C3o`pqx`$Yy5axAR49{Q!8W){
zNL1<&NcOFJ5VzjrHyw|mNVpLywO`>zh>HThi{LedJ*ILajKqF>TvB*<DmTJN?6>n%
zq|AO){&@Ytq<wKk!V$+c3X}hBe$PUY@*>6&_ehAuey~zS*7wS5(F+$FTqY&bz*k<3
zD%Ei1y{HoVRbGr<e)+~%A#SPoLd8`U-@&-<;+w21u}!ag+?&xX9+zv}Z2a<#n^j!S
zVSC%A8$9lly5`gF8drhbq~p2}c`mo<PLUr3Ts!K!5*L&FHpS&7KWVt&WQI@nhijm!
zKOA^ffAD57GNbVCaEef-zDnm7CFWyHg)Vlf0LA66Y?g6DOa(2jk!f+{MKcx3xQeC@
zitFkP5c`9*Pwy6;9vPdUt8uFR+z~g2DsJXEQXE@#5zj+WT-NhQ#{2v*{cw98zv0EG
z&P$94fa?Ix!Qoqg1NiKI;3s=IDA1Y^E(}Pu8(t2~#tSb97nVCtaDdo=<x0Vvzu|7d
zyujg-fy}|%3yvFr=r_WtJmoi1)tLN7F4nsEAik}a{6;vcOMW9<vzPov__AJ<Rzq=i
zdtqYc@Qf+&crVJBjPrNVCB(@7Ttt<~?9lYiVfyIs-(imF@bN(&>d6m?d8)%#h`Fr8
zp9l%BU*U7aoY-49CKb3yVKiVQ3+E<e-46dJX6A;6)CMTLsJ@lnI~=W;0z90tm?vBg
zTbq)J7jbD8Bpi3QuL3@}a0@H&7MJH(ao_OCx2(8txV+Cw<0h`$PILr^3tMU2!Lw8c
zI(dtIlxf?;T@I<;!=sMb->I%|-$)S8G?d>;AurFpLYHni_c0NDH~<zoaKlFsDeuFJ
zZ~*l7qaf*L$iC4*g)ReyZq-FPMw=ZTOQUy+)Cssz%WbkWZOpr7nH#f|hsKRrIe_U{
zZ7!U}X^U{u+km*Auk-?QqLv0ACu(T`4VyF^O-K3Wi8_FeDxAF|oLNi5o+@|Ofn<5a
zZb00bmAP!?v3$le=_5<2(;FF{xm%GpvOZ<>M%I@M%tLYkE+8HXFX4fhzkoc63s{C=
zz;M7D(x;@kZYqD}0^%WfG}|Ei9-h#?U4Sq*e4`6IlC`IH+!@fpdUNQyCNJy)ilA`S
zE+F`oH+Sjj70%wJC%W}(BbD2-PWoUO4$txeCgSiuABb<IkyySbx}T#&*LiG_^mW!Q
z365mA$!~z%_gn{M5DkUH{XpnFk2j`64|V(C=174D{;ucD?*9ecLlGfR<VPK;_vlEi
zO%9Ai3`7`Z@2?J$9eW(38A>k{x%N1EQ%90^a9Ky_L~&>8NXQP_BE(;8fV{)lz~Ei2
zAdW)sYQ}gNfM(d0>M<Ua64cnNqgIC+8#&Xv;#k<V3Y$n|Nbk^VBOQ8Y91HsfJy)sE
zK~RnenhlUI@13PFn#f^JukOfUPOt9BPu>~G5(&ydmK0Gz1M%o69a8A&9ofcvV;mog
z9_gji1|7W_!c=-wAXIe5hj7B`)0+aJxHEJGLa{5@m?M{W$HtsasgZCGkM!Ljy^rv&
z0urVO0W0n>t{}0k&|^H(Zg=R{kz~8OF*ovOgQ_V4)(p8kAkB)0?w72D0dh~JKe=M&
z46*UKGQJhiJ4N7Kp@X?{P<NO_BH?sD6r0D@eZV{!DWt&w714qPZs-aqES;gYQl<L=
z{ZCPerJoF2^pau_DI~_#N=2rddZb+|ouRd{oin;t8IL=oYh}&t9$s5@iP)k0N7iAw
zvPZ(;&H&rkzHu7xRKJ~<Y>}n6GoY51&+Y|wgTb`OZrkyxobu3i#@Es`*%?hMRTb$r
zJes!9A3m~l4r;6IrFdK`o22v94<Bn*KYXOIMKhQ-BT&Z>Yc)^(KtS;*9iO9zLXQhw
z=^30n0PHc+F2R<?80S&W9=}}l5QI@f7WA}FqLdgABB@bouL#5*WuN9fy5S?=r(U=z
z0|DOyKoI%V4+fH}AB-bUdI|!`y;pElP;7dk^FG7Z4H!L9gnI$Y7h~YJ0eE!1EJfh`
zidcF>u5*gFFQ5X8n0$MXN7tWIcRapcMxF!8h!_A0Lj%MTU=K2ihI8r=$p@lCBp<+A
z%;*787L+5;oCXCfWWjqd5EqVgQ^psFKVcx*xHoiT&xnIv>goYoo2VKLvF^z{a+ub$
zGf=KDBw^QHdq58YYlM~SIq^yqCqxVCiLEeb!FVYO_|ZgM;fVEv_mM}Ls4oiR8TLkp
zrUCg1(tY27lc9Jv3WFZR#W4`@fbe9<KnO8<7-GHC4tf+3fl&Ui3W7ca4{8&`NMZ1V
zSV#uqf~zc9cctzg1@snW8aL@v8q3zTG7XyKDKThYUnO>h`U*~#!e9*XwhY8&sXG*g
zXo&yC5Zf3;5;GtZrY=Aj#v!U1L#)GW$K{xG#yp&hCU!ww6z$vvqg>Qkm!eMH2QSWd
z9lH;5)9llzZB0rkWvGZKd<-$IR6IY0(IX-Q8VH$xV$?)9YWPP7^U#2tg-IJ8xPY(N
z@Q~F(Bu6vC58~mR!dL8gU>z2pk|8ZmoJ)l%-@wbX-Jz~dJ24Y1)`zhoi~nhqopDKK
z=A)5{Ew(Z+FpF%efO9YisRm-KSh1N2;PIEK?XK9&KnQ&ulaPV1be$8iRyq1c>Mbu$
z%v^=J^+et^5T78~Vkd+;Gqd!GD$J1Un&`x4gpx(JzpKSG283@YxVW#_s=(JR3bYx~
zG=kz=WNHJM>DHoL)M2O6s?jp&w(8WhPjzL<1}(jALb_z-vmCa`2@0XxJj)arKvL&@
z-b<8b4m^XJGv^)bJ&E%)(L$nK+wFssk5CZzmE(8?v7eW8!^+f<U<TZ72%804{Kbtc
z%3NV!n7?A<I>7oUE<=N^>lK8DGr}qMWNFu~ma<3{Hz2;c_NgTy>aQ(05jf5W4d~3I
z2_ne3T+};TfMk;lVA8iN`P->0HI=(MXG>DVmNTNK`c`wE(*SIdp0U*+sla(mPbL!m
zHT^aiI{{6!o&zz8(mp*0K$WbVp;XMp0k!EdwpdRoH31||B}hu6w7r7mv@jv+S*Pwg
z5?aDJ(W!bV%jClxs~}{JGS|j`di}?3X!QH1AD<<3<o0>a=e)8XXB|hofBl!&zrE6H
z|NO82|Ns2n##4+5*1vCWd#p+NIHq-L^K<Af?(n=6M^jIV)7I9hjtS@}lhlti?Op!J
zeG*0^3o>^dk~zoQZ<TtRKS|YDv17xtm({Iz{(XD}89CL7!SIl&mY5XVH7P^(hP7B%
z)fxCh9k=zNyaUu~$x`FLv36RXYB_Od3&jP*x5}@<BW<Jr8HhbPJZn4d*CHPbEeuR^
zV@8U7&b4D^m3_|PLt~Q&MZaa2Q#Pj3nFi{d4W-vLrLdy0cVzLRx2Y4+=eYY+`nI^B
z!$6CDn85L$b$@htYCOLtU>30Xmc%M6&0t|3sjLGW*ou%$(I13Nk?0fhm1=8XQXNa6
z$-7r&6vc(^mctItlp0Dp3%|BVC`(s`$m2V_s4V%eUjQ>zwY1C1?5A21xa*H}){G8E
z7H@aVam6dldnJ;U(^Dt%htuzgxxAa)tKc1&!vdC>4_ap^h;ShEC1%EVWSRJun`#!B
z7=3&PlIdY=3oz+e1?zQA&_-an{QxrECuX{*83{?<bC`Hivp>^+oCyVz4nPUSzDd*M
zW|SOep8eEM7^1;E(@967J(~821-w3CkJ_2VJ?dojpXcA5X~YpId9iJ=V?g81!S{A`
z)q&;DVw76C{m6-5of8iF4d>`vYDf-Jw$lu3IVoE0#6FTbO7=Vj*qrSr0OnR-b&Q$y
z)#48XP4_B4dL$PorvR0!NCO^Ow-L$CMAMN9n>nH*hc)vgXT^Af`udjEm<ahzm=#!o
zi^_m&Lb@fC1;GgO#|B{#Q*0~BA6G?VQ}a6TQO!kR+PDRr(|bm$O;YVe8p+^Ua$yBW
z$dnk8)o^r}vNJaA>l25WC)gARLaX*|AQcnXmZxNSSYr`iJY{qf9~=|3DU#AWL~;#=
zW>1ubM<{jHoE1x7QdVIKr8!-be}IEao4<*iNIdpV8HAYehOINLPxL1g2GW}<Ba4`!
z_ats6M@$M`(cQ|+p}<?^c$gSlGgKnB%xoER8VEy<AGGU-0_7{1Q;d)VfT?bx`No<$
zCUSj$#+3WQnHOG0ipjJ9L8^=j=S<peLOV+|;*}z~3Y<zUx*X2|$^04lknqNy;^h!0
zdytl9p1l5%%f0*qqL-N2ZLU~_PF_7F3i(I6ZBjVz(_(OY8y^7^UMwBA0tUq}O`RN~
z)9D6<d6%g-mhB1CI0IdSs1+q#FK}^*9(Cd&1*a&sAJ;+sHcZr%ymt#ON54FonI(A(
z%QqhBoh{%A`-oqG@6*mwaBa?wgWf30`zT&IGL%6fETH1UMNcF|-{l1oWNNu7jN;qg
zHE=Y}S)@VxWhMGaicFE0tv8;n4qq;AUr?=Qsw%QaF;;w{QX)MIJ+(T0mS+~B;NKBP
z4?cYVNN3}2=OkWn>VS#9MI0*l*piF`)C0lJ@sFez<T*PThA8^Pi4p?Op=W!r9ME~Z
zGJ^L6Qv!4iwhVHDDKH)(z&}H*@U9~E$rtt&K}tj--jjjX7eflEgCzpE2Z;dJ*SF04
zQ?TF82nYW=gQ+9xl#F7^HfeWV6|t%>*C&5eO6eX}Jcoqxe3BS85pkIM4YgT1|I2=n
zu3Jp(Hk9aE=b+!ru;7UOn`7(YE;PrXk;*7y%8oAukiEX;Cl<j;3K^OMVHllqMsx}y
zGZ@^!V0<a!5muq24i{sBUk=WqQzS!W0Pj!N`N;#HzJ}psUg!@RUgY%OyE!HU314CV
z&FpPk|Iu%j{-_6CP2u56ce6ZiEI{0IQy0_WlgI;VBZDH{2gx<6<6}ej=ytccubcVS
zgzLvH{!Uz^)45DQlD8SH1<3Hmn9uLYXDa-b!h?wBgA1NOuqVJ%W%6C21BjORU%FiU
z^l1pDZF!FcId@!Lr=NG^?k}KqqKoJ=F8|ygb`R?pf*9sIOuuC0HPVkeJKbQ#eN|J4
z|MzrZbGt9XT}xb~xas?t?~B~feY;m^`F;Ul_G8-I{X$`%Za6H1(-q^V<@KB_du~*W
z>lRo{<D$g(+>N9~4*7HBP$wHIT^8IpS=)K$`uhB%T;o*vnVLOaJw4baFE>nn9^{5e
z)0q$XLeYqQC;))B0Y{sRh9_;4aY5u7F6HEpP1AH(-w)XcaY5CUb6t0AT{{CV4|9)e
zC)yh8Z7B>rgzh?@#p5imSUc9Q9tJ|FpgL>dLf(!eJMY`mjtrrb4@C7Gr|`&lMT%B>
zijarfksXJpA8%9S@TJpGWFDrYlM*V+F$*dyebWw4X3gioXcnQQ9q&U#Kf)c5d4bHN
zh$Nj6SjH2yM@Jz`WiH&|Myut}24`no`e`E*bkQ3PagJj&_gdJQCcl1|TuPRd8V-lk
z7LBB(B(N=w20%F_;)pt|1Ee58OhFh73Nv+QneUjsI?rJ%ZsBOUMC742M=(Z{K|=;e
zv=2`Nrcuhgi1P$nn;{Xd=GIdg@DafELHL=b)e`nc*y_{87*`qu<*I|2ikx^g1eGC+
za-Oli8H5wGP`Vk@6p<4@2)+T_D~9Kv#mDDx@^kIS?OZfO(&)+Xa-5^XhY!xISvd^~
z>{BqPktn0hCQqEDCJSeRAt))rB+)Dj=aFr)PwJZ1T)48F?{>EZQo+SN9i8uXZ*>a;
zB3)vpCluA;PqKzHG1<UAEAF8fGkJLY>yUzQ3m>IO>~O(K*uqp<ScwMC3`3$7XcQL*
z5*Ws^@+h26vz;R|!ig){$Y^lFBrby%`15ik9ytB8z2$Vp2?^Fn(!|jq7_5}nY<KkG
zL+9SU#nqX!4&U_a2!?ui>5Nwp-G?7lHvf4X7dJOLdOr@_R*2!NU%bA+BXA6z%#gSy
zm^jIy5=;!^_>4_#-+qNL@oCdinaNTMNByxk@-eVO1rc+*@SC87zx+lBrIXf0QRaf?
zejpfhGmnSK{@8Rs#X41=1&k3EiL7Amku;r2#=e;ygSoEV@L>}cq-HdZFyD|v{?!sc
zEsU0tMiEz7Q$l-O%FXHF4;dwCzG9C1Fa$EI{A?5Q2ZdE#dDgX-mBu{MI8q^*Q;_*(
zs680TvU}v-V$SNwyosF9VUc6P=QDotd4GCjbHn}M5n{ka+@V}NX4X6+0S@v3x;vPX
z5n3HjewCebHVl4tbu6PG9OB4@`u$2ByeW~aG$GoIyTCxOJIex@5K9vN18J8_4Znp6
z@qHxS8|^c-rDhdOK2!2Ua!{CA1JEH8Bp$?UsQ|Y?NWWK~jFRr164|w|8<R!Nr~YWK
zIi()+ZP6_3p;x<@TbUke&-6b>qNXXWn%hx!rDVM5_o?>^$L`4U)e=1mBex4IU%QrN
zgX?M%Z7y`A@!bmqK?Gs3gjFV085$eh?AbaFmolg^)kZpLQ)F~S+@2gBm=e2In<8YG
zs=Y`P+L+g&Om;?(cG0yPGbqI7tvH&FJ=g6=`M{=(NI7oWdwR`jB0xAJ4KjByAe6`*
zLvQg&i$IU+lJR|M5z)y!#iS7NPm+1825~+PJw-Zkh9lHWEPu*~iA8aU)Lzp-7ULot
z-I-));b)el=1Nj|dbs7qfS}Jy`I-o?&!D#^eQWSX)3|won<BVCLCd6%+m%UiK`zB$
z{hjQPK!R@(#0)YNUk3?8#Arw&78334vvq8zk*>-TvX|GyX|q>Q`|$d?$>PRekUk_3
zrdSEWojv$}$o`gOspWln{z<XpYT_35+i|Bp5$YsS@aj@tRKL(_NyZok8d0K2aTNub
zj9{5egLX2{K{XT9R?d$ikBdz6tj;Q#tl{3q^~2;nUXiS2;YSmiD&-nHNOFQ_gETZn
zE<z-G33H;KfNsPQg()C{nt^fZa%qAQbEYtW!&kghpc|S)^-21mSRrvL=(q~Dz72uj
zq7sn#PDaXzinbt=q9Bt-Hj#0{-W2wI^SWWYE|Dr@Bkh{J?CG*l%WNqdYCGo`RGiN(
zHZ=T)aEC-Q0;5}|h)3*rSw3aVsFT8*s=SKMo1Lk?y39I^OiVHjc#@aN^vH-jnfw$3
zmqj6`2(<{M<QF%B6VHfL*=f~exJYpYt+<vSA6<(SLP!J6al0Z36o5nD{VABm7U!<m
z&x5&}!)cURki(BW5*CMbv$!9xT)XIJG5Ia~3F4AjtI8005O7~k+6HJk3nx(+R?Y}j
zfqE-t4PNahH>FL^fM=czd5+NbI*gEiVP@>JneogjJyy76a~yWbYchO3RA@KT<!B}S
zFlIhfq|LLjB9Sw#E7qH7bhNnNkjIL&sTPfo$S*=EH`A*L=7%x%N&NU(Rz)J`x+0wZ
zVA=H+XJpZ$|17B@kz-x4$a3thg&p~^CI88eR=m_#EzH(vZ{=>Eer(A-N={XzVY{v?
z=GofqE9_?eeq7S-<#MnZt>$G}EzhQOHa8)w_F7i{tan)DkF>6sZ<cy*@ou|+Y|(#K
zRT0RsuPdh8O~5-my>&P6_|p2%iYgMh))mw3rr{l~@Va|=Y|(#~RFTNBu9&8qjJMpk
z%ld_N`@^nEUheBkiB}}nOx%||wPD9N{Jb)g+vCso+nvkwlIj*_y%n@W6?uJA))n{L
zoz6Ra)^*GC*rNZet74I}`>G;Lg}CJKb$q)-dVF#0S54I%=xJFE-f6s#ddJsXH&l=9
z`Ok_fW(j6h5fScw-}Mgt0{36fuMDhnUWw&%QK_H0NyF;Wz1s8Qg~8~Ji@0N1p&z%~
zxpyd7y03d&R&K_;RB@LWRu#d?z+}bmDVl-TT8}OA{*M)Tkyw`%d%s;SzC#<;b>rjG
zvY)}*<vra~mUYE;yS&77->x&CmzMpkvm%j}*A?6Ca@1SAUza|%NcUJ&B+}MeEMqll
zym$KzSu6nFzoMd$U*5Yi-|fD6T8Ycv$LY6UWmN-kuB(;X#qnE|5^<IM*q;9^sUneM
zT`}J-rhO{zSJjV`??2O*PRROO*SRXC3WK90%i{4k`R=}bsUq*t*UER_Z};kN9cSaF
z{c$?%XW+AZPgnGHU6I?yj@IH9|FI>%TsqK-S9n&sb-zzRglE8`*!?HnDxg%KSH3%}
z!oR>fHTxSp4%~iJS;@;Jt$k_<o(tX#3(sxXwHzC;1+jX1yLm!PgO_i_FCxyYDCAsM
zq{~F*M+53a_+C7=IQv?>C#Q{LU9sLgIb85}-;T#g_Mb^L6tX@-^Qy@`MXcg=Lmn&Q
zq7O#P_vCca))n)kaMs^&PDj=^{Ko`6R!p;_%Ugth@_c!ojOu<Zs78mGvaH6?Jhz^`
z#aI}AHP2IFKkKRpL{8p+U6I$hS?APNZ^%M0{xh9ZiInv@6`rMZ0(#$q8do2Fc@Ifr
zAX3&E1FpB}Wb}64&YRoOLq&QgRaPV-+RBHD?dHVf!nwOOJx+)JtgxbxYhAJ4oTOYh
zGqRWt`f;G5kaJzJ+<dTHICrnC$La8&WmP1yUI4s6hmV&F=kE3OI34~oef)(S>x%p2
zL-v+iJAKL?1>-;3QHkZgsDv9oc&B*}Z|-W3B5~iPi`D4m)>hRJXhF}n_bb*<UJC@L
zM^Fa7UqW(QR%9%1mU0T>^6<5LoC10?u_B%H*6MI!)N+Dc!jJE93OpdwT9M;leXdY%
z-hke<yMN%LFyPzAigGM0>xw134bjOcF9hK~>ZpV=_&pyg<(nJh`$g9GaBO_2NdL#C
zicJ%}tjLhr6GpAlXJ8=`|5al(zHVt%EmLy(3PBSLugpim_|LTM5y|VXkX$$qE@ZF-
z5P58o&Y?OG63P3rV(xMw^=^hk>7!8mCv{X{DL)@sK=w-)#;I#^YWzhQg%yRY4Ha-d
zq1)?QK_TG?`z#E^+_NH)Yh5u<ZnfUg+0FJ*FbL;IB`>ePsF|{ZeGiw*^xu7`#6<-A
zp2{oxUJCkyq7L4DgCB))qBT||axN<(;T_#&-|~702iixW_|NpI5^^ppCb|pjt{|5i
z^4KC>pmkRuWPMkV`s^tU;mpWlI{ase6@?t@igj|tej^|$9J3z<;~WsEgz~YjME7l3
zg~1~nPT!A0@t?^$EM#pVMw~AlwY{Tvr}9Uk_|K9m5;@it_nV9Q+|{x?(nvVFDiZ0-
zihEFC;A5HU4Ot0?EutckwGnhb!o&UzB3rr3KZ>PUOQ_<-rFmxWa@>C#zihbiKUBD^
z1yr!o`k=JeDHy<eH3tVg4&HwR&0OV`X1+(@0!#<{bwi$opjE+&U8`bQG2$W)_VX6j
z@F)_l2~?|E602$<x#;FSXyQ>YlqM?{$#YS0j;_E93cAzZ-fYEg=*<?ge6tyFIPH{s
zxgiVT_|LRk3R&)#bR1#?$=ubtQUXFa2^9l5))ng<q2fKgg{(Y^=5STTs|i?MnwtOU
z6#nui<>znT^N5?ts@Qd~SXRt)c+J}!xaN49r)r4G$*Klm>2m`oE{5)SFK@9tk79u|
zS*=i-t7^_gIO2k)4n8{1NEF3>j>6*U{BBZ9H)71+we*NkDykSnUaN}mXT#3poxDXh
zJ&M79g^e$Om33eAOovufnt{h^SU<ET5m+DIEgE==z;dD7W3nEn!GFdrK}cS@U<{|b
zDZ<M;dJFk_6bs*fRBH_4T2@PX9XskBH)J6gZUC%Ub@E?U+{J{IecJmBJXXU+si#MH
z%eg-1mE%kX5hRX4-pgAo+@n~ICWY>;5ISXBd1&pp#npK)?~!(oLXmL*6&a#emKBGW
zXWsb&<p|<?__?2J{O5<;HdjBdb0DDiY62EwIAYU%M?m57^Bd%5`Z^ugkFdihA%vY0
z6?@nzR~7Rui1Dr1j|gjgs0i2Bbg3faA=jS_Bo?6Q@2&WgUyOkfUAe1b)h*DfA~Hb?
z)8<?8FAGCwL~YuxrP8Az3G}9l>-4V8$U+$Yv!sedj%CGu%yFY{bI-g5l0LMz^Cf0A
z0L$Cm3{Q^SCHZ`hQhgM>{Yo=UVCnUkJFf!Zf|`*ILLsn^li<Iqs79cy9A0zhrhT%t
zeFhd2;J<2YjbW}UJ1jjZ8LIo9hzPIcXG$@?T@`^S&)!4Dd<zA3x!i+;AE&`vJXDcU
z#bsSF&7sC``VvR%@#92fUy7`TkmcoN7dgWa$NUbO#<Kh@(%&TWBP@56m0xKVqixYN
z)E`mPk3zX9bW|kLmlYA-$QW#I@g9}^*rNX|sUnf}>9O@&jQ5+QYg5$sLq!IMXI2!l
zR^3{c7_7D5g>svM<{nbZ3P{v|p}R0<WFdb4nZ!>-(drKs>n-g4?KGdaK=_A>+(`5>
zA);j24;9N4R{uuSYlPW9PIj}2WhE;soB2Z}QiSf4Q0^i8kJHfM+rx^C{V(f^X(9xG
zOeSD43G`+|wJK+}Rki&_HsE5p(+@mOfv@*V70Fw$ylD8eC^7?UZK5`KYRTz0QK5Kr
z_@aUbev=@<C4XZ~c%16&3xd@E9Ls9;ys<C1<nMe8j}z@b%c@9Zd7G3gxzTlEL4Mev
zdw85|lB%;Jk@XP?p_n9(c#9`K=p-InOz`1kMIbFLE7m@dQ@r8i9%L1d6Yn&<sO06g
z^pncS_f1i}MZp_H7>^V0>s{soF=#B^@{B_@Xf@E{j4WDA@Q_DEF?6g=b4bEY)()SB
zJCDcX#QV?m{t5Zz9jrH25O49$6Y|)i|13={I<gFQ%C+2BN8TcQ2p*EhrRG1=dnn|W
z_pr>YCTMX+7A^YEswx8MOYbw=Dy~zcDZT*iG%Alv&VMEg4w1gL;E?#aF(`v?e9*K!
zw&*|Ws@TLKy{yRCGln*j>mz7j9+#ZIecGhNAF~Xmv>jihGTz=qGV|P8^SB;V@<^~>
zmRb^9jkPmz*F3f2VO*$CP3K=$*l!FtZ*7OciSxLa{b$l>g{(DNXDB7ZjyHIt+<9y-
zd%Rs&a|Zmf#qT%zp83`JrJLmaY18<eqGxS2t-DUH*4it$f}UE^iPc(BT<}wca@`n*
z{8hPg5Iw$}jC5p0k{7MNK;@bljnH5KtM*KWJV}ZfX?c<?*F=}(jm`8)k8L$sDBj{+
z>dQ*ynu(aW=}gFKn?pP`D-v0Mb#NFPwpnj2Sf3tS@}Cs6;-%H<P$#T~U%O;vQz3xt
zv{Ju}VGlkkjAKGpW3it#RRnS_JpvOr8_0L{skpZv3|N2NB8jq)OzS;SXO&gOAjYCS
zFd-{JkS#n^#But#R1wIzG(aY#MB-J++vvLP1YQpn$@7&|k;pQ(KOs>B874->>jy#D
zLq+n4WmP0{t}9+Qy0KX}OJ|jsj-rZ0mJxf2xBC}$=d@op<gp@xqR&eenSF4nJ145x
z7w-)cBR;O>y@6=f&Px?ZytceINY{B|V;hUS{@`bOcsoerCT(5FT3d(v8`<98X34(u
zzx{PZ(ZnTHB(ijUwGf1%3|=z*fC?z+<sLRGm`5(%BM4a=o0w1P(#1c>jDDGpV7b%9
zk&yM>KV82;hUY5BogVK|$?=~RRU~r#R&gfVbM5F(zxSve`OmZfD$^V<J&~32<dQAB
z9yes6Kl{(*W&)(_YvZ|dX^|_?4<tA8z{m55{VEhQ=c3=&x*1|&oQTj*cr!8K<N3~s
zhz?XDo8iKR4R$)Zi1~r}#(DU7UN)|xb2_~st@JO)mx(_S&CST7J%7LBKuBV!Wt6^a
zeWYh}o5xJo_-OHP5%4|m@~_A1Abyk`PehO_qv05R=0s=Dr@pGxZ<La684-f->ajKd
zS(!`+q?ue+JZ_YgZi%~-SUy_f{AXbm-9_>Bi+$5r)^^z(TD>6)`=<X)HV0+s`NigN
z-WWGw%id=W&S%p(gwKjV(l3kpx-ojX$@tFk`Dim{7JF7CIcQl|WNL?`iv5Nx?CuGq
zYph7}(WUcyMo1+INxj7xS+sa!orLk%k@ab;rHSy=FEVBV)W>@a|55tlHHMduRi%8R
zQuSM!JGtuPEsg&yPj>~5EV&$p2qvo5HyL|^yY=x7Dtj6$Rs*nPCbKurrkJ;DEG=%<
z{3jH=XEj+0Vy2djE7Y=%3JXqJodJogqrx(B!Q_3qro3_4KDK9xz>euY?r=WaUv7GX
z7uWB3XP(@LN=CmL-gzL`U4}(yl`8^s*tqT-ynkJhRK1G84D#N!b>9eoNa*`EbLUL(
z`_P)R0EerDm;163QVcUz>n%r#AP;_MjU2<fDiT>96f>9(O86Ur`lS5gZzK+5ofCxo
z;%}5hb^JEdS`Z&UR3JBUf$+Vwm}t<|=EEwSDm_+c_(_GxowE2bde4Shoss$N)N7Ue
z%nubv;Y`00&o#Ahxu`dm=Xd0c%WJJb^w81@h?KQf00NpK1_dTREo%mapr4k7n#h_#
zVTfU3skRpL4SB2xdh2|!q6n{-v^&fcP7>_5SxN7-*neG-?AiHLMe=Fa^)_&dWcw}F
zNvGU?Xo(!P7pK4~EZmQ-Anty@Jmb1}ydT=|&G}*#r~Y2Wy&Iw76@1`tcMF}6$BHBp
zm(4`T+GcX3IV0Mej<3N#{!q<x)fIh-2rOgf=$cu?Iz!uRS<{>Z33{5mR~=ch&d}wQ
zq|I-$&EDD5A1ab$oz}!amexeN)si>*?IzF(d8|khcb%q$tWQ(8P9S;p+fASo@>mfE
z22t_^vex9_HBKt|x4g!KT>h^sii2JU=rfWA{vw>2s{ZZyF(>4)MRMHh(@W$R@2ry~
z;ipzkzaftm$)O)h4oF>6NsNw(YTv3IQ~9xy^YhCY&&ze~V|o^G_`f|xXjyVzI_ZB`
zg)SnGMYra>0B>cx3qJRUicBb=(=U;_KK-8UmUrOo=G+N+tjM=a-#Mi)SbyivKIJud
zn`w2<bMR2fKP39XAvwbO`*t44YbqDrtK5*MipVWr#11E9%?^i%FVgkD8TA$X{SWQA
zk*X+;f{7j0aTM2n%l7b=Z8`EkJX9>&Az6`$BbFpTW_aHto5b4<?-TM^5k?#_{6%7l
zUjqG#mN68#>$)M26}w&>R*d|+%ZhbMhT#F1b8?J_N^W>9R9l!)W2v{`?ty7G-e&B)
zC*F9d$ow2TzXw9rAIs}d8jm+}b}X+>J@3b^3cIs9t)$2N6%hqoZ^&ay%qbF4z>x}g
zS#iI$)_-rQ+*&EWw~(gI#sjy1-F%n=C8<(HrsHKL=JJT~oIf(BJXB<Yl^7S1U&dB%
zd05`cFZ*kY{JunsM1E-zXSpi+wUlniV?~_YYSQaMWKH<CN5XHmn13Xed8o+zGtnZE
zUs{ZW;zbM)_rx`ST~YaM#O*I+&Fzn?gK3qfc0(RpWd0njR3YoN>VyQ$vg5QG6Yy9K
zX|#hl1i&x6Az74bZ?k?zLZ62UmT6uU=IrH<9gDO;Z>1*xg(CzR?I&sxZ)sVn-VzQu
z!^=Gd(L=>U`+gI73ithGMSl9k1_7ErB99gMu@xJHkTu&yI&S%roTulWLFun6D$$a7
zLxilkLlQHq2l-UJA&)Imso7PL$S-tPyYf9b@l<4gdZ@qzQ9A_UrRRJaAVmsgBp);I
zSPl0kR7WBg)sjCDv9O`tm3-ci$BIy7g1?!_FZ|8$G$D_l^M2hkVm(wu;;bUZLZ#CB
zg?Oqdzn1fwMYgSn3Q%YY1>zMJQtY>!U7(VikjIK}FVHa{(toY#Ogw~h+QCbmfv0Ln
zC8k4_a*M4$7~t5OUYF8t$YXm@Zc0$)QQcX;pk+Q0f2#j>8ukQeT@~tYr(p6TP7Ao4
zH{`KmlgWq`f&B8ylyb|#_SQk=7t2K?Z|kZEWNp15uO(Bw1+QiKh4dP(OeJWxiPUvc
zpVDtB<iOWCA&(WAd#;LY5=h<G6^~nrI_D#uk*A8vZ6_)rB5O0qklmaD&pB7`N%0<9
zWbQl>dka}-sscM`SW4|cJ0XuP^8M3sQ^?X%TAbrOEOX<#cuVQ`Pz{OyvZ?`C8UhPq
zK&Hv3laUezK2&60!K8{r*2_(6B&OoJA&(Vl+7!pSkY6Uh^7*4u+f{n3z=gd-AZX>e
zLc>oaeLCQjb?Ohg{A48?QS!xKrkg`o?k_~NMUKXYiV${=jp@?cxU6_g86V%qI6h~9
z{Od}dCNgVFLfXhRF<+$;VB&9e$}IWN3KR>w=8aU8iwVAN=_%hvWq(gt`Op&cT53BW
zQkFryWD;lk%eS%8-xFd!RAk;v(Tox)X<aeh(rdnrcK@Dm^PwX1a*8XLNLi~KE#K02
zzCF>yggjPc-cKFTgsjtC(LG96+?M@wLLMtJt!P$7BFjtlPsfyf^gZ%XOu0xODx7x0
zL4_7~)hl6Kk<s+6JR6bY^r<EMOlLVE>$4nkZ82l&+mfN)bErO4M5@)K^khoDx=!n(
zl_<kYFE`|=V#m=vovOIUYF%wa=Plvu+j70!Q@}p7h<o>>#0Sb9yEGd!j|UUVzAdrO
zJ;m%pi_AnTos&pj>zsXO!rD=%NA}u>pBFP*Wu}WMYqoFXxGQ4svg|(-^4t!7CS#9~
zWh}g9INBq@?%OjQO~_+KX69AK86j)s+kMrN?1=rmCG>r$<XL}XDSLTsLF{xTRr*Hc
z!i!|V4;AUWD#Cmr>x7X=xm3hbS^9ND7A<<x;7b*m#dygB#w=qcD1DFphCEgb*K4jA
zCP`i!2s?f4mHXw`Z^)uW|Cw^X5J~IYFTLF|Grv7s+=M(<WJ>2)+(6P=fdds0UGv|T
z5$~1@`l%vQM$0fyB>l1l_BpZio5>x2@w`_)>M}KFz*@xu=M}S7zde)mggjMLy6ZGA
zH~5VIvfQSu*xukRP4;7Z{ws0?3s|S!!o@vOZoe%D<%~SGhcwV2iG5GmyW4uNp_hLo
zm#jBr(W1vfDHZiWzyI~M15+(tkzlgjkjEC8YFzdtAio65j27pN<lf>vNBLumouO%{
z2m|82^pYGc&Kb|W#d{9)#}*mz$BG%d&pPD^{65Kx{EoEE*V36-iK4Hfibd10thnD2
zwtI{B6z-2L`p?A1FJ#Tee=w*qvIX}WvS`tN78!$y{FXC#N<sg&?8I|Q`iDwRBX>sf
zV6U{!AIu0oZ5YQ4EZVYPoy>zq;974_pg1~_=LUh?US722KkE1NxYsJr4RctZXNYhD
z7H#>jS_qLLuIsGe9{8?L^>N;i$BGEGKg+a5II>m_4luJQ+IzG(Ba0UOXEF;3SzG1I
z4|jBwo8UQ>7p*n(Rg5jSnNWV&aDBq1Dj(+!S+wSa6qhOjSx4(fi*jX9i|gb+YBAE}
zvc=hX;xqoeoo9Z1Hq*WzXZ`%6)s&9@`qzJX{l#OQa)61sFKfUrTSw2F1c4z+g-o^w
zIZ%LX=6maU&49AAN5pTkb85KVtB}(8pyhH#J}YD+G#1N2#Xb<vW~06F;Kg4cu-<M4
zogn5oSc?Gr7f3+|k=W;;3*HtGmtjHgg9Bwoe0>k(a1N5(RNf5mFOQO_ALUlcl9dsZ
z9XWd6MD(&bVB6u5C4V6(k#XcypNQz0m_zE``m`Qtda6xgnxvMUIVGO!3>LeM@s7lE
zorh$fri=)M-ylVEhTA5jUy{8?S@%n#7r?~}1*p@8w#^Wyr_Dq&cYyN)HpR}To@0F)
zKe3)+3!_uhite6Y?MFF=XuUOS_jc><IX8Sc=}rvVJ9kW@Ci3|&A7r!N56L``st4H$
z=<&{yGs|Au?GCYIW9ZYki5wgz`Iyvj9*e#AsbO0Xy-O0L&Wg7@kR7{@oqRTDy+Y&2
z$I}}d2dhJGng#GhckUKZ))wPb<h@O8yUd$rfk@RXKq=_{yzLJ4c#y4{s;v{$8og@q
zIg?lA()$!QkL%I^e3pv#f<U4jC%3BVoX>Tc2gyn?N}t&>Ntl#rAz+_f^IqeFvh$UN
zgnc%%B+POQ(aEr~2D!~8=%_tQ+(m406n7w$g3H4q=qLv8UGyYzJ9&3c>I#yL_Sn$^
z(V8a}8GqnYw(ET}KG?oX0^pwR`_yjnwYpC&`vmMUY?t;v4cn!?qm;q<#yJEFX1k^l
zJGI}Xw+-of+couti1o=K<KJjkNWn^6b3yz^X@jfX!(Rc|*P@+j+Nm<ysbz>`Ws4n8
zKS`?NKe6p?BUDcj(E`~)$$0U}HYe@SC{0^z*xWV)Y*Je6Zs6Ez$23lIJ??spO#yB~
z@F168pZeqC>(L)4_{BrW=ovd+!rs-odIKJr7F!-H4K21jPYuyx!}GPi1<9n2I4!ok
zKpM+7fTpzwo}T7gGZ5$X)H7UGRfC4*rAdSGGouJL2Vmc^-0C!LQBU$Q&gg(<aMEp6
zLq=j4zt!3ZnWPF^20cwH8nUzPxAMgwkZzPCHr-=;A(Gw^mqF-YmXNF!{=PazDtDkA
zQq1u_@)23<06DN)mQavvqh-m2%%s`%EkJvk2w973Jp%~2xFplmAzzm%zCa-4Y1$HL
zplR9?J5n|_x`xpNZXCIIP$!ouqgG^FYCNA5P$!bf1&H-%SC61~<)+P&wES(KdgP;@
z5gYxkx4Dz*lvY|^6_DZgTbA5`u#4o(g~qrUWW%r089TV4s&>`x6hBp4X!pa=KwM_q
z3}K0NGIdjnWSWGkebrRKT-k_!BC2#qXojE|0x%>~rBsqeu0pBo<mf%MxkGmxkosYA
zsi)*}1eY+HMrtRp3vYm|@k5P!ZVWM0+f~%%&nbG23jw?CW{`_P+b&elEVq4LZ3LtA
z4Z#@>dTN#*a6$e9x#^aUL`YRTZ$}Q4N?mi9x}C-o&maLg&4;|%AyxCYF8Pebw(&RJ
z_B#5v;({R8CgFgVscPGWP8^iw1990jDId%}p}44mz;Kc%0kQs6E#gkjar-_v;-aWi
zhg=leo}q3VeX_d9T4V8SFJ84|IoXd})vQpB0&P6YZQYQTML*_<op<H>U7(<6xu5eA
zDJz!G?+~*BlL|ue@r#WRn!@*`gM6LaJQ)J3ws~mv*}SGdrR_zc<L?(Q&oaH82jGK|
zzT5q{pt#BceIFd2+Yg9?!BL=Q^%O^eN<FwkYlq9?=8zAWHGJCB)LkE4ithU0($wA0
zOl>bR&41g~vky{gF%B2G#(wXbbB*oZKeopD#${NPn}Dx{X~uPDZ=my5o&0-I#sybA
zx@);|<SihR0MV}lz5sVEKp|Gjt~w54QFa5`YPr}E*E`E4sX*^6vByKnETJabi6+Zc
zvEW3L%Oxp6fh;l<_^Bq6Lu~Y18O*BR<~U(nNs(%e^UFZcS?FsecKu|B!XgV?hZVg@
z*M>vJK-k;Fp0Km7jBU9{{Z`@<Z^pH#a<C&%f=YY=cBPqU&2^V<T9cez3r;)(;X;RY
zQx4APt_&gG4|A+Y{$T%sB`U!phdWc2ha>;)y+k&SPBRf$V<OYZKwLIbterk-Wao%B
zY}FO$)telLa-k`=fS`RK4P}1_1l*8%yvT0QXcsN0V8oMMKld?Dh?h_q-{ex!+<_xk
z(RPg!Q7()sE1<29<URvIvL8Lxds#OYZBW|38~7&Widw+vG!XXm@Dd)`al9!|z#Bf8
zMG831O1Wq|2c^HIo54dpWs2?88vyTWVQKgLL#H0<vnB<+HD$_aD7&RjKB&c+pt5`w
z3plteyAH;KFHKQt_k2G*k|^s<l8EqCDJi<*B|H+Qs*=#L>Yv1-J(zhs<kDC`Mi%*<
z=m(mM?61u})Z0jZgk70@vGPitk%Nu<YcH)_`Biqk*bUzVvCo*(<>f!ZtBrgP$^=%B
zDu-LOc_+FkrIeF5*nC+FGkfGqlL~u<cy>O>XMpm8G#AV9$b3PRnaR&6Nmvl%$6CPH
zh6HIFAf*Sx6k#*Z7fRl-Q-XydAZzRP!`S8!+QzXypIRB%-?MI1jEi!V8%myz@swKA
z5;JxcHRK6Csng>aW=XvuBpju|$zwYh&eB<mKNGNIS(BNWLo`(d$1p><74FJd#vw45
zn?4Q9w32l?0O?@PVU!u!c(OhWNCRVt%ZfQPGQ9^%Wu8WUD~cb>HslQ~m1*91$2SmL
zVB-3sclSX21*n%29CoY+W>b-$=s<ibJ*#(N@{9W~(2|XLGpM5}yfu~S^JMLYZ+Ffz
z1~JP8^Zsq}fzRSdGX$N+bedpvN~y@)lyyp}xDYT1E#Wk#WRj&av#1P6IJ{*!up(5}
zA5_)ajtAkjL$qtoI^Hm|Nrp=RLpV3fo>^Io9pX6gsmMA3={Gt7;efYA9>{_dUd}oc
z;gC0wgU!1HtA>j2MXqiiatL`WG3~g4k&iQ@U$We73wi%@jrn8NPJMVu*PnHE!WobB
z*WVUD;%ltP{#cpuQlI0BF9kEKG5}}*99LD2*A5j6k>>;QO4#zJvX5H_FdWw+Q7j^9
zH;2#}CSKHM9EUMO&>L>@I)qhx<Uf!XEq5k`z{H@s{;b@;c`U2ky|WIyb;`K9vz9lj
zqZ(LB2EsAIR-0Wv*c>|XAP$>bIFD*IsXrWaQip8No7b{wnt#;dCol30MH1RlvGcQl
zw@yaCk<umW_*c2XOAV>Yq6;}eh0iHAI#bxQG?U7$T$%`StjG=BBGY#KWcOQC#6wyV
zXdhf*HdyH<%ruf270O7mf$U8Wa=}S~DNxt5?vxAnZ>cmw5=wr?ogTvNJRZW$TK71G
zdo}eU9I%XN9=jt##|)`_PQi1qs*r@y5R`qD?fRmVoLxD=3l3F=;K8P-i;$F2s~-d<
zyGBjA{VvP{F4gICda@E^1Ur`4UQ6lBP|d{v);WXFi$EI6Hb2VLZb5%|Zh>j8M567Y
zrV<|GuM9FF=A^?j&RSWa02bWZ@f@xgDCZyn_*PJuC#q-gYZh;8@$=Z`(9SA0AxSD&
zft^RG$Qi7f<sEOaVD|cnoOeJC4{9iTUvv)lK<EKbT1@kP>MphvH4fPnwN2Sz>s4y@
zfv{;>hj6+Y5M=}1I<bm3Ep6{}kh1LZ=o+pv41(~GB3`})2$-JRFsn%76I}XneOIvQ
z-kNdgM=RKLr)IF{dIs^$k&e!D&amkw>6|z`8M5ae2)A>OG0%!cAh~5uQag)36_bJM
zrX(G->@fBwnXt>Qz64S+CN5prJ(A4aelD^HjbgqyXq0@)rO4vQlNDRS5J^L@m^{xe
z5CA^wGM6y>MUvqhXAwiHiwUui26_MUsm8FD{rHhZ#7zQFLvU8W(PBU@PXs<@g=Q2S
zBkl-C%B=tadIq6C2U~|YGdI9)rLK1Pceq*I5DXF}pE9Y?(8vcuiF0RbI{ZWb&PjT9
zh7CMP&CYIQNW2|D`fve83(<bm@K<T7!j=WFT~1@g`7=p(&)mjl#9t)Yu}rhg;wop5
zBajVH#&3T9;{IoBdzri3gm}NWbf8_PrnSQ@Zbljgh!-={kKzttfLLEeO>;G6O$RGw
zP6zJ0bJl#|DOqbFp2CI#;fy4{HCc0leE`~7R$NeVWo!Ukg-MO?I5y^_p|i0hk;juE
z^Z+z+DET?vTHYmeHoZ&efuLoSY~P%UCIcP3GPk)I;cxiP;I2B=cxP}ko#aoDJZ1e2
zaH;70mM*o$OGzjg1M-(5U1}=;JO(d7f+{FvBg?!&E-HNE?}$%;F3{4cN7I>*sf>_h
zprk_&X4wacw*p_Gf#AjPufukO;EAf3yMlfCj`)MI!V~wYDzAdnB`YkL&$c(0nwr6S
z!P|RB+<={QXvJXe2pY0d!Nj8Alj<tZ=8*qd2Is^#ctX5{vF7+Yk<E)3Jhg}T0Zwc;
z#3wjv!PfZ$va+wG9jA;5umV=dey9-|4|ZH_CmgEx{tsmi9*b)48eAZdxy<c*zm;I2
zh;B7KgFuXGQ+A%|@BAic<U1}7CxlumMYwrJp-HBD(dgK<m|V1!fA%#~nTnQhuXac7
z6T1Jy8rU;T2(b|Nq_+|4*N7DFWxjuS3-+X!npg1q9*@DWU^l%X+%NEIBXt#C{mmnp
z_GvHJ_i5`GQAgS-gmk>ZzQ8QX%|CxLl-snIF?uPs%@ORy?z^a%u4%hNJ@#lI?MIoS
z@}1s7;C3OKLEQfuN>Dyf!gnvB?}xs737tRugnWnYpIr+jyM5pX!mn=jrhLcTZU`DL
zkV;qMf$)=GAe1g04A%q}Rd!vs#(A<;Q#{#D0Cg~E#f+?*+oJv#Wwu=~0gd1L0I=ez
zWlg^cfW7m+RCSKaEHp%DdltxsL2{W@=_7$qAK}WA5(pEVMf0KY4q?@o6j;P+&3`SS
znhGfmL*#NUp@9pzE8rtEi=*V~rGM%TVryK`ew6L_cb*G8*T7CS0<w6n;c`xKuo0qz
z4P=z!U}GcPn7mL2B+_5s0G{BuRQ=CfDm$)Qbuu#u&)`CU<?n_R^p{J)V=Lm!HxLdS
zvwU6}cOYyFvxe9)dyr4{d8sW-(HZB|i;rPbL{2ru{pCETBl0M9*cN<R2BLGgkKjCI
z0l*ws1RhTB=<g}Rh)euDbmoVQ&qGZ?#Ha6Gmc9}aJrAAv`52z~A>s2-OOWt+$QpuR
zjrm7d;pg!Ra|yGXhDpVu{Lnir<+H;we}lYttOC=JWXG-Tl<d0fWQl#Fl6XpZINF|)
zZ<C2Aeo`j`*XBWjFw<d4pG~b(<YA?w$iqs98$`<{u!jY1lsn986nWU_DDtYtxrA%j
z2)Tx<TE`L&D;;Mg%ygU?Iz^>ZQxkSN&O@0DmZOy22Fq!n_IuIqfq4jIJT(B;REm!~
z-X-y6nNwl<vhYPbhbuPAoZ3)E-y|%mUbF~r17Z&;Ebj{hm1tF_2$D?56v0r#Hn(Im
z({Nb22a?_N&4mc1Oy+WibPmLi@B=yV7|Miq*}G%{f2F)@N$s-d!yG#xv`!)IH+#NC
zMxrGM>F~p=t_ctUy2V|>K-zTKz>FPnhcOV|YCuc}FC(m9$EjxdjFZjs5vRt-N1T4U
zgMa(SRM#yTL72Lc$&4G;Jx*reGMR7&z>6ImEs=aCXZnycN%%lm$N!F(l0lo9eu??O
zeMU}_;i0ZTgoj^kVXR%<z&b-%Wls8B98mId)_{9l!tH#H?(Qm|!)rMAA<GPW%ybgU
z3{cGUBO1v4F40om;5laF%MAI`m1Jh9Ue1z3yI*ZGFAc9Y9l<?d)=Fq<oZ_i!oJ&C$
z$0+gAc!%0|#I-Rc5!c3C4RLEsNx;;X6<o&TJ-2GNDsi=p7ZZV5xk#GR&2j_aKi~=~
zaid*XCHqe(r=p&nT&Ts1Xq6Ys6(wHmb7^E<>{B4wJTG(QyFeeIs<FA=n5#xYH=(L^
z0dE3|9Tvi@LmlFLa@9z91+CK<gL>csu{lJ~2`+YCLhCfes2%0>%O0ikqL&69<UQ75
zgmF1?_s9&wkxvM7U}c!Lw{OJ!3c+vc>|2sO$R_hh!0;IPtRS%)d{!>j@p<hi?eM3;
zv@ysfOYLU-O78qxFn&c|IJsjFr)HiR&?2`SPbOyN%fEz(84mBB+{4)ja$%@Smcq=y
zluU)$5}~onc%ysx5@Fa3F)=@<%xIEKomBxOa-YhK4$06*844nwEQS$>-&XG2-4A|u
z5ayAke=?{;K4Jqg|1|u&z~c=a<IXN!k6{^En%#)OfCF4+bcGz`GD9cwsXlSjmg>bg
z3Hj$SoOpQj;eF6=F6pz=k1|`&@E+V*Dbafno$W6=8(L(sX^#2Q%+Vd_Qs0`|W#51l
zsW=QkHt6Dy68$Un=mh^tuG%(vWHQv)Jv%ob4X&N+OjXmDYUMV$m1YJ6z&UkeuyOdW
zX2b(1YhtGJf8p2KegBKT*PVAaC8=S$e(Li~SN@VY9hu&_T(LN{d-lW)5FK_8R;uv&
z<(xoeEk*Li`5l+y+qZ&=2ZY9bA1?Y#b?mxIq{!IfT=-$y7+su;zD$TN9tb*^%mbT)
zrq_KSJ7XC1<@x_<dz)QbcUw!W|2@TO`ZjzbiTdpZNEMJYf~s;_K{{2a8z9(j)C~$r
z-ab?07(<%NK5K8UbFU59TU=8T_4A1oHAr?GxJJ=Kbbb|cgy&1pzyZ0~5jGv~H70{$
zhZ(>snG5|_v5ws%84bg2Zu<tu>`Ag9%H^g6e=W{alMrb*PfbFk5xQxTB0}p+LI|x-
z8F7L2)iA;ORQwu@2_~V?*5v|F1m>rWMOc2xgEsMHn-2E|BdO_dhjX*M59r%mOoomY
zDz=RWrQlTtiZ<o_kklxgA1-!dhYV_@@P<B)7MlWZ4Sb?)9CwYypENXsrvQ3L7iHrs
z@&`}}{hYst9|;QC0i5z7DRK_r`R~2~y4Ayz`nakTIR{Mb(iWP$JYEU{0~gcfTfP7~
z-CIA-H!wg(e(U41Q{*9_!yMk#?)ektkK-2vSL<*l!U98wmv@nSTKfX(bZ_)s(~Y(@
zI6_hG(4~NGO-%WIJfG-&eY~X#oeGc(#YfmKf2%^T0{LXoVf#34-4yf;*Mpk1Mz|X&
zT?F%>7scCmN|YCW5d+Fnw%hSfJKU7;l{?JD7<Kt-^jIs>N9l}Eb^D?(Le=f7!4^{s
zmeJ&KN3#W;6X?t5?%^%!aQ^Us<-UM)7eBs&C43daa}lzV4hwQQ+#cgaDQ4&~etaF_
zF&_SqxG=$GK?#NELVo-z=|WzV|Bq?s3xK@O4|$az2Tu1Y_c7>MsTDbka+4Q2ivqPy
z$Mg5!&{>opV38vzPX>t8Djb75qkH#9PGtGcV*6z}%9@&q-G?WOmT?uVM<$$~kee)D
z+QUuw0&@a!8LIt!gs?o-et4lv@nI%rqKg@N6l-5Wd{@bUe0eU@`~95~e$yz>XIg9}
zIZcDDB$sJZ6Lgv8FJhU;VGDA-4zd+;y^f0yIFG-Vw2>3um*8DaPkQ%1$L>xaa!)Vx
z->6c`>!L5cvqX1}N;oH-?Byh1=-*Lg$3$FucfUv3Pb;0#^!TXj@DY<C3uIMD0hAC<
zfHO{q5QP&Ui=5b?Fq{Csq`Iy^2JqW|wBSKn_|c(6v;`f|^chhg1<dDjf-Mv}k+dxK
zpou7IL!n!VB0I#YA@;)qLWEk#7dsJ+B46x8V1;sZ9y3v7-$CSn6U3q*LB<Jm!EJ`4
z4TM&7{5>G~*bP5G(2lGo7`CIZi3lj6vo?MbaXe1PF*SBNX054OyQ7MK$E4J=8-{|N
zsNV?Dp<|UUF|Gc_UoiMd<qs76gp++*Ijp|LP`R2poW^pro4c6&Chk5?ESEyBn<kYS
z2hWKJgCGje#|ax#=$i9JiP_hQiZky7q(P*Gh-1U;f}6P_+r-g%g5NM0Luq<t#BqxN
zIuA)cS<<7CSahqCKX{6NoNzu2*g*aD2haXcay1tpCu|TSI+Uh|Hi!?zA0ovWnR<?a
z)S>1c6vQ#&zHAD0)ZW^iI-jqGNBh()CmhX6#Z|L}$U`Q^jm$KL*zbDfK@f@)1S(|f
z2^>|BCGCnX<pQ}yGiNH^BUCYRMd|692@eMr!siJ}#Q#c~iirLtwYEa7?di;fZ}Fb4
znTVzA=a_5^(&Z(_hm#U}Q5wn&8P>Uw3=c<}1%0c!-V`c=!AWDS4E-j@o}0uaVCc7V
zKr-~33>h_ow8=yfVK^cX+EOLPZR3QWux*7LGiuuzx2uC;fH{QHWsj(c*=ASYu|{@{
zJ65Ucd7#$!AMlS}V$3#ar<D=fWEro<fPFGh(8sKwBat!NbR-@E4+4YJV3$%^8KLcs
z;`80E?nyblhkH*yXJv$P6aGZy(|4>$e=pGoqf~}<qe@Bdw=R`3Vv)E}Q@k?%VXVjF
zq#DgEF&h*a4sb1Tint{O!EH7vJ|!rMS6RK&#Cr-;oJODL{r@7Jd5uozHLs+cRgGTf
zIp7aTbNdnTH1RJjC2mk%I^rQ9GzV*l0WY!h^Yih!J_lN`HHU8OhylaL22l1&j-w<V
z3VSBZXr!xq-@qfC?)|tJM=Ly(rFH^HF!VADQW;qr30K0w6Yi9|SdPH4=Ta_G`J0Bz
znO_n<_Y{?%cM{j{w0uSp6gw@qD-f=iBkpa}tm6l#&3FvdfFg>moyiPB6+{n4ffKm*
zrl?lL46fG>U=-ns_cS_?j&?02DW{r$4x_)9uJObbY6u*Ka6a+i9R$6XvlMOPI<2tE
zpge*C+^zi$WoqLhO@N~xZp!1piWo`eV}n9m9}3@XGlD5iTE8y>w1(VpK1@#jO^NNE
zX)>9d{X=Oq>SspxP&o0M5>uIJ@tZuK52f>H$TSpAF3L?oLml>xNo_MDZqFPlJb~xJ
zY+)x%YL+(z!(=d^NnH|@Cje(L$qDN6;(hC;V3re53`<LssCO^MKFNtm2pGQgreOUN
zRC=Wi$c-+=t7uYT@mNKZN($AGjDQpi-}P12tTQo(Y1R*g`vB&bC9_w;YswOW{wBq@
zn_%f#y3UDGS@L1)=_DvmU{>SAO+aQYsUjBz-);)S)Y2>bAy7vy%*>#R;YC3++XY9N
zAy~q}A3&T(uw0P@-2EYNj#CzY<Db;h+e*<o!e~~wX1es@CC+<aqO52JLhqvRG^KCm
zk|Jfn3+4?aoL=<pTzsqvLNJEqLR_7)`g@7Xg%qmZYK-@yaOMpeDf(N1Q-)wu4&Yw%
z69wxM?$l2p!PT=1lciVqi$a+ObKW}l+l1TnI#*mc;;(bXJrsx_Zj^Ju-K~xgJy|gK
zIQC;w&s~>W;@ou)<*2fl`EhBUfBU1@N#oLZNts8%b5q6|mon-TJ}+G~KJIy`y&#xW
z=U9Omq28n_D;bUMJL_Dm{gQMwf_I2@5TLwSt)p!+LB~ATIug$HCcbv|;x8a;UDwH2
z<#k=@;`7nV5pL(}zGjD8#ah?ZmbK1Jn-s1)k{hOk(w<~^i_jM0DXCJrEE{{`-Rp$q
z>P=iGp55X7i#^2mUyQ~~O;O(5yKjqn*(`3Cm}Bn=R`a<KAnSQLw#nh8V;KzQk6m(r
zdA%LgK!|M0Wh+Zr9z38pGvzW5nlp1um2e+9S);<#x68DzwHAq!E^A?mX5XxZ?x?h6
zaqB+2G*iZakDBX$6I&Alws#Ba6W&mbKgy`qSoY;QW=y8UlBSDnjmZvU6Ejdzs?L}M
zpId;L+YIG~Y-fwV=)qdO%*HWV$vv2#={6RW5iP%4v7haFcFfqZd)hS*F>?}IC~>R!
z1#c4o(t_FED;z^U8of>Zo-t0Z0nvuu0{l_go#fO;tne{oBJp{W48ps_N#};wg~uss
zCq9__H!<XX4JkgDb0Y|Inm5D;!Gs-iFarsnh{R4jR=7hU-y*~2_Bcrm`2@;qp`B!J
zRqe!tNd(|2$-NiP15`A_$F+nRyPu9?#^gPKcdSi8$RoUSZHlR#n4fvE6Z11Kc4Ctd
z{iTNxC+YpKM9b&-&(QLD{)>Sgd_d;upkv<O2v71oz9Ks1?J;swnwp7$t}|cE0JkoF
zNZ|q^VQrT26pt>*T8VeyNIcm1bnLqz%e>H-2K7J!kl{KDdd@iFo={Q^8Ja%t%RW0<
z=7qoeo0zYBumh0`R1Z^lg7!q8dKLEh%K75i=PMj;`P}WZlk>&2?~E)7fOqpvAwTA>
zzhngwquzdi*|~qT_eqw7K(N70IZy(3kJzNDcKnOTveg19;E6BQknfZ%`z;U$-Vpa-
zq?^xn@e`ZifCZ|T4$Q(&g5yC<goNdTA3*AMxxNx;Vfo+(kjOVYUD;5K>HrApZ%y9X
zKlCtV@?j<H!{D-t_pQeX2L}?%TQB}%b?e371UHAj6?;q9oSjAbcvS-GV#hrbF*fb^
zHpUB>U5<-*^s?jK$Q<U!r4Vo(JN|<a0hIplfvN$+2R#6_?6~r^?j^j?pM0|iSL9!H
zc;*Mexz&~65H3g)dYx({)@%?K6<Kt}0tPn@8!@&c0Yb|=K57kbe|B8Z8dSJ^0mUM8
z0r-N#mT$-xq8~gU#r`{xFB~riOE55!bM!+OgQpfiZE<+a!w3d6FJ>nCI)JqJsEE<?
zYmXhTEMV@=4}yPz5E@i1g`z5m+>7uM1nxD3pg_4rrGo{GO|!0!_vFj5>CtZ#<!e)X
z@{ijRp8M=LDFMxBbU<ndTWZGx3D19aT#y=6qvIXqk&*5A1|ds~(F$>XqGvU{7%B}m
zL7XQiIdGnKe1G_c$hamygdnx!tAiIqEBt$KFXbN4Rm4~!bT!!3*{wY1I=X?qwd2C#
z&ws{9gAd>Tg0xsEnvsJFqH^2uN4fIN17iGK$>*7?$d2;~Op2y3jeH)oqBpdT2=NvU
zD0nTj<Di1qLQ_CU!k?`itZ*bAE(gD$O!a~aLzb3<6*la#gB6DG49AqfLx=P%2P%xD
z!$nYG!ysi-0;Jmt|BeCbnD<vnJN_rYjhmu`0$OegBuezThe&!ri1EnogqKKD7*l4<
zGKD(j+oXltNcY5Ab~$%I`pLb6XnI4y*NwHe%RvJYswnmr9~%uG8V!3<z+SvFGEh}e
zVmal-5vdVOQE~bBXhlbOhb+3>IA9^T+&F-8v%;snc#*WrjRQu5GVec2p@(OLmGk)5
zUH)8-9bOpp@<3~vAV`HGwY~Fxe%I=##SK1U^;w9q>#XiGO1NUc!^JM=3>@Y~Cw0eR
zt^m@Jf^U}x-C{zkxqLWqa_fZ<&y?m-s_Cv{m-_~eXgkV$4>pa#u<0#im%j#%SHr;$
zmm`lbm*N2z3Bpb1Iy2PUaRW_?QuiYsEWrsK|G?9ZbVtuHTnz0ve&QN<yg+V>eiN7J
zw;u(^@(vBQJo26x@}tv^cWC^*(fuu>h2#FVx1t?S&@67@Cgz9w@hyoTY{pm&&X1F4
z#zgBTfYezgPZPM|Z9=8{D3Zt{dc41x)~O(fKlo;9cHB2{v63%JcnrRk{g^qvDaahJ
zF!p>>-4w1M4sg4iH4V!w!xPfMnF8qZ9n}<MzaTZ8+2yQ>yUp=wK?*!mKz}-Hn%%yY
z<Y>T0wu+(Sf=Y&t3#xydR#6IOj>Bc;20I>?IE3Z*!aVJETrO)&;9V!!t+XWJ@2r5M
z+m4fFTqTa{4Dwtu!sidZ3<qzQ_b%EwuDRq^-n(Rlvl5i&z1FI4wYnHQ-p&~fA8+U2
zu+h~yCi8fI;&yO+bnpmmcDz4f;<a{sxp5mfjyrI~W~5b6(9m)C1~<pAb%-O**APd?
z$D16{$6E{`#v2{bP1!l<q|O+!pm;mFupue2N2g^&5Cq4^2RV%GxcDH?@uoDCCz_#u
z*Wlr=ccTG~-DJ`mOZ>?FpX?lWf9xk+_Yf1nl-VSr2E6|wW>AK~0SluI9St*m*zp|#
z4#4b$I|(zPDcT8af=bb{DSl|3U?<m4g0l$){jE|=-CfIJCw9D)5VyhXgha`hyb}@y
z_CDpA@emPgh#@C<##6sRlnD>5+}IAMhLI@ZKz}xgp(uE!^9Qj^Cn^dL^b_9%O1UXd
zF9U0se4Y?|!|cR2;Sqk~oA3mmCqM^}@DuWcN4W0IlSeoso<M=NDV<@427TP8CeQCH
zyor}Ebyb`&v`L(tW+${s)jV)A-F##+rXuu;DIF3aADhA;9TiJ*0+%!_{|Q_ILyw&(
zCD5zGN9$2Q8B@9@2AyF<@gIVT*m35X{jEla0r9F5I`CZsgFcZ?ItGoI>l!lwR<mo+
zCtlA2x1746L3118M6K!k{rU0-zAcW28DbAHHhWNfN-nRn2~&x@&Sn(27BH056EFp*
z=<!OMNMW=|T%M_}(WpA+T!%V+JlQ7H>4--kye)OEm{BDvaZ^HnexvxONDsItND(R@
zJwc^@qxb?<Sve-oP^CNDaj#+l<R!OYu&6S1BYu`0zqtjC`HkYi5E$A&NTVr1zz;>{
zdheYas`FLVdBkXo@!Wmo!y&rLheJ`=SA0n;lN-hW%bE*PLdU%r#*tWoJ6r`?+gly>
z!$@L9V>%QLiV@^!(?4#7i1zkQ;h+>ot|?2y58<7V+~EN!7Dg`v3#Vq)6(Imdc03Um
zjP;;IKs#lT_#uRmF=HR`MQ;T5%T0sCBBsQDgaa{$#Sfu@jLwVz=-lO)lyXA$L0_%9
znm7{Zz1+bqr@N`+4k-I-8Z)Q6t8YyAA+VjUd7yIx&@u1ra4HUkOQ4pq0xJ7Uw^iMh
z)=)Z-AA-odQ`j$~{EgVXg%J?|hq<~Lm?-t3i8>Tc)C8^?SeUzOD5Y1|lU=`u(6p+H
zU4UWU2`;si=F&kcUg=PllB)dpV8BmM9+13aSuYpQ$(zD{xapSq0Rna-QmiskZTveH
z*wHCIM<>#2VxNZ)^8mg;LBDL6dB>ihPsDyr>XLz8v)Vlrw2Kp-*b=LEoY&Y%cU;%l
z$A^NuJoA<YN`wt%46B@mFp9XGUj%#W*<fb7I<miE#?%J7;lXiJ{FZWe<m%PcN>wW&
zXpCs3{ic2%5IQ?TtL^i6n%L!-aAgJMiFm_z$6Y@lWoUBQ2-TIF5;mHv8o!4(3dR(h
zo$t{%B~v!TB*0f}t0x>bWY$gi+%Q!AswYxD?_T`m@-`O{oVvXaHNP$I^FvRp*UIF2
zcLvJ)a^|y~i~^tA=V{IHDa2u62nG92;fK!9*}zQRq<+39g#~}7wD;d*7YXKVh_889
z8v0H#zvH*hWwsJue@6bwHwq63#J<ivW)Eem=Y}%+jYB3+%}K?a%uh!hp9ary$e8e;
zL_@gLpA!x5gYOj19S%l35Q4&nIymlFYU-P!;EC`WXG!X;F$qIbZw+NG_GyMgJroWV
z&iy+lz}?R|aU06-o#fB+Su)kVn<S|f6N)%}pC~DRri6S~La|ab4~LT91fn4imno;S
z$JdLZk~v^VIOGaW@teREz!zFfJ@Ydz)HDr0XxG1~BH+U-(jJ-g;AoFZdQhb~;iD;4
zirk@4MZkAcjt&`?RzsjTX)t`Vdm~8K!+?*H30M`fg?t>fjjwb^X|%}H$9!u+Ab*Dv
zuO}zDb!ne8TE5GD`VAW5cIY3_ikVi0%y8j5nK=Zia@Yx76M+{ZD_v8;mG0v1P&gAf
zjBg4X8d^PWqM_AeLqoH}hNxWP059X{|A)jI7dI0iq$ja=;mtg2qaZz~RTew0gQt;>
zo6~7z;^xFgmYRi*Ru(UN+&D{@y+di>j{9b*D}?^LNnG%y-nroG+-id#yr=P!{R9aN
z#S&W*KO*45AMDw6oeuVlW=PopoP<`e3YOUqf0EVF`HBDHL7~H3feAMra3{rFmbnEJ
zZam)-?L~Z&lHJ3s$mW6>w;}@zX55NQEU+Eoh3VLC_@H#`J9s|&kokuh!Q4cIQ^8EV
zbNcL)Wr?}Rj`fKTLt&l56VPqG+AltDB^Vq}s=7+k8)vG@^ro4rx9tu2*e>H7bG97=
z9-m8&jql+D$*~0TIpi1|`S$Tnp~VrwANj6vESGr2IL1vgzWyld9j?l<nwoW3T2G2Q
z868myQ!c0OSR79a95oeLJQ$drEP1pzo`wbu-&%tq<2Us@;~UP&oi}9t#xe}qzPSv1
z!<jk`5OM4nscC^{j>R9cxzn%>`}$@2erQfV_Hq947~0u|Z1H4_?fp0dJVt%a%Q5_O
zLC$*uR*_@*p_PC12oV<Q^Gd;;cpf*feb4&`zX7KpA?L?=FyVK2-dXVVo~Iaoz3-Lq
z9?rKInrq*y@xde}s-6cNOcV|-A0T#TJr6jTC>)tP+vE=&#OKY5$2*?B9+3F%hN-N4
zj#o}P81&9F8)X~b;-VqG&@(4<QSY1zzUZ8E%Q#K#B&n-K{BYz&{9uPvKHQ%y&DU?B
zBvd}#-_^)8=Zo(?ouzfZZpx5jif~9xThF9a@Xt#sFD0hHiMUqb)%F1;wwh9`)#@dz
zKg<$(9>xvZ30VCKK$o3l%yBB8RLoV6;vA6P=egMDeI9BDf_0n+Z{|YQo48e;(p5v|
zvryGJgD7GlDx%!b3iks{B8r=7aN9cgfXC>PWipf0{&4^X%p}c3ok0m+l!Li*rcM&(
zE~EtxgUZ94IhT2q>yAW^s{`1u?O(+ZrO3qnaX=pyF@z2-#3~=_4JGiU8wS0iOxcui
zRTr$qA~usL467l$lT(7LD3EQw(4U;ilSmmb&eQ#_gGXK|_;hd*Y{$Z-Nx&YXw~|80
z8hn#XQQ(=l{osWRuqKY5Z}S<eumpVKrlA*+P)$rkFW?h%)gNpW6W&wV3`z+w7f-@)
zwGn#D=xQT$m(j6C2r#1?4N+o`lL$z2W*Q&W`EF;8Fe~YYaL5)u&BA5o`9NM$kb*r-
zZsV(aLMhOD$|y{~mvT}H)A2>{I|HH*JE;*COC6~Z1}hCGqKXAT4?BZiC8w5MC_+OJ
zF;jeKgDZ$aNE^L8iWCrfc_0w=E)$%{UI9&=QkNUCsnR62M~6_9M%N6&Fby%p4pehf
zfcR{x6G&9ab2?cRiE}zxDA>0(WLM<1bdv(_iBE+t6^>3dx>G2=_@)G_T^e^IgjG`6
z1DP^!YLsJ+Ab{yPq4?+45S7;yB;6X}s*=f#SX5?-g>!^LxEq}#O6RMd(L16jUu(k&
ztMKuLz_G>%^M+`%Fk86LKuB6sRC?R~4~lGWbZ;mWlyq-UT>VXH0dr2O6WvgJwfS+-
z)`k$j2a#=bQYgf%Sp*I?B_A+^7dzN*L-^r?4>!6c07L!+DW*VXOZp{94#_P6atI;F
z?q4h-xg}TND<Bh?+zDjNlCuB>3w;F?yW0>p+HH6k6ZBz$`mHA!{k(*!lT7GH5fIJ<
zUi1cJ`0&tUG(e&ZuZFHB=+;2hQqBeW>N(bwM?T_{9e)YyIEN9%VNX9Imf6WX-^0{!
zlFB1!*>UGE`7tE=xf>iAbbMcxZ~}B3&L^onqLZ64=@_G*S!9u?>%++sPuB;g^D%lp
zoRsjLj*II|7WD9w6~5C|QAhSg;cUe#O=NEGayQgnvxmE(E|wiC_({Ot>0GFU>u`s-
z(yP-Q;$%~&KZG(}S-0c8WC*urC)s*8I&-mD!l{ZY3QO@xVBYCNsAE1HA0idl0|LFb
z$h#f)Ej0u8EwXM{o=#^q>vSsYTrrcc8vCYSp-yGGN6=yI3DR165Q-leI%D_rE7WbK
z)2$GPa5O|OJZ>s_7Aog7eJhwjI^w<YMJovKQ{$=IVaquQk9*S_nU}C^x_BTQoJB6o
z2c!~CkDMAvy_43rH@ZcFc{&yHxv|sYee#HQIu%xwVv+3PB=#V$2lU~{=bfnccwLNt
zV=TG|&|4$x9pw5AS4TdFI;7#&kqw1dJ)O{qO1CM49f!j#{7(&;HryE&Wjel^+K91J
zweRpblv%vX=dfISy}S3?_9n^F&^vt&&k>EAPR@t7xa!E)*ywVS&zTL2ynL3e(-Sc>
zXrFm-yyN-om3&stk<DN5^QQBnEV7-3{hYLs=)5Q;9L_EI9NF|{l*Wzdd(S2%wG%G!
zvX*wnm{=D>{0$kJ;kEvtLIe~z=QATvP=Tf^O*+RjLr^T1d=ceiZ}hB5v;~G^jr{bj
zGvEX?YD5I|UvLc>ZsMHa3^y^gh?9W?xQ2`^G0z%8Wl2M;$Z!)f;PohRL&3nOPzctM
z7v{uEFy!iS^g_y?s^!yAokBqbr65?uQadr1vUqidvN)$SgIV;8A;;pJs1w#BzD2*-
zVKj@ZX2$2AFi-`7Azg7PP-0*Xtn79vVhjx%j87r`cqB$N!SOv9o<f$T0i$H%@jViw
zd*BG54^ld5;RmBr)YCO%nw+j1z%eK}Yf6?Lffpm9i8^LLlhZQ-nxN$KB`5=3n3Cxd
zI~cjb4r4Ka(vSxOSLjuIL>rtC!d4U*#t_``1dlN~Ln*k74F<oExhCAB9%Rl2B{r9o
z=!<f?XZ##Y3j<^nJsZ$(N>O(#9IcX$W%^MmcF(57{>uUw493jJXC^S=1kYNeI3wOG
z2r=oTJWg_!Sp#8`E@l`iiOiHJVKSoxZ!V)ZSJLT=7?_S`V*?7Lgim=OG~ilimm<{P
z(t8%uz%8A}7e%}w+||*V2ZC2BrqrgiE9#UX;O2=;Wz0#ZMiJUhhw>=z(XWho?G$Ir
z!sE=rhZ<yryPC2UGdCV1dffzWR)k1ZzY)+($L+A^iY)djDvTKy=uoOAl8tah>;w6|
zpSLP9Tig^(8pE9FWMwA6)dTiy@Rd6O;%*AYYwtnjHX)W>=7zy^An!kF<@1l$6x#Nk
za;C<2se^VKf7AljEB>M^?qXv|86JplyaFVmVm-^Dz=&sBNIAVS3L@W?FOs@O7{oK?
z*gf^FWLL)skZ0F`W9!(}GbvRQ7kl9o<@q=vEo~>3Tmtb7B<)@HRuU+Oi7A(`G#7=N
z5|OVJfAgmBFh#s<MD0XFzFl;@s+`qsY@c(u9tw9xMS#$C&Q}EZURg7R7~o4lii@Jo
zU2mY5z#(l{0{*0Z(1+nJXZ0H!ES+x;q`9v7^i4L`H3Cw)*2Fj2T>SPBdvC6*Z&FV0
zdyh@MUz0Gejv~_XoL5i2^XAkL{luE{>WGxnQN+fbG`oo+MbbOg%^oE#213;<G%P3)
zEtYeS0QVkE_LR=?gpl|OQF~J)oEeVyoGgcOs(IAfb}<t%XxsUoNvc;n5fAqq6^C*f
z^6fL@6nNe!S;L56z^C0PpEhFu@bPNES(N^BL5kgSzDH07rR{(E_zzG1*#G^P|MMdU
z4x!Nj6wl8{_Wdva_2ZwPt#_su2cQ4{Rr`PZ%kwI~{`=?okzJ5{wEcmUS9|&6FMoah
zhkyQa`g3}9^_PEs{`Wuq<)3mLfBKjI{$Ky;|M<)Q{QOUUdA1td<}9x^dtN>5#%q85
zXMFs}fB*5{UiEh4@xTA&uTKVCw(b4%@z;-xTU(T4WWUI5<eK<`+duuU|M~y^r@#DP
z!R16#FZtSD{k=ZvG-ln_ioeGu@?(lkgwgs2m;NgKC71u(|MKs|W!+O*_Y~SHxxfA~
z(rZ@p-(`|fs>mdPBsZ6TTgeUFs^UpJe^R0QPbw;S2}kHZFb{RVOntq#{@p*d_NV{;
z<HyII5pA!<?UnmpvDZIZ&3W{{KPAg=ejHvc_ip=|-@n^j9OVs3k@oPtc_m5u2PR+}
zkH>2_yf)Pixc2w=!k??Q!avR>pd@=E_*v3~E&2Nki)x7ZbE+u_(3jPc&-AI4U@iZu
zQVrEol`2)uFDuQ0p8Wq&{N~)(mlzo1@6Ww`f9`9TJI=tEso~3kAr9NA)u;}CSq%uE
zQ%!i>FRK9!d#WkB@R!vPkWSOD0CnG+|NX@9JA1$Uf%(U6{0vUl^REVHaQ9U;5`Iz*
z3f-wTc%k^R8gliVYD(VoWi?<?xB@JHa|Ikt@jG8Y{{9LO(0T@^m?mEi4iA2(nqC0E
ztcD=4r<$U|epQV=uc}7EPpZwZg>VH}{>RjnSDifaoUZ+)zrO+>>H90djNoT*oyzo=
zgKNgYp<1(RbiZ2-;NeqEXyPxc1$g1AR{F2>=5H^Wf4szeZ}#_l+uuKdKK{V|e>;(X
zej4X}W4S8K_Jsz9D&yL?yYQ2r0~v9uG`=r<Sq(Tu&Na*5ob9}0h5yc8{{!cJ1~Bam
zPDr&c2M1@mQ!S5cbiZ3I)la>p`U}0SFp#U(;#=BRl}6m6IsJo|>Tk{d>zt~;v(^8A
zvV+%ljY}EPzSb8xF6xWdz<yt1y83<zOkB^uKAHS>e;rJ)eSEoA?8s+*UETcSTfY1@
ze`m-45$*omK}aZ<^6;y-(S1vQvH6<+jav8}HQ+mJA~yeFQ-u7La*C*-r<w>~RvTeS
zKGj6{vKoS=oN6L`SuLly5uJL6@{L8<ZyP^fgztQy`#4K)13Z+kM`-E3*uLtK@O3pu
zzF)Oa{<>12`mS0ed|hqa+ayZgnEbqf13#br@5rVt#NQ{8gs%sN^eI<8QNFBL0DCzV
z59RBM@a?=Rit=?u_{UroMft{BlpP!H=WFpDt&E9^FHS}IdWb-UTopz6x*}q&T@^+7
zx+22TTopz6vLc}@muL{>Te9J$gHCI!ezh9kyP*IwdmGa1SI&6`3%n|d@^wXc5nL5T
z`MM(TeOE<MzOFdtr?dA^zOx$p^~`>{8sECH;I-}IRFp4=SX28XKM&>Wih#gg6-D{F
zqS;-^OJ7%roK9CA627qp+pxBNz6Rfs71aUR7n>-5J-B#Ly=sy0b+vh)5mEZGLWA+_
zR63NeD<U(+RZ*00%zxWJ$DhytcQmDj2-+8?qI^9>cr#uVMftiS{4lPHqI_Kukg%(w
zC|_5^yW~|-l<%y@j)3~})%XK<99_cRuRK3KK9A&QxBO4<H6nb|WSaB8&5KRWpPy_*
z`Pm4Iy}dV(@Uv>49&JeYnfc?>vkeJ9tM>kI!}50*A^qDt-Q<KQ_1EzF`cl%f;^+4p
zQGRMpDxZ7&r6-)1!Zbhk_)CvCIl*J#tc6?%zPT9NGvr_K?j%N$yY?Dk%D?covOd4$
ztY3P`S)X5W)-S!}te)SWA4vE~HDp$lnW+*7_^m})TciD*Q|S*_ve)OA91?yqxX&*+
z>z7_~79iu7m2~{VgTMrAPSvJxbYE8c^pZ3G*h|j*w|U8#pI>t3FTLc<W>=MFKl`~y
z>Npi5wDi|iO1~<27MU-9{`P7!|H!M&{I_|v8Ed{j2$1j-BR!&TpK7!H!h^s7T>DfT
z`B!@T{E{<%=_O~>N;`c#CDeM^>Hpys82csXcUIsJocIGlrq19j|H8|_fal?<CRfBS
ztHDd+RFm7pSJnDT?++0q{G=LELU09G{^knwt$_b4-hs#^l1rVzb^DdUA+zeK*3vIL
zwDiv^Z~rBYw|_<{^<P3Mb-0IV1>`RFy%pGRJHPV{{Gofm=f|BF<?DxxxBy-i59J$I
zyU}U+%lTi~^p{I`&R(ouq@P;+?`l!}md*e5k@t9<`*M80edi!6aCyF1y+}VXHrwY7
zaFM=aQQx5^ercrN+O8?^>i2#<q@UPh<GyiMJ*4m0M|a4c{3|2v-!adnaAmvLy-2@e
zfxK&q@*NxG4#M_J<DB0aXCy9o<Mxogwk{!!%T@IveaF7EBUahZPoeLqdo&>3%pTI$
zJNIuS$)`j6$H(8a{ww45G5>jwe!F4ESm!Li)mZG$!~XyFsIRx0{@a>mX4@~k^Fn$2
z>HpRAd<D$k*5?1`cjd}NN+lO7doyf;n{JTdXqV%fJVOzhBW@2fev7~pGw_Xb(4G=m
zjGPeHF61zpgU)-%VKfKbTxJAj-30U)uWFm%JqBQ47eo7)?te4~9bAyUXpTuY9;7dt
zgW#WOV2eI?$S^bqQH7CDXb$Qs)4~^WQ@~cZT5Up$V)lt*fS(z!NSjdbgJ=-$+sGX>
z2c27xI%p1h&CTWobk{Jo0USeqpg9!k4mXlH;4g>tKy%RhI3B0xAiisM41gApiC7AA
z&^ZoieCA-#H#qprLASO!V)A(zhf~lTiYgArp*di%oFmwv127Ww%t8O(Il&i0Hq1%B
z=raTNra9>S>;6x3Ft8dNq~?HY8hof`__{tpiII5+3!|dbZ{*>bgP3B#M&{sEWg^(u
z9CYtRBAhuG3jsN9=3vqwq`27xRavM4uHd`&qC{ac(Fsn1^V=o_SMZOUosnL{h3;_*
z`iv3HPWRdsg*dENoZ2r!6nsZ@#t&PFPBS~)YT+<AJ0qHgPvI`3w?HGj2vG=jaZh_b
zV6mAUfx%t}|LhDhfXp(pGm9HC%WOg%9mp)RZ6k0?UdMcb27@1l>RNFD-UKihu4|is
zUK_SnXS^3=m6@F|RZl82JL3f4seX2Z3V@I6E+f7J{9tE~FBOimyBG%p62)u+y6nL=
zA^<Q4%qGN#8P32?Xi<!xgTVog2+Kq6mKlL_o}dIv49p0R=Gi0oN_afaPUKuTMLPj3
z&Tw0somgRHZJC{)Et0luLYx(Afoq0TTnpO+0TkE5RMW|H`-yuIoh}TF4y73hR%U0g
zlT86*a0Jahaz-u5@U5SnQA;u$@@Eg1rVN+;88NgTkYZmYwHYgv#7Nk2W}}B*P7q5C
z7tY5?dsf?0*N{w&$mxuL2AhJO;?SFIsVjSpu1)n5p1+&IAwrlnz6@-N@B22@NDW!|
zBB8h$8)Bn^4WdssCHNR*EGi&SK~4}yZNwkJ0`Z!g;<MVin1VcNUA;!)=S^X+4UF^q
z%qhOh7X>BXF|Dbe?jvaoTagi4WRuuU$nZ_6m_rDuR@KY^bM-V7a;h=)=_X9nVmpvj
zt%}_Vc9j_=Bc{uXgdgliO&vp0HALCigy7cH?+h34*-RZnU^P?6A+Z|$!ZVOTVHVyc
zKYE)|Gi*|<d122BOHM!3oRgQ(DFXJ)##p7B;)>st`oBrd%W+C%L<^dYk?Arb3T;aC
zn?ueuC3@SG;GK&4rUd_44QH^Q)G%aSOYn5hIZ7N2q+P>@k8C(oW~@z#O`Fs&qC#yF
zI}V{&m--D~`%S@s;*6YCAAWY-XA|0kva?#J8mUpj#6lR>sTLp&>jd)=M|hXX7ld7<
zlA94HY*W~7h@2^pqD_e<tOE_ZxT`~R0(n=5<^&S2QdfT6-d?57;Ipq{Ok?e6GUV|t
zv(b=v6{>Oe#5uFJ-&pbpAG6Y_JHx)RDX0+=t5yvSBCA#nExcnl1<^+`;_A&>)$qiu
zRW=N%r7T4mIdCRY4n0BgZ(6y4Hl=wPr(F)gFqyF>BOc+b)O$Cj_!9aTT6Uj>KZev&
znvIMcHM16!Vuq=(ZVKj%I%`Jo$Eg&Bo3c<1!!M9pO7XZUJJilpE{RQvndRSOR+GAh
z3{&!kjBuE<Ce3^?FXAXExNdpwgp81zQ<)HQq?VaVbC3(KU&?Bb5l3_?D?mn0m}v{8
zc;=dF6*A2j5I65Fr1<<9u}!C<?{A9Fx<c)5igT_o`kN9*gt6$X^L1hqe1|b$eue|o
zRDgWiM`uK{e?W@S4fX7jPDze4vb;=1rO&|hPG(?!G9uw_3cDH@QP&s;Mx?JZ0{2dZ
zZ_kmgWe>4wR1kd(&z=z=cq;Yvro<5NS$mA(X^qB$O^6Xt5#AKvvI@1H5#M+!w0bU(
zeGw)735qYIzI-HbnFxuV5qWtk0D4BQmZ@mxIdZi;PD0=I5`RXedIRKRfV>NDO7Lc?
zf%{vev422v=89@TxGB>3rUZNOUYZfKdnyF@lMTg~S%V}qz9weG51)$gosmFgT2?od
zWeED6@l2}#-#OTJN}NN8s6H*L>yTtI^aqrfN{Cg1Y*QTWj7aoTF|)Itm+^r=PTI^U
zNOs1G&$84G<QW5CX9V@13WB{U`$$y`?2Oz1Q?Qwg6a!O1u(Ne9v6qM{w<!@GB_sX8
zrf?P@;R<WSXoh+X`BsKH9k^!}>eEPWu?hH~4R^94bvW{QI05qpAy*XEF5~!$$9aSX
znF<D-k?LfYCRQNe6zn-i_Ugw;I24fPW8we|N;FJvaXG_iVrgfo4D+6m`eqg;FUZKI
zGmBK}$m=l`BsxQe?3fr)if^(=&erUuICCJiW|3m-`FW?F3NsQmZ3-t0Nj6?2l!8kJ
zOv*@PH5tJ<hg9BWa$Vx4I2ErsBb&yiuxCg`#ca+<lrf8x<Co;0%n0X2>^y45NC3A9
z>>7fzWc3W;iI~k#kbDzJdqy(Fsd&se)SXR0PZb+W+A_7KO^Tny@5wr3WtJL@)D)9Z
zlsCb7jVQ_wNP!bsY%_o&42zVJg<|F<-XSeBEyzzsDvFt<Jwvmcildxe_uOS1en>m9
zDGg<}jm$jNH^ircCTC=t*c1*M;!|#<xx&gk6|guX&%?}8kX>t^xr;kUK7}jJ(ET?h
z4xI|YmnD`f1Yf4sTtn{Vu5KXrPGI6(A^LJt-w=JdsqckJhoHt?XDTvrjtkM_q{83C
zjMKWD{aQ6Mt;@R{W0Z>CaP!OOlHDNsvZ)&Gby=UhcSHL!Uz(=E1n0PqK28F2kbQ~?
zoN=d}9u#<&f{}9iz-*Vp8f0HC>N;d!F6tR3PKE)_NT)Cv2l#PPjHloSeg-J&Z*J8~
zI3i(5m{}TnSR0-oVIFadQ`p^2iPeyX4fDrT+}%tY$yDIo3^U4$;-!}uOj5y-o?s^F
z;4sQKB`lp8=?FH7{X!O|rG7&eD#mU`?tz)20s<Y*B$?gfOPY+ay9qwLBvrlng;4=?
zciGo3#W@4R*G$sF!{u-$D&as>%_Jo}G6YOTy>-9EU{qgrgX|P!aZ`fVuAU$|Q)gFx
z>)&Pe1kstKgTrVzlRkDB7H6VeI(G!1-6V7#_Q|Ojwi$T<Cga#<g#DjMS~+6;Z%Q0A
z9S?enW1D+aV80n7luqtp`6mO`?qXa$6|puWqW(n8+8j~uXOe2&ai>gDuRA1YlF>RN
z()}i}U5L<RXxIGT<Qwu+(PlR#j)o)^9Z~A1!p&v?Fs8!I<_JN*3G6r6d^RaMuGnBj
zorgqC689Y<HA!tpZ1$P5u0ROIJ`*+WcvhH625dY$YzmoyL`;d{XER<eW|Gd0xaTv`
zgzZtzcahA5=oyOWni;ZuD5Pud!%H{-5Jr3~>faFn+zD*ezb}9)A5b>`W9joo`0Jsl
zs++Pq9AMp>A4}Hhjzk<|$voXdtc^u=IwC;tGENzUdwx-N3GtlAQbM+jXw931@gX|%
zrl4n!ygU>!H6yO_SjwZ85d--}@*l)SX)Gz=5xRIN@M*>y;!xbvJdlB7lW-s)-tJgZ
zo;^(NSW=x4^LDIy)tRV6Ln_`>$6~<3jAz&3flG6|$qvOW&4|;wDe-X+BX6=t4<cu!
zbw{*Qr{K^Z)l2L&y5AJM$Y;dn9E)1^AV61YcErCN3QD>Ov83h9e#5%zvqOZ)O~DtB
z$c|&l1dXVSn*u}0Xc&R?>e0P~uX}WiKsxp4SRq-YM-NFo6!&A3Vo=nxM~^W{%^n?N
zf|fl729$J00HiP!s5ApsI+oP&vE|`Vl+s=H-7%L&7#7r_D5V)_h%upzk1%Ns1u5N>
zKtD^-9$`8g3QC#*<QR%cnt}Bgh)J3qDKe&XXh2CuL>qlT3g%>~M(E2;L9;WCu7S{g
zyS(@Aq^0`F0JCfoCJJblp}3?Oc$P64ralAEvMCdSe`bt8>iLXy-;{>3p%RV;z*06a
zoOOyD5QbuvW*}3Bf|X_<Q#K{ev1zY@H0EholA|#Ly0S@ZHNL~4$fcVS>sHk&=C=}k
zk`c3XD0XSaA2$W3LDb&_974f|Q%Y<r1W?@+&al^rfB9yg)Q)GvR*_X35R@0?L2>_H
z_UhTuowVWE(VdjxIlROMN8Ix_I4X)USu$2n$gnA6^@I?c(xwBUvI(@tB6#kLgpx1*
zkh1JseV5rLMBI?I+7Ttsrl90p2nDq%;W0p+H@@64=GB7F-k4$w-~T3IHgHCaA@elC
z9gm^!&ySih1k1=ks%%p94W!B@pmRV~HU;M+pema}eK`OtL!hdRkj`UJ6$Tt-4C%rv
zN^BJPoFNodMg;0jVXH0)hqT}YNjRhiFG#}CXy{)MghP7pf*=H*YL}gPX~Dp+j6qHK
z$pEm7Ays(MuS4c($kH*W9={~*5X35nBz~NPKgSjwvQ0yxk0IOiqC1K7=RmrQVKN>8
z>oNq@%Bx|7QlFuOj3I3pdde8bVEs~L#*iw!AozxKVdy?%Kowq)aYG{5@hneJFxilD
za(~Hyw2UExHR9ioA%pcAAp^&N!P<c@Lm;dS<jWY;o)L(D4B4x_*QAHLHNm{J=`}Ii
z`uqV?8C_~HfGPvXt0zd!38#{?(q*lN7Cjglv_SVBo!07-;stOBa#f(fk4|%SftEiy
z&DEQ-*S^zYy$OCh*(7uY0oJKvZ%Pbmq7(xf>Nxv&2IWiv!e#WqHX+~y&?>;HjNZkG
zMJWZNFuIQ3RRz+kca(hYdlMUmX>1xlL|1QoOWdS|Y84X+(bb#!4$;+{dajt+hEk}t
zy{c=-Ho~w9ATXm-=Ps#viJdlZU-ynExMB~%unO+(qno(uV8X;!$MPDp=WS9jQm%%A
zlS0;p7sytu$mm6^jkp4A61#@r6S}Iv^f5X$<r3DB(X%=p+*z4DPwcF$-XR-%R_~CH
zLTMF8y^OFVJRrmpCbqjUhNN~Ewn}KmB|O)6k=!CZ$!Ju23ld0;2DNt+oH=2zN`^da
zq4gFAtc)fIa{*#yG@76b5G$k61YM9fYqY7JAr1qU^?<auV4Lb1H@`N~btpQc(F9#!
z2;3CNoB~VXCb9E^LDB}jDZ%nkLy&-kZxy$V?zy6tTVOyPt&2a1x7L4So!~~_H;l5w
zQ<cUbtCw)f0Jkz)6KfD}t*Kv#x7O5e4TItkW~;zxJX%xN6;s|gB8a!v)O(8wuasp4
z7VOcgddJnT@nT(&`)@Q8&m9~ZjRhqDE2EhhghXp51|iX!kwFMF7?NL_)+WW~GyGt;
zNh9<w$9xy@26@(s`kh_^Qn4Uk<0hd~2sk0K3i3n_^noi~%jy+Zx|Y=|E^sYtY!Hc!
zYWJqZ0;Q{#Px}z!s+72*$w{Ihx96sSJ3KhOC@8t(>e9sH$!ZW>Rgh+M6W9wxTcr`Y
z;4N$*%k>kaXqf$mmN8VpM<YB|0aRwx$$pVDYE#&;Px>aXU)<*ER5!7dLolrpFOjb!
zRj~jH0#<Gc8#3p1Xx<<e1;W~t;8=Nr3Nqr3+BFD>#o9TDkczddYe>b~nRK-PMKgrf
zDtN&iwX1iC#@aQk-E33G4U)e$_8gLV)TXW>K7slw1@f~t^&9uc+9WoBrP(C*+cCtd
zzI%+3VjR!ugTS!INioEVu804dO+uVj337mDoRavPu=P|b*P9gl8ygMoO~ZjDw3?<7
z!Za{p4@j|@X`U{C(QFDkcWGLSdd6+D7W51mv<d7xnv64|ge0x`Hx`30eeOtpzA42a
zHpRgmqtYt9%h4tE=z{F+qf(D9fX8e~wEGm`NJfQKx&+c>RGOs=&@sbkmM%cY3|s0P
zZVp5EuuYn%#@<8E*%Wkzi=-{}<rhhlt-1h`GXxnc1|exuqzyvSV$?73XG4ARa%V$R
z3HfIf!~nw#0l5lrOD_saK943#^(Og5TGwzP`>d<$kbNdmZ4i9`uRK8thx?8n_&01)
zzF+iVQoMnK83J@|N+?_=r5WI}Vf@+*LeHc$V=jhCamIu_!-$*Sq>gHw6^K5oUfK=l
zdj$AyQ+BV9Q(~G;-9qe{sauFXlR6$~nN0w!y#OvV1nDXU(Pz}X0gV|Z{oA22!=!y1
z01v~YePi<uLAnaI{4gooHDL_YwQI=6XDHV7COOB_tSjWBWi<=|X*5h1BnTRoXf4>J
z7zFiiKMZyeV*+qy0M%81n%QOcoFVTmscT#jO*(p<IipBJuP}iY%5xxRHUTJ+0_e;r
zP|*RL*=6<}%QK2}bR4RilHyUU;N%@bhZR4XN1^Sy;P4(rDmqU1QJ|s+3ixpXdkPsU
zFjxV0W)$h;6(Y0@^%NrX*(7!a8CnLqYW{DIFfOixc(DR_%?L>61Cnp?($z6!Xpxp5
z0(cZD`88DYQ9{XoN`(X!>}*qlGim5`cnN0>U@@D*8oX~7YUeeiUy<TnA^ijgE6|BX
zscIO)FSL>eq*%nthF$oTs@b2|EK=X=1pBmOzs49pV8^h&GK5-zE;)*+)ew=65i5>t
z8Kv;f17ypl;IIO+<wfyQ2(>~xc7Y;2gxcDaxbhTf)Zq^?N>-zgX(j%QTVJ6mdsAYz
zl8iPDGEOkAO=(_c$1sEz*SB#s8F{Hu+!Kl7Dy{B9{417Suq%(SySvL%Ki<7%X~?bO
zBvi8cf~(lbQv-*1Q||eKE8P(8s>H4DIYD0vZibtJzHzh5(yI}iZ7AD(0pMli!6(wv
zx)<?r1JE*<SiS(yGO|?Wz_X0p)hNZHpjxFtEGmn9iHrD968QpGtC6KNH;TnfrMW>W
zDu?{0!~mc)w`hUgLN4Z`F*gWC<%};tz6|Az-;@}mKGwj(45W;Ig5sMoLuH07WGH8R
zfxTo?IA%!7Ox5}+Zgm+#dldj*MwS}glb2fj8_Y{%?y-@dA!t_#6Vk|1k2^$SmV(?N
z5)qK90Mardq5A_;@Jc1wK`ukt+e?Q)RQC1)kjtjv;c$~;D`#~Lk(i-u2NGro-&KHw
z89B4#0@Gy9>Kg)4>DmiygG1@r3k--u>Dfy-Z$3`KLDX?YR8*V-Aj=TUs|1i`Bx%wB
zvOGhX)Hlh$HD*#TFr$tnS=*bJaIC-%yD2=YV5{9Eb_98rWZCW^fi?yGgc)g^Ea;mQ
zV~QG(X3BuRDL$T|0pj+Tq@?$b3x&X6g;*CQCNBiL2(?uJc2U;x!bJ8%naK;%)(_7*
zUOJ>%l9mm#{t!T`!1O=Dy!?PPQH?#t57-Her>UV76Dut}+`%6w4gQAVvDj@$JS93Q
z#K(BX@Iq`%(u-3e)+Nc94QKcvv{gZR?U7{5M)K@U3HOZ>d9gPEtRU_6rjQp1za)hk
zuT6t^tH(*fqU_m$nMu;HiJ3{%unCz-vS#xkY$%g=A!H^==>}{jN#`acCQ+RxA|@qb
zCCi4yBxuuk+S_F|>5@}9xC>qk`;z9&?5|z$tb$MueaX6wU=Mvkb&g;VeMxf$7^bf!
z5dkzzUovlxhM;Hqnt_km6!zV{#D3wBut^Psy;8f(p5wdO6wX>lur;aD@lf2CkRh8A
zLzF6w3^{#CR~`ccpsqajpQQrFTlnK7vOB>YEZy;@?qwVacz5p%d|TpSzAt5`EqJ`|
z%6naaeCf)2T@VPRFR9WIEX65&&vJlFSKjLafJ|rR>jI!bUov&i^ePc*z0;Fngp%Mh
zVT4k*0cz<>!WW>HF8J4`G%u62nZb(8+%u$IUsRrF#tKOy0}9hUC3OJ|rZ3sK0fX5T
z@>Ve0vU5l1;7wq^ae_R3=?s_#{tHSmv9fGW^U=tzJq?4&XMBdy=xYbAW(WLZwW<(+
zI3#BC64_{+eOa{;o#jPA=~ZD$#|A{G6P&dP&czh6nkkR_lu<kKB0Gg0``+9Hb{pIG
zMM24j*#+M!0Mu*>dXB5!CU9)SOYAfRVxN=#GX)5mE<jhozxtG(?Wv`mKvpL>3r+h8
zQbVoNPH-m!_MBjk>iCR5lh=irpOVR#olU{%fEnylx;U^leM%XRm3aD;G7hv&pVY;H
zwdullF>!cDDmNw;-(_l*4z<|?^bBB4pVGYntm(phdH!<W9mih1G6n_ZJ8+AA%47{_
zV;7jK0RGsgOx6LBe4NA)6mSfE+mSVW%3=*<O`p=gfvoBCSgZl9=~EVKoCKS~zAg5H
zG;*9Ln-W$CKx;OEog?le;bWUHQ3nUjs?IM|>xIi^7hJ61Jlqtt5%O?KZN{m)DP#@e
zaLReP05{WTQp1pklZNcoy+Fo7|LaQNT>>@pIEh_DAPP2C0HxU!9D|Tzo5G&qXTM44
zI>3#a!0ufT_95{N;Pj^83_=MOjWxlquHXR5yeKFkoGJN&>{GhB657KPBn%M3Z^+aQ
zJ>*3}$!B_WaTQasDZC~u$iAUO@hN#JKKNG&v)ECJ8KhC$TqS#)60>Z8%XDGE3=zls
zP&W7kDMu8SMJ$(HhT*`Vo%W$*@X%mi6qJ0<Xtg%zz?*_LjZ<dg1R`yi#s{%BXtg$X
ze%NJp3$ZqYt~MZK`Y7zGVvi`td;nxNfgM%s5uvLsK^6+yWocK*Y_x&dtVSD{jZe}u
z484xkLCtv+g4cXn#7xs%y(z(b(##=f+9sjv5PgDi8IU!7q~G|1U_Gg8$i9)N`5JIF
zeI)h$l74-u-`KcaNH7D6W>Xr<F0nU({rIi0E2V$|M6)UEB^2H+B$&kow|AjO442^E
zr-lfD*(dsjaO_h(tteqJC>{GyH;|5fXh0zyb6Q3FDa7L@p}2!trX@#J3*=4EVm$!7
zaSHYVpf^s!76bOiN&Ji)f8!K%4+DmiFkd-ro-dNNM9$<pou)Dw=ZnN91@l_roWZ-m
z@&-VSlL9YlVHpY%nJ><$(D4TQl9Sk7NIWO;Tg)LBU$m(XLqIwS^XCH637o!=kWK<m
zAtIeZ7A%H0wFO{ndy$5Et5}FY*FT_vsiBE!WQxxT7JwS3V7mZN<0L%S7$7xHYaqmO
zN#(NKQN-XvK6;7|c&Zw3I8I}4J*J#0m%(4wNezU_N<Jsi5XOf4lfe<!Ddb>aXjOv^
z1Cf(jG&DF4BI^yN?H9?!)5IDO8)Pt$I|=U?22739z|`Whn3!6e-6F0QC%2r%TjZ1%
zD1!mtN#LTSD1!5nIOPS8`kRCqr$%LXD0q=*=45_uCqX&}Ovfn@(*_WZ(_(x8;W!1K
zHb6BmQWBSiY$^Pj!HGU-i9f5X$;Jx#N+>!{xGO(Figl2NwX@L0GDyYp#B|R2(5DVS
zj+1z}I3&j@?BB2#2kXR6l#XS1l5!HlTo@j%f`&P-u@%Qu{}l^7CW^7RgGSBAO5;HA
z{;?@7%AB)C28VcVWOAVBy5y_OE0+OK<0LfP!Cx209sBgCVFi~>r;&lqVRSLjITYT#
ztc+c3>K`5)P6Go2`{8J82wLMLaxkzTMiT=#@SKK|2w^{7q^g>eeDX2F3X0@$i7Bab
zWsxiDbA_^0i2F?fQ*p(z5+cS4>WkZy*DN!NQz7-uC{71Wsb=sI3tHmOS`fg2B@QmG
zTAP3+;8n{kN0EAwWqg#QsQb*(>R>R6&7;f#-Vmg?ADV^S97!xvZXWH;C^xCT8HMJM
zADkJb=D?-P3{rFO;$=X4ct$6(iTLU%v^X~9hecoFz_19^?2Lj`h<-B)(!OwUGDH-L
z3{qgB`go6S2SksP*c-)fpS)xmkT)-ylry6s?R>m2>ruqvWfY`+==ek+C#PYaLXP$!
z9w|rrKoJ~v9WX{I+PnIu7*%!}Gl)^S02tstPJ)~P-p5He2aLkj9RbWJY2^uEo^(oX
z02TnBCur<ya<TQr8%3{h{RX_3lh|0SpOZKcieBOS%_w?%Rr8d*U6(!sR&~>Mxo)wm
zgc?>Uc01t*Rw;J7u6>naH@wpy(6DcH^Q(}%avw0je>TaBnVYsq3RX&HdJkBoWR?qo
zIsC^77(DPkPJ-pnYSf8;a#(y^*(3~$mx2nB+_MIN@RLsC5Gazn^!-Ya+@<eVie!2W
zY)Y(Q(jX|2d(to{mAh1lN~zp+OCZX}Y2*P?S<VFpoR5>hLd6bgOFUGZ@9;0M8e+Lo
z)321u@(b9cU=of2Rv~elBA9OyI+tEwJA2oGQ7LiTP~()i8(t7ijVR&p2b#x8oDT}z
zrrSZKz-@~2Xow=|G%_$Sx$q&dI`Q?jt_~+g*ClZ3<mhxo094yk?6D#xE`0#3;%?fi
zj`m7v+URp<jncG*{nQ#|X_I2#5;>?m+gsxN5^Q9R!c@)zn}qqLrPZR6>4MZKPUSwZ
zNtjMv2O2N0P1k{j%WIQ!o;BWHn<Rdt7?#_>CShTu*f&a82-8MkD%igvn5>h?CdH{-
z0jyD+I?9P{1)ut+8>K0lp)73#FKrT*AknAJ8ii@o^`M0?ZAsl%4ox3)qcC+Jg2+7L
z9M+}YaFMOL2sB<~t1beK_t?602scV#c@9|X7!1~*(zZ^u9paXb0*_OIYxxRTqs*;S
z1EI*3|9~}$+;|DF26<bDhDLc?c@bz7xAHKsMsZum85(7-+zhOt9d<skZ|guY_J<q{
ztic!AY3Q9dWH}jF!wtFWwt#TfPGaASXK<C45K*z6!kt7hEnfp`6w~xIu%4pCt6QfG
zuDS(u%3ygCSf>n@D}i;2V4Uhfim?zlVVxov-UQYugsZL-oieyqoq3&7Se^&gLki3B
zU=y%zykqptRXgWP=S{fkYS1Bi<uqWOmtpx0Sf}Kz2*_?dF1b}|f2T;TQu{kaYRzh!
zBDLnj6fe4PGq4VUT4fCG6sT1fh^~yO=K>K9nJ-cj3ysr>>jGlyJAsXd+=ZvX>(l8F
zsz`fiof6fg;CD(?It^IgveKpos>`WKdiR08jX<VNYC&Mbl$18rFt4U^EwE1EX)@S$
zicixA-yuFtcY+R3mDAAt#5OVM{5@KZf5wbj=g%oLO@SqCP-?onfW@WjRg#82C^F?U
zV1pvl;w*iF7JJyFxDU!qlj1&53t#@A$h3wcw12rC*q{hC>Ggv$)TGxB$WVD781K28
zhBDSqO8bZ_t4U=a6sYnqut9-pM`a%tWsb=>2<hvCGS&=5jG?G+ix&l_#Wz17U*&ON
zgYs2Q2R0~U<#b@9YNRsm56W08D0<7%;s@m`y%22h`f8cz1RE5&@=UNnscX{q2c)h^
zFBp`%;hgY*hW$a!9>yT2aKIG0Ce<DRA)G`L!3fDK{{tHoyz)S>LBUHG1RIpQWt|aH
z@WKgU6MQgoLa;%}D=!2a6usrx{|9Ank^O&A^cLO<#*7lqltIZ0KZM5yg>RAZfAIP%
z-vmR>BqwnOCWkxpelsY3<)C1LH`^kWf6%5Z{{ovSid42IC9C`kY*Mnq!C({Oqbzz2
zm=K~xV5&`uH7`w_QH~Zp2u#XRxhB}87%d2BXNVu;6in5m9HoDPP0G=tCxPk3%2*LL
zX>%?R?2~e~=-M!OQ!Uc|CvU3ZaPWZEf`VgdQmz)en!-ZyN-!xx%eer|%IVdKF)R7h
z1z;+FxSj(hq-c@zumOeQH1tTTa?!<MQq~q0F}f@Z!wgYdbd$iVj+4+Zt;%w5u*r*Q
zIhKFCMg<MiIoQ7}|C18eofvF}w51Qj<CK`)EPWr5rJTeWp}5U5{7;J8d<_2+@;2)R
zFnL?etQ7k#%kn>IQAWanCulKVxkuQ<PuM%{$9bX{i<l+*C#}cyde{^ULdyPvq|Vao
z7bSI;Zod-k^?9HSj-}i$N@+Sn*ve62M-<YzO9U?3iL*5OML{iZ2wN1?@`tbmK^^`O
zY%BIB9U^S;t}BlSTQoUmy#y>u^eiNntq|#1H-JTvF3$)9Lh(h?4Pa4(Ge$wsFhraS
z3-Vch4z?(tvsC#-`Rs4D4@h8L?*)tE87>gELO^G|7Ay+rY`RJ;is-E8f<+0PbthPq
z&~lZq1qmHb*$+tAD|jzhjccX%g4Hl!;X)QgcD$uWOO)AinXpCKo2BtD3SYT9*n+4H
z=Y|I)aHThcMOmA130M@gS(kuCL7Nke6>NolQPL(o7%Ylfc}bX~nw<bho-In+1pQ!9
z&dN)|7R4;xBy7<ZjRZbV(0sIVo!FFMGwI^7c*#w)GVJuEU{h%6ns|qm`$J8TwTW*A
zHBr>c0iq^~+B7gvH6oHaC8laqz}7$!EOqroF$=8C6SP<Yc~aDbB0HxoIpI1|6HUqV
zqj;Q#p>_Nuc4cbn9d}+iSJcD{ZsOJBsfiL>&J;EA`kJa(tmKLJhD`!f!hqF8(VO@l
zP!mP3`%TmYv71b6QtBo<lSH|jc)zHLayOYcpzKX1)<g6%(o#^cF%3m*%OVCSof9q?
zHBmZaR-d57`WJQ2+i@xyEbYzmxu^(){2~c2R1?KI9WOSeMVSMk$d*&ZCV_Qb7HXo*
zPJ9`ti87nc7d1g*r=-cG#7>IoR};myoG@yl*iK1IP-@FHqo(z-;FjSN6?(xYq5CjX
zZvwjy!M@;?QGu{pa?7X*Z<A~BE>Zo+dJ%9%*yTNjC8vuDzpe$Ji<;x#oU5F{7+(x3
zLWnOpQ&hmH)*5OwgSQbVm>LkOC3lMo1l3wYtj6lE#k)g=WLS$=ho?e(EIDRWL{?w&
z%cv24-6;*_i8}1u9xt+I!x;H)P$6;GYN}Gf9d!Tda(gYk8C3W=u2scINYqWii2%gZ
zrr_KHU}{t1p>tCVwa87w{PMk^LUY*^PD6_cHiASd6s1KUiwe)uB_E6G(5SVFn(Y{Z
zKJ$zh;Z0(tfeDY&{(08;Ci=`8-$bWb<D1?oRrreZ3NH#uF=t6EOw1X5DQbq5cdew3
zSM2koeit@6?*J8Q{Bn1S3PpcSMG2~}i@=)H^($@)Yf{y(xK1pg`6}WHtx27|7FZnD
zl!%S%%MvJW6AZQ3PE6pYfLUCFo;7L3ued9{C|=tC(l-eJ)SA%fE6`61aY^@n0Qzak
z!J-2EwB%t?1OK$<P^SeW<VX2bK%ExdDJp<YOD+}FVNOf_6cs3^O<_lfinWC9tEGAg
z-+rkWQPUVJhSb<^1^e=G+$85;pKYn&zp0y$l4~|~)i9u{;~1CzH7omSKBB4-HjF5=
z_X_L6npHgm7PV$o*Kxiqxm?shMXhNXWXIkxcHA*YS?Vj|JFHn$YdCk*$SdMQEV)Wl
z*k~49B`Wd~?J`-J=$U$U1;}a5taf8lubI{E<T_?F9Dn8{K&(y4V*s9<lK7j=ymCQp
zf`9NcRPt&G)25Fb=%b~4;?=U3@TG>W@Np8WKx)z9p@wO4DPwqr`Em_?xxglE3h*_X
zRH7E!4Q%8ZlkGwt4O-+k#b=F)!yhNb0Hk4?d5JxTy0*q(tD({@r53LiH^Ai}yy|$N
z#Vp|!(SVjPa~1fZ<sJ?d(4i#{ho{19zU1OiVOL+HX<i|SM$_;ihy<7OhJ0e1x^9@*
zV69_PtA-9iHL7~<aphjhAzmGQv;?=SKo%``lc;#0SVIbOJYuXN^H~L^Xvt5a;_+k2
zE21Ld-jZKLwF!0&CBH5&;paBVzeajVY(n!Qdx3nDlSIW+&>BT|0E3Vl(u#pNT0+m&
zcu!g*t82(O_)<JhiOrYQJEY#o>K&3#NylqVUcwhzq1`U}NmPJ{HUX_7hSySB@``u0
zC0B_Walcl)06m~Mzw(W!$SS!y)m|i?T*^jXk)3h@Quovv1@;2TCr^nA2+@+K#HRSR
z?Nj|Ci``;Y@)|IsC3IcIGw6b&L<PcV^{K8Q2>YZBr2=5I`c&VB5lU7gz2_1_uht6w
z#+fR}wocWzMku;XIJJU7DZY4yUcGawAlbS!U&O^*ohOAOi&mHB3uMviO&vGfDtc4b
z@yFGhx`t>&y7C&}qa~PK#k2jUz&3!V{Y_!tJ%(7-^}v9nQX_WZ0_N@sQZOT37;vE_
zv|J6e&?ewG0aj>JoWaLQu~O8R5dvr_Ie82~x^Z3LrKlSOfL*<)BbRQyXdV{kx3HJ6
z4=v><-;@|osHF|!uM;`HDLxvS$}8Y6i|NZNATo;px!3Rj4O(4NG>}0{ptcHJ(CRdj
zS3rMW6qH<PXiJ<x`ZcM|2r{~qoxB23v?(|%B3NlO#IDUt>=qZYwovj9x=G6hqG$ys
z<Ozz8u1U)dJke@WvH=!aZKC8Kf{<{PVTLw|ZG?>46gJYlM6Mw-mC}4ug4gpYBV+h#
zT|Gf)Hfqo<L}rr$-5@fXB5GD3hL*CL*9N)Sq(TEmw3^gtM-i<iCAxJEl3Fw%M5{G*
z4$-Pq=M?~=B@|r^2+?Ya5mW&fTCJ+D5u>6Gjj3KrhF%elcmYzk%f7#)9|PXFniOPY
ztY1uZUV#Eyjppx)toP3*H4vOx6Za6D%`|fmoXylV1m{V1Ua{|&U~~2LU92W08{f@p
zP_pr5twx*oruYD9^4^4wD){<4gk+Nv-613!zwW+ykXgHSh`^S_2t*)~lvf~fmk@9j
zXrI-9f`4j&eO60i1Ol+qrd<K`S#@dr5P?ckUOT*%mLPEz$MC9Dy#Z`qb*Zn{-LFpd
zgS%gyXN<V~2_IKGgq<>#R{(mJU~Sc<(JnhDj}v^ltBlqVYMTP)AlsCfyaI5(9KcpP
ze6UxQ#kxbb)h^~B+p5gfJ!D&z!MewB@GRypuN~4((6vp85p|UO>#j0ZJ49%gspCSY
zSju@`0S8)DhH3;0T2<;cf(5Or=cx+l&#F?mp-ycI8-o0+GFw9}dr?r@n_cP6D;y;j
zacC7Tv8zfYhsVXLvRA_`<5^W&dZ36_m68q+(efnd75JegAX^1`Xt|R2fD+@Anm(ci
zd&PB8xzj5Y=p|TN9e}c|Dvcb8C^jWVIO4vj%;=jCtV-V=keKxts0T!5m3?~P!dR)3
zzwRTeN*~94Whps&9mZ`cg&a7cO<~uNnpI}$KnX3Ah7OR>vq|U~mQW>8uLwl60E(-C
z2Q8D9?g*h}3Kvvy*IOnf-MghWj?3c`K(69~xeV$!va&3jr-3-Hlr+5p@8cBAK18O;
zQayOp0D?e$zqEmdU1FLH)d2r2lc5^epCwdW1@>o|VC@wb^<~o6<1W8U>N?WkEQ6gI
ziE@^5s6RFQ@)jX>b@<&9xzH<sI!l<i3TwtPTB*a_@mjqqHX!?y=)A&ivV?c5!0~Jf
z8-_#VCPm9L`QI@E!0;@SiFzh%0;%P0&slbE<P&#Bqs9%R&@x%5!x40uRB(jlSj4)$
z4s~RLT1sucDY02t@=27H8iuoFvQje=$zsy-8XmSwsIwYwxSN7f%$dy8$ZxeQo$*1=
znatF)dWpS4&Y3iDpm1Ikl;VIXQn<q)xr+2{7%f-P*9b@FrS#<$zR=GiQmoGIe`gH{
zxFTH{hT2UbXOMA4F?=fQy{k-=oHKoW2*9%nZPKtIuOj_=BBA*zQm_HbSw%{=BXgEA
zoLAs-mM~@&7@So)k9R<DR*^;>0Gv%=N4NnhFM0(8X8~gN1ZhMqb~Q05Y19*Pu~4Cg
zZ~syr^rw1qyd@-AMf$u|WR;$fghf_qU~*QGKE05;brovV0n%AYg<kRgu>dx!cp%wj
zbd6V(P2pLLr<P4Z-)mQq%8jR*#f<3{@SIhoatAu+aT0&hQHLF8j7J(ao|IP6$Gt*Y
z7I~>xgznlTb_H=+pk(8%YAHo}T^1!w30}2VkzpIyn^k1kMi$CdWY|Wg%2i<34tUNg
z%DP$s&sl`0Re*C=k!c&)oK=##t{6`k(4HW5{D{rOfOJj(JhQU2?7+?}!O-dg;Av%9
zyn&oqnQFJchc0C|uXr(CSvoadRX2qOZ@j&365EAj%d~i}_*6H6<A!8Ig7YUxF$O8;
zD`Z=i(Hk-SR;DVBuzyP_(4XqB)XULkH83xWnanE?FDpxb2H@pILCGgJOJ8nyk6)Q4
z?uJMEB_LSC%l^vLpqmF^+-2BS8q(^%NceNiA}!pT5|c=kyCq1v%ulza@Pt~qs$<wf
zb44k*H?<n25uJvR^VH-m0qVJg+iJ<sVPS<3aJh&92)JCt0EAqYow@;TvY4CPDZv-@
z;+9@QE@yQNA(t~d2J&U)tga#Ua#q){e=1*j3k=K>=BokQ@~oWLGK`x!sbRkWDxrA;
zs%Ht@)l&BoH17ti&`L}ELlmaPULXn6QZEpMKyf`SvUcyXdWo|lEpZQFn3kpum%TLA
zHB#3tLAaVjUUs=x{=|1)3bnWa?y}NU*AR|LR_X?@%SuyyhjdK5OE+L$RvPMgVvvL3
zoEvywN^RaSz9qa@^Ep|ms~L#CL^b$nK*()U!%u=^>cI_2yG3kQ1FR*{Y~3>8zbnyh
z-3V++G+S?quYRK0x*;aeN}*A=9KQ#WxDou48v6~S%qFno?BlEI6*oYoF@GA6i%Y<;
zMubW-u?8uYXtHjvFL@<X4N9>@sP`tt#xybqk)@>MEl!6e)K(*|B^4ck1h%B2zG_Tv
zQBM$Bsj#PtsfCn%oD@SU_(2ROtLNq=4i2}ul+_0w@t4qCjQ|#=D0fOszdq<du%vX=
ziS3oBrZz<Pd6B#{KIU5DDzwU}^yCeA=PBG(%kXyGB=#D@Y*W~;3$snYv4|M+6RpOV
zHrFKDqyZ{33C(Ii%4`CA-XHZ`Q{9Gz45tH8FjLU128hdCLwqf;LG`(n1Xid%Z;GD`
zbJ0S*Nx=&&)XkNXxu{O>a`%a&KHZ?vOvWe-Qt(Ryb%Sa&S6An*J<ZkBb!>?lD$d?o
zK*!A0)O*G_C8Pn4nF4IJ5+!zAxQLY_Dj0zzaHyS5iC<W-R>iA<HHEKkaK@MdVl`xl
z*c2QxNFlK)(QfsBlTW1k*(5Ssu?I~(hk%@dYBlKma}{;$BYWm5>bPR@3p#FC`l8Mo
zHepfU4J%*hRnw5OW3H^uJ3gDNhB{b=GTi(w_9`P_%j1;bCW*fReiHZ_;D(xS1Jq@%
z#AZGIz+ALaH$YwHTw*Rn)|^W-6Jl*DYk7;jE02?Kw&1F}DeOExyg3&;k1ul**t>tc
zb1M5&gMZdkZu5p@GE<1KO$iPqZUK4O6rK;}L*5iH2)n_ifI-+5HYFHDn4U@e*5f4K
zd~^5@_OEHTZb<htC+*e^DS_tf>UGPv88Lw$5Msi4Z{Cz(zI!QT!kkUrlo&}<FYq3k
zN^0JKnwe8yG&~^Zl+FxL%oGZ%MFgH_&MICEywE1yV553bP;y?RM8m{2Cmkvp%wThx
zx~Z5}6LS@_YU(&zWv7VdJUxeb1CnM6vDJX2nUm@`fHZST9}gVOoQ3GN2I$OG>hlKZ
z%oL2P!Mr%9l<UX=<`gwFyhzp|1O?LCl;Ah3*#Ul&Mu4D|b5i}bkbzU$H!QJpN?gNQ
zJE!z-gBY9&sQI5h{=>63ZF*IG{cM!>s{0aJY0PS`yU>69_aFc5BY&jVf8&4u%U>Tr
z!zRp>fBl$o|Cowii?y4IY&Ku43diI@2j`%JK4MYN!Q&Rk#8g^oBrcx{8nt5Grf?|C
z(LFnRMELgEDaU|)o&r3qI3gw?2sy<e5KsS)Q~Vk=d*UzfnJCe0PGRbuddALBq$e|@
zda$q96nd@A@Hm-z&df*@GMn;k<7zk&9%VQ5T98?J*~p$zW>#JrGSZn&zH#NSEW8N(
zVsn92YwF1-m)N_Lxdt=RUCx@k6sq-94!#VF-899f%q7eU(`XFH#gFkRn{^IX;b}@!
z4yWhI{A#b^!FoN7kcey$kOfj98{}FUYB(-Wv#{?cBNO42AuiXr>(0VMBUgKsib`7x
znMDc3BYeecp0b9Ghs{Y#OvZ!i%yE;-NTND3)5s&C>x|qvK2dl#pU5qf8&m>ansW>B
zFm>z9%{!b)35GLL@Ju=6WW;NlN)D2NoS8|f<a^A<R7Q>`_fQ0<t^v6t$B{BtWJE<9
z@;Au9p$$O(^VnIjq}gSUoA)aFze5QciZPoJ6naQ8$-r)oxin1!xlV++&WK1kriKi-
z?U+pzr058DUT-Mi%R}dU4(UA<O*}(&7=zc83=sPmlkrJ25)=%Dz0Oc6$KcH~ulTq(
z1^gg2#c(uZW`>OSwDmrb!*dR#$o?LT?o92G-94imit*s_^?3SnpGpNKE3gFIImD4D
zieM#AuU+Sr8T)xlVIA!td()kI+BfwOCZ&WSa467{CqDLsa#!YKq_t_vx`I?_gGh*-
zZP(|qDuED8;g1sBMkd<jDQ~?LM$(}t^#a{-CuNOREqNwXT$eo`sb>*I7f2O3OtX#L
zmqSmLo=Y=Du1yRu{ua43W9mH9WPQs$SwktjGD0%tn-adngZwzo{X4;5iHv`!6VpEA
zeqRuA=uV;+`*kP4v(WhqKrEvujbua4DWr}=*262a8xk>P4ZAT*ZdQ)b78$~@ragA=
z&gO+ikc@t0rMbg~99dx=3UG%*rm_Mg<w#2Y){zVCO4k%u?2%4>a6o5ALIQ+90*}P~
zJ&+4a=>i6#mCH@545X6li;3tE0Jbj;8amTX#)2;iN>0~Rv*3~Px$~7Uy^j)Xy0UX;
z0GW|310}@McYpjR(n6#bc_Xk{q3d+%!v(%dUCsk#F+EA*6F`9tq6@WOpzn0T+zr<E
zegeCOzS9Ty{9|G7>VkS36rL-jJkkaYIRiu8L1=WREQURm_mW2lUkDlw@7qj=QTH0M
zOefDNZ~7e0lXEEMP2S;tl#0VLT?Ca9!wRF~Q2n<;U-o$-nH7a9UH%jLY>$B`ungOI
zh32LAvV_26g(0F(f&ha%uh8ZecQg;V%D|NhdI+nw89hgZWj15@1>%X#=p@;h^uQPv
zs58;7RXX#ZXp#)oN~z#s5kKA{C+?u7SKz|I*aMBbr!qWtQ;?v>xFNs-8h~~Y`z}_4
zLG}=h&Pk2I_T=N;=%rc}V5Ln)km_oSu@zh}SZ5%ED~cCG{!~TB==9fD@@$I`rXF>N
z->G%FubYCzbw(;RMpqbg-o64QWd>+g@?#qjOGKH3Z7_mQ^feU3N-;FXWLS-<fGdO1
zC5p#?0DdFlp+vir5fVxjiEh!wPJ9f;@44cC(1BlJF(*R6>A}(#-Pbdp{yp9UNFRu^
z&=8J+!2%cwTfqq!#EY+5PdNQAc=<B~1tV+F6TjkJ&t1&nwi^*5@RU(geZsH%cumXu
znGVsHTQmK}8T~FDmq*yMFK=I@hg?fAB<M&>*40X@{N+m;0d<$GjWtZyw?igfkD(D&
zn0DP2(#u5-fAXEgE1=teDzu|_N4N096C@uR(o$e|_<gxA*)F<@bbDiM4=Mj4EHsO;
zy(=`MHRL%!>%>CH><YbTF)>MawKzqS48>@5p=)km4S;|{Gjc}<ApGUEaQPObK=jig
z;b8m)=f+FY8`eJ1#RTa<IeJHz6BbTHbv&9h!MiRvG~uiMTCE7370S^K2F5!tpleW!
zRuxF@g0m8*IRQ8nM*ISI!qFFc(W-KWxNwbxDaKoq2~iwtx{O9n$G`=cOL*H0<wkVR
z0h<vegy(XjM)Dj4mtd37jaHH8fnZJt#x#Wp3RKR1q*v1F3hihqbkhw`A<(4)=pv*@
zF#ars7OGH=mh|2V7yS)q_*-lOAK&RFoMrDk@A`xZ;NhGY6uoF?8rAh^e5}uSx?V{y
zK2VNU(hExlHYdsY3iSw2hw;n>?}w!B`2vS0E531o+v|CXW_Tppn@WG!pc&0o_5N@@
zhv-FuZxnnv;6s5PZx(EidSR0R{n*H5yoQP0!pKQU`rO7{8nbC}rN$p7&DXa%OZ|BL
z!(LmVzy9&MBdnf(X3^XOd$VZ9iX4mPhpd^=ovfMu9m<%=Z{s#*hN<!xGh;e0V`gmO
z+n5OhD2<u?G%jOiOx<P7e6wZhVd=7Ec9<@YF%woY88gF1Nkb;gJlwFe@ryWSObVJ~
z#w@Z@!i?FH44c)Bny`=4j7j6eZN?n$W=wtzFk^1R=7%hpkDD-IjFAnKmWSJp3CoY{
zm{X?E5fAlKU}M=adHBhWS!s|wW=xodWX04IfXtYRa(L{RGV{rfIoL9-n2llEju|r^
zO~Z(3pNyEen8AkWR!v$#p~cTkL;W#g^5yH8F=fk@9aDzQxB@>j6CZI5ncfkNm<s(Q
zBc=@JvSI2NJVwl8)}#@WK+R*s)Q*!4Q<=eO#Qbc)<m=-xU^3i89>vX>s4+ZF{m_H=
zF=NV{Ei)$F5oN~Yqb!Y>&rllCW5v{#lNED(+!jo2HySV%z(^KM?KfI55fni7OXb};
z=1X44pJTry^#0f{`^Rm&q>&Bw%Wci%5-#Sb9?IY9c2i_bh6Ph84rReqT5lOJyX-`=
zU@G0FESM&<B21Wa;*<rm3l4rvn98F}6DHq*Wx`ax@GxPzl@m9UW5NXV?^rOE=9VVR
zXanZUQF)Pq_408WCybu7U@B{>ESN}4>IO{N`oex$3yl>rU@9>4F<>fvr3{!#)(+$5
zz!T(i8!(wORrX8Sy=cIcR{#x|Mw|Xa1E$_>js=rhYh}Px!dV$G2`hvB@^LFCc8Cm^
zeEO9UQvhQbG4*<L88Nl_8myertc;i^4?K;S+IKQyp47@TVhWEbBW9MlQASKzn`OlG
zQt0WATRE{oXu@otOqkSqXu=$+z~&iBx@R*-ieFhUm8(=1%=tGK%#*AaIbB0V_J(A^
zq>c*<rl2ow!IaHT7EGn<g9-DwGZf2)N$ldWVannv8zwX6!hm__t!1`hnJs9-)DyQ%
zn2Ov>3nuJ%i8<Ma@>a-#sm!4;V4j3eiCIujZo!0S3gvL6`Es4yWwKzNG+3_fbb*4x
zewpgAXVQRq(yhpVc@m<^f{Ew@$9&mOx&YZQ6_MarF}nio%8J=#vyl<An>R!YW|zf^
z7R=7%Pqbgkt^61;+sR=l3uZgXhm=P|k;G-g<e_^^nC*nZl@YVa@C+;FNg3f*Og)&x
ziuu9p2o({ZJ*5DaM<&c#X`Q4Evns=1yF%=rOcXiHnpHt>WyCaXMj0{T02e0AFe%bL
z`4%`G#>gvjxmS}B(-;T1Gwp?(q>Krsaw^)kvSAh_tdJ42$gIhve+4-k-LCV5SrL^G
zm>6Bjf?1SI^jI*Jw1*l|#NCY<krh)K=&@p+fV8q=p3tuojs*zM`f(dE^>xXJc_Ni6
z2ImPCnqz}{sLrra(vF!<^j+F9g>XKW%*3d&FkE?bM}-fC8B-21$Bub|9Ttz$CU24r
z>R&Sa(vZ2944*^s@mK?ZaUI(*Vk+R=a~m;F2ss)t<)um^rXY1NVy+37O}Ahome{)q
zQz_Dq4O6bhvSKn42W*%RVo`luhRh-FIvO%h1SlFZBM=jVSHVB^*fHfw>2}N$Ux>C$
z`69`fdBR=MnAv5g`u|%yo1IN|EGy6BDstF8=qCJcPmur#1_&rdhzY1033U%>gt&cP
zdp~PMe0lO@oz9|4s`|Y1jR@P}@c!}IYb%`Dm0YK2CcEzw%Ty+)Lz#wtIFy;c4`n`F
zK!h@z`FV(Bw(0nsBAG7p^h7dE593g#lgAy(JSp2xAkzt04rDriIRcq4nt*HufQNh_
z0-44jKfz3gh8@g&lFk*(bZpqc%!o;1Ag$tXog$gV36hFro>ibIrYFEb%!l^XQOqZ|
zRZ+|*Q&mw+e+&v@W>cRyh-pp(2Qgo1i|;H!(h=XOc}MHKQ{)uHG^d1um`^&HveFzX
z#Xh=La+alom`<2*5Yw4UN^^SW9c5B|!0;2p^alB4<$Ry_Vw}4pm`(Wln-sZQpW+k2
zG|<`+Os&Ir0Ml6i9l#Wbznxg60+Whf_OH>)9lZSZ4qQ6TBa`F%24yR9>5%Cwb}6*-
z6S@>;6GwB3m+=+46xPzQOYZxV(51-;B6j(i#?P<5ecoN)ILyx<?X!1(9P>XIyWEY>
z&4@Nk+rpqwx8QVoMo4f>eI~yRdx9@^q1)KMr?64qs8+lMF*Px|>qz1?Q}TF&LFooj
z9o4~|<^1hHYjir)%?0RpI#BU75*ypfG%zcu9H%Pb9%o|ikj4%V#(Q<)T2KR1CtF{`
zx{ZElSDC!NAn3b75<M}n6<F~=4Mgx}8cqSd=Jd(g6wGkcCz^bgn&U2$D6Gl(Uh(En
zW5nywVLx#7>2kIp+9xM-L0LNO*Z{Db4(iOQ9yx#wX854ksAE2dEWdfa$)PCNoXjzR
zyX&{{Z%ALKS@YI?8o+jMrd{3-_S*H4L@TCTMlLYIDf&E8Ag0;#_^zkO^R6ER;3F$W
zHELJH;^WWgjSI>yqP;FByNGT(%=O!7evY`iKEf3tjcIhuqAI|I{BDu>V(vTkuW6pU
zMUG2XC~MWzAo&9u@O6AZic61g3aIAn^2Q@gXBuo6p}^~$H}C+GSxksWvd=Uh9=Sjh
zlW3iw{u9{y?FmMFXj{ObB8)S;K2Hduw;*0EcE$_R-I@GwQ%IPa_HDyno?Z9|van{a
zI+gnEIm$Tw*2jjjnO#~89`5M^vx0R_*Ov{$eG8&-&SA=PP7^OzI%#pZfi-pg<|v2L
zy4_?{q_}i_vmo1!;N}-QZ^uXCYcUF)j}Rr=f)>q~dLP={9I*7vI{$j0gdj#@z&fde
z(_w-Hq+&vzcZDd1BeN^raS0*+8>J;^QUaU21$r_EEBh=<j|RlvwJ-eOxQoP@Zul(;
zmDhCf*%V2a(=2_7yv%9jKq7T>9+tjDw&x52vzVz8O*)G{Ga=uP&fQRHue1V6icQ0G
zw`dQj`RL}3c+I2)?QX|;of8C(Upkv}k+-08iRO~r8jk$h$z;$Jq5|9S98#h2o$i1V
zG;80MoOfa7z7$sBG_+z1PVnp_`W7dRXGJ%|t8dhxNc(<!7<sgyD%74jz_G@gk{`%|
zo~}>3C2=;{JcY62ZHW#>?$D_ArV=GLoX>G2ovXBHL#?XF?Kvtv8|dq(l!M{sqbvaZ
z@2n8Ct4RFPF}P<lQ&=J^V2d={lVLi?gQ_I6Rj(!v`GV^2LUe{%{OsQx<=$xSR{X9}
z-7rF4A&T{*0DVgLX)$b~5c7DR2_}GPIAA)JV6H9TtQY;=<e&WLL>UEcV!tgpqj^rd
z6N#;_bQ*kv=G}=?qiHvIOJX$VC~YU)M1$8%+<ywWm=flILy$i@?aum?opTVh5YrTb
z3Fe3ig<zs6(6l?gB{?o(KZcoNnhfxDtRAiCnycU@xGrY(mXaWpoGxga5^B6o&+Yfe
z^JsEY0dC28XZ1-4O8qp|GkmP-LuP!|DI&l`iK=NLzy!!}!vORg&djS1YJUqAK%W~s
zwIzE%*B0p~?fgJ9i;Az^BSy!&hHZjcWmZ?ZO7O2tm9R~b7c{Fk4oF-kXL>(?F(j&h
zPFJ~21V*Qe+@^%Oca7UEi9uG+17N=C!nEH*Btm<e9WcRnGsO;=I6a%Sc(ci9?^muE
z%G>OKDaR$s`a*dhYQWtJZDDS}EsFQ9?;Q@HH*_O0`(c|T!X&#*=s&?X^h#L^wQZ1Z
z%BXGEz)h6Zn<{~O9Z`(W-#-EE>9~H%<+RuUegG>e8e{Uzqs`4HxFxZ;Z;d*1xhVw`
zr^d6o*iC{UYMN3o0qUKm6ig(zO;ZYP$r)xb@G5bd`bNH>v&{#%C8vkQ)<rOEP1w_~
zkeoi6CNL55n$QIP2vLLDcI56#r^w_MB;O=}Icf!X#+hFnmd`RYd4n9rVj~3pvRQ0|
zKzlZeZH{0@dqaB$Mo94vLk-Sp9>GMR&S@gSL^aO|kzhLYK4-C~lYsP0@d$1~jLDWr
zMnxA}A{iB3+B4tZLys~l8b-q1j(7dwqEOJq`$?wa$`%QFbRYN<(@U^(OJaHpI@*+l
zTM`4R9%DgGKQO4!z~&!J(EV+RZi50Y#fh;64P1;PDrjJ_6s8glC3~WQ9mWNJb$tO~
zp@WODIh5g@MWMG8m3pU(@h0wgO&8-$baa;F`{0Qi`jDtVJY7{cm3ms9DV*`*Edyx9
zEZ#AwbiCnVdMmi-aq@bF<aF3u2Cr~SVxn--i}wpw!E`(u9NP5-h<4O_UY<|Xd-iTY
z`RM5kwhdl8Bgm#0-J(FIIbSxCBxatz&u<}bsBe|bP3Kf}x)N>zu`;u54cJAe%ity|
zZ_jLVqlj-J52hwmb2irLw^%#KCQN*opi`aMWDMyru1-@J?soL9zb=a2by{x#-$zoF
zel7mO6vfVG_D5b(%qBG4lCuo6DA5uioh>0|zeVwq;;!jn1X)ZKtt=+P1VQffAw@bB
z->(N(82VHkgsGxV%|V!enNKJPcRQZ%5|`hD6H%SH(25@Tqs7RWu85mtiA-0-O<}Ff
z?5`Gk=W8bS>3XIS{eDvVD+=;~Nd{(8Q;W~*qPGby=Z}O|#2&K0RloyVqB}+}{i#+o
zXLg+7D>m~&biP&}mnUr0nf<XI8+NAUN25CvCx%zTHlEJoN!ZU@61{_fB02m}p_@oH
z2dd~MUO>@MpC&Zif-|V(&$*&K6XpOu#0*3DLUe}oB+(!3X)?n^zSm6t;w#!S4g2Vv
zN>0P~e*j|*{_~l1PPYYTEr{?i1!wwoBzijfGua}5d|@VA1dUUtBp#P^yta9c$uHV5
zh6h25x;$A@3Eyx!#WvwTPF2lKE%*tii{>W0&}pi~EeS#b?+c`zOs6btNvQu6w+(s%
zR?ly7y|}Z<svkFeQaAV70+AfBdf?}uPWeh?!%SDw-IDV%Y#lU+>!<7JZcz+}9fd%|
z8)J;FO|lJIJq`K%4ON?L91s+lE}xqSoXq5Hh5`vQWu5D!h`-E~{bY1)lEXn1XA4+5
z-vOYdXjAe#hS*8ejH&h0(7VG&PTqK^J@Jto1AyujGkN2og2faiV~S|m8+DD!rQU8*
zp^Rxt#w`*9g<c;tP|4d)J8IeGb`ucVEn&su44Z@T2Y7GzolL=)BK2zXTCjIDeBT%K
z1->r_&$}I0=oV<;+ulN>D(7@L-7SjVI*i%zja^_j1;fj9dEG?emTTVHE{GdXA9^QZ
z%kvc1O@yAOYwM;SSoZVK>%iO3OuMRXB2Yd}qnHS$PnXC|QMzW{iauV6@;1{Iaub-6
zDFkVvNX|5K;*XH@<vM&JOk77l-wrBtG&1O>1R!?a{`4cqc;03=-jaBQjze@9q3+@_
zhK4pBW8!c{nEoq7F{0wR!izN}W8%za3Tu^m+*KnME7Yl~yPJ_*V2h*U1>fEZI9Qry
zXH0SSG@lf!@6rv9<S1p;$xWPyO@kV?BsvN}zmF>@SGXR9>@vCu5~F$BL+GgJTdnBl
z{p3!BdUg(L;;?Yux91CWY-~k3r<f-(BF7iVIp;95;+907!=km3%1$6l6c-yyiK9ss
z$i@=xe2Wf(d<n*sIC>q%Ca04$@J`5xJ#0M1akofBG%?dK4vghEz(_G5hXF=nKtn7U
zTNESG>1QH+VHg+veL6_!$>E~6Nwwr&6ga2*PFxwJbu7gIMrfens<#QctFhWcds7%t
z^P@`)$U((X7?4jRMqxb7LHVe|cSNkQQBRB2G%5q~*FQp04iPq{sQveq*M}4X7#mZ-
zrH9i3w;&dSErG9jGZ&&*4BiibPYkm<CUDLJ4#z~{#33HX{TBOaGP#|69;^A$>Fbl8
z)1$Zkv`3E!*;rQdW6)ixc|a$_WQ^&+QpU1YALLX71;~XcUbTaW)S?_l&7Wi;F5^k$
zM*vQ^LKLI&Q39}>v3!ycNS@(py*ueBrdOqgwj{=Id*y8{I?Umipa^;8DUC%+5q?FQ
zaqck8W0HU!Z3&<3B&lLr!$YqzrmzoNa(1jSr|ukk+;Fl$f*J3fBn7dJEB2<7>olgz
zBP5EXj%nKfc9fwiy$LMSnBFb|%rsP^_d1domCr6gYYnF^B=Ag1*$RC!rZ<m?-#Uzt
z-J+OJpC|we8?Lx}a=%XZ<O9q|1DVdvNRYyeNdRzG`sVK({>I@7yjv3e<LlppjD#{h
zw~>>kPamMunDznyIt@}YlDafpfcI;j8iKPKm>V)N_;I))6S$@^U7;i$WYaKaIKh-T
z%zTr`6dq=ROrMu9%mkUl3o{NAWa2HpbL9pj@xH)n_(~B5XP83qK%hP%TG8|5DV!`m
zhXudS$(xJs#~Piw*2D1UEs35y++?9{r|tPk4f{d0-bB{TaQ;gI$vvj+`GvB5<pUmN
zJMXj2fS@`AXiNVrO0-xJu}keXv(83#a$n9Zuf%S*MT`(uq+$5sZ}Sk-ik2wUGOur7
z?*r2`72A=t)7Icnv@QUgfKQRxcp-|u$(CO=xZLOj>Tp=U1DF~E^}eJHhc!HUai|J#
z3e`EBR`h*BCAnkcIYL~hIhXTI@K255&v*6H(v)_3>aSOzsG;Pg1SsmAxrs6~gfIm#
z>MK>9$m<AVfR)-3jVE@%af$%%R=gS?DIVz57{(7Q@udwL@oO+X8}a9%Pev(faoCDq
zla4*vz2Kk5kd}s}WejWSbu^sQQWF5EVG!b#fItny5ECe<VOFLL3Thagm;(hhj84oq
zRQO})-(#hj3+=vRs`1fxI|iiaV8+Tnd9xRSxPpW_Jc;2-zFTrS-<|CTx@mx=KlFg;
zJFtv7uua3&d^6alVHVYl<MU41g}Z)qMFKM()G&ZCe>|+=TD}>?(*Vwx!8`3XPE-c)
zv_)CJ>0F}+qaa<lcjphsc!u*}?@*CletZUPKDyIPsRJ-f44VN#jc(rN3<~NaIzMP9
zC0Q>J{n!=n%Qp(LJA?BkDm=QW>p(#b=icQ&K@B4yGa#oSfMX`{ee@?ClVHIB;+XGo
z{?^JE^zF%(M&<SDX;U(+>-uH@Ok2WDqi5A!jd;p%N?<1DGP*7K41Q_!;+27BbaCK(
z0yl@Ck|(1nyUzeKaHSy{-h7jjY&heV#Gssle4{;GANa~qGGsWvCR0^pxEydMqBT?w
zIG?!KFkUf7<m@^kdJG_GOLR$e*QwXQkzN#=p)Lckcp-@wD`lTSBW;PE{UwJTNvz7-
z8OYRq8Llh5C5g*e--JJhivs6_U)fB$kt2rs&W=ZI8iSY<TGJ53EfG=ZF+)NW>G0kR
zQavqAAG#HgVg{Bp3{uQVy0uL|8Qt2ZpIphzf0Fmnr_I!r=|sP-(YzZZJj*sbTQClY
z#cnghyjf1suaUWVA&L$^ECDE3=dfnLOGDVhoI<}6(>*)_DA;x=Ou;Q}q5*apfJ<AV
zw~vA~?r=-C4Qbe6CZT<_=68>RHSRE{d0LuB6l^mBdW&L!7!X@9g4tC!MF$&Dm^mpL
zsvR6e2{8a?t#iQiP$!%ds9`u^roz@}X0}X3Z-?Q8IiZzZJvf7G8m=Ck1Kl*5U`CmP
zwrdDim^q9aO=f<M<GNv>Vdg~d&Fp|?ZbCulQ=n`ZLYRRs4MPYs@TJk@{bvA7LpZ|g
zP)5WMv}FW<X&6VC0WgVF0=?X9R%GerCc}cG)X{8M<Z@aX9%{LHqaY`3OGG1Zj&nZ(
z{yt-?Hano*+7g}_`nQ_hG*@w5$TP?wk_Np%`PS)?pnI#RBF-Hn8gQLv^t+n1mV@wN
z)MDna{Kc?=_7!aLI->o)4O`6MnT83}GgK7A$i*$magknT*8shzWK^`Uj9U;R>VDMt
zLiT~yuA))Q;FpGBiy5AbHwiLIyPC5i5KV&$##cyUNZp?XN?I_*418%g<vkztg_%bJ
zopBujJ2ViEQAJRZ<Az$Q=xZl^Zb=NM3J{vfKtH6-OfBwi#R$ovzpIIFGx}SZ__-*w
z{9;DI+dU}94D@9f=9mvSW>onkyB*9cMPGD5dmF@<f%^<I>1|2$#5+Sl4+l`<3Q6KB
z-AB~cnN~Z5E$SJLYc+Rpp%CLR`Y;1Z8b%;ypipn-m(b*fBxXQL*AUz=15z4QfrJd=
zXc#z{fqT6PWYD=~`7M@s#iN*17<%kMHR4=gg0WozGwPOP{o+_N!xaU#C`f1QV}Lmt
z#b!n6!Pm`WQPjn?6Eg^;QM3mXw6dXwnX1B@0Oz5^iQdKkUm-f5bFsrvP_xDoZb@|S
z_zPv<!2UuZD7i&?v#8kO&l`l~DE_=bAdTYBJL)rE!$lP`JQ5$tX`zIRLWsGbgU#l{
zYZ&EmD9(!-rTMw|!NnE>D_|Hgm@67rsKM)qVo0(YVzIq>gHWf%L^42RU;OD+WH{!^
z%`EIuWHr<vZ@1L|T6Yv%4M2KFF~e;J_q#=W6<~wkRPCX2U%W<WSw77xMDgmq7XWk`
z#d|>&o4mY=dX%W?eRn&yR09dOD7u_HEc{&q2{XIgmS{?ASh%i}oY^f$(Z9z4Y$m{w
zKZ>@3ina|LA?)*~si&e!Pf_HImKd&yoI{a}EEAw|d^KDXIY<4Gk!=-J{8}@AZprCs
zUbIdxqny))DA=J)AT>^d?;jA;06DnZK`&*uqRQ>fb}K3x)cC?2pr&DXVFt1^Kn`Z`
zO3+qah~g3rZqj-04%jy1&@|^gnc2HT*hSY7X)T~FT|POJ#W7qzIm0G43_i?ZgI&Ym
z!;GEwCe%V7W*r~q163N?E(K7fA&#;T1$CFSeHf{ml#BI@A^WE3N_4N<t#2u&R*6cv
zsSrY?6<xEcZbw08tLi9?bA^cU;E@_5m;nhL3BReQ^{|D-I>|P1Tjk08{5<s`6GOvM
ziFlKXosTeE-<~9|>quBvIAp`6h%<iOFrh>K_<e7JGSpYTpJ~U>%&Lq5-e=_7cSWI5
z%^`fu<S(=7K+`<88J3XY(#1I(-{Hc=8Q*w_X(Ho34^=!2(V1nV0W(R0TcW2&VF^7L
z{U)5>7Q~T}p?*2=KOezq9JM5DUIy4Rl0Pc=BFCvlocnzp_BI|)cIGf9FB1+K=JU-Y
zc^=NU7<#|er-ueEw3v~5TW~(AWQ!UY&k$BG6A2pWQL-mkGz`_tgp-D$dYPEhNQ(65
z2ucls@p1=qGK|K{#I^=#ybR1|7>u_i(OtXhy_neU7L6U$h{=IFa*Kxndif+D52N!k
zAw1ad&KFMHZwQW;f%=T(z+FInh5>oGs{~2*tJ~j_aCN!k?7bNFaP|_v<|U@*dOGF<
z_$`XLwH@76=fujj<LViJm!qh{0DpIdBs!~qkI8?^oS?Q|<bUI|Vkq#ljO17yG3X&K
z=p3k>VWyQ#v4?Tnzy`-N?)A_RqNH9FgQzKS<!?dbD!qy+7DCZMZPEFNUGO;f_<_D5
z)X=SuxTA$`f5Sa0Fo@d_Z_K#5ETGTrczghTZmUlLeQuZZ*rK32JfFHyKDWPZj$_^o
ziiw`ad0ieb0uNU;&QY&q+>X8v^pPlQ@<1iIU~v|T=WgaF6^`d2Ys5t})GiCfb2nOt
z%uxgbc>sMKx7DX0Jg!-sh2SxJPUf6#-13Gur03xc+@z5)oJuRk@^DDv&D}PeVIkQP
z%@L~23_V%coZF$bK?L<yWKCe5+bS5i&h_wB_Vdqr3d--!eii7xJNvmPzdP9?6r|_2
zT@9qiK)WqiTouoSOx9StE5{M=FxKvHX`T_<rXDCj9)j+>Z_faX#p9MyJ?3d>_+kLH
zO)YSbk#||xo~Lqh7P#lOOCI2!Zu<7jN&1WA6Sz-bl#R)teYz`G<b(F<uj)s!we;n%
zKBdn#Qz+Z?ysy*bDIf>>vi&_{BwNyG@A16JM(^l+430{c-PMybNQkEf(}7BK7gNq4
zdb)9X*C8;y;~KgS$mdOI8h&0ES6&W~Pd9ikPZVnhyqAG~>^5^2m4doUDQ}|G=&gP2
zS(y3e=m;f;y3u-D(!{PxJH}+o0A$dX08q?8gSLnj2{fp$M(Yg7I|{I%F7RFsT+nqS
zdU9+wec2ud81$}i)xOZaHeUK;IDic5%e%@9HdFcPv(a^j?`Nm$<#~%e`tMDKntpwG
zlc6H+n{>9*|LnP?9!jU+a-QSGtD33G+lA%JfPwllYcyb>zLF4_88lE|-edv|bV_{j
z+`&?2lL2w|P~u)&l;fJLpA;_9<W2?{&xnd)?EN6>`g)uLV0V3a0|7qNmnoNl550(Z
z13uIR8VbqjyKsG(ANOhJeTh+*fF9_fQ^Bn17wtL%aruV6?uPkgAdB53lA9E`@Eg|O
zg2kmz`|K;YdyV1Sg6OZejg{%JwhfAD_c?5Rvj{qjmH8}?-O^)X4ZYcjGb8ZE60Dim
zsny1&xC)fTJ}wLZ>K3pzz#jF<&I0hL&xha~GN(Shx9~OfX}_H!=zTUnyE4iq#CHaF
z+g<57A7E}bcl>V0IKA5}inq;Yw^{H#PwzG$l|B+$XN*P|z&YB57tD)*Zg;8Z46^Cr
zat@228!wnwKP^o`m;`-3d(DEB+5CAK7*n5iN`PqhNi9H%Gj;anGrSSqw@X5)lRoW}
ztien2X0ry}SDfL>AeXwy`!YAdJOjDZ#c!I?gnfFuSyK!CsoOUhlHHjVI^PV}835Fl
z=)s}5uRiU~pzXWMJLRRqg1RJnFKj`%?`Xv#Te;EjE*@R5Ro=|n=y)Rw3pUS|oF0W}
z_upW`g5A^wCM>|6x>;Te##kS*<&>N3={}a9eT;*#{ABdLm<$VGr*7uL5^$$JrXqKR
zGGKkkNGaH?eV7b6%-U}9!h+@7VK2ObQ9MR4^l)qelNc6k>W6jw7y{-nEH@$HEz*#%
z1jg{AF$6~UWMT-2-mru>&;z-6Avx<C=wiXA*lj%<Q($yI8dE^n#p@%AGLVbK&={b(
zkME=S2mH{uOx;X~<;E=P;zHak>!+(GwFd3<qFqPpkLqbe>nj@}MA28*`1`nteVDr(
zPqPn^LIZZ{rbH}aXL|FyPbRkbKB2=$@!LR&kL<S*O8n|Wg%xj=*vx(wy!?aecX#}&
z9*e3EU-UwBzPpkAU{w9XJ%6L>U*E^lXO{vRSCWc*>I)&|@AZY8NJR&0TgV#h#@dzy
zSic)?TT&o=;nF5nG6w$!XjU=7Lbzp&so2aG1r}A=K_&7bhbf-7AP|y-9g09t`bw`O
z3M}g62LS+m>VzIb?H3V$hA4XJo}`Vg*Jy$W*G23Lkf`+<5R}KRlUIURcMYFI7P4N~
zYe1pSzf=K;^?F3S)Fevx;b=oiL1=F{@D}XOosy%x)&_t2^VI|p>PTA5R(zI6qIcVD
zVLuXC*m@XR8=LE_svfp614C`wS}sIVA9J~+s2-76WF50=2?$@vzE%+gL}vgemQj)_
zaXOe$l8F2dDIRqbqRGw<(CLVD*Vy)tNY4&y^i+r>&ah?u^yewSkW}i_*u0WlBH{M5
zFZ$U{;!_B`ADMc#s0v_8!9omwi*_^LQAmMBmx&R4ssA7r`=O(pl11bHY{FT^47>>+
z&=a>}*=N<^jr9cP>8urXAZf8yKOYqxi;NDWzh%|w@v#VAMJiM+^i`0;<x-7{Es!}J
z5ig1pom01hHIP*-xLYaZ66WKP>1IVQN+HOS#qMuRaLG}jRgmB#=rQRB6I^n6x~>kW
zxJQ>ZraJeLuqXl{btLsE%fUKvc>~VPzDz>ZGI{1oB?#hIakHkS`OH<*h@ZJ~G2y1J
zMj_<~X<RrYJTm=cYR=VzrXfG`+coAU+r0#8>dS>HmGI?4#_W;~Sp_p5g4U8<^jJGy
z9?@ch;oS9z_;;-p?RHlIPW7e8$<TLR{rsU3zkjuKp@%m$Wcemr6eBKPi!RM<yCb`_
zO9`a^mM}Qm9eL4Y{Va{n)kip2-@l?+`GRbjWK{}w$>&U+k)FLWT`5`!$RdE%k+C#E
zSRE1H1~985V&)FcDhk9b{ia8Cj;=!Cpc1~6k)hBH69lf|h#CThYC@$_T+UiC+)~nO
z%Z|~N#CV0cE&#NmX3d3!aj1$-)D!M@d5S8LbWUtaQ6&~Q1g?<98fnW9Q#qdIDkFi@
zIuZ@HFp{>^qryO%j&@4mV2*?y6yDpb)Q${{cAVbbK9|_WDyjt3rr&jCAkE%Tk#W(S
zS6Pb8i#BP-AZ%$B*%obhq^i5zoT*WY3J<m6SJavQ);(=KI_?VJ(5@YkOi0Mtj!fh0
z>iJVwNM=RzE?Y1w;`IGOMDIIIdfwavl}9o%yMX>WB3XTf5=NR`*&45^MzS@&h<M$N
zW+>-o)mv1qr&;v^n>!*6e=#tt-m)Tg7_wWxVkDI&qYwn6)cf1J=+doMW=hCXWp}8;
zd!;m#!PuqBo-iD{RM`{<j(s7Dud&%x0{L}B4MF>+nokH=4T4>kDwCqQz<WLSP>iKi
zSrbNWmnv(bnU}i2QTe5uR8hCzBD(E;rOKKJ;LL@rg+yah#V8nFOLf64Z#Gr-#36Z&
zPRXEXw|js=QN7nx*%Q@!O_e=SO-sFHg9}+UFp3_LW?1G#)pk>5It1y`g{*}{3rDs?
zwPRFeJyh>PRn|jwCRnL5A6`|uupUf7TdM4Ws)$RKRZz#XHb=DM2U7Ue;S^BauKp!u
zU%lJZA!Ag8vZYGb8=74zy57+2!l<{1CY^JxXQ@)!uHjv(N<$fGT`F4I?60LtOV`IF
zYN`iUWfC<h>1rpCg5yV|-!xq%UD|GS+||ycq>ZsIagj}(CjDDu3%E*?`mIXq{M=t%
ze2S(?|9%m%wz5B+7CP8`u%$@{LkL@%RB*NL+N6Q&6G&-N!DfXmWR;w{ZR&zFu1R1^
zL*v%u-MvZY8i-w*bZ$+WIyvywdqbljoq1ZegwfcQY|_M4M?j@X6W80%lOnF7fG!PX
z{Hi!7Wo%q`L2aeGC;;1BDQ@}OX`Rs&2bo&ueHGz2OOwVf4#c+5*k#!|Zc^E=s&~@Z
zUqms&qWDyk!Y=da78=`xvZYC37w;EMuD<zTOOyI71IwyW2(EZLfJpz8-qY)nYBm3B
zX{grnL|B{rd>CL$lapWUsx|4_Vu!9t-v$lrxmCYUJN~4Da@D)^sFB&bG$3!O(M(}u
z7aI&+O7vAcFx05|Tnp70jz~9};msEZh&nf+GnwA0{-Cs_1=5wJcz5YimPTQhE@f#L
zcIlxj4Z|*7dT^WLaU-e0;xE3V2A}$e(t>YE*HxZylwk1&(53N;H-Ih&+NHrtmo|$8
zk_#FAd@3%Yx{AN#F2}d{OYU-fi@)UVN|FAQyENPZVwb*^n^D-M%jwMyarU8*OtywU
z1z*y;{G)VWcIddvQOynvccPg`){sPRjHWJq(WJj}RI{4#1!mXxE?o*Q4|iIQYIgO<
zjt+E%wbG>n!?Qp48q$G=U6-ievn8|`meu=^2BgsCbwrHI%6#w(rf0|}&Hj>yyi%2X
zyN-;pIp{K^7De`222QEjUblpyHDa|xn$xv6r6jXMCnI!Zb_{PwM`m)c;zqG#4csoH
zM3Z$+iKioK2#PMz@Qb1gS$n~d%6wG=RX96~>Y)s2!(2SG^>2@R<6_QRLch!FR&=}2
zjF0S9YqZ7Z{GBXQk(8A+r1!G+1L}Sqi5}J!@W`3=xr@L1A!YWeYbp(t{n-z>jf7XX
zh+k-+(owHssM1lUcP&FMqWJtn7ClI|?uRrNl&)n+Z<*7z4D?nqMe`O#$6XbBi=yL3
zc9$W|^^|BG(p+h3c=L`XD{0DAg!;8i`H9JDdMZAhrcUR}RDe49ymg`nUFfh(DMB;A
zmMKM;hSl<vNBJrwD`jXF*upXT5yi5Y(uQeRO>iE+Wv6-m^gc4>Q5tT(MU2-m3GoL-
z8C#y7HQuhLqgY?1ZlzicLNC*C?L#12rWC6gWXqId6)e5X(5q&UEmJ;dYK}!uxuHg;
zmnrpY7TGeTe^aAbbdjvSS@m|S-<$NWAnj$MeUrVEDHk+Vbp4b*HmJQ!>0_hX%am7|
z9K4<3l*aL!ZpDCIAXsYrk)W}Y_oOL}or=RmQz|<Znk*TIIHuHfQp6Q3(UAyd0pjS$
z*c5>!eJNTTT08k5ZYl_U&Pt<4@=KG=mMJeZ`D|@UZ9nyo=lR8B#Y`z>aO-7CC7UC*
zOjNRP>jmz(BhfdrP`|Ib%2L5!L>$~X3cBQjJ_z@+q)iP?-=gT2@#$ruPH#sTmelDM
z#hs*1Z*N3Pj_7S$W=Y4ITDGjvvBC<3B$m^yD8$N4?>#&ksnFZNj-@c~199InMq__u
z;db6WU|RAzZ$%@PoX&v0U&t7aO_(L!dwW+|;fWglUY7Li{RAnNl<lj=wLHq(K?>lk
zN2HrI`re-9AZ>dqEqvF@ruVi;mYmGnR>_i+d235pp_N@_Ti)dD?O@59ydAYzIzx^f
z?h26)lJ&6HL2^UDYBV-vDcpN2Y20^-uVMLM**?s{MaQu+H<21Q+w4^USRa`duvGi)
zpy!fuzh%fQbi3-;g@{gNe!;Np=Pc=U<LAqgUcVg%t@j=6=uf?+*lz_s>g@vR1U~95
zEly?gk7lnoYW$XwRBx$qbJW&bYW!6RJux<)p;sP#WU-p-EiHb#RP!AgcrE!l6}Z<5
zaNLDxKj&R({cP7u6u1?**D?cc1ud|6%sIMSCbzAurDby4%8FaY!dHM?%k;KYi5paT
zM-+W?fo<wAui<A^I_Kik&^cdg4Gmzc!DaH=3N-6gJHFAq?&mbR*W-h$H$~A6h_3<O
zS_Z^duv*K2_zG5QEmyFqY-P)U_;=y@MmuqlMilyREtOKgN6dKhL=8rye~#f)FSNmM
zs@K_MJXIQ|2E1!a^xSxVTf%cEBdmUDlMz<okSg%5kLdhh|6}olP&HoY_zJXZE!RQ^
z+I6i}ylNNApm_CA1%A1VJxuJ&5c--pja<gi*HG4Lx!`%a>3+mfD~W8&5TKgUY2h$b
z;9bjz`3ib#8QxO^y|v7BTS0Fv;P87HfZtle!&gk5WoFx&sDN%}+X_Md61DAhM3c+(
zuyR_w!Z6s5gy$3{+`B{yywDN=z6z~1mq!#jb^(B|2ZOatYFkOiT+`<v6?Up+xO)Ys
zwdV9~WBsl<xosHSi`;-SK8l~uss2;+eR`7!>weAQiR<*%yG8;WvZnWq6yNaz5MK`_
zYZ(x~+cBi!dFqU4$ilDG#8@V}tsu9SYM|Hfsh08Z6~AkNhp*w9T}Pm2hr(UP!&f-0
zmg#eAI=6_wV!wEB@b$QyTcE*C2BU+PO3jib)ccXdSen0NoZ>a3qbo+@O$Bh*G7i21
z?OL<?rE}P}%$!?6b}fMLHQ(oN#vaJ7BVp`B4AujLui(0tf$$Yr*O~&G)ZnsOM#fh_
zT?;bZ{S}g(z5vVbc8+V*o5T={dy^QV_nDkDMDH_ETjxk(7365BCz&y_>wx6iZE0nY
zTua#bN;dy8c799F0HaaP8`o|ksMa$2y}~N6W^}rK{_<7>Bf)|~w^9UYL1?|#0&uA{
zyeXVu+%jan0+w3F<W|s9%b47nVa8a7tyjQO%Otrqpi;{mxfP_;5^lFb3$cceMQX$^
z7s%b+G~$#;qh^gk-IDX+2vl1$;o@cH+<Hha*6`j!MXhC6Z3Wb{#_%<0$uTaPXX1w<
zBQ>vR@pE+I=$<!};*hJdC3}k={`@ICwhobQr7+nV&Amb$4niNb+)Q)BU9KgRp#iv+
zaQrg<wi2^nLyk@@C`{nDSBPSKI-sp(U*b&x1k(~cw}N0=!&^cj?`aM81kg*%z{v``
z)EfTe<4|J@_~N0TS)(WbR^g~wrrWI)z+0x<trW>y1K*{VavHqNLdatc+ZqKOIts0`
z^0FTxv~%`6qCZt5Aw;qGvhP~?!ZNLWQzgMvj;fA?;Z}W1iAifrbn@Fmp$@^qDkMj1
zB#$rD=P**ELY}n7?e~L59qbRB;H_ahgJZrUi7cvmjsmwJ`6e-fo7P#feR+f^)2`#2
zT8KWbzC5>~PP_LQ;7P07IRTyYRdVuFKBCi%fX3?6k4A;|=|{)DaU{2X(@tAH7|dKB
z(P^P8yEle{dh9ks3hJ?AbJY7f4L%#rtXJ3JYXw@gCA{>C=Igd6DvTWqMDZ3(E>e4O
z3Cp6Q_Bs*Q8t3(^`xLfvsK0u1Ur>C87FTH6R<|nymD}o^+|(Kk774JUE#bK+zPI3f
z_r3bD0gqbUW(TOG)$PjwN?Kj$uL>q<b?+aQGuYMT%v2H=y5b`hPP~tVRt&~FPOYaU
zSFTouQ{0itc)Z<IG;8;E0~}?+?Ry=`{sIkft$>i0@vRl`%QClbr9ATLj-6C6Gs|?p
z^?;I=$$l%Cq$RT73L<F>^lWM9p8Rk$boXWyaHQ3f2i_T`eV#xIt)7SvRk$9PA*vM^
z((1`y02;ZASYS(HOwaao;7nVfMTbfTv04E!Ekjl-{FYmyM^Ei6x1Sx}ukot2qS%}K
zB2Zh)Xw?eHX$h=afjKR62%lLoe{ikw*D`<bmYe}LTRSy$z1f2+<;<5Ege$1F1%q$}
z__o`;X~1zSP#+hfGe8GifJ3dOR*cRY7)YqqbTnNXpq*tt;mRfK#tqfph944P>(#u?
zHN4^Gcx?r!xEfnlU>R5Qjs@OvHG4!2&EACZzqTm)>-bAUwKwlst(+F~*zk_cCtMq6
zyQ^tS0u8mAgDnAuTFrYDP^i`H_JD+10a3jW#f$cqbdXTXVAKi@YBfh!0KKk<Q@FN$
ziQ_5YW|sh}724xvM&SwocbQRmOG0CqQFx0++*s3#4PXpwWuiY4TCtFwBvg4@OZ>w1
zyv=2H;R*_BnO?X8f?7?``l|whS}nUPxYRAXD`5n*<Y~aCZb^@pQ*9FBEgEr=elfX3
zYYekM1jO}xUF(6cRzARG3~S{hT|ihX0IJn&7=fQ!!n9sTl;g%4A(le(W(0g{8PQrv
zmRePN$yLvWx2jIAD_i2K^L5ebUiDrA_J39HC8A_s2Bp?uZC};9Nyi!xmvCjDU)7Eh
zx?l+}8ltm$O(tA>wAf9^o>-<9uB2Ej5UaIwUcAgKTuIhgVivA-eRW(M%hEO;+%+U&
z2_Afb1%d?#?oQAk3oPyyJdoh-f#49_U4y&3Yj6wh-;$i1d+t5&H}l)s?ds~T?y8#k
z<9TMgVcTXc&Jb=|l-mdZlYv4dMCs)o`N=@`)4YW-FK_vJvQX&7X(ALye&5w07-j@*
z3P!zfM;<K;Mb%x1@l6qb`U!k={q{$Ch;Y7Z5I1Nt59CvaUu~UV=~QO~|9LMDyl$Gs
z)du9Vrjpy$FhVYh=&#JXz{hP;J^SiIP@h*F9m-V94=j2P)<J_l5H#7Rd-6>mQu{md
z76q?|i5vaopBqf<J^B3d;iW&PnHt)wk|AQY0p~)HwKYbSZxcgj+&q!8i_AGPEk&8>
z&x|ROjE^kQFR#Q+I$-4JOEgmWxub(VR0ca2wp6N~l@7g;AU)FfZnaOE{9|*oLzZy3
zP-V~1d;a<rcM36PKS6p=n7)OAno&YY4W_;GyNYuuTE|i(bYacR&D7Q)&ad7`%!@8a
zPa7_mx7O^7R}GT_)$Vad0>4lDqm)cWw0}X!s|*e<{0QS*N&@d__MB-A)qEGS@9iLv
zI%=%OQJ5LPWJfxM6SsB#ZT+KdA;NprW6X3{@%(8;5|gD?@)1EW;~0+Gn|JwKdqRvk
zD$-m!D{z{h8dZH%(Z<a%UX_5mcL|l5B0f={xD)VjBh18Zf8IrDD_k9bX`g%*n)bFa
zpRZGht<EU!3Cz^1bU?26k_OcWSjKFfO5|511uA<({WoJ}^zgK1Qt@Urys<9+)$0XF
z^}z9`bGWKh8{Jiu{7-~(^SKIubQ(31=`Pm?8A}0@jQm%KpDNL#3tLK5S$7o>{VD?o
z?Tpw<D5>=f6mZmrRr;jc9aiN@VKf6Ynb&mb$5}MfNuS`nsagUGYwOU@*(7X99pg>C
zll#c=W}+VKW{${SX}k62NRb|E2}hS3Yw6e|ea|Yc{Bz9RzATJ--}@O<byKN$_6kVV
zh;_Ik{hT2TO{MKc8tR)|aO~>q8_2drnq~QbUqIbJV7WB#YuuH8HSMQqzVb8+jKsnu
zCPqCYdX~JH<XkQ8Y>k;x&CoK{su`Qmx>)k^7`*ZrlzyEU;mVl&P0naKlWA13Da&1I
zHdoCBcjSDvs<>9cl~@)Sd*kyJbY%^CJ6t>2r)nVUCR^eF6RA~kJ8%NpGgnJk&JB5c
zsZ}E5chezWuI35bHLcy1WgiPti&W3gu{Rs0a5$Dsjx(Hxk}#Re$)-}ZG-t$^l-0Fo
zTv%dW7ieZ0r(q2wXnCtyNbu$+HFHn}s*oyba<l1*j;jt%sFhiLU%3G$Rdrt7Rz?ax
zPg-F<sw9}605(*?)oJL<6v3cOwk2x8Ta<|8oFzmUZeUd}#U9<gfvIVa*CL`Fh-vuj
z)u16!*!UD9y6`<~m9L7=OBvb7d;nLKztxlQE=hh&e&_rcH)8ZU)2t$^C+UST1*a<(
zT0Ma&dHsDXlTVey`jmSeV2d<+mL6JJ34$Ha(m&i!V^x_}PiUW7$kXZi51z+7>w;0Q
zjBG@=R?+lHgzisEh>U?~VjAR3w>3}6nISlJ6)_yR9TQYag%d=uZZ9<paa<z5CY$?i
zDYkib#tCiJiaaNy&O>K30>@p6E@82p9gCfdF+NUsYTfa)yEx|O(hdzP|JAeoP*wB%
z{mu{$Q02n2lY;04JbXLJ1Jp!rDhH}(Gts;#*r${qh(i<)G&5b0JCY*FLdm|Y+q0u~
z7Dt<ipff|hK%7Dd!$jnA=GGoB2BIo7c9kH#%263JtRFfao3y5DI;32Mj0ys?r48-V
z4Rf0^@ue<OgY`88t0qnYjC_dC-M(n&dS7UXwu9cJi3#1D-cELoA=Kc0I(wb&h){>J
zxWlJIl+59Z<v@1liq(wbmy8u+2XF1*<U}T?vOLM?U*yo7JY4PMIf>AFdQg$RJInu+
z>ze~w{i2uP!p|2Ptu0zk?%EE710goU2qASHv9pS|Y;8oq9o5?L&X?Lqsg^w+Md?@=
zspoZ#9F*fP(cFg`tmU(5O<M&MylYXAsE~eCDaco&ds9ze`?%MlAcB#8Fb0UM6vr=^
zKotbd&#+lI1+&lr7Cw^Da))RwI$*)4RpfF?bG+u&r0lHPd=p*X2+Iidw{iEIqS26x
zeKj9TcJT`Dm^v$F#M2BC=<Xj`P1<&h17MRj#`iccO2*j>Dqv%0artN)hH8_{#zwhh
z_^9~<d#r_21~-^VzztLj&D>8vJT;jW%9mS{CJpqIitidu9%C6p((1Lc2G*?546)U$
zY|0{W-ip$EBrTvuPlD+DAQT<eYLgQ1p|f*fzV|<tT~j1wSD#|XbO@r3OBU1XlxdSE
z&0dUXr+klPiK4q&O6c@u@V(q%*4P4L0687<2#X3$L)MK{ds4Dg7ZoGJBIKJXJPQY+
ziiLX5nEC{D!?@P<cizTA58Dd;V_4tBY(vZG3%u@ag7hu-jVB{^+yF+R*GwNM;<l=V
zk{F2`^1iM4c@Q`?cxcS9slIEOxx>WZQj4u$Y^_ZE6lE#cAZNu^qB5{yfrModS!)A*
z(J(g{v3H^$Y)0PoA#u2O|9l;nuU<DN_lXly`0etbn)8S7<b%Z~l&vnhw-6reT<*dt
zZ*iG6G16y>n&}RBc{WnKDk~ob>GtK;-^;FWRb_UnR1Dh79g=X{9{)J~D%hYedx-7J
z9_oAlsWZvW)o7Ar1b?x_yDIUAmL;Glw7oij+~o_5EeE{5>+|nA4oC?gY_&1KnCOvl
zqC+hXAdy<T>8U~{T{wh(oBedY9eajNQr~Nl&Cz_fqLNc7-b_{#qrLyf_y~l4V{Ft|
z0$}xYaz+_q?z3y|9h6w^O6jMm@etRGP9TukiBHm6NyREw1D6F9c0`l}e+o1%1qy}{
zD4c8G9m54Db{c}b6vhlYF^I?6SIY<#4K|hSmd0J5dyORp;(^lJ#ab^rAvTF~v?-jM
z`z~U5gPLq1FOxvS0a|jyiTl1)#bcAfsYo(X^DVps5I(FQki^(a0rwj$wd<;f8@Y!y
zO;pUlX#exXBwGGD&+B?CPtW}cH&3R!`v-xzhdu%Al=IDIPqyZ)Hlmx_3Cyl_kkR#d
zj%UMt$I`>V9p}ZSp6B(=Zu9L#%Kht!W3`7<&-;VohuxI>{j=hG`+d2beV6;-*M%O3
z^;7p(Lzm}d4+GT?XSJ3~eD@d44{I@8&63-0<`0*Q4nN`XU=I1}1g2NqP+1=e+C0w=
zp_`oF?+V-vZEdaVfY;AmR*iiQS<SAvngw=pB|p~X)ay*i9$xu{zCg`NaXJ-vsQ26t
zo#ab%kTZN&-+f~2w~$gRBd}*IVOX4(;%AVkyS>%fQY280aDS#-eXjPfNp`<7cTlGG
zee{*M`_Rs2n5sZf*+b2cURhmVEAK-Zlc!~T)7{c;H76CAQ-Si54KE^v;k$qtbyWZ-
z|Dgr57e@2tvF6Q}ow)P*<h#32xWf5jhM#khwVIA{o)4`hfjU#*;ItH7!nb|JeU`kR
zQ*<23PEH+2d<2}{z2CVbwA9=4+^3o+y90HG=?Yz;>9h_UADKC8f2I>4BU^u4j5bhq
zaf0@7bK6~Sz;i3W#p9u!_hA^%Mk>W=<@8e5jbx7VCOIzRAu`UJ?fz-n!bwWV5hY1u
zan$mV7E;MwZNK<MiVl*}rd>iVkEbgM74I40_<cv5b&E`MIenI{=MyxgLlUiAPebeV
zGv2t38;-iA#^9vhP2gtq!(N$$1+Fgj_mo=n3`whH*0OtU(XP!z_EB`Hi~D1>qy76c
zPL>sQSEQ*MG7>HNVkyka!yEyD%IFldZ{BxfQnsGZU5Qd|t^)c#6a|bv%t~8zUXT@^
zS$TffAbVEeERTEZ_Wt8u!zM6i_wE#!$~6S0xQoaU{BWaX^kN=5YLNCx@i}vocj<~x
z^9j<u&vQ?h31=kZy-v9&VwXp?{Z9e}8iN6sb_p4)0`=x<S+kS5%#ZUH?Z9vJ&hhDG
zZuC~_|Ka5LrMU%Wr_qhGM(4hJ*{g>?E&=U4C(hmK=edC4v7>tR*FNdCv#~y|wx6U&
z36sT*-tNxFJWDOQ>rZ$wgQ&KRk;rGh7Ne0#+;5UPlBR>CG|%kZAGo3($W%0ZoDU`@
z;<j==O0V^e58wK&?6byrEG`dqT~s%hMS%Sqb+p|BJYKgd#a-^gIR|*?W!BqYTnkg&
zWo`5ZY<y_sPfrQ02){pSI>otb73Z9@k@7Umydx6T_|DK!cY}LppP8xDSX{AA)ag=2
z@G#7^SsaW97^|-i+saupU)OG8g7&VLNu#B8f6H`A|3e3U<njReKd`IbyAbLt%dz{<
zR?W2^=63|N9<V--vihTfEe-ALZNYjLkH4(+O;I@jEP%&v0002u27);L$l3mq^YT7c
zF^f3ciz(Ub*@FSU1&=a47H9#$EG!6M1uz@vL9hJ$kIKKV%%WD7_W#f}Vq{@t0f3<0
zD*mMe)%$A@z`u<Fn3Y|u!2o7?J!3F{3c&iyxV)Y%7}^)>pSH|0U_*$Wkd-q)6Dnc>
zaBy=2SfQ(n1GIms3quV<_3Z%ce>V`bwQ{ij$6$UN`6Yd90zH_Opr&p0EbXixjTyN7
z5laB<Z5_aWO2SaBw_rzz0a#H?=u!CBTou7~Rt~lXU_0n5zK;|9&(t`f<wyTMdP*8>
zX>4x-;QD)5q7ZX?uq}XD)Ew&Bw_pP+!(W#EQe*{i0=Yqtef<?O=cIl04{rDqjRM9V
zoBezJdj>}3q(7%ANh7JSUZ9|$ASkP1Z>R+0hQBxX*zQjo_dYxa-!~Hb4LqDen^}w(
zF+&IrIjm_Vz@K~~c9~I4BhO2pG{RNETw3<}3x@jaP3gnp(4E^s|5vt6caNdN!z8L`
z?DPmQg1_f=0R&7|xNyxQ6pV!&ku96TIVJZZ0QydTIvKfgbSxjQ*<h**8_KbM@}A3O
zsb7{zZwq#;ZU=V{+lxfi)uVX_+#Am@i(0ml@1@%BB*Zhl&(=xGe=x;Yw%(&oKGAEu
zES(w4!LgnHd={e4oWNlrNTNwM^!>V8{UVO<UVesUqgZ{9Km<8OkW%rLsXAS;uqgp9
zUPbw#|Lyb2<1AbX60y12C%74fjfH${t<vo90Y>_C6v-Rdb1n+ww1Za7u3EAb(b2<p
zqlys3BE16|O-fM|w!yFHas$v^XQ^YwOSOrz2pnkP6oruU*K$hN0dk0I-{7Aiw6OYk
z75Q@c<tUp@`O8(Y){k-V6bUjDPc75dcuKOBIyG}-mh8u7?7uTwd=qJtwjX=W;H2}T
zCO`@QW3oKDM|ue-M)odcaxk^uIu0<UfLfArU+Q|eDO`$XxPIS>hk8u$8bKR@J~zW3
zKbIY+Y{1+qGQp7ghZh6oE8F(%F`Bv;%ie=0!?OvEn!YB-IQS$~nsr0vwjO?&k!8y;
zt0BX$#(hye-$Gx!&m}d~?QSNAG&W4uQ!tJa3AW(v@2+vWElbF6uxHq52~(D>qLim=
z6g(3-*0JFHutCl#dgGT*G#etvOu91lw#h`EF(4(DWk5HwTO21OM+Zx4Z-Iu2=BttM
z#t-zJvA7?n_>r!Cl7kl0y$vr&J{3dPX2*_u!Np&`yztKIh1FuM(?hle&)1a8A8Q*l
zr~+B%#(;2Z`vtNlRD@9U{=D4#nQZNozFs1li<!-fhpOWqKEf1^ZyBZCIbr5#*>Ahr
zg`$VngX5FRaXN#3h>CTWe~k!#i!PI%SR4myo79n7-J<{Vo>WUHzOU-MdQr$j-eCWo
zTExl=zhh?ndqj&PlJ4fLssagfsGAw|gDxAUdrkas2nY1l87>B>PS$Dkdkr?PW1|AM
zHdy-%;%*$H7D}n}n7uk<qNI?PL?2Yp1Eo!3P8~NdZLjUmE65tPj-!;&2rFf3-|}S~
zgb}Lk?(S}moe3NBaT<9H_(#w@G19(13v-I?2x#^_yJh_;KwzOv@jcZE!8aa%RgR7_
za~9W-EF2+^)MD+a7GgIA)pv5geKDT7;*%-DA6VS8n{Y%?fk-royfon!FVlQN37CgJ
zFJ>6<?C!j~+R7ezp0gXUffr+<HbHBZeEL%2J2Lk=HTjL}#VqZ_X5f<)PEhaG+n%%p
zt(sX&t-;JjsxfP0<60SE$)1<lf|0J8wG~EvlZBUab!R+zfo4nYG(`$An?b5JxJvW`
zole*Tm;ts5<gX9|KQUznZH*BQRR{K%)6r8i)lqXPmP+JFXeH*F`PL+52h}{wUJxt@
z8%x_xTo`w-@D*0WNI#Lh%u*6C=X&la6XQLt)t^Ng>&ss8L~|P7UP?MvTYcljnplS>
zdRl)!FWccKiVSVys@-kZ1kVxrK41hra0T=ZQ7m(^Pme3|8Fwh_?7}QUm$E}1NGac*
z!Oq;ehQsIW)_f6<gBtTr47$;gPNLYwv_TSU5q_j}6qUfq3A<+A)8WW7!w-QJ3ke55
zzkHOy9EbqEqb5t=*r`1y59KxfN<Y?+i~x~G6$(dmk;i-`IEU;I?HFeeY!^&#LKyyG
zi*J;&+xW_@j8`JTyk4$R?n|az8PRJr?JFZX#uy`$FfKA1f-gZ9Xh~>VDu$JHin@?u
zTV?KiE#_}uPG!zDj0^K+i^~sf4s1B$55H{oTb_`!TOVZdS@I{1n#UMPky4wx*|r(1
zp_Sovlu(?)UbjS$95UrS*H&nuwzu@{5})??oOZ|bR(r?Z@JQA&os9)AUf-Q70~b*#
z@|)$V_<%Bpsk^;QDP10<oQ{IsPr-<yd3E$G(lBbDb9}pOey#+_R-k@G-O<Z;znC$D
z{&rJGAa&fcNVCpe$3QwrPp2@<k)HIMjQ$0kQiY<$3+?tFbas_FGq(GPRmprgy!nM=
zjw5Q*%+s>q&xE6HPgw?4WWr#XFY;JjpPsJ3a%f-hd>Z8??tem8Yx?!;HZi=@PlX+I
zzAakHC`g(z@<mz`s)BCRgb?2n>s+Z9lY@CSX$)V5EX2CukZW_x(NLXLNK%pRUjDw|
zEwAM6kpIWkWs>VU=Ua4{3`jxEuGZ9Cg+y>{r(}daW})bFd#6-Pelc`~?&(yeSWrX`
zF@{eVLhXP_{jduxm3<{2eUyfN@=qy!3PI)1A=C1oek_yweMe5G#{T$J(MSKAV5Rgz
zQJ#nwi@wOK1os(-+N@omfcBD2;zgysM>sZdA0b|pArfC%5w_B2N#iJ2^$|m@bJ^;V
zfQYfcFKTmPRml}E`<rh4_i=C;)8T3LbBKrr&owSdX3#pRgSV?UHh%m_d!i<ae)OHc
zdgiB*8U_8L=Ii7W7NdQU{zRV}5o|0H!c%X_7KshXoLbe4&wMhDpG{A;@F+=Z$IQId
zbcPnU4#ehUIG=Vl%`8?o)VTO2Sh&6{eDldK^BGO#=;s3q*PlHy0#>F^uV(SAnx&R<
zo@8ljk5yTDmdk3~YHv-9ZmYeo7HNBysYf@uOkPSH5fu=ZM^L3Qe}lR);OI)5H?v@<
zyBl;S2`UZ=j+!r0XkrO}fzd^QCe7@-wm)Irf{~38MjwRM;g0P@6^cdEwrvfmadKuj
z%rTq>j(g0SLzlacHTq!Ol_z2+Z@SoSP5EL^B=L^$*2ox#ib2wkao@b6`bE6U?e}dm
z-d9C|YwU$5czNs+JZcjlo~$R?O)hT3sg2urTiAIc$gdS|SGMeK&MnKGUmfxf4b9`D
zfoglQzp7*J_kJ=d*6Z*Y{9^F^tdLa>B`Sh=kbI+HE8Y5>AuIic;khJ{zshR7vzYRz
zpId_oE>TBLdO&D4D|>8c5#B|Rg?@ca%H+tC;{}q*W5H;v<UK(RH$!ojr-}PamE67c
zlN0ziTI@FUhk<2%Rq;Hm=henwZH&(?Xy0_#rZ@WUI*$8Rg^#^#QN@g`)Vs!k%$c%6
zR5{CO^rTEpw|nKxnz_3PX~m5E5_R=*Odb{{cID9{KWB^?<1;@<We2paYPw;`(a(g8
z%LD6gc%O+i=7bOVRCDb`Dy76@TPabAe2EXo77!X+!;6no9)9&B_efQQ<4Xbeuwju*
z$keH?y5BshncXXp+@V5ltXxH<?wkG14ee@VVK?`g%j>cmBuDP%H(W}sE_#QekwOp!
z>sYyyZT=e=_COC;fg2Wwc#t%i(bQdg*a(%1)WjGCke6ifw0rz=+?U-`L*G`?Pc=<#
zn*Nz3S{jwaq~Y_uWf+>87B3TjZ}p>6E)FUR3+Gw6(b#N8Da|-S$@)k_KWz5Tt{>dS
z@e;84QF<jfQxMpOKiVN}q;Iw+qSWW8s_@m=T#h79c?g_!8)S85GwR+9e_j5%`EdGW
z)ZP4YaeUmzXF2|@@im%?<~a>jV?vaY^H9yL7ro2aPmAKti}o<litp_0On5^A5ul!N
zl%;j8{K%YnPzuQRx_jSpx5ijKRgPh}*)n`ZJyec*Aq86@WEoBbhttI=3<9d!<NLYW
z$hi7!c1gr0H08i;wKrEu?Y+!qSjW3#a+#bSLJXQC4<MTx(hV@)l&!X(Kq;0xKA4Tp
z4Y$$;#p_lmh8tXlk*i+^_9yndr@Afq(u&z;J!S$g6*S~Z*-JS=NSF0fdG0-399G!^
z)k2ThEVTrd)Jf)*n_oqs+8jvoi$#ir4vBJ6Zz*=6H3mBss-lZ7w{{P>mRD_10k~hi
zhN7oDg!26!fL~5>s|V(1E-&`xxFxC8$gP@cRdvZPBU_YT^mdAV@WqOeI^wQxe_+u4
zXmz!;?g72Yrf7kQ{zQ1D)XC0rv!d_R7~1`<>dKbZa_aLkue39GhNKRiF!n|WdIPA^
zl9VF}?fbr{bB*54cjo$h{{-Q~E#+kkCJbSE{;vAK(1<HK$tzbItmvTzU!=_}I^~2>
zHR(oL?zaVb<4Oh?lE4>Cg02KO-=EsHEckUO$c3c26>JLO+TPEmo;j&@G&>NB-=}J=
zLwf<Br+g}t-ju>a%&b9{{F(|uUy4ItN``ndvM2hzt*`Vm0!Q4yXyK;rWYKP&i4Tod
z7A=dKXChr<mjG6BkXIjoh^W;g5a*OkEh{z0uVPp=mq6nknpH$h-DRh9E^_H6(ot&E
zX-znS9`a9DaV#SmBN0i5{3<J5zks|o&M?o5XfyS-3^FCABDa@y?chW?gD$I2dQWs+
zkB8HUbYIglnoAx~G~wzls!=xG_T{V&tq8NfG@5quDiCa%^u3aNNn&Wog6*f3)tz>E
zPkwQISxLtO%-HMM=C>*v%3AGt5q443J}r&r&#+!WTxUauKE+^M7ZBjJvDLG+HAz6@
zMkT$I99%?ZV*umhTVb>?n7li=KTGGxq$^kV;4E9<xij;8b+*!MRbyf6j6T+Cy2P!+
zbvt>sw|91cAf__vE~HQAVfo`!9LMzsvV4BK?a_oC1N+(ejlNC&mwc*7?bm8;vhnP&
z&Bq99Xf}~qnO|fx$F|_Em97iyrC;wJt__`Hoi!&;*VoToH+%bTHC7Pc#AzLdwcIxx
z-gsW7)pWhnkg6WGxcpSq+;!w0*A#U3vpHeALyJ6#B~zi*HuKD>t9gcg^(OM>dg{tO
z=o9g!a2S0O&wcKIozgp+Nl*53>vtU)3l9PhYiZn>0jY;CSI46m?TIEOOI<Lld^1JM
zB6+<T#Z1t2Hf{{&m~8!$S|egI5qC(^3?x8RxVE39)?YCKZmdIichX#($H>j$=DH5R
zGJ9;3l1SyYlf8lOxCcJPT^cr_DZOZ*sKpV$6UXBd>+KP|d{(x?QvZ>=hug%@)fUG|
zuf_u{m)gOQb#yhYyhjmIYR_EtY_l+vaA{_GDNxlFHJ3+REqrX<<^8BhS;$w>CXH@R
zLqvRWDV%3zS&EqtTtyRsCuS1d6u0aX{^8g9q>5o5_=pGBQUwH_dlaX}F;XLD%8L4{
zL|PL`>DO=J%raR4$Zb(Q(CwBf>LRI17tGmn4<cajqfE8xCle{+6dN!;Ep<%pjJl~x
z@AhmKsJmcKd33EJU(C}i1U-w1Y>WTVhxC&@xXAZa=J-wsMPaXctoMlxA{fP1rrW%m
zoUODXevc|7Q(!#YREw^^m^a?@BU^PzSj493b;T(L#E(b(DIGXYVKO#j9NYFy1UGy@
zq=!d_AZjoj1bLCI<H1r-|H0!y@r*RE*?XOni}3nOUHwT;iMq~oi#rB(2}jAB(Jq1U
zE1L(8wVyecq;;YTHtrJ&9Zv7(+Ue9QOs9kQGY*h1-hBZb!Q6M^b6(~Q9TkIAX)v@c
zc-boiP$*JQ-;9x-><S6kEd1n<*s|GHGN#t5KW;qN+jKTgb0y4IrP*h-g>KM?^SR_@
zk^8hwSox9bjlfshiebfVUb>aWRtQ@5Q)x0Ovm^ZRAmy^QbyexM>8k@wVkt~p&Y8a1
zo@Xw+bek`1!_TP7uf#HOiWzCt8M(<fBC2f;#JH-TjwSBi%zNjeqwIVRPK9fc6xfw;
z9-wK!piA~a!I=ahjOig1IUxJ+OW$DkS~uLe_%>9B6EX0durj^@^jF{KW7-iQB4#ot
zcz>fIzixal;q8(oep^Njc~^471N;2Nr6x?%fR7o+Q3zfWp|whj=aXf6n%hdGB826>
ziRu$(M6DukX4BM0`1?^<Pr{=s`5JaOe!L?Hp;iM+gl>U18rM<lTdoHQB!MN^6vLJ-
zxO>WFEyCLoc+YR%<#7DAZJvzYY@e4e;P~5D$e6sxES!$Vq*C{pxX$X;JtSKW^;fFl
z__2?gyq1tn3caHkk8d-*Vx66t(PWXisz%ql+>T@^pAlHUZ7D`<U|eQ|ZN@#y_R>Y=
zVptCM`bf>LhTvT8l?~m2Im!$ECg{>z*!n%m+=HmsAv3CD+dbd|1<VaXgARNMoDSYF
zV3`Q+Jho*h`Do`WjAtdn`FQ=+SD5ko6#~lZ7|dzLWiV_#!k)cwve$EF?yFD+=N=U1
z*f+?ZeNErjds%4iyM6I0bet~ZPPC%)9;ifGdWKPn)R6l91nz6T&Cw>pIM;hT*;!?H
zQckX`PUY!kUt^y4cXh&Ujb08DB5n)h>eaz20(i?4BJ$4-hY*$_ux3-}%VvlLBry3A
z0~6K46R(ohT;9iE#!Sn<gCn5L4TLFRUonPLW#GI*h3%7ZmTUpSN+BZDd)67EJmh*&
zNiFx_s%tH81i_bxw+O+aC9y1Fp0GO$wajDE9(r~0K-VOVMu}%!7C_*QMGixahlDP(
z(X>*)88LW&E>(QBOb$y0myPBu-%^n#KM#vFohIIL2bYaXo0NXsiW#5&-92LDwuvF0
z;XUpFF9ZSKS??vsWjk%n6#PYS$nphp_tc6dES`tq5el4#VT&{DT8VLzSE&IyKM1a~
zo%@m)UX*8<3D#+{<=fL5;TG{+0kRob3e4~OYXI8!HC}U;4kvTG*1L>M9{Hq}BtMp`
z5$d&B`eB6;*HMUp(`}#aTb8vxVx7OS3>~z?=pNCN=QZR3n57PuBcP9yvk7k|V0I7d
zz445}Vo7aAy(>$#a`n1k^gd<hl*4+HNUEp=$9v`|j`AkOYw)H9kSbi}MG4!e9q#W&
zUH4rV4&^y^7(;v9n<RKQTEP^rX-t0-*b(&rLTnYdMtQ|Xgtx1i-6lt<N67xz%bl>6
zu+%?ILtzY1Y9w3eTJ*x!F<~8_S%e{Idl`AXYWdV=4u_A`P1RBom4@gHt0@TBA=TQ!
z8i#r51saKrksE7zAbRn$S*E4gef1u5)=l2(-(d11viTR7%mD<k{egG6|BZpNKH|2&
zfMDkT3k3Zq=BXXoXX(p=E^={&%A6B~Qw*DpE0mW_O6dNrf(#}gO`Phj_q(Hu%C!;Y
z9XPkhc{A;f0Hy&ugB*->r{*m}PGV{^-lDz<Gv60oJ$aOfY}@-)sGfXIvLc3-7Y=Q;
zrETeXsOea*wK$vGR(crt_-SGM7aIfxW^gcd<5a6=^X&w<G8O=;4j4#JOfN=jrz}PN
zeXgd7U#C>viB}19Y#v~bmdH{@>Yx`DjcxJpr01>Hd@?0A^_#rqkzy-7{dj-Skf$g-
z%9Wj-w}&5(YD1mGn$t>W_c94Pr_|YCk!Uc!ud7Abf2h@XRqJ|lzB&3U)dhpyN>U9r
zQ@ot;`&ZCEJH6bZ((IYB9oZCI3TiTD@<ls0JvJQ-j)d-7ZUUS%jEq9no!xi5ymlVE
zsNKrHV2?Z^Ze?&rjq14hU=w7ZcIg3&*p<=p?{NJJ!e8-XV`KRfF4jk&{SRjS8!3Op
z^525(3~V9R_Exr!!1phBUslfoiq(s0NK3tyrGE=H)l+p)f<owj*Nf^|K+IhLw7;tW
zk9BmvE6w$cp;$TaZ%v`!Xg(t=3y=lC$PNMmSUI`bpr}3@@Gn$f!d}lDVjyT~Yz_vn
z{Awp?XYfc1a09u16(7g<SY`yWar_bp>sgC~A;u<9<^bBwFOiZx*g_S+^}GFJLHtkQ
zafZ-L1Oow&i2Xki{71^--`@D$orAvpFS<e*$`L$z>X%eV&kp>H{P_QQ24ZVxFKnV`
z`^N#&dViH!fxiil|8_UvS3rK>EFzXrk^o|93}9A+SPEL&LH-DSSyqD>+MC!xSrInY
z$65T}CmV?6uX+$02=KojC`AL6{<;3&JwO>3&PU$p_X*<o^P7|FKUP7|<l<y|%%uPO
z1hGA`Gf+FMe_H?619JYS4;BDBbm|<?jCdT+BeU|z^*|-i&o8P6O4(ScSVA6o6Tss`
z=AU8vcM?BxO22bc3S#)^rAOLH@o&<|;gMqc2Xn*vPgY9a*2>Vq0Ls<S8t6f6tpKb{
ztQ<_xDbkwQ+grb8hSFb9sj;n|wF$()j>*c_nC^F?3q!d!dx(|g+ehk*_U&sR3lPY{
z1>|C31%jX}gR%f=SXk)(Y4kt5+aD@SSPz={R>r>q{A&t-5n=z~n4E3FMyM<RR(4dD
zzYhR3ENmPABfxJNCkV&}b>HIwu>4B~;%4Xmw~UPo>bd{YgBBix^j|U%HyZ~uQ2!<4
z<luw`=D%eiZcY|xWd28w1q4m8|CMq5TaTUl-!^`w!+*C00lEKoe4HTm$N2rxv$xfQ
z-rKgnSU4q!EBMh@j}I|LD=TQwe{*(^WeH0oXl#Gw#c$qC&({8zccJ}3xlt-A5jj!R
F{|7S2x0L_@

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..2b6a6085f88d032e3807c9c697596e17be2cad0d
GIT binary patch
literal 67390
zcmV)!K#;#BP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGb;Uf|AyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<Lx%w65`;KopSo?kJD9ZO8eWdbT9Yy&I
z%V7T20_XcQc)nkUzpx56+b?2Pl<%i_J--NAQNHi^%#Vd<``b?Kt+ISBeNn#e_&!HJ
z*S;u!VI|u8jOfpw?ufs3Gq$%5_$h8h`F@h~^NINLt0>=hyhDH7`jPN`x96>_o*%0r
z%C{Z6`N!I`{TEiE+xcVOeLVi%O8g}iv3L7L*oyM~^xluXPhl&{_Z{Dl%g>cB%J&`L
zPomG2FUt2FpZjy=MffXg@w~s4%F4HE@z<`-_Z#z5*oyM)6xW;9KMvudeBaTZ=&)bC
zq<r6T&S2iwQIzjH-hJ;Bt-r7i{yu^2&-cV%QW~G<7eOn^w^Lh&oex11;rnjA|FY^u
z`M%@3!{@3O<@=8BxBlm<7v-<0PUC$W&OhA~e@%CKtEs;TT2cN)v_JLGPaX61_3ID+
zYo;92{o9)OdgtUk+x^~YIs0Fy{Qs@_ZpV20ao+7-7wTIDEK}pZ`+vn3JI8&u_gCjz
zS2)+_-`ncV+dmf6_vUF!6Ui4?v?f@xEPwGfxM<5OisK=(C~vVof|QRvklvJ3IY4>;
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTrsi%^q{aV=6!@+~}X$`xPuq|~&>YH$BN*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>%ZP={=M}I?z}1JcBN1(3c6hn42>70^vctF5&Dx`
z?@d}K2VM(F2;TVQLf~;0_R7H@4o>)F>pe%OwQv!F4Q~pz^P<FuX*^q$n6-0FmICtr
z-myrHqYaUO$s;K_>8@TkCf(WT#+-2$gA^=pT*)*TE&>+vO~@(ICb%d$MT@08f)GtC
z<aJ|`Czs^9v9wtIcRQwdZe47hc&$HMpO{hC>R)%XxP(_ur}IEwg!Per*Am9^E((`0
z9RjUi)hQ;^X>(hY*xViKegrAjsMo@$60;~=_$#+^pKPrK>Z5ub(d3^`jDD~cKj#vZ
z{M4dQP-gDB?gyGV@V<4)f%mOTj$0f4O<9cZx!;eZ#Fpx9>y?bx#e3ydvnUj<yz3Wb
z3D*&nV6`sZYhb+R)~UlxUw_kK$xrz^7Ag4H9*XTqR<^r(MT-*aF#hYnep9Zs?b@Xt
z$=5}xUctV0ZM}khZEn5tjB0c1mZO_nw;Z0dpUb1g9`sGbybh3J3a%a<!}G0I4o`RS
z)xo^Hj1Q24dwuJc!|PkOSj^V+F(_v(_xzEhbg0y>hep(F>y{(Zp?^UUX?f`5heF`m
zxpm7Com;nLm^3nIc+DPNF&A!ld(;h=w>?|87?G7=;9j=7riMG$Zi*AGT)Vbj!6GZ+
zz}@+#G#qibD6ND8_o7XSH!eY&{1omylcsj93+)I>bqa1+T?ps9rOROAUNW5w6St7L
zF7}x!&YOf*a-nZsk_l3^mtGsA@7W4B*o1t}Tb?ogdEN>peeF%iFG^>dH@=#h(2=D4
ztZm)$v+%IK3DLmOJ1<Q3<RPDW^P6Mm!yai9TLfGS69@MB@HW8{vz^ijW@>83BH?G^
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxIKCahPbZA_=af3~IRg4>BZ#uKa4My<~a^yNsMxM`$!m(ahVAEKye74ymO><lr
zJ~T}{(N>$|&43HLrG@09Ehw}rj6BsB3A}w%);QjjY`y<Wk}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5h#3
z5Qm&!5*Ei#EfS;!Pg%QUDDsK1=|SoP(IvWTeB|V;?0Y^iHXS4$)~H1o*^K|rwNL;{
zlN@+z!v<Y6DLFQolH4&i-9CzZF}-pT>0p<hFK<eYO-3f~;G1+6@9&n*6>ssTSd@YG
zh*o1WSM)?H#1pF8qCoDUn;l6C@tjg<Jx60x3N7B$i$W<q5u$TT&GOVl7m2cit71x>
z>3L0BSsi;`1+!kcef_%xsow|=3PI`@S_7>dx-J&HgKc)*gneS{x+yxuX6mNsxub39
zDD9YWn&0w=Fy)~Qg(syASykHu%G@Y1q7fmmM-U8ul55s5!!gl{6?`Al{MT5+q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#JB(|l<8J0T
z5R@F-%(sluK+-2JY?D)_!zON~QxOL6Md9FvzJ<Z1L>y)`*e?=#MGMj($4*C#N>DI5
zNQ2$9s&v?$&8W{T3cC%o*$GQaGqNFf?g-Kd0=EBb>Vz#w!?4|Gt-rrCR>StQOM}Iu
z!*u*czDBh1lj#XJOSP$wM?K)nUZgl1?4lG7TpdOqW*@h@VXU;g+9koHt<`j9kJKHF
zkBmi#BhQfUu?TTY;_0yXG$uP?4z!RW>2$T(2izWMiV6y*K-Gaxvo|Fg5Ddh;EDFvX
zyr$ojY`y<$koAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^C?=lU_Or8_hO
zWmk6ZSPN;(wC`Cb2RheJ`m?gex|qOa*PZA%=S{bw8;`0kHW*e+7p24WY_Mf^=VtB{
z<Ie3Yw_5Mq&bm!Iw{wry4esi0MHEX=k`)~$<sju?I{Y67Z(Z+r>{}x%I`n&!#^2$J
zTqN)UuOvfu<Z6d>({$8359ysUFg~7Hou@QC$-VQC*1g_4xWz|!?+x5)+Bt|Z4-#g9
z2c9v<y60QN<fQJjE`o9-2|SEHI3b;kbXk;S-$scR)}TF<P&zjkDcM<+TN#R2l?GeS
z2W45@7A4mS%DTy;-qX1F(N0E5d1+I*k%$-VG$<NP7K>u|HYp<+C5?y1Lr{(+C8N?~
z+nbA3Y?Dz~{>ELnQ^M+FCRM66F`_6f2LlO#BKAp12c$^>gJQE$?BS$x6VjHp5tuU?
zjG}EvX{3?+a_&87sVTy(HKMivvrCQRyu?ck|D0l7Q8+eg{^t<)z!>=cH-4V30Tu<!
z%kgz;Xhk3|vD9bRoJeUUcqt!equ}AJf^UD5JQ`CzC=$Hn=V>K)VES1bE~Wmg{f3Qk
zo?ENYn4-<KC=x1?w*3~oTNH9CxACHYQzWFqcH~j8nmoMn^k_7mY?P_9E03HOS#~&-
z4iG*Mv-XVrFaw2WS%}pl@F?r)yKFF*=-g~@+2e2ph1Y>&N^ta&as-LjL4K;$ZGb7X
zx(z&kn92?v2kn6<=vHaZsnef}aEgIkgi{Oz&+pW4j=bVlQ}<*JhNchQoQ=j0qZg^&
zR9`#HMD4~N<c+)t9Tz#6byI)k)!uII%JfDai_pie54<UxzR>O=Edz|Ase^jQn?SWB
z$K~n)Cf%DhgMm?-akS>SD@ThG&J-z74S5r#WHq?gsfY!^pmmWWM$WrfVp0pU(<!Bp
zGd`sia>l2$!ZaT?8Zo4gHrg<xw6^O}F9<?L8K>6UF2w7WTHG$GIyAzx3&9^$uiHgM
zhYI+c@&yGwM@Gdbb@+Bob-?;w^Q)c#D}9B3pR1X{srzeUWv}oZfc3k0CQr0lzF)9>
z7ngVHh`6}MlQZe;gvFwjLJy~QafK)50?nviUyVizzR-fgPM8o?*Qu2`DHc;p!<Q*%
zP%l#~&g3hF&(1~3K5+81`KS|SFzaPH(B``o6PUO9#IbWkjto0t0p_J{Sb)igO1AJw
zxi#2{Fcm%M7YRMc@HyCvqoqQ0W3)qEa3`)T8T7#+IbD4?Sf0?g2HUgKgGQ%41*hGF
z36r)GWYLs0g;_LZabXe-tTH(^!)BrFCbDU0@WJ3r-8eX0&S4^o+?uqMp5i49+%Pjm
zYEAaw@CFUsG*&H2DBm<`y&|=S-M~Be|I0GADEt-#6VCnvHa3tt40B*0?G!TAHADoI
zIj_M^ag@og(NrP3V56x*wnOIVlz9<3I_rmWS}75<PiA@!t(y1^NQCU1D?JCDxOi~$
z%U~LmG#odLrLh->g7*<@vqzG$mu}7h%eL-GMq0@X+=i*s$gq&e;eo-Kt97ay&JiT>
zlu?>VJThD#K^kS+ZeFHs@Pd{M7|2^1GGst+j+l_LvNuLaHC-(ZMNZcG#*ipk^jEsh
zO)mfh*QdG-wA<J`2aPdL@-9SH&nXYY0TTTf{CN33`0?_6@Z0767|AK$oF$Fs4ZQY}
zlD-d}+D_kxPHAuSSY2c|jt=>E8sn7Y1X@Wv*Vz0-i;!!5F?cW%eNMWXnB*g06q0<(
zTg5CN`m-X%Cv1Llc`Z_MUuS2>+e^N)mBf<^K=)efIF03kYaK>z9gh71`{~JRa8)l#
z-ioxCw1@uaH)-<?MvhPTOzA&dl=M{6$+!}Gu2F8tmQLkkb5$-<`r~zcb;RQ!i6#hR
z^N2Q@Ptt3eL!<ZH_$B(zbu4xI&h>DC|Cc`8BNKq&#O1dT94$X^L;v&@2O)(+-sDBV
zETzGB2#1`~kr5Qb(IL}MxT(4NcqsHzo#BT~|9E3`m;C3AMi)8R-xRsvS1M4-zP$9U
zF@%DS{Kf#Uu7jdMxllwvOOwm71r0=c(AWbDm>raX2dfqF0aHUo_*Mol93Un48Qsuu
z5LE<3qXDK*4Hz!;+~P-4Qly|%;Xtl%45kKE$i~X?$>AWZqct8B3j1ido+>gVGK0=N
zdW2a&6>t(sKN*3c&DIz`A+@7rl4l0CtX76MG4iFsjN_;Dc*Rype^6|dv<1V>;cR6P
zkLg!$sPc;2X?AaMJq?O##{H~Ten4+_sLTi+IzU3GkbWeWUO`B20s@pG;U|KAU?XmP
zsF-V8;Q3QgPYq9~ii}zmhFn2t^U-%8#40HYz-o8_SBO@_)4IaA8s6{-^*TVx&*-fL
z+k|4q-UNh`wKV2bv{^GA3$6!@;jyWxwUy(OK~H*&(Eg_Ax5x~No5C+mjuHcrKcQzR
z&aNTeijjD$jc7i;z)skU6w<dSxjYj16B?<a0+}s@$ie&}XdetOT!eX6{NZYML>qE+
zP*4@cc&yBzhzeygY$OkD!H`HDs(4AJ4pmHLqz=U<R?uZT84)T~_+&(=^xhLje8zV+
zm>3Vk&ng;}6GV)TLP%GpP)3BxT12DcP@ZvPIM<L}XN7YqpcT1A74zEC1gWUl$S%tH
z$qsVDOr`MJMajTY*ZiQpC_*=Kj^adD5HFLCD$+NSj{H_E@M<UHmb|ZoqI)oq_yC2`
z#{+G~9w$#Ct7z;I%ZrkswGh-pX+<XJ0i#t?@zE>qCPT}q`bXYPgl0p}Ka_ZbXzchS
zhL*d&&(QK5F=iOi-Ye@RG};OWU!*wh8804*FcnU|QeVava30AqF{+y$uSLqCYce;Z
z%Bcu0N{*aQ=0)j<oQLUtkwORs*TI~c3b>D)nuz&7(aLy#yj&L{<q7fpD_!QnU)-2+
zs&q;SScI{q3>eLS1xK<-F~!R?d>r9QP*{|hqLLUEC3fni6ifqR4ALQj0!tDzCYYSV
zbc)p;TegMKa;S_9V}O*>HVhammD*uIHL3IuQ^=HZL<|@ol}Lj0oh{kK5Jq)PGzPO&
z4iJ)e)PR`EQ~53ixQfb&F<?<3Z{`3gS5_PAhBm4E8>5X<DLRq$6CYC?o?XoB;q$^6
zd!>XR1EfMF4e=+DQ*<OHeg|1ctDTuu5-b20RPquBUkOf!Wqg)WpvVLzP8k3MD!0l2
z8BqCG!QDMW%QF4Hvbc=#T9Nl<G=VZLY!Tw`l{vO3OgMuuFm_8RXdz885a<evFp$A!
z7m^<;>&+O(rOdcR$=Ti-In-7q-C5?EA6t$dHyIN7lCmZGF#(9lfw7m@hckWf04Z`R
zYi(dBQy!whXj-|7hFtK>WsD=`V6GzwNOjb(n5d~!d?Jcid6kQDjmo+-Bzae2=Az{A
zc_%WLs1iIEC5P`iTP71W2U?j`$=h#H#+GIp=XL%)H`HW=;R74?o3f>|8tt}9d0iA{
z&O&Tx$*tU3L)vzw*BXtxO2J(>Qu0Z1FyRD$?wTQDn!!jM{z?R1ls2|ZVWUY{*~B(s
z)IrK|QX)y4T9_$G`_v*bN!zrDv4JA*`9M3;{goSS%F@;ap)76cSaEBgO2Iyol3&u+
zo{p4o?QP|0({N{zr>*N?;<;TZ<BOE(;4aQ&ruM*pXO?z}3bV9_u0WWusiVH6swe~A
z(x_cI@{5r3!vSyvDX<gHORP*VDkbDELh@2d#{`gs68n#UvOW_EVBk-3hPPzQVup{{
z58NgJ3@l2ZHV}hg5fZfF6!(F@BrF4)M2tAuiGUFb5w(Z{Y;yUpc6?es^hHUuil$Wq
zx)EK&OO*w@ksP*$@WF(4Sgrgr;U5-dYyc6KN#6$$Bvx~=TJA$bq+y{@ER8h3NyDol
z4;)Aq2S^E3LF<VPU<U~jgQ~4iGi(qwVlo6a6k@+O^bLc1KnNX%bnyc5uncM}oR1@v
z@A#R!It`f%vYlg*_BpQP1amYOA+E1NCV7(tUGfT@KiD966U#u!LO?Mjmjfl`0BOjk
zlI<9YTog!KEI^h;2&M?M<yh~Nrl9KedP(G&rY?De$s=HyroJJ_#FHnm*<{?eLD(MO
zx+U<8Z`~5+#kXDw@+PzUdW9wO%uqK6vxd5P4smXsLJSIoC*F4(PLILQQdmAgIc>xH
ziFacR@ZzJ?;EXBYp!MF&0hUAn%c7M;0KDgcDb)tSd!DURLghSLr-WwWWioJ-3LNQ(
zxAF6A2ucRO4?&g|VZ&fzs%POe1tm^&fjRM6-elG_gu50f)S`?HHfptlpS?4zEJ!h4
zM=MaIeCv@QQguEwfJo)Qk=<VaSOz43Ldb#<A_24vxBvyPWr(;12-gA9D4?!1bv*Y5
z=0)R&@V*QPbp;7_1j%pWhT)HL@Hczmco+JZA-cEF$!wftK8>AWu~{Dz&RJ0W77&^t
zBDkQ^49+#csU0B2v;eqfgFtz87T}tY!IIV_A-f$xN{Bcqo#QNcxMh)w83{qooS1lw
zR#}ul)*=uc4O<0PXAUeP;n{^TEWRtX0f2r-0pl%F&T+DJ+J>tK6I(&=EkaINf$io*
z#nbZp4*D0iy!ZwU-3E_ifd|6gcWe-YVHAunJzKY2#b@i5kce7o2c#qs4-H=}Ohnor
z3pFt)V@FmrKt%w4@c?PDf;Ks(As2|FVaf&cxG0Gj*%`T*U8Dgx?oV0M46fCJoiv1v
zH<`{X;1iDxztR9wQ5cs&Id>dPgNqhmnWPX-^8g`PBi+t{!B@sH7=;1e2}*G0CXU#m
z<V5u%+$fKR6Wp4o<TFncB96unO%%Y8`Dde$Kfv@8tSOD#jM~5t1rv#nS_G-`8EH?9
zRfEhI3@a$d2GvT#dZD=n<=hcpi!vxVd8HnO92=w!Tb6Cv0euROmXbrt#reg`m1%IJ
z6r&Q1_TCsp%EqX~r@f0&Nq9C!1wL(UOc8DkH|%_c|4TnbK?Db7@s1$EJE7PTPPalM
zCMnU14XF=>W?U4nNeUAAU{i_@N?8=HvM6`2Pb!3vt${#1eeRwccSzZ|v4(u>6)uY4
zHZ=MB-Xw{Xjbn?4_p@;f1b~`xEuM2@2nd@PtOb2+7Xwge2%}^?wuwOy+BVS;u%~Tu
zK+3(#ZAQe}r{F%d&qlOrmyHOsEy0On>v4MHwWFSY*kjMO$6{kX`xcA+{EVGfN!s^W
zl+4+;SsWA3wI42^biA5*-aOZKxCA5ajaea8&%H5=lw{VM=~o0=o9>1XlIPhD<MnSV
ze7g=~QtB`ck?Lh1!HK;h!|OC&i`h@xPUAJ36?0yvaV*^;)or!DvZC4Rwpu^g%h-XN
zsF%URkuI}HbzR*tqOo09cZ_Ik*VP>(8ryaC<cQ{W-Jda{x!vv-Bf7TRJ$ZC(xBD_1
zFA7<7gCX~JnI}W;?J{3OTlooH>PH;pi!?Q$V2GWY#?q~JV`?>#^`PMeFE#@O^rLRJ
zbqi*ciDHeU%oD&>>55Z_R(1sGqS9#b>ALaa9O;VArUKZN<V6K>6*rNRkmr6!1Tz)Q
zuE=95qg`>tR9HKsfRC?KYJ*Z*Zq9mss>a>w33^6LdUSHEmpLN!z^?FCs_2WtXV-~2
z-g-u*qJJzB-%%&#$SyfUnKJR9=nD1ZqocPoZ72D%=!((g)1@o?lFys2$V$F|dJ~!_
zpGk}K@s#RK2Qgk-UEz&<ku6GeI`Yl7QiG~bERkXm`Sj~eYo9N}-dxWpOUub3Rj-_b
zt5?Gu<f_0kwIj$6@7SK!hy9%!NmJ^RGnnc#GV^Ne&*{DyAK=F8oAse#5w5LUF2ZJf
zh*sGU;`B(v!$DH;`}s5?^bgBJNXv)iAtVNthq706nI2%$=pTlM*Z`a1A(^`w9~>gT
zSs(JI>_iHo6{c^thdg-uW_wtBcjW-Wl@4=H?|tiY<)2iS99@|o9K-W68Ri>hk=Siu
zczTAyjMaOYCkMt?S92P~lr{O1(JV46)h&iNw{OMj_Dj#LF*9HD+>Lj=*J%)kO{9IE
zH2CFM?yb`}f>3>uS<lufM)GWZl39B0j4Lu!$?v?|yO%V?8MX-OkOOf^!+NcCx2;Fm
ziI_l}q%{t2)g>6>B?`DOH){m0M=xPWW-JN?9G794B=GuMiNf4SxY@k)G}xvWiTf{^
zxYCi??ExovIOLt=)X)!D$s^5~hr<(`nCcON;ZnF^hwpxEJyLZ*%JoYYeP(69WcBZ5
zx`1b(m+2yW2R*PR=}X9uKU<&txct}fQgr{tk<noqI$m&g1cjaQ?(aj_MR-j5p!Xy`
zJES2@plbCY=QaE?{DX#%O2bRnPA>xn-pfeVKR^muAGBBH1G+0_h<>I%BpdKWb(~D$
zSHdBx7$JJK`jBkI!+Sv!&?AHs6X8H|oGk)Z%meSBd~qSkW%7V`4xkAyIq(3iaDbFE
zl=%vtz+O>9@D}z#e`9h|hekZ@kD!qE10T|<fyaIyyhqZr*@vzXJpcPpNHjg9eM;j`
zCu&FKQF>X4b@7rH7JwMBgW#)OBr+z?%tZlXa3GZt1#aO!n?#H+f+>#|9L#-owDLQ$
zY0vmKi3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvV%mlN*WA@QVVMG-Ih;7Cna4yMmG!b?;~89}MuI@{19^@4y^U
zjDG;ga()9mcr?SfU;=YC_4!ODaE2}+*}%gp$Yg{7tW|nKu)vhRd*b3D^lha*xGA>{
zb6fDaT*I83%W{Yui$fT@m5AY{^n*}IJs~+Fk;4l&1F0Tvjbh1c5HIiw7&yIvDUep;
zg))J0yQwrD^HUsX5J+K(_C-SQO$n~n61f<kMPUmsd<Eptc;P8vOkP+CNXA)6%1n7d
zQn(A~z&va7;zOPs8k(NtGgH%Zd}h}4a&I~D1At=|NYKdHfpE#FxssRME=@3#9To-a
ziIk{C0gEn7MyWT*s#+-4{23&16Y5&IS@B2sof|V!>L=2>yb|T{Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|AoI+osa<l
zta>G}{)`?{EKpN#Eres$bBuLvf^vYsJ{<hTK3I`K{kCgGsNZ%%^|3NfJuz9mr{1Bg
z@KbM9mI2~p_E4dqdhlidmfpk)z^ZpM1F-6CjS5D`7oX%Wl{u<sdlo{fcRgz*)!U!-
zlsxRBtihC$r@8>Ms}~38>cs)Ndco|+8c?!eutZc@Iao(3jUX&DRYnq&qDlh|1RC|K
zU~K_~-5|ahP(_ms3uD2kbAZG?7~9P*9NMi;WG2np4<Rm4#;fd5tn^jJDwYE)gBHTB
z%I1ZztKBfh%420cLv^w;u(5zy8sJ#q3<kQaUY6%PGoU-|6teTNmKrUAD7IFnLWE##
z=0w(OE0ZIOx}`~yMc>L|$-;1H)XafF4irnx3Uf4#vIbolPg$o<_SGXR*_8p7#qP>V
z%Yt}i$<2~^W$Hyyz1<#+(tDfHID@jvtjzL#WqM|bKbWTvkkYKI8;N!dTDe(FungfW
zI7n0Zfs%x-lzWyfEPFdk8<tHT)ep;Tj{=DYjr$;VnEUx{IyrFU-}G>}zD*B@^Pz~M
zj+-}P6@4sk1&czKM}uV}%j<#Cl7~DaEI(O(6PBnf-wMlEmj4BXE;k<ys$rHNhXpgs
z)x!|0atCGE&GHu=tjbwlC6?|?uM<mqmRE`)RpqxrOw}RZ7K@0M_X~AK%R$Ccq~%0o
zwNiN64v=!ubQnJNRo=Q47?rHt>!#9OmmB&qvR?<?lLyCENEO${R!kMwhFp>?^m>%r
zlGR|#waJRH@_wSGtlXojItv%-0a72Eo0a8j%M-h*+tOA0QuSMTb5S7o*gU?hqFY{J
zR@!xC0c9=T@-4GkFZ|CrHpqgU)E!BgbYu4{3|ww*)(tLKxQYv>ubkC~%a_jj#4adv
zlrS!TJgOWY<+Eog<Z|mfFs;h<pXHM)IDiF~5kPQ!RTbunGC-N;EfRsHoHJB`g`X>u
z0mY$@E!=@IXIW|fE2~V8Ekc4-s4I+u(Pa^6aeS$obr5p5I^(Mpow3SaSMUa^V<W)h
zO9ix#EeeEHwkuMEWw<Mvgw?z&2u0<-D^i6u!7G}@75>C~o^{46EC$8Mk1ckFVOt8X
z@vLT50XU4uswf>4MrR~XunRSh6z#(T>n^}07GbXtAr@(87}23Z?iFUlTJH=^Vl{YI
zITVIeRfH4D${$-86f4hHq!g>uE0Br>>?_!czj#zcmZRoMMQu3>s#Ii`qgYCXe>qB_
z92FlHe5v>`M+p-Km@Q^!v{KhJAr@65&{4^>g4x_C77}blLh%-I0A_oY&s(Hin)s1+
zR>+-aF^>w$LnPD|x#tbYHWl6%(tPeAfRy+O6Lb{Qs8~YmrDF>?bf8ydK;mjS0va*8
zrkF<#uPfg1c<~6Rm`HC7+oUbg8{;-r=f1(x&H&6qCsajg#=&;(k(>^2D};Lng>jqk
z4CE1-ahuRJdG2OZsW*mfPR?*DYLzntR6zx<E)oJ)Im>H{eDy5xfaq8d2IFTB5RwNv
z&l$L-K-{=BPh+$$C^sm`x#k63VZU*Uk3BS)H$CEq7X`Vdh%r7u${<+AcZT{BjN*&a
zX<B4FGZkWnJg4rR(bQ9&CSt*PtMaK(;nnfLh+t}%O!ASEByH-x2Xe2s(~59cthaZ@
zdNUw=z4kIKNfG1mtc>CDRn7OQ!p`}iWnem8^clH+fHKcLx}8t(ih$>{9bxjIWH|e&
z#q-ErR<u3L3Kfv=-Wjo<Ed}gj&W?!iiu|WBrE&vklu`NsEjXE8K%-A)9~_`WqKPsT
zXo9LN2KONqJX*|^;J^n5HZ}U8bP0|g(xaRUS_&&M1NO(Gk~e6^%-jw~ZfE6wEc+^w
zL$U>)xvo6e3M<KkhUH2_p$)rIRcJluQ|d_4*m7Xt=cqIp`e7=U#+?~DrY}95pw4%%
z6dejFQ*;1c=?m`wSwD`{P~-(2AjK~zdB}lsRS8C(_C{qTIbx@nw&Vj*Ch>^Q`2ZuX
zGM$_`{TE;VjvRhvOgY1=Dy_-^f~UMIXZHQYce*p*Ub$L6n0+>Cnwfs4V|Fn8EPvE7
zHi^dY9Gf(Ufh3|zK3k;B8<TV}zg;P8KA3H$TYn5Pt7+Z?-E`Eflyj!nIn&9Ng6GU0
zzXU_+K;)`izC{U<V!EFX0KH5prUS`0NDw@d6nkdY>LV#lnTF1k@F{_S#4|hb2vVkg
z>Q;tnwelPtsjf8CB_-1wY3}i{r%w7{PNt3zW_BwDb5SA%b8v7F_Db#a$qY=|-4~^e
zEk$$@a<pj|S?$cFloiC8r9E|_GD}<OstyBgrL!(dGNz+7_H0;ZR<=@R9X0DKt=1>9
z*p!Rw6NuWCvFl+2uAE-SCz$o?unAXMu)jyN<qf;?t);*z-x}%1j&y6iSSIq^l*4>D
zjL4Pf>`JkgE;ezmD1F+4>on<SJ2wrpuw4n(ItP?sty=@jTgl#w66z-t!d*GmB?-*2
zE>S>|wTln9jm9Pm6Zz^T3&@!pB@0k*m<R8$Y18d;Bq=%AwqD6VX(sdfqG(`8D_`Fy
zDmhkGzawC;W9-nVgbCmPcPrcg#}4fT$62Jium_wu*n%fml!SYbzJa5l)1$u#VGJlB
z1kdxMuo4`m_QF%}`D}O#jtD`3G8`b~muGdsm+>rRlD52!j#?7}h&Y0jFcXlA>)Ze)
zoEh5!q3}FZ0aO7(yx$AW!f_NA;)OG@TV5-_i1a|2fCu0xbPWfNeIal-A{YhIu?Wcp
z+d3r|RN}(nIS?AiA|xNAonAO=<Wq5==5;3ujb8wP5H5)$HnOlwoO$GeH(8Vz4<S(U
zhZ3LV-nzwr1f{Yl!5^WmIMUCB$g+M2>6FB52}+JgHwQD)W$_Qna~C{J{!or+Y~2zu
zW^CO8r)6y4O2il%-VeWAh&JmFphOGx#xLUS$mW2;9tEDWD5-FCi3XHyLGUa}j;?LJ
zVsx$g<ls#9p!jzwl^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&-(Nt*hOmPD%%g5GNs)PcM6~jE1lFb9
zdJ;AG`D`e10tJzxUhc!Nrp5iLm%j9{#X&RWu0DtrF;o6j{Kr;gy`eTcQ%2M2YeS{I
zP=D!GZQ-ivBH%Wd4?n^D^X@3jy9X~cDALA@_g3ll)8uQ2v2=Qhl?pl;d#L)X30;zL
zuyDKgiW;q0Ek<I|L4L{qO+OA$v^L)dQ9dsTD=HAyLsRMoy&5SrKJL5uTUfk53nAhB
zah>)|`;E-xq0n%_{nSm{6yWKT^>3&;13|aS!yU`DZ$lxhaCKBE<Brrllg70a@wH5*
z;m64r<<bhmVxp#NQx0H9H9fsc*3yO85Xwm9?DQ0{c?Prvz-&gyS@VKVrY0dUyur70
z6>dXRcUP6XC9lMHVY2wCK!%GlpCN%tFn=!Qrzzf>!KVtao=jA)P!mR7c=_b$38QHy
zr}dVYSTk5tyq=1n$ep{y<qrhHeiexO`k?%_BP0n*{pv{B>fd(6<AMVBvyM}V;BPuo
zQrkbs?)_~?WQ{_gf2LVsm+;?o!#+rT?dP^J{JU<5=jLwtDHlQQpWk%EHiJO_+%}$n
z+p%?R#-GdAxoyqgbeI94%MLR(z&9P1k8$7NKNZ7MTmCm4c`}$fl5&095s;ibKz^ph
z{o_daO-GzO2xs`Yokjj_$98`lP(L#><KxKs<BmGnPIV+@e%BE>csl=nW*XW?`EAFE
zKReZtl=*GP@qC=GKQp8H<HY^rjy#y{R!1Jy{%yytg8lmQpMfg!d7}SuM;-i49Z9*r
z>u8z(hx_4YU|a3?#UFo-mr7$NwC`^^8Ei}h<oj7AV{iLz8FXa<z3}IDiTSr3qp(|E
zY(E$3>vqlkaffviqLAQE+>7Je4k%cI%kpQO6CbzdZw7`twy7Hk_qW}UZp)kaXRN^I
z-Ta%5yuv#>it>Cv(D`xG|120^-TlAmSmt(gBt;&K-z+vvl~5#pCNShi`E5snWM1q@
z%H6;1_*@@~%Fh6b`&3<ivkR!<G<789{<dSgc10*R`G;oo+dZCt)!2=M`@3%NmQu^g
zQ|wdk`t2#ksC#z&75?Bi2QG7gt{iA3|6bn>^eL!;oF56}{H9x^J#HG}&yU=`Z$zzB
zOIJrw#`$f>=^q;C&+x8)>ZHHvNY!<+BPrg#?Z_nY2G%$s7OC?7rW+Mw!$OGg-9k9?
za8rFwE$M^udrb*{X6i`F^=-#IN0)Z~Gomu2s{iqyQ<)D|pmG0Rfur|X5>k%7ZzZJO
z39gP)PSNi=A{d0viJzOz_WK8h-XW(tPCeMG<9p+u>m~bszrL@j>s~L~;kK%^|0^G|
zdXSXCHL7x6GPh<^?o#6CM#(FfXi&ts0%m|!+f<>xC<=YJk;2_Bd9acc6n#8QF_%1<
z8->=W&{Tlqa_khuHryx~dY!U6fimgCMwC~Z@?qZym24I0g7-w5_cl#ZYMNpAocBlT
zVw&ZflqJ>3gMitQaVzaMQ(nnCy@_qoA#nrfyiIu|5RTTSV&8Dl@qFJY@<=2IF-p(*
zU8Jl}N84K(8D|$;(j!SIBT<gH6sEowGF4G4H|nNNg(jeMeM10@C`Ujv6+=QE=D9Is
zE$w)=*~d~=T*{s1S6z4@omq3RrXMRa5VW?n#f_|5cpB}bu{Pt{?6$Es<J!!bu@VYP
zq3IMcTSwVj_0*J+c8uL@8>1bY*>+?BN7+_$4~{aE!hSu<R0<n+g`B`tKH6s5jd1rx
zD%)<ds%=K^WQ}dkf#ik4i{L;wh_+T<1|qV_HxZz1a#qCD6-ojRN6SzWdSybEDwZTX
zB~1oCxKf&c6zFbg0x3A?lW72fKz_f%1_)2ilVwNC1Cut=3$2*7m*-&>SoHEcpp>i<
z(CKpm7T==$qm>Z(f2(3Dnu{gET!JHzz<{KjS-h3r&M5lry+S!yb5*ec4>(X!BM)C1
zHME?6V{F~Us;d<>lI3gZ9EDZcO@2;RU1fcM^voVAiyOY%XD^)VxM!-kZn}R13KFe2
zDSA1YfN0<Py>(f$>GC(h4ZSGzjiPiaQ1rr&9If)9$I>Wul<x2anOQFMHTXU^7kZv`
zf*=gX`&RrIzWFSWtWG)nvGr+Lb{S|45eMK|cbS5M(xp+Td0qa&`z{Y6)Pbh_NWWko
zCywb$VGUJAnxPM^vr7)mwjMDw%fPXhLM-^mcqt4cYF<0zJCd2FzLUzq@?KP=NwTw5
zTu^Ql;>NxZIMSNj!52%G%PYb7lg32A2vPB@8eY9(fUUv-Sg~B;0G_e33qN-YpNa9!
ztyhk3R<Dso&at#CSUzemrtYBxJOl{0O1HaMuDn8maLYH>Uc`OfDp-uw$@|tT7FWr0
z7cSY>wob8(t+lOJ?EBWLR}QDPJ+8V|VL=V2R#RLMZmm{Q0mo)Lw_Z7(vpS_?Z4(MO
zcx?|Bi}6?q1+JUQg}ZRK*j;=_o$)P71UJVPCPD-DCBenLU{}dIt^vEU6#&`%a}*0V
zg%@8r+g9mn7m`N;n_GVr+sqi#ms6Iue4(JXY4-y!U{Mrv`C!gE0uZMSsBut6v>7Oi
zdw>BVhog*5t1L6<x6R~!{s&K1!Xh-&T2GW6Atw7PqC|6%bOZniav9Rt4F_sPgk-Gu
z5v1yt{sVSdpOzuTfkD|$soc<?7e%~6Mb%31LWp=fE2tPJ;i(G%#gPH6kNDe=g|otn
zXS6D$I1b@+4=K(mRzxu-xQ7(y1ox2QnB*Q(9BZOywgX1vXqB&(z@P1`h+-U9XGNFe
zVRq_;HS>7NIFkdEWN3w$;~8?YmAq8A5aQVvg}g*MQ9G4bh!FQ>3cDB`p5Ku^IC0LL
zQVu508LL1P*cpw1C^H3jwaJ?Fm_OwMh7;te(*cFcqDIEa!24@_(dd_i{E!X@z`z=v
zkx6RVi#sgUM0*s8o=3zYRC+-;@E?lJu}BdJ@RZ!-5wR%z8H-MO!p-+PzQR?;llRvm
zF^MI2)uLdIz@d3l&<fYXqXPuUHH$)Z8=(VM>2c#uMlr?=b^5FVSWwGvQJ92>;_j;=
z3bQ-%G%(h2@hmnNg;gs5B!^4A;_$3tXcfSMBmjGeQxK^x>+3fk5v#gl7Ijg2Oq}hj
z3JeD`;Wv=cW26?(+A&Fq6}fd{WLChTx;3vz@yS1uN`Mk|cI!eIo`rYt>D)ZaWr3he
zAVOQ^o}oY}YXAi$iUd{i)LN3tIvYs%c$3hKSd?2YasWVC<(wtHHA^5RVZhz0EF#0~
z^aj9-kM);cVRg%2X1>{{&lXUChw3^dDOsS1G`!vHrltU#x>Zo>^+gysyXskpU=miY
zN=gj&(kcUIjrFfyU&JZ3j7mK~irtw30g)xZ!duynJ#$q?BmC5t0-YS?!C2xeNg>;p
zR7pUC*|nuLMrE;!nUz<zKQbxp()P!L&@Q^Vn2l+d9*=;`vQ$eCka8rh1%V^6^3;$X
zYL%zvT}9ho$Sz&;>uBZBcpxA@HEP45o#U!>MmTn_3Oh$CtX+C}AYzDx>t0HzwaRou
zYJzQ<Za{#tOPWZ$Jy%<)yHR!z2QA*6HgTV1PQofE`JfqtFB>275u((fC^6Ehy8}2#
zw%PemM!}}!1aD895|f_Ba4UNsK#5SL@c?N=B}e8j&uBr45=Y3U-j)f1Xj8gGM-?!Z
zu6!k$Pw+qs-t$eeD7gWF17k|=YT(;=q-7y6--hyY8l1=q!)<q#oy9-LTinWE)~+M#
z<K|?5pJJ7>1>{ZE;e9FZo)vyyUn)RiV+$4Af;r+39{k8j3V(L!Zw!B<RD0K#IGWsP
zR>@#3AAl7HNIVo&NX{R^wj4Un@rbiB)-?n*3|-ExV+B;aD{xUxqjNb4xdI(6c;h+E
zmSwInMHIAQZR{i^AEf&O!8HnVgS}8_DyyuWWVkX85&q9o;z@~(l;1W=54AyiFmjda
zS)>@gHm*I<B34N5NCqw@B}VUhP9*Zlp(69I#OqkYcj=2r5-?{gMlO4zg(hbi9Cd(_
z1db$g`AkU73yCB|rOb<X51JRC1m1&2JWxk5Cll5u;Y&<Vo{p+erclYiI9YrW<R-C7
z7KKyn;MGJcgw!SfgeEZ|S_U*pd|F2f>Ry@PC>Lx<eu(jPNFg|^GT#ixco{GOHe$km
z46u>-mNXhmRp3}8g7QF}6?T81g#-g--#BqvyA+)>PwB(tNG0xvm0k0s1QY@gr2yCs
zCxpOs4C4uCf+h4!9S914B@bznKYdY>hXNg3q*%T}2*Rn-slcN2oCz$@QJ>BT4R|DO
z$Ks)|0ay4z%(D{cPQ0DUPKrmI5t#1?QY=`P?BWq;z~KuFsrZx*@-wd3uB+`trB5r^
zJ-pzI*3?A^RustIlN(;<)ed~|MM=brMM>UN(CiK72-6jn5KT7No;e040KI<<v_(FF
zbypvRf^|xAf1v5fCL8YeWFOz<0ZSI#bF`9k!Y+NVqh+{Vl%-4&=MKpQRycP^F0jrt
zf<*~N2~PBBn2?_F9mw^IG|-MaUZ&qSC0hJVF1tWLALRO2LDoHt9TP$w%3xX-dgqO!
zy&GC<q|(oN7S{|C7=UM(6+j&_3#=>pJ0V95<-v}G<V)!mKpiTBS|QZk7lP}a!ukt7
z(d2vxYGjdePY`LuWQBfHqD3%6#_<ar{YJv0HDQ=%t<|6uqG9l^2}cv&VpIAeB9iil
zI4h{<1!M<*rU}RnUPY66yN7>pwR6|Nt+xpLG&JynwZogv3fK-FF>5M9+YxeQjhh%x
zHj|CK=abD^0cAewgR`o`g=KBW%0w@G9L^<^ZN0-$WCFlDI+6)Z2zV>Vi`@p=xw^v2
zye{<tcInbNm9Wq+%7cJ1FUkY8yf-CUgbSrS2p(^d*o9o6Jn$MMnusaYvm-bH5w-_N
z*-d!J7p`*UgLY&pTN8LDO!(G%jVMh7P1z_{Q!fsvsTT)i>=dhV1SNYljRyv=)-;|o
zdkM%mli!1q8~o@9y|7kT#t(Zjoc~cT2+4fZsla#RCE5zh7;mvwSjH9bOz_>j4&=`0
zFfkvCG(cb<Chtu4NvWAr-yt;c+yko<PdFcA@`-eqdaV_3G3BCwi$8Nd)>#KMi~Waq
zn4Fp>4-;tA9d=q}4jn;aFa8PpaGH%H<|;IG;VJ<0-x^i%PQ$3_<fR$Z3IjQ%!U_WU
z1k>f}>8RJWC^5c)R3{UjD9V1BoIxES_lrXOS=0{;QvUFOk`Ot??^Z-$gOvapF;k6-
z#JxF!1c31?8U-#MM}(>T!<Zj&-9d>KqCEN->cVjkbs@Mo-j^l-(~-7Z2H_t`S_h?k
zScDW=6b>JcNg_G|QN&Dj5C-6IP5IG%Fcl40%Lw;aZO(|%__{<g3$9#c9j`qz-6}wf
z3JN}SqEi9b$8E-t`y-L?gEdvs0ETO0?jWH=%v91K&C>GCbq7{#kn-CI05Rma^$a^T
z1xa^QbTIkzI^JSdHFrBLgr?ieD{TOWfzNE=yIlQ=R$7>>N)>SFt5N}%UU09@g|5m3
zINpPVFTr$YRhgiv+dw-PdT7#3eF&~g1D#cM0@&V^)ZPKUZi<BO4(%}Cu?I+oX)u8;
z&w11J+PS5rjCXG7yl|tG2e-7asynwdOBm3=W=g@t`@{(Oc?j{tOj<pjABJ4~4kSVo
zD(IpN3<pAyINL{(FdQbiz-1o=N}>sNb=ZM63Jz!!2xDhbhY2~m<A^pF195RHxuv6)
zEhzazc-NWq2B_?2dW!VyLVo_5Shy%7(+ZicN*Pd9g-#jRDLDf?XF3HyR;%710mL!r
z?a_?D^7d#(V0pVWA^6@pU@c9NvmFs1pOlHu=dxtL$JU-a3WXw`MU{V{7(NbB2k6Hq
zC4ZNqk3>}yJOhzGO#XNRe|%EFuV{6iVQeN_R9T`mtm;OI7FN9(cvJxBwBHGPcIA59
z_>rQFY$qEH2W6A$Z9FLnqn^04A8q~teuM^`4@w)y{$ZGFcFI+Q%Q*pfd8bS~n~Dwa
z$?uc_u|op_7A==>@t&p4rB>$jeJufs`bnWULL}15e*8kBJVLh4R<Z?3?ZlMP(|%B7
z540&+5c9M4VNobq*g<FQM3|mdo*Z@}bF*tFB60Ysok&XU#IU9`T3~btwCDb4U1Akd
z*q=+Rsw8Hy>LagtJLle%bq;=IB|Mz<Xz`ps@k!^;sZ!?SI_C`^=sM{$)&A)^=tVHx
zI=K8BK=11^Sd_6{7Y$zTMIpyb2mL_XIXd#lbj*`SC+|t}<J3KgylMEn58Z(awc+!c
zZ1<yUGB?zlvfZ@{vVpfI?v8fzT+N@nq?&-aw6mC!{BInpD&cwSRAsIBdrIv<0{T5m
z?ZC)JX&o5dfEifY$|8MgI13tr-N3s$@7}8E=~7-0VA<|2?S-7`(q71^F6D*X%I6Uj
zw<9Uk7|EU{jgjoJUlhi6n-s=`O?y+mOqm=F7&m59oH(&4s#<-Y(E<|)7*yKsBC!kj
zK%)wkW+r)*UX3&lsNPw_6^1tD#5Q0{l@i|oTV<xAod`$8Q{VuJ-7w8-svAV$8tR5=
zUIXuifmS+n^m17#CApHSu6glRWp&Mqm#T_uBA)W7hg7?`{wkb#as5>$6IK+x*&3}V
zrT~IQGm0_(yupm3$6=!tMGweED~hRz<jPLryA-p4PfZWiHziy7nW@(@T6n~&`1Zt`
zIEOyD^ZAr+lN+DU?Ul8H$N0gdm9KiQGjF9H^~_zVcYm8xy<(h4kkSNq#vi~}CUZgq
z#%9?ZD!uyDSb4(BcF_>-M(ak)(6$XZ1#xU;YiWpFGXmi!sqHqKm9%oh(gV3*2%2m^
z0%?JD==cK!j+q^>-pG3?qZIRA!f=HtT3V#Iyf_nDLo5HhX$)ty^0;N}7xcr$btSE<
z?DlxlN|)RLDyud6&f2)u0|Ga~$gTR?4B2WbuRUm8RXOctI+2aB(R9-E9B8ziG${<r
zb|PbDqv=EjPv*gtQS?nYHedoK#*}HbjWVrrB%Uq&K>yW-yGZOpe)Kc~;|H3$kR4FQ
zo36@%8cWuO_<_qn7U@MvqoD4%L7S>>wDgl7CWw@AsuS0SCe>wRKnjfsuMjCTK}j`|
z88l&-PcFcQ(sZjJ@7z?#runT-c$+syV<~dJMWM{_E#&AKc*SV@27k7x&d#F58mi7R
zoY&#hz^8{gVF}=^Hbwe3=gVAGfEwx`8uJ4hO)E_YwBw}EaqK)PZYd1j)e8(?K~e1y
zf1CVBkT9n>(6jWW9AEN1MdC~@3C*U9a>DTi3G!3}yN*H_Sq@Y6rbZ)+9B53YDJNT|
z)4&ghHvD!myG|dRj<il699?~pOY@}jFTtMZfiprgHlVJW%3d|vU^*@IjV2hm9$TmL
z6}JD(r%CUt4y#V@E8Pmrv9aFtF*;uxZHcXy2bNze4=fg{Ltp56<Iq^cdSplB)zAye
zui?2MnAX<em({V;>4N96bF@w$JR!5_mzAR5^Iy48^w1MvD`z;QR&{#kb)fW9?rw-f
zp+6Pm(vBW-Bq`^dhQgJEbHlNYfi-&Ub>=jB?4v;tG&%5FqjO#-N~3e0Dkx&Wx@yP^
z>g1v+r8Q!yNpr;U!;pkVn@v|4_RP^yV8hB)fuhl+;K6TbUHTkOW$QW{aF|yV#nEWB
z>Dh&{qN9NET`Jtz;0voDkJcEWD}=KKx0WGSu4Qt5g_E@KPF283V{BGMr8F9M+{CF<
zu`T(l=N9?WvW9mB$25BwF_m!x4ccaf)HG<V6?U^I5yH~-D;cLlm6*mN1@koc158Pb
zD}^S%qs@cIjk(KUk?*C7E?P)!iau(1H&%dBQ$&?sl!iPnQ&MJA{8To!xGCn=EDBBr
z#ZFBr>agxqkXD2B%2dXAQ6@sWurAiN@UUhHxofJ5y(k%9bZatPZUzuE<7(fU3q$c#
zO}zn*)tq_j4dulaC2vGjAT!rZb;fn!kFLKnce?AUIuVSQV?#bp1ncG4PN)t;>i5ZD
zyir(imtqMqHilvi<Jc}m60)6PkXB=x2qx4WgPKb=bjM_kw+MB__-C{@wo$Q=Sj3Yt
zp_1y8F`>FSPUsdxy6fqTg+zg{b}A$ktqg;tjp?jlQ1YI^pk6bCZE;A~JQ)otSw9*3
zsq^}5glxLg4f!kRAChra`(itr{0g#826x0tvq{_4pti@%8ykH58{@WAvB4O(HF!Q-
zqP!jf4s|~yWvDD)tdSxULDQ!wPy#0f4GAwRo|*pq$asl>Yz6@sAXsg7{SdBZK^a7D
zN{ndwM#}JO*RZiIr)$*MmI7C>1YA9WG)2m&Z1U`km~P-EW~z!!+=-S!Q}e=qBOV>f
z^P*&IcHVu4l1(<L7c-4zg{bGYiZqsy6dcNnq{#MU2}7zTRb1w}n99A_%@Fm6k!E%?
zV}hr_qGZH9=a-xB;!U;)nKY4uLr&ZZ>>nUx>V|1XLpcPT5w@P{<QR&`E(+4Tm_oBi
zxBiH^4IHdzZbPo--81o`Yp8UxUc9OdwVdoC<SGq?mt*{pt;;ojC;-=Ba0pXx>>8Q?
zTmh;>^rl1$k_H3?yR;jL@oHDe5=@JigbDiLmEwde<KjhRHxnkVV%v$V7cwnlx~^M1
zJB6_bz5&L@F6K!b#wf4r!5?Hg$3wu;N4*k$H0E||rz1-TD7yzpnSUff!jMdmw8jXq
z+x`&PbRB~P03*X+Vh2|;DcOw<6sGeSKv0e(Wj87$u{P07OON%V2qz^to?(OeL&U(N
z37B|ic2E5@yj1rT)56Xzh~<M>J$A$LX~-mBn;rXx@niR`dG+`ehPT9K$PBGpOvUke
zYw?hAR_lk`=c)CBY4q9F&y@4WS;7wX=<G&i5}d}MWQt!)L!@0yschmgQ!2Hq1M6qC
zu`OskeL6XV>Urz30BcbB${zZ5m?ji=O#Uv)#n>a@<jEV6VB&@hYTi|^JW*rBG{-QX
zsM10WrR9%B!n6P*6c^*kAIdyR-K@(*`%sTG)aEgW6-~BEbInVG*KxM<6IyE|DA~ic
zo-07|VeGjfm%37NO}W%GQY^}VHjyo+{=&*?N~AW;Y;Fm}k=}G>l5sBA9QcMVfEl@Q
zm8NVk5;tMy8!9}#m8EDolC$ZD<h2f5zXPPmkXP=tO<+SQJ$q3y8(TL%fW(mHeFTAN
z-&{+eGn^#?Ks-821QN`MB}AdE99vGhDMz{lpeeT<y?_LNYR^ZpFJ#CcAml7>2@Y@<
zPPTG}y7wpW|COq5GoLJ#&QArbQvMAk$O;y~CIJ@CtycnT5nkX;NvLx40E&+3KtKX@
zGacU>QuPx1Ook3p{2<~8n<5VgI@#ozH{?b)Il2R@GRNAtZixj!xAL13Ei52(*+z$~
z4dCC%SGp(!h`<7(^4+4SQ=&A`r)Wr@KAIeYi<B@8G|evEIuRExbpzsp{A<*|k0x&!
zlk?V_{Uw#Xsfsky^_tyVkK{t$rh%p^K|%U;Q-K#t^s5%$9)km*sXmNFdUj(DSrQUN
z#n1};6kQnuM@O^zz%ri1e*t$UqlgcZ*6<aM%m-3y9WA1!@B_q{>01xLrZ}1jnc`a)
zLAam`0cHkTA&_m<xQH$@wk|-IL2HB+i=QC0%-sHdS@K)E&?4#$8B1Ily}6KH*cw|o
zs5%$m25HJ#Fa(pf_MkNqo(G@65!N2b1`%fZiDs~>pIev2VUi99tlDMBq}&2GEp5*S
zNY{`xGzqbay=}b&ZiGG32yO(-C#E_sOKtTEfTO;3N_-<~3cwu?qcHX`@|I~ieknh4
zQP2yJG<|Hn5<Y5dofdPCMdAq)U}jyH1e`;QQk`Ny_PO<mDX8q7AuYebJWBgYlQq<k
zrr%`xG=%Dg;h*hX$$RURGkCU6MDN0N8S%a0fB-x571*Le+yP3gfvU&}<yd#ZU=0pl
z32<&Tq=~=Mij;tCwE7UcxH)qOm>Wvx3@D3x-qDJe`tt5TKAnJTdI9<a#5pO7o`7q<
z^+~)nS!~RSxHh&<K!EPz%x6Ib%^K2hZ1XOG;IvC1&UC2Nlw&Ni#yFrs(k-|1K+@p2
zAYIZRHqa+#PTV<FWFsG_D8hW$oF1-X%(JagNUySb4>D$)+Zu)Rsz{~5RY~V*Q0QHa
z7K(W_+4szG6%Pa?ngg6p_B`51+t4c^9iWRqMb!aVr(A6sTid{69~^2*0uM@fsmaTm
z=!`?m1f-Jk*lE>mW0IRUI5ox1gk2g_+A7woDW#s~;#P(>cx>DFr6t}1CaDcw@bLqW
zm<zpPJmM{|^2S5nUVt1u>4`9Sh1--BXroY8LuGBMN^7W}-C(#oKw1NyQua2=&<Key
zdTWG(u^ea~3io&^4Vxh$Nr@E^D#A{g8eZH-ZSq%Rg@nGaQ>F&H)@;s=n+Y{L83D1A
ziZQVW^V&E=3cnreIF-0tq<iC3oE7ulI7Ny$6|q9((~4cG?F%HWS=$$st2Qh2y)@-j
zOE)*%BJHZZOG=Yy0H5oUf-XvD=IA0VX}Mg}1A*^uBxba-pNYb^krNZ~x^)UbBNaG~
zdfieIMDcBWD<C7n5yglooHe)M#T3edBg(aNZ$#y+<FmQ*YBBVFwy}`H?TAH5GxD)f
zo^A6*OY)T=r;@D@ipL~d5m(xT)+E___FYIy?Wqvar)_&Go@7y?<NOf+r*E4oDZcHO
zGQn_5J=@(%(%3dt9G=hEjwn)eM8$3f>ejIx0%e2QD76zu1T1eS)R|@L;8!lvzVAY$
zo_*hi06p8j3vqdB>*Y)Fc{YBAv^>wo&-KxO&DZeO?=6as`v?%%?n8ynvvwb<v7h_x
zNlIOw`9n<-m6Kah?sX5YLG-h4_g;_T`F8X57@msg;W7+T-F#zYoyEH7=9zUCA6?8d
zKF@$zT-A#(KW_6ysZPnR{dP=taRV;xBeD)Y6^&ko5hx=oSD_TSWJPU2_-MMx`spnB
zSvwGgr|sNSwGoLDrKrWU%`$JBO4uTNDr&t<AC4lRZPU|Y)<};yKzg#~8P(}5fF|`j
zWJHnnR6D!X3m1qE-Rg;p0-(P2iuG5F_aBuAJG0^{U%~v)wduFPZ$$v>J92O7J9k-p
zP+QdM@iL-SFPD%p`*^u{mYuDa%gib6kC%`sB9;c>$?~?vyqID;)d`8az3KIWDxu0a
zCN54_;xeCgT?x>9`t{bzG!jKYVYom&(9Ljx>Ytn80tLI9j#EBeyTTeR{$OnH;aCyH
zCmK>gdmG!^JI6ZZ&4S|H+uYvKA<YT{G(=2xMg0+)sAmw+0ZROi?&r~?MPcX|-YscB
zF>e7h$Oh3Bc}GJ<Z_n0kWO~|%p@Ru*FBwCS<VO2Qj8|cDHdx*pcjxd-rIXPnMypsi
z8>l?jJ8hFJ?JXB2A_02uTc=oRV1y7|s`pZk1}b~|)+YysXUZ5#Qha?8!wQ*<q~yQ`
zJ78dA>y!hVTc;e@RG(zotbq-%?Akiz$Y`8E74OYBfhyiKPGq>jIs{~#NHOc1ZDPiH
z*8ZO0(W4&geqHVA5#w;VEyfkC{QEqSy0FYGu_uuUdw>$7a8sY5<k@V;7`&E0Yi@f}
zhj>dzmhMSYZ*aqF^>G<HS05Lz_pMKk!)s``RDHKi$J)4W-C}8cH%`Z4mNtp}A>4>A
z>ol%EpX!Bz*Is)c7Z;R7*yLm8*Y-Ebe)%nM4SD%3PJD`P=7Vt`-OF>48@4-Jv5mbv
z7iWIB?9op;y0<cw9GrA74X&IU7~SAiFmX|(2@C}@b7h9^0uF9i^@{NglYc44M}V~>
zJs#`hqx>5vMLi%l6W52LmBO#G_%b9mGqi|a#*LXOU>}kjJhS_dWpieWJsPG+Y*IsB
zLm#>?01(lIzo$xIDqvxWDzPvTUi4rc37UYx<4_;6ZNoR#2ZLVVJ`1#llbzy6FPWnz
z&f+0O9G<#9?q9rlU6nr=?bC+}3=k}_58WTr!8_d_2mtC8ngl2h09za&#n+~c-9P{#
zKt@vHV^h{HSPyz8iSUPRbfY}t)SQhR$`f+xJqC!9POHfAMPSJQ{*b43adCFJYU2Qy
zB_p|oi7%3ryk09#YNoQ*C#~ObJoj00lImM8W68{a*A#KgRge_i-<`#7=ptVPE+-DP
zsdNPT+I!hf;E(T9DrFix00i@*4_{a@anL{+pB3VQ(`Z(8TO3AZF}a{;PO6Z{A_YrP
zeJIdN*AHKM2LN=wUvh>=AXFFfsa*(m>}5nj1*CpSA`lzZSuDw5U+ES7bfIo|uka`Q
zW4|g?qNAIXM${VULY6h=&-F{sIMhDqDg$LGm(VZW6bOh4NG0?dgj~u95p0-CkGKm;
z$HkN28W;>yMGQ%U9RW)S%t>BIjm$z8eT!Ivf`ITORMV>Pq$_pXMd5c?H?UR?FXy{f
z4wv(--5ljiR$Ft-m+M^%hg)|GN5Z4?#(9tWEkyd-qN{otsZdI$SH#kNMr$f)D|jp1
zXuDCGpx=72BlENie404T{pQ}rWC?Nh68iHIKxijPBcaj|$!0leDU+D~LR(`{8E%_<
z>ik4@ZNKH@MlB>Fxg{mXr})U^$Rb2C9^>@_G7h5)<-dZWGU~5aOcW|_^}B*2p<4x9
z9oPqn7qmD-5Eq5qbBs<N(i`X~i^M4;+ZLE!V*q3vBhRUT$Thw);N7$E`J$OiTY*(~
zzPNh@R)L4TjCwZ|;HSxIk65xm3&bR$<34hsA^*ESvbNu_OJ%<N9$nfi0t;#7{i)DO
z9Or5IgM~Bj5Yb)^!`0rRVtX0=o-<m5EwDhx4~(C{Z9G6q9!T{-^zNeEqU412Zbe3a
zPn+KXQvQ)bA|Gfh&$CgIPqGs|dHs4C+76Hw6TO0#Sm^$&z~l>mBa02phyfLfl|vM^
zSC~?UY6rk5gX>THjgsCYL~9|J0^ki1;SM_+BgUN}Nq<ni9W@>Otf+C|8@OVfSS(^u
z7=PcQ^%1JR2uv?%F|f)3I`ilwGHZpv6TP*<<OAUq^XuTaYJo7|-cRNOA|!ti_JIA>
zRs?^p$gLTADxCp13pSv3s;q)cAaI3DwS*v91m+mbfV$NjQ4~`FR7_+b9&RN&EXu`%
zh#0;xe<Do3Zl;kzpiH^QNV^EQUW_bNW>=6E@;8ov{bl|`Fk}%py4<oZ<0H$qIALHS
zUMxn}gfD^VyAV$zAtgpAAQDS^o)>0_<<@nR&7+wG9x}69Qc?xpVFuPA(asEvQ$DZZ
z-1CCNu!ipn+rk>Sr}VnCqB_I1S^%K{^7#NEzf^fd5V68@0Dg!UTmuZNUe?i;=ov0J
zwH6>=ZpxYkdWEZiQ3L9PTjjmsqh7!UK!kAP7O*Qnbn9m>Fi+X8hQn{ca`R_ye2aNR
zfIM&&k7m%AD;jJCjk!IwhL8_hSR0J5i-6x~kd8(lN5j84&<~F!E!m8iu?QAh%oThi
zgT-7H*ak347rbQ4H1{J&Ov&r`v;@5M{El+qk#)Y{*&#77wyIq2OL1X~GSH4wv?(Dj
z;YbM$pM=;Y&6%%_TyC$db%3n8Du=ZMX7$Qa2b?Rx>yMWr#JnkW2oYjlIq6#^>KyQ$
z!_%psxzb0FIN}>478DAyqg^<!RhgQbryGBmcq1MAwh2E4&}7cCYYpa97szZ2YpM%{
zHqvZkXAr5j0Z7d&OC2F!UU}*OWnPp@4L)<40we+avn#Bwb*`?iozC@DI$xGyI95dj
zFue~*{;iJ<h`xYAU}<&5<F&A~dRo5^5Ry5%oB+e^GKjOvp;vBtRzY+a$Rqt1o4L}{
zkpt^QPi_F=^Y-XdxB!6i7J1V7R9Pe}R&IT-eD$9Fz4Fx^rMeXqcrZF_k(eBx|K*Ak
zM0nUDFgYHwQ%UQNq%LRHy0dt>?!GX_dZny;J}A6W)?thFE=9SaYRV!3RRD*+q7NJJ
z?H7g9bah(OJd(5)Le_r<jCt>9#Tr!ly5|=3N?&*Aw_f?{0Hj<LVhv1nBb>q&Eq)e<
zLiYpBTr_3lqQ!6CSTJQR`mG)X9uYU93sk+q;_8*&4wI{Adb?9Hbp58eHLI8$AfSV=
zJ17^*cOS-1#1Nre<b8Q0iM<NGBPB!U7a~es4v#h{8&i4n@ISdCG#j!(UC8zgp|&jN
z^2&HJ^x_p30c9@4d<K-cDv~xNd%Aon5m6RxVu_&kkgKq1gEPgu)Z}oLxbXc~n;#;U
z$fZ71YQneSs;7!l$VtJ^+~}kOEs80-stvS(W6QgcHV{!CRdujd4>}QN<<W-<2`BsH
z$Y#7@D*YbuWs8zq6Y*tU`S{B=9&Lj27zb9^MopcF(9_U~_&k&a<wPS!&0R%I(8;B`
zu#;1Lhbh+OXKG=KbuR!SXuR%)Km_UWLLka*=au-6bQji9da?X>{?Gt{oj7Y;L8^p-
zO5;(o3BNnliB~o%7`f+fq%v8U0y8DgU8>f+*kQw-S{vM5x)<_N7lo^oR~#!&y%OYV
zEw$o%5xjPwNEImTCD<(WBKB9V&#HVy>@UkYSUB!4Xq2uu3o_T-bq-(o?*#p7>Os`6
zmPTB6Ws3u-omIJ#5(mCBeH{6EE^l80Cj8+lm(pN+b$7JZouYW<hU`KwYz0_V-KAZ^
zZ0oAi(opC(DEQ1&FV1PI7bPBr(A=ezMoDCM-2$-Fx_}!lyguFaXhHU;yPjqjY#yFn
zo)j|KHee6+0)NQD14okb%bCdPULb_0dJ%*W8mbrKAgr5<G(gCuF9^b>8gH+}1RS8?
zyA6vt;7DU^A&SL;l51FKgHRw6nF1DBm){l9h)0s}Y1|M6VQ~+20}>+_y3hu*`{7=2
zgSZlWV#*g*NI)((UWh70)NXESne*GtJxne9<`x#<;LR;8)6Wfs5kZXWYDB$9S7oFI
zOP&|RMw&xa<u578(Tj0HElr(40>oznd!+IstCaNvUkL;1`8z!wX$>`593l1X;ejmt
zs)q;iPPs80Vtfu9dU{GccoY;e$TPq(f*GRv=m&wU;G+N~a9AiYDdYv@?MZ8nidL;S
zL-K}r5i}tdED5qcJ%-z9P*f|Ytl}l-$t@^Mdl(cy2svfGj20!QT$IKwD71VSOm|9;
z7BF)=xU><HOF}?cA&4i&n`_@``V+*;3PCiCt|*St!HC;WZYesK`pL6X1p!X(sG@LB
z-I+8RVTkyd9P+Ix0$uxjGzn1b)ErW%dgehMzmSsUDP=wJKX<~VS+dKc!NJ1JNV)Cf
z?fi9sZ5uxDjP`b?Fn|RxntW0=?t=0QbDP%;u_(>OT~dZ7fW>V?<1dQDQ*hvrPPHYR
zDP`^YY)Q-zJkZ;vHG=fETa19rw_9>X3OC=4RvKT`<dH<k_ftnw?%qWizqENm!PeIC
zPOej-)7J7q;UNWB{j|*UKsqAotn+|Grw%#5soH5H(OKN_1}w_a`=|punSeK49rF=t
zh6{u<pSsWBVeftFM&sl!U4wbrF}O@O5o60(?=>lD(sI?1=yzRd7~-QFZJ^By4H8US
zhRcoF{nU*H>2&IoxRpB;?z*^FNZ5%B7BN(d)G-|J$GL&3lms_Wm6G5F8hmOZPz?IW
zR}${AD>2=<f2y_w_YW&cjMA?-_bL4f-=4qdR~;+4D46*LehJd9`}K=1*CF|(?{!)r
ze4sU<bdnFTeN?gu@nEj#x9&VkRmf@ZEL8=Gaq`Ggy@*8O3_>(bsx_vJBABl9z@DX*
zOV{qBl|GJ7H+8~Z7)_crW<02dRGEj7Peqk<pq)XFg-$zz(i!`pVj^tAPD_IxCVdQb
z!_tnSZk#CJik+~HePI2CWk0z7Lckwfe*x<cy%(``<El3tCwA!(hnhBbz5MVgiU0$k
zI-(g5N4RAl^<3l}9(BT5HqWnmsP;+4v*~=F)I6&SRlbHX`pK<b6{xtk0cO!BU}58#
zooty+y|4tcsTY=D^39;?d$UtMRhKIL6EY0+>FUJcQpwq?NnL4j;8iiH_NbcF|Igan
z^xT@`+F|qOSDazrL3bqTgVfZ3Z6Fy0wmYLB6C1t(g6e^9U?lnX*&^3kdsn&7d#X-f
z6wrOdcT1x5NFqg%i%XTr@nR)1yj2Hk^4L7A-}$6AYjK8MwXpKxrgif)S1E53%*6al
zxn!l`g%+W)X?$eDrhPt4N@E{YSWL}zR0Ff??Zb36;M(;zZw+9~yiH)k`$H316;VZ*
zm}nyy6sB$;cDO+k!C;;~xM#iXdBcZ(g6|1mtQRFqvrLFJ4GyHlsU(~5*qTEk%@<Ng
z|59n{S{W*_AK+Xy-x)W3m;Dp9H*26&zgF%|_-!E#^)F1f_mnXf!**G4`4iURsDt)f
z&V8r~EHX?GILA9rUzr4kPI#IG-bp=?i;za@%p=)Y3sZoUhHqmxvmU;U;Y^J<E6XQQ
zxZdV;=2v{1+v(i(Hp!QB*V|}6!c>Phl;FdIj?dt`!$66T4(#~-=ujV^%mz<AIyC+U
zZw~BvsS=0GcL(JMEf=I0p%~kErO+W4d~#5lz2K9Bj<oQ4n!!YCY4Gq0zB<sIZUonc
z&Z^+cgHq_h$nfOr5txPEHjwBpur%KJL~)l9uJQns)r*n?ggenR`f8Lf))dkOow26T
zKX4$Taw4D6Jpch0I1RSwOTfb$PU8bL&vcl<x9C#p6CN54P1mzC>fsPIa7qy3dLX)T
zDvIV(K3*hih_jwvc{m|M%6z90rNu&zpPA4WFQkQZpB`8rZ>aRYnx<3f@ZDOOfB9_v
z&iq@!8B@_i*Vn4y6&OR}tMxnc@B7u7Jq4erYk*iPretUb=g2!9C_SkJ&_3u$g>KJZ
zk})ZgC-mly(FC8|Ihdm-cMj&@i%zMy2im7V>t|~p&;Ju4o^KC<ODW#VhhWOKA~%Cc
zS1e`lyp;MHI1a9#Sv~XeG=MYOeVV3Ll+I|`4)vgUZ7WK<Iq7GmB%5?in<h8cOh|n~
zIpvYHI-A9Qzl2pO=E2GYw|w(`ChafE*>EWX4k8QXVpe(L;fXetQKH=0%6H{}7no!E
zJEu18jDj+{l>F5FXgY)5RiSEFQUXl6lz_hts~x%NpjMe}9;KTvQh5X^i*|4F2m;si
zaoTDpAF?W4;RAwvkI)LfxUvn-4=1Nu6dyiLxvA&d#R(G#A14~)ryQE<8Z_n31n;Za
zfrI;Y(3%JooytHrkxXzZ>C=RR6Ym&P4o>ncoj}E!nYs%@SGxM5)L=}Lgy*SlnrmdG
zncXx^{MgD0U+H6*)BX}Zo#-Y~dDb_1Kq;rGt|7xEMlru!OH+tw6WLbq{U4CZYf3rc
zv2drr)~3;ylLDzW#B3GsHq#-hJQVATAb-hJAoB#KRxa2^3f(2a9k%#06(c>7a%48G
zZ=4*n(fTxjww1n_;LdOvYZN9ENkV4hb9S9=uQLAaAD*YLlQIkVriPSUv+)^Y8ZNf<
zW|bRM`n!U694Cr3hbVaJT+xp<e#8O78B0Oylg?O;wgSkmCrLv;+V~L%2>tn2l<I6|
z2~w^x*&E%AW*Zt6oqxMN8x~dT8Wnwig#<utdK?WM=C;gPzeq{{^`ngspCsh1uZ9pf
zA>d3pF=VFt;s`zq<ItkOI}LKzKfmanbk&>s!T{zU1@x)g*bwLhy#mJ3p1eK))Utlz
zoBt5D#T?}{PJzPb{7c#TMY{T*_x_voC6@rfopuQDlow%YlE3i!oD}Hqb23yydk%N^
ztD)AQapBLL_b68s2XwhPGgg4N%xiYIBMfb<G;WNbPbe)SL$I*4tPEyl`$hJc)X_1*
zp->Af24p;;uK$Y+O{1O=t06?##RB`Y*jwa&CU;ZpBakkp_(vwE5!yGf`;C|y0)ml4
zvIBO>jBjbABv&J(5W!ITqM($#alOH2JAxM>8iR3JdqAq7AISySt23krJ^OEhe)#Hl
zDeyaoMg1K-L~DLtII|3hjo_VxPagN$TGRLNg=RP%YA10oTzboG)Q^_#Vc-+{1$6gt
z+BPO27Cca3fEB(6py7sVNde<vxB|T=?4HA+u}^??U7G?v{$k7;AI2xq23%0cli&ib
zGl;kWfY+YH2q6CUBq)F&x~CujT&hI{{5ylAZn=i3gB8}(;angE(tpb^{!PZ_yEI?M
z;=5J@tf|B4iZc-{JDjD8v=<)wMDT1{oiOEC-mW7E82s0A#jggnZwSrlk}CdC0(>FB
zGsFxQ^sWjF?{r?9CcwlliOghN`*yLy=uW=kUrLU7Z+s%eTclAC++um}C1$a_w<Hpy
z*7p*(c}_lK>jYtpx?s5`L)7=ww>=nwL=-}K9~elBQiGrYX2R1fqhqV(-70*xT4lud
z_33&*sQ6C_sPsh}TW1A~#Y4FXCg5xbfN+0#DGZG6-pMIrySF6NMnsZw9$ZSz6Z1sP
z%?MFqvQ04Y4q~1_^&QHuFv0j(Ivh4`gBdanLd8Psuz+EDEZ4+fLoVHKV5%<L{sT&N
zrOV772w9g5QjoWFI^ZZ*==h{3+)$2-xo3r*gAqn|FU<?!HP+;`q(CY()dz%J2MU6}
zlw1c2l%H6A?_l}~134aL9+2*7v2+vJ2wg?g{=_<e$Mw&$p^v50WaCZkjSnyx=uHTL
zi7oX;8Mu@hq%IY?4-2c{LAd}Kbbr9!ed8ib#(oPHVKVj`HE?Mf@*9{y4<CAVpSvJ1
z_*bGp;G9F4Hs1V-vx~XmY(Ia#KblX(js4Mj0bOkNwF<w2XIC9#NqSeQF5gQ6a#s(3
z6Jg(Deyob9u62NHVr=mI*csQW=dg)42tLUcr4$mrT202L%cpTNHeKG5a}!@f>OH(1
zpP{Fq$$<6QKdRMaw2x{v7ww}~Ugn1KP)&G84!N~XNSq<>*vY_mx!6v;jyywdx)a$x
zh|qG&g{KoAl?oijKkDSS;RDEIth}B(CcyuP&~7iKxPho)^gJIao+K47>!VTu)htyi
zbeQ$gQQ_3gk2<v%0iiS9J^*&6BPvu0;bsNi6QyV3d51VYPmxwZ{isGwlBr5fk$v<+
z#G!W`u%*=i73K{~G!frFWF@~8TOaU76PnO7hExnj{@eMeRUlL6qgsJXosU}g5VL@9
z<3!SlH)_-L`GM#(k)>kL@;m|Q_y&f$6hJunM=c^usn+@coSK9ikcD_6W5#&fgeMUQ
zY<*NKZr4Y(g7ne>;ZWdAsmP||j*^hzvoI*f+ggjPE{V=n2N8h`620q|^37-nmwXb~
zKnP$Hdh#13Y{E--2>g6HC58~vr|)#lVim{_L6%K8_6pT(0vn+p-47iSMY(<_AR7jQ
z{Vo9zYnVr1i^w$kOhPOuU-GQ1G(*ve6Ar`!37#jCth@o?ru#$4xGDmyj@utn<8AOn
zGV0OSN1Z$(x?qixv<j<^>kAkr#O|Nzwmg*Bed676$fB78EUdlpo_p|bAM;-rc(S-_
z2*#;InDclWA2kT+0R@0D6xaJ6RnufTl(*hAIm8@%S6b;u_^wh=i$^u`lQp5?B<U1N
z;(I;|YVp0niA)(E(@Chsf_9sD=N;|6%j@slc7&na+C+q*lmg%tCXiT>_}YY_)Rn>C
zFqHfRZx~8`0z@}o621XZD2F})Q7C1@a)|ggG@TU^_gr_>5Q{ZA?=ze@l<zZ~IF#=r
z9KI?;8Bs_Yt#LtCfs+T#q3I5QJHMUtKJEaeePkS{S8`JZn29v;rW`SEiqipm!nlyW
z#*OV<MlJ;tc;48l;&5eoiN8cR)s+y?DyBp^6HoSbD5u}$E_Qd0=xva6pqHPi*?d#F
z*iE?A_W=zMbiAEDzasGm3jnw3I+1seeauu*-Usvn61jjkKuSu@RJ6k4tyw||bA-%V
zhWF>^gY>pNB1x77Htk0lvlOM^S#ZxjpCrr)3{A#tQJ;jNp6+T1SK-Ov0E|EC&F#h%
zVEm%Y_xNh*C`T43Pli0O-&{*EKKL(+F2R930?|G?Pl^kW{y%;D4^RJg|NEE!^IM0t
za>2}%y7IZ1ukyqE%YXg$&(9rDd-e0%|9@5gH-CLz<=20Ij>7p_-`4$1_G+(x`|IDH
z|LLFq-2U8Nef{;Hpa1<&fBmOE{ZIe$-~a1B{U3k*pPzsG*XMqc6=AP7cR#z`#$WfJ
z{kre`$AACrzrE_+#_NCo%io?}(URX*qSpK^5ti;(UqG?BL;IcF-hi?B6}Nx-U;p#}
z{ZD`WzlzI1Q^Re&`hTsp<}qJF?(edBBb#3ff?N_t{wKH`1>pMym;c-U^6$juyi+;v
z6pnL~zP^sc_L|lHcbTN8I=LKhb^PS=f2;)O3RN2Oqx`)}qvJ;tl~4w7&mWkNnW5%i
zuCagjPiy_@zyI>fw>vXhW{1nH@B8Im|5&s4mk#*%riSn^93{iXf6oW}yX}=ay^zk~
z)nJKF623EUtcDQ$%SW-HG%SB)y}#6`+4fzQ*E#&}FQz}g^eC;SKR&+HHs7Oz^7+-+
z<|#p?N+kTCTD?xZYw@+>%SyWh=)2aYME$ZF&KylY34d(*Ut-B$TP)JPfBZYs|MQcN
zu=|hE4H`?n938w1-qkvNe7>qiuOU?%QjET=7M)9Z=)vf{l)qbTPwYb(wg2d8uhoAI
z^xrv3|J?qO)jtrQ_8yx8*1jBD<)MGq8tunRdB8j5T}$pFUsbzGC6@AlO13|i@^`C2
zx6%h7;g5;37rlFr(qP)(-vQs+&wl_0iN8lD0M9Q+hY-(qHN|{>Sq=V+?`m{t{JL63
znY}9^`QBGmZiY-OteSoj{^$;P$=~bPoOvz3H~s&}4ghAO28Z$wMhAG^cP-_k{<0ck
zSl-nX)beFDM47#-S$r(z?^c67;r$6@VECyW(60yB-#>)D{R1-K%wMnMGk?cIhB-u)
z^q~D!rF_9tmEC?U=*Ms5{P-PbV;M2u$IgB)r$4;vFFwzA7X3e@^qgO>-t#-w?uQ;o
zLjUTZDum;YY9i2h@&{(*KG)6lk{93BON`F%DIz~LB?;pCW)sCP#|E#ecO?<Ntk#j*
z<6ZAf`MM%}%0DWK@^wW74}Me><tIKvzoAh3bsC(nzr#;_1?IZ_;8c{ahX||DM@3P-
zu6V6ipVd(QveE?r{Pm}QQ@*Z<aD<PFqWr{{$TX<uhdbiuB%>in_k&kaz8>WM^%e1N
z-`<q3D@N*%AN5H1x*BYjAN54}vf@bR=65xgf8tAA1N@G$&iv|2{FI6~fOYo4rzl?!
z5B_E!6-D{FB0$|gDvI)TMflKtR21dwiWOt=QICY5`4-nXw3L-Ezs1jq&c1%L*xr;c
zhsbEGPfH3ZUsr^?#;52d<?D*b!TwQEl&>qs_^gzrpZE^>Hu2*<@l#6UIlozGZ_1ZL
zTZN4At|!9R)ezM8QBRbwD<V7YM@3P-u2@MJJ}ZjyGpf^dhTA{f6F;XrEx7T1@G8m=
zmiDjp&|mAAzkK^`!{0sV@>BHwK0eZ>Cc+<6Z(cK1=B}PurM_cunLl%slTkRk+@n07
zt3>(H2rZpFKI$1VzI|P-ow|*vT037{Z&|IK{p;R9_)#@lIPn$Qr-k#6e}r}eQ@^9x
zjDO%GH27hC3{Rf7Uyl!YZ$2t26VBHa0Xy(fQ9uM=SG4$Tj~2hH$6n8>?{Cr9PbmB!
zALDv@eCK1>Kk_kJ$0b`MZ2hZiHY%P74zTKx@Pldyn}1hR=94e0?G8gVtL^@kp_<hI
zcfzm0@=tz*bG<;n_XzUy-{6e-o579wdj<!$qjxp=A$?g5ZXxe#@)P;0S|Hv?)j|PC
zUsjVDxV}LAj1~Abu2yPg{3~05$t93C--A;gq%Q}z#z&Pke)RK<n0i-0{=6@%*#4+s
z`$s>Ap%`=hVJH6MGkxPl{}ru`;Lr~r#xN)nz8;tZYw=wzh>Y}QHKcHQS5r=>FRQKi
zO>ZlHPj5if<ovVzlV8AZ6w`OUz&~)}``~jL2RFWaPGhz192}~3{}|nOt083bT}?5Z
zUsc<uK{Z7+5`It(zK8q*EdS&e*w-WGJEzS*paAVXelxiJ<wG2+Avy26+G-!8`);-0
zs=WJmX}lZQ2k&YEL-?{90`m0*+WF}0kAHz1eEyw1@DJSsJ}fh&e0gDl*VISFH{~a8
zh1bKkF6h1gD_gBPQbK&N`a$}EE%#SbgW}H^s&8!2#;etrmY|<G$PD?aKUn=B{m?@C
zn+5Pe`WZv;>jH9q*GPYAxwdi+{amka($|JPAliRceUpC1xOW3@`|la){u#RxvR{3$
z`$77FEo1-6=J2;~Z_3XY&u%Qv?;2<Pl>MxN{yw>VlYU?di{CDW57JM)>dn8b@#9nI
zXVg6!kUp7xlYU@5|E(nX&7u9vxBsE_-!twU^PlhN?>l^rHEw`<eeB;3`~SP6{&<Gp
ze>q{%$E)^rahFi~)BmgK`N}QzzIOjV-<2x?cjpu<cQJ&+P81c|6^cqn(#Y_-Jw*K$
zu`^L&N|#bI421P?!X!lb#fLMx1hMv^DE7=J`6K~7)=NTo#h*pFh=nsUF*4X96!VVM
zl9zx8{V)uQSPQ@r2q!)Xz}LbVlvH^m!>OxOYRxApV5@>f!pmb2i8jL-(GV4%8jPAx
zN78U%z9OS!D2N^jB|~XeV`Tx|Elh3s&m*y9RCxVUlo|p68jztg6m4HPZ{hSg0s2G8
z0#dmqpQP076S+9U83`AT$)~q{<>n0MWgKV~;X`~m_<+H(e9~_bY&kwJ<7$w+GnCvm
zf_xDY6zM!K0o_JUE^)3RFt>=qfwO$P<NX0w|DxQ&!KmoPQ>b#GoV<Vn3FYk#1Y(4s
z08YaPVd#H43WwAGAFw3h4ATS3TvX1Arzph}V>nL-U#$w4r%i7SVBp6lOwa*XVJK-a
zz*J&0#t#`nLy3-070_KB;x9rKlC9WG6bC^4OUR?)7>pN0Bq+F-TSjl?=pI`T+6564
z2~dEvnz4D0gFz>lyZI#-ViSq_Oz`Gvs~m+crH&Q^iNt1@%6VH?&|vY$sPuzekFg2y
zj1;7ofNsmNGz4}4SC7~XMa+1XV03qu^E+=qZ~-+h1ch*R7V>Yq7(!ec;%j10LahNS
zFW@|S{4e!$bnWPhflbHJ7q{yHCg7#i9zPW$5=aYvqCN;?8IepN<b`+wA7$_`tq0oJ
z+^#^?i(S?p#3RKfB-h2+%OV;CMoCg~LOLR!;+-cQ`35ef(&px<lq0u6%oLEq1Jb~c
zP$7F|OjU<b`BK;-=1N)KD>=c7v!(RCz|@O(a`;MT8jIqv17z<~YNK~x>^+x+zUm|k
z!87zWUZqes6&(`-Yv{n?yA%X`b%d{75*vX8T7gn>#sJI?OUI?u0dXmHLI}>`lFEAM
znkk5(#jMM%TJ0Dw<k0d=$Bp2;Sjw`CEDD#xZXt=5lDk*B)Jp)I=B3o=xbu3eEf)z8
z(Ge&ZOKGMrVpx{h3zCz>Qs!V}RJ|0WDsG-7cHtPy(&!w+Sr3ZE`BX0@y%ysQJCM<0
zDXn&c{91KDJw>XqOmzeawkArq(V?+Hel0)}^aj9zOJT>5U_!3AZ+o>`hXz=3Y$+!^
za@am)ExyIvXG;m60Xlan==orL407#&GmIr++A}Kk5|F?d_=d3<_1b}x7Yj()y#Nny
z8NBvh8be4u?+B5N)zvU0nh-KBrIu@B!&TVGo(vqoOTwS=g=xIHlv=P&{TkSB%%0p4
z0I5J$zx5mQu$$6fLMR&@?(8v@M!e4|VSq?(5klFxq+|w(G<roShtjNc;4+5tL%gmW
zwYuIpVLGB8LcaT#GEi-yyikdQu6=VUIp`-z#lO;H_m`+reuh`6<_QTBIuhK5Ks<Uc
zu-9PjgPyV9fwTf0xoks81Uk$n!IS})P}3|p=nk;Wkgs$HK4S>+|5A#zsTl|`r}R~q
zl#@Hvdth=Wdq0@lsTqK9o4}uXl9bC|*!-8WvWznVkdBv9?E<be1R&BgK>yCvK&d_k
z)!7c5)DWJ12gqYgW1}6cy|*E<<Hj_UE?Y_p4`hK*2DnS9>F?^7GElkYx<Lji|J<cm
zwTx2*D3LD;O10PoI)6zuz^1Mt5(P5fZDa{&8M4JhLdD-wo$cdjG^OK&viMy}PP;Pw
zbt{oLjyRt<{sef^fi3x>pj2;Tp?)9^2|(YoMX0>bE!OfB-2A2F@)YF!rQ~3Qn9>16
z`J$kd`({uT?m#{c;>&kHUxYB`X;cm6gS?asc)ld|yfHe-Z`&9l)#i?zxS=$c9jMUH
zC1Gn9qDLr$<|Pz|OFTpF5h4B(io>PT*dX?R)^f`$OY8=MPXO`VaCI9?JtO;QjH#|6
z`Nm||2V>HK0GyKm<V#03+!zA>=#>ulQqcEk7!eih4yWA^G)xD6`K4s;zDvTjZBRw-
zg@Yb~hv|6px)ksSEcF0jOfUTPCkbT7z>YL${4JEw_EKtsySlQRV!=0e^cl#T+rd>R
zwQdLFLHPEL6w4v__UDpvNKHNSSs8*BkolqPz#S=NLm)K0Olwb)u#17x69QlF$O90H
zRq9A08^m7km4i8I89bom1S@%RM-tgEZS4UWD3_X!bO&KdC(*~wB6}`B${-$lN4nS$
z22RH|dQniq2&I=-3WqSM<w*J(gkJAJRJ{c3+Tmc{i>b?kv}qhGA;6rDqbE$-G>)gR
zttNw<Z4{F$>DS1?5y}kSkrO(Ex_&9ex!_kiQn7|f%T7OoP)_oWw9$dF9(?bqjsdg~
zLh0#9ArgXO@5noHDLAx{L^_1D-X|bB!>C4QdeqQMVn>#i5UhF!HdiE;Pe<;TFyr;U
z1I{amyWUG6hhWz`WcH<yHAqC_|2#>mwWr;UlsF+U_Krk4VbY?Je&<rM^XF1(y1Tj`
zImWKe2ga!F4Gk#duhXd|1)$gaT={P@0vXqj7=euIRELo%>JoU)0LL}@VVmU@a>Pej
zKBFJaL0Lzm(_H-Y(j`M^L>;LtlY*}Zk=CI_BR5zGxV_KUwh3Vsb)+i06pj!wuuIQ|
z4j$cAi)P3!1v&Nh5QNb!7bi3lUrO-;rFqt0DRSlkC)AkX;e8401A<E^?;V-7qbuii
zuWQMruwPu;0Q}x@m5DCh8`qsnG5#dk3Lz);yfj6Z<_!SZOTma2?sZ*zwa^TsGbdID
zd~9@S)eAQNKGbk8{<U{;bG(!^rd$%lU#G3P18y;dDt{@t9XeI-L}-jI#d{ev$po42
zfONdBO6(Z2ubT!0;V0PnOR@5Af{i=<g_B)s=g1Tuf}y{ZS{sH^tqZB=Yd%?IuXs-o
zOw^?eRN-jzNuf(I2V(7|@Jg^CPJ8{J<Ybr94S3p1!EpiW$)&JWV625e>pQG4FG`kP
zB2u_h9a+gk@bw)wouoiKF9^wY)Guz6P0D)V+eVYB4uH`YB};(TiY9?xCaX)RLup+$
zswzaJaO^wMj74)Er3FYEP0I6v1Qd#WUyy)uS-h0|Ol_-SyoLqw?R(}uzeSw33pSP}
zg?rWPh2XIIZdn3W^{a^aqHet#ri*6fOG);z;WH6>G%Ca!`d<jvzHf-S290=^AZs))
zcOb@wfU_>8dL1%8>@xbdp=J%UHqb1jSQ{D}q?o|Ao(=<a2n)ZbfjXL0=#AT5gMPg0
zG`VFqTPMz?;Bz4#S~Mxl8<MO^7;YH!8+F~Z%}0TCJs{++YEpGKZ2C<W=?ziVnx+Aw
ztSMuBuY~I%ps!0P{%Dkj+vg>a;SD#%BLf7WRxgRYdzP@>kY(*s(5l1tQRe4-VtGEC
zA3I)QE(Mzj(5aWghEwVFLm0pg<kZKH6y#lh^g{)Chx{zrd4T__aQ_C~_ztdiyB}%C
zc&oY;c6%^D*{t#6<%BGIF6FvF9%<0~V1O6!s(Xn;KQdbb3iVRZu|poZaLz7iWf}b<
zyL?g_e^G;zo(;%SKT8V%h~k%o1HgN+E2X(0N|VBN3@k5{z?=kcLXi5Aij16dF7UJt
z$Wd2}eaEA#pDBrfhuIeirTpd+%t&K@DRr{=z+hyVPT0^VDeQQHcj?&x2KA#2k9TPo
z23vO+0bOY#dOdFYk&X;_c|X#T3x6{yU~u7+bX`(>XAwsLP%|%u-PAekM~3Ho<#%Db
zb;oPNC83**$(2?Od`JgmREKkcADNyD`Oym!?g6Fzi>X)xf6+sBW}p{(NF^@J3MVAo
zlayROAyYFT1RdEZdZ7h+NJj?jpNG`s0`Ys2#A!HSPkJ)I^ezRbQM4?fUx3qHN~wc@
zd2>P0b-=xONX|yX5T$8XK(L20$9H7vyQCZtQZ(E$c4w4;b79!^C|7PW3d`vwky`_E
zy5b^*gohO8F!_Yn5m#YO9&ej<7^YvEbJRM&6!t#Azcz3TjNomvP8>Z~{)}7BJsmVz
zBTt}*l<O!#=|ScC>G-27$40OEm%zTu40<W-YSyTzNe5obFNIw#3~Hcse=jW=v+5xm
zHm2UwW9I>-n3b9w8@w7y$)~hreBDbS=bNiknlkbex`3K4rB<nQ<?t-ASH~*Fv^$nT
zQ@@^rll>YC+(W7~Hh^O_-(46GhA!D0kcKWBbySI5LHxOtUgn&6kx<O#DF3NTsaOMQ
zy>)cB$GZ!Fq=XK@1NrB&QJ>U7+-0IZrKY%R^PdLhOJ#nNlGEz4N}rx3ocqYu<1U^0
z)CX{RUiE{Nx$aVjao)Rpsd^?3a+mcP(4FqGJ|D<7UjVD_XJm<t4X^_J_zW;2+cU(~
zrI58z7Z!IJpG)ky%k+GRKtoL%$&*}eRhLr3nK%MZ-Q?V-`ksHOR@pOgZlro2h)23&
zJqf8)%WJ6GD()my&jNSSqt6C=v_&TpM)4<O^nv_yDBFpR;VxDCY)rod^VxMHNK)gE
zienk44+NmgI9&>xdsoi@I=-X@LJd-T8LHu>7=Kc$u&e9KTVp=V4xBf4Y3Emm%`!GG
zKyzJbS}r9}2P$Rh)4rv4Bl)At1M5<f*)8KW)bdMV!>0`Umy|7AYgs7XtwCUJ>gI-w
zkuFcHOUb3W<sM>4BI%pjxfQywZ|de&c_ovAj!V69sQRxpWk@vXJMe=Vp{r-h66zaR
zrIvju>GSX+p_nXe@dUxRx0r%pl*^UjTIhvY@PL%-ac`7vqf0zNC~jJ+twAd8rH+wW
z-8Xe^YZKfr^*k}H3#FRTsg6n{roUG4l_GCX{JXf|mc5kX0;;mLl4g6TLu8h7C8jYX
z!t>2NY(UNSZEAR97L5&;J>v0AE40CAaVZ?HV-ii>r%;n?)-C6b-CYC3B~V#zE+xm%
z)ofsmP@gtfY#cU<r%1JgOBFWQeO!reE@h(<xjC3V+Mypql0;uLL|d<$vNJi(C0zdG
zpmhn!-zqb-bzI1O(GYz}6=p|6v;leD7Y)(Ydxqh$TL`ulG=v!PM>^8$+%kjt*iBvX
zlyAoX3hyg4!j4<sqJnL}h`N+IcMMrReYwV1N|!H3-^eR`3GCc3B5vM3vVc>kLp&;p
zj{*7qQZz(J$hFlmE`MvI;}VZc+q*+NuFY;I#Qoap8}e~2^$h{Jmd2a{QrUs5vXCYP
zy0XDc?Q5~Cg)uGlv@n3Fb{7UPX=k=do_Z-bJ355uni>^^=$h;b0&_{}wzT-We7X#8
z0=}qo8{Q3k4fO<(xrTazmDAT?S0ysn(4ZX4VW3n?!PGJ2<uVBiWNEl0_8b_Ispr5~
zF?JjnqcQ7=bzCY}SFI9~a_cfALA?~5aKLc(#lM$0T-2@2T9s;e26?z>qBi6Mb_HKt
zN`2QRk%7mp7YU`D>Pa)TA&rL9q05l0*ymBtmH*Y}QO|YjaFucv<?v;A1iTas))0!T
zSOhbO!0D<55jdT!K-^7N$F)Qp?^I8biWh3qhL=yDv`(ANS81ys2)w!34|1_w3dal)
zIJdfHbTO52s|4AXz>Z5}eta&ryfA{LhEr6+70e8`JcTG5o~kbevd1=9p(1U_sOod7
z6~sA{GYG~>Mfx#wOzzaAKr&7VYUE~3O5<-<mf5qz+%pHd#%*s7^$p=Uho%L>Q*K{Y
zZUbJ}kPj&J6%FmeI66)39t?o{@OnnPie0=O^47&JMCa^(VU^-d`xL2xE~Q!>B{!$+
z-Ui1FpR{{lO07cLy)UKMr)GUAH2~SYZB!NZ4AD6od&ZS;(&%l-f8^t+=Z>40vRN5C
zTwD%dHXsFuH0NOmF_-2%MwY}H#NLpSJRtT4mE-}TH$v<|=nYm#Yv=HHAGHdHi!<B_
z2W{8}C!<SY$8bctB=iiMjGVVFrN-kZ<y4QYo>!JA$;QH1B#s9J;E=Wrk1iilo(Haj
z<+fD~r7Rokqf*K;CD}3rb-ySm<$4=Zod@L@U9_x*>4WxagCm;{+N%xDZkNK2^N92z
zbG5-|?nTNH#F#v`E~Q38B^)t}K88AuzvKrT>KAvvA*~!s%7?UaEIS|4rUxaNJhp7M
zETIaL4`09oFgF``fvx%yRu=J4YS>t=lwgL<=W^FFY|u+#zmR1^NouV&x{s#5aknFO
zx4{ea5->6F6m__C+3Xyl)b?pvV!tq!8ineFKs2f2l`-!U>XZjg?j^9vdU7zS-pIt~
z^5wdeWEIYVPmz*W3-ttXXi&)K%zv{N2t$)LJ}C|5%XLXL9%<tf($J)h&yt2FWgIf?
zaf3FF1ch!=#%Bpkr^lBetD!3?nx&+4+maNO3o%LTd1t8_z#E2qz=#NbDaN1VL1pXR
zK<yoqS`F2~<>F;fFI;KWtenWJA+(&*(xhg?5#4QS+8{1XiZ?vky_~#igpije&3l%-
zG%4OQ@Ik0}BWv;{(1cOxN8E-w$76^*!wgRQmqL~yG1KqMkY3YG`tgD=H0j3+!q6y}
zp}<}OP7P#NeyxP;BY#axwjs>Hjh5_7sYTG$YtM=0-hVEkX085gn6RcsttL#mH1v6w
zua_~esdwqZ2pDmCb6Lfm+%nF#1(DW|#)dbAUf-^6LM}Hg!)3{PuuVv_9^wSj4Bq?q
z+abfU_fXH(DtpD1PM%wa*q#dqgMQ#`d@1axZggGh^ump<ySjlGl)IPVlKXg<a*QA+
z?^2GJX9?RHQBs$}M(~hO7sdyqVt8q)Am%!?=T%a!OL<-pa`5IdCSkq=_6<3wR2a<Q
z<9%ta((2izb1zsuyE1MWg3`Q0#YV`Qcj?#_)#iPwAKdWX+4C-`Mx;Gh_L)n-{)Y+Y
zQgHUb&T}aX<vM4&H0m@TxxBdynUq~Q`3ymVmx7Kqq+>UFCK|xo8~{~TVTQMeF(NOs
z)1AwZmiZFcHPSMB@9G=(!7kN&SBV3JxwJzoM~I{|^68h#{*atWpWY=6<+61N#hWy0
zBv<w_ecf%eU!qRPH?|?_<dJnLxh&gJtB`c<s8#r8d!wDY;#9rKRK05@d6Qs9@?@7!
zmR0WLOW-jNGp#pj*s$cfQViPOw^aWEj+6A{4KXG^EknSsH|fcU34T#fx*W&|jqJr<
z{#Or3#e($WT|Z!hfhpW5)%3{(z45emNt|OyCV6OC1x|aD1sbrEFA7Sz94Y|w0cj<n
z&V_o5c$HDebs+C7Lt@@b(eG=jr0P1J0Gf1Nq~Y}@qcqa+dXx6+9XnC(S(eW;-ei)-
z3ywFMr18dc3G5rPtC^-9k44_3L|4SV%ZJMl^Y4u+GGGBN0Wmn{Ba0jn?sW3;x|I4}
zQjk5L5L(x85Mbm@`Y|5boJkrlq4<|5MY`KdStuv-jsCrc)V7zzo*@R6+|iKBb{`qF
zy`<nS53g!yWf6x0Qq=APo3_`@Y%3Y0At&uVGHE;H;w7=?6gXR6V1@_QtsIh8=oR}w
zhxXb;w+xS!ODguYd);3p>BmUpx{nlOyaw+B{kYzXpCpid2M!w*<a%@7$KRb)8V_Xy
zGCWl8^EOxm6J#G5tbrP`5A@~)71{FWGN6uZ0^XX#!hb33`nD)rH6HJ`65JT_W$q&-
z8tE7JJGG@DdE%D;)}^d0zbh3h(te|a+ojZ-q(w=xeI#h3*9ViX3nz%J1epd$i7f<8
z1Ln#;vO5EGWgnWI!!WxNzF`>DK&i%KI=!wdND|nufqm)FQF43B=gWe4d(eR^mt^e*
z?eLgcVwH&nCJS>+d=mbB5y0;Op(a*ZGQ4uOe76jqJD0*v7p7Wx9abJdm%@%0=DMMj
z^Q`oqmy)BSch@B(S36{Nj-4g;TB_!Yf>Le^xqjV*p7~iqz8zMOESJIwD%rV(kb5Z$
zwQv-KgR|OJPmyxonMBkQl2A%DTDuhTT0QQNWF}Wzu3eW@Ly(a=QY`L}of@ON6m)zr
z$Su1_)Va1ps(94dcPThTGKuOADdSP*#2wJHAH$d1asV^Hxa@$YUG9B5q(j36a4QX}
z9T-`*e7g*ugga!qhPUAk=+$?9X9>KXlApU^gdUJ`QHCtnNJhKm+I17w=AsPg)yL}V
zms<T4r9MCOYT$kCkm(v*bcYn}V;CiO`;!TFlS66AXMjO!$#pL6kp7FK>ryxm@NK&!
z)~UW_nm&+zLDTf9HgW90Bld!0(li3M*&VV=!?SiP%dFve-g4M79O1h%;pR+j%%&{S
zB?h+35DiJOUD`FggEyVLp3Fj${I~?`sZFw7dhscN=5p6K5NJ+Q^m7w8=el=l$_MgH
zURnmv>lX#3;zhRT1HF5@jL~rMz7%$S3aS+IUw8a1r>#pV?)^cr&`xD{KBoq=)yKhL
zsB|-#^@f+%Q>0u!PMvwc#eU0eYXItHJC)`Eq?Zky=lMm+wztz9J)j)!+~=co$L+L6
zUqZ15&HASFu08BiJwv?tRL>A`PIL6gV1!#{x8*_gqC6<p0I8x6#4~Ik?6@}A_Mv`9
zExAFX2-B2rAL<8EQjT6sZob{r)x?BDBY#E)dfYO(ha8j_*QFH0rgk9*y{lcgxo+<q
zLy1A}8Un;1e7J7820)E`;F`4SuJM3W%d)HQmn8J2em7P^W49X%fqQ)LLbtvBg+JM-
z!;VXV-215A5|?u8Vix;Lfx+OCasd0F-TE{6gd~*5)}<tCJJcv8;SO;NNw|ZJ<|^GG
zULgl}==(qrmc!NqQZCc&>KuY_yE?CHes9N6yp#Vb;-fxEyR)CPn%>^3gl~%AuOwkV
zAVe%lwWOYbK(eG^vG!7`l7t!S`3+wbecfLFN|NVkJbL{+Nn`?vzMIstOB%&Ey#Yqr
zSCYWB1shFoRJ;ZZIZ0vThT%y28i0mL60UTYmb{0)e>d<hwd|%gE#4#8;Q;FqRAL5l
zhb4_aT2;gnfORZMSOYMjB?&gg0Xy4^=Hg&-fLaC_l35fi!Cvw?N$UZnmWtf-2SPiO
zL>?wqi?p}_E8~l#CyRjq)ugfJBB#7gjf#EEbRT4NldYvK*f$wln5#{;mN?yH3ojF+
zdzGNXjP6*)^2{Hw0Vj$5J3sr>OgR>DDsWFxg7wDXj}Ggh|KL}c8g5{?<2_Hou?_VX
z933xdH}^TXGBJ9{m3(_f8S#_!u88%?i`PJGcan-zYg~(6d|4x3e6<*OSx6FuHeMf+
zgdPo*VAdSgIqjX@b<VoZ2|ROL5{eibUQvoxV{7W%IFP2X8F!ja1VaYY#*mgv8~8M?
z?G9joB(dfIQ}W2aq>YMfD4CLOcPTaD9^!L?Pr2n^Qt|or%fGbx3UbW9B(%={C(Z<C
zvDTq0if-WHEopW9;BhV~?0?lll)L@_)WapAn3vO6nRl}R9GWDd<z4)3F}%s&7RxZn
zBn<~fJ#AjnQsYi07aMo*D233xR#no-w_~095);m$@I7Pzfg?%ep&FWEAh1rQ7+P>i
zNHMhFl8|O-IMb7c!w7HFNg@XaqoMW(NRy;s;~Q3J((*^6RRKH?3gWk_Hz<hZ)PG4}
zQqLY^P!PkdA8EU@45kOg@LMMw6vJ+kH-mCmzWq#1m?ZL0a#+s&m#|rFv7ulsvVbDH
zHx8FKz)J#?GPI6CflGh=OS!$j^}0b>x{ny5EKSAkDN3zMIqZ)?NlJ(POEI)fmL{fq
zhfdFTzA0&e<@}NqaxgI#`Rxy2A0^2!O$(DtPyHliOH%vB;_xK!2j%Z}iHAYix?N3C
zw5HSk7*}S>Wq$yjCP|zTcmN~~Q{u&rw)}9ivrz;qd^5QuO!azmM|mmF{V^af_fq%4
zA!xe~ip!197+6<w-XG&s5eG65z>>tC4z>{<!=9qm7n}G6Sf+V(z-ui@Xu3SxiUPd@
z?r%xMnK3C`6%H^ag{#5=#-woFqZ-N@rrs%78455a1*<{<E(wd%)OqKDrD%XltD%}Y
z?_8YK4rT4uWe{o1o}_^R<670-A)OnO!0wF$?dshqY_>FlIjV@0Zw?Mt*M>=ny?HB~
zkj7hP+QGExO|b=IQXDI|U`&c*1s9A-X`HXu4@j#B92=!E;tK}TuQ$aPj7f1^0S46&
z1+qd6#)Lptn85(5PLeRZg+ry@?yIRyHl_W~63U7hxCF2%<$rE6O67k-+AeAJ)3I(9
z7m#@va_ZJr;}o`QznP-6MQFg7Xohn_QM+_En89&uI`fP~*vUM5>^?Y`xChL`iPSw{
zLe4T0V62u9vt@f7ixN~0{bNyr(xZPY$i_v>>L|?7r)ZeN)!Dh!^uoVM3LEd7#KFcp
zg}mJOFAbAOXNF6{97?XUh@)oVEj4Lq+qgnZP2<X1v$IMtE~?^-a&ZYZW*}^#V;QV@
z|4A>S0T|mPk&(#>Y?_EE-lUr^rBak`z9179Ur{cl_G|j?-?Ska+|--A_cN79PS!l)
zfHHC(aZoZ+{`;er(UY_+Z+yNf-F@LUI;FZVO3W$M9bh$2(x%#SROHAu#-VV4ft__p
zC}J4S*QtS!out*CUnN_WJa8<^Rs{%*MfqA00&J<a%5?Ql`8plN8m#pDMcIlVfhS3|
z;T0t?7R9Z?1TLvo%+y6-;TPHWZHOXw>Jor6@<q}mU{S_SN%u_|TYi%dXvMme`Ar$C
zpn^*R>(u8rMeLk1!)(e}#1)K<DmYFyg{;B~#-@~ISizIDI;<5~FgEY7lN$eqkX2~G
z*c7rAT5ubpZA!rfqp*3BLJo{W(=}jIs!roG^Vqz<PMLI>aHvfw?;Ao>K?P$|W=;V|
zj!mJ7u!2j#*OR)wOFm91>znd%>b+)cnvWDnF!rh<CuMQUVabK6mxO^^?xu8PD8bm2
zj*2B1g~Q*QVhIMY{F8(UrvM#N`ZuqlL#q0QbR5#uH>G1~qz`EIT^K+xDxX0T$dhAo
zhqU({nA`C_31Ih48qT6k5vfRmu}eZKkYM0)ktEz7Ht(WCO8=%D%~*o5DMb}bFgB#<
zJD^}}T8;<x{!P2_kmm1{r3xt+X^&3=tuHXzCk=diBa_<r-pHh0cAOG-)X*H_R-p#N
zDQ<_9eee7zQudwVc1&4cobpxy2g6Zh@4Ss>xWRCmjEC+6E{QyJA#jRh#T*QWNLJ9n
zaNb}Qbubcqr<y_$1C#!byemnn1IA~S$UjB(5KQ!N%IaY#);3aH!f=Xd1||%LlpgZB
z8cs2-*o5IU0uSl+PDwqa);lHjJ3L`{iE4!>4Ci&0@d?9un^l0q@Lff?M-Nz>l7^Gh
zDTGZbyHf}oRCX@`tB8Z=QmS{8F7A}DMqS(~UlnsOobt7T4xXgs`c&k>aEe%k9t@|5
zH9BOBg7bJ$oY12Km>)&M>>kW6Vhx5<peop4WTvJhP<A4jQ_|So;pn932Zg6eLk~*N
zir>q|B7Y*=eNb2`s9*$zr9ownG7Om%_JEK{n(;TmN;tBDuQ-Y;7(r2~z=8pAnIw?`
z<BUVV2Zg613r0|QGPK}Qa3eJt@8jM`6<IKXH&W9rA$TJ-ZT~>X^NS|cK6u+S?d9NO
zjM+y`@F`<{AYLMA<el=Au?QnpmB=>5sj&ziyM#?pm?|D&1f{705=KCpT36qTi?UPN
z1Z~8oEgzJ*)=|VN)tw^h#>&WrCn;C~x;_ML#-{5-@I}XTe+a(lSgVF0fV(aRK>^%#
zH3$k|1wD+Q{H>^m2ejh6vsSjO>qAiZcHJL>!k3W`Pts~2UH6Be1Xk?B2uNVXKU_+!
zk)9qRBlxo0T^vwGGa_OH-+vSlF-{5O?kHgQb=?CFg>k2y|3J`o>Gy|%R`Cww=wjQY
z;~z>|MLdi{LCcVbaZn<Eh%rwZCg@PuD(GPxzRxP^VE`E@No2ry>+8G*96tVZnf1%l
zF)8(vD@Z%__Cq<^hxFk?If{sdaUdkSjP-{yvP(-pl#%_dr5_5(P6(b$8mzfMSggn4
z^S!1pBG?qBRto>QQc__GuOcT6YW&&Q=XguM3-sVN+ojnb3eqm!{!mJGiQ7Xd*&C08
zLowN<lph*@nzZu6hZe;xTv9RG-kumIz-xo-K9G|NT)32Clz|Ha9?wak*gBM)3SJn8
zva`uxe@b>XZRW$<X`^v|Hr`GZzc3pvr;YmkY`mN{Zq!SvuUFnBY%BP)8qREde`)ZA
zo{g_B&D9}aUs|SRnyn;k+v=?2Q#JZ%%|;2U$cWh}VF^rgX%w+-vwvJh6&^7g1#HGg
z++r<N21q<f!)TWnFf7%!#K5Q`$4>c*G*j6SZ?tXUCs+_uW96$(o9c?sI&IRgcs9Q4
zG`{1_hKHR-{eLzJ<u)}~3gwK$cxI#YZA0BH6!CQ^eie2x8%40<E}q#af)#l&8%1y%
zDAr;(jg{h;ffuuFY8wi@n2qAMnHZo5R_w)Wd<SZ#{x`La#^Yo*dPlUbn)HrPgvD$S
zx{9%w&1pYXki~42x{R`zjRLkcv06g5@sOD<D6kY)F&m|<0xKqV_EBKPMCj5vhrIz^
z@0_E#DwW_Mwqh1)b(YzE);<cYn7z0-c@{mO+#eqWQcRqh=g>w!D+AV1q{IZU_rbCH
z6zP7FgHVYHxbRzM-}PP2p(;NC7<3dF@l1$}bGG`rQspQvVnXm7#6?WR&z(bq{p^sU
z=WO*oFedu)%)(tiijJ7TZ$D?D-GKotKHbhfvsh;f<ncLEoK0}TtNR4d&rx8+?C?oE
zjEtCtYJbb*Y+-VTSX-Fep-EX_cJM)RA}Q8Uti<d)OYFJMz{5C+3H9hGPGWX=C7xsI
zdSjH@$E9W+1xri>qMl=H*zpaGGHe3t=bUQdveCt6fUz!C1DtiX7-Wok`h<#l4%<kk
znz$^{dK5V^k*VQQD8rD>;hd(P4_K$xJ~Jo8QQ*X^v=NtrQffv=krNX+wNB99Kao`H
z1hx8^Nwt!Ig9ETY&k5@E6KS+ggxaYi>jbU)GZSYW#ZOEm&N`tyrW2X7UL=%?Iqhv+
zy$)k1X5Gw=!Y8I7dB9Qp#Ka}<D1Kt%CU}Ad{E6%0k>lO8@hWW^38oDUXS3%rBA?jm
zdgS=F`W+bGmMFq~_Q-K>A}IgFQnd-@sE*GZ;Syu3rt2tFVj?NbiAm<FwM!s#CGidd
zC1&Qv$|BDTTbS)B-Zo}?s_$LXJ=AkO;+)Fse8oTV=N$RmO{B&;2$Z<xn(LtfdY0HN
zo?1?rx^aw$4|Wqqo)eOvumqi;Mn2P6bjsrKfKZ%t@fP5vgSYxC`Kp(d6B55h!KT28
zi40gLn)-!kQ{2QX;EtoPiA%_Mpc7??pU8=I<Zm|t|8W9V_zC0NQ5eNc0FmQ|F94U2
z>q}|HClW~=*LJS#Q^yaREi>Z*lJ)(DWu83B9X?^gJaW97fL}QZw3vWrIqyJ=iL6<N
zffh59W*wJ8kDOUY8N?^DW*voE%s~OEP>YGYSx2E3v(jcAMO$1#E=;F(KT6UZcb)UF
zB%gH4o3J$>g<s4uv&2p(#wWFYB=GEECi01_Xh#lu6Ir)jlq{9-bgAVq(w}#>@riU=
zM=p00=KiB7jEQtwr}p}I2~LGz%mH-I<5JQAN_3Qdd?J_Dk*D1pkerIan3YcJIf}xV
zKp%QhvgG&%LtT3fPwG0}PL2=03C@wl`d95Ox!X--*E)=>n3X&0D6(Q!?yM(CWD0^(
zp%oL!vyMV5CUR#TMpn#xp*r5*Y(Y+X*MuC*v6S)IvV?;GDHRXHCN3dcJ5DqDB_;pT
zxRFciC~jf`TkI&e_{3Y`a}X3U3!v;ME@C1P*4eb7Prv~krVyWn26VQZStgz{527L_
zl3*Q$MNGVb9)(3ryptY0qTQ1rA5)KVi%-0_9y!NNr1U%+sx^{+-ZDF?gd&&1jwVJV
z={q47H<j&)WLalRbDq$35547Pg8Q5;wRtXZw?10Q4Y`;2h1lEcJy(!>NGCokSJsiI
z+(fRdv#DNB2)(`3HEwukPxTGCx2O8{Ea9kzJHe6X+=L&(*-ZL0;jD1B6!3CqI9vKR
z01%I|l}`Wwovox#vk-vJmij#dLy`(U17o5J4rh*|6y;AbCuJL1x6YQfjkH^5oBDyY
z+@^kzzUXYK<b@r1l*xP|>()tsxrv-xXVZIrBInj2cu0|I?Midcq+4f8Z%5Lt!(`|a
zjyOk-a?eCYt)qnJvodO(EtMM?wJrrm5)x{?C@9^<t~};*LFO&#({Mw&6gFB@eAZE;
z16Q$iP`ux7g{A=Vjvj3j8Lck?CrhCZT>>6vCz4^E6)5GD$=z)N;q@p@`7GD3BTu%u
zAiB=lAGLDfEUL<DXMtnG)lLp-6W(iQ3C(AwciUM@ZEj53Qk$5wrQtz5DJ%Kw^Fc<*
zg>4p0?^#QImr`*SRc9o6KT1VDR}K$)bItEz2Js1}!Xw|c3CF{;pzap1&n;5Z2C~m3
zk&A;V8=BVxz9b%z%<3%Jx94kxoki33#0osCEZY-n^eh^-C(>P=MKAQZDYfL)Hp}Jn
zEUD2OH@O8J8Hm(pNl(tCSZDF2Y9a;JSyG9&WeEooTw%|WJ`8u+gLL9^<GKIH$8Ey#
z_AKhd<(qrU<Qy_?9(4;TH_v;{Am)@{d?HEKk%QaJBw4r2t|8?nbmnK`a6R*=bI83J
z>Ku|!smf=b<4M5zxDmE}W~i@Rh-Xq|-U~yJio6#_AQd?U)tPU5H*#y8DSa3M?@WKU
zTl~t{4Y_&Jhi#@%y_`uMhNJqKQi<Wsex_7n<kdQJtK(g7p@-Sa=k_e%L;=YCi-J<F
zgSphJ=h$f7ekN3nqjcvJ&iY55Z4+MqXG#f1zN|C3tzQjQkyRkPru1E8$a+yw%Dtof
z<P$pEbLfROD?8RL<LE#*?4{tWM~193X`h}IS#jo&6$B7OC$pGOWK%eDNV}983l(K#
z$2wD%Y0pI^t2DIOGo?2}(>?NEn+Q!gN=QDL4C}}bZDxqenf;?uEi{>)5i4^h72}t>
zf2bU15%Vmq7%)O-N-IW?_L(w6BaZu0C?YD_=L}h)5e|L^t<Xr1b(Fb$B4+3e=++MN
z#~HFh-&<0a*)y!7OjJG{LQx)U6M^<;#GAPVUL;Eqp>>8dW#3@N)er<>Mtxj$JJVyG
zA=TL-28UE<q{lk)K$}R9b%s=DUU|=uow}~YXUI^EoAVhkRO4!Wl&XB<`hCXcF^@a?
zrLgbYf|TtFz)Q+PxwzNPB?{0P)TGNSafWnc<j*=vIX+>^IC46hz=*gM-lLH}>kL}1
zqh$e%B7N2wQkxOgc$9*CR>q+xNjOE2K<f<Y&6Pmw45`h5JKmt$959WJA;SagNk^H?
zCtx~`T+k*`HyvdqpGcy0221x*<P0geFqfSn6&KmD4ik<~7}<`T#wLt#&x?fO9gQs0
zu;QH|%QPTS&S>fvlCOZRYk(8XOHGc6wa`$?c{CZK%XE2^uzWHv){%qR1f0xKs_}`~
z=0o4HS&6NV$;gbvR>$5(=77|)Kq=RbX{Q1)=TgvUX}gy|PT=%)Ojc$Db{~_KIdfYb
zB^#fJ4?pq_n@IO|Z1aIDa8)x|m7{KICbM$jrlut16Zx<X9Lnzf4wm_2GAqM;f8-rD
zk^1hKl;Jp-PJ{*&saTY;`QU-Ts4-WHtD_|16E748Zef#;7{}=QJ@L|UOvYxsh8&Zz
z`CLw9X~tv9vB9|lJi;-l-oQ{e2Gtud3&&(>E*OSmN|8DN)^JR!H?kled6i8h&bkzw
z4FLbSl#RP0@P968;U_g9DcfgM39|%2Xi~H*ch-|6_5(?1vRES@<S}UDl{xDu4f#ao
ztRu&<iPTxgWV1%<tYcEpkvr>{l=RG<b<4Zr3?|+V50aTrB-1+bBb!L3b&M+dfvhy?
z=!Gft8e^A|e(*HWrIA;@ts}>>iF{k9OC?9Xt><*wvGa-bD1G_FBkYmK*u*pK>9Sel
zE%#D*bO8$QbSmJ5m3O*~*2txGl+=78nbx7V*psAO;9W**q|-WGMr+^@oh~gMKt!iA
z;p(Lf)MEGfs*x^cvvOx0ra7NToprj@YoyM4&C}JdS9?jpPW$shPOKwmu!Wphmr{qz
zg1^8))|aP9^}!Z?P_s%K^a9+_QS$QD@JcVYu+?gHUJASJn6Zgc&DKz>Rr2bz?tYnV
zd=*^gZHy}N0;1;W#tOLPbyI(M5a_0%!ajDCUHp;))f(n(zDiyFK+yHhekLYR#^nV+
znA5wuhWJy8@l{x)M{Z%O;gVO7F0U1JDK&zoIm~OHa*Qve$~tlzTMbvbcEs?;{%eOE
z<1wHewTs69_=2s<xP99BXg0TFQ{3f3s;twFCJHa@Ez~zer2N2EX39D(c*a~p4xt6Q
z#$~UC`i9JGp{at*Y@x2piR{QvY{Ap)G)KFzWj0s4Fxx0A`2qycX?ihQIU}cS@edK&
zs7Eij*<H#)x!9#1y~<thNmB0GRRF`MQH@@}AU=(%^a4)tX|!7}B-c7kcI$=gS_iqx
zSFZ|nwk+h<I&HCA$j`RaFH-rQHq|jiXq)P|M5q#;FStM+`hdMChK<yQYC#&xnQOiF
z?rB3+APw6Pzql5*0Xepi73(N_`Kt5a$Zu;QFV<<MZXo>NJogl-KCG!PNWW&Bn-qRZ
zaK3Pq9hJ(a(YiWbSz@PnkZ)Z*;6+}}T?^j5=bg!X0rLFFM{8xatJB&?rCM;bHZNqm
zdQq~3wHnG>zDkyaJh2vFc;X!OQi|=Ru%Fa@<H$q%Qtr$K8m+w+%4@!m*D4NF@rArr
zaY7wuLXbG2e#=&d;{jQ(Latm3Q2L>C<I7r>aLr!U&?$}23wS$mV0>Pwt;C@|y`a#<
zp+fyE=sclx;|qFG$R}$-cZx&*>y`S|i?Gx+fO+C9_FZ?gI7_|P5(%X!U&ve#hkE(4
zD)D4B!{?f8)$p|>Oe-5!oYJ=!6xTRYP1YWYGsS)Fvp7TS4=}4ei%^R=RIpd2dU%pl
zUCsPAyD4dSDV(+vhoOAr3z@LuC|T3O%^{Ad=UD?Xbv&{94E-*wKiamRg=<VGtNFrJ
zCyuspM#{vY#=U^d6Q`?Zyq|~im@izkf(~A*@?*tmAC-!`CVn0KwZZ^c$c`2A-dczx
ziqqJv|D{?bvn2~7s3|`S5lRt9U6+Up<uPAKvl4RPT9qCv;;3sp0Yx14U7IxGsQ28*
z5uv#%IUXVDjlix5fzU5x$O<JgU&xUaL2LD@lvokegBLPl1psxQBIRNXD8dT{h>*+H
zf|24y$<qDtRu>4lkD#r30Z1oetJ`~n3gtDw<(h9D1EYiYor8lZCSs`{tD!9QVi<~a
zY-G<0IC$mYO0tDglrMxUhWxcw<yDH9;$>j^Cj-A1%vmo|{$Lg_QkcscmXta;U@*G`
z_JXLVOTu}CfX|4bo~u<(d))&flanvRltvgm<rZ>bMNsud!m9{Vx2pyxT^!l6g89my
zB;|&YgV%zwGNP-U4PK>L56==gcP<0z)x*JXSF;d@K@;{ueyoVb5tK9xS+N)Fx)GAp
zNRbsG<r^uoB51|_Pv8E-a~ExU)qMTRZM~|tzqIBt$LrejAOHQg|MsnaYp?(6fB(zh
zp5Wf7X8-mLA}Q$f(EE#1z25aQT7?Y6y>dFe=D?_Hb)W-8%OAk6$OW{1(~sX}?{D1S
zx&ip6>DSW8;fq-b;JSm<ZOmcw&PueIl|-o}1K>nkl6kbkZdPPWCrFtBw}eI|2%rI{
zghH_ZO|kLg9SKR?E}2%w*$O71(=A+w>GFxYhx(s**m?VX=p~m14}|3&riOc9#*&`M
zyA+KQ3*M<A&+J+ybG=sne65Z-UbXk@AKv=e{mVrHJmp_4lG?UhB{dMO652F=wMvRp
zt&-k;vr6!Ht&(>RW2_SAHsLZ6Aima#fY`NG01U2`0vzl2Izc2ZR*4`SK2}Nmc9jT7
zZW2Xf>HX+etK=P;t5xFbH;Y96`n5>t(feK`wtlrn^p5z|B9W={`7q&Wkw|2|7l{_g
z>)Q5OA+L4O_dP#e|5&qk-@k8xAP6~xw~Y|wkmo4iA;ZfE5cOlYFd!N^=tPPmH|Rt9
z4JUF4svD~$^qG(wA)L=>NR1F)SAT>chuldkZumvubJ<G*1wBAt4GpkFV;Tfl&;t}w
zFP!gUB^N{fp5@j2B&9Yd9G^ojpYV;o1awj=cF+ej-K%d276TxiMmm5Zo;aL)C{`BG
z8RVwpa6y=G_~IQ5;l1Gu(8%E4kk4j7K+0tkp}vtGo25#H4_-H+ZUrH+zrl+>oT9(n
z>_Y(AaKw-F;3Q6NIB(ww><#DT8&SRCl>8aj8&0_o<?=<yFNph}^RO)KH0ZW@+WmL_
z1D~1_8vzi3#5_q@S*&iMmxnwtp}L1t9^o*%gpxi730uP%_f+bC2;mwLAhBUcLySns
zl@kHFQJw=&QE~xnTGCDx&?PQ<^x{0Y=WSk~Pm0?o;KPYKRmfqpf@Om4n%@vk6LQx?
zv`rLr%9Dg*k$VdHO#<GVuk$A4xQSTZkl!W(bz|#7esH<lypQ9KnuMC@y4h_S%n-?Y
z3EAPoqLP~@Vt8ZoDvpctC199&sgsW<^ccv#rzrWg6EgAa{B5nUvoR#x*kJ*P%?mrM
z1W}kcPf=<_w2+sjAvWE!VT*VXZUOhe&F8a&m&4e&&LcTbY^we#=t8m!acm)Zg1Fz<
zQ?nlUtlY?Dg9#xZB6K%4@8yWxjm>NMIb@3_bj0Na5fC$OFNA)Gq)8#{!-JdOHVO&E
z^j->dQH1nfN_E>SqBn$m*b&eh#65g^gQybjVMl~-?9vf#xfU%2Xm9m<cH7J59RfJ)
zsYS%5g4+?t8=E)yjxgTX4V~0gZ%cvbFdxR^{k+4*cqweRj>1b}yAWdwC`m8<BMaml
zVr(684>`6dTRXyCV}&|~hy5k7=aOzK)G;oQD=;7kw-xHUZjg&1*e`YIRdW0s_r68>
z+7W9T3j(%R7;Ol^uvZlAlO%G1o8F>G?Fgccwbd}>+~O4{jp?x@RXgnMA^gG)oBXA)
zbI;PoEaH|&?84rhQ?@j(CGOT#qmXxtPg@;N6|tr&Ay@8;l*N)+Qh7T9=tH=L9ccq%
zaeH=T4u~Zmu#Oj-7wMLI!>m!%cErYpFbg|geJ%xE_cT7m;ugJxnk3V;0CMkrHRzC9
ztE(BHnOqVZvMjNRVQKXDZ39b#f3LY$uBeW<*bvfTM`UbLYG#pr@>1As#r?z*2x+g#
z*bvI$CDeR3lya^Gao7<#8xvx?ciJ>{f$XolcnICF<B2j<%JYBnS*rsiBMPDL0V$af
zLSe_F>!sl6LsV=`|7a+WhDq_<Ul+d+K4HhJZU~;RBPuo~Wpqal)tE8>bYypm>FT;f
zmf#6H07?Srgf9Z*maqvs0%tF!4hICz#@y;VCD+{Q8Io!)wi*}!O$|>+^lZ$!|MiNE
z4Z#m~#Kwlu2RmY8W753PJEhm;CAuRvHh?|YGcq;=KG@-G5W*hp9Rh4hu6Fn+#H5#4
zha<zKpzrc^2mudvxI;wY4!(v6xc?CBU<Vpc2zKyN0+ndUfkc|JaCg`)V&avmSM+NL
zUa$kZC}tNo5J|um?1qd6G5Ivr5&Igmv)PdaG6IP-n<fDgsbB^lkZRd!Kf^00CjG=Z
z@STFNf*trz0aU@KNOwd+73@HgilGf`5JW@r5aF*c3QBpg6rSLv<m8UfkRgQ#CU^<C
zT!b9h5y$$395y=wSwjw+9iglt*uZX{CHCXsm5_lQ?qMN+%?=l`kiTY!pIOLVQ}!A`
z26n{11`z{0!e2wqm_5T^L)MKBIJFou;TUjRLLQmD0$h`Vb`RL2e%s-Y_oASbtSP%{
zM{H{dC$J;9HRQ3`5!@PsSJ{r}))-T#Xok0jPy%nc1~5^|-5`v>j#$@_zh)o2#mQl_
zmoH=pAg}{HKN1YE135qBh}jY8dMSA2=m>R9Qsa+SmLU=m*cwBU7J;oX`1^eQiqX{%
zgd4E|dwGz?klqU?(-1IV$FO4b_oP9-$;Go{f?^bBFWDwIz>dicq5*bJe+Uh*1B5>W
z2-pF^A9C;P@YjtYIXosu$P08wBx~4FHAp;@wmWu~SOXHzf>zm%Xx5<1XGbt=ScqX<
z(F~eyg|ddA0xzNTQb7gw0f8r^zz!37$T76T4?E}>+Oh4QFr5g%6b%3e_QD;_GCPkf
zv0unP+wTzu2Bhr|Z}hM&<{;ioyE|RlgMfig5^@O&Fz{0HBf-|%aqfm3KrdzB7c>mR
z2|5H0*vpweDd4Ys{X@ur9pL~0573T)fiS@hbi@<{aRD!(h9uQGW!8s98d5C`4_bX9
zv_FjR0UhAGVcOplhD4LPUGg)GX048h+Shj+DCVv*-i14W^}~!kLuQ&z00h*ADGhUn
zz`rDRG;&0`{z7XA)BP8UMVRitvqYjv-A1%*m@c@8mJRD_c!FW=^oaxdk}!sq1@aHE
z3h&O2V45(#XLX?FhbaMA2W)<r_IT-f(U1DA6&juTHlk~T?w(JQayGkk>giR&h#^M1
zF0&J2v}22>%KT)RjNtAjFU=0sJGun=gb?l8zJ-<lBx!-LvcyTKhnwi{2ett7lIS^H
zrR(arNkrdh67sW4ajv^a(2cWa6kK#{(*+#C=#tV1rHf7}U8wWXwIy*^yA%u!v8>T2
z4ZyvES))q`BbYThHzi_Oqia(lb}*0|?S4K47)F;;oFRzOC5I8u8hx-`2)izQcfmy^
zT{`>gG98_2F2YnpZkZjSsxJykw>L@BH928j3_w10-D+{mk1jnJhJcV)W-nvG6J4@&
z;bPbM_uO~AscVS1E<Jcb#P#-`_MJtXPYd#^-q`?wA5Hphh0(tMoLtwRtF>Bp(T=(-
zOTQdCJ8U-5bf;Y<xuSr&Qlms9>?LuqkX`joylw*_u5guW6vGR*-)NG<3xceLx`mrb
z3r%s|_nI!s2&jEtq%7jH*Cd5u8H+|KtmkZ9l+(5r&2<tZn)Z^|FI>yy?%8+C5{?f9
z(?-)BnVC<b@shkD2pe6=dd1F$oIN`%j?r`}M&6ZZ3U=<WR7P9s3$n2B=A5R^Xf#XT
zataQ(diG68*p|A6By5uI2&lglj<O_S)7^Sg61K^n@d_b-&yIN6XhXG9tjXE4BVP7W
z;G5bJFndYWY)Q2?#0sREoI5*k5Tfa|wIk0^G!rv;Q)`BHSN@xG0HM}og5Cg)2>EvQ
zjGm3w)h{Gg!<89vvC(8+F5io2jIikYC9WC-Cjwfd(bKCVs5KfdzV-g%M`q#;3_q9K
zW=BdYKXl{jnYStlY`5;Seh%BMEAJ)HQi`}&Ke83?+QTl_&A#jJ?6?kzOF^puXt)$k
z*{J~}8;L^ihgM)f(7T*AJHk_6lq~hz6dzr?cQ_XC(X}I3)sIZX2v+qY6EU${Tt1t<
zo(cWP<pBUNFG`k5l6^QZAmG)H@?>>nY;!qm_6&G+xoh5XdOe&P>%d3S1}ZT5CrNCg
zlv6)bjf`S-iuVClb=O7g>f>_R><C_Uxomc1#q&djID=RHNE`NvZ!vTfdPzb*Qil=Y
z>hjv`2yu0JZT5PUcH}RAic*V@DluS<{75Cn)3zTOpz-qUblZF>55BX=o;Oy5RAj`&
z`jLu^AXrxt-R{VP=m%T2-uzveaXY*MT$yn@JO}(x9Y%bs6SlcX#V)qCR|_}=kUG*&
z6Zdd$IZ}t2gVI9^F)~%Ud^mey(z{$ZI}qtFrTQ&Xm%r2H_VT>A6!u-mf-8S+N1Uw7
zg|j2Z)$vgO6e+h>Xm6L-n=8L<hhv;8zio%}oClQTK)PuUS-t?G=5*lfiLiEy?4~4`
zhs<7pruWz~D~4r}-Io66a^dXoAoQT-3?D;R8r+UJSr6Tm5hv?PjN1_>>+<95h;nu1
zv+c|)>!HV>N=NG<s}`W<U8!q3{^rbF+bho1D{t)sO0knxE#UmQ+&C{Kw|z*P1~Q;4
zhwY{081=@4P}xgCzY7D>r56+8>B!kJVNP`ZBIWS(!i0Hu<-6^0ul11O3;wx|)V5EN
zYSn4K=DKltZFa0I7xG?5kgEspr%y+es{=8wM|mh>u}5jG?%HPvfxQ$*1?)xnICW&H
zb~rip%46-W=U8l8ckMIm?MtElRvz5$y1l~5+vV)k5%217Zt943y=7YWPtPK|fmn21
zXc6w}!piG7Brk=v09fv>eU={c?y@Dpr`}!L3f^q)xSyVp|K>@9I8~>MQ-|bm*B(QZ
zs=M|WM35u7$Wx@8+qau3gq}l(g`{)WH5Xy3PM4^DU_Ww~fhvO@+_g^;mFg~i6;Y`!
z{JRd!cX#EA?iI7)LbL0L>u|x@b%cJnYumxi(vd;tDN^oD=f=yhRCnET5ti!dL)8(I
z>hhuL2ZjTe7ga|{>ZP#bl5eh!h?vw%LAMZZuKY9|A*t?$QmsH;o3p-d%m9ve*Zufp
z_>Kz^uLFhIUDx9i7*74YWR&X#2&$`llR5(R*5!%Sp#onDTRmX)UV*K(Z@zguwhDxL
zl2n`<qNQApScZ5i-*P)e2&-?JqOFj!AK$$G8sM~Flq^B!?NHZsZFBl-8KS*>D;2$E
zAJrO!mz=Q-2;sh+^&!o+i*bXR`zsQhY&jGNukB)dfHB@?4LI%3_2A}sC-~vb)DXJr
za;!2$uKHf$xwP8H=`m$>QFM7s87`B)mpFt>+q|0^?xemI=480I`d;e&o(nF|DMNUx
z({suY4C#W<dkhhizRU1zh^h2F)pbd=JvD4dwLR1ku=`vPdImFqZ$9%HOa;CNdP<ol
zhbluPt8c|Q8G>0aiOo9LH8qQC-!?Q`m%go6;7h4hW*Pw`qX6>^?&ZFDsWn(`eDkgN
z)lmI_9YcV^smfp(ayeBQtVd43JY)WdOF_pK%Ia{MG6b@^@be6TtiEv<w*D$C!E+f*
zZ7zo?gE`KHpl1lA_I1>1sTN*XYfn+`vXs-5A!gg<G-ZhCcKJ*hAl@B$7+=?uOB$%g
z-s@cU6&yjG-M&J7y(H*z^#iXSU-aj;id%JhP8q^hT|j$=u+<j@rTg<u6QaSa>vEbh
zn0{SAdj>prUt5jBiGOXB(xByQiLZs3r6O#|9ph_h{3R&`vu6loeO@FKb0f=X%F^(C
z%WM-OP!M|t1O#7$+NS{~!HKkIKvM8EK5Es(E4~2ce_s;FhPYH`l2}7rsw+jT<s*VC
zKdj-I!Id7?I&g|y?p6kH3Kve^r4)3%1yo$kvNnvnB{&3kcXxLQ?(QywOK=bF?(Xh^
z;O;KL39iBAA6_~4{OjJ2y{4G1uCD5?E;h63*<BNuSZYQmV}O*F=<O09hjmTIl`x2t
zyWnFfu^l|PAnvn&cMkp(pi_oWS6-c2r&d=^&&Vf|Ph~C}K%}yuUeIk2ruyf$kU6Nf
zmA7oXykDMZA}HP58}^2Z2tF1a6D%7vd>{#85oB>k8q^vp#YG)SL&TzdtatQM_BZ9k
z(vQXsl$4Li=`U)}tUz!qqd%k;(I{6?uOT~0z5gR6ZMWV(&LUdW{-pvzp+bI$T12*d
ztnOH;TB|6rCWJ!=Q#^Y+X(?%I0c7HQ^uh|t0J@|lNj0?`9(@X>_&5Q>P$ac{Y-9A2
z`ONv6Z}k#z1}rl6*nB2D%hKtq4;Km|Me(g-2&MGcsg)U`oZGpJe4k#K%(E*<r&x5k
z1A-PZ3k<}??LixRI`6|}-@sBjl1xK{b3z>awW~i#B9X){Q0zHCR<&<kBM4Pg+tkDm
zSuE_wn1*S&JQ`!?tKq$Aupi%VB|28n_w$L2N~DM+_rCV+$C^5Pa@_anO60Chd|p5q
zKbCy83Nv%*J=YX#;C^keiHe$+<}ej`8jqQ#3#!wD!@$b4qKBlxOylyY6<;+90a%DO
zanJm*5j;oCg6`41&$}_0FZcBR&Fg0#hnxj{$uBHPoUf(p?j2I9Vjg7?cOC)+VW7|b
zM4qvUwE0_eP#LB|gU$uZT?u9@wg>m&?wMOXAE(cQc~X(>Ho=tdcdkKA^FM#9`x^YK
zCL2AZnS)r-$Keo(*S=%=7Qqg{-*_ahy9N<tF8Rxg>O%VH!AWZ6(&o`T3c2+=y*E!E
z@eNU2`q=a~#UC`H`z=QHaLa;YYmH0(!bc<JR>5n08U}HK&ts@YHU>j-F!g!592F{&
z-GXdBgbwe?70M&>4;D{b{AmU4CVOvWdqG5ZuXZ_bwX&ZnK!{~y-JmRHfRA-&v&fvf
z?*MB1vWW&|t>`BWILg{MOLR*;)S%lke%>K|?)}bv7L>|-)OeJ8g7M&1M-R($Z_Sh%
zX`gyEG4KpkqT)exq4VGl754yqM4de4c|+n%d@Y?ZjA88<YX{y#Dw}vgu~EW&lp(=A
zD^|bx>!^$QYy`aLz0_x~Xt!l*Px=+I9=^c0{9!c<PCMxtfRvs~dwLZSy&Ml|Lhg-?
zFmtctaZ|H&xHFjy+iwqg6W&1T--3fIl#zCgSh!g?8>N)H_XZ}tt3)ci;BO7UaQ#fQ
zDi<9OwZEJuxPVf69?;v7XrlM*vOPGEdc-3*j1RhuZA7sSMA~9z-7xzja*t5VUr1pq
z6aVNv$}!||+fnXExg2%0_P8HCB1^Uz2dkLZ@WjFwO=8gNNc&o~vU><nCizID$ycFF
z>Xy1dp#U&}h&Bun85djs5^uG4QHn}s8_qSgA(Ub11<=Cj?Z%O;r_?|d`%%EW)JvPT
zv{{pcKi-9`y%qe|{LP|EddVXC@0diA)n7`Jg{0}Rcto(~BCm5(y#&h?5SKj750v{R
zekHxkk8*B7ba=(b>+4v!rPP0o<XcMco6Xh}MvMz78)DytNQM6M*-CIWY>s$Gw*$-H
zY_kZ--hIw1g};;NvfYG*mQJ3Km&Q2Ct*lSd!GVgbCl+-3^D+miQ3`*Q3S2cpMYH|L
zJYD6mJTG6M&}fq80(*ac&s8O}1Zkcb<_H-*q(Wr~0$RkqM0CWIlOwrhmwECq*Gm#Z
zBSc3q%;{{1p$GtU7yGk|yS-JZcULEe9H?GvlI$O)c+GvKu0)fT5uM=W*&+XIbFagk
z6(&++o@1=|I;jx*utDj@2jIb8rD=~8rzNtwoA}s32tao4(@DUj7eZXeCgs7WwG-(&
zE9{38ut^qCC@*K1Qxvp`1((;{^!|!g<|;jD#Mt~F2nU<Dlh%@^yFX`G3OgLhzOwa8
zc_oa%8_w&IZ<J6jFiL<QQ4x0ar%0M54=U#@B?<mvVvw6m5?p{Q+z2i<@3C;pKf(@}
z(6#Uku>fGEW)m4~Bq=ZOl9^@LK*a2fMtD*UT#Sd8-{WE0WpBd{2WObOlR23RvUQSj
z8OZ>1`OTv*B?mQ;*^IXc+i&y;eBgwB9Lg=~G447Z3RT&&=L+=@D#+Wry3)*>3*?2i
zsEWm(j0;CvgK0G;S&LI*Wh6M6LA2b!cDm$U2&=q^cQpC5?Z{}@3^;7aY1ndkY>4*K
z>;s~I*TW}<(S`9kPksKOEH&)&+t-n*<y`G<R;CTlhG<7OqK33KBR=Q(w^=0gmd{>;
zq2G9GETv6JG-N<wYR=R*b7k!|IR-LB=jYbNV=D0nSsQnWU(%*l?$*B~O|AUcRwWb$
zpkniVE>&zE)qW%m&Bub+)5Mj58e0&Y4-Lgi+QY{V$J*GFtR2xEaxB<Ect4qS&&f#g
z%<!*9!*X5|TX2ABTETk&tBFW@Q*|eLbFK*wG+-HoAor=sV`#U@BKl%!KguFj<2<8`
z&u(qiC3VdknZe2saO!K9$slSNJX>Ijljp7t%}?~dDE*2KKT7IGj7jz>Z)8lR@AIm}
z`R+>HX~ceYf$(6i{V0bh#mF&pmQA`3`0*)+T`dvKZmaxaT;6J*sxc{Jel+d3)Mw2y
z+yf-r1<F6JG(2UX7IrjTWnw1bX4#`0o>G+il_9K`r5o;4E`o%?M{3l{k*jk&jgH%4
zO(cq=-*d-{piq8Pkrsw{EMKt;8rC=0$LdL65yQ`08ie4ua@E=%5c$N%vs9@RLP@mJ
zS#-!y`I;7kZEY8s94f@yjVaYDgqO$&{UXb9l^lU;-cjRMHa6O*3My6`a}GW4(%8#@
zl|_sW(e`tP((l)`?uMa>%q#~zD5N!>vIE<~jz_cK2Y$OiS`<fof|e<_@2(7XJ(2xB
z1zRQ(Pa!Qq&u?2(+O9&aV3pLVQ84-RhRZ9%Q)-P{+8f5;sUsxK4hKRzp&e}biK@&J
zsFD@AluqJ>z2iG?z5Elzb0~?8s?)+0rS%>a?=7hxkap&=d>JcJ3`8l0UT#V`(?$H?
z7v9g$ZJ0`D@AhX_o~|R`kGsDO=uXm-FYB7NSVxM+8u<H-!PSA1Nm6Q}pk3Wts%JSr
zrHyn=t$T!uN>`uwtkZX#@xM{#u%O2`(S_K6ANk8Z3=^q%#Csoeej4Q!6L2~B)dUGO
zoxPLJ4SK44U9{*>VX2pSgp)W^5+p%q+*x8G;l}+dOtJ*Q=J(CccYSc&Cl$%XV#YBj
zOw=TQboYozEA7$VkqM}ZG^KP6Z=v+%(&oI?FCaFtDLGLK+_Nfj{8xeHyNV;`i;ks}
z6jrP%aKbpnqSA<slgdnLA#0$@I0aBY<EXmJZG|$NyF29eV@R5Om>!|Ll@*iyQ#|=`
z3PK+5&}xzl<@v>IOxbL6jGCFpPt8M2HRWDfj7uV*;FPiexaD(9n=7m1Xz*F?f!L6i
z8mqD+@i>$+<d0RA7?R4MY9Va%Dt-%fa%^9)R&BNzGL8C}F9+qU6123_ax-Fu)AIY6
z*N4&~eloAGq!ITsub%*EefzVs>{lb~)=dhoI)ut&<vNX!;0qPnWJ5>ZlKc!rG%Dr%
zl8`mI4~nalu&utRO|B?EBy<O%o$T-BBz-mS0Bs#1IM!1oAeLu3@I$~usDO4Ya5F%t
zCgd#4R@f=UfuilDZhcY`989M2PS7B5j7>@gwVf<Xr5SdFn6l9IC9YYs?V;T|fgEuv
zVY@-kgF?nAOm?7_D3P7ppi)M}NkDVvbWL$V!+k$=8^<7B!xz*(U8B38KD|V9gIgBf
zOf;k-+;SJU%yxOL5c9&oO=oJ2pmZaCwaCAO%$C+M*Y)HGtibBw)~^?*`_{jgTJP4d
zo;$?~=6u+ttWR$7fS4OtZps}^CbM!|g+)QlvA(B52|HSyH??a$^Y;a2`(!%xyYT%?
z<y0+ECONb5PQa-xF7^8k{2up2tw<I*w|x4<{(4(Iev(;rZibEvHv7;VtAU@w@)y3@
zWFOBf;_~f?D_dfo$ZZ^_bVYouow*=BiN2(RMno*Ao4hi?nfT%a0j=@iWgi}vxw31X
zwfp`+9_ycE=~)!;7oG1mQVHo8eiSCbv$uPFGDm>n<$bFV$3#Tim3c7n5-dWKR{9+B
zWD5)ZaChv+l-ZEaS!ZLK*+M;K9C9}Z5~`Lz^Jn8>2<ZU+rxnQdG!GE7LDitM{;Wi|
z6AmzLYph@UzUrnwyuhmGjNt6m%@%UYKY7+gH}EdloMqms%&{@D6iTsW0$fHz;Te9X
z)n%DfEF>aI6k7g_`gB-onU9J|!xtwS%x24@PNvD;?PV!4fw9@1xYq)UUZxMxIY)~W
zI%TPp0l6_Jie$cQxl<5Ge;_-#`c^{j1O<@C)q%>8Ov3?|bi7X+^G_j_quj76U;|Q^
zS+<;p$<5ry%ufw$c_M;6apc^Jt*_(9Js1h(7&)8sQwrW2R>^KXAy$sr<~@hz`R4uR
z6Sw#nyXi-GwY}yOf1(~LN3zjH1#b9AL<J1*&H8_v51IqX=m(iJ@A;j6gU7faGh2!L
z!f2U?s^{Wc>~m0hGuAm3)-=UC3DcB0gl+IAtpMBbk7=@5kgE7n#wS%VS1WN9$c?fU
zRoE}7Seyp4gY0e7TM^YQi6@<iPyARjpDT;+12MFeI*ZlTl`XdmFi-Lv?Ssa+vc-w@
z;zQOEwkS<K!2K6vIBRirQD7rgOV!i20#WbD+2xuczu(4I2L^V%Z8AL#qqWnyH>_VU
z_D>X9_ApY1i$e^I@;!+{Ss7?jDXWfG#d}xR`EX~;fK;~r0cQs&I*##ta<IbN7wj3S
z<#sk&6J?C$%CmJM>F<oSwVLLPvxOt|QDLEA==~aUElG3=MV-XDpj{<6$;vxb7J|o(
z%}Oy%6}6EmNO7&;ypy@J++vyNPvA;1%hc$jZFNc2?2}P$PSvxK$;m-)cbW?RI|O9~
z))4qTeH0Oh{<i1>*zBfZ7jn4#>tZuX<ouqhst^s`8VQf{(Hat3UjtR#v^0EcsZmGD
z2Y{8?!^0xtI4B6IB{wtuI2)~ZAo@+vrBcKzNckTL>(<FhD`;rqH=(W+dvDnZrQ_HW
z`EfjvF7oW)J);?Mi4H9D!8zI5Y=!rQdX(4swDd1|U_3=GwE_8m2n)AcF5Mhfq(8yp
z`VBbpL(W*oQLhlvN7Mr{rhh4L32KNM28ZXitkgK7ph16aJI7B9-uEKAf)raT3V&t_
z+~T+;!q)MMXa!_!8G1dcdi+L?kJj?y?t^d6>rB+@Lfpw)f+|DY%3Feaq*VU%HGBrw
z-E_7;bjr$pN!>`cv4z3=axl2P)m09PX{N~xzh898+z5@F8Bk5jw)(|@CoJ5Ep$SyB
zP`c~;xF7l%j64n*gFWFlDbxm)5uCYJX+Q?)Z4bPJrLi*#a}k?;0`Pe9GHMvrACC+T
zrlKmHR2>Cw1%j5ckhq%{$Bgp6w!!<;GL!sXzP4PzVL@9yfG#MK+Dkk3C(pbtPR6>1
z6XJ=HuN1tsYyDhmxobT>Z}U3&yhxzW=OX2r%>!|ZCC(gC3jx*UtCOt~X$tWUwb2Bu
zGn^w-EIK@|3>4etW?AR(<5jPWAjgYqKhAS4r>UQg7f-X2g#By^IqQ~A6LY=b-!d9I
zvqkSE?l#GL*4ch#LpU#)t&t{siPV3Aemwfxe4R;s&kjFC=47A1Sgq)j(SMcBgI}xq
zO}(*O4y+9_enmpot2!Z4wf}^`vYbCZ%%_417%FeV186z+%K$mlC5{9X+a(!!_p+FN
z2ud3HZ`xbQ8fYzuzK%mSpA+QbMG{gGR=hg2$XY>KVMgE%TOw;K-F;=CGS!K&9kvR?
z?U69c=0f7UT%I(7ODKe|B3r5BRXTzy=9^j~r>V15I$)}#60I;DR7K0ylyqx`g&Vr)
zcgjnZs?KXmg7<Mx2ycg;fRUdb^p&Y}bw8>9vIk!%UE_1yLOJ^*;m=abWxb%Uj`^#q
zv6eXbm_!L~mZKrQssd@xIa<Pj&g60n%GFYCjbYv7_sXJy?Y0)?h{y22gG2MSLfY_8
z45x3KU4DTN!~xQ0z8T`!8tcL7;Q|ZQk(}gEs(o<>wzHQs0cni}2>unsa^uj#k&QER
zf`O3`3-n<0nu=%CJ$wuv(O$ily9&pUVNeV7KdV|5Z9my5d_P_H9H+3P`JyFmNezv$
zeP>b|PxtdI+`kKDGaI9|Ha2v?t@Dra+Ga)bH+i|w7z(!XBj-5o*0XA+pxO$yQ4B^E
z8Y(TY@*Nm*kz3T{s@f3hie;<y(zQrIOE)Vt`a0l|(hC^df9A~|i93%s{pfm59#4}P
z?7(&p{OG_ctC5z8d#;cD=<wGvr}Q3)U9(rwH45S%;3|9DEs$!%s$BxNC{bU|%i(%d
z>vbb3J>W{zdr2vkV(PbakCkh~5=f<*#1hez%jvQkGpBr4cMQkM6nZ~smH$8=##PZO
znA)8=x?gTyV=wGa^Q9%jPy8L-$dT~7Z#Jb>TG(zrco<iWH@7y9BQ&n6+M=Ux1~)s7
zGD{_d?(4+js_^(NVM+@DC3Mf?_n>2?tlW+$^aJHqiWbtS>2Nr5EmG^{7&`rTRG6OM
zyQ^b_P&|5jtc2FjB6J(KxLZyF{dU)wRU0J8gKvZ`>8ck==t?6Rp#v#6OstzgY9p!_
z0(w?;MUbz8ERES)OJRjjY)6)@wv(tsk>T@gmxht^t6;S0TBFX2)pp74QjAg|T^&0H
zeH}1U=BqLKZ5=zbP+FcJJKK73a-586f2Pww)V1Y!V)eG|4uCp|ommMDqqkH*F4bj~
znD?66d^>;@LOaJB@n-CcYXN0YcYfW{qza>}M|LP$%NRZ6Pex-z6#B6iWWvUgrXSO2
zx*!VFux^*P3RO<-st*6tb`D(tey8d|v&)c<hF#6RU+t>Slccpd>dU>jNfLJ+haG)f
z`~vQjHvUHc;7xLIgS|aMBFaU1i?Gg2wI|6=yz2t)RkIv@&6m?GV5K9Vzv<QN{Y)K!
zN;aGQv25-8*9LzZ+e1jt6ngGnN$tYi4ellse>(ksNHMXEF0YV2Mn!Du?6Gg-7}sx$
z%ezl`C(erwRR2|qTb`G0c7cSB%{6@llwJ)Ns+I%HW*6iR%Fh<($7U-h<V`t;ksXPr
z*DjGP&*Q02&uqWY?stvV_D=Fdb|ee?pxMPg7Q$tc8eO2$+9_+Ivy1aqK;8#AUWK+P
zl}$i}EXsHJGbm?v-R`;j)D$%NP^b$K9S#Ot51R%lhxG}2T_Ac#Lr$pJHBy>KzB@d4
z<8Zri^W;Gl`i?sEr-U%3!i_Ol)WYE&Nj;VOUWBdo>NU!p)afKkbS4sy@k~J6VdC6i
zC)%L0A<&AVANC}7HGD5<qpW`$h2fO_yKKWAD*E2e2B<KRxO(WSa!`o#z3j~QpFnh%
z;|rZY?6tQ#&hMf-K;hAjeYvKtFXv`$1t?Vdg6ef?v5V37z;V9*i(`}^xcWBk+gxGq
z>P_=v4FohK5uNI2+{75+s@-H$2=fhKm8MTvtuE>;!g)hTT%}uVU_+#|fbTs_%8^^7
z>r7ej{Xqn#<@b5L-`7e(^VNoY7GMxhySMNP;*e{~j+<*67#>RMVB|_+kOt<x;2bMG
zhtgRAX+1;_jdb32-)C%lo%8O|;6t7CmO_pBc0VWb5v8jRDG>pRdaSwX5Giq25!aMb
zTJes55D_ohj_^KSp!(`upVCUO4qD9s3Sql&Wh&O<sXE>VNSL9o<bMOtR=HCw?&0Sh
z=G)^w^!!X-3s7Opg(6f-AtF{4@Hfn(0n@`=65)VoCgK^uku*&~nJPc5!NZNtev)5P
z{3h&=@Z`q03laF%LPU@&1dwM>6#onZA)J4Y6z`9sUmh4nh<0~z=u+Zah?%XA8S=u@
zm@WMC9;vECqeQxUTHPw<nNnFT*6}@>FI^)GS<hWr7g_Hyza2j^TpxJHnDPYkLFQbW
zcK{(O-{f)4HVQ{sspCO!#oB86hTe{`HSG&$xyjSqC9F~vD)K_rzi^E54Q}MCmz6+p
zH6&+a4%iadx`Q@1kRSUE&atT-bdw$`#&gCys2YlM7!a-aCEeKhD(;qEtT=0MxRKi!
z_G=xtX#UPDY-?Z<X`%X=0W)lHp@&mekR3ATZ^eKai_kzuGPIZjLRHw{0<OdYVbU7C
z*{^wutcT+Emu7y(9Gqyz2d>6NSUPx(Jb5q;w%BRp*MXws0G1viaP%lHXK?n2nuWS&
zyoI64$)CHk2BByx&C~Z<7$NzyUxby2h-_+n?mSVXv(tLEf@4)o7}Eo*DS-A+;^0or
zfMH{2K;7)8RA+&NpQA{bF7gTZY0k5-EOSA<N3A&3w6{rllD;)me~Df>tZcz?{&N)N
z4R>^Sg@9OY=y9Zh;INF6A(Cd9;&hsb8g+H_yl-hYiee&MNO~Kjc2<V*Ih`^kT8S<Z
zy}Da&5%K636?G;T)_uZ$I4NVVS<~QZa88&e;U&;7h1$I*AfX};mfFAN4U6qSIFWEg
zI6#_BiBTh|lWS2NPnu13nH$IRUeSy!T@=4Vf{lGKG5K0&3N1^5NQ=G9)iyZ*YcEN&
z=E(TP$b#>S`4G{g^?e+bH!R@^Fvf@dXuzw_-UWpBDv?|!Q$?x~8>_^bqGyfUBdRWj
zKfwv#aK|IhG;l|sfuC0LWEF^=R<0?r0jiI45z%LVxH8@j%=bV<>Pv#GMIJHa`uQXl
z>7|3<^}@A4mI0DW)YcRyomi~2ujeq8dR<YlLriM%oD|mrK+pfUCBtoH{e~3WDC<RR
zE6oLK7Ga<!^*bxVL=Qt+CP)L7%+lNe$&|iWh2C<u$_)^5(%$k={r;>RO_-93)1mnC
zy{s;BITcIz+W+K*sn+8R-2jzDg?ZXJNE*sBT5%g>>eDK1z^Dp>4}_8_bqGHw_-`(Z
zNGNwCI}bdh<S9S6=0Hf+!hka|G#rr}h}iJKX$nIunlgLguP6gs6rc#AYkrdgUy}MM
zh*T@`!EBJQMt#nFgqo-eOV1Rm;9#wIR4ST_4u;6In&v7|P+Tm2!8=+p6<a}wCgt93
zhk3wLSv{ww8TI<j`(MDoMdcw&wFCO6-5~TrNn7wnRhVue{g_n|z#f;svCCBu@}i5Z
z>3}<MAw<&xr0tY=HowJ!-(4OP6Cr6xFu>LIa6f5=K`zoTvxKP4qIY=|!sZZD$_;GI
zVhbxXH3G6ZL?hT1nL3+;Rr|4`dIRkx60H!<jENH2L?KSFL2*UarlToWP);gHqS%L@
zj&H^x@OZXIZw>?Y2;RwYmzuJIV+<*+CTLJN(Hfc&I~-#i=$a@%X4`5*%2nJ;OCcnK
zYq?rm`j+ODH2fnJ7Kw1stIIrQf<u=L@N5MA{pJyo2=RWAKXGj392|fQ8`z{%_=Q*-
z@jH@!k%Btu*>bS81TE-eqm#&WYfauKqeHK5U9cS?`U%ovTS{%E$?u=eA2*7BnBF#Z
zGE6En(5}K{lRcM+qFhNL%CCcKdLwKLmn0KOt)uK@@imy!0MAHedle!OLlrH?kd1em
z*?7tOT);{miTq7*Iz6yTK=kbxRfT*zz;~SsW~s3AoGgfV@e8IJ3Hag{<rxR59QT>m
zAZIdU$O^^vH2oyd9EI`RKJ51MOtVnbLF;;aICAH82qecYZr1XjO|qfls)@PBpvr$l
zCVwjDQ|k=-f<oy63AETB&j-^qlimf--dyG(^h`ySv=lQ{ti@kttmxu)xS{KV%?8sV
z7FOES65H{xVs$nMj`jFRh-I+{&AZ~tlFn<r52#RIAU6~!1#PsQW>Jbq*i;IInT)fo
zD2Qfkhn%=kU=K7LLXX0htyS^iAf0LVfR!hs;VlfoCg3eh0{x+*pKT4(d5v#~#`Wuy
zc+z<T*9j}hr$RB`g;H}-(O?a^r2`;Tu%-g>I4*wzqWiTyiGHf<1MfKQpm{xijuqqJ
z=CD7D7XHK{Kb}5=MeSK^Rto#Ph>3#WT@zgq&13r;sTBoVoKg2VPS*~s295AwS!@l%
zI|YMys0EgQ$7TqUO23Q!^e4a$0w;#CmyZ4QXL|Q1LI_xEYCIIP)zV4$VxnUW=qt%s
z?mLHd6~wq9?&^lkWZCWEoq5BrXF*V020s2}Jo1B%+;)4L7=?EiE-DbVrJOD*K{8#I
zp!LFdRv8b91`8we=iWws8zJ64C6f^tdvL;?wMbn+F|{C?Nk=OJuWgg<&e&0QzQego
zST!Smmr{u$NI4kB&%qVI5}uR28~*5NMtMEy%6_5NM|p(wLmPiMUAP<FOC7EOFwjVj
z#{igq0Y^A2aC5j4zdCuk9RQtcE+%?nyQ|IvGL^2^t?X5vV6Ji?Gxu|_S_Mi}1gZ#9
zyO(43Xb@tYa>kTFM#SeTego>m#+EP1RIF%d1;UQ1(ct9<8cE8r4%(M#y;SOgeyb-~
zw1om^(~)ok%3PC^`9I5$QtPEZ=ibdmQNyS6)Kyq}!hzNP?r9bj)dQT-1+vkiN$wM3
zL{{%pPGT2W4{G5kNu)mz=BgeZIL(#?6PJDovd#mchNjYH^c@9PTwvpXj9Y8oDuYy=
zEp&wu6<gY%4i#0Q1dKXP;=*M)WkO0UL7<cJgVG0jqfAni>USZA=+N>{QJ`_|$3{oc
zXGRT(FY%(UD$WEaa1zE$p6$$N6_2)oV)XoOui_O%$3lq3K?#H#kVFg<+Q29*Z#$y`
zhd%t=h#$rjW=GvFkAa5GhEjoo5QP(F4s+a_SaxhIscM`<-KIo~_IptwNeFPVZi@r_
zoDeL6*zYNNsCNnCV<LIv$(oHUdF+`n3Oob*>)q-azI2``8@jOo41!uBtvo9u!llt!
zxh~kWt4y(Sf|=YZ(P92fb=Lx4F?tmvG0HS;zFOi~JUBlOs+7NAVD4P7Ww4j02OGz>
zjP%QA#cfX&5G6*fV@Vm$wN`ajlwma6qh3E2SPkTUQOE*dh1>NqqSs?kvjvNkW54~B
zoiZp&EfGTv5>4Hh#>)wC=z#%lLUi;!BRs{3RjB9?t$4f^s)S`IOXdBo<y<)z*)O<Z
zl`f=@wvCSnBAIxNBLV)2w#OUbRBL(z(MX9l{g*Si$3w{dg5$bj$u5M93^;K<xl0mr
z68X-N^`GJ;%EZKOQgr-vE|EaPfd41?Rx{2u5D`W#p2Pu!<|HP_2>Z5%y=?OZ*yeh>
zZy2I1=<u|1`HNZQ{8HI%wq?hLW!&8N<ZER{@KR!n+&zqVXDUp76N6-D!?|-7c<`N|
zt63JhF;zbr1{|iRThs9j7NQsbjQdZiT3`S82^N4*QvlOh&{Tqj!0aQz&Di*`f|NS?
zUOZd3V=Y%?U#LqQfG5}{M!akc0-KU*0KMg;J=%do&hy<-BenyP7R$s#Mx}NQaQ5p`
zCIICaU56GKM!iad()_iU*+7p4C9_L7CvLWo8eXqApdkex*Wtc=V%t{I{tq^&`s-(&
zQ;?L`2$^%t<LWJ=M=XN@ec~uQ^D#8I!7sM{w5|piEdd>~Bqbh0aP-B{W&tubb>PIR
zG$G6`4<R@Ej_2mbU;~^LA`D;Kk%pD%zP3ll7fHkO<D?SS?D+DI#xuw&LzLoIZq<AE
z`Iv`exz3-3@+gygt4B{GgO;P?ETz8u!YHioRF>!V94=#^#2}VwGzM?~wDz+EiS;IY
z-j`A#c@Q@5hRklsAAJ^X0%J0b3Zcn4zwVNQHBqg%fPTBu!gD9+5T_?LRLjT}4@kEV
zI-X5oV`v@y5q0#mXjEEO`}K{$){=GaKAYrJ9IQpo8-UL$$c!6+V-_WsYPXQ#$~790
z?B}WJ)^QpPFDbOw`0qby{XEs0WtjPfSowr`^y6G>F{yElHL0S&CMsbsL(}MV^(g!c
z7P*S6)}E!Dvd55ZDJWm2SpMQy9!l%0TQh?c(<CPVwv$D8k;~TL=4ZK+o}_NF!5Tx?
z5}g4fvyT3IHbU5@o-;N=n5H?}!DG61=`xqi@(l6)%mRKKUzc~s@ZZ*3@q3?JPI}}<
zA(Ly21tF}$M_n}dzyjBy^rp&`;C?m-4}knkZq<QKEX0ufA#TZ8<x(C3j{cK<v1ek&
zRuFBwr+DXc!buO^d{g_VJP3)sMsbDn?XSx^F4`20J}CNG`Wb)3VR5=T|L^hNwRXU8
zmt*-Btvrz~!&QL(QIe50cz-z}h<USozgKvFEK?VhzCdYYKXoK&y;1n_eEV!HP`07)
ze)Rrp<^Ac#vE<_Yt(N~!XR4=wRp__uU9H!-LjnA6f1U|ek<aK)Z!TiKy`JCPZ`548
z-5&n(dAHAbKYz%W8gjK-pYRd@+@;zIY#hGkoXiQlo|U|J-<*{!y}u0+#6*jP>W%Jw
zdzq)Gb^u7OU#$8R^c9(1Pi|klZU1^de4ct&ji%=vt9D)|+iXa3rEBq`dm>X%u(=+Y
zYnWse*s+M;>U6u+e|u|jns*C)vXhK#n0h8qKjGQhlJUh6F55pO=NRn(A#ealunbNC
z{D1ih47z=L>m%T|O<8~s=*peiD8Cm7`IY75yK<NgGioaEZJq{L>0F@p+taUI27(A}
z6+9byH<@`C8yw%SGN)<FraXS9liz9}yI&T49l9E8xSw4lh}2v3H8;5Oig;f=2h-m>
z_jX;T?^mqI-s8W^Jh!Z9St9VR;D|wQnpbrBb_EX_Y{Ya0P55}|>ifdp(dY?_?5)ZC
zL4&{V_J!GVAEC_7zsG)ku?+Y1RSuv2<vrqFZBPA)X7Er~5^xmAU@Y_MyKkEL<G^&w
zZdL}-Mf*q>5nLF2RHARnr0?r-!r8Sw72>R-0(+U$kBN|FuI}Ji;`30wpV4S(`j6Cq
zVt#<*8}KL1g&(YqZj%ot$hEZoGV7z?Opv=r{bj1%T3cZw6G3R-K*XGFZ$PE=mLki2
z&ii^?LEdvVR<Nb~{D7+w#_d7PaoD0_w=9!P3hwoMgTUa<Ot`vbo9xy5WFiSW)FLqD
zWomWe`?hnmF*o}>d!O?BRH8q#R8wmEMKvPi9=*dM=U}85p54Ad_m!eZ_f=b3Bz7ag
zw$h%e%A{!FP4?R*q7B*k!zk_py8a7%9hkyC8t-MZ)AFKMeK_^DExQh=Z#~<4$Sk>h
zP}291oDryE>~7Fvfd?q1PkS`_8Tw41>9Ma~)EsBp)S*3x6l)d?P0v=%Ir1Kd924#o
z!_7H1C0(*dKhhB?2t2`+P+yjDmnC5IvB7^>;a$>dm>gY@2kq^9F!Lwhq$r%adN0=3
z9nn6K*S&rVYLq9x99qDfTa&&!k&p}AgD!75F=6?&_5AdDKtfQTfc6$s!BE`7#w*ov
zAODBRC%0I;hrPS3nBcgY)64s;Cg#Xi4spDqMw4I;+NvGaR^mN5eG++oUdZTj=R6YF
z+11#n?>u_#?|Cp#XJ3B!B+2IpcYS<j?5RCvcv6zJJ#g!vet=*9`l9}uWUkA9x?A0x
zVD35l8B_8)A?A*N|8-#Q<m<cp3&Ak3;24~#oryER$<)yH<DI>c6&xEOBjLwyLPA0|
zE_M!%fB7u`@OgPZx){XV0TRjpLx3sa-;58QAtSIs$RHv_2(0dBYzU<M{2#)9QwDK+
zJHUTQo6#}SF%q%^)hhiX1eE({63qWGM#!Mz;b2P0plE1rN=Qb?^p|l(Lnl+9E~bCS
zGRT>lSQ-l3yAx^yS&YDma}hEzGcpqD{v|E~Gz^q?CS?8300}317l;3v%-=@-;(iPP
z{xB#5O*<LdIXiq9GxqqGEky`$axwk4B?6QZHFdQ#HdT@k{$T#IRwYwsdlx5TQ)j{t
zzbV1}&(b)6?GOKccuLmP&KzJt$oZdXiCfwLOq~cB#BG3{6*V=sH~GubKY~nz9IRaI
zAG-e8GWX0g4KH^zvF4g%<psVCKE64=G+5F!Qq*`N*qWdq5YWU=qS=vzps4G$LPnyA
z@G#dXntC#Xej(=5mpEjE0rgDvDEKGG*Plhy++a7y&@s^!0VMT$XdL88UY=m|9rw=f
zUB6zt*Vt5bYpS_xp0bohD2YT#B4J{C3d>MSzCFAw3ZNQQ5sBgmSl(5Fc+m2v#FmN+
zmr|y^{hr6>GgBby54EkopP@KN@;=wgi20)q%fz7IYhqNljprQ_`}?r2=FsGnv6-f5
z*_U9ADxqXD{n@0532Tj`R`;d9Q3@57YbGYv^$sVYL_U)zD`}La_7$TUd@je^#8ZF2
zM#J`=iO8EdPBOgIfUFa)OjXimc*K|R8hO4KQ##7zi@n9E{CLP<$ly37%?KR1rW9Ee
z>r_zd0ZqQJqtE+9f)jUMVX9sthO~?$;t9wKF_Uzv$F}U=+;}OezEU09l9QO0RxoXX
z0*vAABUhp#<sL4GA$jnlQE-r|ME)ssyrfHmp?eb#!#j#R(jR&Y-pwdc6IQd0+7T>%
z@*lb28y8R<32<Iyn!FULw%bSnNT>|c5}QSR=@oaiX(CpktXXR!r?33|Mg*VOZJ|e$
z!UtpT#%;8j8`PT_9{U>1gL^#Iv>57)3Td)sVaOUZ2B_I~jr$@vY?85+Qfb-MXjEa(
zUR1yZW@Nc~ZHoIU3T{Hwy>9S@wI&u@JTcev*MN^*uA~js<RQ@Och6Y(x=x@CO;{&W
za1f)M*rjKQdF#c`=NVhcgRy%a-2P5o7gFO7NKJM~d7+nM6=Mynq4<))`&Koi?{&Yi
zB>p3HXzJ|K$-156+1QT=dvO2u^EBvY8?M;dPmhViPK7@*^(nY5CE`WCIxUO*oNUTo
zI8*(>1Nze4dN=$BQ9Fm7Z;9CwdW4y8MH7E4QK=!!G=2}sm8xpB-i79^+3wZ9eCGgJ
zAS^>=zd*E$Gq5e&%=lQSq0gw85`Any_K7x2BByw2wZ2;>${1erljEFfo_~ah65Y-s
ztu9IbS^avyt%iKyGDAw<QTp7hi>+T?1^LXQ(?gYvfK@v}N%5%Q7rTQ+xwX%%XmupS
zMjIFvboL!~k<Sl~6}r_ED61h!*8BMmGyG@?--=SBwI9{8zAezhBT@i#$=8W03`DKZ
z5auM=oucwqUsolKJGu2T^65A*uul+U#A9KycwAD>?Ie8SM`SnUZ;tiMD`^(9q?Ifp
z&<sGc&n1-uwIZ^2WZAgexZA+h7~(~o3uTi>ysY{DWKV92SJNzIS#F33vyuiA_6zfp
zh9<@u`*BO++90?fx`bBpGN(r;5B{WNkBCVaqTc<2T#jsI{HJabOx@orQB_!`aAeiE
zdT3p2(R)Z|NyiOavy6T&g=;K|Sv~C;(xsq#M)Rl~pnjw}*;U<jZgs+UlD}ZZrz8p2
z7U^2dWnuJ6HKAtN+~~U(V!kK<EDX;hb;~DCp~zbAmR<ctDSb$s-QJHva&P^1z?mD_
zrEJbW@41zXhPlCy>MoLn`fDv|_%X)hJgsWMoy-ziXucLwD6^n4mMPLT5B)~D6w-=^
zcGh`kXoz}-tDzVg&96KSuKeW?_6f6F>v5}lRO#2D=Bl+rw!ub?gE?+1x4QFHjl10V
znk0*cqdA*qW*M(!x*0u#wH0#HtY+~wF@3`yW;{uFS{gUjJ)G)nd>G#AC4<LD({a!X
z@}51vMV#|6FY<0xod3ugQ?3s|m-XGoeia;?0V@N+7xh8U?H(+He4;c?XG)=GWuHSF
z)zd0c!M(u7{0_`Rx#UWZP!AA{=AcIo9cAC_)N*=fcN1mvD$H4O(^$1FU$a-Cixe6v
zHKq!UeTA-)D-C2oNkC(!-HR{!Zo*VR)SrXmmWr5?!B7xn$7*J(q+R*=gAD1junT7x
zxT(dTV_lR8Vk=^%GAc6aVjQKCiZ#_H6q^^R=6I7km$9byWa}_$xkGnz?ZZ%5e?uGo
zI!Uu(niIG>fW~>bY7BLH)Y#@BQ$`Gj*>*Jy(Gc$BvPJVZmH9i$aEw_ywC%A_c=Kl)
zhe$i<zR#hqE7#X~B0fkAk;ez2ulN<`6UjJgjWs5p4?m5shNdRPJd1r|IKsUSl<pDR
z->0{35|8n;&I&ocJSHK7ZksX>RJU8(bYG9*(86bpdY$vOe{{H^q*=QbUn7i2+WUeT
zKO1*m;d7Aoy=Gw%$@{ge<yYRtOy6vEa`;-y4^6U(ccK@ok;0SOwPHi4*;*9K%Xm&^
zzC>Yf6*`y7t!{NnfxSYBRf6kzZuRF~@A$q$!alMXuUG-F!lAflcE&Cny*>a5*m>UV
z+tu7|-_^yCe$3&k)VEdr<BJo5p$<yyXoRLnAdXcqS7_O7>1ef$keJRu1@_kEE$Q47
zq7Q(V7EOfHUe?*I6yV&S?@QSHrn8PxV&QpHqEeRRT3yP!7f&Ab?M5XA|C!q*ud7VF
z;J4t_%$3~py={X>`if_G&W}D!o7>p$w%vq-S%^&hb9ayvZchQ)+Qw-(L?l#7!pD#^
z!rMO~rNvGlS3@V!Y5Jucg=tG}9$>!GREJH8(%}gkTYkY)BE$c@*6(_SQk9Qvyox<@
zWteE6bSkFxQs_nrg~YXSoOjo~aK73q$JD=zy}n7sV{{QI5m8@nC;D=2I$z^)t##m^
zA0!654I#)SmRZ1%Z;W%5^}9)Nq>R6jqxJf_-GyPTZNH7bW=cRrOM7bkTh~;ch?4lm
zVa}3aGCpNCWpu;^6JC}^CvI7uiPi}jXRxONSx)E^w){v@jFhZHX?*^7DOp*p+#}fV
zaS3Tl?3?7L(N%)_<vfF`CT=>RIn-UWYr)LEBF;`csG=3~{Jbk>D}o$tV)S2nEI+yq
z+P>>n*Pu)$N@`B$g%m1jVWl50y|n*YLHwQ{xjC?+epc~k;hFmn2yCvK)ZFZ?{8#Kv
z1pSiVjX{n5w}PHZ(pF_^<tf}Uh%w)%<4LXSk>nYBAnh25pp1x+UTF2?CL}L%-Xd><
zk0NK63Pa~=N?Igf(uI6%&F68mBvDJJXefSRdz);*P9DvmD$rNrw0U`JuJqwP5&ZJF
z5f~)!%HP}TC#xV>!Cid@e$PAQ%GA?^jLg^=JffVFi)WtAnE&1$hqDu$I5Gh`pu|R}
z{%j$L{rzhodusHusbMDOSuAbV<@f3ZYRyx}ho;SWg>xa+x($#3{yL%eWFc{HF8;Jz
zK_eBe0C+U<4afF1*@j}fUv<AODo`<J-m1eQUvzGim!`72kSfx@(bI<^TTrAM%{ky0
zuT#Zo+?*(;_w6vN(`p_VFinz1I<xoml7U=Xs~#kdAQeU&H528(KT_QHojdR#Y{-2F
zx1p=PkxrB<C()ALwT#wNQrPTc(rAxC21F$RAN!MWeo(T6WN@>IW#{2f@n$a7N!le8
z-^Q_!_LAJq+LxDBSWLK2bWW5#<ijFDu!=;<L>Bp!F;1X*aCtPTS{orikwUXSDZNZ>
zuZq-TpNQ%p{OI-|*aoLxTk#_ENbWuLPVPpP>EA9MH$$34{*~tOwqurkRBMM&&3h^S
zm0n;;iG0Emd)8aZv!=)^qgqj(7JI)i{x()(bC@{$fDO6?jvKeQNvfYe?Nei^<H@im
zY1H@D_&LUI({|SKq9<J*LA?5sqLi+KHI4DU1gOG3p?ax&m>q$^4Whn1BK`=>tD_h0
zl(MSry%uY0(~Dm?w&RrIp5?Ll;aDb)l-W22C?Lilpt`WmaFMFV^I`g~j3r~8jGbCT
zxj(~#KFhDg<2>c1L{MHjftO#pY7EO403q8rVTvpOv4|w7N7OhGP55Uyo`mQ|mfJ#-
zqu0sj?~aW@{9-vFrt`Hv9C86R0PB(FrEySANtL}Y=R^4x*{$9K8O2|jUD`pGGj(CK
zErgpBqNj2q_Oss~@*9=d>R3_G@30MBx=xXy7b$9z)Sq1oC7ugl+>KxGz>5hw!^<=6
zazcOnqMUC=X#ow6ZZ#x<2ix5rRwa(NaT5`-a{SrfAMU?HDh@|dlK$G4luvir;nFf(
z7niWz8~SGL7Ir_d09#VL*TwQ@LOIm+oTt`tE&6b%^Kox{4l?KKp)-msZ}&lgeL%1A
zMg#Tew<gD>%p;b=62LkE%uC%tS{Hi`dTD{-a7m60e9>V4ppcgUR0ye4`8Z}3qWE%0
za$K#btXzKjk1SZH&WT)xDYNUmH63B?&ZUP%?N8ru+734?UYPcF^=GVpVE4)a>#mOt
zUOA4=om%qq*m*?#go!k)qm6zxk6XD`u4CCXdrXO)O(m<7*-3tIOW1J4C}#*0PoGP;
zZO?dXz(Px#W<EMQ_~afwlKs$-BJ<7B^?VNTQN7G<T7+q5Fq_ZoV7ket*baxg#Hgo-
zWuu|`?d_1KWGM27=!+KDaU1cDv9hEuC7Cq2cv(VF!G5iPX9>1zvWv!vJ|4hT@s$bo
ztFNSV6ny?8iG2zQKUhJ_j|!%}DiW7Qz4A~`wV@M}PRm77$>87jc07EfU5MRetv)U`
zk(lxI`9<aEYb`ZBvJ0OwBs!fJH(Cy^6euy51kmYraPY)-#ce{mL-jqchT|~xxoIaV
z<c=u2Kj{l-P<FqKneU7ZLn3v#K(zQ*3U{lCJxG&dn;1|o<F`pC^}*`)WjDcAD7%?7
zyA=bjpOs$h(Cw4ln*bC8rmOPPcdP6oEw*g4_5LqN<N?hIQbH8Qkpf25BX~;FXQCU~
zesJ+>RV!`I6Y07<1CwOdQYSeK5lxXxXDA%@n`j&rA(guACa+IqGE34F)F})#>pJb7
zPCB_}Gq@K&-Usv31w#||4{P-J^nK&yGn-6CXvYf?xBZsiM>$~=#CLc=Ykmvrm=IYO
z8UGgLPI-&3PLP+z1j7SQ^XK<hPvCBBUVTrAW%TjG*nSAm-u=p%{k;32Ab@t?DoAsL
z(T=G6pvE13g!hCLJ@&pM(-U71EQU%TUW8!GDZKg~*~KfcSgCElJA{wU^;$NBPL=gO
zjp-txOJYa+M{>j8E%yD}+mMK}BwcSq<fa|+im;nu1w@Crfr3Uk(b%x^vUAiT(KukB
zTX&C}E0QH8fqS_R22Z@cE+zIxhnT|xe<j9xPl;h-K%3o=WX1Omq{1|(!E-ip!sJh7
z*hJyV<!6E+H^a$b)OctgH{!A)%n?~9tZqLW&e3yIdZ$mvhRAIJ9gI3Zq7xISnF%bf
zW-U$fSoJ+YyyUMumBKA?qL&Jivc-;(=8E>dc;Kh92H6xG#@29O<7vWq%nCz<+LS>Y
z2?Sd&?A|AtkdwT8SqO{eHYQMt@#6bJwVOvHfGM?fl{i7+Q7A2bUroA8-`wvyW8C;v
zPvPet?aLRlo=^a`j9JGDiqa-IC?)ZJt83BgcOBtFq6^n_`x^QQLoopIV*ol8^6n~y
zO|-+*>n!;2S6HqHk7yfW1)n2kN)hR^8F!@`1Y_(6zUo|B!D`qvC@vGY#e)Q&!Vo|(
zoKiH6*h7-n)y3r)-6`r`TP8n^kHqn|Uc9{YGFu`WzU&$}zKY4DV1A)YPi1m|NMwab
z!43EY8mY_KwZep78ASO=sg<!_ZgZ213cqJnfYo_TNNzzoWP-qBS+7F7D>gs1fZ_)8
z?@jFrB<gm|=fOSW1v^8IJLGl_W;1)OiNFV3Efu^}R<7DvowRlHqDRS`YSI9|*`QT9
zSj+*2_1A8)@aQna96o{TgR}by<aCKvxOw<~{wrI3QEAiiFo_-%4gm|CGwRlb_j?K`
zx<=7<(FhNo>+r@1@30Ho)D+{a+JZg$ai5i<MRF{0BxmH6A)FBe4+!9KjXlN_+2Si?
zDMY;#g$8LStx+=j-IhBoZANti`k~I_MZJ5Y?C3{hQUuG!85NwFWbAxWiL=o#%WD==
zFimOjdZnO8FNj9(@!<^AsUXyoNko{Wg4mkPpjM`g;@2Fnpbo5IlB^LEQ3(WtVfbd&
zRE3B^j*29VV6AT`(|f@`Ah(}sTQxy{wQXsGazMPOqjWp=>eFm_qIBzdAirz%G{HTT
zgW+UsG00sO`7u28EP!6N`AyYtjqWqONJHujhNlem6e+Mg6p=r$g7bg6tn-W1yfkO<
zRsqF?@c!-pt^;xy)AJ4H0i@(xEyyGr!oeYiV4nf!a|x%fT2Ic-Rt(rC=4G~@08D9(
zABzj@OO#(bggXbkJUnOH_zuOZ12IlCJSX|qJ=iA3WwPHdSa;<fd&n>74x&AV@JLBe
zk3^tN&@q=<pwP%@*MSmSTg0wg974XijPr2N!lxWU%M4rJ;YvSUw)<Iu{=lfM!P0Z?
zt?&wbSuk4e80x!+GK_)N6Ux`O4A=nE!>E<%kw;d6UA~HsyciBh(YZ8Y3UZWg1#5<1
zZeAE^fn7chqRTLTNH$v5vAmvOQndUDkHgDgpd8%G0b9ywK;qk22gY9Mc7<qJy9s%c
zZg7@P;$7v(wjb<0@kyg0EJ*-!Z$DTO-)IVQTNAWG-DS4|vho;;CT=3>UT_62E5*Yw
z7-_7|*n=rCzfd}`c052IR-?UtM+TC%&Y;du3=9Jfrs>V87wk<26dt38Wq?s&YUmJp
z+Y<B!V%(+o3&r^278Phix`7!g?+OG<x<R|2CD@x>531B<s~^=O2)`);FS)@rm^&IS
z85sU2MOuS+zfefoQ*bdk#$MQ9F#OMqdV)gTgYfBu`hm~|#t(s-jPgAi>mH{d!#BNH
zR@Y2t+n@|l_!t8c@K{BCuVCVD<9j5KFXKU<z(RJ19YFg+(!Dj%5WaIfD58d7F>3Vq
zpfi?&oue}<9*;t^_xh1IOgX^7{$|)Z@8Es0V_099nz*<Y{Lu|{fobI;q7VKAGmJjn
zk&<$67of){w>bvS=M31K3;KfRNh;V3s=48kO_tk%l!nbc#Y!j=YNxBZIT2J%4HyZS
z%nImqW&%jxU&;$f-V173#g=S<mkIsGn)i_4fN+ug6ib^Mh#Ma}MT!g&K~x9(IW{=R
zD2$^g=JPFln03H1C`#aWEYP#aJUr?0EI*4EN^U4`uuiai2zQ473BTY@E$|*4kaHsk
zSjNnmb(F3Cl}U?fNDJ~(urHhwM1ofVItU2R*jj$bwU`k3KSqkG1?33AEa>R;?r6_m
zzHJk|uR*+wQM~;CO^iwB{NH))k0k5Ad2Lok=6^HIT>m>A%k+^#{wpWV@PFlF|2zGv
z8$V_j$cQ3#{}!QH92pi0E=3lkQiO})Q`$%Xau-XCZj4>Ob-}Y6u2cq}+V`+o5f{3*
z&dXt^L*#+nVCfia2w>l0)(;f=eZ|b3v~M8Mu-Uz{CYz-Wo3>`F>1egiSWzCZ7l@R?
zW>f1`?;L{+2NK_6z!Y^3)=}e3Q+0RziY)(IO;S}iaKL{@kNbU94n~Ug0$1j6xBYD7
zuH<2zR~Y{X3--u32IenpgshI-^4Z1^D=e$v$v2)cWTPYKn+-_S{p3PRX)#sqNZH^g
zN}oMnqSpW}ba_pZOcnwH5@jNO*qpFP5fke9siGVfnS(eMneF&TM$uwnpP7`eHDWbf
z%C}<k_xTrTKz^5aXNY++HtSR_nS^t6viHQJR%d#b)<MZnO!p3|Zt2ZOABh7Tuqui-
zEJudUxS8$OUsnz0>fXMfnWV+Y|9j8=+KGQQjfI8n-#ugcNc{hsL;pK-|A8%tnmQXh
zSvmmhojwxrf58p%hPFWLKu%UmRa1;c)YQsQ%|#iQ(*IAtxS_43jRzs+-(7?seN=yU
z+8CMxbN9^ukre(LU7%xPWM(9!V`XP1Wa8jr0ip~n%>SSaQUF66OJgBBa~o4a#=pi1
zIU9e#6kN=le>Fem_tB<f1}^1eh9ZUzlBSmC7C<BesOB%0GQiYUjga&2@gEJze;Xew
z1csw2GvNn<@ZX5S2ZZv!z45m?7bC!5@QDf#v-t4TUtD2BXVbsHnE#h&ES;PIA{K^D
z|2ja{@Sipl^WOl>|KHt&e{IO$e=%ZqK+wX{&YX}z-O^6T&e`%`#$T4zElmIx&Onrg
zh3R7z|M$hh&iGG1I}1DE|LX;Wj)1-Yw}uZc8^;Hd_4mcj_V0TR&i}E?4h%02mXBEa
zzb|%{54;Fyhw0zZf6Fm*{ErSsLRR47*?=+eF`o~t=L3BLa)7VDz$YMxWUp#x`GMpR
ze%x#Rd*l9h7=NH#e@CZ`rOAh%K7cT#|G-!-AE4KNVM$E?jgu)l*_*f+1JNT&V?#?P
zdqO69CN_HD5-BYJ00(XcARq_inmZXfSOAat(AztiQ~e$4B0%&HU}<kB`T^!qigGhE
zGBY!BGIKJ11SJ~{BQpgfBh`N!{U0RoUvTdKYs-vr5QbqWy5|&Gx*OU!Wkw(|A;AeU
zG>D~<q7I1D_uHv}L}bg86~+FxmwycC{q#_YHHFQZ`?_AQJVirxHyHXH3t4(+qb-ct
zk66-j?7T4;d4wDrCWBWq+(e`{j#2T7F*JpEHAA9MqGpbzL0dLJ-kLGF_Akuj(U?u#
z_$Th*f8JYiz;tKz1@F)IB(;(yaZ3rJOU=uGUFHaFwJ(Yj81kakWl#IwblvHCHY-pI
Bn?C>m

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..8da253e7f6f68998d8c5d99491f7054a938f288c
GIT binary patch
literal 60704
zcmV)hK%>7UP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58fy-lxWJB}SV-@oDvvj!R75+!Zz
zsR7%78;yqT?2+L?x7%f)aNnTHFl_((J|fpz)VcZM+{pV}naGR~<LHahrYMSBERXZ~
z-#?e<|CM^4kN^DJ@sG#(qxSQjkI#Sp`+xKJ7yr-s_^<!%D3AZ~{NKNQ{_h`-|M;Jt
zKR6%%-%-xT|M~dGNAV`(|DVlS`!UY?=>7a*XL<bgu=?ZbDt|ow!{gumw8ww?uaAHE
zmt)2t=cC*|#%0asv%3AT+OJt2fBEhB7k~ff^Utf#zx@62r$4v9`^!HZ|LQOArt#BJ
z+W0YJl=frXw+J!JpH{2J$)OquUsOBq#fq#I<@c4^J)ZN(N+^F(X;$>)f1>zJ-nZF*
zT-WdO-oDTKHtyGnMfr<~_3l5;S|EH;t<@jpr5XrdRIBq-Zy<b8t#tMl>__>#{4euI
z{mI_1e}MmI`7}8Y-cQcv{88G>Y9xG7?Rx(CQVoPJs*UogHxRz4)-LwuE5PzMSHPaa
zYy9L3DBoWJd;VFTf9B*s_+oPP^gpv22wzk?uTQ;!@V;8T?X@=&zNj{zheS{L&+^~2
z0?&D!<tp>}w`o7l-(P{p`TZ5BWBllS6XYa(F}deybiPyr;frc^f9ef{FRIn?sW%Y5
zs8;HaJOZNhUG6^xSpR(q^!Nk&|3xByEse|b9NNx{D1K4p+BWVgeDU)>f3&s_3WP7J
zwf5s~DeqbSCb!E|SlvI_>wiGr7b~A82f`PVD;Fn+Y9M@3?QEZV1L1wO`}{HQP28jW
zzS4F5usel4ir?h^Q%<#?Z1q2&><oLI7s_Ahi<}qr#cg6gKQVvIzDxNie<hiI*j@?c
zFV>13IoI#4o4<X_*B|pIJN}Po_jv~)p>E2<FOJflhwF3CmnZ+na|{1O4fxJ5+jK7H
zFhwZul+#iD*v@JqysdV1zu9Cp5#CmtaYSV`5#ClSXWWRgUQ)iX2>1QNzFvgye4tC5
zoi7ti%KI5UH^z3cebyu4eYNM|@KOuq_m!UKP<^RI!ux91zD=U^4d$0IpC9U%-2cwm
zv<~rCCX(=eV$c1s4wJ2(C~qs)V*bxrF)8mWK6S49rN^Yauh`BI-dRzUZ>&Xq%Jb{%
zwfK%!R(tdFWgDp|@25E82Dnue<$c9j{21ISit@hV-TgkdRTSlIMLX|Lb4<#&&W5KB
zI<4RB-D-UAhVndvU&VY<-cJ!H{#H?x_Z9p3`PdZYeZ}Y0Uk|dRysvo8PqH^D-&u{T
z{iyckYJBU)a+go1XHwoyv8^5QGR364uUPI+2WV2>S2WuzdFg$HHeO}02;W$PWmvnv
zUW4zP6>Xd^CnwAAC%5**ODz)KSDU+xh|=2%9mcb)l$7@spLgrmqbw=k;D0aAUccu5
zcQmD5?@woEQr=H-?TObZit@f<AD_g0Qr=g*&QD@KDeo)J_UR}~%6C@dd7HGaSK|-d
zadZiLz4ClKKF{P=#_ePN^BVng7nK-no%Kf>eoOm2?*Fxhy`6<meP})p@Tb6eO7Xlz
z|LK2fdgbhM*2lV0-Q!%{xAFYX_4_l#Sx~Q=76?&j&V5q66jrn-4Op@5azn-8B>o_5
z7j@lz{JOd*OW|0QtVT*fC)fJ*YN%)NS!%eCJLN1vIm-*hwvLt^?(!S<@k$B9$Rhad
z`?9T>pwz9IHT6YVqd8tETRZDk|D<f~fO3ix-B}q57aAfd47^V9ayA@g(_osjlOGi*
zi&eDT80;~NBL0yu#9(udo<I7ha!F>HGxXeM;FNL09<?Y>(Y^>%(+0siia8dy^WN%-
z<toDB=95swgrLl=pXa|FPRgE&8<giZC*P}2N^U+<v~Rpr`>~bSZCo$vxYTV@xEV%l
z)p2R_I^}Q@yAADcQP^!faysQKpD5h(t^+)E`zuS!I-Wh#UY<RRq8a$cd{TT*yppnK
zTH>>3--csorAg^AIgp%yEyZGX?HhCSAN+UUa?i490v3$w+Pfom-IJ0X#};ea%o{}$
zsLrUSl^@tsO`WrxoyV4H+;s!nr^U|NNw%$j>>ta%y`&ZJ5|_P0`aMZp_m1si?6zZT
zn3yjLOFr8g0x(Fv6Dm2cGFjiT4^kX;EIP%};Uu4274wsFY67w9Ma=KM$|buFS@Wa}
z4L{bo{OF&`WPQgXm*hdLXi3)h5F4jB-?4(HIG>cE3B;P7KI{V|pVPUmKrG>@{U05X
z{SBY^nWg6h`>pRTcH*Ld2`v`vN#Fv+)?5@WK=U<v5{#?Z@NRXB|FL}+h5YAZSIWH>
zE7D!;9iK=;Q|MmqYQ{gso>DK)%^Ef=-wyF*EJ`wBEkVDwi95r4in>s6oT8bBT<+I4
zb!T`_QP;f0X~);KD4e!|!y}jvk`Hfa`3*cCnzjXxQ`O+pV2GXrq!vwM?-^K}!q1$0
zsh$|PCrM|JTRnxHfqPxE4h3RSOzqTYI48dTb}UlPJQ&)v;9+rCl$?0*vuPR3OV3#c
zuPWG=%25UPQaP&NUemPWk+R2X9YNvC>Qp<yJtHfsUSo%viQQ;F_=|pcF~<^HPZF?#
zccyc<f_H|J^KBD=6&tbUFoJC<0xOu5BCvXii&6Mpr}!&iTh%xU*jBU}C74vS7;(cq
z7HO!RU{cXOEZ|aVaRpo|T9EiRZzu;8oGRKL1*|%^0R^khZA92rsoNE>=iEjVyDG(E
z0mD)(Mkn47_s9trr3QEgi`uO{5+iYn8VVk@TO*3GElO8I&ZBl~L`xI(vYPSl@JV?N
z=K#q$)b4FO&W|>?@vQCB<~AJPJuT$r0g`t<x8XQDT8hjwO3}!O`7R20Gj7~a+T>uM
z1=n_QFiQ>gzAugjigA^D%%b?0yhvRQbuXKm307R&czkEHYa5TD^Amz$+?e^;#^XDq
zjcq)^ijm{-5{EMJ;k2RAOzZ(^lu*hSg`=66xHQU8(^o^Cn|YDE@2=5IpSUiDV`Acc
z8&6EUOT!%#Gw<7YV&am$u#P(=KK6l&ZEHGo#`Gf2fq_eDlibBEz$qtxv*bgA+8LLE
z!wIHVVvf{1aZ6Z)qDEqp4W-!QCe0g{hDEyAM$AuQ7`KQ;;V)u#l*7l96h*KI_n0O<
z6gQ1U;gZD_1eT*9U=6EQ43~*k#U;NOw5k=u#h^(v4`}_ZN;?`OzFJA=0S&%MIuB^)
zjis1i(Rxw)Zq!x>H0vg1bwImrP*!n$S!MDCDsU^3I-_F(lFPW$tY;;11}bekx8cMD
zPFWuYl+$)<|3EoyxP=cWqt7z;50uSzQgg#SXi>OwP%YcZ5?r77)w_OZ640YTi?>^g
z26a&GQ5F}aMc}GI9khEJ+nUd@NZ8!X|D7uaz0PiyybFoy5el49R3D4t($S>b;&!zt
z9GL5CHZ`u;;)}v@`7S@4#O-7l{M-iTi(%}>7s66>$F6q@H17em%2IZR5@jj5p)r}%
zVO-M|Wex8LQd9!dpds0%u|XlS3#Axo3hf#)ev!C<1;dpsU_hI(p`nB}V?&IJ593%Q
zj0K8{r6dnUWl^~Mp{H01a%d&irL&C!hNmp|^W8fB9!;dQJ+T2BKi<=gG>brH$A(`N
zavP_%(b38J4K_#scb?Nm2^<%>RmK!M&SYzxV!y!#SpsmiTNF;Q;|w;6<$lK}LvPJR
zh!I07<EFRDI7>T^SCeG!I9|=Td7qRk+Qt6B)$d6`DF$10V!(;cNoq9)D>)r^K_{ry
z7;X419*c0IVGb9@T$7m-*TqHQXyZ&Y3GRO3)G!ufxH2-}?&uV?8l#n#-NUYEu38_U
z#Bd?Y`{jS<NO8WIBs;E>i^7o(9M@JfRvc%>DyvUPd0Z?P1>3g6IOUEgF|6Sw?nfL!
zCV`F%Vy!YT^ss$Y$>-kV>{%pEKYqZKf=Qynq>9VpDs%cc66zhI5Tr9Y=KTF!sFK&c
zX=wZo;t;5`M;wL=<RWqSxbN4=&j1(vDk0u+cdruS9X5F<k>I0~0`50TFQ2U9%&!va
zaiw$u_k?kDD8<NR&+QQERYr~unO-lBzH(%e^0;O$3Wx6!e3em(kx60iafhu}avxXL
zDmzH88Xe_O(dfwk0>-6f1Q*Xm;uMOUmbrn74^M|f$33#*a5$V)<2N0@h~eq5=+P~A
zEpCF92Sr>!52tWKr$)vN6&KJa1ttH?YuASlp<nad=(w#_T3<TuYPD-Q&L~A6?ZyJa
z?%Zzw5?2|EforH!I_q>VS5}Gj)AJK<p-#cpYLMls5{oCpO`BLe9cj3NE=o+LO>Qk+
zDH^UoRac4z(Oq$;fQRBLH}w=OYEqxu1e0X&@u4;@O@oxKx^%RV(p5)Zqm-^X^P0as
zRhffuA$7{hN;Q6h8RFVeP1Y$~KApt!89(9r;Dtgiu!igBqCn|wxI|PPinx8&s#CGy
z%20KI!R@owD*1)m=OS@dxD!;JmAHQ{3Z{iiL9N__ynZ?f-BYmFAFNc+3KtIgf0bDZ
zZtG5gpuh!mkvP+);c$CWl*@A8VDhbO)^|p&vSc-A?^X9DTtJ<Ic~fxf)NRmqoP@p^
z5g~I|qv*y#++aYhGJiFgOKZs;YZ{NKcaDb>uNn_0PHCMl2e^1XNi2CII<s-@Tog_m
z2FNNKT3kC1Ct<~*b5|MF8ilhiZ@79c3OPaRV3h*UiU!2(UNj)?f}#OIx<GlZ`524K
zr;{+CQv>1$08?B&QF6u<J=V4pmZqYsVS`LAQa&0iYK6}o4HCIX8EK(*A5MzF;Ig?W
z;03OmPC?nf@}dhR?wX5Y&|3|XxX20^SIb4HY^I<Y>=KKyfh%#lj5*@lFv!@VR~2(J
zQ_)2fS4XGBl2|CmWm2uf#c@%<1%obJq~;i;Y?<6524{jYB@gY=XvhbszeTE#!QfML
zr8QW5%9Nlm$l5Z=8c5nA1qnAsr(lSXwPnieZzGt2e-8djV~U&MB9K>jNG(#Kc<WoF
z*fJI`ltm9m20KfUPGvBv6g?#w<Y&2(R}i5^w`qgHq)62=h|qG0SI~w_YG1fSE)sZ!
zN3<e!%$lZ7UNug=Kxx92u@)(42BSt9Vi@FOk<k_RL8o*y1QA)Jvf=)>DBvLkWRVtU
zP-hEGwTBs=eu{4WxbZCtKSY=$3RFFV_$xB#T8*oAk-CS=n^Q18h`$#Krw*P{`W2~!
z26IA@IRQ5`r(ncIGbd9+-miwD=;3hWFEr62Ei!@toPg2eZGn`-Nx^WLnsFmr6fm4}
zP8JJ;d7*SMyx!^^46l@PGErAbx}Czl8uX9~xh5?Y*D$BVG;r&3N{qQq^_7%RDGQZZ
z+_9=6pbb|lr^F)E$<DC`6<7a~`fjB#>nO#pmcEP2&?_Z)EY}U*f1HF#;nrUCzFDuA
z5``F*<{C!m(qu-(Ee0e|*fYdSg?3n^SL2?tC=@RU>IBItUA=dd(K+N#?dn@A=`IpQ
zkFS+-OeUz>)pb(XGZ(V)+@hJPQjBec0oHM48@kRiyQc9PcK|1W5zzZK3iQ6B%K$X|
zCk3Ur8mQPkh=c2ni}?$s#!t8rpxc#v)PPRzBrt`dOV^7^(X~@z*ZGa(2nu`0hN<kF
zyQ8XeQi}T4hh5Y;w-7GcMdrL()Ok|adF&u>2;Fl}6?GruJJmVM@uA5nv7Y>>cM`ki
zHapdIQqVJZ*~yY~yxi&tn+_`7D~0{UrYpC)sp0%sZgzuRSMHb6R4<S=P?=sSP(*ck
zD^snCP_Xvcl;u*(Nx_L@C}ONA)ri8zt}NF}3C~?c7r{6(k58m%QO=;xBWW-7Yy=GK
zSp&*Ph~`C!4GLlSLI?)QHe2|Ol5#vrQ3MB#Z6-lAz`&}Xh!DOyMQ?NE)M%4ZGj`q1
z(3G=e7&&F=Nrh4^oa4t!w`bQclJYY4vxUj#g`zsakrP(Nje^%DvGKGYWb=Wty)MpK
zRV671)yImSH7nt{=7jr6Zi};IJEB}Ko9!$=K9}Q49-H&Tbq*!!G}_rGRhXT!eIJJt
z3O_6GmHG-lw0hraI4Rfu^&X3|6IR*qnYjp91a>3>`w6j8Z{50f(zQ#YMfhB1KOw*t
zg&pBSxJc|OBw@WTO=+V*ba#|_YOvgoO(HJ>drnGuk@bsmzR3D|!v>p2#3H>O8jHfd
z2iQ4&^iO4W9{Y4r*!k5-;AshF_B<>_(P0_;l<|0Z>@G_GRA%2dc-JX*lK>&nyvW-X
zOH@ftFmBUHz@{d>5US)N8MG?yLR_tyHr=L_fRai{96XCMq1|8~nv_y*I#cJ|Wv0G^
zax7BaHMT{dPRcE1FQuxEJIXkpn>J8Y$4QY+3eMEjNx_DShaRc2Ptr@NsAp`ALWPw3
zphzLbd9z5;!@-22p1Bi>)Iu(NkxGiEhI;F&g%WR7T<Q=>dzsf9t}_f+c^g?IUaDdh
z=l$uLvna3EoJEO;YTb?&X}>?MGH*FpwwX67tjWw970$0k!ZnA>G^wue*0(6UQej<Y
zUa3M2bqdCem6>^`!ZOU)k}g<WlzHJC<YjkJU^+mFRs(!~^U_@&YcMaF4R8fmB-#zI
z26M=4fHfGh8j#~dR)a-3g47>rBv@r$<+%n!W`k(9%V@wAkgaHl-(3b1^1I7wKz?`4
z{9?;KthAskQo)GH;jW33!%Y(>hvV}+(x$UWo7u<9G)!Sz&nCMRIZF9;A+%({C&?~_
z0b1InFhB~hOB|#CyXfAwNHk25iL@16;-SefMIPEC?Qbih4CnJj23A?*$gTQgH}tJC
zr%hf#qr|qVvWSv#yjD#yit=lUQM^^TzJCOz!;VQtl{AQAY$Xk%H(M?+WV#=1kZ2Gk
zqbR_p7<I}bN=BWsi27Y3NVNUp7lu~Is*~1X^6J!Rz^jXHC$d8?(iNs`aOb+Q2DD`_
z%4Y0d#aIHp;x7`d@!-ToF-OCCy(s3w^uEdy%{XHYC-HFre7Gp&Xy#uOz71S#hff1=
z*jgkG2drSgpq?EnBLMwbqB2ZR&ldHf*QDMy7+;775K!Xn@g#3xBiA!ZMby}lZ!MMa
zUwV(JjNj6uO=TdK9(F21rjC65VLYQAh$_RI^oUd$r=*9b%9x|L@gE??fT9Y_O|^&@
ze2gq&1++Rni`5IKSH7K92Hn&mX22m)k8ljG<TG7mU`$vwVsuU8;k=v1!(Gud9!?w@
zUpy_cA&!TepkX`}r5H=q$3ZWWs)@r^lrN!`F(9>S;&2$$lj@@It(FsK{03fT8SI&F
zxAo#{WYxq?<H3USF;W-%%Ag9pC0B+}=)t)%K0=Su3>wA5H5<}f_RVU1%dYG`9wc>t
zy7(YzjCQFEV8B~@z33~Vi_TSkZ144qE6o@EMe(-)z4}+i4#+RyN!c6+7<QVz1qeHZ
z`@sRqfJXusj;<ln)al$WM~6!1{&0ne2-kvUhPt932KFanQ{{ER*wl2)I4a%p<-OsQ
z@G?P(o+_9U{q5x<65*@iXQE1URKbi!Gyz#OCioPNDyw{j7YaPu7|EKhE{tTAHw*(=
z;W0xBTvaBv0o~u-?WWSvU2ZvyZ%x-7#<$A7rw*v1@&KxIWS57K$Gbl0LBv>B`4~B+
z$_?oNg<eM3ZuC=^H`9ti<>0tB6wr!nU<_>fPB8{H{i|yDp;xJ2^g5@P*5Ra@eq0QQ
zO+PON#HKG80%9NX7pvh?9{ysSLf7axg--7_l;pOCa*S;1gBhK!Z5%zNw=^L7j>Chl
z(sx`=b_YXd(-W`KRh-UxmEPj==ZhHHbouib+8f@8_~hXmF3&*^qHW=jNbXaf-<p9T
zzDQn*l`i4%W2|rpm!qRc+QMg%pSS&xujB!O!55MffR#@^mz8eX(gF}E8*ZDi6`<|P
zwR2JG?)~YJv*B=x(g`<KGJ!E>@-VIP!PZGlAM7F?6ndP32QH!0&$Y_kT1T+lt#t&;
z+nPSLh^>Xs?Xz@j9=RS=d(X{jmtnT)*vl~6bpCaUn}*;ZT;b8JQ&e8vRU?H2mmjhR
z-lAE&1UbovYEjxeojnZqo|`kYQ@lx88v9K*URe?mnoGy)Ro)%5JuVl`Ui^WfRq8MZ
z)J-37r<`^36Ms@RKXMP!g;#q>QAX{iJGw{h-uLFR?i92Nsngw3D#v%m@rG~wK}xTi
z|9qu4cl1jaYZ)x$Vy$x{T&$1Hjh_*_>FUp@-3$kC3W5<Z$BPjKF*5pH>zI(=wGM_3
z>8<Dm2K6GufepooFO*`!x|K&nuc9az(91XrP-4GcIhHM0!()E$xy5rh#mCBcy$Y~%
z1cn?Wc~7ju02Pi5#tKEBFeo@fRI2-YM}!K8))k?W!$X8h4)2lCGL>H7ba?{FJGxQ2
zB7}z{gYM3F9Yhg7GN#8V5gEjBL6uiz5TlASdZ>2A3gyt^DyASL1{z0@Ql*c$f|wX}
ztU#wqr}2n|IzU38(+~b6f+=-%>(Kt&sj<P;hLKqroSflXPVv5qc0O(dt!x8~5Ie~7
z2qunMKz4VWJPJ5-3L3unlYw^mAyx&|p%^oev<_!;g~nC7n>XEgI_?kQ>v(`v_b|Ll
z2XqDMG4MHq`D(9Qw4X;k`@ye>KqvW+^q$n?JZmY9ap!0$j0;R`jnWtvAB8V6Qd$v?
zl^*L&*ARqG*VYacV|{e%pbLAG^eu|;B%g|6HEVdZA6qo1le|-1Ci=<vPA(QsMd3|X
z0QMajTFSWV3_q=OeOHJoBe4<3N{X8_73{i5b&rQ-Xm&=-R=UTxz6~g*J)|x-+=&#Q
z%lPe#;br`G#`)G3_9{4IA3=%lO{Ut0gH{2>4DrsO<3(Zg@|g|A?5}M=3}4Ox)jbN@
z1HtcThi0tC=;do0P|RKuoR0a5%4V>*BDW)mJC<Ii%NEx&g@D(_kY;J%h$zo6@`Hcn
zKgEysaP&(5enqTTdiX1<9i3u+YNqbt@f>Le&{qZlD9D}@+#>N87lIp-)s1n^64i_r
zP}o1YxnTo1%NIKYAizaPkO8Nhbps;c+HGhBixhYp=Qg4MLXdoJc;^r_0{6*=pWvIx
zM^v^E1rUOaU=8Yvz#6nG6Vc&G+8`gekrNfdDLxvBXa+U(svBG&Iwk~#e>6Tk8KxTU
ztb(!Nw??Fk2)mC~rdkPZ8A=4#$dM3TBcxy(p=k(_qcTnckR6l?3F_gLGa9-0lR%4*
z|JIYFGyOy2C-FsGMETHU@@YL$NpAketqfhNFGDW`cH)#4?M$^3Y?BObw1^5>#Yv9@
zU!j~$d={6*K0rxeMsV~r$v|KW3}z94>N3?#aBplg5AH!lc8MPBOWE2V30%X|B(ZJ$
z#JT4q@o#Vj9S@-7kmQ5Y(^UiPkc=RV9qB1n8;sjR?BNNRus(iB_Go#ip=g-XPDCNT
zGq!{j!q$VL*i&KxV`y$OkG(jF7q^pg>cQf<%{*9qZ!-@T!vf(AJpjPuKOpRoG}}hl
zA(<N*QHS{A(F_+j!9jrpyeKFv2`5z<9y3xbLP?F=@j=oW{z$n9y;a~=J7ub&o)B4~
zmj&dSOb}4I1hrKec_TEgouXg(6b0$ENDjtTk_&;nCF=t8zl09kDUyJ2NfQVe70CoD
zdr~$aGnUY6C7N0aze+T<*OHiD1+G@vMl4o(6t%Dg3AJq_kn>Q{1^VWcHf6&4I5v{>
zPlg^5VUD_Yg3#?0{o;5ejvX;F66@}Ta`QI?);l$WxXO<dcU8c8*>`}hb@lCwEWd{&
zz{r3b2Th(kWo%u?vX5;IV%3M<EH@ID9mX>u7rsz9g-4<vK1+_U=zlE&Wn`a8;Z7@p
zX{6{W!er!g*G6KW@B$tw=aNF%6E_~fMjkH|EIh72V{V<3!d(Z{D4|y#J85bbv8CqL
zc~EqxZ@5emP7{RVLBP$poeGh2D`zjU#qO<_02w{=3Q>e0TEr_-*o|+w>)bjb<?5WG
zZ$d$pCZ%lcu6=l=#1f%tc;Qtf*wo61xvOjq`_8;lL?tD6Nmz)ky0^U;d`S%97J1ce
zO9aKT9b(EJTakMT{@%i+O-iapFvwo18u5CHQQ&GSgxsBy9r;$h`qoiUM(+8z(OzS#
z<pf#97&mz3oeGo*yKf7y1Nx9;BU3(^?0MSulc2mzdbutx(pGIvYWAHg^JUVYh%e5{
zsR;5UjeU7$%AP3Y7w?NX$LsPQ;as)vlc4180wo*r-8Fa75#D`sZXc^})47QX5>ha%
z-9G2mFbFh_@|&5vSP04{1pL#R_cmfu@>_IX?t+1oPlDh+w;6~62jY+?_qlzq9nOK9
ze7bkBKuUhA@v?B2?PGO8ckgn+#pAsT22x(+?wyY(8%dw@+Nt+0C!Da03E!x9-DgPB
zcD^ib-n-x+C1sLt)_W5rq0!vCEb+~H8;`tu(`LebRf>Rb)Z1PU(L-LZ+ev%x$_y!~
zMEOR&+kT|q>8`tx>aHr>DV#*eetrMlEl)FOAos4ykaBAVzTxh^DN(V#diEWG_ILlR
zMcsW<n@HI-HlOycyM&qb-j$cwKVwsyV!Mp3Gv6M&>H@+@e#Od<t*==5>$SA$NU`cE
zVeE(^_3Ln3?=NceeQlS6Sk-I0mc*)F@--4^Zr1}}x715u_rB+km+Qj4X(dU@dq}L>
z+^z$$YWH>>=!zUbIri#)A&W)ZFJ!T3`-Lo4XuFU_#LxZtLgw)hy1$T;7mxL8r)bFT
zF5z(%8uMBekG<ffH)1n%4PCQal-FzMissPA6L(c7>E^uth6s>P6yB4c%d(0w?Sofo
z2Aafg*2qow^X5a9x0K({J$glhb%rm}>otE-^7cJ^uywoUk2@O9i~e$PUX)j}!-}sd
z8cwj+wn<MPu5FX{=l=-PS%mKY%$4q7r40Tstk~ID@`2I7bifp|C~06aAJ}eS3O?=z
zrr_glU~&nwNNHh;hF|PU9=KFA+~DPIU<zJ#Jy*e)wMc1Ux_X2}sh!~5W?u@%DR!B*
zH9Os%rwtFWN^@VZZS2;)HW7w}vJV2-jX`q8jkN9smr{TYa49WI13L~vjHby&Ao~Zn
zbZuh^E~O|NU`dLy;mYKqYzEge+Icm&uK2SYPOwRDtnFfaTFmjn$EpWbn0^<9%)h{@
z)U_@!Yo<DRVN<2Db%9-Z2fM(oly?`{b?+kz_V8MEfjRd!p4dW?b{DusVRz6HZ{@@f
zoH6CxhT@DVd`5-A-$VWICC<<r7O8{aoGE%n#pA-FT>Qz}GDY4oco(q(l{DTktfVO_
z7{4f$O>{5jFq|KyXcWFd7a@n?^DiZbaYZ9Jj9`FDKKYvRcw+jM!-z9#5jc<=)93Xj
zR?!r&c;GF{iZr<!vrjP@inbL)DJGvH5-7i>C^|fySw_U+mBtvj77uWiA!vBCv5XzV
zqm32Y1`-o?v56-f%lIrj7+OYJ#hcFIBtDd$G2e7jIWgh=u{0*UKbE>HzLovCw4?ji
z=h77v%Qxi{i@d*<`n<a=NO+mGvcHzb#PhMVcqw0$Pf++$S~yMVgm^o$45-1|k(G3K
zDcIR^cqyEwWG-HljBzh`@wN<U!Q+xCfF<6|5rxbb?U>`mlFu(4UTTzH9`7xKNqXh{
z(%q%TGRm$GM*+*o5I7Tfa5bF(eng!+T?t}#lD^@xpcrjXe13W^h3A7s$OapVIZe4s
z#8yoQ7sIO2JrPb9rr3*vo*66b{6o)LmN67?_%LAz(J90-LZTaGO?tH;d2dEUzyZZd
zy0sW4kX|hoY_bS$z=N1&Bm*AAOmPe0D`Oe9fCn;*7zMiV_@pu<!J!%f48SrvN|&2~
zjwak&!~bUi5OCd~r)6{je29Qrun18h-IQFA8iNM#pyuER@^-3SXbB&BVY3VnzzZ8-
z7j_>iOLu=bS^>Tx2+sa=?T5dX!H@q~?p&5m{2jVbO%E67LNz^HLiI_H{SMbPO9y?t
z%b9%d@hoTQdk+t`MS1md^CXg8?Zj|(8Sj^%H9j76rL%Ok$Ge@?=5}Q~+F5$m0~gh5
z3U4SH=~)lwKZ74V8j1;|i{TYpBYg~^Nyu#;P_MSR%>xhC(rq4)vBWd^;NzdApFCU@
z9Tw%}Ph28c`o_Z_(_vdg>0ai5aaz_CsW;YO@Gu;w<IB)V83*0wBYuLt^ci#qR@>aY
z;o)kVzc)^&^!F|fm%~m9I*}xVD{f%y(1EuLm*+zszqWa0$6=68*%fS+`^N}~CfgjW
zA(iDj4Vk<-PuFNQeWxLRU%aOu#5DSdm$Wr9J6T#YF)5b;tSzXdk9=5jI3;-aF73rO
z=j%{kZ1cYMN7F?hM{qs2Q+E_RwE^7egU@OU8!Da9ea~zT*e)bD?`y<Fn|!Mq8kO|I
zBbrm>;P1RQ>YU+<54bBj=lhm6d4%|*+Ct6Z*l;~Gi8sUq7+tOpy{p;gVLdP!I#@$~
zZ7$X!zf5sTgYwI$n|j=X<A8Nm;aD=DBF17Uxtz6(M?wsSrPnp$G%UTY@%rWzbacho
zOmYXWZ;Qm0zJA0{IDA}!OfoW3Dmbv3I+`&<$w@rMS-NH;$i>n%8$mFZ?%4xgRVM#z
zJkUAz+sRrT?PS=Fe^=J_upI!%F>Gg|70xR9Rs2zWR5CBbQ=Jpg$IV6D!;c7d7nESr
z9)1*SD6JU}dXA&VuN!v(lb}Vs6yf(i6jQY*j1hybZ(Uy_VzVqA$`QZi;D0Bp4K&2~
z$I#>9V19h)-Otj){3-z{7~31MW==srC3r>c`zmCWOtc=;M(Dy1y$S}f;fJE&EFI7h
zCkHgd1EgRT6?6pL5kv7qF?qyU{Lo9{qG*N{Yo~Jv5rCGi>xdF0sN;ts2@T%thr$gl
z-PsY5=oEBM0e!v1HClSOUlPwc&=4O<Xvz=8P+B^@BhHe5mLD06Nz}^^MQmEQ!6Ty6
z(hVN3n@(x`P3)qKb3*K>BXFW`=&|W5j~G--UwOo-29Bq5i(*{1ovUj+oOsuGIPtFW
zOn7u71D=yQ8{&94aVVyyk~flZ-f+AnR%wu8G#TkVFdE%b5K(ODi_d3U!lDLgpdp4K
zV=Q|(GnyeQD7$Y3;$4@<bM4X8mM;9)rQvY5L$S0wcRLJJZ4d1xK5S5Y7pI#)!o!Iw
z8x-FSCeMGwnOn=yZWxnVMs`C`w~XvY0KYLh0AcTz(E$jIcM66B;hgaT2(Y(CM1Mx%
zTg$+1S5BMWFA>O3NZz0<(bozJae_6eD)Wp|i~{fh#Qpss!hkhi%YZ>(@z8sK6u%%M
z0_1O#p9H`TjNu7@L$D_2*NL}o!W4f9Sb<o^9|B)6#V`P$!J2M(z;HN-iToj;2Wxu5
z02l<3ls^O*VG;QNKnY+k6Jx^JAT<i06qeBt?v!ASw?_CRSkp_$3_vi#K7SAmBPbY}
z2`KtQXc~*sQ4R(O_Kct$#GC#QatHCKKZNdKjhYz%Knz}K$A?ft2yFc!BoS-6q5^G%
zaM&M0B(Y{F`TTT&1*QoRwS(f@QE$rtLLm(Ihrm(}YrOWt?ZPs)1E?#+^ZpPpi)FM2
zz*~R<et;B=Fu}saMvz(vpcq1le+Wv(7$b5BZ^jfP;(#>Pq$vWk2B_trObmFV_(7JD
zCBVla{CQA<;|-<YwscDX@c=@dAUnZxshcwt*`}*HJVQ(YDsu)@J4O#r+E-HWTZUNx
z4_T9bIw=TctDV4vHHNy(sg7TPkO(CI@gP{zE2YNxsUyLegn;xPa3--vRTr)#)}-nJ
z%897<%ZdQ+k|Yrl%38uxom>FHQ=M3Zj*@SADaZh)dZjq~cXX=Q@`+AWxaAX_3b*$c
zN~{4r5^hRA88m>wg$w}1;6m@jA*1k<Dt<>PF~;I!+bMBfX<e{m?D!RR%$nX4Z>W|p
z6n4yYyzRjp2On}cd8O1CJV3`N?4;}8c+P(%v1cx;sb?-LrCn0+1u-wf2i;Cy3DNyP
zDdwyz1e{K63wVOli8b9U;B;ac0tKg&SBm!>mk&Vd#jewR#3A*p@j3z@lotYf=I%gV
zI%~SI+(TV&lsksU?J?AKQle|h)qALO?wO(9JIb7Olqu?DR}19B;}eNJCm3S?RA$FS
zvb)r=b{SqGn|$r=sos;qX=AHR^^E`+cTHi|kod**nZSOy@ox2#6wQ)5?^aJqiH5oF
zZuXRf=;;c4QHre#rI?Da;m=Ue_Hu{`<#{_#9!5zjY?NTR@EduhM8mNs?S!zoc&(z}
z2=cQehUp7|t;RkD6lxL<!lhahv_9N9UMZ+_&qt!N?vzFyQz-r?zu29E&SP}_$7_i{
z?+H8GNq8g-tu>_+IH!i1l&Axc*%BG%UMY6Jv{I;(?v(n{HQsoSS5n=^U)uh6HHfL>
z0acVk2*Dc@OJ|Eou-COIJuAggyTFRK1ui42h|;myfc8Ap1_;;7z6wm`ZR-KKZrhyY
z(sYu-M&U8fhr?~(2Oiw^wUnu`B?T=%gfo4pcyC`SFsfe(Mj-(P-a1Esn?pG4lpBQ1
z-YE6lWDj2TUI}4vp+qBc_X~l&gcKwK_$!5Sdl1OI=*+-wjW@d#%S0o8rSwhSA0K+C
zOL@<SIvx^4N6&Iq&qO1~Ys3qMU1NjRs;-m5Qv+L;SX!?nc8*O7?06lqc$a%Avv2Ox
zYCrNI{~&_>cGmM5?v)}9;dIX{KD?!_!H2h33eFLfcHIRJY{w_kghGj}SerCcQee-L
zGKCxhyT-*t1Fw`#Z)388)a;PY0E7b+_RVcI)Hiq0kW!o!D#bmMDM&j-nVoZw40fIb
z_8nW~Sjiw#Y39@2D}^0%dtB-l+u=&xl*@lfH%$t4Q!YQQ2AJSf&nG81sh4u)c^B&_
z@gBy7ro7607?b-w^I^<Sw;?71$x9S+h3J~abRxKi9U$qhhB9wrT(Z20Z4_MR5KqsH
zC%ifGp)W6&eAmkhDBtz+l8XE*`%M<lc&`L@9?NFYE!M|qh0078R&*K0B3aRW6iZ^1
zcMT=l9k3*P#LL@1AMw&ez~nctl)76Qm_z4~ErKs{vR6Eqi6?Cu%+`~352o~S$^k;b
zkjZdMn+ry4X>-B&Oa>og#v{|*!C#Zng*<MLv<UH?ER9C-Otu@A_$n55C+1K}yA)r*
z(ssp1FW9%3i%BLgaFf!GNd9=#N?RI}L($%LeCP?wGSj$q+5Xtf6}Cb0k}8rC+S=GH
zgG_Ff)<Zlz$-c;ErZhmtGZRdd2MFW>Imv68N-)EcZ@iW%C9dgOrhI*N$qY-rU9!W1
zZ!|(FfgfIZjx_M{Q75gyeAA(wm~S{~Nk%#}7@L_7&Cm)tHGgatYd*!KO?y$oCax_v
zdHqrTUGrhY->?+Q<Yy3rr<g>g4uNDJdIt&XJ$^IL3|T@!sMLN&L5PQfc#GgOg*VeE
z2s5$YnU54PoJK*IiTzF<Mat|)<&V!FOxl-EB%E<RqcHj35$`NyDIa2j5*`Ve*bi2!
z%=+H=EPCT%gWJS14SeIns8S6#zKbfcU*p5*9glDP6!MjdA5=bN@f*zNE`G^+5<B#{
z=errr;`z8nVH1yU6ju2-2k~}nFL;!bdghaK&8I*L>3l9kp37r<Q{;hwXGfhY`7p_|
zDIYI+q~U>+89q54?t!N9aN<ql!I#0v4CBAUDMFe08l78|n2#|Pdf24`l#jo%S>_8d
z6|{Utrp1vD%~UA!DVjPco~sX#I3DbMdbjBI$k+rujZ^KXL_C7j@G{St;@YZ*cwUO~
zv7T2lzUQauhvIqth7Y5<FEJtjt^>FSr*8o+;Jf=l-0bC`Kx;y}Fd)@#dO0u~FT5av
zS>ZUr2|@tNm4Z2c)7^r3fzu@enS+l995+Cs-w2m-%5S8pGx?3&taY;?eyz9sMmVcm
zek0toxBN!<vEJlXM{#$1VPfX=j4^n;n=&Tj{%v}MSlORVP>IYAP4670k52y`=9o?&
zALOCl{D7FJI(>zh%R2puknsAEK1a-neWYWO!9@zQ0U}vCHzDhG`adx<H$0>ckkX6l
zL+QQK(TXX+(;16-!sW1aD4DnkOVf~WJlwtvcyQ?!X7Co5=a_|W_~u(?;TtaRGwT%M
z%I!o)aJaBprv$H39q8mO^iig5Pj@+_c2AEwW`C!;etaN7JkwBqD22Q{_lz#xa_(ay
z`g8y^IdH>A5Gn7|i*OO>?MFt^&yZuIg9=>+jBeE?9i#6KkJjm(B6R|8)N-4&F2Q_i
zl_{8|Jah_X<p8E*wYzXyz!u@AcYqRpzS0ZaiCP+foT#M%bO>oUny&JTC+Z>$RN?Af
z>C9>!GF9%bi&Etgdw>$otjuLAkL8(d(npqDr#CV@a}Sd@vW_x(BkLps@{nAB4ZuU`
zCA=u^FCb511IiE#7(s}Rbd>baP35m_03L!zvrlrI=?NX;0)V;c8*T7NmP{RZGoXX@
z5v2Rxys!-rLFuY(0Qi+Rw~g{hXKx#YZv7IZa$D9-A1K4=S#CfgPVe(Y2~nDf<wv3W
zIZAY$hlr%Fv!o<2lHn$QfE2#xx+nu^C>`z>h2Hb{Vg~fkun!(VF?isgYG-%<H((EC
zgn-G9I#ch_ky=6yh(ruTSmhY6E|LQ>j?oM@j4YRoqc?RXX$O{dhE7;GQ)fbUz!o9?
z;s7ZI3;_o3Y6Wo^y{j4H;RJNUp|ptcAeW%VR$a9Q)Y#0KJ`~5op*7e<GDG@+UYqIA
z2jf^cHt4xZeGY(fM9>@{#r8f~TC>R<=Je{$9Om@u&iv$qfh?Jz9AHTq6|^W39i>YO
zJ-svA_~?w|V=*GVblae#H$#|gbOl1?U}6drR-e%o2t~;-6bQwkKrm-6?*YMFrqoEd
zhiCe3fZk_#mjQ$+L%=K?#uX%X7(K=_?e>6vok_Mw7;`g!HlUg^V9hCa1f+TK()*H^
zFhR;x`jabW&M7{>P{t1fyi*3=86C`(gL=Ruk_o5BrPw^~?hEG0Od$;fsEiggxS=bc
z&;~<orAm(r`k$f_ZA^wOMoBS<WD?_Qr6SW!J=3n)U}$ZMb4J%H<MCj0t*p5t!fTrz
z5eIbt%sNb0_DmQ&7+{;?8@GW-^*i{;mRWiS18Qmc98usf7)*=owgX4ymWOsQzLuuR
z!Dw2ksz|pH(X>W?_{`F|pskLF;&Hv~oUYqAVy;!=h?%B{W-x6<ppH|#*Sd`Z0mZ9y
zJ+B@LJvO@1GdOt>AY-Im0xgR%&Z}G_e%aIr!l=OudfFF3N-Pp0sZr{W48&gLSmrZ_
z5i>uxQG_W20pE*&Ao6V-3?$b$7)M^z3IfSvRB%*KY`W2TpW*9HSR+w{y8-2kG4RJC
zM0C9@MZo>aSbC@2bBnh(K!IgUzBd%n^>Z6e#MjHnb3qvq0)R0zKqvv;kV7=gZ9oJc
z$N>?20ADeq2LxGQSKToU3@BuYd$1_M9O<TvFA#phqEyG;(2G4I4o<177i?{UYH*4V
zPv()!wVsoKa>kH^Q?mAg9t6|~FSohjN>~7*CG^B$3|eqp3IjfxfGdLH<KTPbWgGN`
zF`nV<bZA<n*g<;lyKplU&W17QL0BA%0vr(D3>gR^L=UI<=p;ce6A%db533;HL(ov)
z5Jrr_6G9<blwe$A$%iX-_cFj+*fwv%r*xKmXtqt7;3+xj*k6`Xp*<3l#Tbks+?GWN
zUg`~nAsWJeaf%BDfy6A5GgA*B4C4^gj8lBT>?inGbjQ2`izcNY9*Ry%!7Q5w8(h?_
z`{Kj-scZK|Y?^bMweLwOr3@7jgpX5PD;3U<F?vK`K#M};pPV%*oHhKT6M1Nn0)<He
z4_Lr=3Or<W5XjL^;emJsrtqB-52(Y!Q*uhL8|IQR<r{FBj#tvqpaYl*7VFDVk%j-X
z%7M5fGxOC6#g?KB2+RVTGGGoSAl0HcDpm?J5qSM&YP&my833X0YhyAfEZuVh*0O6H
zgx-qchRkKmttarVMTrHHEq0?&XJ(c@L4`TxzBf3rokGqc+uz-D8Iy!F6j<DMiYnlB
z3j%GYXc+<VEiko3+2Pi*Y#MMtX|?Pba9eHbI+nVz<dc?Ow^4?86|0=K$&Hju_jQ&j
zG6_Y4k9D^!?HG7Y>Vcehar6Yv(?W}q{kpVIOg@qlxX-TZk-&aY(hDn7LjoD_c%iUc
zpvB)5Tv_H01H$~Bg6jh6qp%E}bl;BzJlrW<;z*WupX#X!RPg{McGtP}B#OrC8%_X@
zJB0>xX3_)@<X$$7&Nm>@B$Ke|Tb}%F>Pb!Ip~3l<6tLw^QL7<p=G-RWn{=kAK~jNv
zZ7q|M<8}Qu5j#QJU_BSbAxg*A4hT)W3WQQ27bmH2&G=@WQfiV=w3GlT&C>Bmlv86u
z)Y-P-1|_wGxxuMMsmkQT9IF6i%`*4Ke|Y@6V`=o~a~#htbk+WB=XqZ_ui4hs?%)5L
z$3H&G<9z-%{{KJ!b{NyUUU4z{jdEt_T?&eCrX!%aCiD1Mhf`8!TZ4~JCIel*KFU39
zg-N5;=*eX2yqWpFT5F!rJy&pZHHt86fFvf&z?MLW;Z{m@kl;^1|4s-<q68<vAh9Id
z4t+*6G$LU%q0S`A0Rb8^aFnmZaJce~&X5{8chi5C9>;XZleTV*7gTT*{js*!-_GaO
zGp&4nb<|h=*EfejfKnbCv5{Jzv$p33YId(&<j<?-S?*DOx{n-D*tMeH^5hwPyPEk<
z>$<<^Qt{ORfgx)>`PlC3QspFsEITD#dT{_3nT^lLX`RRh6Uo*R@d*mzmd|zo@zQqm
z9p9o&m-0QEM?#KbCpmk|$_+Pp1~7C$x0YMDGwb$LsyxhMi3@Fng!_NY@@O^R+kI$l
zaJQ{>`kj^NuPZUjR{m)vEZ^YrMS0e@mF#7WSGD`os{f=SH%C=PQs&!=%zGMp=r>(d
zw5fj5AJa%_cXBWGch#655gYWkux`F=*`HLz&W3B&Z`)qCw-q}RIIjKwTRfww{L@O<
zsGiaEw};BegZTTE+PQyOzdh&^txxSI)tGahoYWWkmXmmk<7fLD-@dmG`S&a8dpA`i
z<$hbS*o#>BO$PoH6hEm*d2*^EDdSzmh$Mp8S=Bt8rOLed`@KO{ovIY&@vf4G)^76b
zH)*da;eJw)g3wq|l>2Q(<(Mwe5-K$yNzk8EgrF@`6)Ae#+lqKMr9A%ap;W&1_S=&n
zua_!Pw7>oKD!)DWCH^L?t}0K(pH$@cHdT>FM|)e5X=8Al{1#x4F9*y|D&ib!w<_{v
z>TfFs^aGBo-v~{s<Lf8ADOU<Ap?troR94bW9E86;54O4;i$AGw3n$_?oTKesg?qdl
zuFpDW{dC;^emx$_74<}zZ>t%f_M-|5KObHE!q(4O`01ft7`qgzz;iOSzv>3RUyT~X
zscKc>L2s(@DI0pmTA=w!^Y}?cC@8>*`)yNM>|Mp@Rfc-ZZ;#nFrRH~k?rKlt&z}W5
zx1T?UcrM-asgahkE;rA=^j69>eo-|=`Ql{`IsTOUA}K>xt$>lg(#nL($<_BtXXNJS
zFXc4*AWz`c2*tLOc(3);ftQRrQIz8ZKv9U_Bg)|<)$z;yrKdGf(*A<{gI8LLgL2fX
zZexkdVcl8|0!p<DSm}iz+Yz$TUuA2Pl%fg5<*U4u&TU|EE4cD;3t11ZGcU_=6TH%z
zD+({uBR!%})NS4`;^W?IK%{JTf;%eZ^*!$R<KB!jezuK!vjPQWW?!xdj=A;aH&urr
zd!&tG%+1~eLiXePbIh%upa{WLCX;b(<{DDc02ONYrLKKD4m|lEFC<xTdLY4R{9WjA
zo84%Pt>4(8V{9G!h8$zF6p@k^9^axoooM?y>KI$+z9GkWqycTabN=-$6jsxb(QrFS
zmd9u&?T%4Sqhn05Z}v`$&Cs*>$OK+83lBPH(QrK4)+;G`8;g9`N+u?o^k}<r8<f1z
z`xgX{A6S?Ddl|MHw?UD;S*lW&Dqj%7L@-jKz)U~t_F@oQJ!MQ%^2Hzw!J~e9GZ=M$
zp706P?a6?Yd@@+0e(r?r{o+wa*}9H3)jNF>@|7m?-HF+FHyLT@#oNj#`y)+{o<2R&
zj5CD`UUEi0QN?4=IJY;NST&k{@rX2d&>ebc8fUHo3AqR^;(D5X`<Av44_b#{Q-c)N
zJh?<sA@BG09OyEtr>u*75Vhaidm#Ec)l6uh`B;U-<6W|kDJN$dHJNjgvM(}Drs#vk
zug~p`(AT7={kVlyh3K^(n^_=bACgdB8zX!L`n55lG$hH)H$rE5zcx+;%dd?SphQU+
zz<5gzcIWdI(@j#hfMuYkY7yxr``8|W!@Am2?!olZ(@cvCbx%>}=~%i#1@P33<n?@e
z4`!yQ!)2+burt|8^7*?)%M91R`#h1QL1~k4)F7Nykkvs6#x-){cx0YfdJ^z51&WWP
zq2z4J$1LRW=>*EBLqqLpVTW0_r<EOc=boa^@8CVX>H+VV33q8lC73xVFhr&IM~y7L
zbSZ_e2eH-HZ$8^Z1NkzO1JijX69~h>=Gg4nbizR<;-EY-Q!%}GGMh0yeSkktkE7U_
z@;imcQ07gBQ_&-HE7S1^82W4|c$`ubHk+PO6S>j*xs52c;+e`ZYykb-Mil%yw-E(@
z@?9U6t;k-$hJru&uzx->)3ptzN>BGvrb<uuQsDVzT5TK1m7d<Ex9;VpcAPyey-VZQ
zN2d99(jzm0)AcR0h0`@IGm6uFP6;%ERQn?nlhX|^lb6#`FB6>GVCwWxyWN4BxznXx
z4(3k3G@uE4X1bUnb^4{(iNW0IlCV&EGrhYFrcRfD9ZZ$3oHGW*-kPW&gW1!^HlW&-
zM&?64mb8qxD=BlOk8MCPd%Xt^rb-tS#bBy*%47FQjoI(+r9OL!V>p-AwmX-`<Ry@q
zm9!?t0$f>Z;w8Y_wI&<_JYs7C8-#9t)PypCV{L76vxPlMp16-HXaVT%%oXJ<$MZZf
z0c7}=cpkJt@ums~VkW~13g*{PjJai40Mz7+u^-TZGon7Uf8`PjO3cl+vBdo3knp?@
z)C_tD=yuJZ_R;w@OM;J3L|Z;{Lha0ebVvNIj5NpnK$&<y<T_pzIUYFTOurX|*p}>q
z7DloJ*b_A)zTxW5%!fgV)sbL^yL`>)?ZGG64A#a~qh@sWfcllO*zn%38G${hUI_}-
zNq7di=)hm_BFrKF)#Kh^7B_}h<LXf}m>RFARgu%fG@31b;*Lu4e}{sSanJy<uNeo8
zi%ZR@XFVO?8B~D`eU`xip<@_dPjQo}8LW(0l4|_@%8_a*xRLBI!;lA5hYUj=p(td?
zG444>%@|_@$5f*q1=4cYj2<4yS7|Kuc!0|A8fT^Hi5d5t$^hTUA6_lp{qZWUVBWzj
zsV40g2E%G8o1t1{=q}&UGEg^?G8|6gR>ZMwV{0f@NJ16&oSGrBou{(VH6zlv*9?d4
zID#`A7I&YT;jp;-R7=M$#B$XPevNQ1C!Fj&hOGE7-wD!zyU$SWs2%5_!d7t_Zego#
z?AwA?afVqtSj59#KKIAg&yYz7N2Mt+ToGzSNFE;w2drC&WXL{~JV8X^qGYUMFb$Tx
zL!pV)Bw>&Srfz|hApo~H%FY3zgdHU}Dcm8Pf>t5iOnP9)Wz%-of$`!x;J1n@!?EFF
zQMbrSNU<%lk}o;u4~BHUG+`PUn=p+mqgpw#jB4$iV#c+`qp4KMZeAkyarII3B`!Vy
z%0M;0_0D)&NTMpm5_g8W#c29PrpkjJ7lvB-uglS<R>3GBI(Shs7}!6-jO&Eh+2T42
z%$Le_!cb+Wu<Rp~9_r!FUOrhPMkbJWL`~N%7PM$|r}~M}>E4g%><Xl(1Ee#4bTRHb
zMkiAM(v$JYFeu?@bSc6-&cJlWh-_(2=&ZwMcm|kzAp_+(G<tL6a`7ag<eywkfCI>>
zng9ooQwmCrd&S|Dp^jW=WLPS4-8sd}Q1ELa985gQrWagf-CLB(N&}5>MlP+Y<Tb7t
z)nCP|O>8fD*y4)el#?}L0V%w3!B~WZYrytOGy|yCwF|GIqm=|~2sTM)20mi-XSD;A
zf>w&U3N}f=w`-OBZ$q!viAUl2&@=uP2z*uXw~nQ^io|Mwx?5%P4LG}6l~*L)FyuJc
zhL<+X4YWa&2Dn&ffG$ygozz$@cqA(^@YiaD>;hV?X2>pX7fwlVk6127fdPG_D%lnB
z%bbEKLR2HH_Xtu)JLxRg&=BX@G$78iX+V)KgTO0`!fBcY#3h8etr|)(7-{|CkaIXG
zp<`k&GUYHGvfR*cwWw8~2mqxyY6c85;WGn<nKHV{l*7!^8A43A!&>u0{Okj_@<eYP
z^Q_qW^)ENO#ctU9jUQ~#J!m6=dTRWnvJnn~5xOmgNj?`1Bk_x_7Y9&gcdxqatozFm
zgw9qBUL}}op%-a_6%{l>1{5#p13KlH(ox1R62pnZ*btkdjLA#dGe8f>O*Mn3+o^E~
z#R|(UBbS9C{<$YujMd(;tYRp-Ss4Yqlpla6EefofMghNLS;dDbb;u~<Whlc9#3=#$
zH#HpMqQMxGk=jO)E{z8{TPkC>58@Y9r9WI04u`y<T$c)DVK9mC?tmdW+zlzw(fa1(
z#gsTT<Gtfn0#CFL;R)5Ej3-Z06frEw@S<m4gAF6&!+{D^Gd|n^y<LlpdPavZ#V_I-
zQ!|Jh*O)5DTP8%R8CDKlAE#i5P`itCHr!fjVGUo8GWE=Bp<owXIf2bnGdkVU2@9->
z$D1-`8iQ|X&3JW#NG`gTTEh}Z(KCo-<n{z`&f$baGQ81DA{oZ4^~eKcoSJd(M8>Iw
z_gyp1oZK@`oXo==zvyMi%u6&B0OaOLLMaws+9LpM7KOZo<-f?m+8~%~2G;}9W>EwS
z8EY>M(;yv-Uf$z2R?8*p18!rBMD{`&W=Ot;I4sgaaj&X~(RVaF+{lYes<=tjLd_Hx
zsTV@Wh-u@*wZ}<vKu70fFRtuGcmKb3&$g4FkAgCAeR7Hh7!6UawbKg(u!ZUz6hfa~
z;V8LbpTYwY+qFWJmc%^9m0s8axGF6I(P<$`H_BA!gfxaEEqt*%2y;_Q0vJy?asr=r
zs%sG{JUwsr6J9QfVt{*1x`R4`ExJw$dnQ6Ht;%Jf80(l=#1Nc2AvRG$5noZlma3GT
z2|7&4xl>~41w=g5@xVh`rQl3#VyL?bx$wL_cnQ<%>NzQ4*Gx=?N`F|Q5W_C9mDw#9
zwX0iRsKFAhF^mu;L5LwU6N9*^*Q8*t3zoR4XD%~E=1w`mxDBRyy&u1l&^y=N)H~PR
zpL<`*vE@3^vC%O~(P;t~Lyvr+c%O-6Oil8Igr9&*Ffo+GF{X6fDeM~>O)cshdk416
z#J;GMjyol~j*W8={3c0`b%VaSdy4udh2oNdmVsr1zPQ6q^wm*fM=Y}&?yr*{vq(^F
z7KLd3w<ehsc8pzD5HS2osxcUBJ17e~WvVZPTTL~L>u;Hu5q4pjY&8jN6??E;8gBv1
z%cXX)FUuv~Bn2&FW0s-OB_-T~0)PZkJxiYgd<umIg6SbnUdq9JT`)^m6;ZrI&Nsyw
zBqfAMVweCA1td_|Gg)shrK%cO2)wtyP}l@Gf8wp}g)%VusC4#?aDdYHo`Hh!N?{$0
z{>1&6lt3)FIqTrVX+Qd>vSCW#BmfCsDOgXe$XQj1<-!$H(AL@ChH>qUU~6s7V2_@Z
zBs=BmV&?GyM1q~WMeTySMPmWsRI6lW+{Ruh<9yj1=c#s+!ts)uCpBi}QoC<;hM>ax
z*2*QNi<``9<K^R_%r_e|2`aEtrn*7E+db6{bkcwja6+4p%+&KrVOJrSnea!HLs@|;
z;e(ht=!L+(5m|R%=sL^BF9$K2_ocp*!oCqQdJk>Rq-b*@M)S_^D=8FX2pPP`s~BTG
zrz1rjvOYatDX%h<XacVkN!|klyD6<7%2D-FewFyd7D&oLaDhBI99!Vtk07E8yi(XV
zz;OUDkQ4@r^88!q0(n*vUEq}hl}&l(Zd1qHNT!ZA%8L>Je1Rhsg@rG$6{>pXrm31S
zcL?uzjqaMn7f7v!@B*m|F;iP;PlOj>2_Pt`djVe{)wK-J+Vjv+Nli*P;7d0o!hjS?
z;tQnGNqm9SRGk8))0ml#8cimmqi|xLxs#Uy7I`JWA_lxb%o2+@Z*_zvo45MGlFj?|
zT0q2s<AtK@M@PetE$SPY4D-T5!~wtI9KRReJ9+y8`)6Li!0b77^#iZxq$p-ux0&}Z
zFneB~u6_<tz?+{a(Kl`u#4N}=rKg(2fXUtKkylp&807U92nI1Ya(3vh4L%NCc(MIw
zMlO=G1Fi+Sp)V4zyku{uwE`trD#+X}Lxm!&Lxf%8ZkOeP-0d_TfVVvj7Z@y^m4!Fx
z2}@zPz_y)DmJ9N-$#l_Crrn}5Z!2$Mml)h+xgdkvBkeVwv=xnjw}$gx>9VJNG8TC<
z*hiX^JYB5JO{)ZR)tTvJU+q;Z+?vKRGEychF_I!}0`SxUAvz3d7+aO?j(np;Q#$Qg
zWhQiE$ReC*hMSVgloD(smRwdsPxy;g$hxrUmnlXSS?;(A%d5%K(+`6a<XxCNeR`+N
zwq#S7^kp{nEXc6hl1q5NrTO*nWXfoUT%tCnMB9^6Pk0U&Z*5GyeN%bJ+}pQ|$Y9Dv
znMY@%Md5HRwiBT&vS%{~b=tfag*Ie@Nle<&S%NK|dx~LcGR8A!cCCBvZ5s9CTfEYy
z4<ll|(x?yKTxrxNZ_=nwR?w(VKSIXT<y%FKaG`pV5tjx-KE!=dZz5ITIyEzGuZP+A
zH9&&&>H-Xde5zsk^a^Xh@qxfTJ?}6Jdp-$O1m097+GbD<o|T?uf7j8>yM}>J1#vBU
zxniVXf|tC4P#hqk66fCZSjDNgc)P>j`7W8j7V+w?<k<{is7ju_LKO7UR~e6>H^_?k
zgLp1HK;f%oN4ak=j`hm-QLeJ_{qSOqqGwii93}8KpD{U6JYy=uHNE+3B720ZepNo}
ziw~JhXALKO;YHVr51G1e1xn))FVs%pQ>N}pSIJjx%&%xHT;8HbZLMa}t2URj=vAAu
zgodYw`Fhc-CG$+ve_v1hmCpK=R|0zGS84ln!-prq@u6@@_cy>#46Se_PdX%UqI~D1
zl6{@K(?g}Be3kMHulN`i{okup<3XpE&X;75sf5>uY6Y95<qp1iN`a;0I=nzUeDa3V
z2bOKnt3~=LUDD}r!Z6JAN%1Jm-ED<&nBmq^;b$(dmpUjZrCN?Cg_A<1`*@XtNbhmE
z-!LGP4mx$vqeU9wU<jrBd>ErCU!XeZ(IRb+e&1E9-SYdcmv4qa$;tPeIv_cvv<*s5
zDQSq;l-pATb<$UgAV^R<g}_gwr7DnqhH%OY%Nz0{*8!IQD*b9ufJ$E)^lFj5G+@xL
zOe(;r&044UPtO+VLUhBH3)>3gbRRc-fONR7Qga3*wbY!^G&+u#ZZ50<rvfP{^qQ_W
z$4Xg!Ypl&ni7rK_zp$JWZ)#Dv=JZ~X8j;XOuO;oRFe0XV<qoUGHXxp@uymHqtFy{6
zy2y$l&*-Af<I>u6$jUjoXo65v>4+MUq6IB;>r{AY3I!|*WI&O3D>r=!<y~H~6&VVu
za*tGGFsN3!7Vw6y+7k4Ju8g>06li6tlogukezZEX5b?Pv><CY!X4Fh0z_Xf;8@WR3
zxREO~?Pc_G)~V5f^;eb7rpnEkXM|juWyzsSv*f>Anw4deA)e{Tyh1O-qgXP(L(*DD
z>DnEoYbSn!oT)2va#Up-S`_(Ut5v#Svt2k~^ShLTH08Nmq-9I!bMqi){AXq6CMSg7
zu;g=h4b^m8M>uFz#wdn^R?}rXvYWue{Q!mj>|_#*ljhgzjyt{*V=c<H``>%eXs}J9
z6>+3hX}Thgv?`I8$C3JId3BYK_$7-MLQ5l5pvq-ja#b$lx>3qyTr$&L#v|5&Bcac@
zZigKYvo<*vw-YE!n@5@YV6oM@A~|v-H3BfmB)X5^+t3)uK|QB81#)m~bSl>+O-|*!
zlF6qWqBMe0BVgvl4;Y=o(Pgj<hX;*Z=>ThoM&1&lFoR`sbP)!0=I8`r_~C)4H~P^M
z8bg3y8Ynq5FJY6jzC>>~#y?5+_E7tkGqTc^U5O<bN1L%p)zdN6$QQ_QF(`_X$rKYs
z!DI}IGPQ!BD1vY^)|SCmbvej4T`v%KTbVqR;FKA?g+SajLqjo!uDb%FaH}$^GRC$l
z4{PmJ0ctcR^_mfCY6uZ(WJ*<l8b5v5R*<yTCs?;oxk|r!<;q25?iO*kD84{Y-owlO
zh_F4i!VtWRzv<|Asu2VjqQu}r-ZeV0@~Di%5nu6#m5%tWYalT>8HN?q2nON$(o!hn
z`qEM`6KhX4+kSF>GSPONrY&VPPScjs+Mntb;>o~Z#DN|pdG9im!kJ&G<113iWyooz
zdq4cfj}HY9XYguWF8@u!nlAqefUQVvrzqJ+KoTC045SqXn1XE?ahw6U3^``hE+`Mg
z^&TL^yk!Gy8AP1J*@B2ciFr>QWG$nJb3DO{JIC|Lc;?FZ0tG#z?(xXTXofOp^mIkU
zf#R!cV*s&iWC%hyGE$qf$!P8xaS4j`CI=7@PRim$?2Ut@vuu&&wS~5!;BzvYTNRYE
zYJ(piTB8hgU+c)=d!o%=3clxnF2&yS48w-V;QJaWB{M#syQp@FW8lXs(ErfpOEdtd
zJQ6E_(bzja?j?8wZsiMZk3uG>ktQ?o4ftgwP;g~LMK_d!HEF+D0T!LMn%_ZJg|^dW
zCc<}JyEN?Pndt=AAW`7wj+%)HO0GkI)GnR74Ng#U9daiTCK5?l<{OBs1gStw_@QIo
zNm2|xB=ZP+Q5n(ErG!IH26o0lif;zVaUl0~HW3>^Z;6n_(4T@3UV&ZewaagyfuKx$
zkfBxx55g7cf(PM=&(M)BlSmvL31GrV^~5-FijR2YhQ}pbP$`x1CS7WFi)OhTQ1cvl
z1!r8qz;G=HZNpb5hNlSO1xID*{85ZOc<GYY2xF5Hnm9Hop%cc2JRpz_Ktz&YYJ|u(
z+?0uIGc^9-w#*Kp9~=+fxPlbSP5F!0t$ydUgSGcIZC6AR2Z$uxB!l85&KgRjz=o*b
z;C6bDv_?Fn5koB^pl47V@#zH1RphJ<*PbEsLnG2KM?x$o&e(wEWEyMVv7M;W@tPkL
zVml3ul-N#FBPHd|h639u#VM3mAz1Ac&M?58DzPyt!i8u_i61%p1*nyjlyw#mTo`Xn
zR4%d>W|{$0_Esiyp(qbp5*lndffjbWkYrsT<frsiMlKEMs~bgMGz|8mZN0}j%B5qY
zB=UNHB(&O*gvtREe2x5umOfIHB_;a_^V>*S27fX^-SbA0_;R1|y>pgBz7-ouKk-@1
zQoB*I>zMV(bGiy=FPTnCu6UQ>cQ0>@36pd3J9u^FY6oLdbdfT*e!~w%fP=}Zxh;3F
zD#ce)vUf*4n>xls$j;+SxnE1$Hj6Lk-ujKlKtVHB<fc#f#+{OzD#0MPlHMRzG~1O5
zB1#w~z!$F64U@tS=md0?EXMQBsUIvBUc8iVglyHnyQ}D`vXQt)0q0(~hC#^T26`#Q
z4=;*W3LDrzuevoGloT(xOkOEnkbgAcNQppFFWVXlO53V+yj$)iNgLcqFFg@$l%Y8W
zektvIB5e8t+&HhX*K$hU$Z)y6uKhPoxf$&Mvq_!jV=rJ!z9RfbiHc^SsWftU94{o=
zTnlj`CZ%Fh`qq%|``Pz~f;3oKYdlAeOO(#B#n7oe1tIcJWF?>dgo3mavXV1V*;z<A
zGKEWlVxcrIJ0VBoi>hofJLS$vb~%LY<=EPVCT*m#*~?R$i#@7zI3R5)a|$6rlvZb_
zuwnm(!g22SM9RL_m!}LrB5d0uK3`@EI$lWZ$;E&Y5bcypKUvIF9wShWEzwaSHi{A<
z?G$XQac<d^Sb{CR@Qr~PnRWuY1@dHMb=peYP6P5ZGeZ@=Whi-6foez>&{qn!Mm&ie
znW<_~d}DehtF5$k?c0>uuyz9O_yypanNw@0WY4}SZ@zXE*He|e>-g)e9_2hEdtopM
zr5=BG7SdloD65udObi3dPQs2w0=nh*kJa5MSY7y%d$PvRL>8%brE}bhgX46TWRA$B
zTw6!Zu1q$$NQ)(zkaAJFmz%~L<?N_;CBEd?#u+_fMMYsJqXC6o-HtobbXLwMvMSDG
z_1db7&^7wCYMK7iDLoQ-P7U6pt1^)&NttZ4Al+alBrWHju(X_+_LTBrBgOY~W+qg!
z8<|kcDR%qu;t5ydX0RxW%buq7<ZnnJzmYCg*<PJ;BmXM|&53-e${Jfd@F6nF`rmtD
z%2`l+J(!gigh*{`nt-oTDdIRX7nPzN9=TLY5yOEHvq-ll;Hy&V#t2`6Qj_7a1WMlP
z+%57-Vv!s`vQ?%BE&%w?1i}T`EF-~iiQth)bIdIl==qHMC`gED3eG5qK{3TqIOUF9
z$Jz-MoHwz+bFnJCpdi_mDVktWg8NM;#ffyRa^NpW>#2m#PPzJ)5xShn&q}BG63Ic2
zEwglCqJ+X91fRRuU|s?bkg*l6<42H!vt3L;#@3Q@4jEe&Ai5|ul56|da5yE{n_>?6
zSxbsJ<Y$!+cJY8DlQXrKBRP8tI^<`Sv$RuMG)yKKcsaBvekDFKnfamwGp}Su?AuFA
zf+VeQKQ3o`SO#?$gjkupgbT9BT2bkabnaw+<YFz7dhi>`Jn>2=F;G|>tGu!zHKq}`
z=k`SJ@;*9{NYmhJgwPk0tI-`f-i1OG;W8c)90l*~;>8K^HAd8<`%=j9D#YFaj1p3Q
zn!JDzz+;ZhbOd2dUOqoa8*0LQx{>=`9zQp7zY9xh#SI-%W)uFY$+rigMkWX=Bs4Yo
z^4yUIzE0jzkOY;{;X&|W+&PS3123wGg0f28^+tTR3FhlYUU;E^-7{uSW%fo+c)9W*
z{K`xQw;L(p1vlmqTPB3EJ7#SHF+-3SBlUyeV$jYU#?^%y;N^*4H4LA<Wumh{B4{oj
z5Nl>~{JD`Hp3rd*#HX3?=I%&;A|D^-$#viawqfXVvW+gNg(!Nbd}T&DUNhzsypasv
zYL4QHCVG@&mNmx^v($ld280B(N$PfHk4-@{+f;~{q^17i%V{RzadMg_l`WRjc2&yD
z90O)$yBdX#d5eNtWNjOYf5X-`?J*|Twz2pQHrekA;vg3(Py1L&>C04U<Q+tn#-uPy
z6R|vDToaM+k8}^~pEV7mCLKOpW_{B$Vp2Wzt(a5KgKhz_?An1LXm8U7=n4ddAmCke
zP{xXl?Yxa`IOyW8)86v1!Rao%OC9AlHVq(lBQ)<Lk8Zm*eI#ad<q%_$F7XM+v+?{v
zh@9EAorVQnUHpxq**yAU4!Y65<R&~oap5CBhXMd8lb=I@OE{6aKxvcdK#!oT-PyGB
zfV@Qzu%P%fn>JoGA&Ge@UO~*g7z(_*t!aM&S<L9fP~f?3!c{Kt+_olfvQlx}%X6Us
ziGdhvi_(O_=B4-^+F;3f-(;1k$a*e+gaTh{6E1ZDK%B`Pp;ROYGT~bn_*XATx>f3e
ztMd{@!EI9Gy^W}M$4BOq(wz-%($=^u;3aMHJ179(u*O|+6u3n@38No@{D+Yb3`KXe
zIxv=qGb)4_B%mNjX!PQ5x<Cn|JkTmOEbvDxTo4YBV)bq@AKFU0$(Jh-6VWQPlXi<I
z7Z>o>a)m}Br-TB}XKTFX!SC7Rl2G9HZ2de?bjEhsp8|{0y39||Z>+=o1oei<l+O83
z4&;tdpwJk`iF3W{J{OpsCbxr9!K*;u3_?L2u0))}axo}SR>-j%om9Ty7bq(xcY*?K
z#k$N+c19_<V=#C0ICqNy3)tjZP@uk;d<zQn7n5&5ahz9^XF!2JvvoUITpL6=8w&Ip
zlczv|LSyn2D9~t}f@2<fjmdeS1PGJKcc8$d*|A?^lfa|d!l!Nt_i$ET2(!5A{8g^k
zf_ErWZkaNW&36=ifbkM#dg?5|P<INfboe&(vRUx(WXy(B!uS6O&}bOgF7?InKwTfY
zqzBHtDGyJ<Q`7+r>!A3|M;aaDATqs=7GUEW-bc%bPG}E9M1?7lP>G-m)6;0dtCPce
zV<Z#32<M?7*n{}sK?y$SK98p;!-Hu-REg=q^eA|ZB3ya=$k%(Mb<&kl<-jX=in7sI
z@*O^OEDn4&%Hvd!gJMyFlgML1ME0O~&>&&kLAs})-GkDJ{*E$+!Y}6v^)Oys4^Uz+
zGTyx);s|i`PJ!w-WcEZblSPEZ0a8OXhzz`L5iCC_E=2TNTM%AlBah-Mdg6$osws_E
ziMTG)(`{j1>mggh<yh>dx7>o<FQ&BLB|^+h*_-hk#!Ll^0#nBr0j*K+KE`YZK?yeS
zy|*CIjtxZS6y)Y%7KI~71MNV7;Zbd+W<bdoR+d@h8DeUOpu};d7vh4%N6Zlc3L4^)
zKqnc}1tL>ZG}J+G#z==m+9*@%xPpJj1UnY!(pMZQuS^fk1<ACSVIwH(7gICrSfJE5
z;=#}K5?wBeP1;AU@nAX-FJZl;e|RKkBoV>yu~B3+_Fz!YP10C{!{9eGI10^fXc*j)
z*Mpf;yo7PE<h-~wQ-GP6p1NN$eIp*aDWobQrket)W}G+;h}DNv;s*oG`Cl4QuOo1~
zDZC1y-L29bKch8VArTzj>WqSS&Q+Nq$eV01D*!!;&aPR}x13QUjd)WC)~x8At2E6E
zK2l@XoU5^W2#0CvKi0<s?;A17r>T3)H9o8+Sn~;2mnP_Qq?&CNg%|;s3-|#|)*fIC
zv<T%og3_ab*p|R4XtD<Z%Am;}6mSPlz#0PzzXA1qh7#XoFT(S1lf5Wjhl6mViQ)T(
z@nN%T7~n;GK27mrvuhY&MSMZcqs3-?JWbH`Grpc?)MeLma};ApAq1NtwtV`R(@eRT
zX2?6I!~m`>y(?a(oAIe*h8$}^^#_#3(G<Nl<CAEzUg71sDVhzK9gA?G4WF?o(NrLR
z1SQ54Te->N1^kfa;cqjPk0$fi#MW$zhnq8|O$RkVm^9@@m^UU$J#PBOX`xCULGV2$
zqZyD?nxf?Zwz3F4iZM?b)ri=#D6s9Gn5gV*Cnic&5wI|gv32*Uxk6dEgYzv7aVO^*
z8|XeUSMRZ4o^)5akteLBp{`(}yg}Rr6NOHB7p!QOW1_;yz6+L=PepgdCYG(QVxoNg
zzAGjQ>mP#pn(-16&)_Z1fsk3oJIQTeChUW^sSE5Yyn;8QB8x}xX1ulB24+&T#S{1o
z!5QD&%y_r;7sBR+&etx^`u9`J<5!bO#(@S*!n2(o1#bg3x)*{goo#Z^*0V(tu4n_u
zk>jO+1}zHydZ$t}lxdlwq0cj%RJPU(%VYibpZ@FfPUT-&M@C^oS|gy9{L_DV{Qa?{
z(D@wW=Rcpd|K(qf={)-LbZzT=wzRxI>a)G__{(p{zxew<pMPGA{L9}T|M5?M`Mc7t
zKmF5x|1W>{pZ@Z1kAL--V+lZHp&sQP=W4u-=YOu>%|cz^8QUEm=r_LvEe1uIiLHNW
zv=JBiX0(6$zy9C<_IH2zhZyBVQ+Cz<?C&W7R?2KE?RSS+amI0&@Xr6nDBX1Uc9j43
z|M9Oi%C=a!5_vbf7p&7$rkqc%mfz3ljrUIulECHrDF3>W!#k*oAF^Lm82*!n3SNSL
z(BHrZS2Eu3t$+P@z5nUIe|$U^N3^~Ewj}5An8E3_y6?94<Ne*{;=}6*nOW2K<`qKo
zH!xtK;9Sq$@Z40(tn&MN;m=K5;cp)$?CfhJxb*BYyuXu(9jPU<nsQCNt#&exJZjP3
z<E``!^gvZY`D>9KJypur>u=nA$@{ioysqEpy?vkeEs{>=#K!##6GKkgtfeHiZ>zyS
zIIA_P3~#I9o{-gaad=w|D12hSQ2D;c|Mj5%lf7U60RQ2Clao8kFHFv6+}%`-gfFTg
zrE^xh7<>A*8Ui)4nj$yeRzrLnSHKiC`K=Xj)A>)nfb#tn;4^DZPVcU7CkK$Mtfu50
zZ>ycxr{2!%7kaBuG*yj+FRIPBFmMG}{@c`*XPt7DIo&V%{QVVpoZnvog3{#V24CCW
zP7X1ISxrHOZ>s@RAgc*w;B7S^24yut2)(UV>W@4EqV!$vFL$lqmq3p{u>W5q^4HS1
zI8<a-nEj0ghAP*#aaZAspCh6!t0=_oZ8by_lGiMMliOv5{r+UH{{eZ=m!+JX%mHsF
z2UN<eCYZ{%)z0>*x3m31Z*YiLEjh@)s{|lGvj3tj^jq9t@Q**)>VH7li4eJ**RWrh
z7w`u*eQ}%E&reKO-?sx3xAFIq$?X7}VEP5Sz|D@F>-W~p-@fJRkNJ}w|3|d@yn~QX
zH|611Z=>s${v76$|LZ;NCu+cVh6yZz9Ht26opOr!(X1xI+iF+5iDfkr-d2O{Fsq61
zwi-QjvtClZu?WkD@9RbQ&Iek6PP`3Nl=m|XtMFEjg!k1vntQ8-^7~4GU$xaD;eEAh
z-zHJ|2J_cb_xUyVzjHQ~fQa4(Ny7Vy-SPCX)f44yMdohEib;825kQDrMN!^YZ1I|~
zRTSkLYq3DVuCLePJ6c&qp5tw#qP(9X+%C3?qP(w&x5TZYDDNvG6~b0gl(!W<4(FxE
zq<rgac<P|j`rY2G#`kV0NJP3D((G5{Jd+h}6-9Yp5iVm}MN!^Y41mhLqA2ex0vUR%
zD9U$MV?h|(m#guu8w*~JwvmeRc8cxnpU%&uysrqf@vWjL?<<<^mAv%6g6AXN>yYq`
zHCTqV`|CCM&RNksoN^l`%I_!Vu-1Dm65dyvyNrm^+X@}Vv#gYq_Z5*^ZmTHDH~8OI
zG~L(y|Bj~A0YAHqRFwBqL^|WGqA2ex28`uiQIz);;oP=W6y<$IcyMeLMfuKZtkeNt
zuf`v^<LDChdgb|ee4fcyxBO4<H6nb|WcsZC&+=kZ%I7B=QNEgCAiHn%2=)HH+NVbw
z623Bje0sJa;j3z|4>v4-cM;Bio~N5~0#tpQ-nieM^sM;#{YI28%}MohkH7SU^HiAT
z=N^CQ5vQDpYR$D!nCmweV?}EIZ@fEcpa^){W_Xrgcw4zYzvSG%^pbObe#yCi=_Tie
zCwf+sYx>)2z$KKKsnN0YTZ?cnjrJ!}=?_@4@6RteBz!Ts&o4RmFTLd4z+Bj@q}MMz
z2u#3csM-{c#@lM2UUKFid&!yqJTE!(^GnYBrI(!9ZL8v7lW%{%9&EM>c7OQ<G3(eW
zc;NNhpTE4?%s=vKGyi#BZLWL1J_wNTg^?aEr&(?GUw9C>0AH2WglF}(+UJ*?>z7_~
zE}$LjDM9GR-&%odz2y941^$4<zu?%Jlar_C+sOe*Agc*l;BB?Ded_IOztG!&GiN?|
z+~+U6M2zrn*9x%w%@r6+0sr542jVCZzmt<wK+oIB0X{mb_45}VTE=IUcl?sZJ3f0U
zjbHLo8t2X4Vg=57>+Ek|f%UfYlW*V;-2*;9?mQ{)A2Q+sxK&KbH?DRo^dl^PrTlL;
z{W0)$8|p^-(&E2Yi{iIz{?Ctm#N*uC`Th8gAY(GbZKxaR3uCi=-T)ivI~Mf?Nc>AP
z{nmB`@YB9ulk|l>HtrjH)g*n#KDyw$%dgCIe8)To7>I4S8|hapkb6y0zGH)2IX`}B
zp7T5NyaS_QA8nG}TbFEp-V7V*JNBi8uVG(Hq3@`BG$8GRP15_F`&TE)C!ziE_^Z}`
zW!^sLKd;#@?6H{ZTp3Gau|H4yf2~<>Z#Cn`J?kvCUU=u`<?*NgDfYZ`%wN{#|MAmv
zWnMS5s~Pw>ix5#m@!Yq{h%*XBXb~d7&i~5bo$zm*7wsuC;(X?%n6hx&nHRBeX9VfY
zYi5Yv3gVjA%$UCEV?>}_I1H?!qUvh*vf}UzzXwJFGR4k|&Od-IT?EuI42xccp7{1z
z9$PToik+Jm!(9<OH?IJcni0`FFQTZ-ctx5QOlR&;KQ95X%rHF6t7kCY^g(q6t$9H~
zZv{U`l$_zmh}g%CWM07jKv3K&V@f@y)H32NCO`|w91+$xFUDEVcqN_!zC{M-c@eTQ
z5LD;I%Qzy{7J=isz<d}i=M}>sK*7AQyo{VdSlS}&VQGg`(CY+mnWfAVUr%8H&k5cl
zbZSnpwi3T9z*iUL5m9MAE208KRNB1gQw+C}MNm-Mh#?8==>+=)Fm+-KjOhb_>J;4a
zePRrPW4;Rpaz<edLSW7a7@LD(j|do>0)W1OcsvCXeaDQZfTZsz6vlS>o*Ik{Tf<Xm
z?+wVoIS^rr9P(30*AXi=g@uh!uqPo3G2Dy5cd*z@hEG2Q|5U&>AWf&jyzhqb&^&a9
z58fn*gHvceL4z?KVY<Zycq*>_j<EhYh^lvYY%K-H-x0z;6;OY#4{i=(-{7f!5u(rd
zT4x6F-|;~&3XtY}O@$3`4@``X^#MIM2cQdY%x?~Un81@;1mMZV&jrdBBcfa0ePKvS
z$qJaZDJ+LTWphG*5P@w9Q2(A-J7R_ep4#D*bHh)25)`pFvDFw~2RyVnHe|7aDnuqT
z)IhhlPfP)kHzvj)N}#kpDNN`E$koG1gztP7gjEbM(m5C>OIXo~JPbtXnnOu(2+K7C
zj`xGuo^uGv1|XeNNg)WkIhi=(Agtz8VhN&XO(mZo9M)vY3cyx6L12u}+4aP1jX3c|
zNq|Y8P*3pJ*a@=>*6M6=7CuQRu7O<|M#C@?U#nppg5Zh@NKQ~r97mpmWR+qF2{Vb)
zs3$rY&Z90!s54UO%|6s?$G{WyGQP_v1ts4xJ)zEq&!mUo3xaQ&o*<oZhA#@y%y3Bc
zga*AZxRwpYIi>V8i!f1(?ck*9O~aiSZX+t-BE^^+ey|!%7(1L)T}XF0s(M1<0VjMW
z6b}G<XCnBVaboqvbiFZ0L&-&N-*EhHthsRhZY;U*h|1|DbPBNEnE*!xIDS*={~~oS
z1M#8Y6zszAE;t4|L3sjrclIJU6#(zf#Bc)e?o@iIMTy}Hg}mUb>+Z?8SYM*V+2FJz
z*i^xRCo@(FkX@&+U*LpKrP(S0v^x{_szf~S6f#x`895U?E0A>;A<$Gxtp8MQu~J%;
zz*roHN>H{aK3KwumB^7al^bnQVi>|1DLCzvW33>TYbv5>QDO-jAW(`QcTK1%fVQ1Y
zSSx_Goe9KN#<Mhp!w8JpMd~Q~$EEaji{d;a0F9%_P9)Y_B@arUO|XctuS@~k1y1a2
zLiYho>{M33Me#ioXnF@ozG;+Pa8V|zp<$d_3FTLCY#|ZQ5hVYno4(`XN0*W#uCgBx
zjVPEk&W_mx%vIOvvS#UDXkC30O{(J5Qtrq_iS@521&0M=RSS8R7-j`L6KHkCsnvv;
zRdH%H;c5i{;;|^~8mCs{zXw+ZuU&D5wS;KHA=XZDzM2;kgfPZ`qQv(pHW{}syVWAE
zUq)TGAmjU@yn+rsDJaD=SHkJxOfx2CS$Kl0#1?U;DcNg5BKBzs^oMiJ1YBI9_)TNc
zhyH>lxY#EcN(4a7M5=^+blN45ZvYoBQbG(yyNUAWAEpT@2|m5kpbj4eInJk2_!guz
zp9$>=u$`Ikp8=k;2yFNw_Y(mUN1sqg0fRHGt1BFQgfexYn^huiKd}3zvLhE@*DMOV
z#yw3rmmR&&=hP_X1AJx?h*gNQ&zb=LVq+xsCJw(uh7Dwx!%67dp2wdF<1_I3f^rgy
zFUDr7f%}_P3By3mo0b56INXG=QGi@BjmUsF$b<}X6hkpM3k;Dd?2%$P%Y++TfcP<m
zc~XpL8Gus?o@tesya0V;8g*%)`c477ltA^JG4%tKU?q-KK=e+5+Y~_SPNDG>Jul+}
zKb*7%Bh;UQ6`w*5D%cg1U_-@lR}-GmqAZar$fE+>+$p!20+`$>prvBNOY9|pJEj9q
z9-ugLg#=ab^~}l|F&pK0h%ayv*y)9PCh@`x(p}H04;mn}vq~MdIOM9dVZ$L;2Q3B#
z;wv8K0Sz*%^kc*MR)y_qIN+)jWV<;yX~>2Ht_rHyy#;0!)GRVePs}EkcGd*fGn{}`
zkbFoWJ*!mecE$vyQR56*m>5xtZ?fu~ZN*C=b8u?SD#h5dEKNNX7NmDt6fz8{rJf{|
zVw3{ZL=vr8sTaqoJgd~=NF8=KiT&bKtkR8<9&J$|VUU7uQ6Mg!C;zNP8aeXiEfRXh
z&8`Zl6#4vSE$SJEXD!0Kjm(0J!k%HOtkRW3-B|?m)UdJsf5y%wS(cnf&huDBt)MOV
z1i1o@)mnn4>Vft@QIh!F<NU3M$;zzk5H~YGGJ|vwbO5%NWi=g9ek4Dyu7j1uW-#?I
zkA!CemF24yLV3<rww{?p5$C2Q#qcVwKhi<VA`kLYC{VhJt!FIDD`EOCS{B>S9keXi
z&z*|(M<Ct6XK~WK9t_e(HYJaj!$?cV%X~!o8c_HZRJd0ADo%8aU4JC%AIMjfaFLw9
zN1*-zd_`7s=J!2qsR8%Oa1L@Z`mV1Y1$CC!SF?hn%%$9%HfNnxY<>@N)h?IE;Lvmg
zD8I+5Rh&wbqSZ&Dx>20`%6G`7%J2G0gph-G6)*X##z|*6YOb#~$sixra{Us{tVf{E
z;kwKcC}h)JUx^e7s~?HG2KJR|)roz@30(&+&LX>=+_;OQ=B;}LJeJA_?jBHVxQ~8Y
zY>{{p)>nEay$w%_m`6@=<#o>h!mm^g?vM4A(~*y4sp!rXWpAz-K7KIx+5{iK;A<Nk
zr_7a*u9PyiM<l&q;k&IjvGBE-J~9>FPjXwq`gx7nBUjRqPzVgHd~K@Vy0xb*wKzCm
zYL)?|udVP5Ib5%da2QqVE8a8`I$iDQ#w}(?y|Srlx4ybjl%HE)Z7Isc9f`}B9h>B<
zM}<T1NWR*5_l11D*l{ebukckmAM-)VOPuie+A626*Lr1@Pp<P`TjdjkeFq!O<U;Rt
z?%J7Oklw-wZIjOnvac%bOdUO68{iX+eKEi@P4arbEYO@OUz^tx1bywaKBDaEmw^}v
zeU-Mj-M`gu@bh)1>q)}=_1Z+AAn5xgRR%#{o9J02cD=UHajie=RqE!>3+5tCnZJ0w
zhWiPmzBb#b?YdqkJ1i5>d}VRxwZeMsz~<s%y>?)8GqI>Pb~YJqFV<_DdxD6sT-div
z>w4|MCT(wQd$8wBYwL)lJZ_5(fW*16Wq*?=H@2PCd9?$n@<DR?AKS~DjI*(APLrQH
z==yzpY<s8YPJ1i1-P1E+Ew;?*xl^&N>ABIHX@wKgV$Z+HpUWkH+Cv?QX-D#<nI5;T
zq`EI%$0C26G5ROEAIO7J>@Q<;$<f&U<__^lzC6&^)H)(%CQdstz5;!>s%h*m-*u%c
z{m*w6-;pDgJJtB=1#;~gSx+$UWaBG0nAf&f@;8O^b0yL&=B%ym$nVEj{xJG&{Y%2;
zD^b;g=)6m^vO@%2o7tI+IljV;Bx4R0c6@GH<osQ|>|*e<+R7#Yb9`kaWAOGAIZ8;c
zd?ZpfZ|hHf<(|)wp2;s{k93gaF}}i>q*RVAJ3BKf$F`XrlQCgsM=+q*djuqf_^Nh7
zD~)Y)JPsblvN0a%;5`zJFg>WT?39KL5h^Mg>C!rFje5a;wxJ#AI*VmP8zM)nFOPJB
zWGrQ#-nVaGy6a8foObz$vUB!S$EI`kRIl8+g4BMeecs(APxVtEvm6l<1)C+7EphlP
zv0RY`Ld%gXfS)?Iv232N{M}>W(k2o0X|pvzOF6`FeJ3k09SI8^X3CL#-^vcku3qie
zu*FPL=vbe{40R=zbK%2XiDjquYW!~9Pi20)%K)v$1l#iFACH9HAisYEY(k`Wj)kTD
z97)ceP3?8Rk$>HneaSjrgIC2~Z73)|$wTve-u`Mz_#TNyHc@9|c*Sk$fmAX%<fv@s
zWZ7B0z_4X!^#a6}t?6W_9D%&CBu0)~8@a$fiLkMJU-i@0Gl96Uw|Zp_;-7@p?S)xT
zN0Jc(vUzjmMyx+ixU(0_-D3S85wpP_5n=Z<nT;d7{_a*2VOmCksd7ZA8>ULQTy%k|
z5-urSpsE~+?Byh^gh^F}48{>Mg`uN_YgLz>Ej<)|PMAeiNLYL%dg?{Ouob*P!mt^<
zLBbev^lyOBrM1fj2;ozm_U*i_VE8K$vV@-kfhAnByKKdE*gXxFM#wz=A#IpqRd&}1
zF^!?QgzJVE5dBCrVuh2~eom%KM6>e<u1lDzRrX+nHlHy<B5Vy~r$l@X>z^SLu9#jn
zz!$cKv3-Iv>xIIKr>*YJ1PRw_FVs)`!e0uMmIynnDT)|jhxMjfz!41u<F?ohV7`QE
z%NGh3hRe^FtM&E89i;^$Y)w;1FwEO3&{SgD42Gx@Ft45zjVt)Rbh|R`t;UKDWd^O-
z-r;Hq_01c=Fy*RZz=vxvRIL1P-G-WF?!u)Wsw(@2ibGT?*o7-fRO;2mT(ojPVa4T+
z$Ayb4440UpX9930XjQl>F{gXdvh`+1ak?Inz5;s9N$bwN>zh=LdPk!116^4*<w3Oh
zT4y4Gt~snbp=%Cn?#%3<m1gbiRt>g^hE<`!glo*ycifhg4tn3u8&Nr8hiO=qvwOG@
z&yi#&n!7dmd2>lVDawx2KM%^DRCO(GL*2?><Ve)D$Rj|w98sleb(mdMaeajA9M$xW
z#4J`Edb5f&FW#(T?O@|9)($?JrByHMCDN1dAjqHa)pIvvc>UbXtCE&+&B*nbuX{@|
z_!u&KD+Q)wVD=ut?VLGSwSb2st=@VGD=|!At}s?&$OT<tti+HD`bci~$FgSNaJW`V
zO<v29NHr(Fu~40cP7JxAD~`Y;0dp#z!XuLM${^)~K9cNm_(33`=v(#rM$cTy%B?t1
zV@&rCcpLNI^quUD*EdetBgwn5TKa9V%fMTSG2AuaZ4B!L-o~)ro({z@XRG2gJ`$<!
zO!?4=fVVNMedL69VOhn4eMHjE(QoKrU8%4fqq)zM9yU1(Y7$n$wa<>=BHC!~Ac!`a
zItZYt6x(w}`SLYBaGohA^l9gOSN9D(8`XN(ZNXHm)K5Mllmc*OWF1M4rqap~(_*b0
z>0JD-a@BGq8XJ%}WOg4({y^`aZ{2ARGp=gQBbtLGjv)IY7j)&q=_jFe16Q{vo-3;m
zxvEy6t#4}q+FZ}Dau;?aNAZ)Qe6aMUl@b2J9gX=|6{<|AHe;>S{tMS{tVxwQ0_o*6
z*O%4gPZ_3Z)x3%PZK=)$P)S%BE>c-<&i?4(c>@+r!m8BlJQ7?gN0eQj9t5!1rv{Oz
z*r!#4iX9XDxuP6|Oz_GLZuDvGKx3aC)_Lr(;sNsaA<c=*(T7z7pRm4a1wZ?+-aJ3{
zVc396b41cR8Dh8YnPU`;bDbU{hCNr5L+q%I`?nqmoVvVgg)|c`0b46fo#-;ID>bQ(
zgokGDn}>rZv^P&9V49q;2T{Jva!*%iG)E%k7fpM$W=@;Eq8SW20_o02<{nWKNqhM>
zHM3t{?vy<`k}O_ZFS#SSywa7jLq|d<C^H#dc65avb0qoPr@|wNj#s)S(<Hjw(iL`0
zG`XcK?3ifV$_aA_^TR4tdBQoVE999YK@|tdwyo<PB%6KJ6-rK+GFBTP=>ow=lHJKs
z|KP8Mb?R{EI>kqHUmcY)u8?8EM6L>N=_jFe=dsyST`4IYuC!bm*w?02C-yZ%H6^73
z^2(E<47i_s;I3hpjjlg=G#lRVV8Vp1BT0j+*=UA*7EP<I0ea0wGjkEmhBFiPL=$iN
zh$dgttN?wj-`076*CXV+Xeu*WA?Sq*h*wB_M<TUAU$Z%$Y?&i~)?T5@gehIM0evcW
zRH4R%D<<7U=(jCJ5FVo0`sU>gQ@Sdze7K&}k>nU;Yxl&)C!Fj0h;EN<S$FW!6}D;z
zAYG=bQXnX@tk;7m2O<0WZU*7<Vin>{!0M{7X2SK$YBFb@E0SuCh%TE}bI*xt3%%n4
zt-^DdGf~YFsZeKvf^Ze$%xOz^{yb4_qqC`oiq}0?bjN6RSiM_wxIkWI^Nwm0ogF?X
z%2$&G{9J)FC5D;|R^iS>wLMP#?r_<`N)7KPT&eJga#Vq;asSo`^WYldi&f|~k(AB{
z(S611v|=!{+R9G=j%p*nr)eHFjr^x}5Y)7@BgvlGLho@~>^0D0jzr(kd9%to&+^()
zZFo~&J4^?w*hEpg9}M`VRq`OpAF=Df7yN4X>@QvxoA1=m4wJ@yW6TdoG2U0DP^;LI
zQJbHd5P3Ob^)g$cR-JiZwj2qY70i~O<hByjs{Gg$Lpsdbs#$vaxgxfRjE9I?{7^8h
z=09`lt8!&mN>3k&oHhfDGmWd>YSU3)E5;F8uf5IDB+B+fIVXz6RYyOK{40NU)2?oY
z-J`B7fB0xCwvb0>CoHy+If_MD9yst;Y&CPF3-hjOp8B3I=}YBgcqHiNWLIoglbr2H
zq#VpEp)1ll=54aLA+$u1#SEV%icRL^vqYJGs9@1ltvZ0kVv9Ks;zytn0gJ^(^AIc+
z8O;M!EQa6#Dniw&BcC9(;9~hK<^eDkTg)(DqS#^{0Hc{&HMuZHa9;E$CHG}4n9TS>
zPFu<W%F;b%kg~|Me(LqQgxOvd;>(e+)y(&{M*dCbZ86V$k)JTNtELMnip}E*Bo-UU
zR2B~sQdKA|r!B7!zN!$Ft6q}JX-W-%SmeU4kX(+0i^ED0@gtIIAhBR<Cle;j@2W6i
zq7*5vxF$=nZUC{o)?FE+Epi-)QEZWC@aA(xY(!M*4rj%w5Lv=BubM=bcx_2TWO?G<
z?lb`R%DBdj8n3Z-j@x2e!4G>R+N<!@9+4D*XRkfmGZE-W(35VYBj6&lQVaVhx*q_|
zUVFB)%JmUwfSmqb8|hg&{z(z@g1hv!g)Op+Sz8sd%RB#kDcz;79o|%V{z+)vx9qi*
zjaxrV(5krpBi+jnqQ%#wDL)`3I8Wa}D<{@gdWM5PR}}h;(ql<&BAyGKRPkfpPAhxv
z8>cF+%WG#g!SG?WRi!X`y!K^BL31U1<4CS%+tUH?y|$<W@Oy1gbK4Z+TRm5lU9>+t
zIWw;<Y;k5@S=ge?y!K}6A}n5GwJ0;Mjc#Z&uWfEoVqTfkV#K_!xRUiyVqUCiuJ%q_
zkG#nF+HmH^aBf@9(eqS4P0y;Na+urRZIV6Ajp>}pAm+B^3>ju_mvFAIVdl1bI|fP5
zyqe+19Eo(#+mc=a5{_sfIKR|sOLMN9Bhjo)lC9a4&Wqx?%?vq`9HLEWD&)*<TRDOO
z$X1T?&o+VcF8sM7b$8J_Jl%Pxe%ovb+`CUDzO8vNKQo&DL9%W~?Cgg5GPj-GBtn_n
zrgSDtxf0!HU4qOJNcZNqmoW{|U~ap**ZXUUYJJL+F+wBwdKsb3ZAdM18+;+POw+&W
zt)@PAbJwV+KDXW6E75Ll8PBWm3mK82!u%w(jzu}Q{oK%CjzoQ{%(ng9nL79gq&Ihv
zXKwEStI_{TD<{^T?OPvxZu_;VkUn?$#@85)S3A6#lkiVp>rMg4Cb7nCsT)JHZ?87l
zS$+~)zb`D?*ieL~$XQ2ld$G){uGA-=%T8?ylpl!{-*<B^JGEgW{Uo&RFsJET6++Ei
zGT7nM%w>~(#cfGx0^(dt@iP?$%`~B_^4DCpv)9U=8BW)tXK86aDH?q1drtPw4s7a&
z&n0tw<v**ho0(t6WM*eB+v3dNT(-sG+RSBRJb#I2E*s;pZRV0K4%cRy-&Nt-OiH;`
zm^P;^tMXE9<`RRXLadp~wl~C@Y0g)rbogAKzdDPDU(w(rXK^gMtf4kelesGN$GPmX
zPKxAnMH)e+$JpDKSu>YC)-Y@4vi%LSX0Fd;4Yg*v@^xh=n69*4bF(-CX>Pm^6)yzT
znj?^M@;-__b_9#>u+i*(`-^G4Ic!eT#VY&Zk?@Sf!)3FXUH3@THQ;bLc)7xxnd|j~
z!NVm-_MW$)j-~xK!(QxU%{*5m)c~StV-+gRk+2PdVn-s)#MvJas*~J!1X6#2aE9R<
z;`EWQ2hqZ#u^0XI5gek-PeO}yrs@~i=W=y5t%oN?3=r@OySlMMeiB-DrenHSITc5u
zW5NdeLWX#I-`mOs|7$UelUB~4oZ9W0WY3l4EH~&f(_FAd#_<{5-vZ^t;%b@8<+O1e
zG_2DZa#=Sl*q?;foill@8#eHf@XV$uYwih<7R}=W)<RzEc7q>ITWW!|FuS_JkeN}X
zs`HLiYw9_mYDJxQ#O&(!f`z7bwfB6b=%Ito7C&^**<6yh!q9J94Oz}dkbN!R6Panb
ztB)i*|9a*~ns!8}PUtg@tHG?9@&21WkX?VR8tjW#mT!YsGvl@HANtL0z4_u!Gr<}x
znj;ysFJd2o^xRY7bV-2*iRMV8B@NzbCRob@?wn?iG!DUYE)NmFoD1E6<6PFXv&D}g
zbev%|pyLb=DABRJyZU`fcswGSCz<8D9jMxpd6TmIJs{p(3GV{bn=9fKgL`vDT1J<D
zb0w(9fpJC5S4p4ePvlpk6!rW49#zzF-AEi!cHX~mDfHcB`39lpijptd(leAIb-vz?
znjPQpFI|z;CE{I?)?!Iq{K=LTCO}>h^LGLA3N(F*kXJ;X5+bieU1&MH<yQb-+fNkM
z*7+flUH>4XQ{jmj>Xfb%S`uomgx3W^%@uK7)1cH`*+7s#mrbr#CQSyH_;^cv5UJYW
z;ar)t&75+XT#b0yD;fxvzI5j#AH>)=KQ#hzuS7ivhSojUbP!$9$OnbSA!dEUwfz${
z_i6DPh#S;!kY5q^7!6L%mC>oKpQX7|TeDl;tF6hc-;cM|Qyrih4*V;k7xm31J+H5(
zymG03M9jD>s>VgZPb4>|>T_Qa=$JH}D*>h(B%CYD@j=455|%cknxE)(FRQxc^lObE
z`jox;Sl2i8u&RE&G;g0cD?cg9-@z8vsX~`OgH5bknC|vGywoA&T#+`HOUbzs>2JJ?
zq3`6IXdA0>C3QulxoBKmrHnc6`6|Y;{>~2^i)Q|~A*bfk>d-*A|2UG7ZOz$G2g7|H
z>SWNow&bs^BUgh^b45IO(!c2*Pu|nd467VAuS^}78pd=7riP-kSF3TF!}^KfxH38r
zybqtnM$(!qQV)XnA%;7^hIeJ`M5O)riMqeJ)K6Vzv`SNb-0qakxw_RW*>hD`YR3H$
z(WyLQwVDuf1=gk4RL88=1gB=|w<b6Zxl&srMl5BoJ~mQ758A82<x%Sh_z85>YOQ2b
zc2O%V%BWUfG+J*AO|bbHbI==7l;^|N5;x;@7loUj_11)&GT)j&GaLuknou)1bhQR*
zh7Mj0w#TjLq;8U5{Y@)QkGh-1-0nf+N04RL1f*v4w<aK+n}bs$qfl0mq6__w_p|L_
z^jwj&34Z6&A+y1}`N?dYH38|=<wa{Vn`~Z9Ksv+QCyAV{jCo2No#8$TM`zHahtnHO
z6N=7h-GWh9r)dosbqGL%?sG-p41Av}VjpM%+Zzbbnvm9!0PPl?au`5Mg3psOsapE6
zz2X41KuW)xpx3<q2H)$7^sxN>u1EtB^qSw_nxJ=fKVHZ?edud&Rgdhn`+;2-)M#C>
zJ4HWeU9dZS?CXNvj81=$@!tC6*TG$f4>agMM|7J-FKsmnb|JH(2U-_0JA|NJ`p*?G
zc=$e7gy*mI{7(L<Vd-+^h!~a*1szD9#RDMy<dta%g5+s?zYCJ5?fouDR>Z)O<Zt+T
z5JKendKg0GX;Y#Lm8VY$V)<N|`T#0BxS+xFxgxsIc|*o_A3FOx@dd3XEDu@wU8wB1
zfFsII5*W}rh&!CY{D@F)yS`6p_lD7hxFh^<A?~3U<f9^6Z2qu$u1NDCz#TpvbOG*g
zp2tQO$tzO_g2^R@p!LP-8`BCGqnietzBD=?5uj?{5_|fh5LYn(t#dXV-CKJXnhwR>
zwIMVe=|62lSUPOjk5@hD+S|vg`4!oy4S}hH1&)aMm8Z4kmzobqLvZTwfg@r%bsQKv
zybd1+28Y+-;Jh|;dL2gmAsBYpz!CAo*svc$Sip1$OilZ5B$K@&byINaP=GcBr<diV
zXJtRVriaj!#|TS@$V*4WPw*<Ht_^|d@bO?In2y)#yN2ckJp`sVh9E1C+#dFAZ5(8~
z4+296+3thD&^fkmZ^A<e?8t#OCWGPk7uxpaXD8e$P~f?e?6qSB+7RaU<$(xt9Y4^9
zAUAIU+5m5Rcxb}gu7ki3+&aRb4Z&@XZ)n0?hZ(fNbEJIn-u9rG?}q~n+8`GB%FwP8
zvV#oT;Dp?LS|FYE6-oEj9^7puWLE4e(VHZgcC0}gf@#GXwE1RBN4F^q?mh)fVXz|!
z+7t#ml%P#PFuQt+ax5ZFv?&NCnxIXAaQAUy3WIz1o;QWUjyz~HQP_b8N5Jo<GsZ0X
z)xP~@>LlEKG?+lIg9h5vVc2m4Z3=li3EA7sLvFX(KLx4XX8#nV_Tpy?QhWJ2rGqYE
z25kbU-Ok`CK<z$2Ojk_(4iFiT`4heF!q9YbTp+jp73krKyF?oNmd*rJDSOza5VhIB
zpF&gx4YYZ%vMmqPhtp>Co`LQrBGVC#6zIW1%C`Jq9Zelt(5Aq%*<m{cpUn$?0-w!i
zf(fbW%6R<ZHEFi_XFfUq%o%M{9~WpgCzfm>)V$#WEe~D4mM!!UWIAS`g&?!#Uizdg
z-{EG%J%pLfhI{ZWR(=RF+n|Z{@6dx5g3xBWK7^soc71@Mjy`BQ=N=htem@)Skw?~M
zlRX5ejxT5-Ky9DN9xdA%Q_~=9uZJ+UHJXf}T6fDEg)7T7AK<Ga4q6Cb9dyt_80(;e
z7TqJYb3cT!t<t<twiO@3S4APT(DAhuu@hPdavhn_La5tp?FXpaY!`%3H-i%%WV|1;
z>~RKNi3TjtZ8q&m2ysPn5kw-d;}2R0cpZVzLcpsKgcicxy1x+$cnLx{f;$)oA+!+k
zItrnMptpYh{}A?8`~O4GTXiakl`Zy^5b_d-@U#&4Ry+Sg$6v=LG-@VYk!E0NxZ(So
z5d1nop@mMi)h2()r|kHGw%%;Y*j_?b#}~9EWF^4h2y#(Y-v%r|w3<wHMERT7VP(S6
z>I;D-9Cc_yTY}L_Lc2!(m@8qbmT*+@32g~StFHvsZFc2~XiGll3a~HXZ1u5W>7-h1
z{V$zVGvMGsHd4a2w1lg*{dp8Wl#T>T5L&+j!0MV_?-;AApFRLA*AMq~zyd|9gNGX|
zlq*A{yvo%Fhb647YBIWF55r2Rtv*R`t8+y>SYBm^H?*aLY5hF^+(xC0=?v+&=YI)t
zZxBOUiMEPic&;R8x7gk%v(y!7Mg+ITj{haNEuZ6mfw#pcfTh!F(U<alEB5>^d6X$Q
z@T4rq>+p!S_=vR2e_R&L{1J<>f605SsD~qA5H|KVNL_5#Zy|NDZNFdn>r2q4$2RV_
zP+GwdZI^6GkwCgkL*SO5xY)Aa0%}J?v@M`^JVe_7b;d*JS^0h{Afj!ZbsZ7Wwp`A|
zHvwCSUd+U5J0ZRJ1h56^j*Mt96n`S00Jb1pISNw75ZM<t`0O}`wuR5dru-H@-#gm}
z5ncCv!4^Cd0?~E?bn$J$7C@Kgqr?_O7he}_A$0MXU<;ugD$zCwombfpBHk753--`&
z<@<s?7_fOETacZ1>G>pKwnHY`7WNif{9EAbaEG>m+6-=Z5Ya2&8Ej!~;SjI|w8e*j
zEuby0oE3VCbO~u+Ul?pbt)nE`Wi?*`l)Scuv@iC-7S1|KqHV#f!X(<3FPZ{APs;9S
z9XfF&+0EAnkF7)QD=)(-Pf9n<mhP|4unvFdFIfBP&Y-`7S_eS%S5W%~^VBmV>6PSE
z9SPkEnsjMemtYpI&6BeH2^>k$Uz$=bU-HXwq`z_{D~{s1GKMz!NWPWtuy)S84zB30
z4!Ez59#4OT*bb)Xua2*8cNe?*q;ta&(J6Dl`YY&tbsx}QLGO*5=r6GQHg{8~`?hbA
zguAcK7yT9PzRf)l_P)(sPv}*qrIheuHk!Pa)g2HzzZ@|7D|BX7pOoeAU#(uJ<F|US
z@;5u?qLT>uCo*5Czk+oIUL48Dwgw`|c2LC;(RCjd`YX(Sbu-XkVYY%V`U_&euP0N8
z{W_;#e+AnP!sxGH`+eOBp|(Ra`n&(xgk{``O1t2QP@it<Bar$8_DxhqhheoHmeF7C
zCim7^qTem+C*X*1+Gh;gK^L94u1(BEFZs9TsuVh=8-q>?@$F!W4vlK>@IwoIi)6v{
zq)=^#TXYyydxyK4zy97jJ9Lm?Zyg<;4t#6}W^^*EZ^vcyOuv35gZAP(Qr@21l;*}5
zb#Kr?+`Wgt(&-(xf4{iBx9<!(agKX;cO((@NZ1izOdSdP7KEuI$&1b-X?#n)8O*Ql
z3p$p|k!Tu5PH+=Rq+=*;#aMJAOSfYz`lUwgUH#a}5WLI_H^N7xF9j2xt@H8X@hx-~
zk8h#0czo+Bl?mS|uke%5$~k-8g~gmHmZBHDynDY^yz@POt#|XH>kQB_<M$1x=otEY
zIZIIg9R&80t=~B*>?KpbbDY>_^L6qH?IoMNS3Hh;8DjJJvQ5f6g2uP>oSeWTp|c!=
zp1tJ7@0^u>lG{3ec}+rq+6#-m!+zT2B|Yy0?5FJjiw^l|JHnzT|7owV(#i<6D4!11
zX)BzfLv-2>spyyHv>i{;VL2U%6p<Bco88xIzb)2&?Tl!6jGZA3>FspiF^)%c`|o92
zJN+M4lPI~@u&Tj;y0>Ev{d;xk8h1q9BOHt<t@n<1VXtn@(4zM0R-OCHcF09fR@7e2
zgPgn@O^PRjw5Pt4-(j!nZ^iAMEb>l%i0x2`j*n&&D$%J+blU35LbL4b4#{b+;^*c|
zy;t#bmwv~>gY%y?3BcMi9z%G#l2@NOop&v$Be)BGrAgk~%d~lM!#>)sC*E7REmms!
z3ZE;|S3oTVJoI!;ZdVNNxG#5j<-$!m68JSoRP$SUZgL}cEIk)I3VGy@<j$H3hd)=8
z1F(hN+HFa5nrk~kPfe3<yR>+3c>>&*gx4=$Xsb$iCmYZ<XRgB^+Bd?XLmk?VaCkay
z^X(9aj$eJp@Vo*<F+6;L$aJ~;pgXa{ss|IBU7Jj5_s{{V=+->*$h}=dykGXwHr=kn
zEZR3rqH{s9!v=C*V(hT{tivhVj+5wIer!iYbPDcm$3^tE=x(ERkIUQqxg)x(QBe{{
zFm6*?z&8g;bgqJSRG$GFAQ!fZVH|C<=X%~J?I>0a#t}>LTuHus#o9r=DAo@0x#)QB
z?`^R{JJ#)1oJ5C2bObz=9A4XH$vgLI+o2LY^M38T0eX<!{yH|IQ&n<LnY|RA+^$C6
zsZP0})IGgtLs~#SM@n=kMB9-PM{-}=xvZBec3V}+d(w=y*>#<3&`qF3hhenmvTA^E
zF8NS81fxBdbvH(6tfsu@HbbxXPXFSYDzI(J^zE67?g+kbWe08eat*!b)Kr0N)0QuJ
z@%GeCahXMX+VX{2wCAwm!Kq>ntImJib67RdM!E8y<fCnxUFX{VNbn7CwSOeiJ#&cN
zs)GU9q$YRahI99%C_7_Y7`o6lTdpTt=m^+O;0hhd?cj4o`Af-OCI!%Taq=91ZR5V_
zOSKvj!0uVC=%U-Ko`=o+R%uE9&~|<DBgp}!Svr8fDdzl<+|kHY-l4y2l`rp5WVQ%$
zzu`d*+S4eS%%E*jTZb34r<~*+>d#L?>lzJXyC<OEu-QzK(e3Kw9Y)cSuvcWV(tMCq
zx7(6h4rF7~x(j;P%7#(2lN0i!<c@CG%1%Df9yYQe3+=IJ-GyK#TvwW*BhoVxqmD!m
z8MmcggPAUAek9q~Zz)qTe2-~OfaZ_|JrXj94d?-64rkQtFow3Pn)d;24x7->i1x4<
zeOW|%*oYoegOn8wg=mjq<v^=Top%UC+bp`C6rw$xBd9|d+M`=n<fvprGu7M0&^zgf
zH<Y^5zVDaqW9W^0*g&RY{Z^^-4hv`xxxYJA@1G+Y2ySPadk=7q=9vRHN3&{x^DB1V
zdGEJrbN#n2_OOx7y4eFGo0YYPeBMWL2Pl{K5lp_q>Ysq*un|20$)VLfPao{o?h^<c
zuR8(+Qlz}Y$lYeZb=W?8z=D5zl704g-4Ot=%ctF;`s}_vejw0A%KIc*X`2$)*@kzQ
z=?$@Y_ibIjvtM7<!`ZK|Z;TxN%#Z66uydvI4xwk8*48f?o%Zd?a|L(0yPej6+L6#X
zu+4?ZJB0In32c25gT1>w))Q>&)13p`y4}??v8~%-J##yFw(6Jn3EG*ub|g8XN$ale
zZfEtS2%WZUTx^Q%n&%xl(C&6rlPqX=o7*G{+TGVv9qP~SHn=gTjzkXv|GM4Qm}Nf+
zt@E<Gym=>3VvC2?35ng^COHuoyW3w)SjMxvt@LCO?QSC-64Aaz&^!F0Z6aHTJ+!Zp
z_aMpf*-Vf8hO}~AbnWzx0liIY>j9NzcU$BXqBxQqVdQzymC=tNyJ~woK+OI*r~}CC
z_D=@~#x9%ucOKc@_BiL2?c(S?nqE^I<nV-!M5;l}Znt!@gm$xq4oT=aA~fR(brJPW
zBBBi`u0s#n%~twl2<_%{L7lVSZZ^`dT3O>99=8c{odf1>nB!Ds*=>Cf$o<Mi(>r{h
zD`ED5%w|t@=&0F(2VcZ&c2q<D+0Bk>xIf#hxDNMcH`CfX2ld@-ujg5QH=FB}!PyNz
zHHC7vYp6dx<MOsBc0KOdl3M5;qRuuauH((vO<wABcl>_6?rwm6E_B}Un{4ylIy{~u
z(Sr$yJfeK^dhfq818{hDvx|DYyaYDOuRmwE??k>hGd5Y=IE8kzhdKj6ce4pjT8=HQ
z+iz2+64Z8S^CQWZMXfuD_EO_G+s$5TWg^)sTHZ6lcAIt9GYt1gXyu&QO-+5P-QI6}
z;9RqtdiC3qR&cJ_0*8h3lhDcyrrO|6hvcrdw{cqT>eWb~^LF|2PAv4Z#T4sn-hbCO
z0Jv&f8At7rsAphYbq=47zjxO~>-Nm6j|4os$|sEvc~{%li-P96+Q5dEv#X8l%gouX
zaNgnNY;(*y9GqRJws$BvyV{~o0?rXg5hp;`Mek5>HWafbMUmf<s>PseQ7>?@%Ah8;
zf4dI)({FLSZ6;Z#eBQ41N-vPG+A9qwXII<Po7%0r%A!t^&UPvE&i%)RY}UCTIc-#P
zi*h8|i@9n!B6RQb6`R~#)ofKv@6dC0waK0Aoac)4k;!+YxG)}D*jy>?>czbiEvuu{
zJE^;lNUDI#ijmD-)pm*WzFW4K5^lA3wPPFZ&8~KAQ-yL@JGQA*xhsC{r04AFs;eD(
z&K5nbL(bXNu5GwEyS`T48BaRUo)k?!q{rldyiY)$*~M0Na%Z+_XnjL?+QlAkm@~V`
z?7sJ*+ttlGH>SJTrsh`lNaXP5?)8ZDT#&8E<GpjK9)ZRUvQgmtNl}i$#`#WcD|UL5
z({C4<;-vlCE`k2^drQ49+pH(&Wvh~Thw-wD?PmxtKMAcnvBmcC;68pAxwr?H_S;0T
z!Oi|IvY^LJz<ApDRt9Bte<J=lXHg#RBgsjW$vs|>u4w6wHzT2T=~j#{v~*h8`{t)+
zD^h8K+$~K$UZ|eiyshyz6jps90j^Yc0Dvpi9RTEt{nP`x$yROhE6IMzE*|d><Vvw(
zK&})ihWWBfv1(wi6syMn>3ZcOIWXItuK~B^+2z%fac-8^555OL7c?KRdbY`3<DIvK
z<vrjE?RUHXK;gTk1tfg8wE%>$xSo+!yHDF%a<6!|dk+}C+tbEj?_E|+>AGzS*SM6I
z)1F-)xo_T^X7PaTvfpLZfa7Z~^?>ZM-(}s2j<3$r1Fp+{!<rX^45f1(^nJUu`Cxq8
ze6MlmWWUpo0s3B<!OwspcSM7aWRGPB514ja+^zww<(1od6zISEmEU@Z*z(G4eI)nS
zf919w<OJGpTGXTD=V1~Lkzd{+z3G%W0x2$ceBD|(0lJL&Ghi-m6T^lWDsOYwK(SXY
z>+xI3`)&S)Q0x`e`-t+zZ0a14<)Y*xcZY4())24dt=<AfY<a77^_<*lO@P*0rKvNu
zpzL!+Ii$)5ayZ4B$8BkFoaWwQ9bDpXv$=){EGkicB{}_G(8*wV-#_2U*Xxy;I>_$x
z6Wvz)v-Wnc(yCl8Pd?x~FY~TOA=>eXq&30pNTm0I*%7cUl4E}H)Ldz6FR@JqRGB4e
z)_^H<1k!vK_1ep7(?iDYAQsFrHETd|Sv%aXO*dpdkNVOTna@XZcZRj)p+2JQ3m)om
zjgz%yPM`L?6DNCmV9_k)C`?iIR}SidX|(pV@@qY<J*+xkiIpbKd9`52tUau~FiwLs
z<d|i`)~MN%;;J99Yebb17=hF5ypsGx%dU0zwb3=FuO0+rEEBN?6(Wv=O@<N@N0QI&
z_iy!+az96;&UW6xX3YtZ%T%p_&A)cF;ybcu?P|rHAHSk_@Y7c-AH0Osx(B~}RaDKO
zX2;sa$|uXF_(78{V+@ab7W=hH*z#OS_U3i}g8sbpFX)Xd-vQNS?N^Vz`3KgPmwG^T
zS!=s<30Z4x&rHJFa@F#YbyuD%VsGK7dn8hx3vaD0<+(DCK-%x(UCY&<2Ju<Twao{`
zWR@9WN0L1>+(LOd673J|4*5vvAbx`*p@aApjwCxsnw};8)^kPo<y&z-a6T=+^`P9(
zTJl>DN&>Alt@YsB%ACLtf}C)jn~x+rKW{5BVXa{`HAgb6h3KK>qUHnE%vxU2L_n@(
zn;BBfG7D>D2A*fF?!GkoBA@iYNA;7?x_z+`jf-n71yl^&U~4t2=}c>L=Q^|6tT>-4
zrDStnw}$zENwdt@8Zc?rk~t2MW-Z&}$)j1TirqG#&McQcA5dqOX<P&M;#xMYvj*6e
z_(5@->N+53lGc%Ae~TX*^!N1$NLsm;%<q;MxNLpniCxQZjkk6!+uscsTu!L@-~Rcp
z&v|Lz-&cPhi#mSa{ejjStGC}-=->a#KmYTe^3VJGFaQ7F|KnL&8~NP-_=i;KYr5b!
zWiOWVQWX3=%YNL_nW9zo+n14RV=4NgMExh65545li!Z0|d#eRFZP6{h`DQ82d}5_4
zShVwiO5%oa=wBtF&!5^Efz>dLk`;3BT<4LEgGT1xyjpJdw@Zcp62djbXV0#*6l4@}
zP+TbV0~d2!imR=P`hYo)sgOM5`Y$ZvyJhV7m^7w!=rZ!<I#Zr|3h8Xuru)1+HW_`g
z32&nfV?ti)d~^EvEr<SlV|x32eg6K4x9nN|pDzwMmjCs|$v5E7i<1NV`{Lv-@~<yW
zz8U|w7l&u)#c`n~UYwiLxDeML!|AZUw<aI=y*SG6ulMGw`0~9Zf0M3evTg?e^P((e
zH1JzezBDU(Q8K*l`CgQ1%D>)}uK<%?manQNugZE~`|cB7rZ3caS3W0|-WJ!-=54u5
ze0h?p!VtgHpI(;_KY3lue8{)uca;0RF29$g%(KD#{usTKnE!uo3n?g<^KmZ_*v!-g
z{+gV+$`7#2OXc@pqNTDcFQ?(oUHd1{?Km6z3SW+|`>QPTR#*C7Rw$JOnK_qPtK|1w
zVx<1FI1erpQh&g;oT(dNTTavs?k(|CLB_?c*K;M=&B%YgJ)C|xJ=A)K5xtzB8`AW1
zB&bXm_7cbSGOw2jt|Yo&m)}Yr{AGIUI!2?JtrS*Rrm<pmEVEeQp)XTXp{ZX%n#DIy
z?TY?=BlXMhAl>b{1XZ%(F7s0t6Sb80G53RIaw=Bdat?1^<YlsIa{X60YKw4yb*ZY9
zQ&=XdlHGTSr^*hnOjKR>v>7%xuwa)dsf**M8L0$IEHg=|PO(fT-S2Z-`FToPEa&7V
zIAe)vx?g?=nGl>6Ryg8{1I04Wl-dU?bgR8NV>%yqo=KKjrx~2`TuG|sfN9bx)jk%S
zQ;LBsvrcz5Qs1-FVY<X6-8rMnTvASU%dAie7c7%PRV-zh6iOh^n(;j(JCXO)yWc<Q
zPrh^uzR3SL*Zw)P&epg&L7Gs?xp$dRnkVCBI_d6-8Vfq<=JaSXDW~ftE-7d44?0f~
zgkN*$65xNsRsyb;d8C_T<kZ0c|H3knG+hwSm88}@XqrWe6Jwc0ilgHQ7%0cgOy&5b
zBzrCo-HlsYQ-%d7w<ee0gubn*`)}16S~q<orHGajIPR5ipp1jP_;GRFrCaE>Ik!<p
zY2A#BH{x%ZQ%a$xWl|}%oYqv*md$bUOS@R!mp)Zmw?lHz9YMa4vbPFew>51qzuase
zQSM0vBwtR>Sl;|f?il3--X{OXulwqhTPToqMA8esIU{4qc+cg0j7PBfQp-!Ug0pg&
znp*H@F6CML*|fKzegbJGot78I%o>~K?b(n!z7STsl!fsKPRGnSEibsHjAlm!vW;cU
z32kdEYX;he_J<=m4-OgGM{wVm5z@^G)MVA48Gl=vqrv#XdWXg*cl{A%f2SV;@R513
zT%Y_hpS0k%U&9F&3cmd%yXpwiVAiTGTn8M<pnYCH(@D!qnBf}3eZ$8(hIJ?4nP6I|
ziLi!NcF9YQAFRSCE!=~w(XHyj-00S`7*V$#fG^WC<`_3GQ}frrJ||lIofCd78M5cp
zkn=BZTq$H2TF^twO*ybk4lQIQSOYhEp)TVxIrKlBMQ+zH_m4=b6YoZ`W?ZVHpcuS!
zKE~&WayUi0!Mstd`?PeCUGh%wN~A?DRwrI8WRh5>kd`b_u*@JWR47<Zs#vH{@GLV(
zkLdQU%WN*(f-Z4NOX;_vz5<ASee(n&cF|%AH?7N@(!y=*>dTrF6bTo2QgUCqzN8sk
z?918#M&<=rG%fW=jy>ALdh?2EnU-39=hh`kYT-hAIjLeHFUn7neM$^8+q95>WjR^m
z??^*0<+dx-t6id-K39}ooqXUtbhz7~U?1)`IN0TxFGWDuhc$zSW}ud24y-;roW)Bp
zXx-N{Yg<2v@&&+qU#O0-oI$aa3zC<4S|Ca+=RiD?ds<rJo|c*rXjW-~Z?Q}(J(BE*
z{P3l6yz4$u7fLCwUiIK|8+40QMa$IELb2x6t2N7e(B+0N5K)%drUm-S61B8IaXA9%
zN=IwAqpwt8(diOP{h^>pq@@Ca-HW(#up=j8sp%G7W{4JeLCX};0&i$FFX{@!we9D2
zHb2}9g?in~9MM9(g4MPs0gN+Aw4C9!Z%sq7T986d`>x-%{Lplww&iC6c}|%46xdzM
z2^0Sh4xXEbY_<5~J4~;M0applRx{#~@@zG)+X@ig42lJg+iKHlaI-d-t}3wQuISZ=
z?wGu`N!_+?j>ST5x8)p*M{<6{CV;MY(_BrB`-(KfY6a|?7F&C7g8<J$5rHFOSdHt#
zW(>U*1XlC<YhYVzex|0&uGR*)H63|N1KXSpu_Qn92>3l4f$~d<4v!??8n3~YEj={P
zvq!>9l3!gnBKSd&J@L|lk-8cXnv~VmysjEJ)^zlJjwt7`cvir%_Ih5xF{Ldmt=|UA
zrs;C9u^#yuR(q`&6l<@i1Qc@u!;-(`%3G!!ArM7k!qdLLpc508>j7TQN_g7$7pw-^
ze8G;>Q@*M4djn64ZGgH0%P9$u<aVEogoSr_<vaTzy1lQ$*OuT`4X+Jwt6r}Sa8oA2
z=ZbQGVcmdR4Rl|4tA<=S;YU*SfqX@)F9_HomXjG4_K{VmN1f>AWQK(duFtB*=f+K9
zoz}kT@9=Xr{WaX)y>nI9d@by+NAx}BBC@=~rE~79_B>}Y+r{R3=Bk5y)z=yw<f}Rm
zAIW`nowe{t?yFll6hEcsH@?f1{PjDn{N;5fE;ps`ABTAd@@kWdt#shaX$p@dJEqm%
z+ikEtfZeOgXH~jRb+yvW7f$@NLhQ+r=!yBhdF^9Gtoq?9*_K!Jxi>TYFJ~q!B>F!R
zRv`g5D+?dpi3i}S&$@lw7F!h-(sClhf)TZ<S9|9qw#xQH0JOs5?iaj@QM3bI#YfxD
z8Sa*$dXU^Vy?E_neXhdVCFA!h23ykmFQ_edgrHaP(Ka)TuM*bHDXz%%RXTW9SgD=e
zVU@6|dx|SQ$#zb0C9H>2T=7!nJh6&P1{6*mSH#>wm?^qRC?x)0#VeD{|3^Yjjw8B@
zwQ$0{k$0>3fXgvy6|Kv`*{;ZMRR$R_R`F8h@U@B$xOqNXMeMS|8E%nAuyDP(lC$+7
z%0YJN1|f^r>TNZv1tCkbS{R_KeD_;;Ig1Esg~RVEO?m*$QvKwF%~EaI4{)<oKN#37
z@^>9c4xm~Uuvt`wtc-qJ8V~2cqE^1Cc6SXxv)J7=aO|&Qe^&;su2QU(qhHY>8Q;Vz
zUiJ7dev*e~z80@FL#8Qqcu^f-mDhS^wwQaeX|M8H3ou$<TKAWDeT2@y;_vE_3LNYG
zOlO=x>-BMXTs(Yz^ria8dYAjfaqnH)@dtSL8k`4s_%2%a!q0Xz;n>T!xFx-3&lO2?
zvTB@Ju;7Ec5+((>yjcWK>rQhf5quDhE07wX(g_5QBu8UAdV+e&{r6l^-s1X%JM#nd
zgPi>9^;wpT{67h;(~a*WJ3+Zu#`P?8qkkHh)b5UP)FXS~lcJhWmR_*(W(+Jii`Q!l
zoGb<Fl?6Uogv;py%WStLt(*m4ABZRD`T9US!N#{5v~h|r=lm<_Heat{8pryPuz%xu
zU!(whQj{GwR8x*=DFI-a<2KZL(DJo=ddlVb+D@Mw8J!{UNOJiYsAnD;ogMH9ZV=>B
zcEB=$*w>~yOq2CusdG)ToEWg&dzAH>=u)_9S<VVrD4iAChwB;HV&W2mWBXt|;Z6i;
z0gvF<#n?uBE}3H6O6MLbwk>t4zec77d=RzU72y8nL5Xd!=XNW$kJedtHYKk<bN8Fr
zHq|L{7S0}6ZXL8M(2(*(8XNeZiQBQmhlISji!D?AR(uN*{uN5Xoi-Z?b>ohNFJ!bu
zY=e3fwAyPO1--hAI+DwA*tWN$<RS{?1^iDm4=zt*8^NiJ{D(ty3k5_b349Ptz9co3
z{tLpRF^vZ8XgQ6|W_>h9WXz7nh?+;#7?Dw&E9y|%z^6pNE%pE|xPKB_IT~B&q-Z)4
zY0aJOiETvBirBFY=+Svey+=@NF?OYuV=3NAxy}z~A1qw=hie5N9!G53=#T}%xd%&3
ztsZ^gQfQoNuw?zpE67)x8kezcq(`utTtoPXvhPOh2v*Ze>u`U3R~7m0$I@L@hyb)~
z)Wg*XXCEx&_dgO1FwylVp>;=-F^k!;1j=w$!6O;B&29m4C7fHZz-<ZT7JN$9s}H9Q
zEbwAt*&c@&6V4l0V8+A}$-FGC0YjMt3w*<HCcy$HF`P@VkX-Ia*okiHxmcf7PYSzG
zroaLL<_PrMnnS=`U-|mRvJ-5zC!370G1oS{p}+(g01JedaJs)jF8)Yz%Y!I;=4DHI
z{#drPSI@3BYwFBy^2eVe$jNP<g3jdHFSa@(^8M60549z(q=`XBz{1>|wjO$?FP5&O
zF5@Lg^j9Da$0|N(z$^|`?=35m;YJ4lujNZ5-k^^KS5~N7g=Tij_H(|4vAjZgQNz`M
z3ommllST?$mT(Q<0-5DX=w9Mbcr~%of@-}_if(^m^MTVB*Xk`)13!{{@u(OcuG3pK
z@E_)79?^ZH!&k(Y5Fg=13JoSgtsIPNaTG`}p*p?=5=?}zhm!>pVTU#QW`xP&1>Q@9
zS1kqI!)1F5!2{u{z2$}%ge&%zO&<6NlW&Pq2p8-v&_%;Fdkbl4Llt{VB2Z+#-UrED
z39i>$K(Zs@tp)AE#d-^ncqCef`v+;^wGMqILN+<<nF!nD&}Sl8?VICbxY}<?{!E0|
z{|3`s0l1JnKV1K}q}dQ5_Ibgy2v`3tm>)s$-?HcZTaN_O%=0P=zzNs$EwE_91$_&V
zJV8C*k}R5VHQxe_Ccc8c1tQHAF)QGl%lQ_VG!edyzE<36PrYP-U9gdmUjMYEJO4HJ
zkc^KCYWkjL_RIA?3Z`zTqHnpTa7<gxSj*u;y#<RprmmQu0%s;%skcIzi7Co$vSz|n
zdMm7%aGBovQV}DjZ0nk5hM2l#t{gpLE<G1Wo68R_Ne0$&{RnahI!RX;FJXpPh4BK1
z_-&Vl4uxE~-NQ9@EBW7JYT;Ine&GtcN0MqMt(>(XBdn73K3rqBz5tpjTt{-JO^dcd
zX8B2Ir5WIAyY(Hnr6=aOE=&Qg@K(YEs|s)BNOB<^NzQWfw<a^z+>yzQHBSMkHqEN6
zR3?Z^#j5WQ(x%p0eStJp#jSWK!bNe9BoWPJaVyl8Fkh=CwIyct#Di*6_rF!tmQZEf
z3b*A5r0bs1OwX!tTf+3L3b!TFZ}A|?pRicfW>l}oxf#|g-C!duttUk}s$8ix1Ex>2
z@f(4TE}2^k@aTfMN0RX9in*0o?GTZxUfxU$E#?YuCMcF$q0PkDIxkjuGcmSR1CV1|
zbpoXMUKPh*kaF%x(S1Frv0L#do;HId4E{)@DV-c)cGpwMVjn}t;(F_(glq8D!V%CV
zcq{c*Vg#y5Srevn)pWeZ@Q#3QHpa9b@Y2P0D<0h^#<VH`6B1Z0{r;^Hf|i4`bcI<H
z!-cpi)S4K>igWQEi4=DRG_1GtD_yJn`3b<wq4V~UWY@aCG;fQ&2C7WBCT}f*!_n1W
zu+QapYw~AecsqeV6GKPm%EdyArek{L_8~^IF3?Z)c<a5v2y?_L$u52pTDkLmVIF1O
zmZpdko=Id!l5<`8X*lsEi|j#^!>j5<BB)tpm3yCXL`&svC`2NAt|&)WteeB5BdF@V
zU<%X7D!iKzi>!)v6Q+?JQU1s}1=I@8awU?I`y$K8uUv^eVQyLFUM<WmJCfUDSM04f
zc}ti_R$<jd^2i=U_bn8WtirPilgTPXn?OsR98Dvus)ZKjkyQ$&g?VI^s%p{YOt0K&
zhInMPw%ZWwz|D!Ad-CXnNo4hA+6i;WDgk6+4%v~U_sz9=D>uAhrdZ_~ILs8QcXYN1
zD&X7a*R%9~$7P9CI5%NdSWV7Nm=spw+=Mw{RW<v<q_CQ)@WZ6A%H4SMK`W=!MnVOu
zT~_x<ax69!YTTBz=GiAMNvuMw36sQXB}GP<6jmYAMAyN(Ug|=a5>_EMgtHA+2oT|H
zgSGD4Qm24dQ^G1q@sET}wt}x_gjJQ53{%2t)}9QfAFR};3~|IN6p%1StU?nxlI$By
zk}yTAUam<vL1Ar*;}ZBo%L&uQo(c^o%oD4m(+~5+D(UpYJh3CWoiR`BsjzYap4e%R
z+fwHMMzh3@<W9F)VzrU}CYtSX_&Z<tToQPqd6h%p`Pc8<SFSnIszTri=OwHVcmfJq
zZT<eu5`-cZs@Pi_$#25^vkHMHOh2on<_qU7tfcP?=Pj(6!T-4;mNFG|!zl+V6tHky
zWo`4e^bOFmIlQ~V&<Uj+tnhK78OoE86Xusy2szPwZ&qRCMDr;CLQXhYVI?7dC|O};
zC`SM{uacranm&-@@g~sLZE19%p^_9<cs3y()e(VW&8U4}wJ^u5@-~JG?pEH|xb=2x
zCl6aRxwwxgXU&V8Oq^lfStVO%xU_D~1@(jr>sAteM$2aaaZUHul|>n<t6N#M@s-uB
zmsb<6saq+!9W8YNW~QJWNlxnPUbJ+Sgc)R&{V!Yrx032UQ~>t~#%*c_I6LN6_8_|R
zShuHu^P_oYwR3)~Ud~Ca2{J1@DY<Ws@);h%eRG`CutK&8=QOM!N2vDg?=9{5SZPjp
z3MDM8AXqqIVa@9B0fnq~YP>`hF{NfU-*9rmO2*%)(=!K@)hRt7S)IClt0Wf=>fhEL
z_iriT*y&=p6^IXKDy&`SPS?V%ka5Bsvzla_a3S0Z87JyMFTT|3BA69+PB?jC?SQ01
zkuN(ZTokur8HGt`PsM&ZBK0LdpcMrGid}XD+4=6LW*yVG1haY>H=(k(6~awaFJjEg
zpX9dkwCB>cb>PR2s!OR#%KR|DtY*smFukmjGCwZ6tPT*a`j)Da>N_0BUJ3Y!YBTy8
z^HIHGISxe4f7L;+$_ZZcd=b_5F-MRvk*vaiiDF}z5SZtP^1Zu3GGX3W<xmwaWm}1?
ziQ)x2IHP4D+Z-aNw6bZPzL{HAIlM*DVub<|E@68lm+l-cV_RXxL|N86{{)xU0d$#I
zR>_qgHx<)^BqQRzev=pzC9DSMa+%u-S0*^!Jt?aBEvW*zT;{ft{XSIX_6RZ@UXJtU
zh;m4*>5)%hO%o0lu5Vij84H)Ut%@s);zSSxpM|R1)+EnF@sh@&5m3`A9*_9y+E&~m
z;lj2RMoqY`ZN1)=a8cWe|0Tptd#)(o79Y;%ds`#_=J%01yy83xGtcVvFFjYHY#1P-
ztJ_xmR6%ju3gIS-P4r8;2{}kokbU(z8`e#@ifx5;6UAq3ST~V1Y@aK*?}4p!I5$yr
z)P{BwW};PSH{tTNbrL%grC2xUS_(q~TTMN?$sO(pe2%8vNhH&(CdVd<&&P0V!nCpq
z$0o|F-hz=LmOWRL@929!Fm4(WHW2tVVV+r?oCLpAB~#amE?`>;?v2-b2ob?Q$!#U~
zGR#D)8BiQqNb^B*2V-_x#kGATEaeFVnp$=w_l<kQ#u4lo6UnOBF|T4Ys@O4?T2{r3
zaedl4VWY;YwN6I;c(v9m&i*jBtddYaUZ1RI{=0V3$*J&Grai43j2HR@5MM2HqSeFH
zv^oLA*XL|v-ou2oN>qHjUh3k;m~M6?Y1X{D+^WHm@9q9tp@&}1WXKP5&Z;uxhe&5N
zOI3v_XO(JJN0J`^Lf>Z9An5B-)s<_iFb}OJhvxMeTof8rr>$bpywyj|0A^o&Y2wtp
zUf*zPOjD~O(3q1}RbcFjnBsn0`OHq|eY(Ckh+(qXX=hJe0Pl#hukZIrx~da*4L}#V
z*=gUd%G>@_QD$6*wo=F~US&_KaA@YX6Acc{H0SL1pn028oWMKbn^o?8r_0b*ZieU9
zSv!c?pWCPH<kd`b(kdzRr#WerTq4t@YHMa2IRd$0Nl0=;>^9^qnOi6BST{?J9=hng
zH;KG;f3E1ux1{7YdTOHV6ydDq4gcJBwMU}tPm&!=ke%DxMkK}_i8Pao$5|EYCF9KP
zqCXWj&fMNLNW?$4@90RqKb;TfNb)CPt9WYW=sE%(Lmsaq(PIid9<;Kz#`{I)>!}Qi
z^)f-G^CwoSLeA}tgvya~ck3<u%-?|=a?W&~#hQ$hxxJ69%FnEAge+;3EZt|SGLzce
zzT6|(+T1?auf`B<DL}HByV^>Fh%-r=Sd)%(n(AGrGu{K><IJs7`69E#+;*PB$2pSx
z$hd#AWY*v}w9}0oHAezzp<c4m+&;LI=znf+6KgQLYzk{KwZ4N}^YR|&_NI`j{jNj<
zOlX}>saWCZ9ErZg>2f+3VohewbmGGbGv`P&2??!p;VjFf{3N4#kTkwi^^w6>q$ja;
zI(uTJ{O*zHqHg5}q&Km3F3#;R=B86AR=7S>sTAwN-8z?-c+!35@?{!RHkWVCnAYk1
zi4|tfGnWtD&=02*B33Ah)A<l96viW=hdU3W_d(gkeBDl4`MwGhp8s6wot<T5`J8$^
zQ<V9@e1mr1`?-97Mmo{CbP$KjGo51bsgQZ*&9PV^@=PaLtjXk=%eQIJcIL7ZZiA!K
zDHSX0e>$yVWs8_Mt70X){&ZHwBgxUYfIz*;T&D}+R;qJPXm1r_?lkSKLf$<RUiPHz
zJXgdTN#4$MvD_obx03bEZaiHJx9)jcS^coG>Ca_EC;9%Q>}@6U{`_(af;MxhXje@<
zIs&}{0AhIU0&CML$|~45oujO7E+VJ1lvN%g&A_J8lpVo+W1Xk0lBRfuV@xWUjHhet
z)+F;xrz)#ds-G&KTQMW1%I7{;lq2whCtdS&wzBrVx0Ri5FOcYbW$lHWJC(7lkwbdA
zqVADocZ1gL>iksX>llvBZdh^CY0Dbip6Rq@4a;vTZ&|yh;dJ7%r@`%+H+5OVj-1Y2
z)<}0VoxiM+cYC@rZ+o*e<8(^1M)<{aPP3K<^iR_Ltw!I3*zKC(GrFkE4F=G3Ub6-Z
zXx_wT4Z6>a=FTNxI+NKET+iBcF0)1|^yy?~4NlN><=sYxn|afjwf8*oPaea;Sg`LK
zx&NornYEkKeY)yyBM<y^KC`EhE^s=dS%d#Gozkpv@SDzQ)_w=W>6~UQ4~}Pa0_Mi)
zaw@G^gYYw5F1ID&XF7{ngYYxM;USHns_8^#Ed#HnGnqAFv!*hcH4eyAsmz`$x<ewF
zS>v2Noz1Mh`L7xt;OJ_(?cD<V^?ilyYyJ5e@UP{x*}k=G8+4yXK%Jtp|6+B6?jx*j
zm+kW*b%X7bNc|uY{G+;*KQP^j&~;je(ADd<Ky&<Hx)njAmt9F{9Dlwv0djRt*f`ud
zfnj%d07JoYgQYW_>9`faqpRGuOy&RKaw|edaJiLkyw@}cAUmxz;El_zBshBM7C~Rr
zGl!v^Rat~<Rab_s%xp4koDZF(xRI=eT(#Hxd4N!T;L_uW)D0nF@k|Q~<s)xJSm=eC
zWn-RcGWn6@#OmL3Qk~ZnHqKNA<3@3snJJ8OaO*au6_8smtz6b#k412{-K(w5Z@XLD
zh|Ib!!n5_~K?@knuGKeTlWtWZoU{89BR<U{Z}l}IvqtM{K;}@<Dln&Tk0Z#9D5O~+
zCog)d0=dvZwN;^<F2Y((m<#I`icLMYGKA^pR)KVS$XiDFPqW64AUikQUCwl3jUPdF
z&cWHO3g$>^TodGmyDE$u?rbv%OEYAeY1(+Jf<9egwF>mf|J}%zFrkgND%|Tj@w7i_
zZ}br*y;1ju^XsU4!})b?_ns@t6fE+nw0niO+H&Ve;9>4U;~r4ybDCH=U%H%@teh`f
zPJ@;6CCh0rbC%f(4Q9@>Ojl@7a~4$=Ta8SV!w5+&&}5uBGfv2d-~Ob=k>W2ijuaE1
z>>7(rssFRa;+ZGnlba1R>g269{H1+c>^;zRmWc~3udg$s4*lJ9#k+i7i!U=38aL<5
zY=y?{`f85+YkyMfpzBX+om53;9dGi=`QJLN4C-y(<WJ83<}Dsxz*5b{Mvj|hwnKx0
zv)Z@CUlz_XbD_b)S!OOYSU9VtPN&CV5;LdIb46@eB>uTMbY6XkJUn`+a!utwE6<eE
zM;=km*X!|-OR?!D^hm~SOK<0uxO;fxY`0uvvE{G2L~Lj`sZD<MOK8I$K&{RtCc@M1
zo3>0uXiCUmzdY<D+i-Ek#yh>tMQD2QkBA*87sqme#Rh+7iLcP$&n)v58uXb}LmZ3-
zhh~|w&{{r2nu*XCJE8r_Rime7mXHNG;j}YB%Jd_*v*PHnTUl{59P&<8XOcXk?7#N%
zMtTnO6K;0$kx6mxC;Iy@naVq5f3A!-0&Y%<UVZG0@rw9SVCP&Bze>-`$SdN7gr9Rn
zx0%pbUSE<m7&=#!gMgy*T#-6(!0`&CK2LpDBwh73^Uo{%H66;?NFR4)D7t8Q1sXx6
zyYKQ-o4Wkj0FZlrGQV4}d#;G5x9qatE%-fGq?ZeV&z12i!0@>u-UTQ=SH#<p93Ryc
zco4Phyxv4uK3AenbjHl9*hltKp6?@|mwt!(P$%^gO_Uq$A?^G`T`5=_w4Ic_`q<2g
zGvY(sxuSe{WJA*tdP9Ac)*$a(kvb5(p|9@7kBE^p>nA|y%2M0X)HZ8ejILSV(&$7?
zZ+*L4)nDA|7T4SDGH#BbxCg2h@XFKO2G#VgY#`zN(tUQL68#lbeTeDR6?YpX9RA5f
z7C$oPS6=Uy-|~7NMN{|c(YQ{pNYB2`)9s6|29syII9P*qzkO@fVCFv?O;i-v%etw_
zwslW^B&RpqH&jP5`4(ryk!9Mp7wMo(8(*M8+qSoh?6upsSZ!cXZr@_H%kJ5}!)ma5
zwu^%`xI90}Z4E}_Bq}YrJgWPUf}DMa&^K}eUlA|wnEc*(SMear4Q1=Fb)!peo3%^;
z$`!FK5~gxR@<<WPa%H^GM7&&)`ViUm<+B;2ohu3^K6vLGX5ZlLT#-5v40_olA3R5{
z8q(VQWZI13<y?s#y>j(%`*GS^U(#t{Y`SgOA6wn_<~+8#t<8CC^*Vg&Ar<zO-4D$-
z8;oJTfQqB`+Z0qPZ2!43h9<I8o5IRv%R2+Zu7qu13My~d_;F!Op`}Cj+Z0+Z8w${Q
zu81j^iI!`~v)o8ier4)`@NoGQN5ox<@;8`ZWJdNsi0G&{@hOlbxW7#y<nl&7g^<?)
z^C05c(k6&>ynmZQNC*5M5${3sk2eL8OQ|~A1R{NB(xwp7{u)9guS5r@2}C;f|40~d
zbsvUCEKc(g(bMwH`%qWyznOsN=d76m&*klY3OjuPazy-u-tVWdGaWYbAm`_;A@|J{
zsf%QUxiV>w{1IO37H;a=q)}wyO4!Awku+U9Q#cxig9(m0hd_h(b45~?Q1GOTx!t^m
zF38ew&;G5>G{M%-f0J(BCuQ^#U+@vp%sv?!LcnVOO}yMre_KPm&^`<naCheRicap%
zAHG6M?#>a&DG7OJI?+zUlRlMbr$N;@L<8QwOV#<<3N1(%Ft;78kaear@3d&iUO-DT
z<pC|tj0e5;Ts9=1p>Z2Ax6k8Qcx5^bPlKv6m1C#LNdsBoitvXzT~15h%||k5+`vp{
z%xT=xJoBc^Y3AHicV#e*UVC`FK3+m2m%`kx&vHaLwLX?#zuDYAl*bgkf!2ajAjK1>
zmI2<Rn_|U~ZhUSJyr#R*N?yYU^`_7GBt<Q->3leiE5VO-&?s;;*Zv-~@$u>?mDi8+
zLu(e^{J@$U%&DX}&lRPc*Zwn+XqG*&zg0h%PxYeI7|oZi4?i@=DSRZTrtsaLTM}qD
z-z5pOntKDnlZ&rA^x(n>fbEt4s*d6{UEe_o-}_V=owlm4Hvly8W!BU)MP*P=xmuea
z5Q{DI;V{`{=JHx51I?dXlbfVwuFv@@ip^3*x#lYp>2Cb;2JWT8WkZ+1jS`Q4?or6q
zGe1aP!#5zgf|D`xA+5SKom{8U^N(5H7~RJ#Z(I|7wDGp42<tYdl>EjyN!$9E<a!V>
zQ09%d1%jD4-tN!-(Z(A$V`7ar?#@2uc;kXCzPzT5Tey!p-jY!B5yu-$8xzMHOdB)D
zpDUX1!u62_D_pw&vc?;W?qi9!wZ&NXp_!~X(83!mqbU9vv)Jp$6K~Xmg(v<X8j!$w
zEIGSAqWF<4h~Zb$&d*CrAtQ!);|&@P%yA?gQaEoN8{<bDZxqG*h~o_&4#e?a8&0c<
z;|(T`iQ`RKb&AXGwoI#I-gtwE^U=l|2y!IS+)N^GTPZ)xB5$BnD1m89LR}P}rQzH}
zdHu*v=U;oNA>Mq{@&@t7)bh47w8Y2lEtad!+fUnKxo#^L%heW^66Tm--bk2ZdU@NF
zYY$~RZPbZA0%^~%t#qc{EP<gMrl*-bTgvj(FoNPu1sVO}^rVd=bvQq1!;boB<t<O<
z&mUfSQ=Xg4E6)d*Tf)&loUgP&u!&4j@*o<2DCG_EY%<0hUW&^Y=b@R<>a|(5x28&z
z@eWfaUfD&RTI!($rJejWuQ;3?B22vIaQ0Wh_%8LBex2xk3duAan|&mT=*~~v;ASoQ
z{*rmh;n|)1p`j8U9g0hIE%}~lNPmm5H$5~%q_ylj6!9;hyF()XLb^MiviPce^jGos
zu2lJE{C&0R<~Z;{TT$Rr?RflZ-QA(!(oHgru65t>N`3*^J;^UmikQrCd-J+?1YI~p
zyF-5oDtmOeFQ<+3p}*5{-E|<S`B<qT4x?@N4s29V_j5%Vv%9TZ0m2*IiVoH)?ysVQ
zw^R!l9ie?h<4=5cr^M$MjC~{->Z*fQhYv$=^@Aw87k=gUpD^mK>^CjkIbcoKlU;<E
zaOvQ#>^HZvM}HMCJU<<D%_VNx90|vM5Z$139j7`wtfR3z@jcN*AM0Fn#4Y~Oi*hPD
zI=h$hMP{ECV;R-~#x)Vex-!;$7n5BXYnqs1o%Gz{!XTX#-r>3+y(qM}-_}W~=zGat
zNO0l1$s@_Wi8^*9*|%o3R0sItwR=)yzHsdhH73KgJ9fm0vX*A>t0_T4$N2c-xBE3u
zzUb|)Y&E{|?8;U{T7z2(8Mtbqh95}|i33(ob1Qu5*|EsNg+qE8ZO;|4D-aa;MQ!);
zr5DzylwNrHF_}jC#pTlB%q)Asdva!e0vbv_tXE@Yi=HYy#@?O-B?;cNGDWa@^rZ-%
z{zT@nUEiApitXj8R*K+d&7=r+Y2l(2!D?mFHG9ZAjGC~Ayu+xuk{o<}ZwsxkWg-JO
zI#ii(07p-zOl%DG4pAl?zR@c|QeOba5!L(>L#awL>;+tvW_Z%dj>}N*^-qdnG}la1
zj8>%>9v+HP40}aaka7=0cC8FhmtH;DHsO$u4%;Ra@zEjMgknCPE4pu{gFd=a)i~&*
zXR4a5`>qb(CLHn6vnt4w>5EaW%)(y!Rhfki=9M(UM(&z@zo~}x9N=?T4Z?|qJ%fWD
z1Ksy>Ikr<Ob?%>I8@Qp)gu_BQVfNv$kY0gPSIzF^xN%fSSB@K^LV8sK;^HBafY`f3
z<=`K_Z|U{RKnyfOgb81fbcirl!l<tW{M<Ce{7xJRmw~$ip9|owV5e_FI_#Oa*;8|}
z^53NeG+l;mCA)E;NUzF4EUlXaqTG}m!Qw0IOcgj)oJen=srjczQZq}jkiUINiP6-Q
zl-TGGKP7y%(M6D%4l3x4iljFF*zj+S*4xh4;#OqMd1{%jfBFp)yJpSm9#g$$`qu~K
zj)Y+*MP}O26Gdje^0;*IWJtu<MUt61u62=QrVPF0$V|T*nStikLe<Yk3Ys<ix`;^Q
zOnkkm=;-!z5)ZtF47*0U{oz+6>yoYEH>9a7so#*MvZM|P?qbn6hh7(pW*7ya%#82X
zg)+lk;FF?DIvFzV#F=p#y(7u~T-&ZuS$h~68o+q#sPgNo?&!4YtUGGcuBq;*p#jVG
zC&>ZAp&7R1;Lr>kbK=m9VJ#|DnqY7S2><02IOS{5U)Jzh4ED<!-o?9WkGkZ<5pBK(
zbamAp?X+(9Y~gj)9o2!YmjvoHY~ghk9`!cgRe96~UeA`4Qk`bBhh`4XJ3e`}js&%o
zsu|w#lPYrr0%}fwYuLWygt&&ccutXPc#H4Usu`GfPwzeJs?u}n&<t<iomw=*yEpmC
zPT5pFRkdiws}W==n(=x7l%g4|@eW6HD4^g-vilAwIHK(TYu%S4+P5{s5$#)wRhiTo
zx_TzPxuX0CMZCK)A^9}794mvS%v;}9tTNtxSvN&Yz36+Mb$ta`R9p8xsdS5kz#uI>
z0|Q72NOveGCC$(bLn9&G-Q5Dx4H6<qcXvx8(#?O+>;3Nc-QWM5=bSlv?X~yXd#$z4
zJkR^iIYZ`nLF+6t7nAXPFB|$;H-l=p?t@m}fu6(9xO7;8_GgAxzv+&RrZD@4;8UNk
zQH&BO4;*OUDkq0I)h|x-Su)0?k_tQ(JQA{QJXK?eU3S<j5YlN#cWsT%n)R?oGL)Ws
z#yXzaWf32@?JuZuxEOV+0yCKxcV*HUTMN9FHr2M*8OsK03)O@cZjET4;2WjG6yY}&
zrqb<UE7`Y4rP|O}!BVPjri78-e6tz?xY&rssYeXyR#I3KfOP4@7l}dXF490Y<Z<yR
zriQ!cQRYeeS>$Cxhs<Q185<o2q%fVkGzuQelYokiw~KH1U6V7XDw|JZr68h9#KJ$}
z?~t1_?~g`w@zss%cW-K=p0*e!yvnfJ0>ht{E1S+^a456k_m@<x6F{2a1zhb;GCvQF
zwZ<pnC$*`ybAVN>?W?OB-xyEKQ}O*otN6Oy`Q5!tTz*#rXLhbV%(i^-vzV((64h)~
zJ5I52a_ki6+ZyRWir4+_`LC>X9@r9GxmkPnqbl_Kg-ub9rGQ;Zm20FGZgK#UtH_IP
zq+x91&tdVFA66pg){pbB9jIdD-_zMz@IxH@H!4!O8pZ6URnG;a%ga-_t^&vwS9p@^
zdupSNsk-+Tj?L0iHcsV}=1uNyjNH;vOVHCz^j924c4_L(joq0Oy(}2|_oXeS)1?Io
z4{LyiRA01l1|n{r4A;TQUwms1Fwc|tJ-4Y;x6Rp$vMX9Rv@5zx(@p7$J}B+)waHi6
zD6xs&+>e`SauDovqW~C$E1?|6;5O=h>!qX;{pvJL+rEFGeaa!qFuyLt<%p1bq<5Bh
z-M;5DB?(>h9c1(0ujuxl?}k>U;x-PtEl}=|(;jU3Or<Kd-%KC!XxQ>oIWXAYy%ySq
z|B_0r{+p|3?12A#G)1Mb7$vmNL1>q9&didbeLupW=17l9IxOfF#riFFh4}uJtDN4m
zFWIgn)0vYN8(;T_%;5@-GW5I4jYkUFzBkinh-EnJ#|Rq2M?y1}TjW~ER{8DwWkxkX
zea9)zS<-UX3WHOVUeyZy@b82q_N=EIyJDHs0|E0);pMUTjf+wr_d=!y@z(;#?ozTj
z_ZO{5jtZ{JW9J$kDkV9%o?_y`bhh1{Ij=yy%N<Y9$%*F@`guR7-<@<Jk(J^a_<Xgj
zjB^2&oNgr2eB7T-H)r!~9psjTEjZA}(bV58dQUiiWJYu7;+oartK*tY)OfCybi=ov
zF|vC@u@NO#DQ~qM0l9x|QSzMt^uV;HqU;!t%<5~03;cTwUYu5zj4}YJ&A}eJ@*oS5
z;-7A`X}-wOc6#&9H2Hi?kIag16ONhOUY$#LZruvN%1CNA72g|)c`v8VKnK56O{cr!
z6!za<+bLO|ZluXp^xu-Gq=r1w)Y@!rr#-W$5NVjbUT=1(A>oWKy|SASiJXQ`6t_!8
zr#ufyyt!C;*SEV))JZ`+a64zqVPEsvHvUy*KXiL7b2^XjgmzqjNuO<_bbT)sszV;8
zn!hv&=C5Z+gz)z?9x2Y|<hi$eruaH<yR)}mOj^>XlTx3ScH3sztkRiVN3lM?{KcZv
z`7FoF(%;$fmD+4i$4KIuWuC3SWsSVXHm`gwP0Q6y?rD5ju9)AnK8O8W^=!&Y+HS&o
zgN7@iXVukh-5xdB)%+oG?+No@Q!K8|b{&LG{g;AKDHYq~N!S>ybP{{XG+Eir;cKTo
z3xqOPd#@mLeMvlX)cgw{$?4IAdLM16h7M7<#B2828HF^6<l3W849JUpTUt}BqmVNs
zQv1>Y2MrRCU7G!wGB&{IxypBbPb-DA46O$<o{WXFr}#JFCv-`rs;6U!Z+jYPAyZ6S
zKAT#(aTi6^{Jd!WQ6sqYnfW5A<#N`i_sk(5CS|CJew<<Qv2-sKQ{W(|q_1KkjD)b-
zR}AHNgVWCltTj<zUD4GVlHgLj#c({tPnfe&AG@{@e{q3_Mfg2v>H@5>(GSDiF??yg
zj~D(@5O3jvM9yO9G<EYu#{w`%@*ABXPYOc|I6!BHE$z7uf*kRI6Y9I?>o}X7g9}gW
z!fCH)bSIpAb?ZaJc<$l|!aU#P?uf)75Wi+YNQNKL;sQDdERG8dbjjAa`pc75hjBD1
zX^(N>KX0`kjWK^n@~Pb%%Tn6VY5f6jR6>=uvOQk*+3vg`=hDpnF|N|={0;J0`zd9-
zh+T1}7N@tiNn`u=JIw}q{6Z5lVbfHw<AXf`x+FHCch;7#)G2&``||?LFPpWC<HRzz
zw{sagX(lH<u__%ej;dKh)<G#hfr&ldAL;wHeTgZ9Y8`0bfr_QZwB>Tjl@^A6VqoQS
zV`Ak`wu4h-j~)yJKdATJs3J)4<Hlq`#mz=zHTn=9wdUVs=!JU@yrP#T_rdW<5Rj=a
z)`FfNv%PGYymNUeYAaaoxq_90rshkXji$z5+-O3PV%+}-(JWg3pvoE0Hfmh`h(DK!
z%W8>yo(=i=LHd3!^P%!vG6cqNdkuv|M^#OQuXvKNRr;NWrAH;8HZ^v6*cv>8;%=~$
zC#sQ!0}(;o_I@#^r;HaruQFzHDod#X^Iwr_!QZj^OzcvsqO>&4Sz6e&X`jD&;-ul|
z{O#n<o3G>BYV0)VyozvW&2+9t&8{yb)C?!Fy!g45?5th4cx@`FaYVeEzuYMz>wEs9
zUd9vv$Y{oU^O$xHG!UY<xujzBa0n6Ggx{-IifrJ{Y|qSvrdDrrzNM{mEn?y_!$=zw
zhFRsWKf6`1X%sB)^^}jRBg>;D>s+d!TLbhHhP+!6D3C~G6rINiEu?i;mnKuF34-`=
zrKG%G#nBDz4tWT)g;sojAUA_hwCX~l%$)R%=wZa9Zh@lqNJLLNt?@St|4w!N5$^>#
z{KT<n2E$21=4sI+?da%lid|POxp*4GM4@~n!#R1#)7)}Os7@&q3dRDTAG&Vy1I4E>
z9ZV924duT{k&zjS?&Ippq7_L8I(>r4Gf$S^Qek#=65lE-Wchl)2;LbM7m=ybej>0}
z3Virxo=mh*o?d>3+HgiK=o4<vOjR8L^?2TcxPy^Hl-vF=myrlOE1X8zq;oNMOKQ48
zCZH-d;#RfIcX@-d3^MMg>3Db}=u*UZBjVfKrrQ>DrbA=Xb!1%j&-eWbVncsQO95+x
z`w_7UPxxsHDB&+hAa%x$G|QFD>uP5O*N^MGy#gI_#82FYAho4V^n`ry<3}aHD4NI)
ziSSA&mLyf(md`d`;q=|+#`p#j*)Q~b4w=XcVX`0jq)duB)nMu_9kJreX9lFqtW?Nc
zD%=)M8pRiF8o}3VhpE1i63DI=C)Gv6{r)_|O(E=3L)tmjLa>)H!&I*(&xq(<>L(M@
z%s55(wU3K1U(ZJY!?7}4YC(E)6#?pXu%?Ot>J+>ATZyjt?%}77wCEtdBo8m2M2qPo
zqIacS>S;<J{m`c{GT#>Xp}R07Fz>iaNa+s5u_#iHGdE!dy)iU*|3-^1O%deDTVT&`
zAY-(c@^Ec(&9uo6T^c-1u!_!IP+`x1<$TK<8~)|+=&*D5!;=z6j^Nk+;%U|KgGa0F
zgCi;#rFX0c)(WciY{Izf!IfZjHnE?iG>UV9*T(|yZ_djESk{g6JGUkqN1KAT_Sbti
zt`-#*6&KU!-Jd~b-AG~f&e~4Lb#cOw+pWfn(hsY{>pvFL86J0F@Tz-j3|4*(!$NyH
zAB#09K`rL@!~OdB>}E?*5B61q+WDCyOO2znCKg-Tx?1BnX}+nDozL)FpmE<OyRaLF
z1dXEUS|C>9tQ#?vHIv=Wz#-`nbnG097sbX$dBCjiaa^mvYgQw>q9Ul$q6o0_%!YZ;
z>;ku=f^qUlK=$~Hh6LHJJxe^|{Pp0mgHjBF4XsENkWl651^SO9^wR~EVRCi^aLY#Z
zDV{u}v2Py~Bq#Jb@#SL5E0}@8nb!)rJ@4Kvm!I^u*uzn+0BVa!nmz2AP0}+?x#mxD
zn8EH43RR@|3aPEn1Z~(d8f8qgfhLdiIuEJI%aPx@uaE?&Dp3p#h=+PfiSB#4H*SZW
zyIVBanAPGw^KSX<5VLHp{2++Qp5U!>ZlsTWV{RwYG7{FwGx9zR4II59-g@ksZQCkp
zEbUD-Oqcgc=;M$DXXg6V=UoSQ$u_TTZ5f}0g>og>8<Mx-t(bGjijsW+#|-l%5U{o4
zO(<bo5Px?HA64dHtG8r6SYc1~!1%si_W(Q=0%<GW;cipj1aKF;JKs5x(nntMS;12g
z5+ZLcjdyQKL#nO+mUv(Q>fbmREIqmKt4_0tnDS9+(<t*vF!O#BVUH%JBI`}(*gvnN
zU-ZSa@w=5&%*2H?Lkup&Qxmd5fjxKdt+W%-?(D(qHq>P;m1P9Gf@rJ9eu6^}D&>dq
zEyM*;z3(TAFFyW)8UMW$ay7-bf!Xg59-4~3HY6Mvq4jU0UTprtg6M(fx_4Nj?)<q3
zcY6f+yV%CakG3*<eX_D3%ucRWR}B8aR{2H5J?{=it2Ml=cJ+rAM0f6;VcEl)8BZ|N
zjuh`CqrWRXtTm{n!S;o139EYdBCnLo=@pYb={*~de4Oa`v0y@DPf843Fe=p5l!hWA
z#<lZ%5v^dAR=M4D>7)di44I8uhCg@&QMw+1rQV!Y8&`@fvUaF^HqtL@g+no%s|S&9
z=S^MF+FV#yp!RXvtOQw)H1Ecw2tT}uc?6%9J0^wg85;SBU}Y$mPQ5itcTxQ5=(RD7
zbbIxf-S<=T5{8kLp&blrq-S}5Wvy?9!42R5+<yW90B#T`i06+S^p{*f;J%7o+zBSB
z3e$rb0e%baWqKU&0)Smi1i%SkH_(Hhg@o>vf1lYUtgT@G&^Bh}VC4XS;oYkIr3Bae
zYY@P{jRDxzoNbH%>`HnjMgTeh=P%<*dQc;HUz~s1vdbG8Li9wfodB9}5eI;qj}O2J
z<lq2k|56u&8;0xK0l5BdAPKd$xB16lejE8Ey>9~F*j3@Cp?X$!HuuI1od1ZW0Whe&
z(VvnST<fKg1H`~cMN;%$_}5%jjO?uKp$0~FfP25GVEkulJn-_pfA2jdXJlmpgTE8^
z?_o(mEMP`Z0K0?*+_Nu@46F@*S^7(n6Tk!H1K;=cSIC@F_B34Gh{l_QP24y7cKdb>
zj4R0xr)bHe=x`~~(a}-VUgNF53L%JiXW-o)z!?87BA>`73hxCnlJZycSWgm`P<(1c
zvuZ#9^?2M8tNPnQPkr)87i9}Mh0A1YjhU<RyM@6UxBb2}(8hcB!5=?T=wk4)B8^Z2
zJT5;$jHrs|FZo47aM2?36w-Mn6)6LIX=t;ksMTWP1O?0oGMqu^KlM|0ozKgCbH#gF
z@#1tl__{%qNv~H9=IjZsJi;yOL1kacwckif<#?T}kyd_ZOQ>$U#h7@g*K}S!J(`aX
zo%25l)nHHLwiF@NWE%W(S*vjtFL<jo&9PppvHM6IEnS3G<(ZiVQ>mEQBLc#z${zvO
z6xBa-31~<qXJ;M~WEVFT3xe9@xR3*l^_gf=*YReZmB$zdtXo{P6lh{%hU`XEAgCpJ
z`wW`266m0TG%Usb5UFGOIH_{&$GMN}8Ie>((TY~{%hv#ksH-25pP;mIe()^u;q}c|
zGn))htl?}N<>fCCVJDefVyyF!0hK$paOafm#bxikF<y8PWt+Jdcgo_Z^Sv%mmB>3)
z3ClgJj0Zb!hc-2Y-ggZjnEr`ghIUW(a;P~%mSL!I&yk;gROJ#y8-=+bJAkNw3%{b@
z!a6F^kp8<T3+*##`_?E!1Lcy}z|qi5Vw0wi=}&wjQaa6s!AhvRZ%$Oj62eO8(6ccg
z43C#xJ7@*uhPquX)R3mn6OA;iBacN|3HNqZdEAzymDahk?X<*bD^}1ev)+DsBK}jy
zlE-zOnn&Wwx9IUqs3JT0^5n~AQzh2G^f-=w-KZ`p{Lp+IT-n`u20Df`W0UpoSlgrV
z-;ar+TzX{&ET?)tQ<D0XE>a8O#Z&SMRW8lHv8J?MsCT@}v*b@pKmWeE&VV7DdujrR
zuz}4}HDjQJVf7Uj+)n3dANBS;W;mPPIJ>L)*)2$%&iygFyemK40yFPrXS-<3;95vR
zN+tfc;O`QWU6pB(5ihaivyw{V5uqs^8MUqYhqvTfq6xh<r?m^B?n(xGZ`31~DSdyk
z6WyX(9*}mm<kozWwt%~tML+ob^Hh(iFFtX<z6Q%#Ki$z9gMN>}#${Y|(B?X4uR;8k
zL-c$(eIdK&x7cXe2a6JSudssTOk<B7HqN1!u+u84Cas^*s+h#p^7StTv-iV^)pvGw
zHbzgxOayt1-TMO~86FyIU!H_J#&ra?_?%pG9tuCQRHONl;fUgsK(wOBM4K~1U`Q2#
zQb=yON~VR{MML+6+ILTqf41~!lK49=-^>Qm<LICV3`qhE5tdIgKZHGEAM#(wHsIgc
zesi&zH%yVg6Sz(oYpOoZXq|feRQd}V-x@vjmCM--<M>9<!*m{S&*sbS%tWoa87r-U
zoF=+a8xxayc`=#pr+Fe#E}HdK#=R58=d%qb{Dnd0i|-jqlw&u7U)vI>GWUOT#Ouci
zgep@%Lk;p{%L(2bB_6B|>b78Fre|xQ=T#|}E|k_vDlqq{OUVnady+RV@+o{Yb1P|n
z%-+&ROdUJxNaj3ORoH@;!a+XPYf7sxmpsmgtLmZV6cJ2TE>2rxopM#OLlY~ruTKE<
z!;dCgo1|uE%O%lcn7J1i$qZZuzd@DEndsGnzmA44jB{pw2BlNYz7VWh1Y@zYu&Lwz
z@N#pmgx_ABeLEJ*_&_H~@@&c=g|mbxN-mmC_~?jBvyf~k>cr4Bh-N-<|1jBG8mB)J
z_=cV;Ykj-^lsZfR{s#i1pHopFN*JOMsLo0_&qQX?>|-3_4MOZfm`#ZzTsH+rXuC`<
z+$sd56D=AQn-r6C6e}J-$JB;DS<f14Y#Po>W&0>O*b*}ZQ|pysb%Tm7q!g;gSER-M
zG5J{j^sPy8kwR(Z58HiP?t~x78+}$s)Lb_EIf7O~DI*rK#<Jw}7H-h52CJAAgdJrx
z$B37$k)%J^3MsUeTj^m|KAloi?*5rKY%jI9VTK0^R#_kp!UX;Iyx9b(s!<=UR;2pX
zxXs?f<ja`~A(c!tT)xW2G%YJ5CsBscdpu)X6?3y?K+q?R3;K>8!P|xGX{?tUI>H%a
z9wnL$?{y61g7tKY!yTB(Kg#Q$F{xImSW;@Ye`m6*&Yy<vq1L1d<_i=Rk2(yiPq9xa
z82J;AxRG%Typj(`WIrq9bRj!lM&#B$<M$g8AnAL^RBx7+wnc*Mc&NOsA-Ks%8x6@+
zLp#fC#!%Lc9v2l{<eV+{WV5%(BaaoVQh?Ze{=vJk>0qeADJrAFbgOjx>7{_o&R~G|
z$`a{igVQyZd^Y4$-Hz7eY?X9K+&7s>eVk$m3YcRCj*ujla@SObY8*H+p9K3uI7)rL
zY2%PHA|0$+kU9FTe(IsDK8=W)f9RBw-}fbI-!Euc^myK6Dj)Peid4(ZmlTS7a_Eac
zOME|VU!S`J6xLp}O**TFxkuoU^b!+B8$J-MD8W<pmobTU(HJ(=I#sA04vZWPN>-l@
zuSu<X+Shy?u!m2;nuW}$pa1yr!0Fp_(rL_Z^dVcd>+9dYXFgPyz&iLMR6BiWtWLwc
zp!q!Yh{JeKyf5j)l{g+QDe<wFOsn*|On&|AY=1#{2Y<7pO+s4o`cZQ)b)CV5&3(yP
zc^<NF&C?6DpX;1`5-nYx7QgWG&3VEQHR8W->2laDFKlf_b}>U}-6Fe~|1eiud$h*d
zqf+7Rwf5%t$d>xMTJf(>a`c!+mZ-}~BBKN23m?_In!CbS?{{!vES#P<)ZGa_kpY*6
zhD6VmC^vINP-1t|V9K%ktnQ85v|{IBhcgFbcD%=Pqzl7k__}2SsdIE<`H^op1srpq
zu>d9y#2LGqbQX%+DVZ&_+t5<(iYMI=UmKg?)3M0-vhG<_)lw!nUw_%65_nb;w8~X{
zL|Dir&96QV=FfeY*X-;zl+m<xvx!$YjP_jRdU@0C>eQ;z>DdpV!NEBqOmKa7UYZ8p
zUXPz?sb0s2fn<X(C&iqK=+TiR1JvuEHnVI_S#q<kSSVy32fSKIaFSFT@pb!bO7OTN
zKPxaSkCQ7dtc36^*iyf-E`4J7;m>)}iJu}d)~UN9Z`}-~ILMOr*sA$@8YjkyuC%yp
z8-D~<^wuQsbDq|k7-?hsw_<+OU7cF*yXpAZyCU|}6N({eY^~8b24v4s5T(ms%48;I
zYrfvCWY;X%Nz5!|6_RdfRAh6vG_|XY89tmgVNJ+!mCXzMx}xcZtH?YZI;I3{yb^dK
z*_0nK_@S0}H%c`<0nb{MPCPjw0#8_Ubd@k6UTx^vcQ}wP&YcV=@(oMmLnn`YG<@gC
z&F!9n6@Mrf#3@!)>%Q3ASl6ya6LWh%eSTSS^}vCz<pr;5o3q{zi6~KsvQ3=g(U#B^
z0#}f`i|`ePeF9jH%6RgoJ$#t%mF)N^4N!n|;kaw;e9VW-<E=ha#`krm`V{jME6hwf
z=?O!M-6aHux>irq056S$a$asa8cU}c#gVu?R$0w>VwuJ$VqZKie-~G`F~USVA@m+;
zo^%w@khk4~^{kDyB=pAo*RKTYY|n>NC*6flx(sqV^H_DShSHYOHtvp-N8VeUFN}?S
z_^_1l(&Q5JmF6h}T~lJTs?%WIwI{Rl=%Holx3l(eiK;JL?QDdD!ja(aG4#bXt)i&>
zIdD4I=dx?hYNyUbBSVp8sKqK`StCr5em)&fIdln09G}P8F&qM}*%dt8X<}V@GP5Xd
z8<xKBw$f9es{T%XBfR6yPip!6ZenbP19u?E?ZFi=!3<R2_eeF4FChfP<VH|!i|%<X
z8p~%?fnA{AU=%>&aZ7hymfVK()n?QbSvGjkg|>%woR}&1P;K@dQ#@|PJl%Y^<P5zu
zuIy3Hg`00xkoqiGCfPDwT8C7vq^BIO*an-64nxIRmruLfs9r#QKpD7KyNa%-Hi-V^
z7C=-<daY+9#9mqI#eGd$|F)oJvhB5VQ3ch4(t?*`%$*Nztn2|_WBVP8uDA8Y;+i{r
zkxeoJlL8(Sn$f2^Db7f|QD<onux_YWT+MGR%(>9c<{y;(;fTFE{HQ08E;B_fiWt_L
ztid~SJ@>8P!xuk@AVIkRD1<najp9x1zM(O1Op0fLwvmdvI&z6NyTqg;cFlwvd8O|r
z<b?|rU{IP!B!yH^a;`7q>yk*?V6Zc3OPi4ygm-H%kAC{7*1>#VGGULdtpSq~z)VXf
zpVgesPs09|D)l)XioPtjzN|dSMpSpqJE)J`lSd8&K`~;@U8xdXI^(WQ)|RacnkV9&
zlIH+UYOrT7;PK-&_aOXZD)roqeBY{}*9DK>zQMGPjBPmo=2U=IzVYB7Bl@^50!0t)
z&_xQ@n88?F#=fY=TGuzQaFr+A<1EHpV>O#fm950>X+yhFlA=MUwV&QYU6-FjnU8g!
zGqPI9?9((8=q{+!HedJVuM94WaXmGja`gNp(mdgFA@h{f(2xVqS1Y$G^Zb_j?DD*t
zi65A~+r1@ZT``!u(oGqDR?<EthZ(@KRz=caONBMbV$u*8=()bxy}3E@h{26cZaX!k
zgv!<c;e$_=@%%vQ&cxmflLMQsV#A%2!Y7aIX^NGZYV(!1^P4Bkan@61ZXGULsWUx2
zGyRWZtD|p1dv)%XyeH$iFI}mMgzUCP61NRtGjnkKO8=?g>j&+Z>R%NSxDZ=@qO4-t
zM&;%tE98uBB3-IpeuBw8-}$jRc#M0}k~G!WID6UR<+IsTMRFCd^&`CX_VbS`kMqpB
z&NpvmYlke){YqLo58lT&2j3jFByM$RQKxX^D7Qg#P8>U1rkPi+qOL9{FWv|Hk(`T#
zGpF$17WCVxzG0Z~;5xN=(~&)YCw#Y>$(IwD@#E>rSTrl_@q|pdGfs_9jzmS2fETNz
zDW=Z)mBB0<)HkIqGByWwn>5ov8eBsF^^;wD#tOKy2^HARbaoo0wm_Qg+&7Zn1x?62
zsDw`R1ij(w_lrL_Y{pcj{7h4iFH9&!C@9&}Epq;(Vwt1So3ESC)Yk=y@2FSjj#)r&
zZ^${al3CfU0x5^F*F4!M&LLi$o>~lg?SfIjFQpzay5{_D#IzzbO``d27mpz-k(4a{
zlZsrGoIBo<@t`AfX+D~3uJM3~OMP;ca92T+fz=FQVG8%sjCfXh)EotgfLBpAk7e~6
zH}PlKtO3+e40kNMC7OmPy7GAou7dqY1fpm&t;UHYns}AZ*nW#06Wb$hujO{SH$G`N
z<4wAEuArUGG0X=)iH-W2@V)oJAy-I=&$FDd?NFNH9*sD!BU@A>bf|onMHe-wyeeUr
zE;L7YEW%8SsjpNZ!NVI=TNWO<VRl({j1BSSmm*^_idUY9%O1mnzKG;Q4vcbl&lbT5
zVS=D7fI9B1^z`rC?^I66gIc`SczB5~lN%b3^2;=Irdr=)<CSrjy%^~f9=ou;b6-8o
zKPPXHn74gDuH51HZnm9CqsnY5WG{Ok?d(l5_yFPd8xhZW{@_6=_%#Ezwxs}9l`uL@
z#_@|$@}nJ5VcYpbZs|?iEmioVx{W`ZPW3jNOfp@Fi(WJAaYADzS@8YKo|e3yvJJ01
zaJdprW2_od*%Dw{Zfb*I=8?%!$(kP!jRmV!d|i7j_jT%GABRL12g)<uJJbEdS%7JS
z5*l$rS9u|sgI~(Zpux&Vy&hR>yD!OGOE#Lcb2aBxfQ7#8ACiI8DkHoj?bOfk8Jj8f
z13LZ$7-dusrNkcXgOJ=6UXRV^8)u)-wGoe5_>VYQUjX`QZ;Np39-*S<uqS$bWT3um
zdMEAWoGW!*K@WLTcEyiKL3yr;(A@vQockb@u$kEARjbFtC1!@}>IWq#OTFW@N9?Ft
zC0^`i8BNHyBZwZv2Nz0pTu4HM2M}Vd&m57upS&=6587Vx-bp_YUPMecZ0$t4rCrh@
zz8*&Q_~=!MBn18H!RiI_Uphk)YG0;e^BT2u{5dL{vB$=H(x~As)A~byxfV$X@1WUp
z5zVyNE1LD^b&hA8lM_3p0vd14$Xch{fdcK5M>a28OHn_wF0mrE5FF%r>SFM+EJb*F
z({rh#I8}P)A^ST;dm>*2pL>bfyd#~xlkoh(j^Xh27T`*QaE0<&2RRf;hj0k6^cd+h
zu5~c=U^@-LqZ;LOtnnfZVXSfa5$$Cx&J^pC5n?0CE=(-dlY*V^B8<hU8=XDw1)9H)
z*}FzhOU*sEWY1!UsS3U%YbLM$>IaKYu&W<@hW|kXQd*Ji!3N40?>j<;88u{b9^Q*@
zYEw%-Cj9Si8pPb1JnhHD-R7w^YC~QL6E2O5D^VB@qAWoW%_p&z%uzp)A{0gTkJpNg
zKTB12eiw@qJEimn=@DZ=5W**}WfP>=EIbz&h`sVoGOa*FSyYrpj|M~Zy8=%-*`;m*
z4Xvg1VB|8XR#8OE6plrlBQ7V=);S!;AD*53?-U-!peL{{38M(ap@m~4K*E+l3~e+>
z#w=d`<topXs1fOq@-Us0TB|aZ<`8kGGNoE?kn%7XQ?h=x;Ur{zc^^4^-OQ4}@{V9%
z0D?l~r1zBjyq&Rb68S77bm<JOYjW8Nk<i`n03FHQu+<51wag^Nv)lkn2#oZto$s6k
zS%QCw4bgF;^&?rGSgTZlFx5074bGRnRRH6=I?q`v`=eO_n;lj*_absD((g;PD2>`2
zeTZVHYv?4vsjvR9)+H@(+|w6UVFPy9UBh}x0*3qm^NfK?6s$37kl02dPS=p$3y)Y_
zj*J$Jn~Dr;7tb?RuVXGAMcfxj<SMF20w)eq=r7Ve2d?S>8DbTlw1`dG5dm)W4PSJT
z&?)f3S=!@Yq#(O7illo^;RKK(4r>Gw<Gn&^Qc`I`dAX9)WqN>dfEIwa^bOGpk^ayu
z48Z`sPNtQqRWE!E2hrh)WjKnqr?Ka=R==+nNJO|@bggC4nW#>Pnj(O0a;<ILF@&d{
z;NhrP#nI-w$CQUH@~tiJS8j1;+?1^U4JO|sn}5J$AQ<!q-sSr@2FiJl+x`NA+5ayP
z^q-igc2uvG4+oa`*#!oBelUJ1Vjh8LVIDd0`;S#r2!WYWbT7T$9Gq3J4y$b=xkb&H
zYj*^)_1hWbV`n+GY!dU3(3=aC^p2bRP<D0~(xQU4_G&OZ1RWK`4Xw`Xzt)$3%__vm
z!hNpA)ADt>n?+EF5g}mVvxx9CK8|ku>zbJ&J7M1JdBAIX><16c&PM7dtt0|ITuhNX
zPp`R=suAwk*vA_wQ=pB~!73>k-Q?%bDqN}aGb1tcow(+g1(hFr-|l}dR1q8D&C4p>
zB}%}srBC6^Z)381nu3>K?qsm=cp#y-vsEo%u+3ye>vChRB_@sTjKyv_r4ElRK~e18
zvnuw>r<-(|-P6$F4Uxs*W)n6a%u}<UW&<Hnq<od8zzM^sXbjz%J%{s4r-8Hj&7w1|
zr~{HV7AK78jw@H&U<37YcSO|A?ACvW>sJu|iWdmP@h4oI_dxp}%=$M{evjq9G_o^*
zLTq5x(0kzf7rd{aX9>sZCEv=)zEog-X=JAN+Flh7q5oYkp=SxPa0W2`t^(ZGG5xNz
z&@+K!<-or+MSr9DtehM`4gf0`7zp6x;RC@@eGu?3R9_mVX8|z~u`;nR0&x6lCt_!C
zPYdt?d4Cn}$9G?51%kML3B>elq>LaYrf}u}-pwzOD$L08HGubb`}=~_pThkN;hAUz
z1l%L`|3vWbDT{x5<9B!V`mkSgg&LeAxcAgAsi>Zv(J%7j|K}M9)D9+Qst5h!06D$C
z%ACO8gvWoo8}KV2zZZ+R6`Ul1SeXFW)ge|QR(6m-f?t-^A%-whJ2)!>;=G^5|Gk62
z9Dmh=L14iD9&m~VF8y=<zk7f)E<E?V(eEA1{pXs8_diy_@Z{nF-DlGOy@Nsb><ruv
z=bzTU^?*G8>4O8n1)n-MJR|PMbI+{Yb3Jeg{P;!nz$qK+S5}aF-UM)ellf=Z{+-14
zoYL>yl!X}Hd+DBbQu&)SvcIR8{=wXE{*#qbf?6Be8^F05Mgu(v)EdCa#>veFpCY3v
z3}*A39ZrA2r6y248&imZ9h)`Ogz0ypi@~`z7{uD@<vn%A`0_cB0|?~c1@dxma`JHT
zF>?SJI5?R8Y4kt5+aD@SOb?#<)+WCK{A&t-5n=z~n4F+S#uyv`PA&|Nzc&CpEFf-x
zG2pih%mH6nfM2x$tG{I2AP{_={jUtj4Ije&_O~AV`aVeiCF2GGfpCxiw~P-A{@=Fn
zG4R48@!xv9d?5HY#sA8{|I*_Ff&Xm-#P`2rhR+QQPn!Sg56l7Ng(uh_84RiiU)#`M
zESxID#pvEw_ct*WYioGW?|uGzc}ZIt!()3N_+P1H2h)SXet8$n0fKX*badj15*Ysv
DpScds

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..8cea1d6550d228ecc2560e0b6d161468df77155a
GIT binary patch
literal 67661
zcmV)zK#{*CP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&4~N}^)A_l6Ggo!k_5_XDoR8jxYobIJ
zd8MO2im467YeC$sqKyZN+wwZ;EFF9*AQ4W}L-NdG*-C8aRdt#87`dE8GX=s=fG81K
z2(P$EZ;ubD7}3b!8bjPltJ+B;m9|25iqN@UsO&c$*{T-TaNoM-(;9PCnMDH2(Xq@#
zh^{ckIa0gj!@zq5criaz=D;(fU~HD>fi5TLUrwXUscRRe^C4sU!ySA}etg__^S9i1
ze->E6`#YyS)Bad|A`1<<F+cO!FcP7^EGu#JNr&*{@B+Yr5UU#T;7!;c7NJ$>2P`zE
zaw#1S8nZ2nB#wn8U`(%Mx$QmGe?+}sVBe_frC^~il;XO*<cDRD2yn&nBSYxjsAq7~
zJy)2e%y%=y<n<xcL|E+mt-L8K=OS~-D=9pWi6fHh_ITFw4z^ZQG6SG13XJKz^yh=+
z^q{^XTxs3hvhc2Z^E##Krn<8|Sz$^)JFToseEvW{=BI$PYW}uM%9Nu^HlOpmF4y@X
zcR%&aDM|cIM+huD1G@;1Z#yC<7jpeG4#f{a|IOUE9Xh*_@O;+|ap~MNKhyUAv5kJy
zk-M$4qbSd}9a)1Ld-7+TMmy!V9Z_U@Om-w?w(mMF7v#R@e@2MU=PB@;jx1Dut0RvO
z|F&c1OzTYf88+|FQ|6C5>M-i+NXqkVM?^f~%=#I&h>t_;H{E#DVNZzAzS|W{-{X1s
zGn3dh%5OWOV5W6-B<1<G<Cq`k?a#>i{yc$y(~$?Yv7;#0w;h{r=lRbBOxe!&-*n1L
zV6aoR-M;I@s*k)Weg^K==iTv}j#XGWJBl*fw;hrFOklg8fibvKe%p~(n5iQv*S8%}
zwHX)P&%lKJxcUCLo9@TXZX`V4bz_yKyhVQ|1oeKc{$`N4eA9aVbGwcG+pmp}EBa?u
z(bA>;n~uEO2RoAT*tZ=Ca^J|7F+X*J-*ltqaI#yMf$qCS=pX9E&p=oGR5*UqahAsh
z9YLArw;k~mqWbbPUId>C&2KtV?`i5t%Kcr(mJx+gkAA9jV<}93+>v?}Vw`?%npXd|
zW1k=D*H4umD~0Sg9ig`&Aou5{$@#Y(0qo#VNLpBrOWXV7P8X9}*r_qA@S7X=9MT(q
zF5}jwMgFG4t+<h&sdnnU_s1Rl{Ln>zrlaXYJN-?^u166&lJb1p@#-JC?$0gj;QKpW
zO0w>BQNCpgaUrQn|I9GJjq=-$1eTlZsG!>RZO3#+^z4(#AN{*Ohh{(H&of>7_Z)Oo
zrGW1LGa?#39s|GWmQRLxsT<x9{o8IC%)p05>fawPjo&K#ZOA?KvwV)<>X`CT<f|pD
z9qohi+m4Tngy<;B+&aFmy>q>v->>HP9eCaA9X;Gux%hw0^BGMU^Wd#*I!=qy<-ZNn
z_9B!6H%xbTg+!#bxWGMV(IMsBJ{7+4c0Jp-;+DJQxy;nAb}7UGZJELV3*Ii_CKO3N
zDLAUzb!iT4o4ym)Q3f_0JB40#JixBGO*1K@rkVIJ{O)=?)88KY$)%XkjY5u~tl}kW
z8>}#`EK577@t4D}bjd@#QOKoGT!@+z9(L4Xyi80&Eyk<DSc*~+0bv-uPO%Afh_7=C
zJ{ZwH_3f-AM;4)cV}&$LWSP84Y>q5pSF8%TnD@r2q+A=TmSoIp=TxlnoEu|eP3PPg
z6Dv6RJXxU?3$KYxL6&^mVv|tLamud<$fY*rR-9QfdAb;P!GJvb7S<8GoL!tkIma#h
zD9Sl*!AGd(I0Yo-C=b}Ci8ooiaVm^prVpk~d5jUM(x$=)04>#qe8xCe+ZJ$i>5=q`
zNSKh{q4@BLjGQPWNy3?hB>-JOqQA+!tj0Dfq6AglMn#pN@EZ$6zZ99%D%=Pa=SFQ#
z6sjAwIj77j04VURw9rOvP!!}FwJTBUPvtw`l-2rrG0^DPs(m^nMdd&lo>Ub>ee#J>
zQ2}Z2IX0su;vooW_fpIRVedfkyWT1cv}joyD!q*`-;Z(`!{}cTMhN0q6gq&@2T{dK
z908KepRHG{fj?WXRY;cqHP|oPJ50YvkScm)vETRLk(iN}+Ze_vm)jVAuS7Uv;7rWO
zD|Q66>3vqOe6W?<7-f(FA#l7DfYY|XqCEQA7FdKD_D;{S<rIADl3p~W%R7$C2CTAo
zJN`{iGwK~HH=RL8q2?bT<mlVhDfWb$1STrpEAtxxPlDeJzdfrPpIfJpDL=PvIo4BB
zcE-Em;zgMfuQX{#Nzkg`%=j%8d1i=L)q#eZkr*9{6I*;G#v(8Fer;VsHv0AJZQF&J
zr8~6G?e>Wc+2?lu<nYFJ1LgPzQ4?@U^|5sdc6Q%71vk5I*H(_u>n1r8k5;F5j;?R#
zcQUW@26#|Xyw3ZWVpGBi;ssmR1u(Lbd3A|3?R$h_tZC;l_+-WK3Nb`+%YJU>V2<S6
zPvG`!J+f50Muo$*@jtJ{Yxnl|F@$#Sr)ayyUR3mGt)fnGOg1^35c=8LwRH<#D9<w@
zNb`qE0&+VqN_7jtX(a*aC2MV{7Z6ulD;da3VHx}s<Ql8feCrir((0o3WJPC458`WE
zMGsAn7CYp*u{?#m61#kd>;d&J@UwC8z-QWQ>lOmqkp41pT~xm0><QD&HH6E!RS5FB
z1zJTQ!wqhVN|^B88Fhm2FT`i<*}8o?;3f`it4Bpvs5b=&OvFV7pt>Tn^IQCl{7l`{
z@FQDo$oTK^FU+!8ZAKibR+|we<E<1h9HNTnN&Tp8;XH^{Z>DP*^{<<0B>*-;?E9pI
zD4A-}dsI9N1bxNH$Br^4hv59H48QRtbpONn{hVTD^Z~~e;QvX88CH1DfNovkJtzYn
zmM(A}ps{aCv{2BzlJyWO9yJb>l#m}%5iUpccvF7fz(I9Zst7d9vr<J+WfvhpN0Rbm
za54|*f~Rh6D1ogK@Zc0!6pAVI!ge}&1I_K!V~e)nQ$e37S;%@8Ny+o(>}ckPbb^l&
ztx8kLkCe3FP{~ZZBPm0rI<g&-epY@7j*zp2CCs_)R4xe)h_LfN%DQ>~%O1U@Gtk{0
zc~l3y36IWg*tL(SWuio(5r4u7<bG#Gl%#~W?YWeHbgeF`rL!pE9ebp)p`58z7!hEi
z?a`5pimaAcjhWyEH^!qFZYZdWQh8Zxs8RVPX9dK(Md3CEYMoWgPlkQSzRt8UW8E9#
zLYk5X4<el{64U3xuT$|pfFq0QHA+y6-@S=e10=B{NJ^AT%QohiOj;CvX5vS5ze3YR
zF`fgY5&jouxkd1m?WusVCu~axOnHs!LFxJ@9Icg&$n%-ID9m#6{AK3&{A0vLRv121
zmnccmsqzf-H)}mY9=06AJhSYs&`*H(S>+g}PG-03%U3zD9#WQk-YQZ??767<bbhSc
zN2+16T*(4JfJ42h*VpDW@A&UIrxL`OQ?A6rsUlcd!}zFa=is?wTiRhNt+r(yBB*K0
zI&_Q-`Q}LqQDyF-7Li8?*079m?pbpTLr1AbyOd>uv<Vh3OG=FGl1Tv8^hM$L0S&`C
zX-NvUUD6K$xn-9Q8HZPwCOn{Nt#&2%u4TPS<}7EV`^J+&R;h`28X0TN9SUM%8M+q%
ztAfG-pO}@RP=Q7j<?isL=-338l2UpyYEdvxq+i%YbOS^byb0M_wFaq-<Xg!uNl(Uj
zSsCo$aIlNv3xw*oOQ`6P`h6w|3)yo#Rt7g9LfX_dz_5W?r#eb{SY`ipobyu*?y0u1
z5avq&H&LV$BWigR8k750NJF%c_a7(o?A2^TB}rcq?GZ1Ws9SoH6w*Fr0YwQGD_a`U
z5m-g_m54GSnp3wx!;YTXe|TuvR3s>J6s(f{SO+^Q$KsC|q@vrmZQgzTbckMA)Ebhg
zO(}eiXAKMZzJyR?Wo2tPHHIuLiANLeb|EgH{_rdC7_PyB#n}#KRmNXSgNGrn6@U>T
z@<W$8P+}txXOPkvh@iiTt%JhO@k0&c*Ym73j9+oz0GC-53^9Hq{*{_kRI>(W4a3*Y
z11_$WRS)HgqSp3FN(S>)(jby5qS7};2I(Do%^8GOX@nNiJG$=S479Q`_5oAI$|7h`
zM}{;<!_77X^-owC7HEGZ7D|kd7C~Uh*boSb;UYui!7D0HWyyJbIuDT{Ni|$sWiT`d
zctvsAVDv4o4?N{;$nKAqoVi|)z>6_gLPCZY8MT9?#MfQVNhE0)z6_}odU3eZ8TN}Q
zp&XeB+xJb17JstkXKys}_hp2%-2Mi<+2DODeO7smaQ|CbArmtwDEun!3Amuw51j}y
zay@<VI5UBl0>vmO7%-5I-jrx1;DZS%l&~o#WKcSGja3N<sI&-JAONKtR;J5DW-{S=
zItt^N7i1LTvIN`7>VoElw{vo(<&!$G($a-aF0_v5lM9_kbZ`szP+3CHirFKaQ$B0T
zG<r6S*_4uqv<@qK>52PH*_S77GnW>XPc#z_rV|9+gnH?Cq%8_(abm~?N_Aq$g-Lbh
zY3$3~MqDu~{7S@xTjxe0HklP%<&!-K@{Tv06*48BaHcBve-PvRO!6+~oRu?^d3<XU
z=dC6kP;h5XXk>ev?!tYEi{1RxXB<1@{3<{?>yJK>Nmo{QolnZ!q9j@+ayqQQIRS@f
z1<v{4+URV>PE)a*1q73)Ru^VDfcT8qn}F)G0^h`QkFlPB`}1ThaVGKLv%=d1aG-U8
zVc&SEcA?(^f6&tCeS8U{Fi4rPaEDRdWCbVE;mRKX&>oNwjUoSumKd`Tp5~qLheFfD
zBhU&@^Tzqmg#vwNrNR}ph)DtO(PT;|CZqu?lc<rlVP!h_H=w8!e9|_oOh>N*%k*dw
z%MpsjhLedp5LQ5$@o#<<!LcgFMW{{dE=FR*ca<&&W~Xg9nJ`mqIGKh8B24DVF8nmG
zi)@3*Jk^Ks@lYC+JIt6N>(mkeXL<w)A4i(yq7cRQRyP1BUX+GLtk@KW!wNg|N@-~L
zcmBP=h%ZWl5wbSy5nabAVPLHbco^x!R#2J%leNOqL@Kj&xu`mxOV&^E!O=~bD9FyX
zLf1r!w-I6U5X8$OaYS9+h#1?{jU#I6r4ccD_|b^cdc7!Q5S}^mk90h^jL@8iu!AE$
zJO1QUCvxaiC!ilc>VkzzAmd|^(99l!@<hl;B_|Ov+2o7~%op@RXas?m7YXcw=gH);
z>2NHW06!5&u?SE}2?K5N>;Nk|f~Yw}92!lv1b{cqK<ncrQ0gG%7C{P_HGmPr`C<hX
z3i#_v)jIwlX9w>+YdZR7wm8f53tMA~*aUR8HD$9*9QaKr!ZU@+3LF$(0F#fY52O^E
z@IsZ3)`VjZuoe@9Xn?h>!=mW~O{|vup&TRLb*4o3KyN`WqN2wQVy$56xqL3%)WPKw
zEd69BPGYDNLFtG3474Ng%37h)bLn&*4_7D5fNNJM^{MI|)^tJ#N|ZInzcUN3fa>vV
zRHA-I@Px_v)@hn<1ypb9#R-{u4YcF5Zk_hQmA<wP`KCi2;4DVm)F>T*PMA-^vzQ!x
zfM;2Z>S)IG({u&UCN1>Uj<O>r-(Zi)G+ItN@Xt)}teu9-rYi!qp$wIAJ02`XV1gq^
zvFw7iM^OiByhQL^u||lr4r{VJlAUG97Kt??xa<urW?XQ_Q16@W9_KO(2;aHP^mum~
z2ODiNi;~<IG`{2FZpN2or}a;WvK<<2P{3a3agAX4G~&UDdb|`TYK>25f~dSHXeFz3
zrzLE=H391Pi>#8C-Fg1%-s?Pn5o^~0pl$+xSd{!-){ubmW=$acwDvWjQTGA%L3@W9
zw%R}oThJ(1{xIvUK!F#^M5oPgqjYfd)Nu^0$Qog;p~{%xc{?z^t)1c~EW1re*d5N{
zPg1fp8hCOE;<sl`jtM%OnPetBtxlt(oZE{Mj4{2#fYG^A@Tjs!dk}Y@Dfapw@<iW+
zy}^tqy$l);_>F`U-c&gUH=_w+qbFGDPRJAfFhL1-fTHdcXljOgHNaE$mSJ$*H^5H;
z2^7cRSUL$$x{U&9NDSixB(en}^F9g9RIrCOzKvqyLds7A==ujG_KgWI91HqM;dmi+
z01ZBN(xm}I5COpZN#O|5>%3t@`5=+y_&#kh8)b^8IgN9Qfp{gI;Y{0@L7U1(@twz@
zh=plF>F{rFO9TJ*Ck2v(6+WRVo8Wk(oEttr@F$Y2Xj{ouN?O30f41{MQxbcg;zLpV
zQ}EAItU-eE^Q6W1gYrve_Omx?$039Nxy2_q$QI@W`Gi#Zr*>Q(Bkj?SL-I86>q$A1
zlzh7J2g#+X4#@piwE%Mm?rrd?iUV>FRw+R4L6rjJ7OYZ$|CpUl%gsi?^PIsti;%Mx
zAi|TLL7Uvk4eoa{S~?q3X-!3*QJcU3N8V_zA=poXa^&w$OdQ&psZ8brZOv2``hm8_
z^uR?3tK*_@byHn470!H4b>d1=sH$*g8e>ALuvGV>9fx(e?>Z!MJn+D4C$H2B3LDvV
zU$raq^KguF^ECL|YqPX0q){8=Xf(c*)B|j{1pOY`lVHW|+Lf63?UJsqtcfbg%2faw
z$0mJumuO**Fs3BZ`T<h%iZ99rV~U}^HBBj|`quDQ8=<DMVC=+p!Hl4gnZP&hGg~<u
z;N)6>SFKjZoes-fyP%s1+P_^q4O9~Qy44LLe_iU;Sz4E;fr?~bI1N-I`{HRpvu(Sk
zI^m_;uE}1Q&^6SHlj6EkpJ_CmPysq3ZG_q&C+1QibD3y4kw(_8u1+b5Q4{%7WsF3U
z4?Qz;`${!!S5qJCunQ<hrS&q8#DrePJQ7nxBJxP2Zm%}`P_V93oxu0`uoL)>{3C0`
z-E8xbu73^Ix2CR-A;Y&_&yj{?kb1y0MCj_3a|DTRvK%w=B<l6l5KU{X3T{tzLO@zW
zqCq{~nxFtwaC_AA@4=to`Pill5CBe>2He&l<+@GJM{BOy?CQc{b@d=C`?0;2BNGMh
zXAG&S2ZuxhifUx11tnkd$)bM*MS+VO#t2Y$b444pS`F>x0e5GkUo63N!c>w|9G5y_
ziest|uN_%EhDI~h4HAy%z%uzX**&JV;NY%QIcZrwba~41p^H(bkGcrqaW=&@FABSH
zM5&`SU08tLUgj^tw7{WkLRxGI>TL?DUWp;>#qpRr;Q$y3m~X7yvl2t{NhaM0IOW!E
zwDJ+BE5m6HyP?lEV53{3Pc|}1&<oOs9uPj{l5D_Be$zHbpH_3&OLOE5$fHTMId?0q
zuFbh!;aO@v)rTKOh)2^I?Ngoj-Bi!JQf3<bw`E?A#F8_u+x$56xSntC#we_Q>Iy{N
z#xj66@9M;lcNpY3Z92zzj%ISnk@k3So3?IRO&UY0Xy<Q$tF=zp+6EVD_zrL+BC4u4
z&5{l>oqr6W>J77mc;xFpnSO4rj@IcK>u9AjjkdH!p{s_VTz9&_yUwzHm#Ze{*KfI9
za(<m|F^2pu%IbcYGUOM@;A=`=((KY{-)w1i>5MLEo$e5a(W-Si$_Q`QdO6C#$gGx|
zez9nmqYQSr*2`1IPvMMb`MO3sj4IqQ|HPC5b3_8llO95R3mTpBW*QcwT!yVvJft*t
zqg1JSJR`p7uWT^PbR939;-TZE(|=lzuTKAIe&<YgYc77HaL_Z+8vUkFEgK5Em0!0t
zddlehZ5c(@iJISlVO#Fw2A4&+n4$F1=prcP24{mYMe0|0ug0)44UR!&T?ZTEytcv3
z_{C%)?j?)^6newq!D)?Wi_R$8X~M}4lp2K`w7iSUP2cj8Pd7bg0&PI}(~H8G2>uKr
zXG}i>V{BF>JwP%9TW~cPP@{td%9}ZZ?;4D-=Exg-MJ7sy4M_iK45*=1y)pbs;V8^a
zu}r^PIUo$Mk<MZau+gqJ2H3cM2B!xy{~ApN=2BuTL42gL;8kd<AKdWZG?gK4c-xvQ
zh`HHha1R#3@@^4AdJBL(Q$^<nq}z%;T1hY|WeQMYri?||YG%opOEoZ@9IC3_fPHJ}
zRX9KzL4cqFpUG5zycwfyv;&O6HrN5oo-vh*XZDP#-hETdmELJa5z*D11=kYA2h&D;
z89t2H<2cb`99!-yBb=BF-H}c++7|1!D2!u+umCN$LgpH3WEnyIkI1KqC_24K&Nyxc
zgOXaJ=UPtWyc7VKLpv|V9_q<(UJ3x@&=^9h?ZB9>q3v)^T-bxYs)piMHl*aA3?c0r
zT}s@b>n*cwEXuANXfuE^2aL;#07#9t$f4Z;L|z-z){n*rFU57XlR>2Pkuv*+0isD!
z5Gj<TlToDF5<<q(mY~6M$P9Eci1gCU$f&O&xKBiV4OwE+jH!(E)sB_SvE>7HJzfs9
zQ|M^G0LHJWD#yyd$v>gL;8#S*BS|?yL5x0lF-<y3jP}XN!+23L+8S!xO9?hM8Ed*I
z@zaxTMk8?Q?D`?t2~j!acrgnnNbJTS@u3l6?IuGR7p3EGCZ`5vbq-Ap7lwcu?1ABb
z^0Zo%jMkQ=^-YQZb^bxF#LPoyH6u!#|1D$Aam6zE#u#6bq#Qes6GQzj6O@H9I_u&s
z$|N1TPC<7fOUEu6M<Pon{z%ZSH^cm?p0BK&%mfg!gWVUy`yn|Q#6=K~XvZokBVbW7
z+#e<cy8+3N2?fmSv5U85q~FBYcsfK1jwgkT7)ow1P7*rG<>Ew~7=kxJN{(IBfEOXh
zrt^S+wkAMZ!pzw<I04*S*F-DFHZ}gvbdsqFKmop{79eghp}inuXA#JKC_2|w+=oJZ
zU1C38*Vj!cf*BNrx0uOe7ay#L-Aq$?BtuA3dBiwV8Vy+oRp`>@ziH&YPc8nb9G`(U
z6MQZbGQ-F8>D&{yjB5rc`bsY{K-!xspK)BK>S#;>vOwE@Wlm6t^G&g1pxUhy<zn&{
zZA*4BcZ;vF!>-ES;-{FIr85TA7#0PK#|XBYcgO}u$h4DRFm^#f8W^Mm5)|LU5Se~)
zOF)r3q+B;hYNfFmt+&ddW8x6<><*BUV>;k2NdA3mrno@wTQfzT-A!w<(V%<NbZsb+
z!t*RCDF_8u-771xekju&Ax;dIduWC*RD-d{G(g<20!5ExrI_kN-QQ>{e$XY;F!7Uc
z?>xGkE*c!3roqCF{B*Gjj)O-h6oc&^*Vs;GvbvTIuHwhJba-_>e3KhP@}8m9JoA3U
zsW6#<D#1drHhb{4jyolqIF0~nMKsUAWqy<~izxxff;qGX2&c-jHGo!BCaxur((zTv
zx(1L6d!T;UWEQK=A6%gJ=m44w5G^QjU=!K%XqtebIO$8UtZfw(EFOR-j;87dMv$P>
zG*e&#ohAkWZsMeA-T?0t>KV4;ocNmVI%4;nO)MJtSQm?sM;<yPMl_Is-N~YXlz3fb
zz<Q!i`%3Wk_?yAUDe~8XM5ehi)5$bf4m_FWN`e>Ew<`;tOzX<Hhe#pa`x47KSavaQ
z(Fh1}N+Tj5#EI*PfDkI^YYPzK6b$)n8=?RR#1kNgi3lMjREQ9#)`fr&C#+!voo%Xm
z{H8>UOM>bbETtU!>-w;2rdZ)aw5?ZuxoMS%5z)79`DNWh(+CPdob`mJaI^xJq9g&h
zJ3^f>6e3Jiiq%Ru0Krxm3ive}TbB<+TSFDVCQq{=!t`iz5u4B{E=`Z<6!+FG;3@8H
zygA={n_-wl&;##@rs6-A^%<L@m*QP=1}q3#?<aRtn3oZ!Lf%2k`h%_U14JEBhiJ|8
zpG9)x8bQndn80*ZCIN|#O>VJxTP;%*{+)O$T`CMJ88$hsm<QP+aMTE9p<q-apheT7
zj!WP#XeI#5*t#V0%h<XAiUzG@%B*oE3R|07kHo~evb90o7;!HIhhqVCwnlWLm0Y>E
z9yy|W>yaa>#TG~p4Vp$|jP`8Z5-sSgZfTHBImA1>;Dao2>W{GXvJ0Ry<ZcMcnLtG-
zU@!t<scl^nVX4*NfS24`^+{|a9q40Vv^vj+V|;n_A0V9x)r2!?;ILLoNl?zjfZ|U(
zAfO!D=)mdS$JQwaNK1slnU^jBwAVs)y*<*Va-?Gc3<Sh=$7PSu=ceo-1HOlHj+lYE
zD15M@lI0@d-iUbVMmw?r0fZ>Ppu~r$35K002CNc;$Xu0QCn(|e!2t*J6MaK3X0{$d
zVwc1c5;&?20?O6C#$Dnatr3na?H^n$-X(Xa8KewG0~Sg1+S{mC<jO8*25s}Pb;}v*
z2@yX_jeZoq97O|;kLFVnl?X;Mx7r}&+_m+}DPLQsh!$*uNe)stHYreqpu?p-2tZe5
zK5)xrhU@`SpwiVs<KC+ZHLzYbT0;#8f%N3Qj<0{LF~TJh1|h5M6iy))PRY$!w{&Wo
zRyyV|`j4?M+mI<K4WV?6Z|j)u^N)2LvM69!jY;8J*fAuUfDar)W+N`|kWz-~*lpBV
zZG@@pVtTR$2lP?PJ9Hhxlirk?zf&Yz$v?WR4@kgxHX%uD%V(33ME%s`pHeZ;ZN(FA
zQIG?%<ZH~+Hg1se=wrdu**0c`se!Q{K~ktlwYVvv+|1gPP^nV+JxCe}nF=<LP^T|+
zB2|U9OuA@L;a^8l>hw*usm(fVNvXpYDx9iXA3KSxg0eMf+8F__C_oIhOKU=wU*Xys
zazYCEcBg3Cv1|g=CFLm8T|+PhLaII}ZJT%-h|BtD-o^1)X`%%0gh$_rr5FBiQPd*@
z;TqelW5Wp(nd$!Rn%iKLQg_!$z~+O^+c(a~pWmYfngl7w|5)kB5iq|ZG)Mi>Vr>~Y
zNO^R#0S=%E!3mTjqDZmQsE6F1_Sqs2;$Ut9mttFR4?$QHc%-6;BI^XO3R)Q_HVT~L
zhWHo61OGx9Y_COq#>SazDC~F%dr^v0vD2QpaVjZ%Z{o6H1hgoJ!lXe8ZmO~sym^eb
z-YMDRVWf7>4|txBwh$-``A*9E7sJ9|au6bPoIkW?+l836QwG`#tGz4?h&^Hy`zyVQ
zYl#`?jz4;CMZ@nDZYxK1YhlJMO4QiYKEtid*!-l-n3NtMK*U(}5zva!kDXT}6|WZ9
z{W-Nw3Ld^|w0F#CA_|ff>mnmT!+l}`rKFtE`rOWu)u6K{&V^390*;Mdb_E<Z{d~4l
zIQd;F3Tl;}&wgkHckQgRAh>Ji)+=kEejeQ2th&rB<XX30zFZdN*{_zU(yCbo@2qVH
zexxII>)SQgZNCP))isFPrRJM55Rz*uOv>xGo0m4wvX*VBjKL-wn>LU<;Unarg3xVl
zO5?~fx|`C`ZEh-Kh?iZP0<oT#T><BGRd>6#ULihqZ@rQWDoKd{t`$Tva(hZ63)!$|
zdo0A9pY5p-g1{){R77La?c5#<Q5%u}9$7ZIwEmc%as;8ut}4je3nf#G)FpO;3SSry
zyL*%M2rr?YnV@`h#e5hL`wvC;=w|PVhvh>}Ri}?HKIf`7HGT0_yP7aWtZw~&NM`bu
zo}zK#RE2E5Jy}CLz4u#@ZK5AlA?`)V(O-2v`;W2J^X5ajYJT%EU3J0v;O@*zKfd@Z
zSAp>b)>P%k`Hrs=<$UX_hB>SO$5!Z^HiIgLPBTMQP^T$^X@p6+^M_jfbPP^~+Lz6v
z3c1rJ(iLw=y9o-y)07f>wfC)C4$rr4Aq>4tP5H(^d3yfPwU@AG#6ncLSFe!GPHR&R
zuU;@$z6BSl%uPAGi>(;iwROp%U0aVF+D!vi4D0^IZq|Eg#jBN5zcD2Fp$5v33&X~M
zJ=^_6D@4!Ftw*e-pIeVuOE;SOf-jpbBK3<!VHYS2PGe;(+h&JA)sem#B5;R$tv{}8
z?_0MViSGG)o*hA|ZaEsQKY}&7keX;7?ur_d4H+5LNf}DHe#r{mg=P;!b@y34k~5oI
z!J^3ysGIF_Dd48@@+sh^@oVc8r$YDgDH!;0Z{1?=mw^JW%Pt5nK<phsqGw?pO@am^
zEMFhz=8YK9mMdb7f0Wh-w7))V>k=OxdP~hT9CleW5=F4npm8YZrH^tf^dI>r>XM%>
zuL92M(YG$Ko4b(W47ES{aJ1sP<ylCzppWt_r2D9kfCZ+1sgLq3q!X%_bz_cbQIPWL
z0Eokjo~=VT4@nw=f_Q!XL4{bPvvk%e#!I@7t2lpwW#x*z;%9I1{lehohrBR$8mAAN
zcLHL_bD4wJV*q7f`aIDZiMuiA{EStZN`9x$w5#w5y{Ze-L%!Kqlro9HJKKR#ek3W*
zgQ<WA6g239lVp@ouOO<4%?~eI_|&ocCxg@tB^mmpwt$4EK0h4SF)_i@8VW@8DSzYz
zb#&&BU~^B2%7xuMb%QL-nj;7dh=5KwDJ`%!5Yy!q&iY=a6<8noL?z!O<r3-ffRKPb
zFHSJ^t3G8VLu5fm{uP1`LguEN8Hicv^CPYyn7PL_<bWS7-Q|MSd1buP8u7)L2IxOm
z#WY~gl|kl$;kZ|57DAZ%RWS|FUM_`qtZ`fw*O2P_qVPBdoGd|zk`i0us<?)H%LSMb
z+OhQ*iIq`Kaco>AFX=t+mutM&!dl9IfdRZ(5Il1bo#~|r8zML*WnC^p$z@nhXK^e-
z_b%)xT0Kyat6wsiUU&YC^b4e7_KK(ia&U*O=y)kEsxzkQ%4hENXujBI!Xb{BsQ48f
z9XGF3p&2hybh|4m54+~BsJwho5cTWDxTqsY{B3NLJAb4Fkl05&*dp*7xVDf%dn75A
z{nq7y;In?~?#TGGuE?kiU|TS0_z)b}i&8;vA*8on6acgC6*`4jx?Z7EH_Yo@u~U{+
zu&bV?-6Npj7<L9V{l+5$zqQ)%_T#5|8Swt0=(ybz@N(J6*;W7_O3Vi)ox&937`ZEk
z4>#8>fy006w<PXH4t4<IDb6zF^p-sXV0i@ATa-ImT#P%1m-30fT0ngmJ#^GEMIt7&
z-+Lr!h#FDg4+WR@r$R|_$&|ekKd>l_i-k4jG3KKN*8G_y3_n7+dPQJmWNc4^=3{}3
zm}5s!Z2%`8AjIq*xpVL{{gL*QD2hSBafkTb{?y~>!B%)GTDW0)I=O%d5a^JKC^q~J
zFLi_z_cDSa>Z?B$WbELIjAOt{SooHJF|j8KQsMwx*3dx6Y;5Kv89WS~2S0X!DUUK!
z&OA+Au}2JW@~8{3TKV6ZdUgiO{d6=Ie#HVj&HvZ~{FGt-(Pu%ZGDbe9=V!&p=kz>H
zeG1Tj^U2SOf6oKmRi&c=WW>*kZO`k(&q~EQ^98veXHWgn{Uk-%3OQFKc))h(r-I(E
zJfB>JM^-HnmpKsG5R1S$=Jl~Coa2o-%09@v3s>|}<Yufnn$nt(zu__&vSiAlaE>aM
zs?>CZFFEaqRjgN;A!hYEscu9X%agsBw9@oDOj=0=$Yqag))Qhl1&3h8u3)D~x`}x*
zJ;ZVsEkd?)54l308mx?-**M2n<^L=+WDYLhoGv3K6N!kSoRnaD1VpWnrMTc12s4H<
z!Et&n8t^+@F;dKWS`?-YrNkUAQ)dITj4N`gC5(mJz$9<1w$h@~(coD|=m06dU8zzx
zzFo;u4;GvEO9O-hps$Y?tA;OR>_{>T*lcD6p7^TLq=1y*!sbv>B`@F&U>ta&Y$Of=
zLA_rQ-jtIQ8V1mh76tHp5d#$;deF+5DNhjfi3^b;Ane>KSrJ7WTp(AhRON!wVqlaD
zHUe=`PC&4rg!kNKkZp-Y=!FRZTq#1WzasQ0SkRP%4D5VwR(XucL?;@Z(lA|E2~6g6
zf$JgTllbxnNcr2TJg+2DFO&kHfO?@6z^dp1Dd@nKBKrL+f|r8BiWG}{*Jv|yxnUrJ
zBmfetH#u(*&*ZJLc=Iw{l#BVexdtCuyurLlm7&4V=mjo-(#nM`fShDk)LBG4#V=Ep
zIwIsLembN*kb7C4;H79MFUWw7YXeA}EVg&JqSaWE&kG=+Us0)nxy~2ZFZ?2y9laHV
zOusNc;Q=IYo-4);;ZH#!pRnH%^|m%MGJ0Jg06prPH>J}eXVztoX8FTKK`K1_`z`}@
z%RE_EoLmE-pjX1b>a8nP5E$32pp8$hiEo+tOJDOXFF$+xM;d;}R7TGoAjN2SMK}%=
z0RcC_sJp;|8^G6{^#-GAWi+v9uy=aq;R6NU1!UY{>U5zUw={JgS;QQK*j7SJZYW0M
zLRD^Q==4g%N0l4YsXsspxm6lI%eYq>ew0b_O2bDimaArC#91Y?brT^N%lkkpyC`E9
zWuIKu_{JCkS7=~MpSt&<C4*)nVC)7@u?sw#rBvUdu#EUDw(7mWLryGMfrp$}umTUs
z9!Sb-hy(Ioz#-6E6oA;`zhC(;EUz~E03w4ce;-~jS0PT8wsql_H#oFhu7ie%#>2ZV
z!1O+O7gpM!Wav~tuBa=_5s_TpZ)w^vb}kZGFw~29C6m1h&xM_0_a!N%P#S3l=(+&&
z8$2SeM0_|rT$u9*QE9xVA-kc%o)<s>;+tIn0q{Y%;O<dTIcg1|89h{km4RL^1bqg2
zdFAgT&dYgHy&|lO-7uK6;3ow?Wa@^6f|=9(l%fqgr>hpiqGUH|x)a(53n(lCJ9RJ}
zi42RBf8y%H0lGSIfUZ8gumBG2UPw(iFuahO2D&v3Fr~tU(=^HT9jJ+&@=q>y;qaiH
zsB8se#@w4;6B#t-g;Ic29run_$ZKI1WEyG^@T0(W@Io<wIXNi#tFRqA$_h6aid`<L
z2CJ~U@*5fq!6@Ga3cC?*tVOY}_*Wh$im;6cvm*<Noh01&6LwFn%zdCWvLqSCgr|!S
zT8#-y=Ja<FxXcSB;i3@e$i0R-4cznBP&YDQs2h>XAOr$-g1MCS@&ZY1f^9TU0ol!c
ziVc(l9o8^nx+~I(Fmf!{_Y%~ct0GLh9@T|=C0^agpCyDGaAjFa?iCPtaZ$L=_&eid
zys#cJ=`#q)K$Iznl5_+(Oxunp9t6you5jgr;1@Ta7usQC55fQ-DVF8&UWpADQ!H%5
zlmG$1+?0Szcvm+iKrg79BA_efrU-1{h7;pM9$kY$kv0Ba0h^d>aHEy{*OhZ$suB1~
zV8+nS<lqeW#u%Eg4)F{vd<*1bx(kpdi*z_Og_ocsofsHEmvs3}7X^L50vHEfCDae%
zR<c@U{!uOfO)anlvRq<P@^=Y-iQsjX!F(mqW=!%yD|s($oQJ2q?#8F*j(D_-VVHAy
zc^4&DgZJm-SPbDRK6qLp)-Lc;2RJ2|4;c2`rLe=W=dPFTGu3M(tEM`E!D;OC0t<OA
zFjzJwSoU01?iU5j;`RO9<W&*KE^_=9yU6p0?BbP*GOVtM{PsLz7f`E_Tj_ycvRc6_
zRn$sFdvE6HF$A4`<}K>-qIck1d{R=K9V&y7_Q;)(SCunaU=e~*L&Y@Cyih<%#Nu?f
z`4A*{7&v_hMjRD-cM6X6!em*bfgwBif@2-Q06nWz?ahhN4shoBA!d=Z%SJ~%txpO?
zY=W7OL=47?MWT?U1Vv=xFYOyYoD$V(HYDYUC__j`B7$4jt^mO|@nY28Ck3jEz{~BH
z#EBq*%U%HD{G{YdUSFn7X(v$HF`+b=d=h5utAzR<+WBA%GUqn_q6Wt&g=>Ilw2s>E
z+d`rK2X}tNrQz#rb5BEj(tLD$kYE$k5fh<lzqGlK5axc0HLzIpeu_ER7X8#}=g!G@
z|3~}t*gSgQo4q%&1v?hc^*W6^?MEM!+|@e7d&1sf!pM%R7Vniu6y7T^Zg-lAbd&Tn
z6@9dmM=Cx8Bs^VDy-Vp<IhszToA+GrP`7r%<W-3I0rsUX(B7$Tp>$Wjb=h;85AWn`
zfw8)!J8%c<CSS2<pSOL)r(w9cf;7)~mBDcnKd~Ne;wP2^50lbWdb~PZ;Z{fYCQS((
z_AW&U92P~@X*~6<sSkBtVKbVgZRdAbmBU?iy}Z<Ier8Bbo~$)8q$XogoXVEU**Fz0
zlmi3&rn@i=S+XQZ_|~mI!X9uQ#;OoT0}GS*4%Soo%6A9Kt+-dY8>&+@{q#X?N_E8;
zP3FRMV>B7dUMJ=MXYFlzcFS??u=)NKXL#@6-bmC3scC@NKr#qy-;9DxY}f&U?tvW`
zN&bBvk!!8}R=Mk~s?$aR-LH5aZGCKQk)jqC>%kcH;;Ur>98(P(#K$sJ!KzyCp$TJN
ze2q#_wz$zwI(*0C@%hb&gS~g6P&M9^IDC(9N}S5Nb|uL0!x#Hz#98mD5hL8cIBAZx
zb!6n1v-}6MJ!c7TQ0Z`7HL!^-l+XgazI8+%i|^Ys625O`zFB<T#*yHSi&XRizgP+D
zaW_@Mp0FEhVO!YzoXa`(l&BVplHKgiS{T6QVTq-xK#%R%#+5}k27zI(tAn_(*Bvr|
zETqFEVPUAlna?E2QxI6@$&w#t?4>%G`@K*Ft7tFo5K2+A_v-}0bJM%}CVd1D>~$_N
zLD-cnW)+i@3e(`K#O{VFac)DkI@6QAJ~a04*G@E~Mtl8ign=>d_I;7w=;FhA00qo^
z(`bS@W(v4`VP5nLLO~<n+v_T1PPkc_Cf(?NMBjjdn}ceQk$F?t=~0n+lZhw6zcq*S
z6|&q-QHwGY-Yjm^2O?I(%cbjNC;=N?C-Th_{RIc^0}-onuC}UiuC}VNM_aWJi=6oc
zQLX7g<#OL&9$jvCC1nFQ7kuA*5UXLO6fkXy*fw!vaMoj;fK-Y}&Yu#|S&x~2o%QU`
z>#XPGA6BZ5s+=&-mz#n?FU;T%Hm)Zy?ZN9ICRYnO>!%JBfR#-#6<k=^{6!v1R>2$q
zQO2C@S2F7Qh0W>?hi^OHdmPL_y!SZOv#B~XZR5SiVaxA54qJw|Ub}X1U72P-xUQ6;
zEb7`uxyF!qbc#_rL0(hWT|bb~v=)PQ*x=O-vs4BbgLYFoYTh)JQMA!aOaGSyX*FKi
zp?_Qq{P%i8Z$8|XC7MNtw>COzB0uaDhsHQxZwZ-W_Pt3&7TT}3jmTB|-bezpHBF}_
zx^3)D2@EqMFFvbtLsy~LxlUS(_T~hJ#(5J+9wG#S!~o3SJKuDX#i2D#dlTI_CKDJO
zTGMFoK1?M%-&By`(VB1GM-Wy{5!7GF#{F|O_6)?XPI2E4K(?m%@kdf=-7@A6>&284
zx0tk^x=_cg<M60#kVT|5O<N9#wBDO~re>b@n#v&3dT;!h<9Uiw205T#-~bax6I}4T
z*`;6n0a8$Z!6+b0^%d0QTufRAumOhTY{Vq+#`VI~rm{X<nA!lqq9$S@o^>jh#B77`
zi17o-x^upj)xMlP;_aD4q%l!O<_QO|qrZ8=3pc>edN#iPvVe$Zn+o=ugrk`-kW6+y
zm3*X9q^E#G#81R?#GL6@vQRG9ySR~Ns|p<hBG?F8{R#?^6KVx!%9|L67`Lf(Is~gt
z#a>Qi8k<Vw#eDO#3v8btvs0)g3=%BLFV<;-9qYwIO+>VQ0ZjoTmLg1r0B1atO;AC<
zc&#bS*`!Z%3UoI0AY#t6JbUQ~#l;r9Yj)y76B1TUDd~I%;G}Cg3U#LC2p;X3;klTT
z0?}bP(reb0Uq0!&bBZuo*b%yt%L{VW-!bBF+PlWcWq=hb#97zm5pkxp>Qj(2su3<k
zzWcx2#ae6QpaeV^^#&I6lS>LK010@mq?RO-Qch5~5qmWo&D#kouGy3$iC^DT0QW?i
zPcHeA5aY=Xme;t+4RUve*<5|YrqYNK;)av>Q<RBNtsTOE|F{w?7oyV|@4C1dzDU>H
zF;7YGY7I$gXQP{Bf<u2cZrs?gzu;;=+q`zEzfcLxwrJZznY>utN%tg>ywh+3N}Mmz
zP_qs7o#);*^giIW5@{iUO1Wz<N~)*!<u|q9n|4lEIaiMiNwT~2{eKK9X`;Urawhd6
z+!nyv6zch+R0atlXoG(QSt2}oqcjs9E&Vr<^!|#l4d67AFm60QfDqSY;%o$K<AEsf
zBMt!(TxV$9MAB>j7(~*`oF%q`CemMYBpu=&&2#K33EmA(!&ky@Wfs&P@3Riw<6tYu
zWBV-`i!}}WZAPFR*^UG&jKixA`X$EES3em-Lep?gMv%zgPS45+sV*Q1M$qz0Z_cVX
zhtO{r`LH;=S!OeaR|_Hng?!I}3t2kNXq%TL_st<%TipAXm5=T(M4|A8n;yj>4qZ4R
zD*}YwM{rauO+MmAXk_IzI!`54tp2SB#fkvZg2PSsm2d!vYz(b8Tu~45O#emB*gRLE
zZ=rM7Uw-g1c?1tibV(2LBg57Gq=bTcr>2Pm7fKNH!dr$sG@^4S2i)Ifjxgounl><g
z1RXoP3LGGg=5^f&T=qQ^^cW(fo@BpJ%+-XO^o`4!fT9hNUr%yOhzV$tKSB{;6FgsU
zl-MNqg96FsLKGds%^=EGAljjcSX}xsN>YJw^jFUXIP?&s(FDie^_pM_kng~?1jugS
zv{~lmGAM`5Q$<XMmcYUqPuBHY%K0?S-oiX+Kd;;d6?VuGZ9D^;OQl*EqL-S0&y7vx
zPf~>nU}e`T5L8xd@-U`{jbl-OCO#wNJ{u&%dS(Iat~ZY_X(K$-HDZJz?$i*=(_zTr
z;yc@0hCe*UW9w@sAHiN2E_BG2#vuOy5MtM?BJIGQddC&5wRIdK&%mB2RW})HcO|tb
zwyaIE3T%DAU^TsNT}(B@hE3}xzr~`ueITd++pehwAI~QB@!YK((A5>Nw+>ObO>qNk
zdR=Fc18h1}Z@K2Fp~N_Ays8amnx$*Yi5A~r?1>Z-ir1d#;t-YHWaK}l{3%g2#^e0l
zRl<}2S@;H*PlfptsB|UkYlQk#r2p2mnBv|!E#pfR{DfnDkT9e~`FfO%WWv|}#@kPD
zD8DiJQ*r%M>b?T|zr^)V#r12sFt%R?oMQV8yh~HD{aP*x@3$|tYM9yqGQ1yO{|0{U
zr8}4i_Z~}U3Xtaw!5*%p1}S@D=VtT_0Z}HPlS6mx6S*k|Z>=Y;2ZkU-6B#W>UC}-e
zt-8%?d`iAa-FQxLe-EL&Ciw>lD7$k70)oV;P0|kt4>!p^pma#H*az~ub7GGg@5SY;
zSo9%u;RJ?rh!J!mI(_IKaN?dKxjgDZe1cqk=sIq0a+nN$Hl#3l7Y8X!hP*MGG$!0k
zc9D;8Wr)E<E2G%U=DRRJ=*x@e64g(*II#QZLT8qm7_)t;Qq$11XL-v@anx|^M*us|
zx=y)8G~yua8u6t{lD@>RYYhE+zC6LOvqoLs*I*rFCocwk7JuRplzbw!3ULA@DS{j+
zB!u)|xB-|yQ*=&|<e(aO5(K%Q;9(rPQkb~?89@8vLB%n&zEsPVJ?58c#g-%0<mJvL
zJ<wC4nqfKS>Mm(0i{T{4g1CrgvOd0SMUyN8FP+gO>jJ|=uAutYztpP!byY%;`b)1g
z>yqkaV7h|pP2+>fe|5gpDFQ5^cqVdEhz#lq?i*DY&xCFDa!O4QRf>1&^Wiw+d=+Ih
z$?#xur8!8ibO0gggJ`gx>14gySf$vVZGWj$9bR8rD$=W^I%PJ9uxpYhLeXI}$0*B^
ztPv*55;t>$ae5`n6{#e>DLF+shW&u_5=<04ai2F3ME8`aM!-9iS&2$sj<iVv3dQG5
z7|%qC<(%)LVM7%VV~GxalA|Ko;%C9FhZ11V%Aj&-^v;(W#c0PTt^%v6LVo^AW1o^)
z<aP9577@kh@8=K3EM{S!xR@Nu_&$O19&i5niStAf>0x}ZRQvnhp?^BxyNjWZFOehz
z{eACniM(!5PZiatULmaAPR)S>(CETgr05jqAYUO)o{IZTNe*1TB8PJ8RU#E4`U*X#
z@Z?EukKS22MY#CZuwq=)ZX6<R<W>S#PCI%Z$=1`}&l~I@2=mU#hqp)hDpGQaiZax>
z9B-2W=^;u>P@<$LTi=>&*zd3N&q*x0INjtGrMK^yBqM3E3Y?6ZI`}ymHOD{mG1c}^
z2jQ3-q6V1JvV_hB2{onO1HP$-o6Jc<lP1*13^HmG#4+o*o+#nN2N%VrzRe)TW_wFd
zL6NJoxWcw0{fwkh7t(yx-&K^Z>TQ+liZRQp$Yb%c1N6#An{t4aS@~`zuFLIgMmx`n
zVMwCdUlzMMdnYu>Zq?bMsa;<t7c{l&%j`yualW%#oV4@HJVBDB;_d~8ghkE|SksTR
z?-vPY2vqB&*_h1UWk=3hkj^AnfAwEUI7eXXKC<si@}!7QzQoT*9$pAUJu;C?>`JCO
zObJipKqerL;THmy?i7kx<(2F&(~v#~Q`#$tGH~M^^~&-)=2fvDEZvzb=iBoOQUB6%
zF0SZbUP(&4tki$^<KH~}$NlfW{GXNc^)rygjcp>0U@hnW@*jWvr{{i0?bE+s|Np1@
z|M)M@r~LWvpDL?cUq9BJdiy-D|M-``KL5ji`lt3!?bFu3{HN!C|A&A1$3FcZ{>y*;
zkN^08{LBCR{7?V#+z)$2*yowMpWW`mKS!Ru{l~xk*FXOAr`~;d{qKMHYjQQ;>0FuU
z@2}#;s&WnO5BBzk-p%iN`w#!?zyH7g@n8P0>Sf?j!)<-q|LjoBV_q2g-|8m9&e=-?
zuj5bjauiPZn_m8J|I5EpFXx@gd8cq3>-+PEx6iEhzuC!wG{EfT0O0X!FaO(0z&xlD
zjQ8&=!Gd17j{ho)df_Ae6Z281o^RLKzxv0u{^7s=<u5<(%xIY%F0;PxoBRB+X1_TT
z|JKw@gkf-$M1%a17x*`yS9Z@raLDI@bvLsVE%G<#jn$CK<@Texq1-NiX1#y*+S&G9
zmKRj^w-?hteRdPArawQv<X3)22fF3&#x|j9RcT81ep{{X3Eo<~H~6+vp*p|R+B9On
zt%f~E)Bgqq{F&+h=o|lhVo^SR|BdPY`N^Lk+IUAdXg_^BIuP8v)jHkD-&Gsnv{$tu
zlKXF~K`p-3#3c7^wLS42!tFf&^lq=!pBUWVSpDtqS^f0cy<?LT@7uAB_KT&A^6yjv
zI^?Y-xX5?auC0irj0AdTe_6`ESq&DsUH}DuPL+M+-7j_A4R~#T`wRHde*Oh8;Qk%m
z9)Dmd8-g_6Y6?&Owi-YPZ#B`Ud|NFUs@_T<top7BvTMH6Pr;x40zUfp(q7)&m;1M-
z|L^$%KxnDKq5M0e!yU<6OV>f)Rzn=iTTOv2-&O<T&Rb0sJl|FWwCsHay?<F+fBFmP
zmo4mXZ$dx*4jq7SVh!%hKd_LI<5`uI^ZC0<dB>(IyZyeRAHUM`;}7hOg(iBpo&7GS
zKfUTNO!zkz{oiHuoL{cq^9R=M7dw!G{@q5k>umQ{lYqFqKQSZsihr(~v}1kL==?21
z<fo=2omy`<QT%pnz(Bv1B>1*k2eIH=@0EOC5j0p|DoXNwMMU>~sVK=$yoP?kPW!VP
zobTVmPrL>4zJKYdB;OAac$O~}CHcN$x}?5TL;2fEOgZ~jdnMmjM4-Tzijw@qn@C>4
z^SfWf&uPZXpY_Y-_Da4V<o@Lm@vlE#$@dk@E%>D#1>aXgCaW*?B>A@Db=iMyj^&?t
z6X{fsvCjPNP5hLJcwG*^Tx_r8`{4nr_NAgE-&fr0S8x86d|xs8uipGC`MzR>VtlDb
z!Oy&l>t!ut<=c1hbE>niUoEy*^6e1snRfnS6MiM%R|GWhtLmlX`-;e=_@$yG-&c(B
zwNjRT;yvW0%kO^^KV>wY^Q(pSO1>T1Dq7gLo&?`l!<GG)dXju!5pn5XDoXNwMWFA#
zRFvdrOs9((+rRrw{G9EyfT;b_S4n<nY5&p={iTihmmj}=@NaH(`6_yUw~zFxN$}^)
zo6k&@yQ^nT<==3)%%9oH+0juqoOdhFt1?M`Z-kbZjW6{KQTg9js}Pbe)fiLqZMAmx
zFI$7)_o~suiMP<cdN}|5OK7ov>-h6e<L`J04PobBhPTi6`V<v`s{K-NG1}_;ir^gh
zQc)}f-&X`l?w5+9&HcV2kPPp;5VYYZU&f7e`;C`jf6vQk9fxd<u=Veb*{FDs>Ou96
zazA`q4H%%en$JJd8u%pMYP)~usAe_98SpI}QRDs8OE{M~_O~uUe*PUC&<MSQ8}pA0
z4vgt<HEUl+_nXxa1@=}`SlD;f;uHW))hPI#YH|bD8;GCr0$*13GArZ1vlp1XM0Tck
za7x$o?cmn<Qe}<b`*|Wh-wNY=bNz`bw!c)c{d+%$qZo7j#ZUa_XZk|3{yTab(L+DH
z7{j3a#CI-OR*M3oyw!r}ly9qf|5a<=|43_yZg{IH2iv#RK={P@XZa`JfM107Z@huO
zW5@Tw>og8-e0!b7YTY?FRO|j_biY}x&0n?F<{xNn1D&I4TX3Ckt0BCJZ(u9j>8IYn
zzDTa$*lqp}18DE@tHJGWFXC7YA!TnhQ9^!O?bjyn{zDe;MxgOq&Bh-%3hZ{+TD^gG
zzBKmd-@uJL|BY|p?>Yy3@yt;2?SToHzAqJD$xoaLFFv;p=)M1U_F8q|t-o~ji|BWJ
zxxbhi6o1B1ePeYtZmquc1pUlLW}q1O($z1b-}R9GY5{x^{fr~{1|9yPk^a<jMJA@N
z>-80V@7P25<kzaN=x3aJmub5Hk&*77@hc(s*O%^o5&e!YWB<bE@Yf%&<Y$~`HxTC!
zjWd4Ae^$g9UwiwCe#aFSzg`SqL_c+_H~)E!-`|CP#@wR=>1$_S(eHTAf2~P=wQ2w5
z$A9zmKQitd^FQ6u-+TBPYg{t+dfC4o_WyTB{pA{d|MLlpK0dWQzF^`0;s4e2d<RRt
zx848GZ|ao*<UQ5OT@2yy69Lj43L6JJI{?g$`YnP`0e8NVnqdHX!x@wc_;5I*2mtgA
zMVLngn1?fZ1UCtR<e^}+4=25AW$FwCq$6QxR9M7Qk{T3a%@EcfPUw0Jbc@teks%zR
zP;@c{gfnC@DsCyf5QAX94`%=)@^Xg5b(TQVK&;J^<(+fIm^38$yaKejvVi6mrnW*>
zVqpY}(F8b=1k=KTSwEbh`B*h1VoqXX0Q7)VKF}v6b@~JnJeaHY2eNTqL3yFVYw~#*
z569#y;sv=m!{M+jripL{J|T-|IKlVe<_{;UM+E!D2$=}XEop!**+mx1wvWKv0<0f_
zsZ}6%1V)w(9E^%6p2`Cn$_<P(prQ1^fs78}M684DBb-sXAdCxVXeL<x!`oZspbC0*
zIy%y-a67RH&p6fi6;!VfW)MoATxmU@l%UNTQ7Gf`sX}emNb&g*R3TTCNCb`*`2R|B
zFF-IvY=(`TI_GbmPC-of5mceN>kRCN$0nFY`m^zexCTH56Pr;%00PCPd+1c$RaA8G
zQxdvQ@WAR1gB4C4fUf`@tlP{hK&zkuip^*-U^!xw9PZo?E;hp*fMbh|pd$pXM8#x3
zCCS$c&Vy55d~8N4g9|UjflxUOVk4I2V0>3lALem%yD+55fp-h&prc15&jBf3Yy}`5
zN0*3TDwezytSaVGBlqtKygPys56EOf><K5}sp4mQ0!xh{QXtifP4c*Nuso2M794xA
z8Rm9Q4vemGz^Y>t6x_jr6q}K5SAvc)8+?vjxxhiT7n`wfS2FM${2t4yamTu%T31ca
ztT)uuk@DljQYvaheq9M-*m|Xh4Y4+KF!se#R^euF-ZAlTt4;3;*wpxpZiU*ZptM+_
zAwrogB{wcszm)JHAV2s3sX$i0h)}#8b9G~)8^qCdL=(hvcC0GYxB2u2b+o+x5nWJT
zc_g~M5_SsuNTd)w<My7Eu+@c*^ZV?rzRQmUrCc#fY0cZtk%$+dBh&2_v6<50S28h&
zP*Q8^F^<m7_d%tn79+i{AW)0Xfu>qh-3@eil0U5@E5%2IAKZs3fpUYUS_m2K$dDUr
zsNJaG!z*ILP*_XZnp<hC#gN60tQO@KzNOrHmvQgBqI&1XmJePzW8QjiSwf@8uN#X@
zTD>FqFl7GsOr3Gd$SaMQ(^w3W>m6!vAuzI6cHUb?FzS_5-)X2{N%g<$!5!UK8to2U
zS42m5>U)(q8fZIY7`f$Iv`W^EJij4cjVsArJ(Qs3itf4))5aC#x?pyVj?msvo{TH8
zs#6)cfqV}!Z}dK^go%YRRPux?$<87#!Y${wqf`XFL)nR#<8wMeKU~i(l@mhwUrD{f
z>3DFeyQ%!^9r|v%<^&o~Nv1xhw@+y^ko!}tX`IL=k6gkbZjWBri<nFnpCpcf`~tU>
zJX*m711YLD7i*Np66=3Q7TyrWe+PkQRAz(+qFgj{>cN3on|v^|78(0fQj<2wInfdK
z9#h|O@{Pu%S$xZ>AV{9yt#n6-F284L-aE?tLhZK66z*U_4duPNl6wD!Qq3?8)?NgV
zPm0h5>zFe}qh85DH4NXNwZuH%i`exEk&blm4}2sj)vPu(4IL&{`75dA-8AzyvWTq&
zJP47g5^st3Q+#BdzQ)lLdHhmJ#tsh25OK+sWY@+)sjj&~PlZk!#TR`gD@%MLbeghK
zc4WK>v9)&)PR0ne3d8RsLNU9}+ldZN;VY@_0kp#*o)h{<V~Dk}Bacpq`lKhXMJUT>
zM>gOPC3^=;atxTmPY087h#RGYZaGBK-a*NHCHOk6G@lsRdnIqaLtGjaRNq(}6*QmH
zr*?zl8~Cg(Ro_qs<qnd}E5g<SzUnJs(>SMzfxUzEI*Nh)DM`LaeffxLi80YKw4W&0
zJGeJP6zsiH13f81+vB7DM8V#H*9}pyUrF_Cs0Pk&LkZh^r3#8+ss-gH?({3E?$v$i
zE!R4wA^h}#V$JM;CKK<=mDFqPY6iM&bTva=HaglVO*UjqgMB8L*0_&>@pLs^nyiNY
zKvGi)wK|~NM3mmagCBO(IbJU-eO9m68Oq+=@y0_TN*${rNI266&T1k)zmmJ9n!b4?
z2nfMuI`SKZNNM`mSz;>%mAsN7L+IcU3bCMfd_5ltN;Mi+tEJzRO1m?a!WE(Kj=t-I
z9ypVUxV%@U>`-d(4tmwFO^-px_Enejy>e587;ZYaR>PLM0tF`;^Il0Yo)lqI0R3v%
zQq!s6#Ea9BkRvdfdbLqo>;q9QCL{Y+2VHBJOzPQcfU>BeLvBQPmFk-`>Dk${RC^Az
zR)|)oCs%9es_>SpmqQZ<!mUWg^A7&jFs3``VCV|+@buEkx6EE6*<P4zV<e}!61EJj
zX#9vf7+yo<J^iEk!^BG6kyq!6&@xVT*3~o=r**Xq<!MUL+l#pDO4u@7l_p!c%$+Mh
zOA`xA)-tW8E2^K=@7Z<e$}Te)sh_R{&xES%VzlkxgblE>-*N&)NF&sd&no&+-=Qr#
zJ;+Z-cGl>!o?%(01k<0|QVc{LOmkPVP)^@S^ibPSpFPyJV~{ek!Dts<M)ri4Il2sF
zfbCO)$xPMPw|WQ7*SGoy&3EI^9|)>9Qp?B-cO~`F6_H=`t!AM2I$X+6igIE0rM98^
z`cm5mlMY3Vv(7DJBdP<@lOp49YR2hZ?s=?=PVe$9*BE7@FP!}Pd&pi;eSN4J&UFe7
z?%53e%e-j{(a85Yk3K0v=b-z#Y;BxrBZ=iZh-NQ9No`=Z?d=+LpQz@q#0u8Lmf_;;
zwA+#HD@Z>7q^QPY_(ARgU55LbS;7_xPeOEA=nDzRLQM31;S|@KdIm+<Wnshp5xsq>
zRnFl~UYQOz%14r=j~Z+;!57qElMN21Of;p=>|l(IcGNC(p{VJv<bLB#W;&9#e<WFQ
zd_Ur;zoHypgWtJ>S2jdke<dr+Y!(jAR{IPbU(sZR7lUjx8sR`xMUxR;EUD3ykEA2%
z`xW8K2DfSmve=OaKH64GP@QeFsXX<EnC&|pf+23J4yR#=>%POW7>$1EzL81miqLrZ
zCqv}-9huRBj948R=A+3f2ea&z)J6kx*(*TXyDG5VjuFZx->GEVWE(tsHW}a>Iu;E2
zH<r(;3Lk+pWs`Z0?DWy(w7#P1>d<qcLc!G4_sGB5Z|Ki9)c1j{p~*xCWo$J1tvdi1
zA#SfL$)z9*9j^7~imKs>1!iizG-{K&2VZQ6609SKTQpI7cd)%)QSBggtq@HPY+O7<
zlLH$!6VV!J*E()5LRkVjm|UaLg`GUEx5&<v>TzWb=o_qESH#9WOV|K*ofQ4h{@xBy
zrJU7uwF6M)14%|`AAR0C(6Y?wUCPhV^?baGXsnYM^@@gmbN|tq%b*tz>MdiJ0S~HY
za)S<jZGV}`uBayfR32*3m|h85P8w4`GRVE5>#)e56rG%uw7<bm>PH56C7$ym`x|$N
zSHf0$nOZK&v+iX_y7DOW<OlU5)7cGOnP2Jz>d=vjJ5^Vvg^p`iPgb;Ecd~w@YwOxJ
zCG~NW5Z#ab(N5&7tZwjpx){~E&n&UgYW_-aBj3T+>4#Rf6QC<I+h@H}8QGxXbf$8+
zv%m0O_1S@a(~qodP;I(++B%puuLO<~ux4Hf8{1jJ*X<i4kWK9yZ%7{L%7}NTN@g~A
zFRuin+%+bd*`Ty^&`Nc%SNdt%BLGrxWsm59m0k(kzWUIWO`?N%(&K1^<w5n3QyOT9
zE2*Z-rR7RDaV3R*mZ9zCI`fdB4IqbyOl@F2JYZ@kQp7_xG@v9NqW<jQWb}}yx)>Kz
zg2#eT(ZOfciz@LJtG7=Fn8lT+q65w1Axj*178l1|2cYFj0*W8(f39Q}9jtvGaA|`|
z@0PJO0G4ur;jClnKyWeRbs$r&<gHa5q+K23Q;@|R1Fz(@m;qh6B0jag!z<xa2j1J%
zQ!&4j=#!3YfgZBF@sC%6-Jt4U0X89I*|?HQB5)-&dor~nYt&!4*n`$FC<Ctm8v`IH
zAIXE_{k{CvvC*8YVWbsw5e4?}Eb)QJtaZUrRjkR9vl?klJmjnnD6x<=T?iE~*39Zy
z;Pp3@^5wgX<y`8w%x6NyxxCd;+50{cl(H8>L0w5j4AADSFV{W3JfWygLfyjme?^!L
z>=EvAPa~6|yS~5NYTO0O=s>Et(>MlF<qFU^pepW61JD6gaewXQ0<5?|RlV>i9|=ui
zz){>~3!f_Sp}^<3P*hhmP=!xTP3W?M4>X~Ygj`AWf6>toW=~hzkba;Dfv39V?7XaC
z;8)yf2|pbG7I&G#hjATpPeYfw(>(rYS{KBspUDxzGzQGYUA}2(ba(lt55q}hKNr%)
zUHNM|ur4mBRtH<EyUb@8A?~t<VW+si4(pF0<1SMeOs(#+g<<=+!xTm$$6IE1cPR-a
zLg~ot_=dl9Kw4axQ95X3uY@gugV~WRr6=&k1;Xk;zPQtRK91qYU!AQsUEG23&0W?s
zl0&+1TOBYJ-!g*%RB<4$o)WDTyp^&mTi$9|(Y|3V8*Fdi^j2G|8$cK2%3#3zrn}l;
z<-0PuT*-a+n;z>c$kT~4w~K*L_zG$suA~MPDAj;m4fh<6Q_mO>E?0zSLcs~3Wx%Sq
za>7^}Rch5yI9+{jRe|=}8>O6kaT*$qdRM~nLv`)NyTmIxs5UW?P+fbe?NVKPspW~8
zT_}}VyQi9lZX*oK0D*C(p|Q5I#6}l-Kkte#9I;(6EW_E|_fW4kIx*C(jn`YB<Wr*R
zh<$lb^~BgU&jPzuZ^V_h#>$EDq=-#J@d;gJaD7}!Tl`I~tgeQgE332Rz{=`s9lCLM
zwGRC#l$Isx#W#qKOHi+{@wo?MXnO9!QYp*WDstU-Q*Tdge!gh-T8BbhFnbMo7F`%D
zL!M4wW%XJDR{YJQV?eC<q6^x9SaD_6F(mTz6>1skkco#%beG@?HI0+s3N&4YjxV~P
z4UWJofzB~_3a^Nb8wN=qv>_d+FV};h0SVu-^o`!RqLpiKpk4|42lcl0KeJBtM&CD_
zvYx4<YLGKa*kyoQ@wL=7sJFG$F4WsvY8R=qU6?I{)A&l*^u&}ejtJ^)Ew#RC!Y6f^
z!GrB<s&yRw77y0eq0iP(pEr6q=q#`TtoR!0AT*j12Hg;#dM$$;ghE?N5@SdO>j}!T
zM7{W;6Z)2GzD<3DK3k@CBTGOk8uHIx5gLVp6C&$MYBYvYg_w4=iX+|XY83~#)ipM#
z#6`3FO6mo*FST;oU5G2QI-)5^;tHxSbU_;~oIVniGH~^1;&El=1XmfdSX=>Hfohv{
zLL2VF9CSHPiR!^@x2z0Tg&d9WSO%z!&tSXAZ|pPFa8A0<P`fzI%}_J-DqS!wtDDHr
zmMSiQE2{3g9yGGIu6cu66bQ=<YH>PUDuz7JKDPz|wKz8iQCe|sH4UveVS+y?szJ~M
zH{9U*+-e=Fac&LkK6a^L<hAm-*m7xRpG!?ceFF7m2K}jwPF7HwE1=o{md2Ii$!ueY
zQ*G}WBh@&r)1APuCq*^HiKadO<|Cm_rxZCrGd^isn*pig;)FCLJHHY<w0b`@9C$+K
z&@@7s7AEY0s1`Hb(*_vLm9X*Drqk3iPMg!vGIY=tu<d$e?GcrI-e>=37OP+S+>yiH
zD-r5bl3Rmb>07QQX-8j4ElAqY26)VsARC7PN8%G+X)C0OPr9WI=olY#OB>KJt_)UJ
zl2)n<A9h87YHYpioGU?7I7p78w(=l3<f}G7a$Jxx18cbt8PWqva@43l>TkH(<l%0(
zrV{#ZP!R(R;{tLSa7!NvN;!{1o@zt-sVm}eq5H;G)1~`{RP})B19;^rQ3c#@{2;&K
zA>;ca_aVa@I2ae8>q^St8Zw#zKJ&q^4OxU;39<}x;X{TqChYM++_WLLu#c%(f$AGG
zOZNf#9s$0)lH2N&lA7kBW})`RP_s~d%DH8Qmbn7J+6{0S7o^JuRNtWO4QPxjFP9}W
z#)qu$0l<R~S>IT^E=ZSQ$@`G8joigPXlu{XjgJqR*0U6(AX`^Z9qxKC6y%^|+K?W@
zD+AaAQ4NCjcWwr*lwbznj04qWK+W7TTkg>Jqp4{e5r=H_+H+ia#0;sB-KfujoVfy^
zL=4cGE8<UbDcDil^?I&^P1mOCAV$4w0z0n@9cH;TyU}-T*u33jqGN}5gNZ(oyWE+u
zEJapN!HxjzjGOH72^DItmP&;_SHz~EL(S3D%D*|nI=DLVVg`7P7o_unD3`cxH4GhU
zvhqs-yUEB00jwiU+H;x1JL+KTm^f~lEcEGF!d?Sd%$2YP&znZ;e3tf8*0d|gg(^6h
z!6tH>dN7oqDOdOv)k~awa4J8Wn*G3Hk@=3S%P!E^XN>g&HVp48Dbx(Mq$?SlmAUDO
z5wk?LxEaqpK(<^7HY*@oK9VezQZxFo4TiJ}wRI(R<S|*)6%XOo^-$<EtAEC+&*;iF
zWLb7o>hUY8+0u8sQpZ_S!*GOVW;esp#QV`haZV(P%htSw`m0{MU{{7DtKLIDzO8jx
z$d#A%NfA2${ialKhIFppWi{hS=fYiCo%)`a^u=&8yb`pHlb!O%8OYhLgpEVzb>|hS
zt(`@D+yJzAr^O6Bi+7pKg=g`;^-!usLA7i_Eh-0{)j|9UI3lRUE~9x-Ep{5s$d>F~
zDtJLF0;*-Jp1@|I7yD~5FDS+?iy6ol@3NSYKG}uTvcke#0TN~zJRRO)GQ$^g%WNEq
zvQLc}nzGZhek{E%F0_{c_;MxKYIe)gs=v{BS<Jf@^5cSbS-FtB%REM+W$!YOkuBLl
zNM(Suc;(l7AgaF7NKTN;EwULX#7-Bs0pxNexH!C`TFPBbLnU??+l7R2;kyh-81J18
z8(fpUt8FMmxSdK;W0XY>2cj#<A2LZiDZ)mC#K$gH90QQW1@p23vUrmv4Is<o?WogG
zaE-<_+^F89Yxl|$wiWncuY`LQe6`->*oHs%O4v?mpesQ;<wm*!Tx4ERjj3utn<?Gk
zmE?F_1H|dC$w=QD2MU3|j98Z@3!7jUp|%WQm$tuDDtBp<!y7q>KN6I3l{Hz}aO=AO
zS_ap@mwWkvC{T?p)eqPRoTqJ}R1+&JovGuUm@Pxd_!Y3((s)f)I`J`WqEtQCjgt}U
zqBMzyV0ahW%8+>1n|#^c(Xt_Y<4Uq++0#g}>q@U^NV0n+m;l^1Iq_CcimHq9XBTFs
z$-*XPhB+CHkeMcLHZQ`wNmmmx(`0l5Hq&Ht6B5&CP7@K+8nKdgAu$csG_LksSsg8}
z18<pKudR0<S<cK&y9LiOP&sVnpE8g=>;u!e$RPHS<qR;)K1V77XqbKE-u4C3Gkwj#
z$6N{9-dSS12uQf11;Kq&x6GF7ySWn1+6LL0OzFBP-bcs~LxR_RWJ)8~$3C)^k#=<x
z3}$}+StfAZg+D1`cLTkHr@QXdvy3eP_wJj-w^kSPyQ29YNHUSgk+U1fm#t)$1|pQL
z>^D|qDJkK7Rsv+MfNdYVdm7UK8f@jiv}m6aq1G0SBa{Y5-q0-onE}+YkCZP!EnDy}
z%hZkg40R1D8uyW#J4)N_L*qF*-jFmhpfDc^O4p*?M}BU=V6KFHGt9R9+(jLH1#Gu=
zkY^w50Wr{jL#ZZKp6wVp8u_(jU@-k1-@s_}wF6gk3IAAaiUJUuM64{a8;i3quQu3O
zJ`$8Z6+$*PAVQnqtjwi(e;z_sUs2AgGJM_?oH?s;)NroND`2y=d_NMDa+q82Ed!ut
zGbN}2Pjdwvn`eoQmO|VSjGr+eXtn@dhQD^m&W@;_Nu5TZXJu(WC0eNUKBsyo2X+Ly
zM{_*tpV`-gnGfk?%+8fycfbtpkSz|Z%?=sk^(LOJq^1V6%?{e)z}jr#y9`*H9k9iL
zw7F$kl?k=E0<;WZ%?{b#0M=|_zA{y8u8!AVeL4mO<GXN+JLIwkv~df}Wq?2KkjuIt
zl23{_0z;2sZzr;5hdkCm*6fh|4P?!Z*JBN6%?^32u@hVg+a9$ZWRYV(xsvii09tbe
zY#h9ggpXZ8pbj>gGqb-itq%^HTW~SMez=3ib#19TWHw{h-669XxZE8IUN+!nb~HU0
z`Y`CoK06ESSlNHu<;5=4%#$KE4TUJ!m;p+2CD;a`#jb=cBhLPc&~$+tx683zig3Hs
zH-OXIWssu;kH!h~S4VIFWj+#=KxfK+LH8-~mX-DJln4Wa@^iVmVTXJqDCJE1R<CL*
zu7t;g1KsB|#Bbv3Ey&nSj9s(1QK}iFQ+uRI_N1g{c>pf6g#{a69N#`w3tEmSu2Ebr
zw+zPtlYeig%X+|q{YX&CIiuHlzy`h&Jacf$hI#^(=0oFyT621>D^2+=vstJ$7rJ@?
zA+z1s)WjMwwKQu$riLcgh|txeK^F?zHQKGx`Ot;Vc0F{Vv-L^d^4(UQmh%-<U;Fz+
z%rxEAS5lpCnmLfBT@jit)h8I&0J3I#`)B^3y57_@be}g`z5}?L?M-cewBJ5zw-)Xe
z5^MlPb0rJq)Yw<RcJfrXl~P~;L~|u<r3~IJB-p3}?%qO=3><>@4h<0sa|hana@?Vo
zPL=R7s2#Vf8ED7t8c=D+-i~QKm3q7)6fc=&I|@`Cg}f<Qy$=9yQi8Pr=uL{S#DKj?
z5kI5E-=qZ1!-0_^%vUd;=SQR^(L4Ly-bZzIoHr6zRGrrw?j3y>SbhLdlcK_lj`9qZ
zh@H3WsL=5P{-qSLxzczk;<wn5eX+?58*pBw2=kW;G6kHz(vT@apGrlhgk2alywDPW
zuk9mpwKnl03SIv|hEBOAX0cPeP8bEKNePw<05vJXb<F^zCS?nPdR;QPM&Br6aHStJ
z#Rno)2XHtkV{5ynoF>;myljdV1i?x<C-oqV4d<tUK-`qD2acgl4YnLaDO&X)=QxP0
zA8>7dL_>WFyaQr`1{~xm!ac?SrY2?R)ZuFx>eS)vntF9Ox%R%i!=Ca0HQ>Nc5qe>*
zis-pDPPySy|B5i<w5SFy3O*vbIS1|%QUvW-FrAb@O%H%@QdZ*w2qz`@v;nI5h?;t7
z?3U=)27>5I*7&o@ntYhCUk%0V6VA#{iRwMb!WuU48f0Q!QT5#QsRNLcB5p1T$w>*@
zA6SddI<*pIV+~wMr3f?^0~c2%!<^4riXLiz;stx4STEP<)O?054g~ifSF)<iIa}<Y
ztIvy_bQIH;{FHg*8UWO!2oK)q-&T(|*6C}884jB%V+S^evDJaiq44ZA%x`h2eME4i
z3>|Q+hu2~QX-$gQ1IK#sr4C@jOBr?|(0+VGQ#FJA<YmS%6xqk4PRX3J!(P#zGwM<y
z?ym@)sw390QZXq|TU@3*W{p90Dy04xRHsf?>KKR-D_P^uRteC9(Kxs|YFz<d0gqZ^
z^eWOW8XX^{o0{(&tu}^1wfP!zfH#z=&WB@^-t?v}Qg6Q2+o0a0`8KFDU2$+@P-{94
zU1LCNIuBk0XphY3#BPFLy_FTmN9AU*k9vUA%8i!YpduBbe+(+peQ<CZU=*qhQs~0W
z@xHbl5IrekYgE5Gc*q<;-h5;-&IT3f=H<m0yNcMn1{LXcZJ!`=N*U&<^yqf=k$QAH
zis<3i1~aHd_g33fqsmS*2GpoR00!VbDT1B>-X}%a2L_dG1_F#hO{++Nkx8c%1~3ZX
z^OTHD1z)zl_(9bxT>k*xD@A-*y}uN3AXL4=_m4r<yQdyc&AWBz8^Eew*)7kjc9l?L
zOsd^Y_`#S|yIaS;Nwr(i=?`RBw>tSv=v{>m48VV`D2tto)}#d|H8Z0J#-wIe2*F7B
zPYN)2;C)gA&)=9;r~c%yc)4;#7#0r&6DoOk4FL3$DdP~RlDF*rNtL{1?@y{^Mhsj@
zy~CzKP$TcAVNfe?nG%y)dFzxwluydo2WVvl7YyKhQiLu{tdMoohl%|i@daa+T3)pD
zC$+NT0<Ne!iNJs{p>dZO%&!QI%dVfBt!u-W)VRy_aBAEOFQ`X(m9Y5(&66U|2Nmwp
z>0nafF7Z4Lut=ti9dJx8VhA$vY_8(9)nH(BTMB0eN2enKpxT*Yj}@tL83QmT&ZcW>
zYoFAni!pa&QJb#vpN>Ucx@6d|#vV-W?W=Kq2{syw%2dGuSA_Ycr*%}Np###QI#u|<
z6=6Dg99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_t_UwihW(<3g)&`Krh@$skjbWq-K08I
zD8N`$r-^dnv#Ou^rWds-9z$Ka2wu7(yn@D<y0NHCmyQRkl<8_}esXB~pcj>C#t>BI
zk?i3-Y7Gb3se{1cL3ZjOuy~H0N1O1X23F+2SQ~@E`=_>@p=X!6WuU;5lIpc$1;(Pz
zouPqH<tlz)EUMhP2^b6dcDjZ}eLHy&SX8%)Fc^#KcKSOs>Rg2xjD_d0@xZ#Bj$*A3
z1sIHlSmczUb)JwFWH1&^$Wx~U&{?O5Z6EHzQ&vK;VyA>FiE3K024hi8GuB}2RwW+Y
zHg)jSDPU6vE0SPr>R^Quj7=4cUA;s#76K>6rV2(h!Pr#7Q^$!-9XzM@yiF~v$b+#<
z3oG#83h>@|#@L;2?cHBCPr_42gALWIpn<V@7*^cC*wnlegzRJ2A$Q8`-&CnnX8)#2
zon6nSN}c`f6c4%xGZ-5Rb;=pMsZgg55L+2j-vdMiWPU_VU09q>92dZ?p8`I-^e!R|
zKA+BpQbpRsv8hpq4E#-v%AkR<udW=Sf$DHNq`kMJ?Li>Z6|EBR!PJx^^k5!M6<RPh
zmFJMdc2j*0eefIVbLdR40jf$F9v@gHLpJ}eC)b}fqhs^uRGLG?lEbMrGhATQq3ctU
zh3-_DiWwMAl{soJeM(kqc*t;f>dYa--BAl)zEfq6g(9qfg&qv23LUcRojP>Lu6O8A
zMIQ{FbFU0#ygwQ3UPsm;lijIM6<;u%3U$0DyN@b!OoM}vz3$YpW1xsJnA#q7qmZ)t
z<{kP~5eLJmUlnvPoH|xP2g9dED(Aja#|}d=pDZihsb3j|Fr3HN(TPqNPL-?3gyGb>
zL)N}S>kiokPOV$P2@hmgAGGY@3`z+HOr<+y+Jg`xMRXB(X<o%245#8%1j2ACUWOnH
zr{1;mj*yBMK?qlngHaH|aB5yfAq=PLwb%de)V(JEzf<)ZPX!)T!k*&Pyof`1hEw^P
zod3?_uVNDhawesSGY}lE>;A^6eifiFoF`k8$?x<jE52Yvt0Il<pk`Hk!3b(r1Q=XF
zeUzr#fPfM;fvK*j-nlI`Mm=h}5D4l~g(i%k8Z{8w4e-aL1XC5%ql`}&K|N}^5{N8L
zaz%`w&)J~ZgL>9<YzUrIP1b+#q*?(74`iz(*p`BN)y9`c;YIOC5LBV|9spu;dbMN3
zWIuHP2;~pgbwEIinu3Q1P$(%wi}Wg+4h}(GYb;`PT^@!gRcks);8rI^crd-n3U3&}
zgQ>lqf80iu4AbdsU!MP<#?2sx5v6Sz!|<e}X1B}U2eVX)I3rZIU5@{ty6vyyKcH{B
zP5{BvYG<WdZ(W}Mphp=A2cDAEcoiNo0zYBv^dI*?v0h@A?hks88TD`_7=(=d15Mp!
z*B@%?F5CVz`s=%+j2_FlKh)9;h8U+;i49Rn_bnB8=qK*7><<;Sq9MkiqE<Y_I8f9T
z55Z^E`eZ=FI6UhrB4Ql6oV#uU4mElg5^J1N>0Kv)LzS+`hyjG+N2C+Lp$aEQLCG*g
z><b6_S#b{IP(OE>@`w64?`$84&~@Dx9I9u8K#Wrgy6d*!P(k;hqr{<#?z%2G)X-gL
zf<q0hP>FG%q3bI9fe32__XTJ1UFp8yEDTt<kVBPScj@&c>THEfj6>bqW$_;>Uxho2
z165nW4G%=<mF^4<b#2EX;84+a9Rdy&ZEti|@F{GInzre};84{nN@66cIR${^jYCb_
zU>_XnSw%^VLp94ViE-$QMgpIwWI0-ePFzWKv+3Y*c*t$^GTii}=%&!pv+)e8@Q2x;
zYa8zjW}~WA0K{xmwaqb4vlvNJQd4y$=$501E^W0%H4CiGQ?hymilmqgMK(@fa>H?C
zHoB4-NAaW#L)-XCt;)94I?lWbu9%Gn+{UBFGaEIwf+=R>@wH8Lak5W5H(U`qB@EbX
zRK1P&0kcu{X57SVP`hoYo7B2(ypu$|+jzd1je55Y^?<s!4RyU#FPWA~f`vIy#IiJX
zfZDm?fH51jGiLQES-pQ#^E@3l(_rauR?Ni&5%NbQywGe^>kPcOl2v66geqG>6<36=
z>##5zb#~*;z--jn48E8R8oM=3CN*{wr{8Q;+X}*%jcU6!b%I)3p&7HC9|vI>IZ<U7
zToIZtH}w^;`BLl$Q5h2mtD~@t*>E>`4$l%Zx2%r<M}%9xV>k-Bn275-h`E@({^nfu
zj*juhV1h#YD41dbMs<$sp&fnmLcz>}P#uL^OdzPvadoxc{y985OlXF4cyxFs)W=a^
z#sstaQC!9>`t_77lmm6x_;|9&mIubjdxHs$d(KjoiQd8XpQ*Rc(Vf9WoZ~rD9Vv}^
zCD;*wn7R_|TL4U5NnLba$v`dkW?_DLUoc_0TnVRP)dUZML?#TS!x)Q+$kL-2i<!`<
zb4-uj7=k|YjvL`CVkO6fSLyz|YkYw=yT%u2v}=5kjnaglNU!jbpj30#)P=yDF_vO>
zczMrhYWUPTZ)*2oq4NwdVaA^fr<gGGPlzRGehvaBXzNd$6i(38pEyn&q4_3wg-+0B
zp9YWP38~mRz8rz_u3(@RpHmZfCFm@ULC*<#@h8qoA4!((U-~8ifI0z-egge;z)O19
z1JF-L0TvVBr=tjqS@@?Du0{<b<VX2TK%EZ5DJFnUM<Eq6VNOT!6cZ??D`7)m#X3Uw
zO`BQ5w{H_8S{mcTkQUpW=)PhcuPFPk&(<dTztl`=$rDRWEevRCJI0~^#AI75M>I9U
zg%OqYKH*(BG1W3)Q75LFuKndG<YE>o>cr3>H`c~r!yAK?r+$Lp;e@G{XYXi{Pw+z=
zg-T5LXbwUpCh`*9GP@FJnRfOB$mvAab8Atb=z4DOJ$5{}{+W{iwHDIH06e9n@i({g
z$^~@=`N2n-<a0Dkn?7!!kB;(*&(X7lFSUGyPl{LtT8jY>vs{x$8N(;sm&f(x0-JOt
zz}H-nRV_ZZu#v}u&xJm6dgQMpXN`%&pA^*qWMPkyCAM7V+HvPo%cMI>Ej~w`08fJO
zX5xhovxHBu0UcrHCh$WiBOE56Lq`z~&xG6jD8ymHuYP=KUZIG5Y4}h?g3INDa$=X7
zUYOYG+Qy_#4IPTgr&`{1<UYzFJ`;U(1h<<&7M%=}n7E)gE(5tPF^<c9Hi0QRij$bQ
z{5Xn=m`J#H6c;f^pt}R5JT4#M=dLKfMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=
z&~vlyla6;a4IPJAiYFzt__|t$*7L5`q4|__e9o37e4!K8?O~k61c>Mg@KkVk9i=6o
zxK}$0m6*l*b?OG_fh7B@*ocX&l4sNGMdHb$Y~&N!DGwlZ&zx0YE6{w3l$d}J9Yso9
zNiN$RY8P4T4zrTaf*Bp5>n5&24+1475JqQ*nua3WK_AKl!07By+XEw%u10##BZS_Z
z6aDjds-W98P2X8mbXV}!st(HV#WnQVn^OhNwq^N(7w>HD6p1W4Tb3`7MQ1NHyl|@6
zOHJ25p1ssGR2$Nj&jKGE!R#ik?XLvB0bK203ESQ^#Hpqo1CmJ%?!p7i-BY6KjBH`R
zg^tj2v(Q3Ufb9fWp)1J_J}Ig<MSB?(Ku5{RYXGv1=Rsdg&42**Y*Rz2-L`2S4(8X`
zO8JM5@{?al4XDi01@*UyoWGJB4PE6E@R!5%<r5H@Lx9|8cz_0-EiGEepd(P*1TN@o
zI>{%XKOYH7X*8^(o<RF8nav;>J<3i#fhf8X>=i{;S`T8=BTH-+2eNfg$`5+U$_Aq7
z6ei>;NseyG$}T+7Su(N#7CI|X$`3(ExJjC!E8;UsM_maYva-ZpLuV?b`IS^(-%lAC
z!_V4k2}*O(f?lOEmkj6ymAS;IIe{2D%4$9r^yZQY4H(f`GNThkbe4?hwK+&y(SQ)0
zwbVFNt5Tg$0EmuIbh98tXNe<d0x)#eR9jx7q799yK1zl@K}UQ5sk`M|U$Tz@Z#+u|
zGBVa5raGTM0i8wn_e9qF=ZY2t+1a7qLvgO5nS<h7Lrp_*zRAuf*8LG|ZhpRtvt(rB
zyEzL+HomO0=<~jk93WlZSFlk9U;l=ZTr#3Jl;q;qy>B1n)}9+Ga5Z%VDiBG^ClI+u
z2)GHf&sjjhKeNC-XEk*M3UJb=JpuJO^Jx4~fl5+7H=>n}AaN7h@R>Bd0c<|=sIAZ0
zZ-&~z*>A=>MjZZxkDD9HPMOLl06j;rwwc=Kma`{M3Ua!qoYqikSAxz#w<$6C1mOH6
zfNgHXV4o?E^@eVnTb+Y$n{rq0(rr@?>s{NybC|z;ZfH9}*RG^Sv{A~hd&*gz5TRS9
zjSHLNDChYE9Oz6rszDZXrp#@S1)ZtusR`)MnKHOxPF)Ef1pPPVwuV{uk)U)JyV9Fa
z1WFv@&?Z7+&y-1yh>J7juSQtLbEd5HLJ^%QBOM^3lS$Ag@IyyHwh8pmNh9xpq{b&R
z-Kz#$#c@%&(<cn*BUsyXKv~X|MUF%iS5hPNIxi|S`V~}HWp6t)=6oI04wX6OpLQG=
zCvEc2dE`vl<2bJzB}bn=xJ+e`11EGPY#Lf~$}L?ep)+Km10?iZ5n6^PR7un)h=>kA
zaTD;MGi0SFLg)<91x=jw&XAFw&C(jj;qeF{H*vr`1LiogvYZj`18Tog()0<uPf9TR
zP?<xXYUfdNI3AoDbI4H*@Xr}?R0I2Sgo>NM{+uCL`@}*04B6{-mOn%0I?~{r0Y5bo
z<s9Wue`dwy9YXA;=h+gu&?kU8N0_(?Z^jw)QkT2q^Y*5?0o|uW=M#RDBfQ%Lj^|4F
zU<5>7Q9U_Y{ySy>7@jlaqK<||AhSIEIcK~l^1zvK(Bg(u=nQ$ND-iSync$%1IK;Yr
zHg#lzI!bMRCAC;s%1M-$8jiCw<fSGP$zjs+SrN8JsIysNxL1Nw&6(WP$ZvH<d&dVo
zH{_;{nI*OgJvU^51BLUEpi~=-$>1)B<T2UXa9SSI*N8ypqx9tyvCz*UQf$V~e`gIS
zIFqdmN9~ocXV7sb4xb5s@3BBBd#0}s1U$#+lZFrZnC$C7Li1xXumQ_CCL=qMIY$}J
zCvZ7O7_$is&auty9T1#jvZxDya|LV&CqU&zpMc;TK+K*JdDUW5fkDZl4(LUrL5<k{
zqde%(%;b1SNV19adB^0H4roG?R~nd{W3s0Ya<?9%MO`4Bqg3b<_a6sfvxy6mTSn8k
zMY$60#kgv@BD8&O6`9<)syWP<J^{};CX>6+IZulClZ`rTxMMuBuyLhyOdt0tZE1>9
zpP=r#A~pqeX)v;JS9O#keV$PzObKqakIAtO?9DMbwvmPMm>k>4RCx@3?SkhVQ`Xf9
zc+Md_Z33KgOs;KUbB;ANJu#kgpgkqp_z@pd1JXVL@XYD5vI{$N1Vft#fTz>t@dk3{
zbei3HA9|GCeB#FRblKFnRlO2Aym9w>MSLzaTc^kS)Tep{95*x@5}ZFJsxinoKc(Bc
zoZjH{JDsLDX#b8<pg%KjsZXNKW?^0qGnr2yUQU<&48Y4rf>KUwm%Y4jAAdSs+zXfX
zM?kQJoBh*iL9ZlWyk+=S7Sif|MEK{LMS8feq$ZIj_iE5|ouBS%6$y3vRKxIv_K8yU
ze(0%H@@lk{T&5;p4N%V`+}3IX4H_$yg6pOZK*4oW2cYD-{L~9@lf&HPDXD(ZE?(`U
z<a$@bP;$MqVIW^l?`j%quXi;K|EKbmufo6_VZIiyEzjwVPlj`|H$6BHfJ$h-fa*B{
zcdfRw1j~B?D|FgX|Dg)oVJpyt?Wh$fLZG;wRav`lS*_Gw(T;i#W!R3U4TrrJY8t8Q
zjv!nsAuqSQCx4PFua#N60Czbp)HIZ1lb3n{>~dPD?b42oXXyp3%W1Bb1A}zZIWP46
zD7E>*_>S;iE9d02t;az1HJZWC0z&SJ7JgDarX9S1v^&IhEx=kD-PWrE{(Bnz){DTF
zMz{5q<lAp_TQ6_|omLk0>h*gdi5I~yZL!^Q%3J{(?m51xR&fGU8uMoXxp)K&TSTa|
zp{_xTHM*?V=Sx0qs0OuIBh>qfYGDp`4k}AY$ye<TN2skuTuU=;fdsZRQ(Lnp*VGb}
zRx`FVF}2XLPl{?th9A^$x>{aY;^1(aYh7*N68{LzwFqEgit?1y^y`Bz1WRjQ>eTXT
zG*cJYeLkWr`Hwh9y(+6Rl%9M6?;OHit&V8ND`Kmq%&vs(rZT$%Y>VKS4?MNLv^YVu
z$pTa+2+dkR%3J|kz8`g*P_yMB!|p&7ObD8_0C9=q>eoRxXg)7%=nBo}E6JT94n5RY
zRDFSmdZlp^hvxJx@0>W=(+d_&kfX3f)n7WO7fho#TaBmn6lbaFS`twv&RtqS$HZA`
zy<?nG(g4SV09(td#D<M8adJe45l91<*_o31#i*`L^>v_YqOV>E#s~qi7BWO!2{sv|
zkhqe1?##d0Po(>~B6fCS4Gy(j3Ni%MTCn-!m>SNJJ#kD8PrQ6X!waw8)cC?8G_}3(
z=8aJ`3pqRDbTz*5*>pW<qsuUcSDwW_We~PJDXHEx_0Q3thW<HvL(6vo>Jq2%vB^IW
zhhFLhs7u6A=SpQo9L-FrwNTdbRe4vQ6k%_{QTIyNczt*ghmF^lc?E1eKi&vse_Dvo
z3gtFmNG20Pgk4GXQ0f+tmn-4^FmlLOf)2uOa3$y<{0di69Ry8J5Wn@LC>LLN{^0(a
ze(QyFKN0j>FQf#D*lP9aw<u2F2ZEY#o|~_vI={12Iw4}I8LN>jwSwrOP*U>+)J%lF
zXhc9p$Yus8CWOLT#lZ7KO!Z};FZ4+-_^3V-l(H`}qT%9-U_ix!8!Td|nTcr~>fFSv
z4mDg)Wustoj?7`cfTRf_wib{y5j4jEq=}F{UO1WvBf4z?IulBLz5tyG!MGOOixD!e
zD+gFg^dQe7yACBNkk*w{f4d&*=x@^qKw23=^LvyI3|Zgs#70P6!&@66`+GnQh6pwP
z-H(6s+(p|yRX;y-Tc5fgrPVy<_?(6Q?Z5u<pMUfp?eky#?|=B~6Z|%6@B8ZyP^E{+
zf;!S(#Nxzs_<3T|(CHIX6!cm3Ri8#E4MO*u<(=;1UZ0-7Y{)IM1#IQK>$MxXu1*bE
z!CY4yHkn>Uy!asXaadjth~n2}CNI`oP_dFac;Kv2?1b5sB!Ejayerah98u?prv;bT
z$=SeoXGVa$aoWKE+b#@6Yb1W_0u0n){0mw*_m4za2?qj<2XB!8va76_^qrS~MwexB
z`t&acA0Bk5z6Wdz#U|EDn(MPH=4S=X@u|N*e|YO>_iq;xX8X%RQu1{zB(7>LB)Rs#
zEF|SX*Gi&GHCK{Y^R<%R%*3^l7B#}Vl$45sOX*E4$fcx6(swB(i@d`C{gPckOG#1K
zT1!XKRPS0+;NF+DB!0-RYYA~k?^;qI{JWOozg<gBD}!rEms40vUqMG+IGFW|mE`i#
zaU~7=;&d#ZM#!<?I<e81<VtG4TuGl}-)AX(7Es@JGy43oX79fL*h&g$Vqr(4S0TFr
ze#;PfHumQy9HqOriaR@M4TPw(!M+({ZY+k*5N+cF7SBk)C>TCNtl3}z4W}&-hVIf7
z_^7gQ#b`noM&e1KDnoG6f-i@#qyRXFxEBLpn-B~X-1R}S>{$6Xe!eg}d`HNQ5JjbZ
zH%M3xAtvpBMil{L0mnn+i-48~sTT`;{-glS;=>k^HWC7a5TnUf8-j}lwC~HJ4IbPe
zJTx5diF&@i`w%)5=3R(bu`IwRCADQ2%0Gk*MI1l~8H!vAL6U7S`-Y2r0qnm4j_t^k
zrWm#(FbrA*ux3O2+O&8>{Ms;zgQ(H6nnU!Au&V>)j4-_8rDjCvML4ggk?SHvtbN*N
zI_a20o{SK!_5p4+fE2|!BZL)2mV^*66x&;fWwA~#@e*hwjwJ*OMW{;v6^b+=A@=Np
zLcUtCVLu`6Y@{6tVLwm3_Sm#2POXdBbsc?j*~HeCcFKed>2DkoL%fVQM~0xINRtqP
zjvidW27sbaLLvS|oQXsD&N?;Ua_t2NC(A8g*}>Uz!&QcZcnHjSGa_WMKKHMB_2A!g
z(qB!BlsH$APuzH0yvsT`b8ZG$z!`A``1;_mh|O#1a%hCGqHuY{rU3`HNbEYSpE_@D
zp2QL27Q%!g3hoN<L>x9ZkKss6bOm|9I8lp?-}ec;9(dPIV2RO&I(2Z2&GR?CNU?c=
zg{(`lX&)g1FrXU|BN&_hwu1xb7L2U7hJG^6>PoVw^uJv}b(IJ74&U6B6hqRL<YHPp
zkoP-1f{gYCMJLE;hsQ4j8SRbc(>iLX%=TC~jQ5HHjm5M06_j084~0Hl^0@VKUtS3t
zh7w$%R-gr!j5I{a2FTBz66G=zPV`E$FaD)gE-L{;KNeBFq2(x*%WZAVOD*dlDD(<e
z7TE|+p~QryBv57WB~}$S3bna5N;MSv+IoY|Bp9?;0=Xw8Y__zfz@Q&<4<lJ>25NHg
z^18#{|HPVKs@3b^=i6IpKA}B3LdipD&)(o@T|AxlN{kR|sDDs?0DE>^YJ||9y+Qj4
z?fG<EkA&c!JugsVnOcSlT*j$^3S6d^sRM!c?1;w?;XQlB?1%849T^g1bv_nKZi)1)
z<1`gQfOcG0T?w9(bOpDJ?t{_b9!jF{>>XJhW05oY>&b;@8E8NNMSJCs{BpFZ6q8Si
zu(mr?;A-j&wAwtX2DLVihESRMu7q8NCY!wP>L8xDlA4@KXb|K;Ou;~%S`Ijk#tbzC
z|LY8O59)1(nx3DMt66$rNq%@GH6WeyaVvWz{6#Lz>1wxB<aGKmIygZ>OotuBAt}LR
z)-mi#*xQ{Y_H?svyw~dBM2Wfd5a_+R)LrPkxzOEGds9><9SkiYHp9<B2HoY|R!2tL
zm{V=TA3GKHd_^k-Y#JI8M1~!w))0?j2Pz;Ypk%$%8#||(E+sjKT80vw_{@<W;g+#?
zBRRsA7#7FLuIUI4{6vVn@Jgz4y!^V7>YOn!q#G3Dgo3^Ts|TaEfNF&J4X>ouB{g(s
zg5{XJ1?$Md9FxejZdC;%0?kp(&W52WUtYtGY|tTI!ww(Gl|Z!^PJXkg!_a)QWodl6
zHKcv5PBS4&!z;;l$!K^5+3MhZ*Oesc!$*YTU2r4R2WZ40?F+b3i1Dx&CMhMbDm#En
zF{F@@==)08G!)}tDJNB2hyAXG5Yb^bD8=Dw7m9KC7mrT$ZL1b|hEpW};mR_5hQr_M
z20{k)0K&6_11;-tfH)5l;@JUwy8^x}_+E#$03hhD1Sq0j9?KAmVh5jF5DMDC`E~_-
zaO%9Fue+$@o)mHJaB36M^Ga&|uRpzy&yj4<BiNB%;7T~Y0o6r}XV2UMAu_{Tu2~x>
z)r|4V`btX64u)Cv0j)Lk)fQ|shCI1|c7}KiuOtn)7=~gkldguU#5N48MBgSJ6<{lT
zN|ck%f3KIT?+!557_z8q7DAMSoii1pB<z^Z5Gu68b9N=1G^n)1iT2N{2osM%ALRiF
zfkdw)yDpGu2a{!(RQ7;IGm(~E(H)-YBOf^SS=E4k6D8r5<ohSi^a@hpgutdf!OJ12
z=`H8`7u2-F=^UmneC#aYP}h;KAcQsT_y}LW{V0Ve6zLUI*KuzC?CS#xPe9TRjCYtc
zHgMo!w8|4E9>SIOLXtlz;tz5K8__ErM64m|!VZ6J2v^#R(lt!HWgWb)L0st-)C-c9
z2fjW85$%b<&vK6Xxq_PA`K40z5Bj;dZA0MCE2xHLg-_7Dg}lmFluJ?&&<=GIK!Eny
z^KZ<-geo)fjdjFCgaDyENq$3c&<=GPfO>W)+%Hb`SrLgLcxZ>-{#qx$CX-D*amFKG
z;T2TRb>-dX_!OngaZ?k(f_8+fgh^9_eK`d5>~o@LvcAFmAEw;^%>Q9JU?V0cg#Emd
zI_q0wcUKm$9ZzVpuH!Z$eWL5gJ#ow{c*p}$4nYXgUc}cS{AdR`b`U?>VU<QdME!J_
zt<evDkn2$thF7w(%n?HY5<A)_xR9>|A3K=DqqCIVlCp-~9^KVZocId5^FUPn()k+)
zgh=S<E!~Ie@I7(b>(cj(J-Z^d4ERmg0UQBrA)3NoF>WCU>J{V-UL*#!BPuTXQqwpQ
zc4=-T9|(a`J8}<17t=|{87>4e?KtN}pS-&)rPz6)(!swUeG(qf!O|azG3}u74-pPt
zNq!r|nRXPg`z?AnJ3ZuARIhKSSsVttbUx0|A*R8Okjl@4bOK+{r$nrFWE%)UR(s_=
z2q9Llphjpq=qzYMp-r!(dWg@t0#t92oq?L`^ld*Ku8knpv@fVSVNE-3cmqs=9hm?^
zSko)1BS6>D8L0uHH#PpzbwZzZ_;P~i(~j`pC>-SjQO+;mryVY%5d5^4Pbq{x?MTTH
z!kRuEi914A(~j&OA++h0tgkniNDy)*UB9T$M%dCT%J<l$tryf^(=B^xzb1zoqPC;?
zyWpYznpAp4e}~YgeZlG3sH_(hBmla(;8R03eZmV0Qee{#=Vmmyz~BH4phWx50m|70
zUjArO!(io)#!oTbupvxnhoAOJ>Zl4&ZZw^e;q8q^?{<enIGR*-xr_tUgHK87mKj<Y
zYz5JziTB77pNX?xW5m^!qzMvD8WSx1LHuVg7XD~D0E2`-nsg=z8lrOGJ`h#kx~2hV
zwI(BbuPk9_-%xIi2jGo-4AHuphH`6Cy&Jl%N%ij1ZB3eYBg7{fwJInwqDiyn<%l2Y
zRq$-M(4!rRuKc`ub$b>$no>W0q*QmUUO!Z-yVks)P&=N!PCwG3;12O4JqmsiKRP?(
z2Fj0o*+o=R4?<g!Bhtr;TP@e`6JBt1aK^ou7bj|suQZ+?>EldemIAh0gLQ#WuVk%y
zaxdt3FTxj3FiXb;pC4&o+yS}(r#-I?{YcT)z2cK13<t^KJ`$9w^U}1HPA(<&ReG<k
zFW!n?N%dXcZtv*(Qp=?zuY?VEtb=-L&bjsiF#0%wryZ%0UBJ_xnF4N^Z5jqL31YsY
z8jbKGKC1INd;??SN2=Hd`aXC`-ir?@MeO`Q=kxsS^YfR^-ndJ@622G&Z}`#K8+Y=4
zq=j*9??;F4y3}{22fl&~EA~?jEvx{Y#*u5$nH;!-bIO$)_yRBd)Z^hLb*1+0NFaG7
zsK2WVI#nZEr5~ND-O&rhgIrN|LwSC$<Zcum)W{c;kwtc^l%k6!@VTOVp-TJP!3E~Z
z`r85g@Q{NX)cnr;zP+-2J}F^i`EMR|9o=szZ^F}@#p;Uu*hn0IC8c-@K<482>%gse
z=nRZJtF8pTSCXp;aEGTvxr~s$w*xxpA-xKCp^NdagD1|F()Z~}Bj+Jc7ue_=sd_tL
zE-r?@UN{$Ln%*8Dm+_Fcjgcj+SD-Xq`FJ}}oL7Qp05cVXxZVz8eGeUh>mR>h|2nAl
zT}ga<J<$<6{FJ1om;Nwx%$2~m1M%w0-+LuBxe9vjv9gHI65tmPYG{C8TuFI*p<i6|
zem&r8aHZt!`SP5}cRO&wF0Q@~?C?jDB~QE>800!o#~xC%AeMAx>g^z(baDB0FjP8`
zj6I<LLYf%(7S9~L9pDys>0!WITp4;h;4MJYJrJ#`gm$6)oZm4pF8P$k=jI#s_e%!K
z<%+oeO8>b&WPJBmf=>zvHdk)met>qpB0MKS@VER{s{YAr2A1BLthWQu;_f;N0Mg=)
zd#XaTxa*n<h!%HQ&49GHi{kT&^2IBmZ^y>$u07yX2}>V4yE{Jrg9DhmzW<CuaM#z5
zI0aV{-;P)YcYXfQZtmh4>R`BammB+hbe2!`3p&g7`JX!Pxx?dCiuOqX`v#5W+yP2k
z-?AF1HR!sL0u%m~(84WpU{~he4jz0*;@(@X@#xm-EDVSH!2#g&O4#;C(YZDQ*g&rA
zydAg~cj;uXD!aedH>j80<>F3qX7~Q3QoRt_-!KK;u_Js|M*TZG2A$=yy+M2LE+;s`
zm)x~09I7$bwopM(?%EYjV7j?00O8`w(%S)X@uG}*Aj&arZ4F75eamdS%z59izYX@j
zEA{SUbtd>o@bCG?Hf?V!hH&3By$vklS5mz<a*d~`P_|$szmh)rqv|Y6_o1}C4TmJ(
zvc0X2QYm7~(2koISB4{*Z&$;mAGd68Ltvk0+Fk<)#+9|#0D^Jl>@@@s`ldN<Z9G|I
zvt@I7CgQ!N>ig0op*?>gsjjbgd{Cc4nO%t$2AUHK?MalGA*Rx|g0T%anU4rRsIE`7
zyt2fhRYg}4Uu!sHx{~-BATKULK?CH)m3`Ncioo~yQft*J7<w7dsLH)-$a~<Kde_=V
zql#eA8Wd_#b3G-=&r3OXtwEtG>8`<x;@i}!*NU}wj-XL@Jp&q5X?P8g8D|z=17PL~
z*l<EHu7K@Ae<~@jAsK}$C$E9#-j$Nq+Tm<BHdRMM(GnWGVQhVKcx6qqZ*1GPZQIGj
zwsvf1Vsm0^V%xTDYhs&|oA*24ckVgQz59<^d)2D$>h4;5?e+YstBOHeB&cOF*>Yv~
z$GxjZfbmTSH|nJ}&ylW{8+;lzCUZV8%R$uoC$pis&yOBlCRUC9Vc9VTo`p)$F&2Xw
zbn_!=Xb^E87rOb!Z6}6c@u*&;AAaOE>r7;RlIhxNW8PJw6*TTO#6O}KB}H8wRMqv*
zTZ3Gf(QpjetFt;GG-GP2j`w%N$-0&;{_<m00rAthi3E|ZC+DpAm$&sXTikKBd8`!d
zv(%m#AnW9KP{PuSqV_OzbfGb;eBc<dF+8OASzKFp_q3fWV0*wLVPiJr0h2hBM-gK;
zU6jtiLt$IU=*#*<(-PJMT=!$5znSa~I^4o&$I;bkm9B|@+DSbhPOQSXmWPAYP>n3G
zw<zUTocAf^+lxupB!6)MTcr@;Xe=fHiyg=k3J9@j1Ttcz{^;hx#|p)zt@*oRmcnQY
zy39m$1+rX=bYjqxz=sKyWgg0UG(T)OTQ7?XYIp0yqPpQRb*z%>q6gky3xF7mhRrk=
zn&hejgf0REf*7nCeu>jD^;+r*u?@JE!iJlBYMliZqzC-jf);1hZEK&u(U*>a+G!BB
zg^6?{SC0#svjLiF&9j7<jfRah-=%d5n5ib)>C<hjt+e~Cx5^5NoB-=>ZrJ8-I8(`W
z<$HF(mS>>5+CW?WcdoQ2;f!#OT0<FCV5!*x;2a^W2jXeo`r%GI11E(;c{d4E=m<PR
zKnoQB>uC-&&lPV0ffobo=|=t-E9ZK3E7Hpf8rToc$2z;);co#!7D|gVmnJn2&DS8q
zaSD=yjiTJ{ZxLFV%&?mdoOBSv`yFFJJp0rl_NO(^0zx$w)yo{{=;b1#40ws^Bpo>I
zATUP@*x6_Pg_FnzkJ?p5$qp)i0d7t^=cG~RjZgTdQD?duI>(KCttGgGKi+gDSdrDx
z(FZTdt_4i70r<FV7oh&VYf0P&n@5S-6P^nXlW%Ic(t)oLhMdbP1SIUBzZlzri@_r!
zAoW^Sju1#&K$iy@tGZ@M<^X!poCy43?~D#1cl7$bu&}-75yCxXwIk;0oD3-MJ9G;_
zIQVtdsx%f_K`s*=X9OI;n&+q+&jE@xGJ<;z#TE;@V2%}qn2p2)tdNvxWQEV_5_9y6
z{f<zUJYnEFejitb5srst&NjsX=U9eHxC_ts-G8AK<w;+<i(&0Wb1es{MTaIz1B(;X
zwgh(HJnzZH?7YeNugjk^cBXIv0l1-$VsOib;DuHqTMoxUy!k(?)}2Jwh+<7rrQrdw
zj=+mHEN7}1JZU%hKuslLOWC1>KJ5h$Z5)mwrcax+qX0CKDGHw&hVTrdRJTNinwZUG
z-W8xcN0M2a{SS*iS%OU3C?6^Wf0+pD?;scBF}PW4O#6KK!YtPy1O@~H&N9QB51u`9
z>ahs)^+_Sjix7@)OK#gWUuyX;r_DO_W?<*BFjTH3FRoD4ruR8H1WZ*%!(xWz_W?Qn
z8D+<!kHc-`y1>DV$R`gS7B{lYGk5!eg#-1_HNUqEq=>Nw^H4AgfMA^pQ0Vw`_Mys}
z+_e}(v*DlWm^dE#`b-Xk(+9)Qxt^R9ru^zc|C>m6%mp3`*MdP0bZ}UH`6Cd)C-Hne
z5Cu(U3MTwuywVzIzZK;i=fXN{&$A~FoSq6VgE)FnKG#Dcr&T)UU~*Tam_JlBB(Zqb
z;l^PO4F`ep+qu1_b9ys$pC50np&HdzW_BV${OvN`?rx4?Zx|#6j_1yS_JF5k#k849
zK;Qm;C}XhwX0p~uz?n<-S@CaoG@7>Q8z_%%Yj#UnrKM^ku%F?8##S2N(pn6G2##S5
zs7CJ{P8L|f=muOnP3`qwj+a`C7hHps=?Payft6unJ$CiHgBHwYjk(kiQEI)q*ovpD
zQpLuKlxl@E^HcXzf-8nb-Ouh`-c;A{JF-@@wLok}You&^rz!z}<*nIi361P_JCb#>
zb9p2j7~f(xdAj;uc0@pd!l&krg8yKBNytKC59%1}P&UUV;)xAzh47E1C9NhG8F^P4
z;NnE_HP0LwW*{Xn#KnBf4`AI9_p=Pgdt~tT0R{0E_d!Y`M*^hum27wLK)O=jiHZVM
zxQhp38S8dU;6d7rc&ls_F(!X418q9`FB1e2E{15czQ}Yf7>Cg=eY2mA(`9_E!A`kY
zw~9*z@<WvoN={X3T-c`3T0*5v8U6M^f4Ehu;SzSOnx>&zEc`=AD>H1ZBm$PAS2Ks_
z^)zL?tb@1Mu-Cpxs<_mq{DONdm@q?L#$I`Erhv;Pg$G4nQw)}x28!+mrK}C6SN$oi
zBvvP_V->R40)_~A6%p&Wk~P%Ov&3#BGBYV%CNjGy-Ntde&?;P?4TPPK{aa&S%yq#m
z6Iq^9ohP5VDOfdG3q(5zX3kWv!){D2ixiSBwr$O!mEWHRcHN*hBs&Qrxx`C3A~{;6
zR=p%yl~@3%Ul*ruQ!BPhaYj=ouM6=CTuan8PcD@F;=>$ItnIkCb!+_tg<tDRnY^bZ
zJXPulxISyVrH8d8Oc;k*RugRSk9sZ9X-@k~e8bDXI))syY?BfUTA%@+>fhAwQ=MjQ
zB(nD>;dT=CsAO}kHN?*Z-$B#hEH@o!i>Yihwwv#F)j;@_<F*KGR;9v=-=NG_bI(7f
zt!ORfB3HkQEdGIf=DD~8&BTAc*BNaZafs-NYq-pa^VPN8!QL2`vi4uKAunVX#LK;S
zvefFg1F!y|?XyFN7d;HX#?yZ9%xNiDTMul&E^X~*dId6SK(uk&wQiO|CY1G=GDpz?
z<uj$Vs6r1kr8TPx;4uHD;0Yy{tUDtfYW;KpCpNSuRYSct6J&7#+cd<z=xSkR2?kX1
zDQi!?E(>Ik1Qy>JYD|ERY<`jB_;c%wa?l!1W7JLowXcPBH>df;+%=0Ym-gKByR<6!
z&#P1Dg2H~8Q*2U-2gt1c3UFSR3AOeYxm@@$u0M`OiMXTAq6?~KAcNzlDmoW|Uz<&T
zlNn+WF^)c)o!#aLUz?3TKjVLCQ#8Wf>(=aG53xCoaW&<?*oK0@D0mhJ6r!s&o?~se
zyA$D25t~g{xAK@*RoJSbtY=o%P95ge8`d5X(a?W+8DEBAxudSH3#xBH%UF%BPf4Ct
zud;EC;WUlX*ASA)O60+T`UeMyPbb2O5H#3=R-@X8-sYATXL$m{VLCQHNQT+a@MaTa
zSZm+5d43b;hJ&}5$MOV`{k@OcEy{TAM$eY4z3J_y`EC=Zd#Z}9CA7vp%u*9BFS|;t
z1>)&r>YHXPeJY;@@cWJU+j>zHe|*_rT6x)y#2o1N>@!$ku;wpL#ce}`gOWw{j+vsH
z9`qt0twwP%-93}KX(Y#v+)wlEM8L16ej*G}kk_rMy8ckgRjx7tEa{Ip?xe_GazSX$
zdH6drk!5%oDdUrj=rPw1(ttjTy&$4Ydx)VkIwX(GPr%7xMPX7af;|Z(3xf~QIvz`b
zh7lssLJz@ySIvE3fFyD|Wz|G7CS-5(MgFzJfaDG_W{>H?D|*-h+nN32um!aEB7f9g
z<JK*7)E+Yh*2L)xo;DKLfBT;3<<<n_ua5Pr`*%^96RPb@;VsYjXLESR{WP#=TbdP$
z8m(AI(dpVjoc%6rbt99rQh@<w+wf;|&FL8KRX32*aQjg5J)qmEv}-0YAJ$rz&{BJd
zlxd{LsmLPML7$D#NtW$mFPJJ|5sMX9p#1%Qts`H!x;;46Eau1b$=)ICyaDVqE>RmU
zP-KgEc#EL{Y~ul~TL(8rc?908@-kbY@)HLLmT4gTY3-SwU$k~g4}^#P*kGSwr4A|7
zT%x92L9Opd*jG$cy@+*tmB1v&Wmf*9W7%vSq;<qJS?rVdqPkq7T%4mJtYSW*E?l7Z
zN6mRjad}V6@Rgb00>Tk~;m{UEgMx#>tb>gJYLqXI<Y#!nQDOAcsVgMU@H_L}&1hsR
z(5y_`z(Z0jc2PD?(BBmFOI@3!SOtyPZpg#4!|B3`eq<$6)4sx?3lPko4UQ3JT${x7
zSpBH?04v3Pb7E&kd5^|3rU;DynTyuV;$pAxn|TRJ7>b3#Sbf!wMR_S@c^n5+s~O1D
zz<Y2iKtAH5W{$k^qT6y}CPll_8yTPgHY5#T9Hq`*_|j-JKuga)wQ+i}3zO6^t}Ix(
z-j-5*?%>V;Ja_su@tsS?JKy6^QErD;fK|q7)U-aD7`_=U_qK8sM`3pgG(j{?y#c7A
zOr-h-v}Z*J-{MDUH3GZ9>QeqTqMPdpb1wT@p&SDv`zgm=;DxSQfqT@Ils0C^h>jEt
zJCRenZmOP#Ra<*K$zfrD{o+2qYhYzSQ6dKql80rHm95l*0xA(0?w^(jW3AAx2e$mN
z3N>U<<&9f25$n|&MbsBkh~g>R4%PcYl}Xgb$v8z&-9WS{Tb?#q8!i`WTXu$*-d`9%
zL#}gG>jrBOCiF~`m296A5JH^{2yfJc4ADHPdK-a1QeU!@8HCq(;AU0q&T@R?VC&dT
zo*S2pUk+WG%eZ%)HfgIe;e4{#md@eVGB!x)JqJ=78;$k{j+@yWD|z^`y{_+n>)}9E
zA;n1H;#{~Sz0+){avIBYVVdT!0V*ZrAyn)IMtK1JOOPF`u8-+MZw(X~8r()cdh)0Q
zPE@b<sF4me=jtNdG`1cY7@g<scl$5y{GCw;H7y_7=op1D2y{;c4B0UqIEZ|ONtNtA
zX$r929Jm4oB{5Zy9pxIG0>LHVh?thVEz&itmb`!hDCY{^Doh-0RzUxNxdr-t2$x&>
zPga?A3a;20e2C=C##;J)ha*}7GwPa}68cUZlnVA*&-q~Y`SAYxbj)ZbxjF3yk-ai4
z;K^LJTTBljtMs2q@QM-U;G|Hp-OG_cE;?+qyDkB2j-4_1c20eJMJ|>tWdlmj^Wp8H
z+;8T=df^Khz(2?(tR=*f@v5+qAAc0GlNQJ%E=PyMsA)I+0N+O2r#7>SYs5a^1#jwC
zjab656b6)^E5MP(l1#(Oy9C#Co5@0jMXyrZYJqCd$XEU%{i%a?j`iyYN~4ZFUQFVr
zNs(j<hCUzEjT|x))5v^(4hl_?LZ;ObJ3(Z2r>(z6xj%REB;)}}t;>9%ET;T%GZj<0
zs83wIk>f7daQ^6UL{vJoVNPn7YJfkNi_=205fS<+7xC>cQ+JX5s0c&OBmz@~PTZ0=
z9S=@4bnaUPminXM4#z-m3qytC2w&&zcGRJETkRBHVwC*`$u)<aMh5qhT`Qxj>EqyY
zCrV2MTl)-Dc1h8?HySnVdl9*a`3zL1G8yl}DxQjHV9<(V4r&LdKqHOA!-h!iwQE@U
z&8g`aInZQ_Or=WPwWj@0EVB%!K)z;ZgsBqh=%2ZFjz$kfiXHNvkZ(T2;Z*4`O&#H}
z07fvdT(%{+%RxyblDp<TOq;BDDm86q662L8Ny^p7YAVdIr4o2lPkWd0p2c95{y*C%
z$<7otGTQF$BzcE`DpcTPV#92tRaf<LSK~ZY>nc#NB5mtzqSd-KKsJ_UdlRJ139FkZ
z53<sH(=sebk*;<2$#OcXY4%BRaDc6d1%ocmoGB)lduZZkfZ;=#&10VG%EVw4DhRJq
zD<;sBh1qt5KT2hj0#K6qB}YCZ%o^{&^k2Fu-gxEmrj0;K(5Od+tPAZ*_kL6RnJH2Q
zw~z}Du$d$6YIlhQl$xe#srfOcW`tE|`YGXUX;geO%Tplp8~6F%BJS;*#wE1nuMe=8
z>0Oj)zjHWxy<CPW($<HvC_@)L+8cycwBsF~0Vz3cZ>O_CSq-wSh*So&>p@w{$T)R!
zpU{TBS>^dA4lM2Vf@@(V*LojYB(<(Yb0g5&GZC-ZpYvdlScNoEy%0gFiv0}%&(5jn
zC2=s?dQ6Bwa;R^DO5m5e(fYc#FGLs}zcsJcouS*U&xGm6;_8>+v4hPy^)f~;LXGvc
zWP^lNpDX}OP!r>fwZfWiAvZy_7pd!zZ13cTScB$0N`qT-+owQuvTJTSvl}YCOyQ;D
z2(`jOu0FtZ0ju+wd^k3L`|gDor{I8b#dJ|~5QlRyI`1k`hzzN~*aNuLn*he=tdcsO
zU>xE7#UbxN@O#bl91^4KRlpELD=8VI`!wFY5D5ATxaQNst!#bIhCqP(KN_BhHskc!
zGbVu!@xk+|IqHF~IJ+lgR~bS+9BoB4IElU1Z<Wl@ofL+-YiawBo>q(4HHsiL)P}iW
z`m`iL@&(nd?0zKXOjQUJz)M(hiX`Q~b_^4Ve^bxrH17zb<{hx5^3_41u8`$rblb@d
zN6oZJpzh{0S4S=R&RGjabS4cpNpGr+`^(dDH^ZAfh+Tiut*TA?fA{O+Xp7=1UoyHz
z#v-%6T$`UjvF!x%`&X6W%g<zr?ubOA!duGI#O)htCNqHmdE+uM2gFP`wq#So#QfrV
zI2#Zr@*wNP_)IMb4oX55Gn`ejeU_zOid*$I2o4SOHMgqqxW+n1iK=n-T4~*GHgrRc
zD-L>Y|5<+98~<54HQh`&JH|>hidt;|^hV(9)BGk=#8PT^u7YvX;`hKR(&r6nMK@$~
z6*22@py8Xt7i9po;)Uu8K}+suzill2fXj;Vt)rxT0b6z96Qia~cIU+*@HrP*=2%io
zn-ucYQR2E<yL8!`wxSkHxpc#W<NCGWgWZj8R0zWQ(j8!i%taCKD0Rt$hEd@$bfLB<
ztw`?@v)!%bn!z^Y9IGUzv<-ccV=hTC1Y8{@h*gjL`Enj3m?nmQ$XCyBT;xeAK#a^N
zR!M9O)&(_#ZDmfrD`d;&USj0wuE8`z{Yk}uiIS?ugQ&3QX~obX%VLe{6Y7wL4YRHf
zql|2$^hjmLuL^V~XIV9FmGjio3BHnDn4JHP=0&t&eptf(e%CI<_dR-I8nS~oEh3fg
z<e2+3t;>-k$6W=f&t110IUZtj42Z6Y2Mn-b_`8wgX(FvBI~n%Hzh$+_z#6v}I?yYi
zS*Hc{HPpk=h3`qRa*c<^Qr{r<dsyvh6FH<{Ts1GsIl9?7f{}hlFa!}z(;D;z3i(+H
z3eva;@T$zywfg$FeE{(<O$$2=JTLYO`0vOGam|A<qTfOyXGue0giI^<H4*WUj_gwD
zbV;G~HyJ9?5$nQ23{8sH3Q76suggOX4^oQ!%u30IkmDiuNyC`*5|$EFv`Yp<);op9
z2)2+u)JDolwlxIy5Xhb751*0Ysx_2~jt2eYWt@aJIYPw)RE$&r;`rMJ0K2Xcol1S|
zO7RQ5U1vl$GSDl5y&F>2%|H(vmjjT@?26Dl<I0GNqypa7YL&3wq=g)Iwceyi&0{m@
z+gObpU|0IaB>=-N)PYqg-X{s0%ET0e)m`#6=?ySWSc|TFCFdkgJ6cY$+Yt_<+OYNG
zYNvCnT&VT%&W$8Rjq{JQI{6c(mWwWA1|18(h?J^|zDUQ+JBTi1MpvX7&H@u>z0Eaz
z4MgZz`0->j=ViWZK~X=vp|hwmc8SKRR?*8CovBN1)KsbpFmU@#Te~dSPV`ZZ1D<u<
zAI;d29v+O`y>SgOnwK$z7MVxD_Ci~3Wxf(4SQ~w@OdEZ;b!evuk{MpuCoBj0MXVkN
zR}FXA&Cm)QS2SLvc^tt&+ek2+5<uHnFf9}<ZNOVDB88k+LbTrv9a~S+Rxt>X^QY0_
z>?a0M^_e>9ZMucH;t}d5-VH=fkz&&+lMwdO5nMMhD$iPso{5uAYw0^+1H>Q&&+S{G
z1yq9veei-yl`w)Z32Ep%PoQ@w7~41Ec6mM>l=4Z6eTK$bnU_3-g{Xe@0i))Ng_>lJ
z`%O_=@Oy8}|IjZD4&b4ewZT&K2&O>wH>aZR1Fq_;1XCnX3ARRp;UN_>c9~5h`S4bc
zz@zMXF=PTyM8lH}QcCIH(-aDxN5iX#R>}xmQ8vZpg22aTVv8{`5!Hf;T^u(|>E~G7
z%?LH}F*r7D*b6|=QzV3Z8*FMdfyN@~=T3>p7XuU2NYOM|5)ffRB$f}Qaj+|*Ez#A%
zx}rG7$U;qZ%p7kk4h03>Ui1I~gi9P7(u?0TN{s~ah!r@0r#p=Gg@~dq>^s+}P>ums
ziEM#>hQcehJ*7IfP2Q|7$xy;B->T^4PI=*soh4aTR^c|Udx#_zgNC}{=}*&?tsxD}
z)`SAZ1O7or4_B?X|Fb9P98LN15w?S~j_P`EmvU&nBmJQe>2nGhei&ulAT$)R+xX>=
zRsk+}81d_tEwx7QoraMGo!yGPY~Tz>9iXP~(rS&l)n`c9b{&F4e-!&1*q13&q>yI@
zNFb%+@{X-^^L&>!B+V)80PR(?-zjUmfxc5An~Y&kf8<J>u4@6)a$oq5{)m7S-PJlb
zhpZi}%zK82gH6leyg*mb9-3?omy`l=K{n<HHGS`X0oPDF);brJLJRblKH^?kF=mdi
zJZc_C5jZCiVXev(2zm1K_bsx7>Zf6lu`Nw>Na8zOm7KZRyAgVq@awTTsbmKGnmrfH
z2|bpjs6tNNfwuvuN7w?U?1875t|f#%NF8rn)uA?Bgr!U0rZ{c0-8nuza10KCMnx_n
z!e&7&`3w`nqIi>)i}f+eMqJ5;%Yit_b$2xiq3n{!twJ;c5`jXQ=(aa86io%hCzk(O
zX+0n)7)^%PK?*kH4q=mr=caNWzL%R<n?@{4PXm}F66g2@2uVha3ojR1q`foN{(Dae
znBw0bRPcR{vHIbtE%ewI!P7484oM;rPzVXiRLFf%1!&`<4ku9f-;!ZA%HeFsNEquF
z90GH)My<e9$B%G4@lM7Tliy-0;qYtaNL5q9N-(wSn+{oGRIk0aMzm=@yW90Zl4lF6
zw#dc@?^<%;2MBM<RPVjQ1~6uXHWMQ3jc|@NrPpHbuE8LhQV}b%WONdxu6YH@D0m-5
zd6QSaid`JRe%2Dwl%3g$BDAQw;<t<D!-2UoC5e`|BM_*-r8rq8ht$%08jLJb0ilO+
zENt>e*<jXE$#2<?<;#I@>5UsD1y*|_D~iChBjhMc39kq<!AS4(oQN~mzW#Xx@Ryb-
zrC7CA^z_#E;c!QKArrq~4tUD<uR3^w;3aNXiOM+WtR4*3=X+qA7J9^LyCY#3V`YLk
zNRzHa?I9(My2i%_!n8?doTZ!&O+@K;TK2BVV#0IL4sM3o-~)OmE`%x^`Bw%t6Oj&x
z{DZ|Dx->~7Gs<uE!zqw;Atk9DCfkGZ9+J-OFYtIgB#B>jATOyP7C!MSf7|wb08P&|
z?-qEpOSw5B#WsU~2EkcM5wFP7u({B^a~w)YxX>l=26C6}c(u?iC8^*Q`0G~%38C@u
zeLCEP6*w1VPUgjPRRv+9p_FW;SgF8nbayO2-t8sbo@^3;irU~ZeePP`okW^Bdc7j^
z=x?2e-`n=$LhG&D_JsgTCX_s?Hg`>MUnYYJOKXKi<(tgn`?k_knFVQgC^x!io(%N+
z10Z3wdp7!kg<6*%8IJJ7s|Sqm3i?~1i+mb8mOJu5#8<ppNYxjZ&$gr18tFZvgx=cd
zsg`2qo!lDfmNJ3O6?ZFJe#`O0JK!R^xDbFGc$|n<Hri4vzM>EyU;vcjmnHLK&;a;0
zi}55?LG?Jwg^$3u6G)`CndOq}T{s<u8mLZd!qVE1Ba~hXXNb-UQi;pVj3H^3`YIYH
ztu7;z7zCTPxaelV)<1ZGbYtC}J^so|21tF+EMRLYPoT<#1F>!nkM*a2^ic>j@sKv8
zO)#VKkq?nVqUmLG(sQH+WIx-Aw*ZUW!Re_a&fRuU-x1N@U^eR(^6QT%v%JLhVVt1s
z#eHm)2Vx@~$o^171TmumSWieM$NP=)MAYm>hGihKGfg*0PO8G#b7^>(tc3JzFbbYq
zZ=&`@j_M#C!r5Whn_!Xs)*QBcQhFO~{}T{bGC*jOgD+9W0`rBwC%9w=4_s*OO+WUG
z^xHC|lJa~@Y*wfPzT=+eVTd(zjH{s#;fi$;)_xl|M&ce^mNex$Mq`XPKuTmqm;$Ek
z<c+Uk&^(}M$br|eJS-r}{w7o;ur1crLyBqT7aHE~&ULyq2;Y#!z4mn2gHucXTOm2m
zd`wVe+eou2Vk1p%3b|a~E_TSEBR<=22l~+{Gnc{$cx;}f)d>*u(_<biiC-67l9g!1
zs0H}QYMP~HVu=ZBkI~~IBpn@mN@1U%Zc%v0qirzIhh9ZyAy{?@<v*lIS16wqV}|sE
z&w<4{^9R=Oe>jFC9`7RB!ZIU&<ZlGecl#+fZ-x4(7TTPLuZoIs<&s;X?DxHb@oWf{
z4M*#uLDo@LPOt)1odV%9nk%ODA4i1GJ_H6WqmtEgWAOpE?ecF_rijbot|~*<t>bw{
z5$k7KSeal6YF|5rz8LA&F#^>Cv}%DyLsM}jg)doj7`QmdqwHiKC2M1COPGwg+=`ol
zYgnncjpW}2#K)i)=CR5NjJ|_-XDgZLVyx{M<aRsq7?3DlhA0fuQifL{qh+m4F3^XI
z<d6Pn?dL!}VIF`81O+ur*kHfVcBheEbJB+g&~kEB7lj5?=LK*d>h90uhE%P#2KQLw
zX%&|A%GY(^DYI+@rov#)ZS+qdT<q)XTBh1eF_>rv)XVE?TLcB8lDKhmaXG?YItGTJ
zrn(g;hM=ZC71hn*W2WxI_IgIhU#$}K$iIT_9u@7jxvjJSU$fTlwuDTnW~?>mrH3E@
zpyLLfLB4W;JOPfe*RYP<WACvwNR9wk1SbXE$mCnwgKzjS*2+~sS2C8Z&)r7^x~>H;
zSF0J^89AJ1BQWK+l>-Er;xR|Q>Wu&LHPK0MtHFlyr-}_ertg9}OSgorY}bU5Rvs!)
zlkCPYm+xKkp-#*J^})OdZe?a`MzyA5jsRkiBPwR<TG;nNIn{L(+!j`!%Li@~qw^FP
ziMK5oPwDmhZ)Le*&`9FL^K6I#Lq1E_5)!FOAaiNf<o$k7Co5OhJ;DxXVY-YNs8~8>
z`MV<5FN#<)rb|=m5jDBG??*klij9twC1JrTN6~xW0#IquNu_8wqYFp-@ya<8{v_xp
z+>icFEY@F*3?oJ@jxZR+FQ}%j+^ej&Sr*&3uL5GbXD`EqlsnT1Lj&<Jwu<tDL;>eg
zqA_&w4Wg3Fg`yjdN)B0@S7%&uTrSFQb5X&lC<T{9D`3$2_=_2{Mkifr5t!h}?1ju5
zQN*Z)j+aiJ{o=MG%#*+<D+~r|ptzG8%D=tGSa;J^EqSSEh|$*(2xPNlUM{8@MneNE
zl=3d~rh?fld8Js1;n%lc_O1^lTo||I!qJxd!k}xrct)9sJ=bz{(||Gy#zEOV=5CRV
ze?CHZpgvmb%xf_9cnw5=Z5a0D9(oG}tm#Vzhe;XWH>M$-Rs^A=+VYz~xGY4R;LBCV
zW7sMl$w@^t2XUdoXBtaF+Ea+Zo##!7Wm@3@trWlM0Z}rqZ^w&Z*p^?0*eNt2grlZc
zati6n%sk;W>`I%NQMrdP0Ed%`R|chH#tcr!db{c<jU%bAH)b!UNw{1U4u@kk(|hjV
z-nQo&;s%r1ylbhg(jis5CY`CbX7D#SPcJsd9`g@koyVIYP_I0p_T{!3Z8$xq=Hh+d
zP>$RXs*8Y2{K*+4<Vq7eDC#AGF7rgoLO-{96P&f&?2EKvt%C=rFrqGa4<sh*ECh>I
z;BI>M)(mz9Fnjri;Wox{)7e-6Cr*#9YrR>X=f+s_uR~i%4GFZm--&djk(z=5F+4S0
ziEkvz8a??`E=b;j$V>END{e{|Eg{qBIp6oBe0UvWe7jdfQ_a2$eyz<h2BOKe&<T0O
zhW<zTMgai$AszhZ>5t+Zh-O_s`kQW^6INM^2KQPE3~@W}Uly^AwWkkOAxB^iW+|<P
z_`2yu3#%>U1102Y8?j3>1*Ml97w1k>-4lNph=1yg?^)=#;_xkZ0=Z2VSlTi=O`<GS
z1mQIlB#v+N#c3tfUFMBc&TjfQ9l=b&Yb3AU3?1h;{DF-V)mXqJfc)$IsH6gl;Heql
z6UmZnokQO9#lo$W*oQJyVba$VIC1?`cmQx}^Qga=W-Clh*ek2RmD3}ucipP7!g_<R
zNF-?QI%}K~tFe<3Yh}}BqRN=$M4`uH(6!^ZhytiI0R22D_F|Nnj6@A_Qtk7U?4Q|x
zJ>y?vkcDZ$-#bQmuOJoEOHw*lz1EtS-6+OWuj}AZu+k!NcQuu_g|%0#9*QG>ZH)b>
z5dWrlRpk8|l7`(W`nF)#*8Jbql|Hp)LDg~?6586A*qX$S&cwa7sI!)BIl0@K>rmxk
zVlKrJQH%5vWv^o|f03s**h;UYc<67aGMr8|!V3HlX~vW_qbF|O%lfquY%Cz8EPgIU
ztGn;%YD&N`*V(R>a?@8LDr`}OgEgQx&#SQ^Cwoy9`!P-~+?YejiVw&?MjxO@Zf`E~
zaZMUmRAEIBEX!Q1vWT!ntEG>~bG2Ea2jtnxx{B90nUxR#KoZaq&84lIO-LQ+Mc6Hw
ztf4FV0<~mc)9~5S$bV`ml1yrQr3(jZp{Sp)j_RJP9tLgAl0#^W#GY#RThKx!acM)A
zm_-b`x`09`CpD9zdP*lf83_FJ%_4m7@%xyGYjDb$LG}I}YEnkz_dK%m^W$ojQLKaU
z>)@-W;_DJ|M6dhned~=&<@Z_l;`ZOxHv!YXVS;#m_Z`>k?w58KVLSL=Pg96HIRZVe
z2f07rFMGaj5Jz@C9WGXCc1WEKT(X$gyW8X51@8}Xzy2Qdd{^c>d;BiT7j^))alq${
zdWJ|yDKOTn)b%bCc2Aewg5Y<r*z=le@Ap#U<g%yDQS-CKW56kM;_@N)At?-ETm^6P
z9$QkS?YQgr*IQgq!tZX##pmyg;O<I(g3y-)8~2o-Y=d)m3l4_c7I<5YgD>flyBa%B
zf2VSPe!a(C*5?H7syM{*mp>D3U57b+G|nW$5v7hrf6}C0!{!ivd4K#7|0Uw|)Zgn(
zMnf7J+G9obG;g>4Y%2()GySLJd(PFFPvRCm7nXCUcPVQ6;Pih^Q)!n2G#MW~M3&#J
zT<h;;n?h|{Tb8uxnR2aSXs4f-tT2}KEVGgY-BFeCUH(4E*BUsWHUn+uFdDRTz6|a9
ze&spbE7ze`>}WikkI=t8s?i6Ee<<H-8!V9+j~(k<DqbgYnuM7dv|_I?wqYyX|2)l)
z_3>O8=nViX$K=W1wPklO%C#aH>8^s1nN*RNv9_<+BNEyMPZ9J)O@O!$(K`M3;2&j7
z^IPV=uQ|mNz~Eb|UimYQSz(lTUA8Pm@2L^<E5DpSe}BU&uk9XzZf^T4LwrQ<IP16^
z-RAwYW%sx5Uj(|+bG~fc18bg@%kSc;!`pxPX4HLYG=09DRo>c7mP<r_LixPkZ;GvG
zn#g`SlXewV`Mqg<y@1cW4OS=cus2OTRGXkOuc*i$`*&7B6i=wgd%b*D9{hPxw!E^^
z2+@u*;uqQdP{vz}$QsAE8DPM4aNXcQuWxRM^Rw7_mD{KMRCasAN=o);`S;7Y9(&H$
zZ>yOAq3@aAz-|W|Ges+I1@Ji>!Zu7XY68KB7YJl0%A9RX2N=AnqV9bcgd=419MP!q
zfE1_~TzXjgv}O0<nZuvesGQjf$hLhCao@!p0#@uLnRvAmZY3hUQ}v-+G3cq?h^{f?
z|ETWKs`!eFcN5_`8Ct?z*igv1p9zH+QgpF@9+TMad;Wa?%Zj?@N&@@k_&D^?9EOR)
zs$U^ctoYzU*o14aw4lgejdbVXt53MFk%J@kR-;C^K<U+P=Jx)|&X1paQg*Ph8r8vA
z+`=yoF>5WaB``OW?cw%QO>o8H4Vq!Dq9yLsR`9v{FpeM;^Sfcj#`x2H!>mP$H-6?y
z&9p%Av*MKj(O4YC<&NLS(9*ebkHBBVk>}DY7&ALlXBQ_kBinzz*&ADZyBe8@{y7p6
z5wUY~vvK{0&-!mZAKyQh7{xtYBvo9DT+E36i}4T7i0S);h*4CSh?$7d#ORv}2>c`b
zUzAbeyJFw}kT$1hqGuxF`0iHu-$LJV{~iR(e=8$mRP}T)BVtrCvM?heCu07WawQ`t
zv+ur`|I?OH-pmwWBx3JDr1Q;U`e)!o%q&byM0)=c7yVZJE$>Xk_TLR8o$Os5{>Nbc
zOUb{u|1|mjFsgj3b~3VacKAn`iRXXV(nKy!u4ex^6aAJFGjju&m?=w&{KNeBT$Rn7
z?OmNr%$$k-SvO^v|2s9#@AH4w_n(!LGqbaBu_WU9?_o&*Y+THoh!`bozE@Vv%*5XG
zUz+|c$V|k^#?A3hU;j3lN7kjLw+EVdbIqB`68{!I{{nwHG+8<sY63BIO>i&}a1ydu
zP81O^>SnF5u~-r;)E$zRzATY{sKx9J4mnX^J##%0!TH%8im19f^!5ZgCc2UfX}vxg
zCq=Ti7YIYgv-4Ni&S&=qyP952HBZf3wu&efu^4F-RD5q?8ET2&%g3@Hs&N&u7>*#|
zsS?POP9QbDR6?YbD*f-tA~wIdBJp6DZT<5c<x#TFm40U2qXslHqvB6f<GMY3pV0V|
z<GPw-(+j3%+M?B;gd5a}CDR%2rbWzH8=SRzAA^n3sL<SV-@mCRoWv4^EZ*$oan{;T
zjAqb<Tpv>}gFiKzw$IGOJ}keaB1#R(J7LPyq-;jVeiGdwF7{!{M4RH-TV5zkh7N}g
zPg2p2!BA*PlSi}71h*d17Kk|deoZAh@#Gh#=_g^x$U4HG1FexT%cObk$sI0CmXaAL
z*P*RAiEC?z&?PED86CWGCn-@K;sO~_guEJu1gl9FTtFsBxi%PiH1RTiAt@j{GFb9$
zM~j)VnQzsOVF^(5<biHoLvSX-c#~`KQKs4MAp|0zGR{hF7Y$@oJk_R)T7|J?Z-`!e
z3Je+(B6HY6jwweB$3IQl=&&?sG&8;qG+2c6dTwYl))^Pl=Ey;jH)sygupgKVL~`1s
zU@NE5aj4U(L0^8Tf(p*barfC24^;fV57qF#ClJw|T5j>e+$`8=Je62WAF0WQV=(BR
zv;65cg*Gx}okGb;f^=?|@tvn!KVdQ7#7Y5#!|UkbByCezT_7+m#Ub^BL7q*VExd*j
zFO%<Y)rf)j^VW()Puj@LCGz>Eo#W+1PozC)K>JlXWU~!-{5<k&(x_8mPnH2C4?r?O
z^oP@`X#aFm&eEk?4=?aXck9#WBfL&72mcBS0CJ3le@%;EB1yR++$`Y`!Hv3Vz224f
zZ?oNJK>7X=qF{KY>Yv|YU0gwJIp!v3!VLq)#Z>4MLvn9)*^;@%Gwb!;ve726TF8zI
zYWV??qRRC9%XE6AgO~N2gSMIqL92|Z`KK8R^RBl3`4tp%uTC#jvVvCaa3#g#LU?vZ
z%kmp2Y-n|)B*t4974-HUc2Vyyjum><Q%LKf$<}`g9OeYj68(zOVs&2Cv;CGBVBslU
z^e8roD-6Y~FX0xXIGm#M*FV>#Ogee=GYjZBF|g0!<0RstvUy!ouk0j!6UOAW74FaU
zEh=f3ztg2#Mxq%4=Uhpt1ZhX+?8~w9wDGiosxu~tIv2{NjCou0KjuttOH|XYWCOND
zMcBwfhz3RY$ikB1P5gPJaBaS`ZM%k5^08#ZrVRH}aYV)?j?f(7A(kUrnLO4_gJ=YJ
zC#i|Z7LKi(RF7<mFZ+z>uIRdBYn3r9q;gM0vuLEhgS-Cjp3^!lchNXio9?Ray0SXw
zKQCCa;#Zb}X^V0z=C(Bcq@Gd-G&lY{47FGmWF}$cm44utpj2Y3ch9NDQ_dKX;IQ|n
zlsepe7;@%8bS+y5$bWAor)6pIr+$iJrTI}y7IB6#y-26_`$={MEv!HrA&f;x1<MTK
zj+bGpTpD4`Qz!eXGb~gi)6Ga6jdmwrle=Iwlw->L!Ftl_8CB+Uq`7M2n0>fW^PgZ|
z_qwZf&8NJCnq<p{(*>Jm7Fq8U`Z;~WjWr6h>}H7#aRZ|sbKYcpZOwb@UM>xGehi<@
zlHs${*<X-L3SPY@qR#o4*ZB{s&W~~?RGTA^WdjfKKZJ(oK+1p!#C*~7x`)fa->6J7
zm{S?pI2Pc?^|gysaj&s4W7J7OUGrqdXod*KbJ3$lPIK<}Yq@-Kx`}i66c+$Iv{r4a
zcN|sdqJ>7vjcLLYKOn2*OM@7Z646-b4ik!EOqqWZ59T7dr@^OYGX4&>V>35X)~S5$
zAxA(FapejJHM4v?(?g0Ru_9qEqb8>*#!)V**idUiviXp1PB49PooH%Lu@0w^KlZTD
zISzvkFtQP-lQJKrJ%_1t(Yz{Gi=)Yip4dKS&Wz(U->Zfq9>JYnwQTlNU3{X7z?io~
z+nWf3wRpF2h_ZtmKnZhOySvL5^+jNeIy(ycB&fKWO2JWYtT9D7MxI;`OG}P>7e{71
z#k~uX=@tL;hrzl@BF@V?JM`@4jFcR*ZN?%<!){~SV>6CZn}99)bHT^{)#09scH>TB
zgD5ij5Dzn9{?}E7?@@Y8&C)W0&u3Z7PX6`Wz<hN|#70Yx7Wvc{@rTt|;d$*wu@S_4
zEfU}+fs2JdNyJB$-nDYKTZ2mQuuyWH@NSVu<Nd%VVc?i(fIQASUJ#^k<kvd~Q<shY
zfD0+eRsO@@+l7OH+v^d7xZ_W0zjcGN>vO`94l3+exTYwM7`fjIg@A5=qtzZ<QU)V6
z$lop>Dd*l$0~c5su_PFsRo#P1L9RcG1Bu&yx|>KPmR|QIs%6P;)unug2^7(O_o{IO
z?>w&gU1bu#PlRsgZsp&fZ5uo@*1RHedj>FV9^zwcyNQOg;h6;%p1`Nv-vV`XOww_P
zNvV}Z&cNqH_WHqP#LvOk!=}+`2c;cF=t}NipnlL+htG)7<BOO8@bHz%2~ai$-ENVp
z3J^`!vFC1$lI)W&#I-*P-KiiDxVO&opSqW>)?4M72M@3}x2buJucIU*>+9{rKJLsG
zYdr6?j{*vU#i94Wgt*1Celr%B;M``PG%1ah2{dxH-rcpkGH$f}X%ncK5fs(dnVIzK
zn#mVcme@MZT`@`_pvs|&jl5>Y&(`e3Ez396J}2i2@lqtu4ST~@7%PgCmUAdgD2S1k
zlf%k8g^rk%lmTGhr@W1?6V|Wh8&);(&<ii19-!R`WepT@b>c%5tyvW0-?CT{=IW53
z@94AkbRD(D=vCJsO(#id&E|&|Dr;k9oUMGc@2tVc6hv(gt!Z3VJTATSJOV-Ixl1q1
zKPddb-i9+MIcW@T9DES+QkJnQQ!h{Dk%f<onN1+Gu18Q{>IJuBB8D&~M);u9m!Fcl
z&ixzp5ONwdzfu^sP*c((36&x2YiqHHn=OS}IzvmjgY9Fw3q5^0hpNa>iPProqqR1G
z`$o9qc`rCj=v{DlI7nVWxQ4s_{xRZ5wKns1Eh{@Q0Shnh<m#1gGZAoj$m#3^BY{YW
z?owi-TYtF}%<=Ujh$AibyX;*S=4Cux_DxLn5{=e{<4e=_qT-b>Tiq5=pg^7QSBkKN
z54S-2gOIT*cOWd9#Fk_GhFn9j-A>)kbp<Ns+~4Z(s1MzHm6e&CE`*8<KL&<yL`%vH
z;{^vClTGShn)l~Q83X$)8gyDmhRoAsQO+E_edIuQ)@nydV+e(jr_IC#U$2zU16K~b
za9i>*pf>c?_cBS+<)qp&2Y^_8WyS3QX3h3EM3?Aff@E`9=NDxFIHS8wJO{5pst-%4
zZt?+<#2${NjJMQ5_8$cq#pT53B<Cc#V}2}RIIAe6EJRV{%t=DEqnp!dwc1EQ%2e7v
z(=w|x_G$>d_DQG?BCqZ*LTxYxwG|(-uM|ErUli`tSpn@5zvjr2DSpttK6K1;jBD=`
zsr#%Xd@=~GC{s)Uu;+cGy=scQGpm&p=&=73COpJTZjX}W9I-=|!0_M}H%Si)q$4+$
zI-ZYukwwR}CM+;@o3*o*7rp863gOq66s2|@ZD>voBtjGp2-iy&K<x_-ZxIh15(`9P
z-kyH&q?T3f9ky6on_chV*iKSOc$LQ!L|~aZQsv+nA_18I0qa3K!$hf_EruJoF_lbo
zGIeT?<n@OKqbO`7;JoFhMpE54ftKI6X^txVepA@^B|@3)LLw>!>=`{tOdEkB&zl(A
z$olYIg79<tJ;t#ySU@~C)NHZVms38_#>IN9d1Vq<OG@=H-1%6cMQ*q6NLFblt4k*s
zFjp5&*Fv;CC3Yb%YCj+IQqZW(UdM)n{)BDh+I4{lxlCD;tnuzvDEa;y%EROXAGDaT
zGon1pE;p=ahib7IsRcMBw$+Ff7Uba1s2WLvjk~C*m1F<lU_`(^nFI`JNyg_uasmBK
zhil7d-LJ&GzOcX6?%~fvOVB07hh40XQz~I@SG={38?nbDov(+J3*fmwj-8R@__~jN
z+XwcUY&Fn~`!zYPWSz1em$+;aLVeU7rFU`UqL=<Q8ZF7Sfh`&y92WK#ga{>bDxbux
zf|pqBNcmMOCMREz(UT4B)H#*MIAea7zo9Fl)4B4ptb^=_({{XN`N4d6U@&LZgWV^O
zGmbMceCs&AZ~+kDweyVbhl(<)ql<mF__cPYQpb8={+b#;pGICMyPxvnp19?RQO+1H
zk+G2Y(4P6X0ShgCmgV&F2-zcIEa#;mRo2hZ?P>x3Rin&(R+M>vIEUZ+Xtv3>*baxM
z#JIPYb*rKJ@84tIl98w$u@7zTvo?}_6BVhSROB)g5@m_OzyH(<dX-?irMPOI8{oUR
zDSa|S|M)2-6AfGNN@|}<Dgg4krKf`Vu!_{RQNKLQOMT?rv=gvQCKYn>Y{$z_)&<{9
z-s<aW6NQ;jUr<zzzR^<CE4PH4DcR|~yw!4at4M{pB8X1EkAp9MAYl{Q9cJKlJNgUL
zfQN3XLjIJh8`(fmldAjggvI{EC^$lwD_BcFrAW8B_=^k$wy7c2DnXk}@&L5nKu!~M
zg^IgrvwN}2-MjLK9lCw8N0STXklDJz?9)1jXp1fTe0{(N0!3hRqO>rjNtB>*^%%bL
z?4{UNjz3I-devH+^Hhc&@6a^4we)!|V`Nj*$|Vw~{WcnBMQG)BTKLa5a@iFbN}5#0
znoZsIPAA<w^Euq>p0DA8456^ZKgTut{02W06tbF3$LJ;t;rIMkzs9+s6D9U}foo2L
zbWMo?MJ6X=JgI*ZsuLAtFhTG^(*pzoG!l6lo7cZm<C%Q@G4@^pbq;=T<-8xfC<>xI
zw+hjoVzk4nyr}a;oZ`PB#7=ze%l0Px4iQHslqiBT;SyQ@it6GMT&~oyKNulE=l(1k
zL8s3Cn#FXL)FZW{dz9J=aF74;`#U1)EJfef5VdWGxF+ImQ~}muVW_BCPCPNHvg#bY
zOg!l_)U9{O!yUz%n#i*{0EI76UzZwxuS>#dNw5}YeW=VhHKfB~M7s9#38=y>x4~;Z
zYRdGnGJL9V?FNN##NB8*1T_KD*PW!S2y;x%39H-RhHL!FjKK-{%m}e9u!BjrCpIaO
zhJ_GtI}b3;XEX2u@>aO@QjP%N#IF2K&JjODSSUKg^CU=P3%2=v9ACq8hpz?WIWO|P
z@t_RsR4~MP>EJopl!EjFZz(*U$AnNh&YK^P`XHZH5L0^PHff5|vrtCjxti>Np?T14
z&ZO~&zGD9&-3Oj|Z<q_Vta-;8lJYhMFcrz4R=1+h7+sNL;%m1I`x=HRBXJkR*Fbb?
z#DjH8n^=dL&w0?%AJE*9p0PG0ioT~TRH8DMa~{eya3<I<{MC7MLe<de5ZtCP%SVa6
zg`qAXFv_vC;xEbGx7Rll^cSdyZCL`ezLIBq`Uwg$tL#ba1acdo1gfUfLIs7gy_G3}
zqEQv1zwbe>(a2mc?-Zx}%fQOVO07)v^O~DnRRz4N0<ErUzLO1QfF}yRmh~yNyI~8^
z2r6x{oNVh<Akeg9z7HRoEZG@xJ|VVqvY6XzPX)c;YOCU>v2oYV>!xp76unC2R+9z#
z&j+u|Lt_pxZhm%?N5qE1=kg2Q9bG<8A!bOn!YslL3f$Tnh{>3hhfDS%aSB@ET+*~I
zeLYh`&^L;;i$!|!-bFM<`h;KGrlp!>*Zw|anDkvMTBg8~KyXG}8^IZa^8`yD>pEmQ
zmn*(Sl!n(&Rcw%P(jF(bKWKT<)?v~xWEkl@Th@Oz&WU|BA%g=n&Z*+erC=A3NnVbJ
z1MXPKK(u5)>y?9Fy}=rNCPy<-XM$1Br{STJf5+Es2e&e37Jue?2X|nNl4g&Yib=v5
zj>0yxr71=Zb5<l{glPLA%^rsIfbYH2wQ2$HwC(BubAo+nAay(T8PM)}A$99}B7SN2
zHo?4<gWzQDGRof+`7^%tE&<=P`Onnvj{jl)kO9{njz}HpEmCBCDWZ5`0~J8Nsq>H0
zy0KvNQ3b{X^EnCl(giw>>-B?r0V?sU1)64uJ37V?8ZhK~FX8&B-kZC>8wawDd6VNW
z2vu6+&*}>O5$)d&=D`W80L#@jxlj4&K!Ots%SEyK46==Jlj6Sv?V-|Z4~~cKAl7RH
zi;xWQN(|ft8F%wf3VXD>Aj#cb61QDW;h%X-i!hKP7o5VYjJq)~rN}q!{#L*}7_~K6
z`p$h7-a#Kr#;YA81J4jfagh4L1qOh?Ef9T-TG?I&L{;e3+k~j=(ZE#Q8)N2RN10ZT
zX4uu{rLh+1)w5vwOp})s<5gY2-4wGDpdS{8kI_&iq>mH2l*y3vXJZ`*N2U8MJfL<P
z{5-?(GK18o%AfsDh|d(VW<z+gAm-tp5G4ZR8Sp(V;0g`bg9`A<GYHyWQ_0UlYcScV
zo<<=E6Llt@%t-}>GC{SIfd<f;?SuQW;B<9{b^hWY7%)&xf1Ub3{>lQwV)U{OF$vC$
z97FB_fbYR3UHkATCzp4rfg3Um%~AQ*z*sX3+x-C`f8~2orEgmOsh5ES%;5Ma4DUcZ
z&~V8?2#}TN3={mrz~wGL#pRj$phG|iP?+?Egu91fGl&d=Ab*>@1ZgoT^lEN;UI2~W
z_hDJxF<<ThGe#3&3`xRb6%BlXNc^2VBnAJN3`PbCJs5QW9th3w(L{rb;e1g-4aH*8
z?Da)wDh0VhXHq&Fhvew<Cv}){fPy|@+`a1H`><o&T$-7>z7y){hPcMGauqcIeS;cB
zpY2FZeYOkK=a=7}faP~~*<J|7!}lT+Y6jNYa?K&n>p)1y=9yt55)HG{Q`?>juBLGr
z3!Kgl>~v;!k$JvR5SIFOr&z_8Y=M>upI|L|N^*j^N+HM7<ptp;#Lti+f<+S7L8HWn
z1RIBQ_Qs(+z=m4~t^y+k#b5znM&;wnlxO=}eo*m1_<(eR6o7d+1WNjcbZUe4>H=LE
zJ3upK&21v>4z5jG&VpM~l!D-KO%V&-2I|7WL1JtBBi3Sq74(c1RSU@zfmqVh>p#(5
ze)#PXe{Fz$Oi=#q0Zxj`_!nyZzj5t<K-T}@+H6cL|3R9$|6e$k`5y@RUzjxG{|}G-
zpYW?*!h~HA6O#Dz-$<?EsPHgQY4TvzB3umL(ndm{r+5-{6YTokYu<wh<ucf`ftT%y
zUtx!ve4KW=#GZ%^0LKs`7mi&PgCOCPTNa+=KZcSG+ui#ca@iWt=^M6Mj#isY73G14
zK?terHnraM&T)t^KnX2|%+XgM9W~ChRZnN1hzcj_QfhiZLjn8xJYV12ccs~`ab=GW
z+AqhRN?tbkL<o9VvBxGcFn6%wvODt1=Nm(<u&hF+|ME^C8lOVmZ-J}*Nht)#h^z5L
z$%VX8`5yix{tV<sSI{EOVkIObRUsCD&JB+eHKkdcDavJ)J^IBeyO;3FBvvfqJD2*S
zM!bew<w1P$x!^keo8KkT8ETP&%{G%qF6kVb;xqNC-I>v)eN@tq>Cr*mEwlaVD|v(i
zQbqX}%aO73*WBLc&TWH*hR;vnEV5$6e@ybfZT2rq{M%@(tnB}>8S_8D|9>#_|3dEn
z@hym%Ih!~E99-<3{sH3u<!(?gvi<fQ$jfP~X^GQ{nOPaByQ+Lc`u}}h!pIizf9f*3
z-n3yT4BzuBd{Y%PLH&_9p?8#aYPCt5+O56zLI{>vf*d1l`}KQ|O&}>WQ6&8O_~U#y
zk$AR$**JDF>YK#Qt*P+ey*ygpMY=E*Tyi!|v}7WiD^La{50v4_o2@Mtb+s)S591bX
zL6~AL^U$RIQF|)k3hi)dc8{g4HXs?8CP**7{Qb)EIG!4hU4uMCIhK+ULFf|&LMZ3a
zh|}$V`G8M;fLTzaf_i7#GQgORB4b_ammA}{0DLuvwvZ9P48zSrLgI;er~xf(U9p=t
zTQBO?c0ySB&93~W1*K7fytsTT%@6%rY4*_rbcEi^Gmx5QM6%+o)9!bcpVrkVuS`)b
zUB0y<UW9c-H#*wM>@){w37k(+6SN;<Jw%_N;0f>v5UKfDTOv7(-ZlNiotH6Du2`L4
z?26(<Anf^wvGxSLdMruwIoWsDto8-y(YP?yHB8JzI)jVjjrY6T8vr?|l{34IE!tV*
zs!1&MCFq~GO?^)=Z+w3%xs*JYITuMP^d~N_IiK_wJ(0i;&MggUzo|lsg9`^VccNZ@
zT)7@`CXx|9UJPkbDO<Cs>5Qj{5M8Y9G%hkM_fF#)i5X~UP?83k<~%_<hMLv_AA+IA
z)f{mgYH6OI*&(OM*w9WZ`F<}Nb%O#K+GXP0E|W=bKJN@pw+meG#r`WPR`im1ZW<(=
gVjd6JQ@uuRLtR7?Xq*qx)tQ_pqpPcjZ=Xm10pXDm+5i9m

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..5025819c3db55cb23db1b746584e3f995ca67a77
GIT binary patch
literal 67660
zcmV)&K#ad7P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q$ck^V`EflKiig~m{q9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R`X9q@Jj
z{RL>Ve~K~*f0&)mPf;e}58d87`a_gS_(L~q`x%+d@4MJDC|JpU68^P2VBFr{qGj)`
zI)BIhf6ETA>;4dBwEr->X`iA@!XLW5|Nn<5lkkUb?WQQB8wh{sW=7G%5`geGcYvAy
zXn%bOef=BmfX6>28SU@qc3q!xjQ01P=DAC8wEl3<^k44z{x3Ki+k`yf*qJ3x|7xj!
z@6PKtLjP}4dY(_|ef|ZqyXk=>*mnojdqXT<RW}jdH~hc$92oC$`gq?LU*mm^`tKBx
zzr~XGejnQ~(foF9@1v~08CIP{__mw9&&~DE)vqYucYMpi+V5LOQNHi!BbD#!D9Ybh
z2J^QTINzti^Zh#fja9JOei5^xd_TqO`9;u*@_ol=ek?rO-*#$mmF08ki}HQP_c{8x
z_C@&{E79I(M1TIcBmUma*xower??g6`$^8vC*seqqI}=+4*hZKN5c2rp0~1keyoNl
z-*)WgA8XI{-&l!m=Z|^!@%VQu@wZgO-t8A*E6VrNdq4I*g{>&xcYHrCKUcme-*<dJ
zi9T1pDBpK{?$4DM;qR=)^Zr&UE8nig-@7{BZ_H0&E6TT1TyI+cIE0JxeMf(y!+!OW
z@_olSgLzv=QNHhZ_q|iJ{>D1^`vkT>?}@*qG(OKSf>xAor?w0`AA%;r_uYE`Wz~!F
zeaCl)&s8tV_Z{DF{m)e|%HL6)#``v$f7}y)Pj`B&slNzXQT`y>pL*!0j`{lf^@sl@
zQ;zBW)0+5t=j1%w{oZLg`(LO0|E>9M$9Vg3-tAr&>RSaYQ{%t;f5jI&$9=c=SLa(-
zIM?Uj+v?5RzZTT@=4ne4$ro6(CRnm8fAKcBXv-^#;~}#sZ?Qgtl#e}--jq~1KzaYy
zoAS{zyefmT-Xw3zTV{`6NNs?yo*LH~KmI|e;jU@4`9#;(*RhjapITbiqND|{D0oo^
z;r&mGP?L;tEmBSLEj(|^6<_$I)U?NHZ~r~lw>UwMhZij(MHw4kdKg>s1P5jD?oD~K
z<=82{F{Z~0&tpJIX(I^5svyv^6`Zo*RR2LHn8VJaPbZ}npDg&)Ha@-Ca|B6zdbg~2
z6fN?{U`smjU=2!4Cic@o(wfctfFM_jLayWo+PKAoe8w%x82X`D)^UpqmMb<c$+zVa
zyeXy;#S)CUKFS{oj=xE+5e3KJ6w`=;onweMmh2lNc?437$i*KEzAXxQbmop5T|CMi
zuqfiunQR+PJUYRnCLW#OQR9X>!J=G+1Ed&`NpeoG$i%c|ka!<xV%Z4>oj>@q@1Y+-
zFpW6a<J_2wvgFTeTjn1xifO#-zus#8z4Z$2yea5*rBEyix?K+pjTfZ!%F}xh`jcDl
zO<E@hUJFSG-uUD~;BglA%E2EFPWWW&Jx8ata1nwHZwj{aqQr-3JX@5QwR26D0`mUe
zu}F=h4UvG!BPluQu3k4L-P!5JoN*R|6fAFC$ut-)0v7U3$SKk$xF|VAi={k*5KS!P
zbz_nzm*l#!v{?OjJEnMUU2L6rtv_3zm{Hg2Uw5>)gjY_d^FUsN^^tzp62|f_3YRb)
z0<B-wDJIitb6b?y+#TzF1S!_2*TSa~vnX8nE4Ol=Y^??Aqk0_C<eyKBey|lk=Mt3s
z)S^&OX70M~2bwwXzIDlg_pM8gTO0mOS&Z+w-;bokmg;Tmm5kTLd*xNLC={-|>lbAS
z*AbLpwJzRkV7%wnsl!ZPf74;fPx(6*DfrkPitR{Nw!3;oixTTF{_DVgQ?9k`+NB=J
z*F~vb!M=8Fy@GvhZoTr1YIEzBqnlf|9G<kF%cI2}^i9OP4v=CBt{xr3^Q~77Pj~Uv
z!MwbT50HX;ee0IP>sz;2%+~ZVC}%DA{E?(|sMM~9M$~NUmLt-ke?bvxdFbPZLg3oD
zb;}W*TeoDGG%{#-%^qDb7jAfa)D4%nJzKXJk(FTJUbefYhCA18iW9C}yS84zA}is*
z-T9_89C5fPt%L*jqD_f6E<v086z)8ergp6h?FdSB3T{|k2<N+{%V6SOGMx+)w~)Cm
z_L(Zqn}k+!p>JK12~xF}UK^wD*$Ow<gnZ6ho-zJ;-U=pt?M=upN@trlzM7iQk)-^r
zZQb&-@UXrK(ZJC=FHH92A)k8ln`7t09%&O>1Y8Rf2ln~!Ho+6Koze+rYHG(K;b-EX
z*<t2~PpNnl=kF<@m^g6HOB;FOd_5%<GtY%Zscs=%C#7PAJS^^>DHTVO7JE-g1vL3Z
zfmFOHIZ6ITPOzk6-~v6R6V4Q(MIrm))H%CW4F}`dwFb+0xY~v%)^tpg3jNI2>>_Xl
zJX&OC2Qzhc%+6IbaKFb#q%F>lZ|L@b<9JcXlO8R+XJ(#f@4wMb$s@}YzOpDI+GI$|
zGr!rAW8sV?DO%)&;S<st;q|fSl3ZDQA|&ttp@+v<PlK6y(Xz;s9VeW~B_t>O%v1Br
zc`rvZ=a&YTay>6f8$qCu<i2@RR%<+|=h>r&!-!q92$<u@^L0@$$MJwkopT&eKNkr<
z9RCbHuGds_Xk5E-gH3u>j2mNbI<v+NM)41F<T_7Ap3jTIv0hkU(^#*3w%H?1b6glc
zG)+9wR-5C^fD5~&h2*0xD6}h#Jk=KoynR#FINp?Oz5h#+GV<<U6pn1<3*K&tO1|jc
z6de}B(M?y#$nCf&{H&*Fy-8@UCBFyu;&A-v;9eZ?s^5bGIC8h!9iKZu3g+K@P>g)P
zzX{Q5_zj&C1DosCIWZasrl)_t84Wg>B;@GyycpP1H=maSTj~xS-~cIv1&{Nj#1EG!
z7=E}!;lvN8BpgY~HKZt<SizIuKIL9}g*7@uC>TVtC?OAa>CxfX9hYtv&s)bXDWo2k
zrM;g3*tx#$oYm$9>yUjp`W-J*!@FTo@+z`R#|DC#EH(cFq+r!0dGXX|-;`{<|4UC0
zhn!y$7ROI55~KxBS-WH?@`<tOLFxn1CAw>T<m9aEdp<BW9V8yss6`mrjQ`HHPykDl
z9C&KO23<5MIX0P++%Y!YK8k!Xy>b!hV3(dRZ%U3$Mkepzn{*ZL@0QLLZ}FyBl!5k$
zR%0_)^h7Jf6RO&xK<=TN9Z3rDoKk2#M`Ke8E#B0NLMc5FqH{~l^3+5ZiL!&MVoIIq
zc}-eb9eZ8{vtGG<{ksII-v|y0LFyM;1FamoE*89lZFb#+ePZmoDLTYv>Za(qqiyIY
z?U-?z-|~kr<)ICQC#4NpRoer~+$b@k5h1Wg5Db5kYt}HsG0}<@d>_;N*I2`$+qGS3
z+cTWxNqX~eIHjb;gJBT{{~%i6d4|s{0+p+lZ+06ru{vIsivnS7sRAqtnAB1QSQLYu
zxD9Ypyln%V)b_!H(}onc=3rZ+-qEndFc@4f@AEeAo7TZIy#n$0Tom%D$0KJ^Adl_6
zmC6*@aF-0JcCCR6dI{hqYH1zJ85*L@r13S}9j<NGu!G)|fp)C9KYYkFXj=Yg4fEM%
zWk77HSNW~+ozcSB?7>;*dOuihYjcUH;aYHsD4wZ{GSCj*`z4*|P0HcR<Y<sW*DYY!
zi9UHGSO}q~ezGLpa0j@I6b79qt&%puH);_E-Nt3Lu$dydND$ul3pGDHxU4q7Ib9Wa
zw=T*+JC@q(t!j>M>7p>4;jTS^P+C)n+M>jgbefwCQGgx~Sc6EpR1a(TjC4?I_>3+O
zGi>OxcA8;I*#(Na>*6q+wJuczuh&K4fraPmo3vWz6U!rEKOd})g#DysNJl+ysE>Z4
z8FEp^(Gzmf<=i;KqPYnCRcO9FubVR^$hyQFZ`4KMZ^Y5K2sj_k8Ld1o&yjXj>$+CX
zl!ZmXLY=tBJEZ(f1J-IoYEE3xed>Zf^Q^P7ubxm)yPimAj~0aS#De3JNeV_c(aezz
zP1i6oy|Uvqy4svAE}CAx7d$_$OT_aDx(GScju+^n475W;I*<LM;|aP*Iod_Z_48<@
z#@MMTEkc|pGVU%)zE*q3aQg!dQTE<N$)8D9uXZw@_TT<YOfl7&q~r{_Q5Ge6&yDh?
zM62ceaQSo^gL(!GuCW=ov`9HWTpa!JoFeayMaU_dzJhZgY|1${+&10xsU9;t^&O~f
z4B77w>;j$k#$%CE&QE>Guw<t=1!YX8={F@><jILMzdd6AnTtw8^&-Ta8($0kP93W;
zTV)aAut?S804ZkOsN(heR-p7iJ2=&D2-Kp))^50fjyDOy(DElj5E}RCY6qJdZ=;S^
zsL3L}DESs>e3dLx%iqZv-b0-@!vVfcO)>SQMbQ*-E3~O8;+@+jrs(R#DSEUFqwP2k
z+oUAi9qb?aatHsp<vaZP)`mXJQ=$!gxv3MsY`JJdABU3KhQ1B8qB$QcJwyB!h2Mq_
z-dx{4)hj-I;lbHxjX4&Hof`ipSDN;jeo;C)=N;}hYrH)>eQAq?)xIbl^b{;gc7ilt
zln@;zcz9a+5)P2E6Zn7_5NlLAJN!aH!OuWRXc<4TWECzRYfYnZ2$qf<_-BH0@^9FS
zLVq!XAm<HDwCNPe*JTj!8!&7%nihJxHI5*0Fpa%97E>>d#q=p0=ox^r2)H^roCwxV
zEfh4(c4|C%nY5D&H6L|?gKm-73u`qW_JYXb!DtQ7(M4dN6q{p_vQzv!jBBRjZss`<
zlpNd4w~Wz1(kCu#lT)U{CT^xv5eD!@;oye8g~6pn9A-4wFA{o13(_FRPDhMNP%t`3
zgWa^Mbl9EEsLw14yA8D22}?^evLScw2+{}ww*PGEge^$Ju-#~_zrQqA!}haFgT<r6
zbo@rXMzryh=?OPWwW*IsJ>bh;q&OSwq7)8X9Y!B!AGf+;thBt^CBdYv)pTZ$)E$kF
zj75ke&yer22ysl}>9F`TCOcscw2&g{bhX(B+#YF)3JRt`)qzg4HzgVn48*)F3eFt7
zrr(roz5i>F^@G=h=?b8w(*|e4^da2|2!1i+>t|6`rz1!~Fm>WoOr0R-FjCs!M6mx&
zj^9N}c^q1v6T%f;{DEN6{nz6myV_Wov^E||${G5tPC3IgH_Bny@k|X$e%0}YT!G>T
z2q`7bee4&6gqKrytTzJ^x^ul9kFrI{6{pv_J6Bxy7ao+0f)(}n)%Y*x`Z2DhJ2V4j
zS9b4M3u()=?^!1YI@eG7v$Dpzn80P%o#;5{O}C;OkE$*<7*<RdrNi`Wuw{1VX6_W@
z&h0F>TJPM>x=lN`bC1>y?&@wu6iZN&6&)t!Amv~>{2vByUGI48TO%tv^m~)W-{Fc}
zB=7>SBtv%OYKL^wbksW!>76n#KAu^fr!+muz4MUPz1};x#YcGW4cuzlIfyY25@vx1
zo-xO|=Uc<%r0%pXf^sAYJd8g$A)SnLS(IeoMu`^IpgojOIyV<7*;$lZ8H!ky23yYu
zWm()7CD#ecy2+#7)42H2PDV+2X;Zn8h!^cNC>l)`i(>dTDI*yrjfciVP>v)eqtavB
zn~PO!lTldy#$C8m!s=rtRjM^Hq9`o~0||j5_DM+xq)7pTVzW`~;iPgC(w4Rnm@^uT
zqHRZMq>=k_?mcL!DZ;HaqP76DOO4~a#7hkSoMK&3I5ukj=MeY682J7-ex9xY76r`9
z@pWowMIbM+)MwY6NNFW_DIaH};Nh%-Z-0|K8dE+f61?Q+X(f1I`dJ$;rT(n_hK+Ha
zTdUESqRq7^5-O6m{T94i6mlxJ@uGlJB&5Q2<WaDiJiPMsXf&Q|l&P~TkDL}+b~uy{
z5IzsH_Kf{71BGW<h}9zSDC_CFY%rJT+-z{!<8TFq*MVb7aP*RL1c}!{eyY`NfGM=P
z4LpCC$_^a|?SUxhR%y?v)1QlQih*2&Qw#*p@6>OOyy8|<_hb%+rVrhmjm8h77pdJ;
zUpvf1?ZzJDjl2jQ7de=9Q-9^v-fr&7^hO?w(8sP1yeXT$(C#5E1B{}ngL=oCK(!>t
z<>~<@-J3Rpfl-@rwC1@hM~f296e&;*c@w2%HMrNQhy}r*b&(@R&bwG*QVX-wDW#Az
zKBX0M#;3HxG#@q^F{F<++AyTFw(C(Z2tq~~r`Fpp#Osz?+%Bp*G{UqC!5>tw+eJl(
z3izAy1qD4vM#U#}_;yWo!1`YEtDXTXeT9FYtC_*6`)gulukam!^}Bc`PqbRTU$A@^
zmv`!jxVXlXGwJMv#iEr$52to<g(v0$&8S{qjYbN-(1OBFm=IOhsg*e?7E?>ZmnmmZ
zFH<be<ST{G&PB;SaPqYIs1s%|>t#C7=DQRVn78`Gv2#R@3_D=~=A~{}fXRnSw(v-~
zHQ0$T6+P$|2|dX0IoOM%r9yOLv_oBRC$20R^uZxHU41xMp3t`j+q2VyMyEXmr`?1J
zleQ9M(UdiXSu|yFVG<3jGC4NGW})pSvT11W!Qf2YI5=F+VIqp$nzWRj;w25-Ff&DJ
zP4?jM1`XUaRxL^>-!y5xBDIFyz&rT=%QCho{1yZg&i(^7Hjp|Db6_Ct6f)H{L<E#M
zufa}nl*zBrR3W=yqp3o+L+0p|c@a4}>xXh$DG{_!W_k{-n)nS!gzTIvJqMk*cyRN}
zU>cM(95;=nu@{Ge_YrKfN0PFaZq5PAw(dzrTFDIDhN;uYu#m{%fx(%pb*dZA5hU@H
zQJP6SGF%@)8fDsUUZ!pEf|d*z$XgmRWI%6@n2@rvH%3V{T`dkpPS*OykSJO7SGvwk
zF8~DBr@9Ta+t@q@jWJL1E<{$(DG$T}68#wbc=<l~@$!A}+vWWj$tmBQC5`3{y!Mik
zz7L(+PTz-4X>ascU1T_p4*7Q)<CNqCT1h<D*!)C`kZXN0crX%uPP&?y<Rf1cl6=Zr
z#VjBCvm(VOY<_ZiEmCq{XJ^OTOTM#}#FGm^_gd>Xjpc%C9Y$^)j{O4r>B(zwRWC~3
zinN%thyLg{Y4Z(6j!*bZ=|5bQ^i<NxxDtD=QEteVPUT~BRW4Hc<8^#>#N!}|CJ1Bm
zh&Gx}(rcPSqxanSCHl^FEOq+M^>Bgzmp<Gh6M*2v<+l(VEkAHW|MV3HA%#QU<VC<N
zrNMUyhn&)p5fsDGA=6K|sk!=iDD+aD;fGECcw=;z{O65E7dhGA6uID6Dp1P4y!5Rx
zgo2Lz#sIIbgQ7vXP((mWlgqIM4Mcj-*aHig9h89ws}=D9Q$t1gRt7H|ASL%1-Oz9l
zRRlz%0j5t47%ueO;zv?aq@YycK(25MrUq5W#>(-@;UKJ|H69cS`)IhHDl#N8gU&sA
zgjqioa1u#B8G)hA))+n^wWDQ{X9l*cR)#k*@}<Fy<EQj^#a2mwP;8a71;fqZY-JFS
z=~r*4@`~GOc5iV#4T@^U{j64gKyP-a%m^MjKtiaHek7M(K}c@`0+b@*CxU)pBW`@C
zm}^_$`BPC(4Ns_wj9L_iTtR5_(RU!kDk%!UYIp%xh*rbXy27{`-tY+ZIzY<L=&c0X
zgkr|t1cZ~dH0D&aSu-9Bt_O_av8kxFmE)5^PkM~d{-)@+$P9{`!Y@sZ5(AMxp=T)0
zt|8uvk$9_(Xg<EcPS}eS(zhtNJQDa58mXcJnJt9K!Tcd;9}F*Cgn3r{;c9n88*+3|
zP!+{^tjwT@3S}~EBoA%DkVqY>cuA%XRZL~14#g%`&}BOr5h_*qWJIX+-V;WA#&<TD
z7!SkGDjJj%M2wC?NLQv%Muf^*M5E(So^fM1*N|Ojg>xyO6}d$f^V-q`si@e<F3S1I
z4syawrSRHC$-q+A{Gh!kLN{`b;zU;vFO!Zc(l?Th{8lXRYA55Cysw0!doYmr0EN-V
z18v40Cr=`)XzUToi;|(W5Y$6yMJDJ0qg7Jz(JSvJL(8f9N8U|@W<$?Elz4+^?D!*w
zmb<>s(DEEHW*E`lE9)gR+6o6>q&V&wFCK|76;8fVU&a=29?3B=s+%6KMarRTGB=~j
zsR%Agj+{^CMd^r~hv|NiLI?%d!JL{3xR0Egi1|O!%6NagTo)nb3Gw_ZUFN}G+?a8y
zbV>+Vgt4Uz7|nkLN3uvU#mh8&9N|h(Sd^Hek{A{xcIu@ROao#J(jkHZOA<3Cn4H6O
ziq#%lwuRAhsEiC_fRxfU3>Yhw+F?L7sq_z1$dqzK3>Y7kNP_g8E!o5nMs-az2D4NS
z5R!M)fSAft`7Q>yipq&GU{N4%<^U;IRvYVvHmUp@qm5E2I+67gA5$EjUCiv^^THT=
zrGy{@q(UVP@h6c}bR;Ey2U$m}otae<EC3f&@)8GM2~LM)e3nw6$OI)$82|(-x5@w+
zQ2AHE-91CgGX1}@xQy{yk@saZfif*@5#sNaIkqTFID;@Sc1tN}Ax$w5=n9K4kiljb
zk{>GT%^1d|%(z9#+1?sC)K(?kS>~D_TaF$#84~%DvL*U40f@<gv6t6}Gkx#?DRL@n
zZD1!;9-_f$TDgjbT=2|gj3eb>t|JIYb=0t!sHszYB8pgfm5XwX%DOZpc~@fQqU7*-
zCo-3)5<C|rhwnODCKEOXTA5YJ+iy|EmS!5~b^bj!)MSL=0~_|6vZb>c?Y2sJT@+@{
zLTqTst=w5d+IFSa8jZV3!Cf~}@=0<q;RJu~njvDE!AKnbN(5e%HnvP*qe)oV#5Q5n
zLCSGbB1xNCm?=s7)FLuT+q8(Wfg<nuKs(a?l^bo!($)o`EN$voaciGS!9J3bU((i|
zj+AiiZRKgxaA%RHt?OXoxm_vai<If$F3x18_P~E<mUf8>v$Th<K$x(pqrRl7C<ETo
zs9iboi;(lf0dNE<uoKQptV}Q}CFCzc@={921dxOh`;UOKJ`)OH;7@Xfw`9y>hL6|}
z+$I4GEJ~m@5QAV5613qI_kq78ECZWFj5yhefDsB2wTJ?2a`~@zd|E#AMM<=Zrd0#F
z5naPel?A+!9JYq=!Gw2Mt^6|K9~Nb701=i+-v<yRR&%jh?n6VQVWChgjWoYW!>b_=
z97q-iNC{Oz>xm6u2MH2`s;y8nY!EeKG6XghV!t=^4TF0?2pxuW@dEL%3~DT#k0X@t
z_?f#p4VeqFonw*qIj-acb2JwruCGESd6NWP@(P_l*dTZl%RtFOKrtkj1104EX~?FM
z?HGw%6i8bvK$b-arU<m<Snrdjpz8H{N#vQPE_sB>BVd`Pz9GoOlP9p*WZbtw*dE`y
zCGd=I-4f=-w_XYICbRo`g(dRLP&Ws&hPrtUac-SL3<`uN-gg^LkHODUSUy2HZNvMC
zcVi6j;-l2yj49xt_1??@mP7!{qLoAdyyt-_)ds<Po~=_t<vd%bgl6JpGH{d%9O;O+
z@$+m5N(R3VL6#O_!(d{nXW=vjB~EmKIq_NEWY#r=yA~+aqKpkTYPEx(y)&#VNHJbV
zD^R3->yaQ*bv`tJNaeth-CqD$1|)z&$bu0f0kjOb00ppRh`0p^*8$QfpsqA^Jog6X
zMdOF?z6=O;1qpTp$#3F@;g53gH+$iD7y6hXy0_5DY@B31jh$h!SsxS5Sy22I5Sk$(
zxS-Mu&NaZP9U#TD0Jvs@KzVf*;F^%ZlGY?4yB$GFh&U;o<1Bc%Ws!;*2|>=Bn0Sm<
zS(HH5A`l%7TLo5U4lE+!*@ZDIzALo>fPO~-<1JFoak6#VhN}k?TS4zFLQYwM?dC+q
z)AIWc`WLpm_y!H#29INb2g2TWY!HKC6pSxDTen=rXX}=bh+1g}q$Cj!4PPxxMA{z<
zH8Ch-M^-dIMF4*B0BNy;HaVst7l@-_$_4beD2W)^8M&BUqyaeYPg&CpuGNB_G=z;e
zna(WW6ORqQ(g0FX7?(jgcN|QEixyy+q!3Q?03lf;-Oho*SH>|Ig#q3PN^s^Tj@Y8)
zMD-%vD368{+?uE4GfxyEj>Zp76u^-AXQPlm!1NQWDUI8V+Q1J56N!&n1gY{FX-|w*
zgUlBUD=5bX)k?#9p}7X-+!0@kGAKEDr5=SG8>9_emTlPqeF~43l0(YH`NhhWX>g+y
zqY{kv-WWy7#;C-ny^B#vcs51_K5cDG5pE4P?0kj)OFu<H1P5jDjv&H2q1X~mw?ZQ(
zDbb1zsSkx_TokWK3KIEXQ;H8tSro3aD0i<<Duj@&fj~Tc?w%WWNZGithJ5Q4E{fnb
zH2M49B#D%bV~dCPvvCXrfSPeFo^xXe2%8wJ1$}H615juPqhvg`i9rzBHqj8Ur)_dT
z%Du~NM#S2u;6Am_Mzm^|jR><X!HHw*aeCvmqn>}*W6!q7Vq-r07K{D-jGb3W+V@$M
z%-OeD923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY(MMR|Hy{?uHPO=h+V9^=~VD
zyAESg>M#zG>SZ6niM=Aj>oi`A*-zU}<29QVb6%%$EZrj2ZMD9#qS@=VT0hy#*nyj<
zm%+o4F0)8=UEMLFv0YbpjA(4v)g2=m+jaHih~{?PpE07j-R>46y0+Urd30^J`!X9Z
z3R!f6A@_EfCqwS-GG9Ym`3YU>M;zpfG&P`Lh@G3p(yex5YBiDdpy35CHUkCpqi(i!
z3ucswVvVHC6TnsJic^PHb_D67(rEGNy7A&1>59&#0@#)0MFnvcH<6N%=YB^7GZoFQ
z$YUy_U2()zSUaPDkFQi}gHl><&U${T#@*@(dPYlnbaJehIU@DIuJBf>=!?Q<*NHja
zdPb$9e=HK;Q77ieE;&P)GV!433iafpqqj3{C;77IiqYiLr7QfB&zr8uO1^-46PhQV
zNsILHl<G|fF<x6;;f;KeElPAc^3AqVgQ`y~kzx?}^y^J)pD)AST+b*=%gG{DubhLc
zSHm3Ss=za~BghZ$*q+vh{hb?0Q|gm5nCde!^J?tR>Ao2s;Ku8l^`T)AuB}@x!e)Gk
zR@o5Z^hm?QK~nJh`7|Q*56eSH%ZKG5BnFm;vR8DO9$?bwABKn60Gr_<nY$Su93sD2
zAM&Q`L<*r5rf;@~Jb3$NdsusS<p9E!4s%cMed}}OpH!C|U6~&o!}Bs3<{M>^*ll2V
zdWOP`)q9yI2gX-da~i~yHTja!EHW$AErvL^Z^i2NOV6z_Ghg%Ejd#7*X%L4^q<x+=
z_~lsct<yMyP<@hF&(<kM@@##QS$gh_D>78c@4VZ)mo&r~wg~Ew193^idaZT0tw-32
zm_VDPH4bmpB^cr*3b-&gYXq)GFJVY#ED8l2mtmPC@cLVc!rVx>*}U{L*rpeW`!AWe
z(vjKi0VjAk<elWy&<|M2Bh8tI!xNmC>JftBQn+D<?|yAPQguMe^-C6gW@W!*_3vf6
zfM=kW=^}gwJ+LO}OUREuTc7;6{MYbObpOSX(P0`oUT}5<g`M*5??cx`cue}B_ar_$
zq#;b8YV{%KHT*LCgNBbv!%NprF9QbN%ShHgKnhtOv{&T=x+`Xgex^Po8}LPSoJ`?Y
z!Xc^{A$qm?kZi=mdqES>BZLzZ;XrbnEdp1}1Mi@GaUscN@_=^^pb0NI@BplEfRr<o
z`3j!EUQt8v7WP4ZV{%f5Mm+70ppf?iAJVCT$9^BYN7A#|hprJk|NBr#G(Dt!O5;x_
zYDeW!dRd8e@sbx7fEclZ;HzCEGA7T=MFC@QAe9jXZs9(gM2s(jDUTN%%zbvW@;kC=
z&-gcq3XYoDYl2X`%cK&1a8|mepFF@x27e?Dm05y<(7-<Rcz{Q~PsT#PY2WA6{Gg;x
z89USU->VD|!vp%%6@w50z_h#&$<!+X3qc8emNOKQ3w`PoNs~vPL_=gq#G+s@FoG-!
zV^NmorBEsaT@c;o#mJ0Az!{9*h(r3KC@`MmSR@3AK;yZz@ThOlFD-n;I;}QGg4)}c
zt_+l8AQ(_m@>le*k8qU06H)|AEG^4b9SUmcmyDkXeCZbhV?x?5sSb#p2?V4)w&qBf
zBz!6N%*9h60F@T@5@$Ry5*g1B=CdgDup<<xUwSk~uu$Say%bH<S^Jp*NByc*MpRzE
zYMCMb{}9{MuZo|+rK#AaG!Z2D)gDFFZ@nZCYSnLD5D3TWw-ku`RE5PC1GtXB<}$@}
z1-oxqcn}KKZ$2s!Ek+cum*T6AfC@WF3R$>y5=3O$YBT68pBlG>1Cecu!Z;O#zXggJ
z#)tdr9%$v1X#+x--6AmBt>dJ)b%jK{USO^<+AW0r)~SGizkbUm1j``6-1fjhBEG#8
zUAQRZ9WI)iRw4u`_B(%daBTFGBhs;#Nibp|iB$Jus29QPUW%s-#5=sLGUhT!96#=i
ziqOK``XfIIg2EO>{Kp0;OCo|q7lq-Hum?R<S`lly2>B32IBJ(+5h1G!FOU)xH$Vk)
z-A@7x?jf;9f)HZXIHt>ph=~NaVNM8vw+kY%D8Zxt=-NQ2SfDdLq~!Q@10WQ5p*-dk
z5iNWyV9Se?)yd1ehOlElwYLzO>=kZ=K&b`7NtPqRIgmOr=rocL&a<MV1M<^JnV?L@
z-sdATa6%Qeo!yj>fT-;N9Q}yw_KGuN__xa{hZyldF=b@;daJK?*I!&iz^4&=-=m4(
z_dF;3yuK=oec`A!{&O;u8;Q~IivpK4W2sygJ%-e~f|3|@?`P#74Dg`xixIx>z#LJG
ze*nmGegiysG{d-H0&_O?`AjBohAtu5z{4uYWP|{$ReD0Oz?8px;^HCnZKXZ9DYp%C
zTkyGD!<?JTa)=y@Lm0c2h~cL6gHTC5Avq$E!wWY9sUB{PV##a}FYpQ&IK6-=kXGV_
zGJ$cssWcw*QygdzNMVWgMMCgR39i->xfq{CVGA#O1?13p;VEEDURVi8##u<pOnE_4
zxC`jOJZtmfL!KNOnx5k`Q`2*NX4dp_Z#nS;fMXU&(8$?=aLK5-l9${rO)!%k76t2x
zl&D1ki!Mw?sW-@~S}4~186<HN>RP#3@kjWb8#7YsC(^sT66Nt<Zn|EWOSVYphFr6S
z=Z$X2NApTpZ;*wI&dMLkkU_7ka#%PCFaA=7oL34tP|X9B9A^Pi?YuI^0~$Ti&2y~~
zWwj`ojF%GSO8!0?Oq{MTE+z|lrEMdja8W8vF}~zz#N@nH0wq?jRRSfJPeEPGhxAri
zl(E)FAjxA!xKEl+Z)937O53tAgTUcF#IR?wXRcGFRN}g66Rlh$<y0bL)GLR&N6@vy
zO3S3v)yB|~nCi0JB6~GJ`<W-3o4l#Q6LVm_a;A|d>y<N&Tv~732%YPGF%E&jRjaB1
z6J<N5$UIDB_C_HBe9AFPSO5=X2rt6LgyCF8Axt34*taa{k&{xMW(T&rZ%NS;;;f|T
zi8T{CM8Bf$0y&k(fOi@anOE&wmUNy2zGX?rT)hkT0k%z+csO24^Y$%GI-k%{8Uo$&
zdh@RR*rAPdXm<>`S_G!iuSd&jGl?D|(&Gn^)V_+DL&h9gjILlhWXH4M`AZ4(UP;qP
zvUep-JI;k(*>FhK_s*vZ6Z#j0C;=Vpq=$2X0<2d4DDd>XlBfYI-~th61eW&#Wk@~V
zyOQV}3YB-E2?6N9E44Zu_s;BU_`$swFvC<ACU66E!TYbk466zVKMp;j7cj$(UX_X(
zAP|c%&|(*U8#h5`Vrt}Gvew9pL0U%?Bq44Hg+nQ;aI?9r{Di$&ln-o-{2?Nln7R=g
z10teR1~42h=K!%f4i_dq@H`d)z$zV`blW0V(wXX=J{weGN!$>JRPh*sv&Ad-J6$Q>
zgD>!qtU@o4_<@{cS8g~^P!@sXnCdmq&W|W_7D<oZX__V|OO%wsuRt;A4_etnXBM0T
z-XAT{&9Mmz2X=l}2qv*+ywj3NJeoz}0-<_`S57(%@IgtLN${H}qyv!wIF2in6976#
zkO0<W>P563Q?L9BoEMeL4oi1XaOb39+bg>rW^C5}c@a8j)dxZ=I!Irc&Y=-m0^md}
zG4vvSkvlE1#5i)7N&^(6s8ocj8fIWu=qUh}f&%$Y3?>#qdI_RwQ7pshh~wmR5E1Gr
z3Mt`-@uqN{wlG_I#k3MuYLSR^^r%~Ig8-*mO%51Wg$u^wLXjDF9mru!jiOMwOfY4#
zOw>zYTJ8e60Nz$mh(VT`-y+3WPz}}P&?2&zSJFSwzZNB3<^TxuLID7Tn9B=BoH6&%
z_Y#JT#j##QDLayc&p3M!h76a3>)eM)Gbs2>>RX2^-j^_I?z#=GD_X!DgQDPt4~N~J
zkOavlY<J%Q;!^bVFiLCYB5(o^q$+QZ<0a@hSEMoF>0D)O2w@kLoD__U4#(d?Bs?$l
z17PL3;*|-g=fXp{xwLwj-N1BWxwMzC``j5{nfQKDV-54Xxwd-G!OC~I{EiF)bSH)!
zpa$J_f89g1++Knz^bCwUKw_8tiHVic?FNWMFVF_SC_2Ni4`D63(~6Q-MK4?jByqay
zX?b%a>rT88cD*Xry@U+u1qE^EF4m2Ca~JD{3b;x4(%ykd>CSr<u$5kT5@{cF*F}p;
zAnuB)BOs>BWlPXZCkh2%HQn_nczPD>%h4tb=b;*YFM)M>0apOf^OMpsT)=MT8GW!i
z;7e$t?lL$5anuU}1E{2*lsh*vLvV?A>T)_06ZMml{FBa*xT@}VF&#R+3vdtktnO4R
z9z6J52z*GzB;`mTSa+2?0Z{BGWn#R!kqJ2Ka*_j-_V|T#<J;q_ux<Bt&gT;z*BQ@W
z7`iUB5aR59QphO+<T^Qpm~!Izx)Vc?n7^MCG6smbQ;f*#f%w9%BnDy-e^Rde_zmve
znieTAXS=KH0!?Qh6fR{-(t=g~XlZmf+yTtI{YE>rO!#y&F|;UT=nZ*Dpy+K*z>+T3
z0NCz>K;{uc+qn^U64{590`$@+g$%{|CWiL0Q>LaxSZ%6CJLN<8XmeTZ<BOQzo3tWe
zY^P|$LF!xWx7-;A0m!$_(th1>Kr-Jcy|x$<3JH*2Bm$_{2|$$fIwb(az7rZ=PC9J}
z=<fK9_REn)RQONI;4yc66_k9Pg@l`TMbZ$HUMDDF>v_l?g0`<?m+@eASTi21PIQKY
z>BK*Tw9iX{Q2e?{h}XZ}HpKL=3kkUYM_pR13s6@bYX{VI$N~d(VX_FpkvA%f6x1cm
zLI!nFv)X~Ka>jEx^G#li=qi<f5nZJ=u+##I%Lb)O`^Y1U)(rtfv8qF<EUf%cDoyuN
za*{K?On%aeSX!b~CzhWm^@=4bN(1XuiAqgFsf$wOSPetk9;3HV_ZAc?jd(1v@J8v8
zS(<~2CM$Q8D%xqxkh&TLKyqwk!lO>ulH-)-2}TU+J*rqWfX!AaHtLnQkil5eq*Qg5
zJ&`ugkS%vP^cb{NF9HN@1tmN6dRX8~y&e{$Wi=VsJAspMy%VsSBZiy*g}+vvkO2U!
zdL^;`j2==fP*ZO$gk#lnjCF2;a)7`-9Q?&TSdl^fwrfSG-*!Uvu`*9RF<HH*-l44U
zQ*Tw40per!P@$lD@MZv(-oy&Ps&_L3u<C7%3P#5lpX4u<IjU!S7DB3bJ!>V^+n@E6
zJnW*Z!IYAxx&X7Q7YFF-#R0l{!R*HxP_kgKL{wQhSVt<2AS^RgMiP{wN&^i98uhAR
zZ2^VdAifz;MUxE+W5K9%fW$r++s!T<+O1AxCe7LpAudqHtL#v$^i{?xmIEt;7Q(K|
z=7q4U-7v<=V`V)<b+R(Bv4B|`;8@@c2D+?XmghV(pgZjpvh%T)8ZCh+wpOM>gkWvv
zMAmC7lOv0|rAd-S-^yai!f<KS%z;4;6idwtb2N>z23;9XS*K3+)gvp}l>wH;?#fEb
zf_P=g&60U#>P1n#-5!k6dz;ZXgR;u3%<_F@dS;0~n5Per(yXi-iFOQHxmirG4B;#|
zNK^TNl7z05dzLLMdpk=TmQ5bj56f(i0*MEW`yh3g`}u7;IdJ6P^l-SoO%I3jp@^c6
zn>S(=eJpPUi$a!1gJmPj>w(gehdd)JKUsbgmZ&V>3d>lQ{{@9EHy;hEVU{0<1vAUl
z!w{=-2W8pK@)sSf%2{3|mhMci6H9xRSBfE3<+nmi)gj*&i-?x@3w1`zLB>*~<wRq(
zQh3@9kaE#<7(Vt@-ntbSm8{(BrqW%P8~QP_UkBZj2gg=O71zdAOcmFLT#_vGdX(Fe
z)nLoD$%?V^exjzV+@q>G3m57EQXiX}mE~*86T7P0(pCFX^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9j73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<&t4xnALV{JOD~y8CWf5p`e5sms5OTLV<Es>%vC3ap@CK@5Bf#TJ
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g*V@d&7xNN)_=q%F}K<2F_2zQNMY0L()tR7GjV!FKMEoDOg+gnI^sahvcA
z<Pn;2o6t3R?q*b}H->CZ&TuMfl`{lXK?SZZ5&~B_%WI2#^(^s#=vWX2<7W>Lk_S4^
z8MviD+_*JQW3(<PHz>%t<^^40zj2F?Jv5j%J>rKK1-Yh(F+M=bAXvtChWZkW;)~O1
zT4X#k6=H@wr|zB6)Ki@%V!?T<@~Kea)$zcHU}~65@{y7xZR)-Ua<8}3if~t~w|B;R
zGa!7u_A)I=5##Z!jN$QB&G)Io&iSBaU^-p&8M%IdGS5A_olo$JfakLvVe+74IQyx^
z^T=IRv^~rU6_D@V8L^)&1?*$aj)?Gz{HHOcasz0TQThNaIGJ8RqfcfZ9H2y^i82&u
zf~qVA_aPNLTFjN;zy}95HTt1+3637pqnry`3M(-K_Q#`=H)zJp+zv->XXSn@`zn${
zvIU;Gt~}TZE6Ie0<w`@L4ZBiRXg%js>PXVqa$w-+s5BY+VJer#of$f&FFl-~&UddA
z9SSK^bO2uI3-16~KaSK;<OLld#V;s%$boWI2}YjwMr9>AVyBq4<O5MA@rcg(03)t4
zot!!S7hnI59DZd?Im4?et;zv{r@Sj?_Wi|ox-;KixmrG$eKu;EnSQ2Yb};=cf7CHH
ziN^38n>2@kB%(?_TcpezlXNh@T`6onm~Ez8e+)9KY2E|fbkwYrbEelh)5(>B=gc0z
z1ViaS<f>f0MG28&x}OgKy-X>l1Iaf?5Im9;duG<^BPmUphR&4mDS?2*GduAJQl@_D
zR)%S{@*Ewht~AsoCDR;f?(wmwPWoU@rj8G0b}I#QQ6dF%aBvXzO6~N?3{2YH7p09Y
zMRXBzv}qSv?aZZ=6~vjPJ$0cnOIzux4g+qbvo1<9rlU3XY*=Sjwo+ytHR~&_)+e&q
zl#A;Vh}xC0>tO?~oL<K#nDy(h30GRMzelv?4ZHHKrNAlQ8tKQ5bZfm>Ci2{r!+bc5
z$d%~qO0kwMHgT^gecFTTH0ftMHx09}T?y7Y2b5r~TLa5m$=-_+>L(MzT{+ez3CyuB
zQ9zQlix0Ss#wH6B`RXML$e9}@3s7&E2k)?H)9rF3DLL4-UdcddCiD8DXkbSxU*9Jx
zIaXG`BVey%?9ix$3E%*CE8GCb4($ZTS){wL2b?+Bf+tv%gnN*_fuo?)qrV7Y3@9K3
z&-0_O5*()X!c*}1Y<LTf2tj}{93bVFXLZ4s@hoMMw!DpwS`z|@ID(Wg6OfDR+yEw=
z8QTJ(@H|ujQ~^S~-wVycaTFKgg)^~RUMs(d^gx+_2jD1l4F`^WA#gY%7zNU?2+0N8
zIwcoW;=<uM5E{rLBp;-mUN~#yQ*of?btejqUjTs+E{P*Hvam~>dE|mOS(F$LAyD#%
z5})PXy2XG5rLri&AEB){($9s+vVI8Zl*DWaN{&c32Q$)T@ej&#7d%Y<P>yJ9-4Zco
zY~2E<Wo+L{#26ah55HW9HtP?dL<{xCFXHXU=77Q;1)j4gsc>|O29#|<@GMG>u5G<y
zbgla2;7s<Q_;)Fl7l0_bgo0o@vJYGY+c~#RDeN>SFUr`!iyWF(0URyLH3|aB;p^F8
zk`^g}p!6WQaI6Yz$)V*H9+M+8A2!}2DZxycbRF7afj>FQmk=CkwR6BS&pK231#!J7
z2?jOPDYz?~D!;A`$I352ju+UK!#P!mSc{U-TYc-6<L_Iq6b7MhEmBSZZjMDr@GU}k
zElRMwZGCe5^!hph22^9!uX{ribHw)+;+VrxR;Xl)638V{eRj1H8%+-iL<AS~na9H+
zfzg~;1q4nzf|ST;bqwT9VRZ@+@lLOai|}@|-X!F~v7x>BMTk3DY!Hepz_=hh&xR?t
zC~XjS?f@m$$LfM8h&zf(;0poYE?UC~fd@)zG*-(_fV*0D;M>)r6W>mYPJBC6w_Bvx
zMMC!T8!$ye{&V;s3mq^he(w;1o|SP5W^fU5Y0s@!a^hrb4MtFgi?Sp`S<XRNLlGq6
zqQu548y^88PFf-E9Ki;*=m_*KKt?Bugg_gE62sA^zm33;IYC^kWsZZNwIC!N@#6(E
zxhRV*r{G|n*c8I6biB|D)6(IuE!;~_{0bps9zlrVNYlgHzc4l(WrYfd(*b)SsLn-5
zj3WVhg0z8tI)dN}7}Q~TSd@WwVv9b-ueL#rvPC`tHC}L~i;~!*^gAT@#!;}RByG^B
z4wFd1r+U^+Du7iHRJ?al5`0#-^bOQ|g1Ht!PB8ew0ScQ7*?=o69ZnRz@$Uw#+40db
z4K_}R!mkBs!?<;zj1&%TQLK0sFY?0EC8;oX9lra*<=rV=!(C{!tPA%+5oZF7Rv5uM
zW#~&GF8571t|DFA+(UwdTD((gq9Ii*Fm)6~+R@!N<m7D8H2R;u{=>2M`T73U_Y|)-
z-sJb`c3!u?57)2%`0u~|`<H#4@BhjF`=5Uv{-8Dl%nUzyoo*oNONk4L3Uxbh{#GR<
zdKwUNMKHDuVz{!fE5m+JGmHoHx=LpdDt+Ls5U2)HWD&)mBbL8q1<9)Xi1MXXM=(`9
z%fmP^^3qe@Oz<-C_}_uj2}n)&A|FDGg}P&~IP@t{(A$5pA{Xq0GC@0i*u43Ub}@#T
zr+$aCkCv<q#beSg!)+?tHh=n%8>-agb_t`S-jHd!(;X==Ibv8H4!d6DR|F~L$j5y*
zf6I^eXMrZ1Kd$q=-u4?Y%5$RO#rYN^M65LDJ0M!7qZufgb~~LQEZ93}ON$tQCkysg
z@LR07^uY-4UcXbA53C7hrtGMh=eMcMOl$mU<y4-i3q7kw8ge57hbO+ar2ER+Iz)oS
zAw4#XU*`Sb-&3osB8Z!HrZAG|7XT*9O~)n^*KcHbSAHD={&9wPy5CiGp*y4d8S+8d
z>*d>qce6F!V;vzMXJ{?+T*4PC=z25P@gF<jOoe}m&0h$H{VEtpzaizf9Vt;$9YML;
zw;g%kd5Yn^iQ#WLKvMhtA-De94k&y_Vg8wqst@u0O-JkksB=HJec|7B#F2;1@-vOo
z`|kNoH|{ZGHxjPzy0z4`xe<S6INnD2UB}$QfzHZ~pvXS^mmT{vKQ{VL1=Q5m|4m13
z<AIK%$lCMQ9btOqLGm+$Qa_HC-*n^&bgCmM^V^Q?`Z%b5hVkO_==$r9I^nuHlJb1l
zv7wS9&%vLeO74{3c0{F16l44ORh0YNjwn&WbM~jobkxcF*ByC40}|)wc4Ygv9ozgk
z$A2c0$;Zk5n~s#6$&REb=KL=^8e-LWPy7tLs?VF_ufNC(1`eU0+m++rbu>f*^BVe@
z@O~TRw;fr=)!C7h=lr%Ki_GOU_cO3zKkmK1?#A13s9O?bK>6!#@aFOk{h6TFAGhjn
zhRMtKR7X<gw;iL#$c+tbP~N}Uyau%#9pcerf9SB^`<T;C`DRWxO+*jpM8n#59Z?dJ
zYQ@ijiyhw{Or?)>btL8awj=EfskZz~P{Uo1`As)!JI-z(Jm)vvgcFxK(NC3=l#=wD
zZnr|MvYT|P@m;qFH>bk&6Gh5O0sBp-8!$#Zic)LyZ#%)63{CE5A{G?kcirGc0Mx|K
zuOi&vbn5^gq?-6sX0B2kf77v2V9`+;r+?d#&_St&{tTDahhF-dZq#0#-9Q-Ucimtn
zr;htG!aqK>-rsbja_sD=r`q{l$BKK+qvvOaRBn{tbtK~v>iBb0$H%uFnGgC_(SK%o
zjuiIabbwv`xk4wShTng$I9{Rl|4hI4^?Sv1y$|LSe|REb<Tt9XeLNq^&QK4E-*j~O
z#@LZBk#FTr#_D*Uq+<W)=ZfAm4V~D&)#?24oa=4;ei6U#x9eVS<ndm*YyL~0#-hk#
z`$Xx_nVCLpDW3O%w`(a=uw@}>pjGGuKou6u4(tJ<Q1uE*)We;oFNJZWA|oD@7_Hcd
zjRGUW69;!24;>{%=$cO$D)n9{%Dqh?uj<@C#|Mdju<U+=)}ftJvkuGZnA@z+EKn$C
z=Ht<7Lk;;aX#N_ClzY-+*@o~}iX;aHES_z^g@Htm)g~WF;cFsHZA%%FPUFDJSd>#A
zPl`fb9+Y7n3VC^uIMCD#VX82PjY2L(wd)~I_5*|7IOYF-(&4*EZR`YpHeQ9W__OgU
z-^$O<t0fA8JaA;iG++bl?P67|dIdH-h!t-Y-2hbJrrdCUU>jAkwWI8OQ(ClVlFpHU
za9}9xx5`Cclwi7`ejK<bz@sB2M<jFG1Jkt%i#m+hsy(_0$wP%JJh_aA3YaG8w5`ag
zXRcAzL0yF8P;FEA54?ih5R1zitPTKjK#jk6m#WgbD8V14W(H*~X@6wLg<e}VVI9v%
zm5mL8@0Df!VG&!EpOxW9=HEpL_9%hT9~HJ`YoHRY1{@X2m1nppAw3m@@StdU1tB~v
zb4&NeV*x2i8~?)^w+cddPO!mg_Wv+mX3T7Jr2yOm&Kl=4DoD8?*$M{o&ru+{0zQCD
z-uhjh2M6EF)#u_nM&;mgdHP&TmYc@KW!mXne64P2@sg_-*6fD-P5clUOYe?<HKbuW
zd=LcYObVGu4@Zv+q9J|Kkr^2Ppz4z|>RX>I+Dvy4j-g)ZBM2sLy=|Rx^lj^wgWtVK
zx#}ioFugQ=cN(oDx_|hLV#tdBqQ|PMwv7B>?b*7;5SzUE@XNJl_vNi$28=AcMj^OO
zIZX63HaRcXc$>CV8unVdwhnntwF}KGDNaemhEwJp-Loyy?82e@JObX0L1BM2#q`|k
z&*^&(o;Kfn+A*N=SE1JIf&?z7c5txutyeOzZ{2cOZR-`1*(&)Bj`~))Zuc3+2F5|4
z&~vMRo=5hGQ{f7+!0p_6Wm$WAzfi)tX|HF{LsJf0>YD3Uwz!U5=tZe8jbN4{J7T-5
zBwhq|L`~O^$d2HY@ehJa@|H22Bmk+^BNouE1I-+TB;d*@kyd$Vh<jN+o@~XTQwe7o
zOLL@IXE0PIN5a?|*|60m+2LD{9Ej(*P`}d@0)XhD018(;QLKzfJBsY~hJ3t;g+V=3
ztEiqV##-SW7b?M4cn4mHi;|rVhFdkO(4GM{FjD|FxMn&CGR`X~3_!^$MNMg57tB~E
zVGUM%*=n%^u7Oi=19ZlnKu%&@TdM>vgxwRa9+Yq^;QjEcvn_-7azzx$)??%qH<%2l
zD7GdBRJ0-F;6yWrQ6is5+*y%KP*N(34FQt^%}>$|p9mQX_2Rs@ZX>35DWEghcGU{v
z;5wxqA}}<3#HYeZqno0lFBGyrx41SOPG`lnp-la$=+~U)9srwPQuM?`p!gy&EILn~
zlNts<F;?{j#)spaIV&a_h2PJPFyq`bXT`(c`J)vMk9zHAg~Ov5J95pApv3rX^AhK0
zlm>~1X;ig185td4VthQ$gbJFOxfoVKGcz@iMIjUN6j&4mc}GC6JryRO&X7f6*!G0Y
zTGt|i#qA@Q+#Z#yc$1>Z0PI}LMXBKTiTH&Iejm|h<a=BY_EcQ-K*)mx12OfB!uh4@
zV+yQ6?X&m%T=R4ANvGuunXpHPW#Zfhg{zn^P<uL`+>u>i6<dS!1ACNHJ39ufmqsG+
z+GD!6P<_sxijjx+<f#yO!=#jghcpaRHJihcZDDt<e(ttaY=$$>-L@$F*b=8GP@_Jf
z<jFsY{FETDJybj=+v(8MV}ImTyePcm$DKhTdIPTFidp{WVfIb_ij-OSXjnohl5H*w
zMSB`a8g_G2M+M1u6aSsR(DfCRGqPLZ7yy-KC8eZ{Xjh_AOG0D5Q^>|$G0Vu1S|rX7
z;(aSV3aM5s9`*V){^Cdq=bWGFnlKaBI(}C{`!HshQvMFl3=X?>k&n*8P|-@Q-B{tu
zk<AfvMmu5$tr7s?)nU=9R~V}w%!j#7mWy0dwjYBNK0wGB>r_kV^PrI3lv?G5otW~8
zRy-c;lBy4wGP`ugk5eVYUJ>ZC#&s!x4Ca$Xq45R5KrB|4lo;8iI}kvVcF9Tt9LFq^
z_9`^cML>?{jj_o(7Jsh{;<UiqB@2q<T(`;>1cV>TzJU@VSP6r`+Ota<q61xo_2rTj
zC(EVxA(BqAaNX;R;B|I!KRKlK(y^C55xew0O!olm?!5rdW|dM18;)Jl5gisnmiT*R
zZg2dNOfInMuuR}fsAr49#9LUG?2<$w4aF+c5bh7Vq(~t$VHH2TMTvN4n~##EGng)?
zlzN&er4ZRAHm@RNn8j6z=s29_o*h22xaPz5;^oxUgoF^2nfY+oS!_yCXDG--kY{&A
zc(5JwojkERic#8Bx;u`MDR2hBV%n4f-t$DXvO^<}BfQK*f7J0ukUPBht&G*cAc~r`
zgOo6qL}6R~QO6%aNMIANp^e<*DPThzxyS7_Zej*j_{+1+A_REI9NP0xi*7Z*#W0ov
zcnKhY<%N?H^Qyc+B%DO0V^MMv7g{Oh$_mUXC{b=XN7v#q9R<e_YME7zAOKfwsFJwD
zT)}G5FBNuSk?EwwY7U7S5>imnn$Qh7e#ZYXK87}RU<|R`_KR>4sL>6=I8@jBCDaM4
z*i`^i*w8f$+Xm~7zld#dgr}Xclmq<cErq<5sFRM5rygLHd)QKu8%<XZj2=<g9bfO@
zpDwP}!9OYF$YZfgEe|*l>;`<f<#+U0Yb{!wAi{n|p^?DmwW1O@L7XtkTWq-b%DNB4
z6mvc35>&<fsR_RCIzb=@hEGJ$z}64XrU{JK5#M8#)@Tf}6w>!1#b+ezc1MdqFnDPQ
z6gF^b7Q<X1RDr~^)=P-4iNv$o{F&6Oh`LIM9rFU;0nmu~j=mE@={i+`v12Ygp16R#
z(0EdPvMLM^;6O10`ST3d4Zua;?f7r<2nS0gOERU!Tu3}P`6_+V47`>m1~i;SDP*O{
zt~J(`Akd9fLM1X<%yomNf#Xd;BhENCG5_ScOUO^IyM+8iB$CTZbz<3#=%U1^F@azD
ziBrRAmpLyCPM5-YMT<iP#;>_{!wE%1D3*&7yz9Cnko96^#E<8H1eFnID^|5^`gr~?
z3c;@O^=GPVzbJ9Wb<_oT1)5A85nZU<{}}cBKpPZnB@#^*0e1gI8bKg*8+5-ejBB9W
zo18Qqp|~bs$^#HIThKlbXsquraUmfEMET%7-U}vf9?|57pftz@5dd}wzvG9nwd9ll
z5Z+;3k@0YQTft1iWo)W~M9@7elu5W850j6G=zWXApUy+IAS3Ziw!(~rm&>Xi6u|_o
zFe8y~VucZjd=pbGD&iO}3b8R0>(IK8e{V_wVSaB40iRk#t1)^@4k0fZ^I{3iXq|7)
zj*79SOxeVDv@Uqw8>J?!)6x_eH8BU_@d8QGI!}d;Lb%5KS^`oYCNB&TX{-x=H=S#?
zK}B*O6;vemkpaE<<~A~Yo4bg(y6`nwH+>q>w*4faz?&4!!vD-J0**vplofd7oh^P9
zMG;NNk;rXZ1R`TXk?iMJqM3$tv`5U&U$e$&ijIs#D`d%ZTPy<eK^}F2kRexdQQ*J>
zB#jmJBpe9VRM+5wnWL%tK&HhSy;6xc!(LzlDs`Jm`gK_EtqFA>NyXMwroF=yZ%yaV
zg;TZ(4Ic%_tqJNLIoKwr*U|BUv_h^#NRYKl9KyNK3N5#*m+^<Xx{*bAh_nLCg}p-A
z(H+_P)`%y6A$wv`xMHSW18w#p%S>Maitwo}$i-MB_9Dkla6>rnctu(vV*=yB+MqqO
z&qv(|2YsvCK%1SwFJ@~IJoD&?CpCqq^?9im0ih`yIyL_xWhY|jM-Z48219_*F*{AR
z4fwZdo^3)apMxwHUOA1gO@O!olw!&X?~^joqeXcrblgdKXyPSQaXB43jHpd`xwEMg
z*woaAqc!&7Sn<GXO=HC|p?vf{v-<p-f>!q6OQKI66T&SYumUtZv^(&Btf|u3n-op#
z8(`5a3ib`6u}mS`Z%Vdu<Qa^01c|Wlc(^qkwTQ+trOI~%W0~BnJq??OH36FsJk^>`
z<T2C>k}~qPkasqaXo4>)bW1FnMdGBOf;XMqgXtfqCKd+uc2d{}PXe9fv|P4R^W@T>
zXhjeCg%{3DC<=?jHNrt)f=8zjQpp@WBV0|+WTMX;i^P?~>f3{&3s`#-_%NPrCS-w*
z@4_tJQ7dMVm@#&%3+9aZV7>r&GkefVCy7v5J1Sq9Np(g23?_CYWi26rTRY(E7J<hV
zDodE0<Aj?r6DTs^W)@|jo!l4rWv5k7Nh{s4!R2D_wCWjwl=C69+GGl!S|(^^pc0zt
zCUd6R+-M~qb+5Taiw6xtiGqZYF{P(!yuiq3s`2tvwk)pro)#NL1a!O^OwbP<PXrU7
zEhA}z5^Vs!F9J49nhHPKhVeqWI&OTS;&y<;n_ZHyjvL=p^JOG+w|2*H!R?M$fJ$^9
zofbx`vM?_GlG4dgw3t{0{-?5g{6b20>P?c0tC?>4f5<Ie2rc<u{vh#pun4fDZ3M20
z^n=D#nL4%_mqqU%TFrnVoK=+eR<4Oa`7;6S_=S{<BE6$=O^Sj=5gIpc^J6D*4TSjL
z{G&zwQ=7?K6@&v6P8n<64D+crXN2PiN3AFa>u#A)lYwcn6Q(|m-ANnG2gNB5>}Hxm
zQMmjVkDdBf63z!toSMaXi{(Y(ERd@U3)W6J!5i)!6hzy2e9nE5P(kgJ!r@|NPt?c!
zBvHyBB4?MB6=jpNvujmyA<rgmLQv19DHnxPhQwz80yo8x6mkLk<TSAXn+w(OJ}Kl&
z1~jaSdS-OwN69_(C<^(4<Znb9)YeCJzvF{+@hJVOqJh=o5ejGmR35~UbbvIrgN)@0
z>#$=<L!F1LdiX&|kGMj-Diu@N?GKMb)&6|A9Z_HU;ejZeo`&%0MamUw4-Z6D1BFe*
z=s0f=(=-RKpoTbKGgY}qjIIgAydl2Ugc}qkETfG`1eUq9h(co-%-XP7D6{q^OKH|t
zRISb0cr3`Nea4!dwW(0nvvv^+e_}fvUsWEIJAws7OWavxw8Z^Q*@PBFNe@Y_Dwl3z
ziYVbtOlkM9swdic+*Ae8uKS&g=n_uyp-DKwhX&EaY18iZ%LU&6i&IL#qEI+FZBs9}
zvRPzygY-afr}P+>sx4Kg!M<Ve031P~Vt}b5pt5wXc2R#-9Z!I1NqIX|gID?;>-3gV
z$XdSA998_cw9TU-!@pG0hB!hgvJL+5QgvB-xYS{kCyo~ZniIM|r;t7*>EsOvdZs|q
zc5%fY;-I&SORk#X7nfZ47FSa@&Y-CmH17rncs);|{ByQ31LIpNTBqJooIs#j)w2m@
zsOxFfWU;7v;t$?l7(AdXw?|!*y@D^lCW{4J0j#WTjo2nl1`C<|nk*K4nl@Q1s?K=&
z8Jnt%PxZ+GA1oMN59gLZsP(pHnQ>EL4VEI07ke@{s+AwxtDY6j^VQ!N2_~xmilUd{
zfHl*@xBzKDVRdU&Vq8WG4z8&e+1b=-4em(P6!hZYXtwBRWe=4TXM`6En4sW1%rsb&
ze}G~^7yzei`ND78kKSb~IY2@W{VJ}HnldBDWT<Jt>a~JmX$jVAs<2W32CAYyps6<%
zQ6K52qMhl8e6;MPqUk`2HlY+Q3VLA)##AR5Hk+&@G?gK3%@jP()HQ3a;m}Az_d**P
zhiocO(+2JqK`kx{dyzdbs;lzN%1g_`N*D|Tg|b{;V2PJOu&r1x8Vn<gE&n*p7cZr;
zh1n6qhglN+O<l+VQxCGh($ot17!*2Q@&g*8k{lXhu#^YUoc8lcPflaRl`Ox_VLw-K
zZpK$NUZYMEX%*FW9yz)s{ZcRR6%|iSFrAG7R5XMiK}tJ3KMwB-D?T-+iB#7X%_g$c
zH>V`r`Zn!lx}=<vz<+OW8h};stTY*pno|gL+c*V5cZ>IEVG+H_?Lp?^xC&1RW|+r~
z+$)QaF0fPcfvrp~nua2XNBD6tAt)S5>tPC<sghWOr`J?$tN||MFw`S!C^Hy-D0I5z
znZl=#tYw|8mX0(S@EeeMt?QubFroE^uR!^bt8FF2l`pP!`mcLOlU_m2guZK?u${i^
zj!z8v1bOZuYs-4qcVJHII#-YgUv5jJ$5|J+W9xLgF($Ur5YwH=Rdl;CI{r=B+^kKo
zUrg6402jtsFpI1Fw~bL<UFSqBn|0wHHY~Pvy%2!fYh4EegQ(<lZZ!Fj??Kue*M9*V
z*65f;C{1hh%Svf#k<Jk@2swTldz3)fTE#kG)(xVfyhG%9<qr|ZY(+cd52V(jboxfy
zkJFUjfZuDVys}mh_`MOmfq@JKW?--8fo>|Q+Th$VR$e`n0#@KT4Y!XXOICJQ46y5G
z!p@-Zl$JMY2DM}l7?Bv{(r}rZvT&LERlzc?Wf%<)t8|7iu%<y_GuHlX3WRd~BqO18
zt5FX%B@Hth%v1!qDfmh92Cd#y{J9w_k(!D~H)9-(9)fuDnCtxpi?6BVcFT8KMonQ$
zC<sc=D#bwQ$%GfH5hJAG1%8-{!Z*C_E3AunJ|+PB28crwieUq|Zvfv65Ewmnk$~Va
z@Yy_L)bLpb#+^D{fc0B}Zi|wUg{S5S5g9t{4Kk9^b4xY>V^tA$%nyqwJg}HyqSC}I
z4wNCGw@gMhW#Th`%2bb_0S=guJul^pnR5IiUo30^EOoH*qcXY=Vt>M-Jg6BqU<8{g
zC@`nWhH6-?d?|!SVtfHwVM7|;i9=^F0=uE)SHy0nZ<a|_h9VFRh5lAM*YSkjI;4=D
zP+Nx#FDJ?knQ)jIW2}ahFveI7ovkO1o*`St$wZuSX;ve{U@@nR{~l7MqGsX>rUkoC
zk5=xsqn#A9TRfnY<uEIT7t_UUG*7gMa++rCl{J;o+&Z^u*Ax=!KSE136qQ^QzS>Sa
zgA^5QG+a(T2V(UmZ)jr_*kpuk<U9qt=1><HuO<~{<}2AG6AjfwP1R>icE@?E8#II|
z>`TCL*rc*(K+3TB=x=(3wom<0#~%TK6=_T>Mm`0|Xq~*sRePu>T-5yxcnfwJTAA#C
zXZxEFjr{Mt1z0v{wMS+EkeB)F6t<)RMZm76<$!7HYU0ufolyX*#$d0Dp$bfivWt7y
zP?*dvYF36|ufr}r&=x7D!{-<?sVrx3=Wf5CHLZ3w!+mYQy|hb$aKjRI(WYuB<7*f1
zr$x#11==wWqdoMR8a_^hi@S8?TII+tjUFb_OHn(E6nQZC=axw^7(B9?E^gG7ij`v%
zk}3)wA9nE?Vg{F~8W%ITOclF~X4UJ__=OP+djeCsOi;>1%rjOBvzy6LChjpkD!oKU
zl9+deopm!m%JlWlgf21<mO3UxMdDLtM0NaoOj0$}m>5+_S9Z4?513$h6Wy+l5HPUh
z3-9W?<O`b6ofF38b`PpjV1}ux9P_5QSV_rWo%-^rd^}GZoWb0C(}r!R0I=cgVnr#C
zFJ)AP(B@ma;0>$W{SV#l>Xt)92D~9MGJXh;u=~-7AmgeU$Q&wDRYA+LYjz6;fZN6h
zWXH@Z9u!H*WYtsSnQ_>FUAbS6AYr9wSAM9h7^CE#hE}GFHcc8w^`p=xLp2n8_;Adu
zD+5-$p$-er^jDl$ncm7WZ<dDVHMW6frkoD(2xjPKh(|qIIOl1UekKwdn5Pwqw_p$s
z^=FDfQ1Ks~H%KgB6v-5#bqT1Cqki3yTv9~uDvfwia&=UZ3zr8uWJ*`2eBlN8JYqF8
zzDLK)b^e+gZAu|8F*uR0UShy3a*09$(jHr?wxKu^v$>HlR_WdbFhOc9Ny#s50Mx4)
zXUn{i60fsm-blV@22I@e@i)lI3zZ;%DwN&+CT;2OR3j=y-cUx1IrIj!d1ToiAmwLt
zav*=a^7Re*<Be5j4f*3t`#+L&jSU;XkUrj2-gZ%PIV2l1VIxk8#zA$dowxV^+=%l*
zD`5*H8^|dyK!im}xHaQ>faJTvSumiyHB}roAm$3H!H`7W%!*k6`LQMr0|Ua^4|Ynx
z2PrGl^?rJ#PMKp9a5-}Pnu@MOj^9XR4;%{cHZ=3C*V@aAf;A!3#HdbsL%t$0FtH{E
zI}mDOG8#UT2}k0VRImK-)G9WCpKuicsbd$F>NiQR=U1rK`RN-iV%ma3zk<6@;G;FW
z^%H=qF<li%K5UA!GdLrfBKmA18Lx%c%usuv$pdCUT5XDSGz4?DW@sg5j@}E*RcwuM
z@`hyi*7%bNFeH^0d5MLfgJi}vuFmFZ8x9Y$8#k;TzNHG!$56Wxpg#vlITGKxC9;rj
z-9CYZ)*~+2G8nGPcU_b9pU}i@ZoOiA$hvQlhTmk!4>;pw)wOkMLngMDo}5jg=!OD|
zO)>43VXa4EHlf?Z_-=KZShr{EmIHjYUV$=opb>-X=hh(suFkDP0$lOm6X47wJ}`T>
zUcvxOo6bK7V5_$ENMNhBbx2^V9_J_!1Dfp0s-)4oWHf=%WHXM8&oeQ=U>JOp5@`)R
zaJcoMF2p_40WpYs#sgv?jHxNf#|DAV=GH66JF8a?m;M{ey0wdd$PQRf5>f5s4<~Q+
z?j1xrV>ut@o3_g0GQd1GC4bR)6MhA@&nC~q3+A4tyfhoALQMp}$XOi%`2z*WfYm3_
z6lF9(#oy*8-EZ^_U64txg+LhAs`w5ay-0f%kf9AI4+VBeqgMeUMr!PanP`J>h`#m7
z2`LSj*|P!1sBSqWDUk&A_K8;F9O~7Y2#>lLV8Uz44>c5AZnB?RqD3@95YrF{kKRF2
zOt97+kcKSVNrPgOVKi#fJc*h~%@hvI0MZ=#qcvw4KMmN+i^3m{8CRJW8aUgiwa*q8
z@dT2oUYh9KMypj!*upASG62yem{PG<P^Jc~4T7DDzX^wW><m`Mw++BL30RdZ7xpSs
zpb5=-6w3wODwYf1H7FYbtkz)EQI2fqgpn2hhwgdt|K3Cf0JbGD1hDPgMO>4oRzG+r
ztO2c&Y=Jg*C|#`4vEl8;B0aYdd9`Q)?WL`I1!$1Bsi(}w=oo_!yv?>PelT}x3#ZE2
zX6;}=UCqwum?G6CJ_C!m?r}V2rXGD8g{B^O;M=V88hC!Q&g-IF9AFy?$4NrIGp5W+
z*f9+3*(vwN(Oi~$+Zw5T&3j`{uGAy;L_@5J7DNs%iv|dfBT2Drm#%10jIG6iOIP$p
zfzV}%fFt6tz$R1;Xcxm+;67;=9SR~ylSk%9goPa+1eq5dAcvP8Y@*P7=s9-=u^l^U
zZgULrxUP?uuFCNJwCmmmKQfr_787E#-sd*7q~K+kKT!rHv=v~euin?TJW08WvwI1q
zXgwRdQW)+>Ukp(w8x4;0_UKI}iWR#;>>k?(mL%!hfJJUk+ZdRXj#kS8c_kwOASmE3
zI@sFd8&63oiHP0yjBSqj@O+A^u}7cr>q<QH*Oe$!O!EGjQY1jQiV4B^N7lBDQi~Hp
z^iYdFBzrQu6y@3G9WwmLkpQ`Wc=~$g%SPEoeSC3bQHob<x?MPS+@-y&EDo%`MdA;y
zv9GpH;0$Qj>AMCQ5b-)+)(|2vo|gql+wr?T*w6j=UBB4RQlPS?C_n<@LPSx~^W*%D
zDe+hPlLa{IG<Hvv`>FAUTDdX`>NFlB%YD{qOo~q98ROlL<A~hv=YAYtBmSmN<6MIM
zG$uv&+mrQ6r97Nq__Jv?t5u4_2})@W!Cl!^@@_t|9;@!+V6Q+fdF?Z;qf`T?er&o!
zH~vU))7qvx1fz&TDy5|hr<97#qHM~;e6oD4l!xF;nO2}f^)jtM@nZT)T+pbjE5$fC
zgD`(8%3YE7RHnOP;w`knV=MDZt-MMB8z9)aBFIy>?~42;3{J0{Ha-YCBdzgh$l}G)
z|ChYjy*(Ln&QFOvDim71mOIKP(}~_UyGdSyeY2Y&h@|Q?8^RQOv#nc9S+Tizd_|U0
z^$PW>YDV)7r?S#~<W=QqJ_M^gHD8NIZ(940nt-INNw<=r9<BOtPMkn!HF4j*yiSki
z+lO=7UZag=1-Q{GV-Q9Vs!z^PZbMCRZZF#${?s!ywsKbiG`^XcqqZoH8C*a3I?wUT
zFO#qHo`3;-o#!gu>XU19Z+$`xTOA#!`p(+w#}^Q$dV98BA$9%Sdc}AZX}ByIF<w=A
zKUkDX)!<?N=-swXG2mWruqgfBTlENap^DN6Y4NwWtxxc`_v#hW(d+J*(b6M2jn$p_
z^_EYn-s|O!s_)%5J5?~VkJ@@D``*W9cM5Lyv31MA&CObsql20l!5S-NH2(1d&wjDI
z^}bu)a%gPju<kM@rh3u)y>&^R-J7v4m-P9?nArPM#>7-qyPs^WAMvug<qNTU+1*l=
z?OvA%;HtXY)-6Wkwsi|8DTHoOVl@7XG4=>j*>7`1P2F-j-TT%pM^v)#K&CcJ42q?1
zwiswan=J-vj^f^o=&PMjRvG0IZF(!9eYhU+0pZ#Sq7@eNwcf70RwDQ<QuPUmQGgq9
z|GMjfnYh0FDyIkTZ@;&0$qXD26IZdSkHE&?o$7y<NsEs|{YTzIcLpmP9@@RkGpznQ
zq*<=F_mO3E)hRwbR6RCxE|~D2g!uBX@|47<3otI6C-Lp_-{GoKNti@l><TCgzs=$~
zF157*5i!&iL1uX5_u<jXTcZnG&k}^V4=I|Nh;jsp0)o?aNIue1OPq$Jgq)R?2e2H+
zR_=C=tZ^(aSsW2VYGtA?2Sq({p+}kL<^aRXTQid3w9ZW&n`PC3Q;)b9!KpkcN4aWJ
zC+-pNMdx9_Z=C#%nDZ<b9v(<t0bg`f_9-78DsWYB7yO;Q3_Wm)CV+@sp!qR+^>EBh
znFCnjc}fGBIM-%rpK#&!S>kYGUV3RxoMMyVg9d9!PvZ|f$M{;w1kS7}nRvjzl8Fc3
z0vuG5)>2Jrr4#S637rBsHvt|a*ZW$iG7nvR*GyS;uUwNp<?#ckPM`Vj@n4(!KLl?I
z!P8)_StN!mtXE-|ndrjlF{Mnvc+)R|VKanbkr0c3!{L%j3VTj3`_R>+rML-bv6rq8
zgj@8B%0!^zCP0zGFJh0EZ3rkx06JnINNlc)+9(3d7Ge^Il1`d_=`a8YQ_u9p47do*
z=8}2$N~NJ!z!?yOiTm_Y=vf!waE8o8w~FDJ=vFa2*iF|S!?T3p(lc{mARj`wN<z+|
zLV9rfUlq-9gB2CcamS>d3Y)<mxM7$_>{(Y_7=Eo+To{6x2nF`ah_$s+6&7~k^4-G1
zU>^|ZHAAWTEnDCXcXVf{SXJQEWpJC2&R!YPwbpiv6vLHycg+zP+WjM1ES6x47K4<t
z-n5~@O~2U+|4_fR>+gmsR%{raEL&_C9wfKy5O?Pk<<9xFIQqg@56C)9I4`bScLfIB
z@471x<JN^VZvdI=!lGy7V1Vj9q~roT6)1>H=YGT(DC;-vQukc=e)(T9GL_mz2;31Q
zjvlv3g@XaxzCThV5O3KZ6PFO+(1qL2h`0WfMB%P@N}_OAJS9=kvil?LBH~DU8YnZy
zv_E`^+)p$(b{zeWd`HQaBTyMn{ZUR(r^}6_{*fyBz>4)KV&tKuKk^ErAVF6}1_SZ{
zi-#vA7UPldq%rmgsLKj19?@oCagSDoBFCc9h!OE|39gx~l=Fv529PcNJd3b?%1<2#
zPaaAO>2rvZo%oz@uvz-asQdUimlY2YUw||Hs+jUcsVMW9tDhA<pVv&lrh<}s0-;rt
zvKZ^9QVmZ$=>4SSW(9YxpY*fB=JRrJ1wb(XY*BI!=?qM?*aMW9rJZO67mUyFcFt&3
z#=v_G2uPcR@pZUDrC8f#;o5S-c~!8IYEoi)EQXVTV9UipfZUgA>A30!vEEJq?VhA8
zF>^#%RUP4`>1B({@#OH8sTX{4qfsZ)K4SEYtyw`}@g@v_;2asicU^YEh!g`Q^J)wu
zWk!=3xGXPwl}e_6wpmMjW8}KD9INu{EbV(<7#;?&doN55gDeSN19Ni%WngArKp2)P
zircKQp_*+0Sj5a+$WjgVPcPsJz%V;8B@Py+a=Y>G`QcmhP36-I<N+p8mwB=!!cAaQ
z=aL)c>(P`cUk|5D@lq}<kS`7|palS1xM1KK2IhsEfUgGX_SZ`RW}cSK1ElztAoEyn
z%muyI0My_@>}!D2^QM51hCla8vTv+BEOAFznFH3aCFr;d3?K@zg^X1GKl13k^59$E
z`QDh(7h30PGBXkoxZWy(kL8nL&1%R|_sU*xIBFDMwgSWg_tYy_9X3o?K00#7f%gtd
z2&`~1S3ae$T6l+|#ax!p2F!Y|%yMLH1`>TrNaM;*ie}5I;FUqjl~!UoGDuzVY0NTp
z0h*$?;E}-jIh=kbvVL|!{FpcV8<tNy0JyiF)diU%+p1uB5^_nEFOFPiZ^{PD^ya7*
z5GY|U)m=mZfh5E-(|d>VjX_}sFV2d_L@TBzdnJi?k2(g-6wa56D^QLVJQszT!VrwE
z%C;y2>caVr5|$%>hu_Il&IK0SkTlG~5J!??l3iJZ8EUo&oKvo-3(PpuyPy0WCiVkb
z+Xaf;`W-E>E^EdMMx;Ypwlwr7E#$uCp+6X#?ypQnX1R%11d+vgQmN<wNk5#q=zeNs
z%;Gmy;&^2~ez2*d6%y9@+B}-G)VlV6R;PE>^K5{XciFNTb>;-RUJ+%XZ+lmkFF@_1
z@;Q2SEEx|8R0C)Ik)#aPb3Z^xRtn()DZbuyXaLyX`#>vuC>7XezABt{a}^-=%2#&?
zhE5fPqB%nvBN8o!uK@Vwl#4*Xic#s{0Whb_>fVsA>s<+!G3qI?N1T8&9<ss7z6hM_
zgXIcLGx(al>mFu#XqWY#HKe`kT!L5Cg%9805Orb5w}E0+E}(e?rFp;6$R1Kb2Ze%(
z%IV$mt|BRIP$p70Z^(^xxe3~!ND!e3?jjem{?P^x3|;YvVRMCYGKS6NTxf#_1`oKv
zZeh0qcwsjVXsR30O)mA)h?a-URh*!~wc)Dc+~B$J0uP9SX0ECSZNR(k2qkTBEqGxG
zL?tz69fbx5fveO4A$8mV26V>X>x4vow?zTg5A;x%>K!p{?gf!#9F<N?*xKC-B&nej
zA(EQD!+}AkNEB8g9*rOn!3n2>^HfDTgsX-{gQeP4=i+F{&TtnNN5D=;ohJ-ts1pZ+
zWq0Lw&(tCd<^TZL?m|Vn)Q6nP&Eu|f5|-Y>RnMc%Tipr*i`@i)71Hc_KcwZ-UCzP=
zb1ceWfs(yw0BSI#M)9ot9b`T&3SsdwSIUX3aOK6~^d2>o5cL90xROb(>M8Alk=hGK
z;p*xJA-P=Lur8>9>Mr<?D{Do#JW~xeOOL4GhLky1ZTLl5hjhU;z)tB-$kGN7doKV7
z0NuNa&NpNVy5r4r<@Oa2;B`^xmH2*fA$c@kTt^+v*A1DG)_4Kf-~B=}yGV(=xQYb?
zc;*5X4j`9x1OCH-UeFTAXLa9!|JV&{ghG7o8}MIKH-a9f8sRSBza9<Z9m4LQx<8AO
z8lVgH@8;4gpa164>#j(fq{}VXP>cO=!Cc&2eMX@**zJOXuXFit&3pdH-%V+_r@9d2
zk!!Cj=jLI}E9d4~=Yk$d8kiF&&TV^Z-Va!=YYAzl4p(MCZ{o&wfdxL$`kjh6tY)qn
zP7PV4j*!5mkv=dbx!$l(1Ct-&hZ=@Mu+R>U>T*jn;E^N@ho>%e{3ld0xmp>-=!%VJ
z5Tm<n@EODi0@^p`1a2XSaaCS?DS*+3u26<B`p{$I!Q-v~NS=IGv7qBiQH(nUZzmrF
zGo&eR=q^SOqYuFwB8c&mvP72UBwq?+bh(%r#`sCOG3N30QV^pfc<;p^MiCUm=z>sT
zAR`M~z7)v#NfEztDG|u%1Ns8v7(WPPRxU2%7(qEeB9C*uR~+L<E5&uFC;*Lw8wF{C
zK2%Epag3joU~mou&oZ>2OCvz=NK$@8H4RQKBJ0V}SSLclxTvb=0xG9vPNWrBX!zk=
z`3_6l2O$}$f(xrg`bSgag&Y7OcBfqWP7dzYk0xd_LhiOM07CktaEe3*?=^hLDew!o
z3D7$8LE*>1hc?7uTs$2$O^Tt7OUAZVjf(<XM^O$$izO*#H?1unZ88h6-Ut@^q>L0P
z6|88uO^cE>eq4=NB1O~6sM10(9Bd+q)VxiS@ml|+NdEJ-=rE<!9_hV$C3k5`(O%4_
z^tOBR-F*B);_-rA-(ANG&I&wxKPfj4!2FbsUW!q#<F_a`&p*ub;%Nd?RK$bfJb}#g
zI(<pG#nTiKJoR`$XGMhVOpkCd@DodoN~s%#h7nyC-4R)k_esw;Qe8LQZNH;H;cbXj
z!UM*c<nfBIF2l`>$`?3zbzyeeLUgNk@9KoS42FKWDmAWftp048)*@VE)5W?|xuH}2
z=uYKUg&~{@4hlm!)f?4;@KkP91;VA=stklv;bDyjze`iaVD4Wu)$Y&#&)VDcT(=`x
zLi7DA?y!1Lg&qEg@DvGJf&l`G5n@8C8wq6%Xw(A!J;xDit$i}P?sGHWY+Whybv(!0
zAKTjz4zE}tOSR0&F=+rfN(Y8G-T}Q8GLXlj?W6P!`AO5r9*d@ssN@$-Ara8y@0gEe
zs!_Y>GF8BYES_k@!Vi#bN^04zp@Rk%DKc%pXO97B>w7#Ii>A@e63rqdwYyG<IyZ5&
zv}hLxyj6z-E`wG{py-d7qJ<xHNa%<*7SE<il?S@pshG`Cl(-XFTAq^B`%|tcKp>|w
zV~%xrfaFU(I(CBNWh}mVhPx1oHI+PbY`%HkD34u#$9vq+Iyk&S#431iyV|WayZPpo
zvTyU%Pc6}Xk2ACWg`X>X-{v89sM|crFrQxmt;$n?<p(_7d*&aYhj<+WWAj@d>iOca
ziAnzuclY`r22gFUn_^Vl-4xbz0JEm7)_)SRYLdcnRKn>g$SRYBO$8GV(1TscERXl7
zyw#IzkxEA<_sjrj?DgP`LWs>wF^a5b<v79wgHq*n6aj7ZdXfebb-&&wW?_4-XhDEF
z=oy%0<ke!bH)iDilM=#R3EWS^c|4M`cOH+Vq>+AZPHAADs)a)|^Vm(1fHK!z`u5Pp
zrE2KnQYDa}5QH@o=}Z9D>ttkhzDdebCh&WGl}PgUd^t3k3GnrL4kV+0J)_Jh_<B!)
z$$GwAtiySyp)^szRn74xBIK1uXujh0BC|)egN!%r-;wWm=sD%!mHL5Oq_UGT<6?Pg
zrCtK=u0j0a0F-JDDGP9F&GF{&0iJ8V8B2lZx{`WZVXB1*0s&Y#{zvHcLpyt<cawJq
zBY5?peH_TG_XdK<E!<KtX{PQnFcDZuB4ZfzlZdQ$&`(l)zL_+Wt4S$OW2@Fe+3V&7
zOE!4@q3txlUpmDdaYc3iG4v7w)wGEQ??JR>2EdyWY{w&T|Adx#3!<ceadd6PhItM0
zCIUQIBHZ^5%zcGzjKc*&EY+ykP+jDWf+sy+7kvrN!aXB~c(^>YjU_y3zR6GNdKqGV
z8T7q~&iYDl6Nxc_#%n5kWq`(Of;#&tQO&sA1*a}bv35c1HI>~Iyk75}>^LAEnWnwv
zY}`Y0Z#f&c=E`S!a3FXSngX8n=n9#+iRYWX^ti5~IeR$$*;iiVi92p?sfV}ip|*J2
z&XjNT&xmY&Ac@cf8%*Y+uFLjp=c2s^uJCI}SF(A9pYw1fb>9v{_#(otU-`ZFpN-e;
zG-4<HHAD~0#@lvUrB_mL0vyRFAzc@?kR?JIYWtX=Je^|MpKWHT8UVQpQ{KOstf#no
z3YNx<_iuXaE8%E~t(XK$GSBu@ssf_d68?d{d6w8O;wuKH4B>?@#$-0)D@=37_etzZ
zV$x1wS89*V9Oh{PDnADyV&6X^<b|K-mDD>#$i{^G#uWBFiIh^p%-M;8;paI!Q7|2)
z>K$!^*#&*zL3{R@B|ee}n1+(zM0fy>2mQSLBG&HcA)62>Roj9|aZ>gRlR`3g`j&cV
zo*eir&Qe*01Y@D{7lLbc?$QEzP2|LxN^Uff^X5g15mZGy*`1I=Uu_!U6Fl56P>pjq
zmBwls5pz_J(}<Z{AR?S}hxLWO7haC1j?XI5TgX!3<+S__TpWqhn-o>6)Ms48lR?1K
zh?g7x#B#llL9IQFfH{2t1&f*@cFWH)%N#D@a=hz&rV%ekILI{O<+Rp;fw~g(j*z*I
z-XSsZQ~>oPeyUUPTnRy)?B2!*w6<$UOduzxuU1sk+`+DFN4<kB(C8}xj;Y|L4+J@Y
z1{E^t`fEqMJAVOVB}C~;R-u_Dc)F(80EtL?A+i&pqc4n>7$ib%pAsczS1Mr?6c?``
zGZwsvUfKXte20MZJhi(XibnkirK*C>oG`0~J6OVOW}5)1PNaO8B5$Ofb|p=cngJSK
zGzfuVt_NYyX*9NoytvvE?;b|?Ri1yU!^JtJ+EK2+DS@*IKNzB=;KA!!8kp%xB)C5C
zi2%B5(eOtI*%Qi~N7NUI&ckp5*d+m6oG0)+i)R^2{&V8LHd?R*417VT=#&`8P{IIt
zD5V!=94QC5V}{s9=+haeX@HvpZ0dZOSyzHJ3CGp7XW6@5aVJNEahk+W6%ihCP-5Uj
zZ2(C3JA$SY?`lVcdXFfJAwHG~uu>ZI=su#&LJFboN3VdLKY4Bl_6)HFA+raUlOu4D
zqL1_=K&e7j=<I@r_tBx|PjV%Xpi`>c*dw%Tz-SR#H6*79ksI=EVT8UH@<;?Xc5*_*
zP}5zJI&hKARlz-M*(#33)H0&Tf^L(Ed`crs4Z~M6g6D@xs(`?*O%{OAf~%PS&~jsh
ze>BFyO<<`;Xt}{<c_nNc(fNKjXoQD)T^c`=QS}~b3PCm=8YO~kT$?T2mP7R7&t&wv
z)3rMpsxG4P$w+g57XTtGeMt|(mq{N={iymlF<pVjz!f+bgT$o9S5&N-%vJ_~yLLjP
z5gR@<TL>I;<80N*^cmuMn!DY<*S~7{i!5p)|2th+C1Fq@00FZIOovPN0+TfyC%Cy8
z;3&nq8Q_S)?2ZtZO`p!(3VO^ELcw;ZZ?$xl7~l$W>28H!O~yxyxoaYZ^-31X`6jlM
z0f1fuEWdwxQdIrdd#`Bdz13N)=Djq+fuLFGiw)5E5R2IrF^&~)44L@GMqI@N5AWDh
zub`ME_I!tlxH6?|m`M6JHf+2KlpT9$l!$E>ciS@=+q|_IAhvnyh=bu>M>dCv;O5;m
zOk@)tyK9(Web_SCFq309y-rX(Y?)^p(HcWkcN1~AV@cU;N7VMw^gy93`U2+$UTCb)
z5_LvxW24{DF-tlIPG;Ual*B5CoW~t3zOi`PW`wht182FRhZ2xX1~_AT$@PT*=aou@
z!Ocs13i!3JgmZHg6wet2QhzM194M!ymE%pfKv_ZvyjBgU=EhRs?nEk#vFOyF40m2S
z3X~6gELbA|?TtmV|CtCu9;>SkVnjtHIT;1btN2+#(7L9c6{lSM2UwsE{l>f5iNNKd
zYt!j3(*i41zn-ByLK7&$At=<9tSsZLfiivw%QYEH4dvw~dI?q;qL;vT0H*qp*Nc;(
z)w&v-MW#1&t#<`QEx`-AiSTRPu3bTKY-nxx%o5zplhN3^xtgVAlBa_;Y8eZhIl<YN
zx4tkO5SN{-AgWd~FutmhaHQ5CvIGnwV4oC`Z-fgG%nP%>wQ|uZhu8!`;1Ck{nNYcd
zVB*QhZvm1gE;fdkYu|Cbt7_uAnN2H^<I<|a{;I1CjZ4=QIjpM?ugKQ-uyo%rVG~@*
zTWe)mRf_pW1Xr^FqeHh38s^}h<6B^dEP<6rHf$w-cv8d~=-K+Jl`}QgS1r==aPE*q
zeaKHgD;dR5BEIRQ<(aDGi45Uqj}3ghCpyP*K+f`ssQfYPt6EK*sUg@@L-|>+s3xy}
zRdY}!p;$B5zgi*#Q&ssas}KcKRf1_Y<R+;6F++JKC#=W>^q`#E=TJV&39Rj~_^MQ#
zS32e(voz5~CCQ`7P`uS7HGo32rXQh}vQ!f+R;&pK@38%D>Yxu$I@5{F*B3H{j|m4K
zd$$#+9C&q}5*6*$d~12JfxVTAwd>tk5QzOIpq<f*b*x?*5_OLxho5995PSTri?pFE
zypxm#RysLgvx=d9CXK>SY~lnUc^EHFXMjM6p3o;nB#Faf$Ju2lx%IrX2g;c}gZzN{
z-a`a|@m9&+D@1e#`2iWEl9E$Acnjrx73IZzAX<gUYkX?4;K_+YdIjaKzmlZEBY6Fp
zK{mkkRjY=mlS&jfAYNw}hN#yW#v$^3&LI2W`%24H?*oN=U9amfNc?9y?Sg({ypF;s
zE<oO@&mi$1%>@9zhXS>q8RP=g)*j#jY?^*(@h0yP4#xul<+CUyo??nbheuIKV)CKq
zo4({IhuC;McVwYxPLCLl<m2_zRgR|7{CjRsv1+cbX>9T%1bGIUJjR^eCZmtD+vfXD
z?^L$&^;V09bI54m>^A#)tCYNNwa7YEIz?dmzSiPOeLp--cKdp(<Vt<tYfXQ9-)j>1
z*m=K1kjbC-OB`9^OC2EBmA(HZd8fY>L#$pZm~{Q?#oh-dYFn>}63tYR<BR-Zf(PYF
zh8l;2rB%eaTP^3U+7%5oUDUa{41-h0Uf1H61T&S?{zn`uuRyZ|qTKN{Qzfylnc6uq
zu;$5)as}^96>)C=nkh=&1z%LUw9X)S?6j}hOmba0cOX!*s|gksi}N)xCDC2$1Tx`@
zG!G^4uVLP$lfe`kW=URc7D&0E++?prC*qh{LOU~KQmT#r`M3Y^>A&6o{^S3VsbX(K
z%Src#w7{kG|Kq>^?LRzseYZ~+{__7n)&J{%em>>TfBzW8Ahdp4m%YV4&+EVa^S?a*
z)qnWM_K)q;)<6G;=YRc&fBrXp`ak@~|Mc(w&Hwh#|K0Q7{PS})=!(zQ{rRf;+3i03
zbDZAWfBT>Q?Qj3rr`~;d{qMi~mrTQY$GI-Q&2Rsblumb2s$4_+D|>rm;O0-g{fGbI
zfB(P#%|HL2)yu%6hTHnI|5*pkV}7*DzuHY?f@UvCt^W(X9OVf9p_l*5fB)aAm-9~L
zyi+)i_5JyWx6iEhf3=ge4%o{9oZWXX|MN<?L{cS$nEzY}5#a0Q5zI;`pZ2%TN8w?9
zTx0+3zgg=a{?niS^xK^oEwjUA*7tpLpMR{`Z*IANZEEs{f4!q5q~fo6f&c3BO6e{5
z*FO)eZ+Z#4{jbg&s{y}$`%&E(REU4edjISNv+cVqZ%p*RzL@^;W36d5{q5t+d+2v`
zxR(BDZ1dC(s!A06LAA1u-dbe*`mqwCQ{P&fm*PKG!=9t*f5XuJmg)bP1U_y&_r2;k
z{yWqE>yu9y)jK-js(u_DC~w|s;=uW-+5lg@stpm?|5yzthPPVuuciFE)%L`92&eA+
zn|FJy{`9B+&gyS}&+4Z??H!vOY(I{zZo%JLqy6zx9w0z^Yl#u*r)t;I!%~J(arW0z
z{@rT0)Y1zu-E#dcs_Y~0-Xk)Qwf*Z~z;Er>Ux4Ax;2oVV5q=yUZi?S(3QhR28julh
zHL<z;SS{(X-b!H0`l$-jg=+fW{Gor_7x2-)!z<_K{=Mn{d%l2c0DdoJl>cCKAb5Ri
ziShNvYKV$>t0_$4$7;aIywxnemh$gbL!jdO3i`J-{WpIBy?+eEe|;1B?eEY5Xa4z0
zKJ%|w$naRIlKWq=jFas`Rd)MhML+&R&yT-iZ!DDOyY1|EIsMJ6{=#j4XVL#%M$h^4
z)qDPmwfkiUQqX_esBmNXR+E4S-M?W*?j71(*Tc2$MeXkyBEK{xNe}yW6U86L1`PFE
zNrE4%bs+WLdavZ?ilF8Cswm0N6=&Tje^r#^7hXfZTu}S78=Rlt!!Nvr4&=aBPbK+z
zi13nsRg~oCikDL0yBf+rRx)^9-)gVq=ZXLqepQs@7v4lBfIWZsMf{p(B(v35UnTi@
zko(V%i2w52EBU!%Q7?bhqu}RiNK*AxPm&)ij%1^JtFinGZz8i3#aL(l^d^4EL>$Nk
z`_)fLejXm;b-yY~@^eKXWxgs(@^eL8ZG2Uf<mZY-y8Bg+f?s(T*Fjpw%8&2j*HkBn
zRKFCVBtH(3;Y8n_6iR-s2n5Bq>ZRo8io4);Ulk?!xnhj(N?H1a_mG#OfBa4SlF^83
zimzTu^5f91W9QEnngl;r1K9ejo+Lk41XaRUMM-|H2+Y-2MM-|ebh`1^`wzc~U$dPS
zf)u~{D#;%#?LW6e|J=s>({F$I;NRWo@>TTyZXfAWli+VNZ$2|s?yjC`wSLFpGJj<&
zXGalxdbjet29e~CMp)rfU-cMI^>el4>He<P&JV|1R%>Vfd20~-Q8juv@fO;*hx2cL
z2`$#|9e@6D{2ec$0Rs3nynTMwr>F?b;8#VV2!E~!nvk!G%H92QMUeJ>RTPcy&lM3p
z_Pz^c82rVTaWNIY^D^x3c^SCT{u-g~xPKbqiQoXM9tD3;4LG~Eni8V?SZ#MWs#$IK
zpB&Y!25J_*g(Iq#UwR4WLNkBw66Dw4!2tvBJ2+AD{x~?mdERP@bo{Xz5EySYK{9@-
z7Px0uwa~@;kJaP`t~U_B;sw4Tie*;De_<~$dx?}(@8I_SYX-N*SCuvX=;s$s`Bh<@
zAFe-9#r9W)3`YL(=WrBbuD|@mfBQ_|{HOl~y^ZLhA6|@MP!#+;Fh{)6TTKB-KUM=^
z`mLtaPd`>eio&<riod2cQ0#F2S^mX0;Fq!UcizC?vE%#Tbs7gZe!Na&HRM}(t9Abx
z-S1Xw^DkO!^RH-aBX^IgZ6)*hv6>ecoo|5UUwi}mf-Qe%xA{8^puNXm3~v8;5yxtv
zx_qmN`|`(Xe`)gWzslm>$T#s;Qv!+~tAW!|Z=jv8#{Tv<a3ivR=NtID&H-PZ8A^UU
zFadV^Rq>Vl!m04W&+CBR`+s4tRksTB{p#wM=ns6ke>OEJ{)(ge#(8brTK(t=`jw3=
zQ@`W|+m{zuqCfPI{>1|L68(xJ_;Ua`f7M8TX}Puvjrv}%ujpsT9>PMutG=RNaqeB7
z!v5EcbpMK9382}p?tY2>z?ZTA%;)egzrB)Qah_e4t-orV@k{=*LL-0o_7(ksD=hwU
zF?@-B=~i$4(;9!g3;l|@M+ee(XJ64Dc+dY*ll;Y|{iomlv#0+x<IXYv;~o9Ihp(~5
zMdH`X{>x$ie|OYh*YNwFPFVEuseL10q?G>Q|JC&T1WUcQ-T%+;>Xks;NUD{)7=jVt
zQ6Z$^gt#GcBM=cD^;;0jR7gfjYK9Si5lY#KaEnm<ID#v}iTKY*iYEnVv2GH=D=7$~
zBtp^Ug%}QJ&<7y-QL#o(Nor8!GXQ2hoET=Hy~7#mQ()<E+A7Sg8O~5sPz7AUs$$QH
zA}~EFmi`J1Kd1+S&@amI5YC`xkhz7jt;Wg%np>FK3Rj4Q5iD{>;Y4yJhF{dgGTJ0o
z4T+eO*cbpkAc0V}a7LU(L9N0W#0qkUaK@ul2G3hY4aejwQ!&zdUP<-Ks~aT03CHUt
zYb7Y+LP>Conc_(aS`ExCBi1s*<t>(Nj})N6yt)yXT4Rt;1V)w(9E^%6o;WoshU$ZD
z;|kCK;(=3=GjkfIpV2U2`UofQ<7wzbd#fB&L9c-D|46EEJE641$Q2r!bU8?tnSzF2
zRIfJUwZTpo3j9A+sLdKd2azNIl~(gpU|2_`6n#>Xd%-byE6DV4>YTrMIz{9|WM<|w
z&|PPwKRh<EK`Qmx_+yjQ5qSl!0G*rY58Xqjf^LGjxl=;-2_9JeA&~&6V`4LK>(p&#
zh+5z*EG?z229_f>gMu?vL2L$d0>>5`v3#e#)~NXYrzH7WcYUd+zW5L?0m$@X6SR7E
zbsKSh%xn;wA7%x_q+nICevS@0dPJsL#Ms0h<X%D6gV;ncoj|9G!Jty3#%4^}3A{Uk
z5l>V^X>3L#BS}JRezph)3gt0J(u6BOqX)~wDop4cOf`d^Zp2X*(dfaz2ny~E>PqAX
zSAvc)EqjifG;AID6k?Nirz2o0006t?T2@Nja7DGQnx0v2sHr36$BD&A_}-wFNS^Sd
z=+5doY8skpF|w*70xTAjk+<6PVjVR#KBHSoUfwE@>Pk37D6_?zfdIfjKff!<b-zLn
z0XxP=gyQX(5-zuiZYb?Kq6vcB3m@Ae3!rc52$TDW>W}CGBY-;6!d?kG1%0%(T3w~-
zmy-Rqg^u(4>|n`?ByYH-Tro=ts55_TEYKyFAQ#P27IS2jy^@JJgpyiQk8yNvz7Hxr
zwUp8rykH^5hu)y6)>L-`-JK+G>7X3@i135^(4mH*sTNbWBl7VI*e*D7V+}P7g|(Cw
zya>`lL=qi*iRBi)rQCX#_)t4o*RBXHAG~tLWA)y$ghoN-b|q-EgX=$J{$J6`G7=>t
z({C*0u<lTU3w#8<Voc-BBXK3wcN*$fQvFv3W~9FjF<5k@{*B^$x>Mh)#L+<8A<aQY
z8sLx{>q=_THnnTDtA{cP^j=C&i2|-5*9CI`^j>>pi1GhQtm>=><?O1`1@%6wgo%YR
z6hp?9WM?O`R`()*3nfwNV2}(YTI$HC8_Lhr5hoEs`S;4P`=n?=u(HHCfxZ*fe@BdS
zC{5Mp^!6z!`)@~_bRd1!E$7E2=8az1i<mHtdj@02T>r#UQjvsMH#+<)!9--em&Ou>
zd`A-CE8);8EIg*NMP5-Z8j*8!gp&tp;yZHm#+(`*)K=wNtAz#4rJQV6va*cbu9sp6
z^0#+n1-=42*RFQCqs%YVZkxs*Lu-jUy(7LprlC|bOoO#s=bX`I?a2LdCD;i;f*NA}
z=*SkFlA6b&!F)pG=-r^TCjVZus_ga#9VQm^4w}rEO*3yJi`YsG$F1Ztza`#J@sV}<
z8b?p$@oUi5?MNvcVkPh3vi(R<s%x&$Q=!u`cVzWyWr<IOP8*?qLa&X`^gyqTP^&Qf
zVz8K9=j}uX<>r;t_JAxoF<cEp$rb1M15u66)pBY&W%9h`{4fXY;|^BNV0zG}gSjHc
zR#T1<ZH>_}B7L1jiF^fouygj8Mg`SJ2J?=j#32Ur4l>Ux;V)K};4HX;8UYRA4g!x5
zdwE9`V~7={gFHIKUfzpeIz(RH5!DhPFYgBJC-(AgP<~=kxss&a3$d5?@lk(+Ms){X
zH^f}tks>HWJKm9OIEHC6tbEKdOtqlgl##b1F>oMfZwJLnDADiJ2Z}YbNY@<V9PgkI
z4RMZlU<^a7<9$$<fw86Ins&&Tu5PEK_91YOhLR{>Ne-vI1LSow)GFv`LY(6rX^BFd
zE?w8l_`shO-OiXyW4!TDh*HO@2=a;dfwP*}!>{CSsitp!Kz#`|)4{<X%8=d1&JtTG
zsAMFS_yb8!uDHZIzMe4FsL{AuE&XP$Mjhu&GKXJD^<5t{GUbNJ94_Xf6ky(<<Vf3F
zBHq+jDI1o340@!nrLI81nGED{*g09qNU{{R)O0F1Tk0(iXBbVr+Ndq|fhZS~G2p)=
znMIgP>f(S3C4ukIAvYqtO7%^OT)fYorP_0#wZdc=XA+RmRbfX$>!_Ud4@A|~fl~F7
zOnn{9SyzHq>KJD-i;HgSNfFzHRuo@(N5a`F!45N_6-~zRNArhuS>#CV5@aUt6DK?C
zY8r~ux>|<vwEBvl66GS0^$g~*Fxkpw?py&{npjw}mT5IzQT?QT&#psPiomBMbI_IG
znNXGekb|^?7dQIhGYcrfOqLzFkV3pa9pr4$=|O%vvMz<FfI2M85Dj`y+cUcCXXJyr
zl7({mMxuw>hWZqHP)9PWE8(!AK1Gz?C%nwjWgr7=pAt-Fsy;Cab=dXMxB3Uo*O8Zs
ztP#<rmM0Wnr`22;wn8LC9r-^mb|!oGq$n4rh>1EflZCj{JB~65xw&PWb#56OQ5}e$
z6d8Y0GfwYv&tp||dY3zLcZK-YJF?qd2@lyIC=3y*cO>u%1qb(RhW=&VG({ik9C&)7
z)7HkBHAJx9ai)zVNxG%#h`nuKw(ad2bYC|$UAj*k>>YW*qSJ0i{_?<4^S%Hu@qR@3
zLGA%vhWnaX!WIcnLUdW^3(1*74DB7+%tORW9gMqIf^7lrkLc~IRyl`7$==~c`AD+#
zQG+6C>Y(fmk+XL=Wl~a}&MV4^Zb$7x7q+8zOBagY=?ZeWwW<KJpJ>wA$X9kHwUdDL
z_X@B(WkU53CsYUJ??+Pof+`i2d#`L}(P)GNQ58)__$t-eXmCFrjK3jz_r9Pz1zGG!
z!X9m_C8*A}*;JnTZ<#GYb&3?e!)X{zA3Ge2A(r^Q!F?S~c6s?Hqsb}<y=ydD<r~*|
zO;$NLVXve%8YF#>M*no*Re|kxj8Hat(hEnMY=cM7CIfs!$2J(?#U>nLqrZacsLbmP
z4cg?i?#Rz}MSLz)Xd8I$$bYln(4TFn@8EuqCKG)_gEsoDI{+A0f{kjI0&TL;;aY#9
z!9*{5;QR?2FOAxy?!h%2O=kOs&TLBib4B${(c-Rag=lhM<Kp2;*coWVrWC;)w-?c5
zb8l!w5`A4kJ(ry+)#FDV?8<5Xq==1smaqYU`}a!lOb4h^&g#0_0jTnUBqOxN7S?y5
zWtr2vl%J#P`FKC_PFE(mCq+ZQxqrM8bmdgTvZnVzyXm0zQfYp+>{GAvoQqrRO75Kb
zk%#(T=4BbpdPCP?kv}OqIVov>BR`!V8Q|V)G_t>Ohj=Ay1zDx82pfWz9qC8Lb5iEI
z_{lmbbN$S(I)OTLq~cE14>Oo_T)TcGC}roQYwOxJCG~OpVBh4Ab|PnGb%Q0>l~JMl
z%n}=|=C1@d@*U){erRPo0lG4?eby_Lkqx3)$4zC<{=$3JX9ogYKeDpH3+qQNXkS=8
zosJUFzFr9%+gZZb?HePIO%0aUD`7jJ0Ci=3=%BK9^0f7$boC=M8<egNTB+`i0V$1c
z2T0+H*tTP#${fFht-pE57zbPHm2iaRL3Po;b)X@xq?#_5)-7|?0rayBZ7<iEhYW21
zIXq-)1MA@dQ#+9&9<reUCGpBG@jz6alc(AbIwwyxm`fdeR=t=?UHK=T4ls+0nXUuP
z;>t<UfoJg`iA)Ee#e>%Q=RqAKka-Rwx+_^I4^+a|09eWehO>^P1K~>Wp#zz6C2y_j
zAnocHpMorAuqJxE7BiqLSH!2*cX%ay>cD%OdMf635`EIazULv!8-MiBZcz0-<kbdw
zp9d`M=Sph!WNJs&sDI^RC!^mj*HV#J8xWL_<U#TNUjFLXXinBJC<Z-b42Nfl4+M+r
z1xHn}CQHuhfDQ{es{=|bWK9=B<qGJHMQ)Uj2&H`aE@L^D`YrRBP;oAAbs|chD?urH
zAr#b=RKx&n-uiM~Sv5L7ZYTfoM}+VHiZC14Bi!YlMs^u@eSf*txC@rifmCs)aSWu&
z6`*lIRoqF8+yPZ_f9>T0thhi`9Vv3$X$k|5;!5$+PnGyk;B#Cksw*0(!l$MtbXma%
zn$TqiBbSf+qND#n5xVSP<Y08*sctztFDn@M6?a;~PX~a-U8eA1T!-A#(53D)k3X8$
z1+nU-iJuhV&$UEdzG-OmE8&P4P9pockS^|GBkjPtxS(2>aj8Zq^BG2nD}_mio#OsF
ztUrc~yG-E&#pkkxVf(nl6h<mYcd6jSvpgliWJAj-{G|iZ;x30Z5=ObpVST)GpgSDa
z34C#ZusV=0?zEnfPSRce>TI>?;tq^&?y{zlUeblz>VT>EmKhA7iUWD|lxU^kt(0Ba
z@>au&_6=*<V0-(fx7u3W0J<Po1_R!eh{a&#`=-14O76Q?YL+X=(~0k3Q&3==Cia!o
zpaP{DkgMUI<8kU41H$Es@JuK;0kjNQ72jJu8C7c4Q8-<FZ&iWz+8d>udvO{Xj(WbA
z#t+rCmCyW&4ysK|BvjX4YP(d|UTS$_W*16j*6yjMq1y<<GC*K_)8@9evcyIgdOz=q
zFdVU6Ff7B_-S<$hHaaoXt&P_^$dqfy9_LCPb0yUiW7j+j>{h)I-=?m49RXa)Wv-}t
z%g@x{`tVIl*~&ZOyQ^X6%Ia)6u(G;Zhi=?mtwTQwrDchF@$w`*5Y#JdeD1**nx1>G
zRLU~8id?@%_7<t;e9`Q+4u!a2_8O?jT^KCu(1)w6UQ57=FF}|Mh!tOSK^qV&zUYF!
zlI;EpwG4H*g6<0|T+5ZPX`K94py@Jne9;AMa0I&Y<U9sX;T5rQ!yxH{Hjushay<wd
zknk-_-{_qyTDb-Xsw;Pn!O40htW&+w_YJ4)mDJss^_eB?GQh3)TIw3q+gfTD>TNBx
zi*&Uv%$C7v?8?bwa4cU5Mg;Y?mResm;gh<|;K9BkwvMCU;=$TF^w}Ef^F|K`ods5a
z6<<RgghpFK9fU?(gB^rIgCqH4X&JJodV;bnQ7^7cKet@-ZR#8J*)p{oSprhgkigZK
zu~8^EA+oNdMq?;dh-p`=IMS`IR&jt^U1NhvTr|54d1`&NuUa|nF2t2t9nlmdaRt>E
zx}XggP9F(M8Mt~h@wl>bf~(A++LUp~aL?tFPH4kjn1e3oDN#L`?Ut3{s*s}*9?Jlg
z@fmCv`6#c14d<j^0o%oCZibqvSLuRjS=~f_wp4Ke7_xKtbUkQfZ(Z{SwI~qQl~j+#
zm2XHZ>vL-mP>XYO5TzC8R@2am6DIhRq8bEEaKjC*&#l&>8kIT8^07+|FKGU`*m7xR
zpG!?ceFF7m$W?pGY`4yjb4hIgOXG8?-HjnmwY_VMRO7f#cLKwn6x9$Xn)duR9|?6j
zrN{xANlD{x%GV=KNJHLmpMwvr-VY52p3pfojZmhA340)_#Z33K0Y-BrY&^B;G_{P=
z<}|bn9puy0c0IE8h|1#bv;Px|)h~VS18Q`p275|!YtSow%he?9=qsrONjusAk8x#;
zdJH%cXYMB}q=`?ur48s9A9PC_&@n!a8b_Fe3m<kxfog2M>>Ovps4K{M97k>CL2}4f
zZGhysAY%sBavw6J2bAQfQGe8*l1E(%{aW_JHI>kR%qL|4!?=K42Hes|f>O@okf-{J
zaw5mpaH0E@hU!Z0L=LIy0o4ca%2T2WxZn6ee#1k?_ebtShBt69E<l$J1Sa^9(G2jJ
z4}NXP4(vllGv>mF3};N(<Ab>AE83{WS%K;sGfVdY`W^wkyOP`LlaiX|p=P1>#!$0R
zeM9DWp=GWBuyzAn#s%rJ0o6BXdjlHdL-uz<V|>W^9soS}koAql>w<I{mb?!c+p}Q|
zw6$mH#^*}#=t{@tf@~R5t+}#p*@S`|bW9u4WB6$F78vp^JBhn3H-lTmm;jt{pt=mG
znOkPd9r}JWHH{<Ukd0n@j+-oWq^fhHJ_mBfO(+oqbjFeK%K)6YWwu?f=StXgZK@7p
z)Vn6I^SaPsmRqwcOPFEvc9V&Y9o`Kl`a~K~w@^!^Lj?viU}xN9k58yjB^EQJ2YjxG
zO+km6qp6ku<_PQH>coo~;5A;5&Ih7g;<nW=bg1%^St(#Q8TlZ9bt@zPu?Y<-*x8j-
z&t#!b&l2_;z+zn4%WU$zX|&E~X+M+UjWp9PIGDjEa+`WElwVmT4@C76Cm)>3&!%QS
zuvlci&p`L-$Nr45e!zy|eI<pO!Ir!NKDAV2V#F+wEpEm$50EWag3SuZmX9P$rPPdm
zY=a@~LTy<klYUZ!Eu!Kf+`1kLoo4lCocfHeY(oanE1}b7LB|QkWtleAt*K!+LM`oW
z98J6*Jrw6eqPT3$Td054YZvUwkS^ML=*PFUE(>{0?1Wu5GLB;2Lj#9;>#~}0q;uh}
ztWJH;OZs9s8D0t6#>uYBt_C^Vm9TN>yzaarwY9T|j~jp%@3feKXYnqRx$rEmWN@~q
z76sL^1+~~^G1o!-3OFLD#V(_HQ7v{F%?nzwO9d}zML@M|)f3n(^kRQ4W~93IE{hq+
z7w@u|7ZjtAT2@$?E6ALbCCSCuVKT!Pa?5NSin33Q8Jbf0>>f+6iwo^#0KQxawwm3t
zwCdmJye#Hj3;A(DyR2MD-en$ds6?f}Gh{|~5K<W+Ew@as4}4WlD3>M3<rdit6rytG
z89**qf{Q~#=H@G6(@=>W#&#iLT=*^n62_Tn&k6|hq=aolA@-)W4P%r=4hN!lS>zSG
z`J@ON(Z&%`tT+ZBiwovu1!VCiOBz6y$J<e-q2L;gYq(LpN!RX`C2TA3!(IvZD)?%z
zhz&uXHF>s?-up_>PPvgBx&NLL)tIUVv{{p9d)Ilexdw>SpK=3UNgXHz{xV`+nk;OB
zU4+^)fL+@Ds#NaMCWrTil4~2KTxCsGHr)CyfR@4a@8w>8APQ7tOZ5Xb0_SO4DAmNu
zO0RJ6Cq>TRkRFT8mc~<NLnA(>O_ZwVx^XgMU7DQP2!?l|tqiH{y~&sD9W5KeH?AaG
zmObrId`%WL(oA0oCIGihPQ2BVqUxgj*@c;DvapGnX|%8jnQ8K7^CHZfbTuI}O-46h
zGfg%(Au)~SG!ZeCd9kKzX0iS}(R*3bc^!Dm?0RjzTWJ}s@+LneYW&e%`dj&@3}g@c
zz;rG$h<#)^0}Qjzk%|BsW*@n?k^Fg!8_$4`xe~U$v&420kZ?r{g8Qa!nJw3Mb0wU$
z4YD<v(sfb1kB}i(QbUv}ja(o5$W}(S;!QA^`Tes@;JOQcQpD~CdIwK;-Kl38TLSLg
zH;HepF6MVd^FNSeB9S9!H;^y;$k`1dl&$PHR%9tD;eA#DWUhd1AG~`S(*PRmBUg8{
zPl-@#i^dU3gGa*%Wo`r1vX7K6KrLJFFU!og`zU?1A<^wVa&sfC?LIV~qvH)pBLfQa
zk)U)f%B>`r1{lnhuy2OhmY=(*gRg+?B2no++5?a;^dmv3CRU#9OwhTH{MyK)xlez`
zH!vD~?ZDMs!ar7<q5#Au5i3jV#^UVDs||LRj|8Ppg^-O6h|nfD>k6_LA!PLx<*bIB
z+EJQqD_iH4SUs4{*7E&GP|9I$!M6;6nkzxeb=2D-lRZ33Y_t^Oj$r(Z0YS3`=ra6k
zhwSW17P>>~Gy**<OZzF&Lap~X)jK(`BhWpX<57QRUk_$Jq?0i_SAyLEGq^*xIIuQ5
zWQ^CFcy`Db2ij%_ZE;|2w(wmBtj!MC;y~KmGOfyl+FSuz2C!y_Y;OQ-wlH6r<uzBw
z>#sf?gM#s0xWyfESp(X*1?DoqA9u)QeUQt2hiq+NYj(iiPGrpvd8~n~*&+KI$eJCm
z#~RR@9r9RXC)gpAyf%v+vdFQY>@avC0Ik^}mo=a@oA5ED-c12EnlrP%Fs%;`n_F-(
z!+yAf#&vC}mspcMgFXzI&A{dEQ1G$=H?yPZ!O(|6NA}rSV8_b-+b%D5p=O>Gv1uqo
z!Nv?wn(eZ^p~be#^gf8QzalhU;KuE8Y?mV3F7*xI^p#)_LJ1xX<Z0f5jTwM49|=mJ
zGiAS^`;>Ug%6fQ8gaJbNxm?|_Lp~Cea;AN&S2Yz^!ehdL?sFRAqqQv62Y)kJ*DP+7
zY6j`l9%+(2DXCc=fXi%Q!3G$|w@=lAmLrO56qm~_!*MWRoo=VgdccDHNKnc-qt|-C
z2EGzJb8yOrdIFW^L*s*5b9${u20z>~n}u3)p{oZFGTV(!O{@`9OS1-KYG`7O2wgoI
zbfKVKqunZ<4_)YN*FzUNTc2d*R)21BEdHSS+TSN)rs=M}lIncZ%z-rRiqLeaKEb#K
zkTu)eKk*0E^`@qw`@GTe9l+IWZ)*Fa{q|A2wQ#qPU;`+cD_JO~#=Zi!lc&P1lmY`F
znk!)|W$<nx!A2c$_ZE6&;1IlbXoyglJJ2?i;|{fSs)Uz8?YLddKs#>NfJ!^|rUc}p
z;=59W;w7_eM}exNkT)f(_W|HdO0X6Hy-5+47_c`f;%Aijo0On=I51L#`Re8K{D`z9
zdS}1e`>4*2^G4!|s`Gloy`%2}%MSo*QdD@+QJ$d^vGbN46*_*vzmy_2R~j!x{1!X1
zFE*KB1J0`yVg6D<rhwB|8Zt%bQ>n<5unVJx7g_@FwS7dc)+Sy=q3a*W&?(o%EOv_5
z38MftDZz39pe9AQt{H&Tq-;S@uS+J^=o>{0uJmK3_&}uU01hW*Y;D(+)8rb6mrc=v
zAXq8qq#lH^;ruiZh?^4jz%jI`!Ipz4MXMg<90!s01Fr3lXsAztcR*~=fP*|mxW^d4
z)T9iZI(#idojROdQ?Cvu*WQ<R*i#;$1|0Y)LNBaU5k0rYDK}i|UlC@U7S+H-!AC?l
z=fGV;il7|}rjrt==>ZT<%4&Q7;iLqgHb6BWQByCC-4gxUKoEV&8h<uflMgfYtD%^E
z!ddw#QN0IQSi=ThgG{U|s-C+(bpUcw#LXokIVoZL18dP)r&gkDtbr@36oKYq;Nq%e
znDbdn(L?P|ykHL$>*YF~n$NJsf#Ck*N>-IQXNw(l^?9+Aj$+!9pE8eJ1Av+o;lUgI
z+v@SgI(^MB!(lUJ?7-$QwmPsm6rR0?`7JKBj|h&Gp#zTf@LFsjtw|Ak;8+j7)B$XG
zDZ@?#+K-QDs%EgCyv!JeBKvsMDVcM2*elv|MqMhz{S~28b;KH0DkcSLi_4V9tTCug
zh14H|>eT5<9Ro39C2RcIDgk;h8V6TLtt-GQ;8AOgUPanPqvNA=Q}dmp)y6QWHeX{7
z@P-oA`EZQVo8Ht#>dn`B8`PUL-v*VYD-Lc9YE8$XYYb>j=fP_L?U5Os*iG=Ox3c2+
zsN5{}Q4f$>xzVy4RHQ=mk3mJc4-QTPj6#(`3SF2v-q*GRq9;Xcjp}y?519kVn~zM!
z*`Olbyu27=R}q`npd#I_?Gr>!DZ@OK9^I}!Qjcy&5k1`6U<S45-fEj_RM~09fErZ@
zzyRDQMbI<A`=ki_z@W0tK!7o*X%z`DGU=4U07e0Po|3Vt;LFw*Kd5?z>mR^-rHBu!
z_m?6LgsNBg{xPU}_tfL5dAAOI16b87yXAS+t`cgDNwvEPKNyp0ck9?Usdg(m{ecYY
zRwus+y{qtn0r<}qWwCS7nzZ1gW@hxjnAFS)As7k&NdX2AyibbY`5Uw9)IT{aUanjb
zhQ&j{gi79B0|5PG$~Xk7<Sl!DQYCNM`;#h}5d&9J@33hQ)X2MO7}UyJro^OH-Z~`^
z<&!e@0a{tX1p_#r6rl?fD`Xw@VPbzre8HHdmKQDkNv*87fGes_A~0Y~Xxt?R^D9E*
zvg_w&>)J3THSTgfoErDS3+ho`C2amc^Q4ILL4~_?I+#?rOFWMQERrc>2ON`&7=lbZ
zo2z(jH5eG(mcp6A(dmc)sCK5<V?}CQ#sG|ov+0`J+9$Q?V$9uG)TXQar(;o<E*bW#
zu?LfT`)ZtDf{n(aGF7m^6=8nqX&qH*=zz4SP8B|IMVL+=2Nn;nOUHqQ!|PIT-dH@n
zE@}KlHLS3KE5eJBVZW$hp-dN*sbK#DWU?t@H>pk)3NRMcX`-C?tm>z}=|ydd$559p
zf|srcub?reZY(O(rQ^XWWxAT0pB$P#=tX6kF$9%)BzriITEjth>L9RqkexaRES_WM
z(I&j8ffYG0*2ZA){;6$e=-H)i87T0iq<XDbfw8D_XJ{Z)xr!eciz>Hn0>*;Aovxu#
z-%cI`7S*jH4923mo&FAuI#*!^W8pb$Jg{!3qgd-h0S03s7CB{TohM`k8H|M!^3-Vo
zbk-?i+lPDbl$B7d*eT&kqMBB$!B|w&j5Qd$Rf$KpO&vUS3fR=aiX<4DI#{6uV^alV
zS1(bGg}{lise%zrFgBI&)Nx`{2hXWJZ&M2^@?h-J!U{aN0=ze#F?Q!$d-s>klkn8h
zU_<pPXkcs}h7~t3HZ|`AA^X^M$el9#H&yDC*}th$XV<f-QfGfV#e*)w4912+opJ_m
zD%7b1#8$@C_W)4=nIBP87Z#@z#|3cfr+^PHy^BbL&!@AYRFU>@Y--dY1AkMaGH77z
zt1CxnpgNomY47c5dl1NUMXLmSFg4`}J(x#Rg%*rW<vHZA-Bh1LAN+>;96A$hfT~i4
z#|M_lkj=mA$@R~g(Xsh+D$OBc$>G$R87?sD(Df<FLU*c6#S9Fm${e+qJ|(L)JY={#
zb>@)a?x=+?->EXkLJ`)#LJx*hg$~*EP8~XA*E@8mq7MeoxmSiV-k*$iuOsV_$?jCB
ziZ2*Wg*sl7-A9!<rolnTUU%x)F;K)9Ol^<4QAk;R^A7#0h=bwOuL?RCP93YDgW*#n
zm2=;zV~3%bPnH$$)US*}7|!GC=tL(Br^;1i!f<NcA#2~Eb%*Q%r`E0Dga<OL4_fwc
z2Bm}prqUfU?Li2UBDx5?G_T?hhEwq>0%156FGCQ9Q}5b&M@YqsAcQN(!6*n}I5n@L
z5QbCr+Ux&!>Ryxo->G_yrvi^EVNY>tUc@0h!>N2t&VT3eSFs5LIg?Vv83+#7b${bj
zzY0(o&XcXl<ahd%6<;u-RguPaP_rt&U<5TQ0t~L8K1$PVKtPF_z*JXM@7$IeqaHO~
z2n6-0LK8+%jT#8;2KZxAf~gAXQN|~XpdK|{2}Bkrxgti;=WI~yK|O0aHUv+qChI?V
zQmuf42eMTXY)e7CYUArscu_nO1XZZL2Y{HIUhNn$*-sq+LixjW9T3o>rr_ZL6iUj_
zBE8C{gF{f)8jBcRmxm!r)tXKcxYbD!9!#&Y!W%~LU}~@DAGc8@!*n{^m*+pIaWjZv
zL}^>bFgz)#+3m9T!7P;`&Ir|Qm*YREZu{%_59r&j6F~5^+F7aATbJiQ=ut+(fv03O
zUWG@Dz)#pZ{l`5}te4oO`-9$NMm<~!1|ehrKvQ?w^@p0e%eFs_{`&4HqsKDt54ALd
zA;#%dVnbBYeM<!%`iZ+N`$I*oXozvBs1*+}4it68L-1L(J{b@(4$r!Zh!}@1=dPQ8
zLyg{r#2Tkmde;fyP^Bv}VgRA|5$ObQsKUunP%;b=`@(^KR-D5))X!a}{Goo%JKF~$
zbY1rahw2$25aX1B?z$~FRM36sC~>HwyRHikHFVdR;7~&=RAL-x=(@^&Ai`R~eZg6L
zSGq4a3j-D|<WObTU3xu<I$I$V<52f@S^S5}SK$uhK-E@o!vhg|r8|Q|UE6U8I8?M<
zhk!#x+Z&w~d<xs5rfs?~I8?QYk{F3<P5~f!<51H!*awGtR#6h;P|Y$-VjTLSk-+CE
zS&mkr6IW8*Y&v)x9&#JK3^zR~x+%2uY&^p%{9!ie+QvJB*{Et205Ka?ZF9`iEJo6l
z)Kpywy5%UMOIvMG%>rxll&oHXA}MA=k&V-r+;AM3jjm+IQ9LQb&^CTjtFkS%jx(=<
zD`w*XxAExl%tno^V2aszd~H)*oa__N4OfIt2?I78Rd3^cz-&~#88<N-)NUK<Cbe!G
z?<7(0Hl8nLquy;pJ)rJwLtQV`OQxlgU||jvu`Ep;pmuIJV9ZACj9Gn3R`1``JWt2X
zG+6qZ6>~8`g!~Z+FEks~Is-4RWL231p~_ZJ#TB9JIxNgao!xjdFdKC?gD+--#%@iM
zNsZma={FnIwt_HbquOpwouJlMXvS>kw}Y^ZoT#!3t_aPSoB9gad@1&WsEi4O)lpc+
zY`B{|hi8eITh>Q_Bf>4;F&qV5OvH5^#9Yi?|K?ovj*juhV1h#YD41dbMs<$sp&fnm
zLcz>}P#uL^OdzPvadoxc{y985OlXF4cyxFs)W=a^#sstaQC!9>`t_77lmm6x_;|9&
zmIubjdxHs$d(KjoiQd8XpQ*Rc(Vf9WoZ~rD9Vv}^CD;*wn7R_|TL4U5NnLba$v`dk
zW?_DLUoc_0TnVRP)dUZML?#TS!x)Q+$kL-2i<!`<b4-uj7=k|YjvL`CVkO6fSLyz|
zYkYw=yT%u2v}=5kjnaglNU!jbpj30#)P=yDF_vO>czMrhYWUPTZ)*2oq4NwdVaA^f
zr<gGGPlzRGehvaBXzNd$6i(38pEyn&q4_3wg-+0Bp9YWP38~mRz8rz_u3(@RpHmZf
zCFm@ULC*<#@h8qoA4!((zw}K40CfTu{RH~yfS2^H2cVyh0xTxLPe&0Jv+z$RT#Xt=
z$dB@wfI1z9Q%nGzjzTJC!kmucDJD=(SHgzCigkqUn>MqAZ{H?Hv^2(vAuYB$(S5}@
zUQza6pRG;wf2o<$k|&m$S{TsOc8o*+iOIHBj%aFx3nMD)eZsqNVyb1pqE1XTUHi*X
z$i*yF)QO=%Zmf;LhBpQ&PyGbH!wFL@&)(4@pWuf$3YD1f(Hw+IOyniHWp*XdGVSaM
zkkg5-=hmV=(e>Qmd+c~{{h5;hwHDIH06e9n@i({g$^~@=`N2n-<a0Dkn?7!!kB;(*
z&(X7lFSUGyPl{LtT8jY>vs{x$8N(;sm&f(x0-JOtz}H-nRV_ZZu#v}u&xJm6dgQMp
zXN`%&pA^*qWMPkyCAM7V+HvPo%cMI>Ej~w`08fJOX5xhovxHBu0UcrHCh$WiBOE56
zLq`z~&xG6jD8ymHuYP=KUZIG5Y4}h?g3INDa$=X7UYOYG+Qy_#4IPTgr&`{1<UYzF
zJ`;U(1h<<&7M%=}n7E)gE(5tPF^<c9Hi0QRij$bQ{5Xn=m`J#H6c;f^pt}R5JT4#M
z=dLKfMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=&~vlyla6;a4IPJAiYFzt__|t$
z*7L5`q4|__e9o37e4!K8?O~k61c>Mg@KkVk9i=6oxK}$0m6*l*b?OG_fh7B@*ocX&
zl4sNGMdHb$Y~&N!DGwlZ&zx0YE6{w3l$d}J9Yso9NiN$RY8P4T4zrTaf*Bp5>n5&2
z4+1475JqQ*nua3WK_AKl!07By+XEw%u10##BZS_Z6aDjds-W98P2X8mbXV}!st(HV
z#WnQVn^OhNwq^N(7w>HD6p1W4Tb3`7MQ1NHyl|@6OHJ1w&t7U8stxJNXMvB7V0IJN
z_E!Sm0Iv40gl+E{;#AX)0m-BWci{o%?kQ1qMz%2ELPu!1S!kgvz;*(x(3NBdpA^-b
zqP+|XprhpEH2~Sh^Pn%LW<UUYwyB}iZrd~u2lH!erTjxj`N^-O22^J0g8JJ;&R<E6
zhOY7n_{(AX@(GB{AwcdkJV1lamKH5!&=II@0vB{Po#YeHpN|BkG#b`XPoVvl%w~{`
z9%Uz=KongG_KG4atp~B`ktH^Z1KBz#<p;fFWdl)k3KQ~_BuBSoWfz|4EE(AV3!N1x
z<%b|7+$7D=74aFRqppMxSy^JQp)-}z{7R~?@28B6;b(2N1f{uXL9bGoO9u3U%3Na9
zoIng6Wi_7*dUMHy28`$|nbC<NI!i|M+8iXUXh4Y0T524sRjJM=07OS9x>*pSv&0cJ
z0T?=Ksx7Zk(T2uUA0<Pdpd&tj)ZKEfFWJX{H=ZQ}85!#jQ=LzsfX<@(dm`)ob43e+
z?CenQp*Yvj%t3Lkp{AiY-(=?#>;4EfH$UISSu(Qm-JAs@8(-F0^m$)N4v;SIE7+)l
zuYW^HE*a4qN^<e*-nS2OYtIc8xSBcw6^JC|6Nua+1l$DL=PaP$pIKm^vzj^r1vu%`
zo`CwCc{F~gKqV=k8_`NfkhqC$_)MDK05+d_)Yj+hH$&~<>^I{bBMyJU$IT68r%dG&
zfSw~*+e~eA%h{7B1v%YQPHQN&D?#U=+mx7m0&sp3z&1Bxu+NmodPBF(t<FKWO}VRg
z>9#3{^{(yUIm}-^H?*CgYgbYu+9>7MJ>{%Uh|n$5#)VCBl=FN74s@m*)gTKxQ|30v
zg3i?S)CBbBOc~rTr>=w#g8rLwTf;2-NKm?qUFppy0woS{XcHl^XUZf;#KoENS0gOr
zIa5}8p@`0ukq!{i$t36#_@N^p+XQ;(q>=YPQsa}E?p1@W;<%{X=@SO@5v*-Gpe$#~
zB1a;ME2$BBofnlE{R*n9vbP-?bG{C0hsvDtPdg5blQ#M1JaVS&ahz9<lA})_T&6O}
zffKqCHVv&g<(4j#&>6DO0TOzy2ra`CswC<YL_`OmxCwaB8M4w7A#{f5f+o&-XUIs;
zW@(M%@OT7}n>b*e0dpK#S<Z;}0kvN#Y5D}-CncDDsLUZxwezSs91l*7IpnAY_~#5c
zs)7AELd8vBf6frBed3^ghV1n^%by{09cggRfS($Pa*lGSKeOWU4k32a^K6M+=o3Jl
zBTU?cH{%R?smtB*d3#gcfbLVG^9jGn5#DVA$8#loFajd4sGb}x|Be{|hUW~qsH0&K
z$ShBP&Kd8CJaA?lw7B6EIzt}n3IshvCOBw04zX^ZO&yt_j#8UnNi7zZauVgGhU4rE
zd8x@na+tJyR)p;l>TFgR?v<cab0#-6@>`wJ-tj@t4Y{dfW{Isr&kb4NK;e8ODAfjI
zGPuhjc}(^;oR-J*H6qaYD1G@vEcA1T6q~X0@2mj@XR?*ysJ#;Q3_8xl;WOdyJr*cs
z&-C?yfae%}((oZ4lYJdXXnsrvHefl&WMn5Y=P1MZ1TN<YV>W@oIkvgI1A=o*7Igt|
zu7C~U1gN~|6A+vOh}lyjuUc#>Feq8n0ljE6s1e(Lln4EpnH=v3Nj8x_@0h&O0ZnM~
zN&}N~O!o9a?$%?ps0*ZXlnQ;~{^I~_HgQ36%V-+6C|AP07*{P<gtpJEB9j|eHHR6~
zC*V29WO5fe=SdNNvQdW(cZ^3CHm;P8>Ek}7ElpAC6VzQ-#HOGw4MsNZs*X~m&oioo
zDZ#DwF*&w@y*VbwHnLD2lVcm1Dv!ahUGSV^%DOrM&pCvrO@MQb$+Zn^&atMZC&p6_
zw5LQHKjLF*K-wn&o;h7sc423ZU}*CI@N~L7-ayWrPP04jLyxkXPu!TEE}I&+s#ijX
zH|}1qh|h&)>-2b^`c$ug<A!EKg7c?DH3k{yr*vDF(;J+Ar_&S%?cY%f^k?QR^+~kZ
zEX>PcCi4lz%jvS80eJaHP|AtzvX>X`<4>oHd*Ral2ne=tvwu1*=#>PFw+!FPLR#IA
z2!F0wq=)-TY7%L3uLe!m`RT4!kx-{kH4I;9pD0!Dhn`v`uSQGBWoq)(0QEe=ZLK!Y
zps_+JxNhnI6kIoT07|aQPrU#)Im}I-lIj=j;?+J%u6H#ICD%I}2J+?fuBM^(dRNo%
ze=1-3Dh$jK=4%1l@|@oIWH>i_(}VK>sD$PVsGcKm*J?XUu)G(rLZ=<|AF8k&wgOGq
zj#_~t1d8ifm9_hp)k^IZ?Wp%qhV5wDaM)|1rjfet2*R}z@^Z_2@+Z0STA9TQaF^3U
zO+z_0d8rq`E~kasF74QOmR`WRoaSmdFi0nz^FrT`QkyS~?+EX;a!yX$dJI%wqZ#}x
zAmpxS;V0E&+QAD*yF+Z(0<5LcZM{0+zo*e}y$Eb+bX#9ZzWqkG^#Ui*X=PEbUcU#D
zcoF>47TYbS%oVWVp5vQp6(>NYF@F}2i$}n)MTANl>Ke3Iqsw}IzU0$}YEX+cLcOo3
z7Up2*pt6*deAVu7gxXrfwKUTfNMK7dwKZ#UO)WubHDgN?QwuHoq^O2u_(2V)tL2p?
z4i2Ze*3||s@sH44ivSj;C{IaEzdq<fu(bA7r<PZvnYzI4^ATmqe~WX}tFkIX>B$%H
z&LP~@>WFr{BDPw}>`K^fDzhuVwg`^-z*Fl>ixWhfEI?&~(5wZd%oVWZ`%%XUHCrAs
z><&c1grHdq5SKWvejRj!=JT?KuF!nGlH3{M&_jJi)fafER~jdAXineq&WWQvy<pJ<
zISNZu{iTC?!8D4q)p%M@ah95{B@t!f+@%F{Oq`|GJH{y`4RA~du(hm8Y}oh`Cr4x$
zfi!TLohhkbjOyA{UkAD-`s#&Xj1UlOAw$HKV3R=#i7Tn+&ips~iF7|##LiBv!J(E*
zL584O3pRfoQ^Ps3CyuG%iI;C^c;VHX8edq1rnVQ}yfLa~A!kRNuEsY$o300KbQ#9*
z%Cp#~48oQtCDogz{yF;7&_73SX!$NcUE(x8Hu(qQ&`Z4lb%{9YT&b*xqnRnS7Rp+_
zD(}jZBJ3?V>Rt&OuMaQcu<`mbuYj%R#~Y#SPYdx`q1@&R$z(!^uq&w^O5FnTawXg!
zMh^K(&_VbOt^^%~U*SrsgP`dN;<ug@<>Cv^AKYKlZ@rN2CxU+Kg_J-MTdiLG7R3qt
zKu{CTbMuu{=XaJ$CqyhYV>ObcRuDZDN@~7<nu*XCjR?pH*~|dNgiu(k7<itDslE*K
zg+A#8AJs>KQuakgG+bN}45(OegGCHAGcm10otv1|p@!?JY!qzHkvYs4kTfC0)&i0y
zg624YG!e4L3r7=SM7J$KXF{pZ7oamC7}tV(F+#?5<p4{G9^_eM*P#Rj(z=rBZ`WfT
z{cRcnNGl^~evi_DA?q8S*a)d>cxxkMe-Eg^5TWM({M-Nd+(p|yRX;y-Tc5fgrPVy<
z_?(6Qr+@p~|Mgq{t$qHh|NVFW@<h{Hy#N0%zkw<}m^Zm2>qRVOyoZ}722xN@%ug8g
zd|&lpL{lbfx8Iz5T(9rW<INYGsRH&_>d@MYG8t;NYRC!podOHVRZO`%YT-GI(+4c^
zt1<zQLm6DGq1aiRHpr@YMaD26mpL>BqqGGC7`VnxIsiu9G6v+0XAXwgzIksZ54J~f
zAsvWD!Etf}IsRt=4<Q*g0)3816(*?X&X6;b9-sH<%0rG0naH{HglMO070vbeH0EdZ
z%yF#m&p*8NPy0VEB24zzB4QSHEg~iU)*_<M;cFSuetwq`eIK=qlu;e)$jRi6Wwhu8
zdzX>Y#%LM&f3}R2NQ3LBePw9?+pEl^?{$P=Cat3*s)TnPy|K3MI?@V!*OA!1-gTrX
zukUpPcP*CDS1<{ekx-Sjie89Mt)v%s^0kuwY!!8R3E>I)i*vF`l@I6%2T;9M(C4W4
zSwf$M)A!wgKL1#=ci(^A3IauCIE?(Lf7eF_O3M&mHn!xC;Hgq>xx$EIOAnGYMtW4j
z=}wRO9Kz{L57=-aI>(~z3~@Pv*)tME3f9jMjU$*r10;@jO_wSWiQ`ATh3Ffh{zBZ1
z(2n7>{{eh{LWGL|M_)lL$OKg1VksW**N4*!4vPD5lBvYX0{XMi1v=5NH-|_WVPJ$4
zl^qLuOhk<ZFb|P50)if-Xaq<-M9>Hf`xR7|>X;g0XG~7p5HlmVaf6W2C~rxKZ?TNN
zCncy-x>aCMK>tHTib$UjPM<c|e6Ik&aWMV{c(o%>mtxh9z)aH$fCU@k)TWgi&W!<v
zaEO+%Oyv+KBaG<)BO|Qsc=;F+ZxK$#h6EQOHpbIZi&ulEwvzxD6i10Cga^fWLwdh-
zb!=MW2uum#JQ2GRFNY#heOyWH-^c|L8=KLof1`V4i-qX151geTeCIKAnwQR}Y`hQy
z<H>~(o0k14J25r`DRB}EkuTz~7{Z4l7eWXhid+aG=EcK<rof&D=gg!}tb=iEn&bzE
zM?p9bPLF$m3<sy{5P%a}<s+!VO4V7L*Ox9ucNX3hKV(E-g}4(B&Xi(KgtOraYO%l{
zaRs$RPu&2<=C=!%#uenJ2CqkmH4*V=v1!{QMC}T&Ml*;lHoxA3(<GS?k$5P?gLtCW
zT-lZ7^0{l2)(TQ21t|^@trwe@Pl)J?T_0)&`~{ev?z|sNCBIbUatd)D9vmmdeArt<
zC;6pbiRDzumTAylyFS(qzuPU>$8{z3Y4B^klKM8}LhrXHiyv%92CM*+VMmgzSVs>n
zHMVG}H>8A(#bb6a$78He=b^Vmf7s!^46q;e2HmxSC)W-)=oO)*kp(sa^|f4mhyD^Z
zVsD`72~i_<1lz{q$9yF@Ab!og(w(IQ4cB^&r8KNpl#5_(wO%UgN?<j%)QyWD^eu1H
z0l=*zom+?ku_HqHBS9(qw$xcDx3$#UU9U1oka#84H->a{xaL0+lvbXs*iW26*QA%Z
z;{xF8_|>)!WNa8}aPfQZ8AzUjURMqs(dHi!{$6uG)O6{|H8e+1lwwWnEjT`Y@*Pq0
zu}nXLW?QD;lxkb1&XsO^u87kD{f53km5ChjbAG5&y_w$duIdwcN;FUftt2l&h!nAd
zx*!(+TGL7x3XUjGig0Lw&vi95TuSjh#UPPn055vWH4f?NE2_2Dc%X(>6kxRXPf1|W
zj%&o2`0zVIF0KGC97Gc#<Y%u81~K)aBY{B(_t}xa;E745v@6QK&G>q9c5d=h?=uVR
zX)UOjB0adG{7eKM?YM}&5;hH=>(r;-OKAd5`jjNs8}Xza%pf5=X$O5sB%ZV*@oET8
zdL?&b)*<Q&@+}KI+CN9xAa1ndzB_~)?VwHhNUBfei=F!DLC+F`iGEHr=;hMFgJPVz
z=Dwop>cS81L-o~ncw&Vs?Krl^)JNYj;UQdU2WlXMEA0g=2*FA_um_Q_(q7<%PifFs
z+JRsQ0!urRCxn2dy{8gQfM^GfA_Ne<l00k2gi`NT?$@c$9dL{gBJ@hCBQ(mpK|fBh
z7Ib7<4kALk^(>%UU^0ryLv%+j=MZGH8$AkBy8v)1F}s?E6P5tc4g^dHB-)FhDW=#9
zI$RVXjA%EgydfW$!Rsn8XD=L30J`~<B&U1u>be6<6hw4(gMJ&K?m)i*(b+45_mcv)
z1O+$9P1cdcAO!pDcSwSKc7y&K^etRTjYt|Bz^nk`^Op0omM^6jmMaALd^!+d*U!V2
zUe6Eqs^lsQpgB9p%)UHBq&$nU)p;nvvGiCd!Lc}T@Wqa$iL3Md6JzNmK@pCnA(SE<
zOEZV_;Gi=L9B@|v)OSy!xEK>7D2+GxQ5g<%Lyjwhz8iJ3)kn*J(-K6sf$L$#=-~B?
zA%|+F8i>J@?=9D~86U|><E7OV)ui!o+y_+L(3e;^&KNu%UqJ@c2RuSoP%EkHxmDsb
zaj+Y7jP;^YjO_8<4gpFHxpF&jt1+k~3)vb&I&wgtne^m9p3JbLIe|X2qgjDI1CL-I
zGyjdvdqABTGYVWuE*g^w4eH7;>DmEpW>U7bGy)8QPf7B_27_Q9P-Z4giv<=&O^YQM
zCT%-PpPB6HfwQ2913UOY!}O7koh9fEd_-45Ykok-85Qj)Eob^3@vVkv1^a-Ov)5q8
zHy$S4iftf_`Zf27Fj>^tNkSxpeSnAcil7a_zIr9lhM;H-lNv4_*DGMt0h5vpgB{yt
zh+weSjvDxLYBihxq+<1KN@ow84J~zN5!r?)1h1ghBVi?1lHauPF5pVij1Re%uc+Qv
z>eJcN+l`S!ONEF8J5*Vi(Z|x0&o@lgHJE|J>JiXguM2%bQwi63CHQWt_&Lj2*RXJw
zv#tj~vGJCrBf=!0fu9o9Wb+w0(K4;Us2tWbFlaezYPg8sL*UI0!v7E%VTXYfNj%tL
zKn0lxKa!Ot9-Ux-g}|O2Mp}q+u!Gw=1m(PvT-U`D_&~H$z<xkO_0Vg@DXp`V??jNz
zKEYfZWDe}0{SFZac5wVhcXbZRNmPQpSjM9}Z>6pz=Qfd@A0dV#Z9Ad8$Rc<J`IU-D
z@JjB?_pNr}!0hkc49<BX4D5(f3&B16#LP#RE=4wg5bs|{GJp{6Uq?285bIy(;VC*b
zZXT~fkk5_-SbzesFP!E&oz+)T9Tr-<FX%e)1onyx46y`u@azY{p&eZOL5jd9MY#w;
z5qQhB42RmT5=U%!(bDCMkQy-oUQxYisdI!%26zBFG6sZ5|9a&vNCDRAf{qm9U&rA+
zdRI$Ok-e)WsK^B5<p^gMcn1d^+4=p$%MfA=ypmeEP3^)oiY~WVMYDz&1UuqgqiYXX
zP>G#Z0K#UYw|9)d)QB+fO6rnO`@q^+;!~jl#SGXNkXAuvz>aX?Xj1zKDgH=Mx}9(F
zHc_2#q3s6QI-==#jg%hIr1X*ZBN~<dN)@U5&8NdZc175b;6w{i2zEHyLJWc(&bXB1
zbU(eEb<ucZ)e+Dg$sgDe?;WBK>=hFpO{eDt7Ud9G;1$(~cvE#H)w}got$HWBd*}On
zLY#jcSLo5?7~9aEZJ|`}REOjZ#o6ff?z?A+Z2*!Z#=s80Z#12c(=8k#3+x*=JdtF9
zw^&2bez2ij8}|cn4TOjSd(ja@6AgI>WkHB0u!Gbfnl=SE&7<j*48Qu7aKkFsdx+ex
z!#N+izVD#<4>J4pqWO=;bMn(c^B+wIWl%tb0HYmu3nBKuj_ZeLJSTr1be}7~_=a*N
z?O#V0s1WVnmDC`cTIQ9ZNdK<L>%nZf^skf9uY-fbkBoW{clbH-vLSVri@>jM&l0Du
zJ_A3p;&**2eq_aO;8k55e^-=90C4=>@~2aNbkGJni60%b!C>Mq6<|k-SU)o4!G+?Y
z0_@3_;vxd<xM%Z&vo>?nx|jeva-8|0A&)F*e&jK$+dLN!;1#Uwof3%lqL6Wr{&jH7
z+%i6Tq$0SIY9}ux{SY4B>(=r~5xS3yO+T{Parfy*MtfzcO9`IatG7$Ly_XvDLzwuL
z)BvVhFNN$!?lbRL3{z&aSCK6nRs-#SWL<Vq2lh-t;35v}ZXBar=Ey<dM?P~mj8O-D
z9~dL71s^p;-H}~M4N;qe4-Ang)?Q>xABk)T@HP2S#8>y3MK(M!MA#3NIy=i)KDg?4
zL0G#(Yx~ibQyI8j2-c2Nj#si!uI|el0M@HQdsWZ&rzArF)LJe$YX|PZ0cY(1M!4Xt
zy>Jsxij2R>j>$m)@P!M{+PxIA3(tBb+4*=630|L*3(tBbE6Z%VzDXyV^$PO63(fj;
zFqC;{djU4Z1!wJmueji>-48m*ec`#H>fwucI@uj5e^9r%(5xLf?VV`WUU~1Ilt9%*
z&66jZ^_CKUC*2SHjSJA)0l@Lt`i7#EvWIqtD5dOzv~~a=J#=&cIMNg3+5=&LE|hCe
z0z4PUwSyzig>miR(Q{#3I{-Ew?-ve;jfV_?7+GS^240BNKTtNF0M{PK{NbU`894!5
zfYvLi_pBQ*WC?HqTCe0<J1$UbM*?F{Olz+`e@Z&|1F7r8v|d4t#dHRZl|{C?&~^FL
zF*hziYX`W-g;(vdIr-A_39xa&RXY}d3$EI+NStWZ{#im^P}S-fG%H94J2)|2NYxJB
zOb_XJkZWE^gFC5kIv2{vcA;4b?&|>RxVQ^DkUH*g?iEhw`SUvKFKXo4`l^v{*yW?g
z7wj(VU&nXuE^DH;0(X7wU^aD;B6g%azY@emcjQHP5ghj1@Z9~YQgu&e0Jcqcm;nbg
zsqS>K_d@Ep2o5`-I_}c?!0Ncm#Rsg;<1QZ`&^qog1Wx@MpE}?=PNu{TMdB~Av8S$a
zmv;{#7FWVHpdiJJ*r7Zfd2a4ffQEI^8ul}@#41p2E`1I>&Xu5Z)MPFNUN9XO(P0Np
z$6en$DEi&y<tx*~U75r?%oq2;rl9V8X#N+5G*GJ1=yN~&$s${YwsYeX>*(pCH0)^v
zy7L4ME785n4FszFk0?v`k8;0(WZzxxH*oB`>*#%uO3qz67vWSXY5Y-6VN<^XQ<x4p
zSlhnE4BTOkUlE(GFU`eM*b}95%h=n1!TCsjyO3TS{eAQ7ZLPEy83+w<n=7bCSRG2P
zfcWy-&aMPAW;oe=L?~59c_DTs)lp|Nsi!vmb+=p=;dZqPMYUZGcMOJ_*Z`dM%`h@6
zkj~?KtL-{M`rco_=IrcN>(GFEt8pm6tvE7kBa1-3gUa6b;#12^^}X~|Xgo0%TCwv#
z^&^Y`Di4%}w`>Kw1~j@s-|eNQq4SD+>Vc>RK-1oE*uN4sUO@qDw~m}wvQW-}UIAN%
z78KCU;Dzu_%iapf<9n!G&{p^!c<@I5hn~C9e|+`UK1y(#`UxGlmB_>3iE$AcUP<+h
zzIg)*$4O~u1;X*I=uiU+$F~6Nh&}e*)jHImU~q;YW(RD&V|1m>vo{>uwr$(a4kxy4
zJDHdh+xEn^C$^nTY+Fz6KhAsBI`95a`|9fIuEvG6e$`b4tR+CjzI$nfn-Mn=7OHqc
zyCWuyep%8SAHEq9$~trLc6ewM4%CCfS0;){fn7k(G#tfw89>xgZ{dX787gm)+1GGv
z#KY!6$e)f-wX8WX<YM7qpa=a5ZZnm<6AhHHN4wxqQ#B6l$|`pB2GgW-M6OSFpu(s=
zUJm{p$_P|A`p+WVLLL+{{0<(b#H9b^O_QaSX0E0QdRbr7B5PTn*l%nDuI>~si7F`s
zQPA1$sDT-w#;d<fY)BVxN{#Z2Rjnx;^9WU~7yx#x_WLSP@`Sl-m|Jbk;{1n7^ktPw
zF4XGsSz(39{Tctp8}<cOu+I)C82VWb1}_m%+fYX3qdeZ!I_G$BIo|tHBHPePB22-2
z;^?HPyqP%ju~em7o!O60b@lO?+{y;iGDXA9>Y_j4@H^5!=(#U|B4$ScX*5~L$$)3T
zY16GU=jmecRaYEu_kEl8K;C`Rze)Mp;yriJ`u0$|1%#>$)CT%OUZXfxqb&t;ckvrL
zZBQ+6^WGSdO<ta39XXCaA46IecC|znSfrX1fjW=jfOxrauVRDpI@G0+@7T0`YprYF
z@q|Rm3JpTW7@f_|ts^-`cfwqS$Y8o~rMxDpEAIsW$wtcOXbjl~f<s?HDhv2=FK`gs
zKyV7IFGV2<9e5#DVYV2@K(KnF7h)wAmckt9(_@ZSE5J|ZJko4u!SN7`!vLt-pZ*Fb
zs~KAeHmkNRX~9CT5EzO8^KcSq=Y~33ABaF*Pam`)We?{y6r4o35cSCn=%v-c9wKQv
z`5Kc}=J_w|`Atzcy=aKMEr%Onc{D`Pr~L1%fcfnsYfhrj+sNlcoZRLNK$a)C4F-(5
zL;G-C;QSHp6GSr2s~9NGNGXSZ|L60<kshDDLS$`|KipLO+cFTM6Y(zG36Rh2_Z##W
z#zBdVD9#7(0ny6^k3Hv`H0gB9L8`v#Rsx}Lqe9?1hzZ2}Q9)Qnwu1UpD@Nx4iKvF^
zfHe@RR_TSnilarX4S>9+O>iJ8jfVX)8^PQu;A=F(a>?I@BMWBm6E%L-gCv`Z`@1ae
zVA1=*1&v^PPFIWktTC)4MsM(qg@)!UhS9wRBp&VDY{1~|AMYtA_;i^7*bIWI{i{S7
z5z`-~h<8Lw-)YA}ir)J;@>In`ETBwXhvu{bJbbQ$Ke6%>1)v6*cWATE!#VOqhhi*x
zO}q|)yNfIBlE7DLkA2c!AqdanxMPdYL=X9vTM*ao8VtqwMsYnP_@Oc2k(3F4oi&N%
zd-<xqZ27CWIx^r07^+w3513#6m0<%4@PTUZ5^uZCuo8ZXF4+?PB9Hn@e}IE(ULf~v
z*)56)-JC{$vt1$CjKOKwF3U{19BiAPVaDSb>hK`vCYWPb3wA<#D40}=G12o;O33E4
z)Z7WtIq`r${Ue@WF(ZWl6YZmT!a7Taqw%)sA_QsOgS%*DIHube!6E#<BQ<Dkz}9UF
zK_J>g%~~UD-(i7zQMjCa$`<vYo5(tAfY-`$i*pXinKcDW;uKFMphiW48BqYtv0os|
z)*Gr67y<Zz^b;%O-zSl3)D$!y&OehSyyJ^(I3)ePqW1ds?1Zi2m068|p9P|JN?Zaj
zI*#7<gG(b(NXkafIaZ!~%Jv|^oSO2dbUHX=uMh5sbAxb*%M?)4I8j%!FFb$N{zKzm
zenkNTtvwT3QiEv@q3)zN(AFRQvj?$Qatot|q^eFgi|N~A%0j~WR6wP0$3+c@g!2a;
z7Lb@-5j#h3NGIzc!MAPRK$%s>2BI%v>*0me*q=6}hTOL6sZcEs;BE1XEA248{590L
z4CPTPMAP%gw38TZ+}px-hYSX%{M&3q;`!<z<Ysht?(FxShX(G*`syH%vmmTf<_1(?
zU)PK9n)qr>3`S&M<Pe)kEEYAxTnNcCm0U5vK4!-|D6#KtPP703A2jfz$(mO~u>yY`
z*g=p%DhK^?xMSf7Chbc1)mymO%@$G!#52_!As_-lF~@YL0F&%0Aa9GM^B&@S20ia&
zQ-J&e3wI1fu|u2TOFXq2a%31hs{!oAV>uPBW+l1PwL)_MyeS!UDkOpR`M8r6WO8Tt
zu9}p+K9!44?mM!};-J)=Viaj`H=5eijwzY-=%Ua`_<gk~hflJ+K~`VpiEah1KR)Kz
z<YSX%Mz;u%TjvQan9=aMFg2yNY!pOnO-tb&Cf8@z4`x!bHSymTP?>IyWH@!)az!O>
zecVP;Y=O=hXT*xu@Y{HfTqLrMx{fpq{bHnOrM8oF3mH;q(NcKvRBMOX#8PPRbYBc8
z;-KR_iDI)H(xxW%S8qqlOIwPr-w%V1y$*B=;w^vMGeVUCI~lK!k|Lu&rmlpB+#aPE
zoZP%5D2N}X_+Mj#9rthbb2@DvC{;>^Z5k->tMyrQ5r+;Yo{8A-Dd3onf0Gx=imYL!
z=8LQ&;w@ia!{d>Q!-2_z`XzhV{1gpxTS0ys<@yBR4<)+@+7MI}pBVSc6-MFT04ii^
z>dt34NTfPZDk&QbEi#KF*)}ZfevoAZ(Yr^H&c?CZeN!KEXdL)n%+Ge05x+LXDn&;1
z+s{K2c<etzDLt{B3VP->(bl~>8ZlE4eh#_Ku`$gC@~dGuv!t*#1v&TUr26Q+^x9yN
z>Pp7(4P&5tj!8~bZ}>WvUvigX10io1-UYw}4MRB=t!>*od>#N5M6-@!_irzkk$q5n
zn5`;W;pjmgKI%RK2);qgFGMD^?Vgk4$OSVI?Z?d1C4bvhfU9+HvyB6#){kiuY+l_T
z(>B8M1fVYy7(A0ge$7KA79r%TA_dq~3*WivF}TKUnQ8QXz(?frN#!@AZ0n8sR&=`q
z8C4evnC%!o#<zo~nG&{@8k<7v6PB4bD{X7-7}+N>odYTmI_j8W=L+&pxBJs|rCsGb
z!Ra`7N)-g%<f?rZfjDhJCgFbhWlA+riof(hS(yQip3f{3=8*f8`1jfvjnD~!w1AT|
zi1hk^X;LjVfnzinxvUY_+<k3-e}gTYafjdDBcG`7lO}3AxWBXMa0xj<Wl@z9rGmNn
z_X-RK#P{TeZK|?cYkS>Wp+m=|bd4J(iq=2>P=?3<Y$ID>x*nH)C=EDQ?sI@7xtv-o
z|KNpx3pwkuH7bubQGRa#t{6xAveB-%qsF;xw(;zv{#<QVxuX4C1>!b~^ylb}PAAE;
zm3in2^XG_UU`5Aw-?^ABNP#cAP+%U1*ncc-H4Solb3P&Bsj+k0v^xM-XUF$Pc&R5^
ztZp}Ba4@7O+=?;kmp!3JxMnFGu>{>nqYhkSW~wN`vI5<+!w|K-ug!||<R#K&#lCYR
zlV>T#vIc$6p#HPw|Ne<)Y%5ge8d=AIk~=w3Txc_4<qU5M>rt9`Trw`}I0Lc5GOW{n
z2cmDrV3#4BnvSA}mp36B{0F}#!aIRWL%P!f-_-c_XX6S4kP(9%5>UMDt_|Gcr)~cP
zSiwD5x~;!7zqlE$Tysv;yr_tWOQZ>h+a68PCD6IN_yWHF;b?e!p(p#DUaYylNXWu>
zbk_;(J;IHQ^0;=;jf_=d*Vtw-r#eF~`HU9%<~pPF1eu2ANHdzEYDZNzY~^L4o7{pd
zO;kIx@_bEXQ;G;9H;}vDH~uvhcztHqsuxD(tXkW$)KZJK^*M5<q_tJ#@{)oBJDC>E
zR4WTc^(ue6f@E8nmQ;cLtr9BGCgK2lbo%99pLCLVO~ye=^r`dTVuCb^TQh`^W4Nzp
zG|{h;p&$J!gX;rC{Q_6{8KBEzh^*(LC1O**TWFM#?Jou$_r*rm>s^*xRd@_8{F0b~
zts_0Gk94UON#V0nM#Eda4L>S_+Sc;p!ExyUGc4$rOY%}M3exGCKMB~clplbXsDY|?
zX)8y8THQcSdDPZ`mD><!S$W@<=~_7Zm4O}LGY`svTG!`%f8KtMAaxl4uqSzX`;u5P
z0)SbOftP!Krf*m`m-7to|40_@GXoG!MpCgB$C~Yo%AOYDo362UPN|r;Rs$Ym<C0|`
zK!Zc5lv~zA3~WsMy|3a>2}9_Fy{MIYiRxt7ERgkM>hDK}nI~Nt*m*n{Oy>wyHMO8t
z!IQ63<*H(0ImUy{t`vCJgF}a(a!vbn>J<vFsV2xV*}2;QELm2`Ap%^%?921-&veB$
z_xV6IbZN>AkuC|*_Id3|Aqu%w98q^517Xdk13JK;GEsAXXWxPg;C`>0$Q7~JB3&@z
zj^+LyQ+c@<<se>dg31xHMb*<Sd(NzpM`dqiGc`Kf`fVE*YJo{GNYJjaE`-9qs1nV(
z#Zq@aWY?}U#OQ)Aw`?$OgPKqlLSf?r=a&>cEw2_dPJwGq$$asE?U|_vn^m|R6c;+3
zapj1oUqWExYorf>4#vJBS-sYqN{x%(s=*BJqG;9(J?h00`uYRI1u@1o&TOpzmhllG
z`jc5>Ri?%PuDeL)08uSX9}$beRIfxi2Dd9ozG?A5UNgrhZglZIM!SHe&r`Cr>&}w;
zDu?#7JAhP~V&XT^Xi@|?&(?F7M~hkBSQ0!r#MVF+HiWyG>ECTEXGf=+Z|9_$AOlmo
zMaG#+qc7ZN2Gjn4v*teP9ILff-ccRSt);46c=?HOw0;q(&?I^Te^8tbMFMK&X?%Kl
zB?v`MI2a1X%<;k@2sh6r4NUcUdNpyvi<REonE(^rECjOG&5H`%g6)9ypN;VBOG5S;
zvYJd2`4!3~emr0nWBsqmfXQZ}04oc{^+o9kVToT|o;!x2hRPghF0<x2j&`UzX7!t0
zIe|>98zi7uWo)K}pkjw_37~^!e#{0##pU<n?00>{!=-uNSu{UugR-oIjUkaYr!!1{
zP)ra)aVk<wfJpq#q3(%Tyu+R%&r?aE)c5B0v^JEe&C%89CC{3>ikS8vOAIT3_ynXM
zo94}*(gL#@J>8}IW6yfKo#3{Wx&b714%I;*BIPwTp3lj{yHS})$)?wsuy-}|fzpsA
zj#P%!DY@CP3|&H<kO9&+oS<UzwpriXib`oRQ#=-mT~Dpb7<IM_rd-jEo2Fs93o#a6
ztW-$fcUKMD26Fg)j|lSAH3)hNt}P6R1~wc5Da_nY;@(hEcFZ5sb;9vA!*`hy%^!o|
z6EDe){^rfMv*JDIJ)E-{E(!x0AvE2{Tvo?m<7oY9+HXx3X0{&pXJ%%^+30Y;c?_4i
z)J;`>Fsr?RiPA(qnit7(Z15JkQ2F{yXjUp9A5|jg`b=zAihEagTdK*wusdFhhwBGh
z@Q6Gg9K0kY!JoN~bO#yzIox18eGXu14|dbQ(!tpoB$s}R4PSX%KleyeWbwU}M9x>?
z4XZNTkH)LZ8=}sLG`d_x+(^n@u=TX#(BQQ+Ee@_;juIWB+R)HeRE;1$0cRr<KGHSl
zgg$FuXCR~JuwNe9AeM2KV+-);Vv{q+;0+zJ(Ts9mcCeAKBIaq2+<g~T*E#(>spUTX
z<tFCz;n|bw+-nQQjIu+(f<fx27=zPTG{3H~VfM^~_mzJ^!IJ1h{R$ePl+zkehcqR@
zg2-nC`(ya+ZHu>Z6Y1GQ@6gop(6?E=Z`lG}BW!^uHp8{32A}6>C5R=am~cf8m1neV
zk4odCmXHPm@;Tdlnq{=3jYL0M-9n_+{&>s$0~OC){K{}ByJd$!4eZs{3X)pHTDa3?
z(@+bEZPu|iEE%o}yrp(7zi9_Ut?_Lj&|3rfyVvf5E$w$pml&cMfaYWEPKoM-=XXHH
zn|*hfCa4#vq~!kJ50Z+K>&J+WY9tL9!J4xNEzo-EnUnB!)x0p78~p&YC4W@g(<k<b
z!MXG%X)?FvECJx5gp8(9UmMHGwSA1GCZgPp{y>+XN#)+P7Ec_w3!5tMLm5__0=zO`
zE3{4O8EkL1qD`$VX+UNXb8BQwQ4;pby>uj9a)AwJV74e()UwtMeVS{H>rA^zOAv`W
zbe>w7VCIgu-&Ms5)(s&y-|rj-q^xpH>n<Q`*lZxKj-`XHq=7=F<e)w0YzmcJF!O=B
z6EK9#=4t2pL_n+CdV8W$+Y*K2N~3SiprOU`S|_hCT-Kl=^|D<eGvatp<xsJnbs~|h
z@MyE^oyfP}EVKGA-%NiU<VRa4Z|i9aACyqJ%xmch_J9Yn{m4*z)Hv%K5Ag}~vn@NL
zYC~(k-0Mga(2j`KrY3F!m_rdqPGa>z@9#3jLQjqSt;r6>zDW0yT@G?4#~~;4O87G;
zaqGa~jkK<=^36t;$nlb$ot*e`OD2$wC~U~`WyhS$>hWL2LS)~ek!=btYWOPKpiG>3
z&K-4>7B^IFVn=Jv_(hj93wO~<7rP6JdcZ#&uol}`bGD?rolYWi729>lZPJq2f6FP~
zHitS0na-{6`JuwJxN-Ia_LuBP&WYr=!8FP?2yD-0NwT#&B5G0En{cUk*$V6n&NVcc
zw!kzkH`nBT6|Yon25XdWuIVZuOU~FC{cg0qpcn+~EIF{LQ=~L&bZN^WWF`Np+T56o
zq1?wXbUP0IpqPj``leG#M@vhq)G8*(mc`E2QBttk>xH&uzhYJ}^VO7En*AH++MC3S
z@H1dBX5B2<Yr~rz;-z?9M!Ff))MqJdb`|0xGWUqn^aqy`hMK?)k{PPmCyy;~{UON$
zS%BX#0#twdYJ)8qU94NF*v@?d!|FXK1|h2sZM2B1pgV74{BWfr=m>EC!NIfRLkue2
z33ma4!Gs?CRcKV-l<z0Ugs#4g(U+v-t1YB_b8QPP7v^>nWkEyJP2Yb~EP5->Mb5vy
zG%5ZI>UG_XnN&MC&Ff^xhrL8^t%xxg&tvub2m_SYiHR++FeA|G-_Ls#Eyin1<ko6g
zDC024E{{vtm@fMMO0LIds2aI?L4z}OvWzZzp=ysuh!nNV_Mt=}PyS&`>7q_HtGiP&
zXJo3O>J~B;j;>ECSRInSEtFcS&@S?p5~CGuCu^?=dJE}$w9&1EXXunJ)7*2w%TfYl
zhg^f;T4P!SfsH@<{8oa6mnCJ6nDQU^RSuBiB<mJv1WQFT(qgLT6tOXD3k<nS5yqT&
zO84x9nx?^$yE!OXlJf_=NYYN%RSl!O??a#pBy?>rDPSvSb1)PUwaX!7G^M^C9G#Jw
z_R>3K++Ve14v{(A0?Kwv36d=&d)g=$Q)2ZPA4*wGWHZ?^;;6@D+}5M~C2Z#OiBC(V
z^6jV|9t_C}e0=HWFOqYO5Qj5AIJ|`DlDMjJ%_+T0ZW5`~>l^$~cI9vUKEMXExrFW#
z9o*#k4+94_wC!Q>a`=94b9nH_pBwt!KHFsOIMgx~c?sMp<BqYaa0x4bH2dA&D#LtJ
zq33<#_MoDBmNvYdKX)!XLM};ZRk>o4<*TpILnHOG5uqcAN5_6BZ&Vs*NFDUBgqNK;
zN;5O4trXl^f}U~S2#c{tttdqgsE{#?>%}m)B1svIejE~j#3hBlMQoNIg9zm|_W_dq
zByYTF@}>ody~@(_uhe|S-}4AoE}wsu=1S(f;K-lT>3-8Z8j@z#8m6S7X4WznS~!1b
z;dG}a=Rd=WNN=}t`?Z|(_}f^qw8$KvRFIhe%=|0GFQ6h5CC9Zkl_eEmHzIp7#WNy9
zy}4>z9;zTc%~RBbI@hpux}Gd?!oNr!V*ar<G$kPfc}7J}bVh_v4sO!*B2EpyYOAp*
zA*R-Ym7)eykAR>A5MB}%0nm)_Fi|Edp7|G(4vlS>*lDWYsFmj|=uxv}-j#={&8sbE
zHYFMD@QUp#-`46uW$(}NGWp=nq(|H{DwBgw^6g9IZH8tL?W`%Hg89tPxn+)VM(g-6
zq^<g~Uz*aS-LucurUL#{iA9!N4G91o2k{yUQj3*1vjiVzI^M!po)F}Jq+dJHEDAQk
zlFaZ5oJ|bntJ6-9stdGrh^vp45-7BJ1a#6L901rM9y{AmMrUsln7#d38|kT9@*QwB
z97qizH3baH8OTA>WABpZS_h1NYR~itV*-%Rx;Wt_)1Tu6G)LGU@+vnEl$MaoNX1c|
z!S1+}#OiFV!q~~`N~P-ueOv;;-M2?45qW7=FYk8N>e>La1I@)e1uKT@^>6vDhQrM&
zk~(-bg>{VL2+oS(PB%}R&^qAiWjkoh6MguA+5TozV$|0m>xK-HHD0%dHXYco-LgE=
zMO9|>zq;rFRNYAmv!}j7#S}w0&T%11Ma+=eR8cI4L#Tk8Aw0sHBb?{sRbjk;3g$4>
z^cur`qLFlmpv=9H(91DI{B00^+YhJ~vABNFmQT<!#R25LPz{ytej^K0$fj>Dl;WRG
zSwO`}`uHmOIxya+c`(JT`UoY839ko*KPM@U>#~p>9|AfK(O@UenCQg6&-qu9m+Qt9
zwsf+W@!l_RxXiCZQ+kY?ySY}JLHtz!R4(QZ$In<j6x`z_OOOW6CBmRxa;3=Lv~>=N
zDz*Pc2#6;oo;c;YnaI>H<8c8f-Sp#YQBW(Tt;6ow`4*fKosb<H@ap=C+zfUNq>{H8
z=nW5ezUebBeh8n_4<kD#bRKYp$~(4ffJB#g+(Qky*(mqU#H8U_@+qS^NY1p_8V-QW
zU*4!V^k?SV2+=v#Zr~K6y{_jgC*r?#gd(_Dq4f2*x39k@{N&td)3^e+XFzZC%Fl`f
zx`bLvg#o^FrA+vytsK&dNBEKAo@Z{$#MVhqqXnoRuPU?f4v}D&1{eE-D34Uii_+(G
zVNP<9PnWHdfRkFD%Zyt?J?^4Hr)oq*fQcw)z?KRN%`-<*SigMOxr)4*MVNgu9AD-}
zxSh;{yEugV6`D4TSZ)$qB`?u$E)4`8g{g88oNhFT4SdN=Zt&lVuYmGeo>pG!t)=G1
zH`H=Bwnhf0D>52Hmy9((k#oACT_>HXLo^#6EDdhZ(Ocbhc_inA4SGmg%2JMOghs2s
zOTfzN5-TU*n)9j*L^1(`_+mLGJJ$omDTzi-o~+(V`2+Z`&g=bw{y!oKF1LusoUIn#
z#EL^JJPXw}R(bqwVHmpntFR3q;dH^}(1@;!pbQW`<!R8`f_fA2quwoKQ~~QcOgJdB
zBltyOSsC0yhtl9=?!%gvG-RGFQ9{e8_R{kZB#@=gItWIR5>^~GkCG5q33zxpaJD9W
zB%?$F1IV)6!a7`QDhSdRi<usYN~*5cc1jf$1fZV=gM{lWJgA{QaIFJy7m*U*p*ciI
z1ss^;A_*@Ila0!|P5}^z?nrLUz+IRw*{Q{}kZ>wH4)zuDfaJx#iB$}Y`BFw{!=*ym
z#loV_Q>dHl`~xSkQbpgL0u^=s>lZPA+v3f*3Y+6FC<{orlbW?@?H?8_)=}YM>CtMQ
z5i{xoReK37O$`UzkFr6pq<q@rXIFSka8&neR~8RA@Ot^s6940lHWfO@Veg3<t2S(3
zMo<)8Z1_i@iO`gB^Z@~M%MIiM0dxx=?KO3HTbD~XU#?wXq++^CPC3frvC}x3sTnsc
zylfR9CqyvpRf=DBiZ0FI#na0i%xtZFv(lkN?o2K$X!eGg1#nazIc0@Yzlm<Ms?k|p
z@=%F~d@mjMc=9uPC6+0$&@yZTNP%RQUlwe7`Q|VQwd}`TB|<E@btP5O+UH%xLQeR3
ze|-lc?Wie!JonY$!B|4YI^~JW(4)o(iq>sc+Y+jExhN8Lm0!-lb~-rGVomM$Y+u1e
zXqRoDD(_8^9_GP;;XcXEu+WSih2}nTsmjzo;4ij3%?l`9QAMbGrgKUTLQb^P5=A4W
z5HEB>GE(BB8CDOX#z_t$N(_H#^A=b#(A=lFLf2~NDAO1uk5G+q)oXt&MeTPu5z+aL
zrF>5N9YCNwZYL&|NqK=b7pMl!aICIO?xwhNxr@3vDTpeOM26dgMKXczU}vx>?T4R!
zvWPhdv6;38oc~O&E-e<b<yuo9asxe8X$v~F)nYRl3p;`lZ9*jS<;SR0Msqb3T6~cz
zw}7~GUB$b^bsL)KSf95vbeh+^-W*$nU6uw-cgr@son#>M!A@V%@ejTAo}`TOJ>yd}
z*0GyD*R_SRa;K);A<T7XN9AG8O=`z^+mq&l-G%5@$8T*Mi^ie{AR|HrPUkVoWHdD&
z&XK|gJ1s?RI%gkwCsZfhyAcp)zJ-R~iQY*Em$EMKQsg*E+d?$+&6wMv#W&$6*SNSM
zmYH6@#wkVs?p6kALuJT$a&ntf`~<U>1;t$<*3nF_21BLO5`+vHrPhT$$5n_Nj~Yy+
z2$qAL)}kaCd=zL)9x(>w5VmY0#^4AU>Gaorzu8vTP(9H|<%1a)56w85Wra-whCKXM
zZ3HbD8orlimkTyqx^oQpyFX|2)w2pA`a)uRSpfr0Y!_3GK&hdd+{WzRUx2OiG`307
znH}kQCEth4@q9~@#qr5_906GWva-W<C0DSc@zmvM9}2fPBd3@CWc|p|11>x{<~BT^
zRIw2!`+6CK-Ism>Cpr`+A7HVeziTO{D==E!^oz`BjT=#HiAApXre!hwOjrKwiK0L~
zX2mno{-G%H58(1rks${|=A-$v6nI^wNlN&+j+EbY_+eG0vYPNZ&Ty#fgrU6bZ_L%0
z^RXB7b`E8+ax9CgvQ<H!t0=-G8!V92ZSr2`3too0+9+Bnnks(4g;QEiR9D`!2111l
z0?YRq8aE|2n(0cV36OVXBuB_ea>ye{9nb@hL&y={gBiT|-k$tD_F&|Rd~On8f6;A4
z8)f!73TPcSa?&{7%K;~ggx+k;7+C5B#g-qI-!G$;CwPKP@*St+6*^o7_p+O1Sg;#%
zbif9(EK5yN<_Cjve`yTuP|>xeV3}D?<%dVIgC!;WN1Y1Yt!=p*=BAZ4&MA4&X<kp!
z-$d^QeWl$|{QcBUo)EbmS8EjTD{@BL8ew1QlRPio>ym;*ZzI%^<9*5W(`eC}1>xXP
z8Bp|BhjO962=Hx5CFPWjbxI4g_QdUIH&(dq5?CFr_wqvo?mEAYien4#mXFGJ_ViNE
zs4-H41QHF@JwbTIYi^CE@JtPpYcbK<#`+?q<IDf@?dlOaLH2JR7IWnRPxW!Yf6A%U
z=eEypZizkGo*W*o2sD?|GO4g#qXrBXrn6CVF95|;NDoG$8Z+1A*8}Gln1P40QBN*#
z@eUaU<fTHm`LiaP7=UB3QoAl#NB{tM?0IzQzexQ$W&LG;)E1D_C<hFJ(xj~S13;Li
z=hi}VNYSMD<ZD!7{{T7v^PE4%!O#=r9qp%!{Q`=h9DRs9Tq+`of-GbAd=w4HBk=;4
zW~VMt_g7B*>nZMNr9@UE^n77raAT`65-2le;isCz`31Hv8v+%J+N-5gMRl{tS30(j
zp7%EZa+EPi0^XwYko!Sa$l^ym$a&i1rGN2OGDx_+45wk){-0@96^3in;NQlXKzZhG
z!1pRZH?|Rgh9o^X@&~o?IUl&XY7kwT;w+qFS84%OosYL1@1XP4`Gw16aQ*LCe~=1w
zAfgn~e_(!<@eM13U_2bf8TZODHy4E21H{;w`tKIfz<Ccx5-T5p_$j7k&<7uH_uKh7
zcn`^NhC_@O6L)=Eiig1&V}syuJRlsBsjU6^N#&L-JaY?W>4rN5N@<`5lR?g!@7K9$
z(e*Jbq9n=BrqxPv!l4e*y~s$C%unOtOJME9v+1fAcEAAi)U^<CHrgwC(QdS<TNuY|
zG8MmnAhnf^YMp3avNVk?YJ+bl_ls-ma9X)nCT?8Y(2NI~C-PgXrYj2&1y3fZS@{b$
zBs}98%+Q?_Lwp~O3YxBJvopPpW2vRl!nO+ZW2F@>ej02i>%bvuu2JdD#iCq8c~V=i
zg`5ZE7}(3G;E+e7(o>rb*`8`4H-c7<C*%Cdo1{A~{Dbwts%7Yp(T*0#D-^kk(aJHC
z$>uQZ|E(aHu-$j9M2w={%wj9QziRzSX%^z@1z*IVuZOI@oqn?ubL>)dzF26Jxl@S_
z!+S8fG}2Ke++7Y>Vth=wo1Kl`GGF3nhf~tYs9N{$BzJg)^|`Id*Yq6MpE@$a9xdfs
z-o=1R-U0IXTA&(JX;L~Kf#E=rmD!Y2W9$5#(9Wh5n5%*6rj(3B3H-Kk{sOlO8L*mO
zGq)cPw6*KH2}1Da;p)<PfBa836ZV%mT+uz((ZcQO2lrvXgfvlvqhsQo=!SN-QmP9i
z*ry=WMtv_-)Fs2UkD#pi_b?^lWsqAy_4DaZiXgbyWj3mS%FWQ-X|Ma%wK{{hQcjzb
zq~QlEHBkWYP?vO$Eg*bZ#u2^fOPU&|Ax}fJ$F`RGa)@m^XAN7I4b|iU^FY&P^wADT
zwipK;Ad(hQ`<2VRtd(T1G1xrS5)IgT6%wpzoHFN?Ou+>DXs3~fTXdr?;8Q4=WIsSl
zqpdC3o&xr@P|V@P)U@`^ZACk#MSlaWnnie{%Qb6;Q|q&X?Mv^l^)_n~8Gy^%r9P|u
zFz+~9%4kvesn4!5a&Ajwj>f`!UX2C|+%IflU0O*@m|bOCk&-mC)a>G$0_g4#z$t&O
z^#~|_nAZ36)zN?K`T0D}h`H~?z&GnK@Bi^c=y!L}GJLssRLTGO{#A4S^X}sY(DV6W
z=i3&Ub?>!+A&ci&b2k3eBl!8+vYox1UDMzFb#YU(?eleU@WlD^dC$K4qvh)B^LhO$
zmf!F1qN*NZw)&K_;O5a;?%TNF$7br6-@&@Vx5V&OEUZbwS;av0_RqHGNoU-4H~kX_
zaTw3DYtFCdtFOC@r?15r2EOr2<Qf!x4~MPsi(A6`r2MOW>cDBAKeKb)o>#{`@87vC
z%B~<DHsezEGHM7f?-rYv5nnB#GHAYoIV<^cUqefB#xnmbfPFt*54Zn(?%4KSWvIj?
z^X_AJuk7}N`sq6MG9d6Y4DFQuzFgz<^3Z!W{zdTfMbYQoL%gO(pMEyiYwo&1%ZTye
za@l(w-=KlX@43qN$jegj^gNaqrhD7Z^urL6{^BIo{CsgS%m<W`>8hdW^eoJV^73QL
zjQ0&UoN|3MmSoG^8fs2Eu3-O2uODNt^NP?9`Vm&IKf-zgaWS#|^6fPM>yEgvjOB_|
zq-Rf5g4(Nd8fxt(?3b~xYQ&0$z}4TsAjgS}#<}yKBjZ>-`=&x3Z=&!Dmk3*nOvrRX
zFG{nZTV_E7{fTmOvGxtbThEDdz$4pcq8hy2;3a}DD3Jztqz!WqFYdiEyQNO;<bK-R
zP{RVNXe$@C9C+LOtMa${Tc+Ch>^q|p0}3WVKD67t30Y^;nl7EUI!{e%jDtTt(0sTB
zzaTJL+Z7JPwtThQY7sRf{U0Bvqh@YQfO__9Q<h_%Mwt#3K0NWaE2|vSzS>f@+$jV%
zmV4d<yZ!bq#gYqleTVF9m~(B`oVzC>XeJXcy1Pr*!d>`Ri-evzaF6G0etwS?!VT!^
zJ)ZL#*32g~+?R&3U}$}8cmH~{WG4K3W;Cmba)x7DrkT$oimN38*glyTm#kRb!2dL)
z$s3NH;OH>`X6uvnq2au+rh&XXOq4U3YFYjC8RhM<8sg3Gzcopu8(+8a<-hF=U=>7r
zyxZ>WHh+$1zK(hXo(>gHIok|$5Y{>yeb)Fht-oTMuv#zm^I%(F>0MA{4ZM3CQe7}@
zOYOG(tH?6$UF^Xv+hz&ZN57}%bwZ4TL8?@s+K;KLYPWZpoUlQlL}9@tEM&5#;-s{l
zmVrv}ae4T@xdh_#YxsBU2`c;MX``dBoZJ!RcOnfkABU%)6I;2r#9YBq>T$|bO~PSc
zRsLo3Q)sn0NqfTibuWl+@b|cfpnn=tb{Put!}^-FVRCtX9iJO}Z99K~NPpVQeQu`q
zcz6k(E)RbJ>v5Id!kF5bIJ-ER8ruGIWp88!!%oCR^v^#L5fM8#Hyh`F`K<rp^YQ&t
z#VGFKBB|_R=weFrZ^l17L#FQn5u>Ou5i=2^vEerr5co&<-;`0p-p=KJNt@9#(K8Wo
ze0Qt#AE9r#{|tiVf0Pk1s(3n>5-}<onwt`l6EXiwxuT(y>33hu|82`CXKG?;C}QtH
zr2Wle`e)!o%q&byM7sYH7yVZJE$>Xk_CF0Io$Os5{?}mst>j<af0}&%7?r<OI~m$J
zJN%=}*z><^X(AUVSJVHNM8BoPOx-MvO_d}?{$c)Su1coP_O4FGrp`qFteX<d|2H+x
z@A5zE`_D?rn%bGWSP*gj&#)vcZCp&9h!`bozE@Vv)Y#tSUz+|S$V|k^#?A3hU;o)M
zkE{y~Zx1x_=9*LGMgC2G{(1g%XtH!N)C6Man&4m{;3Q<RoG2n-)QwtUBe5h{s9PjW
zJsBeZQ1h8<9CD(-dggj0g0s_G6j3#I=&f;dOmsyT(t15KPKso2FA#=~C+DxO?T_wt
zc2(V)YMz?cY-Ld@VlmPvsJPyua@5kF&+kius76)9VmN}9kH3LD=>$^a$|OX}sM0@=
z7qI!w6o?1IZ0nz9DG!r<F7+~FAJn0l85R6YjOupreL~}okLqfUOwO5_X^U6<2-m3-
zOQ$m4Op2MY);Vi+-v=9|QK7kKW8>T&aS}`Avv{+U$5?AWFq%Q<bA3#_^bcw@Y@e8k
zeOTh9BFYTNJ7LOIrEEq<{fKT67y2*(zfAD#Ezad9LjQ#RnV_N_g`v=tCjZ4Y9o%|I
zTOi`-`!$*9#FJl?rk8{Pka2`R16n0v2BdlJ%I?okl#%Hx)uAmriEC+v&?PEB8ScGs
zCn-|x;{q8{guEDq1glCGoI@r^xi%PjH1RTiA;}{=Fj(+y{Sq@_Gux~k#S)<C$phWI
zg5XSq@g~>gqfE2iMF>PdWt@@RDjvwFe5_3uwF+a)UKc(85EwKfMCP!C994?=6Zbe_
zqs`Kw-pu$i&|n_Y>$$GQSZ7p3n<EQF-k>o=!@g%c5Xotif~}NB$Du~63Vrde0xCEw
z%iU*FGEiA~7pm@kM<Aj#xzyr?xlyp*cp|ZyK3tOz$DrRmYvJcMi8efGokGb;f^=q=
zkuC0{m#~m;Y$XrE;dOX_oVFpXCJ>mG;*k2zAjc-o7G6V%m&x~8HLUObw7D$NlQukk
zfqb@M=Xf#R6KM|`(0-W?*=)ldH;4R^G~!g$lci6|V=0*+`on2Ow1288XYoR{hZp$0
zyY+G80bV<ogMXRD5^|J<e^rxUJV~h`+%#by!Hv3Vt=^UPv)S$=pyKZ#qF{KY%0Z!6
z7gtbQj+ybPaKnI62^ISIknAg6wq$O}^jdwl%r9eDO=QP;)%<`+Q6>7nOLV%VgBSH1
zgSHy-K`V@@`6n6kbFQ}j`IQv2FHX-@GJ;m^aHS<<LU?wEOLFTdY-n|)Bu1MUmGt%<
zc2RH7j+MIAlSpf!$<_x24zmJii9d_eVzgh>vVSfzz`|3y=u&JDR~m>}U%<^vaX9_T
zU;9{-GVbKj%PgSh#K1m-kCljn%I0-Vy|k0`O&FEklD|9EGyhGylnqd_h(t30&bgFQ
z4$_Lu`76uL)5g;Vs>YZg>Rcq7GU{#3|By4aB~eYgoNc)&D#At<LNqACM;4Y8XY9`-
zg=+)n3hx^Bn~x<UCgo2*6-Q)j;xNq~9%2QemGMK}6o`6&cao}zOws6?arN+q_>#}C
z&a#d>wq`lQd@A?&FBbLmH*nX&?pe)~3K#Vg)v2!Pu1l*k{<DHbD}E&@n6@al5^f8l
z59&!Z%jQPE{ZR8IL1q$0Ug>*&2}(t_diR`aJf)0b2@ZRIN~!&g`ypo@MA!29fc&>s
za$1%Kf9l65R+=BRWD%zrQwwyeg^%AE&ch0{5W-l5l(9?^Zh09tE2I%tJ+-qhJHtZN
zGu;fu(P+2xHMk2_LOCYQ?yV=Ro=^cF!_8IeN9=zZH4f)_tlaA^*EAmU5^9ny8cybI
znptGLQ|M>)4AxgEOtYIM*2VP=d(3!~@wGJWtb4iC+4(ViHcJ1Tp3KBUF3NlL9*a8X
zV_xOot2jT%8dGfyLzWNR$NdocGYe7<L?Gsip4a`S9Q>8aID<KrfsJDxeoRlRSOxbA
z8#7vs6x1~jFiJB-IF^eZHGGnD_qUeIC#Rb@hfiVNl84r+ZRM7u3SG3wP^mFZc>D)s
zm0Vd6BT^z73*CM~akL3@A@N`?l6x9_Y9?c0upOJ3sgm~ZmmYEi6cJaha8Of=hf`go
zND?a&=5lIsni3qP(#mz!CM278>E;BJN7wPD_7v-I8o476bM2!r=m0|-fjTL(5!y4D
zIv0)03e{Mej9=qhN6eYAoMyY#P{hNyQ!5tDKUEeUsUk4u?9g_{!(h$dY#gHOAO}#w
z+*WUI^F@6T7^6-P!#)TqFDFxQ)Ea9{P>zr%*22<~W8cJ)8BcI;g8;qa2L}w+O%kzQ
z*4d$_*Qcc9kZsfELF#tvTOJ#+oLU5Izdq)D>|Y%2sA$)3CDw@|llSp36XxPCD}4{s
zqiYtI5PUw$TekDBW(Ve~QzF(|dNj!=zlh(hMvKmB*Gmi`=4z2FuM@af_>)9@ROnrQ
z?{uqE3GNq3t`XiY@TkA-`6LV+5e<;XddCTZ6b;9}aWHk+=nc4#f?Vd`f8NaR4cuG}
z>&G5_NdH{ZKfO959PXgPj)7~6;)s?loG-HMwsf@Gg-gm{qz3uy@{w}x4b^vn1&AfV
zXs_t({TAdpSQtp$`l+*lRBGXMSE^E;>{eaIx1T`q>*t+HEWsO(YkpU`MB%Z}&Fqcb
z+mmgBXU3{mL~hRjrp<j^v~4%hpKN$$f%!-9N%z-4ZEfRp9AZ*xC6QC`S&`j-aDez3
z_*&Q$I_;peqX=E;-80k=+UoFWF?xIvV@o`IC2|6k^+C5Aq^bf$<2CHr8^a{~<a2SY
z_ab*H2n6oU)BMNo#mlu;Ip)DV?2RpIUZblh$;kS8JF)j$(}fz(Tdl)@f?#pzT`(bT
z@vK6|0%M$;?BgcI(Q<)C&eq%8c2~yrwu3f-nrT5%E$!)vpIy`WqDm5*N4d*}DFjqG
zR56iP%=p<Fow()sCR%6YTp?Zx<hfz5*z%*rvC^^*WeEk*(z3Ex-`?&K6OsT+?7NiL
zu{FZ_m3)J$CLVg>dDK0$TcNChVy;enh~icAg8Um6E5clD67+37)}F4zwrJhz8l<Tt
zDb4Rpnng-lSQ)3w@9o>G@X-ZPTSKer7nKi-Z#)k`(0T6C^K<v|Kd`sp^h=K$gBu6$
zg}jsiR^@6HsXQ|9vC%ULWY+Zv@=U$pc1*+&M#Kp3bb4}=Qdha3QTHJyQFF^hVe>Vm
zEs{_f!oIfV3%J=*sAbc%l-t-oCOgnmC$p#u48L*OynQrR2XJ2rw>|F!{}6f??C%ef
zR}!w`uD!hv|D;--e!Y^B86Ss*mveIU%C{L0*x%=Lc7l;WBt&;9wb7}+SPbU)`VqvD
z7PDe%n1y)}N0)saUA;)7dG7e!w6&mcDa=;42^1($C;XKnEaAf~kbW;@q{1Btizcz@
z*uE~?P-3@Tw|!NKiaGmP9Uk?rbEmvKozsO-nemf>Aso?yGQ()z0mpcQI$q=MOfh5N
zFN->z=Ai-e6j_urM{gfF(5<!VVbUl<QRGQ8alzLM<<r2W125dBTr{W+ef1q6NxFhm
z3$SMyqo<^>HNdRV9*gMmE14kKOvd?H$r7B=-6oEMS0L4grA#Mzk4Rz{#{%FjwU>P$
z4^UW2d`faol0D+bB8IbyLdrrEMb4ZcR6V>tnNqEd6r@b0J(vQl(AcXY^x7w(I*7cu
zKMS?N=+{=h%e+wdOn*_hQ)dOVOT^ETB~$#MeYx+L;~3NWOQhzrobbUQxU57mX^B1O
zBkfgF?44PyC{KrdP?T^VC%H93l5@xoSqj60Thb&wD3FfaSmt;(;zjl=x;0^*soS)j
zt)lo<msbeCzO*>C>u_CTVjvNsXh67Lx&Z30;Ga$6fqi0uNX(m)_wR#MRlEBw*4Cz1
z+c>rpR1#hlaRd=qCXQ4&I0i^S#z4Tj(9SSXs;3L#`fg06<DE>MTElt$;lU{K>j^lo
z`Kggq*G`}n*KQgk@`bPR>+vF#*)AlaQox?SCWvVxP~><MV;WiSi%3sCrrx3*8-oSJ
zb3;uRYJEB70&QHZN1K-?fHkF5_QRcz<XdES`VM6jx3jvmgDq$4!s%LwwkE~S<wWi0
zqMr*ImDuapkkB8o4PCp=5h0f-Ym(L9+=?XM3ZXoV-|<092s<Mxvg~rhdbX(+nvq(7
zLt<JDNnt_u4n|Z-5^UT>MXenB2L~ep{*p<+kd|hA3?vuOUw62+jMT*^?)HU!TDylo
z4J|^Kmh5-2K1?cyxn1(sI<ChY4R^lmPt1eo{y1_*lI80@EVK{oGu~{V8T;AfxSVyu
z`W<&`gAnSy?l8TJBNzQU@Y+aet_^JQpTR%E-hvRJWKI<mm{sr+D;+8EwPLbz1sOfr
z&`zC`d5qI$xB2TjBHEqH&r90KKXKZQHZ9(n_xJQ?t$MKg<Z#At#{b+nj?JH23h>%_
z{_2N{GOVMEc{7h+y;ZJb-7|Yhjhjm&uao(k^6Z|t>4;Im7%q`9pLpM%`PqPlmOjIB
za&d_45iy$c+>k2s)6wm69{xqW+<iur`R|_`e(%GXCf^b}9G+66-d@(thU(AHBi_>C
zs2;I*E$-7clE22vQhrqA01Aon#Nfh%T0yT;Y_}9wjWd0G7dOQZX6PS&Qh;Bu1uvxb
zsiXoRg)Kdm%==ZOu8n#X-{E?P&rCWkm&l|-j-Tv!`N_KAyUAO9U2UQ;6Y2|!E6~?l
zYI<cCkuxPbotHLS4sR5wFqZ|<>Hp&3i|<L;gm#DNd)<u0W9swJO;*aCP<12g3u;hx
ze~z2~9UlQl=yC;X3HUA2ttS2qpujdUpjshl10)YX>ki~JL02lfn>4$ZxZJ)ez1yMN
zCwnxxP!5@{$<I8lafr6qvd`5AydzKqHYZ98QyNDJ8dZ<tE6rSpZRYsHB&b!bwmDB`
z=<*Itky}fj<uXP#MJ-<-aoTU8aaM-@)@?WWcqNxv22j$ZGS+P9w0An`<eAOlUiEza
zDaa5COFTHL(c{<mOOVfMG8v_tD1zVhU-=s2f=-n9%L`m{ETm&XY*}o4EXI@inNXc5
z55NS$2TczU2vAStX>4BmN{wUk^~czK4%FWJ!Iks2_pBg@_S7mwdxFspul%gW6LEt7
ziV!pY^;f1hp)f=ol~AG>&X`MN?JKH_PjKnCw*B5P0Xp|b`7k<l_SX!itE4We9o>V}
zW`KL#*U!&kQD-UozJ{nRJH%BHcf(4s4s!zqjSAxN5#<%<UrWRjE<@eA`#juHtf`4S
zD+5sY67_Ydad$c-oE8MDvDW)a-@dEb9EPN;evd$vrnwDXb5WBf55L1Fi&n2u2#4Jb
zr$SH@Abs6Q%8M~aWu36P{cX6$E=?JnkWUQ}+X6e7bb4Zv5@}cnEpO&5P4e0Fy@0&s
zZ@iQuEOBC%3zKuiPZ8#e_whUl(%6D+3XkGycy94EVLazVz`|_G!A=B2tQYs5l1(T`
z-|-g1<9Lh-m14d5@u>ImX$3K*mv53LDLsn-5>M4+dkoEkZnMUXKlBv(_vzm8%zDFI
zuw~3TR*{spD1fO*4qDxcKcaO+j)<?^GVE&@CJn`15MKh(sS)?qC~aaKra$IDM}9za
zM|#HCkSO?`uuzEtE@nNHYT%5qpZTlv=!B}F(;>J`V3rOOeTza}LSU3)XvLqCy>G6r
z$LY^e_uH}rXniG5cl8qF0W0iD>;$swpad!=Q$htrGQGc30!5=LMGNmhuh7U`FK!hk
z{ma2BM$4>>_41mVTvY_TssgPpYeMr1Gr$uCU&{Lw+TE}PXap5ES&p}~D-megG2i~|
z8!y@!ay}xqbF!G(YfT0{<7%nkr?GL@&grCYm>0iD<yMmg`p*Tg$w6ZdF>ZWxlSjma
z!{_n~-X2~&O(JGUw!$pH4hr1Z>WcwPE5apvkvIh{a4u+C7r&k;A?O>$+Qq&-IBp{v
zBYncJY|~PWvug|Y876#Ji<c;{BoLetSBG&%;XJ|8N4xf!&SXn&5T)VuQWY8iPFiE+
z_IoXlTG~wN1`NZUr%QTIMmaGr#$<4ojk78^vnkjGWRe$S;g+|oWFVRV(E9J3EZ$&^
zJ`*FEsMEoyXH)P{$%Sz>Tfwc&nI#{&-oYJMBc$1*CSsCs1|zV|Y-tLSe>f|XF+#L{
zBF*fF^nmZa(Y0y<Z@2Ae19O7Ct0Q$g_UY5^cp-J`c_Myk^)|sgSAgJT?l8(-7yC25
z_AUZnxA{-k?~ENVzXQN^{zRk>_ZBO#J{MCwvw;dAU)T9ZX<nN%`ltY7g83W=eCYrk
z#rFP$dIl=}Sqn794tIEjAv9pX^;XK|r`DVMcPAEP3-db1Ul6LS#-G&{`u&%GJD3M2
ztUN4N+r(eW4+j#Q7+5ZfohOhjjO!HtZD<eWUVCsnbO*6sLs*1lh!<kuCdk-pEnrAQ
zwA&!bogEUl9Zq4tJf;O0NRe|+;T6W6XqYnO>vn%D;2w<H8Z15MzDn<)_eG<Xj^TkP
z2*X%NJ>dd<%fL+#J&anJUU@_n=#`s<sH>5{RGn)h=3qxaD@Zf!O7r4q3-roqFny-+
zbBfW5j^*tnv!Z1`EDj%|fpSP6Cv+K;0jXbO9SFy7_ZxW2+AZ+241<ddQlBb+_Ja_g
zNo0+N@MJ;E{euui0;6g0T}|Lhb=SR0@ZYBpwDFV4PeQ9O*{Pm}AqeAj#-7Yc1x0|M
z+KE7YXpQ#4zcS!-bq00*;vg6>P)(mseITDQz_1v-tV2wK)5AxQyOzLrU=yx=c$5=M
zJJi4p83tyke5+ur83yhCmLQ*Uy{OXHt^U+YKmw+4d=v(^ARcJA<RApdigX4E{$b#<
z=b++pOnuNHAOt8(dP2h8e_%6+^n)M^jh}-wndEylHayRPM(+BstZtbvc7Yjx5nv2S
z!eSK<e1J%NPVAF{zfS}sgM{vlH~<fXX835J!F`ABQA7>JV$$gKMQ17lxkP7DJRO7N
z=<_Fan0A1IK4#px?BIL1W87Grp1ish>gk5K!nAS~)dzir8bP1wNKJjR3)JJ6+Zu=E
zcXrvD55~jyA`@x`*4%W>A<yeTNXO=xW+M^}v(r`GnhdU{aTyJq$`0&wW_AHQUCRqg
zJqc-9#g%S?mJ1(aEqF?Dg1Jf|$I;~l;U>gQlOcjd64yba#DxSKg>&}CqTIuVTL-QH
zBLzic0bfMr;{z(P{Vm?9cp!X0IzbA+JRAZg{X;snKznt7E{z<ZnX+a#kah-Frz~c`
zEhx%B@VF+4g>C|M;NT#!wfqrlF~JIYM!$25%MpQC(9`QZ(p|j&+$H{62YVl<{Okcv
zip}8qzqs~4AnSi|Z8j#B|02!Y{}+yB{s%(-7bea4|A)u^Z}?R=Vcaf=2}%6vGg7l8
zDm)BSnmkyg7#G90tdS7tF^&Y?7`uMwigzzUsT?+K;CZVuK5T!3kJC<v*b}kA(lNx)
zg=2?BKS=oahJ`2jz(BHLtNZV|Y_>Xd`ns*AqtymeWkukA5JD=uO|5smb1WhZP(q6V
z^RG*gjv8m$s>jn0MEPSiDOKH|p@6@7JYQ>aP||EyxH3n3?H8kurOz9DA_P6G*rO8|
znA_NJ*&TTmbB&=^SXLoZpS<IUMkkPWo8YPkDMgk5aaEou*^pN%-+e#gk3ep8c}>zR
zRzgBjWnuy7-0&z-6PktT;#^jl!+2Ji-Gmn=u@VvA+0-93;x*jL_u>mr1y||c{4R;k
zQ1cXQw&^@_N#~dppUD@k&WtXt!_t0Cj}Gc?z}Abe<RK1773C+EBV%X$?C!_*O@q0*
zj~{RrSqb9*-Lrq~#D6x8m6iR!d&c|^@c&;7{oly_Keh!iQ)go*O9vNwr+<L>f0-NP
z4Q;<|2XeAns+!`oVy0GxYOc!PkpBPFOBmW(+ISLC{kw|jpE~M)SK1hwe`EJ7|05~#
zZ|ed*GZPCF5j`6R3lTFXH|w{RftBSyRt9MoLmNwDVLNjhQzE8+wG(zW{>Mzg&BFDs
z;y>g2r%ccC|LQWko(5qk4Bzip^u{=2GW!7qz0;}DXrl4+x^4`5AuOd!jKALZv}1#9
zLP+RKX?xCj+nWcW&<dw!c~{u70?EKIL3;JY_Xo@4|J1na8WbVySV%?$p-&VDq3mZP
z4!8R90iV2qSx}~edS%)oz?lCsV_oZ~m2q7H9?iNfWCSq7bhA*9xMOZ=Knq)!?CjIl
zmvw79A<X<~=e}w|X_TNS4&O@i^>?i_`|kld!q>wikeX&hvf{1N?mf%5^J>^DQ{<(?
zw^qc9Fpuc|j{Rh|9fPw3!Kd&9t%q0-(I+T)0(=5QYTj#0B!|&i(=Xh<jfrwacRtuT
z<%vMp%LZeu2zvEclIU}?XV=VEGti^)%vjejF%jtmA&x8WmltOMa!^ZWmX)2glg5=N
z(dtvsKX04*nqc1e`a*Ikc`kD<5|zkPE{{1s=})>PfgPNi8hF1cLy1EOYc#i|UO%o_
zj5rg?h;J^2vZ$0TSk!dJQykKCvAWZ^$PnX>#x<5O(9obF4K&TULdJ)h)?~b)hHj|D
zP)l<%%8qtU=h0BpO75;j!#6PIuwRB9zNg8gH=cI}yW0gW_-cO($`u_FFHM7@Q_kZC
cyRR3hZSX}TfyVieU7g8uH99)FdAc3_0d__~>Hq)$

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..8c3dd640942f6580b83c934beb0b16b39ceba9a8
GIT binary patch
literal 67362
zcmV)&K#ad7P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q$ck^V`EflIM#e1|vq9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R`X9q@Jj
z{RL>Ve~K~*f0&)mPf;e}58d87`a_gS_(L~q`x%+d@4MJDC|JpU68^P2VBFr{qGj)`
zI)BIhf6ETA>;4dBwEr->X`iA@!XLW5|Nn<5lkkUb?WQQB8wh{sW=7G%5`geGcYvAy
zXn%bOef=BmfX6>28SU@qc3q!xjQ01P=DAC8wEl3<^k44z{x3Ki+k`yf*qJ3x|7xj!
z@6PKtLjP}4dY(_|ef|ZqyXk=>*mnojdqXT<RW}jdH~hc$92oC$`gq?LU*mm^`tKBx
zzr~XGejnQ~(foF9@1v~08CIP{__mw9&&~Cpt6x#R@A#I3wcodnqI}=cM=IadQIx;2
z4CZewaK2B2=lgZ|8>?Wm{UT;X`F@Jm^NXMr<@=7${8)IlzwOlCD$D267v=ko?{oBX
z?Thj^R-(Pni2nR>NBq5;vAuP`PjM^C_miBTPsE>JMftwt9s1+ekA&~LJ#S_8{8$Z9
zzU|n}Kh~b@zp)bC&L8vc<MHoS;%}*lz1uIsR+R6j_kQes3R_XW@A!UPey)5`zVG;c
z5`C_GQNHi^+@C8i!rxho=l!izR=!<}zjt-M-<Y4mR+Mk2xZbq>aR?XX`;PuZhyCg$
z<@=6v2J^O#qI}=+?t7<b{f%|-_X%u&-V=XIX?&hv1g$9FPHh=>J_JpK@4NN>%c>XU
z`;PAppQ~P!?>oNV`k$*_l)s}ojrVOh|F|dqp6>KkQ-2Y(qWnR$KlRX09rN||>kt1+
zrX17#r#12Q&dGVU`@Pe0_P<W~|6B9jj`8;6yxYAl)VB&)rpABw|B5emj{9!!ug<rw
zaIVk4x7C}se=Vr*&C`}9k}t4mO|WEH{^D(L(Uw;f$3tdO-eP?ODIa?vy(y`3fb#y=
zoAS{zyefmT-Xw3zTV{`6NNs?yo*LH~KmI|e;jU@4`9#;(*RhjapITbiqND|{D0oo^
z;r*W$p(YvQTBMrfTX^1-E57hascDbZ-u^w;w>UwMhZij(MHw4kdKg>s1P5jD?oD~K
z<=82{F{Z~0&tpJIX(I^5svyv^6`Zo*RR2LHn8VJaPbZ}npDg&)Ha@-Ca|B6zdbg~2
z6fN?{U`smjU=2!4Cic@o(wfctfFM_jLayWo+PKAoe8w%x82X`D)^UpqmMb<c$+zVa
zyeXy;#S)CUKFS{oj=xE+5e3KJ6w`=;onweMmh2lNc?437$i*KEzAXxQbmop5T|CMi
zuqfiunQR+PJUYRnCLW#OQR9X>!J=G+1Ed&`NpeoG$i%c|ka!<xV%Z4>oj>@q@1Y+-
zFpW6a<J_2wvgFTeTjn1xifO#-UvD-4-g*Uh-V}7ZQYaP$-L40Q#tTw<<>|c${mHHO
zCaseLuZ1K8Z+vng@Hh*5<=_toCw#K?o}<%RxCp_9HwD{yQR2fio-Inu+PNl60eOG#
zSfs|$hDgBVk(8WtSFanB?(B49&Nz!f3YIsnWEu<?0Soyi<P>QWT$G%m#Zn$Yh$a^D
zx-rR<OLE;<TCD!N9aB8FF1Aj*)}O6U%&2SiuRB^?!YilKc_1&s`bfWP31fK|g-e(Y
zf!43;6qD(+xh+a;?v8aof)s1iYvEIgSrjh(m0P(_w$=jmQ9X`m^3NwmKiG<&a|ud*
zYEdXCGk0D01I-+G-@4?$`_?7LtquRCEXMcT??+N%OZB$(O2+Hrz4EGA6be_~^^3BE
z>j+A)S{Ls%Fy3?P)M2Ktzv-~#r~Dm@6ntzC#dahs+g-h)MTvD7|8-!$Dc9O|?NX2A
z>!MVzU|+koUctULw_bThwYhc6(ao(}4o}+8<<Vjf`X*vt2S_mmSC5Y2`PM6kr@Q#-
zU|wFv2S~xazIDst^{rbhW^4Kwl(Uw5{zy_fRBG2lBWkvF%Mt0&zo3Y;JoNEHA#m;7
zy5)$@ty?lo8W}XaW{<9z3pczy>W0hPo~>Jq$VxD9FWX&H!<}n4#R*rgU0bhUk(F@Z
z?tD`kjyPPDR>FaM(Wb;3m!M643U{7KQ@hrMb_At51vjiNg!A3fWiW9snNEg@TgY4&
z`%D$*O+qWV(6=th1gY9fuZ_|7Y=s+aLO$m$&lvwaZv~US_9o;PrL)Z&UrkNuNK$^*
zwr=@Zcv#<rXyE9b7bbi1kWan&&9U=gkF<#`0<MLL1N(e<o8XDrPU!?QHML`r@H6qB
z*<t2~PpNnl=kF<@m^g6HOB;FOd_5%<GtY%Zscs=%C#7PAJS^^>DHTVO7JE-g1vL3Z
zfmFOHIZ6ITPOzk6-~v6R6V4Q(MIrm))H%CW4F}`dwFb+0xY~v%)^tpg3jNI2>>_Xl
zJX&OC2Qzhc%+6IbaKFb#q%F>lZ|L@b<9JcXlO8R+XJ(#f@4wMb$s@}YzOpDI+GI$|
zGr!rAW8sV?DO%)&;S<st;q|fSl3ZDQA|&ttp@+v<PlK6y(Xz;s9VeW~B_t>O%v1Br
zc`rvZ=a&YTay>6f8$qCu<i2@RR%<+|=h>r&!-!q92$<u@^L0@$$MJwkopT&eKNkr<
z9RC@7T(7C<(71Nv2AlM%7&pe=bY_hkjN%{U$aS8KJf9bZW4*Azrm<f6Y_mt2=D09?
zXqtGUtv1J-0T*^l3&}@YP-s^ed8#iGc>AWTal9$ndjCt3GV<<U6pn1<3*K&tO1|jc
z6de}B(M?y#$nCf&{H&*Fy-8@UCBFyu;&A-v;9eZ?s^5bGIC8h!9iKZu3g+K@P>g)P
zzX{Q5_zj&C1DosCIWZasrl)_t84Wg>B;@GyycpP1H=maSTj~xS-~cIv1&{Nj#1EG!
z7=E}!;lvN8BpgY~HKZt<SizIuKIL9}g*7@uC>TVtC?OAa>CxfX9hYtv&s)bXDWo2k
zrM;g3*tx#$oYm$9>yUjp`W-J*!@FTo@+z`R#|DC#EH(cFq+r!0dGXX|-;`{<|D`90
zL(VS=i{qyj3DSb6tX(n``NY`tAoYRh65TaEa&lJoJs%jG4iXP*)FO;*#=mnd6u{CX
z2cFunK^IL*j!mW{cZ^N9k0M`8uUter*rn&oo04Obk;yywCSAq*yQOo*Tf8Y2WuQHx
z)!57xJ<$sBgsQeEkbCH6N0LH3rxaSx(b$wii#PS6P)bjP=-g7XJT=ipqU_+Rm{MnY
zUXxZ<$DUWgtXFPd|6PLAZv+R0AoUBafmRM(7Yp9OHoI=ZJ~4LP6dhtSbyM`*(Kd9H
zcFZ`<Z}~%*^3aCDlhTH)s_g+~Zj>0&h!EH#2!=n&HEWpRm}tcczK?1C*I2`$+qGS3
z+cTWxNqX~eIHjb;gJBT{{~%i6d4|s{0+p+lZ+06ru{vIsivnS7sRAqtnAB1QSQLYu
zxD9Ypyln%V)b_!H(}onc=3rZ+-qEndFc@4f@AEeAo7TZIy#n$0Tom%D$0KJ^Adl_6
zmC6*@aF-0JcCCR6dI{hqYH1zJ85*L@r13S}9j<NGu!G)|fp)C9KYYkFXj=Yg4fEM%
zWk77HSNW~+ozcSB?7>;*dOuihYjcUH;aYHsD4wZ{GSCj*`z4*|P0HcR<Y<sW*DYY!
zi9UHGSO}q~ezGLpa0j@I6b79qt&%puH);_E-Nt3Lu$dydND$ul3pGDHxU4q7Ib9Wa
zw=T*+JC@q(t!j>M>7p>4;jTS^P+C)n+M>jgbefwCQGgx~Sc6EpR1a(TjC4?I_>3+O
zGi>OxcA8;I*#(Na>*6q+wJuczuh&K4fraPmo3vWz6U!rEKOd})g#DysNJl+ysE>Z4
z8FEp^(Gzmf<=i;KqPYnCRcO9FubVR^$hyQFZ`4KMZ^Y5K2sj_k8Ld1o&yjXj>$+CX
zl!ZmXLY=tBJEZ(f1J-IoYEE3xed>Zf^Q^P7ubxm)yPimAj~0aS#De3JNeV_c(aezz
zP1i6oy|Uvqy4svAE}CAx7d$_$OT_aDx(GScju+^n475W;I*<LM;|aP*Iod_Z_48<@
z#@MMTEkc|pGVU%)zE*q3aQg!dQTE<N$)8D9uXZw@_TT<YOfl7&q~r{_Q5Ge6&yDh?
zM62ceaQSo^gL(!GuCW=ov`9HWTpa!JoFeayMaU_dzJhZgY|1${+&10xsU9;t^&O~f
z4B77w>;j$k#$%CE&QE>Guw<t=1!YX8={F@><jILMzdd6AnTtw8^&-Ta8($0kP93W;
zTV)aAut?S804ZkOsN(heR-p7iJ2=&D2-Kp))^50fjyDOy(DElj5E}RCY6qJdZ=;S^
zsL3L}DESs>e3dLx%iqZv-b0-@!vVfcO)>SQMbQ*-E3~O8;+@+jrs(R#DSEUFqwP2k
z+oUAi9qb?aatHsp<vaZP)`mXJQ=$!gxv3MsY`JJdABU3KhQ1B8qB$QcJwyB!h2Mq_
z-dx{4)hj-I;lbHxjX4&Hof`ipSDN;jeo;C)=N;}hYrH)>eQAq?)xIbl^b{;gc7ilt
zln@;zcz9a+5)P2E6Zn7_5NlLAJN!aH!OuWRXc<4TWECzRYfYnZ2$qf<_-BH0@^9FS
zLVq!XAm<HDwCNPe*JTj!8!&7%nihJxHI5*0Fpa%97E>>d#q=p0=ox^r2)H^roCwxV
zEfh4(c4|C%nY5D&H6L|?gKm-73u`qW_JYXb!DtQ7(M4dN6q{p_vQzwb7}re4-OO_!
zC^@#7ZyBS3q)%MfCZ|k?P25bUA`IY*!odxF3xi9EILv6UUnKO37NkLrosJllpkQ>6
z2D@oh>99MSQJ+~9b{lB36PA`{WJB)U5u_0WZ2#HR30shcVY|^<e}8GLhV5sU28&0B
z>G+L&jcDU1(-Ur%YEvJNdcc>xNO3mUMJXJ(I*dNdK5lixSZR5+OM*#TtLe-hsXH1U
z8H*4{o+0035#pG{(_!&xOm@N?Xdy+?>1wkNxINMo6%<T?sso*7Z%Q;E7>IdU6r4GD
zO}{DGdjD&X^@G=h=?b8w(*|e4^da2|2!1i+>t|6`rz1!~Fm>WoOr0R-FjCs!M6mx&
zj^9N}c^q1v6T%f;{DEN6{nz6myV_Wov^E||${G5tPC3IgH_Bny@k|X$e%0}YT!G>T
z2q`7bee4&6gqKrytTzJ^x^ul9kFrI{6{pv_J6Bxy7ao+0f)(}n)%cfl{TSEM9h!l%
zE4z2Bg|ubb_pFlxo$Dw4Sy^LUOyIKXPIR2}rd!dCM^zUa3@fIK(qVcw*fP6wGk1z{
z=XRD`t#@u`-KL$}xku{;cXhWSiX|w?iVl-<ka92`{ttt<u6I24t&tTS`n^fx?{Gyf
z5_o}Ek|8^CwL`jTI_jN=^iCNVAJ44LQ<|RS-g!vtUhf^;;v>BG25vR&9K@Ih3A4Zh
z&zNJ~^Q~cWQg>PxK{=8H9>yP>kWNOrEK0I(qeKg9&>l)Cotul4>@3Qy3`ML;gRSR-
zvMg?klIsLz-Q-d4X<YnhC!?giw5i-k#EW(s6pbc}MKOGvl#z^*#zW&FC`Xc#QR%Vm
z&BZFV$tWy;<1XAOVf8VSD%F}8QIwX0frLO2`=q1;(xiYvvDqm0a8kJmX-nG(%oz<v
z(YB*B(#U-|_a3y=6yeqyQCoo7rN(hy;w6TEPO+{i92+(NbBKFj41E6^KTp>Hivs55
z_&PPTB9NC@>a%N3q_h&el#jDf@Nibax4%gqjVT`#310H^v=Tfp{j3d_Qh(Nd!^Swz
zt<`8u(dJqd2^C4(ehc0$3OSYAcu~M95>jD1@+eqM9$tBRG#XDf%GBAFM^1|@I~+;}
z2%m>pd&Yj4fx@#a#A*?El=bvoHkeCvZZ^2=akzrQ>%cK3IC@Drg2d|}Kh^3sz!X~D
z2A)4mWrvP~_COSLtF-6T>CZ(t#Xv5?DF%Y)cj`AsUU93bdol+@(}!-(M&pOki_~ta
zuN`Khc4H6nMqY%DiyX|lslW1SZ#Q>kdLxfT=wsIh-jq#WX!nqo0Y=f(LA~QmpjwjS
za`ga{?oFG)z^KhQTJzkMqeTg4iWI1Zyopk>8r<tt#DZYZy2ueD=Upr@sfF3;lv2nU
zpVA6B<5OB;nhzU|7}7@@Z5UEo+x4gy1R<l0Q|oOP;&n?cZWmP@8e!Un;18<T?V_SX
z1^i9<f`XnSqvDe~e7mMPV12LoRnLHxzQVuH)y&}3{WY<&SNIOV`dvJeCt5AvFIc{d
z%R6;MTwLSHnRIr-V$n*Whf}+_!V`0WW>l}QMk57ZXhC5oOo*!M)XJO`i>amI%ak*y
zmnjx!@|D78=b~gEIC<K9)Cn_~^)el3^IeJw%v*ip*f}CchMlkg^HMh~z~n<ETX>}0
z8tg=viXQZfgdSx09PGu>QX#rA+MzDE6IYfD`rwe9u09+rPv~2N?b+!;qtl*(({93q
zNm~iBXv&(xESj>oFo_0MnH-y8v(R=E*)%lxU~r~x92_p^FcC#=O<GD%@sb8^n3*EA
zCVOyrg9dIIs}?1cZ<@4Tky^uU;2r$`Wf@x(ehY#LXa4~k8%Q07IWUlR3YqE}A_B^s
z*I=hO%H-E*s*qi<(NrPZA#-%fyoel~^+P$WlnB}<Gd+h^P5cHVLUzuTo`X(YJh=H~
zFbzr?j+@5P*o#BK`v|t#BT3myH|Kz5TlXX*tz-sn!_;YHSV-jXz~Ic)I@Jy52$Fcp
zD9t1u8Lp2YjWTUFFVi-7K}!Y<<Sh*uGN3m{Oh{ST8>6I}t`>(PCu@CUNR%x4D_!TN
z7XX6mQ{4vIZET){#+WC07b2_Yln3GfiGB=zynG-0c=<l~?ecz%<dkpDl1B3eUVBMN
z--k|Zr|(0jv^RRJE;1ZPhx|K@aY}Lmtt6gnY<{9e$hE#0JQ#^SCtXcU@{unJNj~MR
zVwMm6S&`xsHb1$%7Ad)}v$NyvCEwXf;>iV|d#!bx#&W^64kNb?$9{qR^yD?Tsuv}1
zMOsYSLx1#}wD|@j$0vNI^dBxtdMfE;T!}r`C^uwFr}DA6Di<mJ@jAXb;&G5f6NIsO
zL>tW~={3!v(R*(E5`E`7mO6dsdbq&<OCRo$2|#e-@>>XwmLIsGfBK4pkisEv@*-fC
z(%?IULr&?)2#Vq8km)Df)LeZ$6nd%7@WZBmyfL~<{_{qoi=6Clid^t36)0t2Ui#J;
zLP1A<V}MuJLD8UGC?cSx$>rFB1|mIZ?12T$4$8oT)r$Clsi7i#D}xsfkdph1ZfH1&
zDgvU>0Mn-i3>SKC@gpfIQc$XJAXhjBQ-dmGW99hda1hqf8V?GEeKcH86&VtlLFXPl
z!mOVPIEkd6jKI)lYYd-|+R-w}GXq;zE5n-@`O;v<@l$%dVymP-D7H%4g5l<Hwlavv
z^s6^idByECySKQW21PaFepV|#pf@{IW&{r%AR$ypKaxwYAfz_|0ZNhZ6G1<)5jQ?m
z%(X4>{Hds?h9^`-MlA|Mt{}Ae=sOT%l@tYFHN1c;M62OxU13}eZ+L`y9U$dr^j3mx
zLNQ}+0>a5!8gnYztQn65*8|4z*i_Wo%JIpdCp|`Je^c~ZWCq1e;g=>yiGj$U&@&Wg
z*AQ>TNW9fXG#_7JC+tNE>06Xs9tr#jjZ{&A%oalAVEz!a4~7>m!aOVfaJ4(44LLd}
zsET4dR%TE{g)$j7l83fnNTd!`yd+bHDyA}0hhh^e=(3%R2$d>)G9pxZ?+GJ5<2xHn
zjECW86%EP>B1T6cq$^V>BSK{@qS0|E&$uz1Ysjv%!nqXCirk`#d2MNeR8(wa7v=n9
z2RUJ;Qh4p6WMHXle$ZYNp&L0zaiS}Tmq|wz=^IH$ek&GuwUcp6-d94=Js3!QfWqkG
zfi`20lP8f?H1>$)Maj@w2<oA<A`|q0(JHC<=#_Vqq2*NlBkv|cv!Ul7O1wcdcKi`T
z%U$1RXnBqpGmL2OmGu%DZH0p`QXKb;7mq}k3MXHwFJlWhkK~vb)lHArBIVFEnVV7N
zR0J0#N6shnqI5*g!*st$A%ueKU`|a1+(%AL#QdLVWxPLLu8WZJgn0gyF7x0oZp=7U
zIwb@w!q`#<jOM?BBUz-F;$<2>j&LO?EJ{pKNeqh;JM~furU5Yq=@3DIC5agmOwM6C
z#cGc&+rnr$R7Qp|KuT#F28@+T?J%I4RQiW0WJ)<A28@qNBtiPlmTY1Oqq-&<gIOvE
z2+2EYKuqPSd=~>;Mdid8uqco>bAXg9tBrL-n^gXd(MG8hoyhu$k0}n%E@t-dd0~vb
zQbLdcQlXND_>;&fI+7B<gRG;~&de$a7Jv&Xd5MFs1gFC?K1(T3WP%c>3;+U^TV;R@
zsQjzo?w+A#nf_l{T*i2<$on#yK$#Y{2=VvI99tA7oIw~EyQLJgkfs<2bcID2$Y8Sz
z$q$wFW(?y}X56CWY;TPmYO9j&EOX6|Ek}==42gV6*%JMj0L0|L*vsp~nLc=c6gic(
zHn5W^57A&Wtz1PzE_miL#*uO`*AWDyI%-%<)YK_H5k;)L%0;<GWnCJQyelztQF8da
z6PZg?37(6R!*`u6lL?yxt<0+A?YAgnOEZo0I{%&<YBIv`fergj+0t2!c3Y*qE($Ye
zAvUz+R_?4JZM)KIjmBN2;I11f`6M}*aDqQ~%@8roU?dKIB?2!>8(XHZ(Il*FVw*7P
zAmunIk)%y6%#@^kY7v>FZCb?GK#})+pdIP{%8fQ<Y3qVemNs>)xV2BEU>`}zFKKH}
zM@qQ%w(_)TxU<O9)^#xP+^&@IMapz=7iTh4d*I)hrCp-JEbXBy5GHKus4uB1%7C{t
zYFCc@BINvV031OI?1b|YD-(=L3HghVyp+;00VJWs{v)8Q&x8UP_>-LBEg7?z;Uo3~
zw@Cm4ixQ{}#2{FN1Z_CQec&$%%fKcPBTjZAV1z<MEusLMT>h&apOz1OQ4+19Y1M#k
zMAz_AWdUy_hpi!eFyS3mE5A(mhea71K!jz|_W=Zn)m*HW`_K?+SSS=rBh7Ep@M_2d
z2a?4BQbJYGdSV0EL4w4fYAe(X8$^wm41o=W*zXN}!{8neLWdz;yg)oGgBlCx;|S$D
ze&()DL*{~P=UAkDjw?CA9L+_D>#LAS-XuYnyh7&>HVEFtGElM*Pz=fCKuI}38nUTm
zJ4PZG1=1D^kYy2qDFSUd*88L>sCvC#5_zVnOCDkJ2w0}6ZwNB+<Oysx8TV}vw#T<_
z2|VLlw}g4|tyhA)$?U#fVTn95)Xl-Hp>Cc-oLi?5g971+_uYomWAL*SmQPSl+wgwk
z-53MB_$W0vV+uHEy*G1!B@w`~XeAK<?|EQKwL$QnXX}(uInUN9p_zD@3>>8bM>^td
z{5%_ilELpokflY~FqoL?SvXBWi4$F5PJEU(nRN}}t_2FUC}V?-TJ7Lx?+hyoQjFKp
z3KS{ddL)QcoevElQaNyB_ZI+`0STZGvS5Tr04)P9KmlwSB5nb~b$~Pqs4Gn!&%J?p
z(fA>}F9SkdL4qAY@|(C}_@f;B&0aX(g+6A8?k#jO8z-4hV`o@w*2jc%78Jh)gl32c
zE~qqva}9862S_n30It~}P+pw{xF%$<q%}#%Zby(3B2G%@I13(bS)^h{LXa~jCLW_z
z7A26i2t-H2R)N)-1B*y_c3}*Q?@Da|px;rzc#D*CoNS%8;p)M}R?vHkkW*G*yE#$u
zwEVt<{)H_szClB`!Q)uqfw1=-8^mB31>;N4)-6}@*}5epqE^}gDM`db!&eIvk@m+z
zO$^G|krfS45rAJjKw7MzO^#{E1>$I!asfRqN+L#fMlNO-X#kG<Q`R(tYqek}4PoO=
zrZWrp#ACy+G=NkT#$`~>9S76kq6JtcDTLEJKuFd|w{u|dm2nJ4VSsmn5}dh-Bep0x
zQN0K^%A?@~x8^DN%oBx(qwzx%1u$g(*(l@>F#QB;O5--8Ht<8iMB<|sL8^R4+7n~d
zAoB&o3d*rTwbHO&Xs$sycf{AC3`$O3sYfBl25G~VWm|SYpTeW1<dAZ4ez9_88r&$w
zs05?EH%5`NF)HzC?_yLEo{dp~Pg@&Pgj>T6J73}d(oazk!9iKPBZ%-$D7J*tt<Z=`
zO0;4_>O-L!7sYFmf<!*pl;VR@7KN)U%H8Xe3L#``AP`TVyXVFoQZ{a^A>Vq1iz2uU
zP5!<&Ng`$A*y7>+Y#ajtpk`c)=iC?q!X^f5K_A=202CU+C>f7!Vi1J3O*91TX`397
za_@4R5wZ3uxKHh~5v|%~Bf@M;aN^i{oZfitsOKN{*t6}i*qG10#bQ4{W9L<p_I(y5
zbM|c($Ha5(hYKhjuV$V%&$S&c!H9cfR!G%zZ_FYkne}G+6@k{KyCH<+dA7rN{kIjq
zU57C#br^?8^|FuP#9oo%bsDe5?5Ay~@tVzwIj_?=mTr;iwpw3V(d>0wt)J{=?7&Ub
z%i!TimszB`uI?Do*siNPMl`nT>W&eO?Yeq$M030D&lu6%Zg-0jUEA%RJi4~qeVL6H
zg)F+kkbAq#lOgwZnXjR({Ddy`BM$OKni^0r#Li7)=~lZjwVKF!(C~s6n}GuQQ8(MV
z1vAP-u|`tn3E--9#i>IpJA!mkX|(us-FR`1bVX-V0qjchqJp@Jn@CB>bH5{knTlpt
z<S~`et~g>UtesK7$5$$~K`AXaXFWev<8Ji?J)<Q(Iyu(M9FclpS9mK`^hM#b>%<&y
zJ)=_5KNgAas1tK!mz<$YnRrlig?jSQ(c77}lYCip#c1;B(iMKm=S^2+C0{_j3C)ww
zq(%C8O7*6L7_Y6a@J7DK79~0z`DR<GLDeUgNHK_f`t_!@&zE6uu4j~`<z$hnSI)uJ
zt6>guRp6Q05#)z=Y)|XM{?3i0DfP)2O!XO=c{TRubl;2*aO3sO`p~cl*VZi;VKY8N
zt855ydZgjuASw9$d>Rq@hvgxp<-_t25(CRa*(<tC4=`!;55q%jfX(ob%-xI+4w2ui
z4|!8|B8AWj(>L2g9=v_CJ*>UEasc5<hq<TszV*5CPpV6fuFMaP;dz-1^Nq4d>^3kw
zJwsu}>b=a91LLc!ISpdUntaJ<7MYdm7DJrdw_<hsrRUa|nXh^7#=G9@G>F3{(mqcb
z{BkV!)@d9;s6NT8XX_LrdA2^uEIoI|6&b4Jci!#YOB&(~TLg8;fw-h$z1F(h)+6jh
zOrTBD8i%*)5)APY1zeb$H3HY8moOwV7KH+i%dkumc>S$JVQwVcY+iaAY}1Rx{g+H!
z>B#K%fD=3%@=kJU=m)Iik><?9;R#Mm^$5XmDcrEbcfYnCsX8F#`X!4#v$9{Z`u8$j
zz%$UxbP>LT9$1s~CFIAStxtYj{%d$Cy8q(H=r9c(FE~4b!cKYj_o3?|JSKh6dlH`=
z(hw$4wfd0r8h#o6LBmI-;iYS*mjMIsWhCn#Acd?C+N<&b-4!!LKT{u)4fvuuPNwiH
z;Sg1f5WQM`NH*f(y`Tx`5yFXya3DF(7J)0~fp<{8xRB&BdB8gd(1e#9cmP&7K*|})
zd<9Qnuc#q-3;UqIF*&J2BcAq0P{{j%59!pvW4{mHBk9@fL)QqN|9vPVnjX?VrSYc|
zwWIPVy{yE#c*zS3K#bTy@YOC78Ixz`qJS|tkjjVxw{V|LBE}cNl*bDW<~}=G`5oD`
zXZ$yb3XYoDYl2X`%cK&1a8|mepFF@x27e?Dm05y<(7-<Rcz{Q~PsT#PY2WA6{Gg;x
z89USU->VD|!vp%%6@w50z_h#&$<!+X3qc8emNOKQ3w`PoNs~vPL_=gq#G+s@FoG-!
zV^NmorBEsaT@c;o#mJ0Az!{9*h(r3KC@`MmSR@3AK;yZz@ThOlFD-n;I;}QGg4)}c
zt_+l8AQ(_m@>le*k8qU06H)|AEG^4b9SUmcmyDkXeCZbhV?x?5sSb#p2?V4)w&qBf
zBz!6N%*9h60F@T@5@$Ry5*g1B=CdgDup<<xUwSk~uu$Say%bH<S^Jp*NByc*MpRzE
zYMCMb{}9{MuZo|+rK#AaG!Z2D)gDFFZ@nZCYSnLD5D3TWw-ku`RE5PC1GtXB<}$@}
z1-oxqcn}KKZ$2s!Ek+cum*T6AfC@WF3R$>y5=3O$YBT68pBlG>1Cecu!Z;O#zXggJ
z#)tdr9%$v1X#+x--6AmBt>dJ)b%jK{USO^<+AW0r)~SGizkbUm1j``6-1fjhBEG#8
zUAQRZ9WI)iRw4u`_B(%daBTFGBhs;#Nibp|iB$Jus29QPUW%s-#5=sLGUhT!96#=i
ziqOK``XfIIg2EO>{Kp0;OCo|q7lq-Hum?R<S`lly2>B32IBJ(+5h1G!FOU)xH$Vk)
z-A@7x?jf;9f)HZXIHt>ph=~NaVNM8vw+kY%D8Zxt=-NQ2SfDdLq~!Q@10WQ5p*-dk
z5iNWyV9Se?)yd1ehOlElwYLzO>=kZ=K&b`7NtPqRIgmOr=rocL&a<MV1M<^JnV?L@
z-sdATa6%Qeo!yj>fT-;N9Q}yw_KGuN__xa{hZyldF=b@;daJK?*I!&iz^4&=-=m4(
z_dF;3yuK=oec`A!{^w*SHxi@a7X>b9#!|T~dJL&|1tl@+-p|TE7~nzW7bAS%fjOcW
z{{WEX{04aNXohjY1m<k&^O;QG3|&I9frnL)$p`^htMr6mfhm9Y#KlAC+e&+IQ*ImP
zw%~KQhB-Hv<q$a*hcI?45yMUC2ceRBLUKeRhZk-JQa#)n#gf?|Uf>llaC!k#Ag#m;
zWdh@NQ)xWrr#R3ckirt}i-h2t5?rk%axp%O!WLfm3do`H!c)MQys#3GjI)rGneu|9
za2L>ldDiB|hdennG(E>>rl#lk%&h6<-g4px0LLtlppml!;gV5vB`>*MnqVe7EDF{W
zDN&087G0Q(Qg4t|wNR}2Gf3hl)U|T6;*an<H)f>NPo#HwCCcMpZn|EWOSVYphFr6S
z=Z$X2NApTpZ;*wI&dMLkkU_7ka#%PCFaA=7oL34tP|X9B9A^Pi?YuI^0~$Ti&2y~~
zWwj`ojF%GSO8!0?Oq{MTE+z|lrEMdja8W8vF}~zz#N@nH0wq?jRRSfJPeEPGhxAri
zl(E)FAjxA!xKEl+Z)937O53tAgTUcF#IR?wXRcGFRN}g66Rlh$<y0bL)GLR&N6@vy
zO3S3v)yB|~nCi0JB6~GJ`<W-3o4l#Q6LVm_a;A|d>y<N&Tv~732%YPGF%E&jRjaB1
z6J<N5$UIDB_C_HBe9AFPSO5=X2rt6LgyCF8Axt34*taa{k&{xMW(T&rZ%NS;;;f|T
zi8T{CM8Bf$0y&k(fOi@anOE&wmUNy2zGX?rT)hkT0k%z+csO24^Y$%GI-k%{8Uo$&
zdh@RR*rAPdXm<>`S_G!iuSd&jGl?D|(&Gn^)V_+DL&h9gjILlhWXH4M`AZ4(UP;qP
zvUep-JI;k(*>FhK_s*vZ6Z#j0C;=Vpq=$2X0<2d4DDd>XlBfYI-~th61eW&#Wk@~V
zyOQV}3YB-E2?6N9E44Zu_s;BU_`$swFvC<ACU66E!TYbk466zVKMp;j7cj$(UX_X(
zAP|c%&|(*U8#h5`Vrt}Gvew9pL0U%?Bq44Hg+nQ;aI?9r{Di$&ln-o-{2?Nln7R=g
z10teR1~42h=K!%f4i_dq@H`d)z$zV`blW0V(wXX=J{weGN!$>JRPh*sv&Ad-J6$Q>
zgD>!qtU@o4_<@{cS8g~^P!@sXnCdmq&W|W_7D<oZX__V|OO%wsuRt;A4_etnXBM0T
z-XAT{&9Mmz2X=l}2qv*+ywj3NJeoz}0-<_`S57(%@IgtLN${H}qyv!wIF2in6976#
zkO0<W>P563Q?L9BoEMeL4oi1XaOb39+bg>rW^C5}c@a8j)dxZ=I!Irc&Y=-m0^md}
zG4vvSkvlE1#5i)7N&^(6s8ocj8fIWu=qUh}f&%$Y3?>#qdI_RwQ7pshh~wmR5E1Gr
z3Mt`-@uqN{wlG_I#k3MuYLSR^^r%~Ig8-*mO%51Wg$u^wLXjDF9mru!jiOMwOfY4#
zOw>zYTJ8e60Nz$mh(VT`-y+3WPz}}P&?2&zSJFSwzZNB3<^TxuLID7Tn9B=BoH6&%
z_Y#JT#j##QDLayc&p3M!h76a3>)eM)Gbs2>>RX2^-j^_I?z#=GD_X!DgQDPt4~N~J
zkOavlY<J%Q;!^bVFiLCYB5(o^q$+QZ<0a@hSEMoF>0D)O2w@kLoD__U4#(d?Bs?$l
z17PL3;*|-g=fXp{xwLwj-N1BWxwMzC``j5{nfQKDV-54Xxwd-G!OC~I{EiF)bSH)!
zpa$J_f89g1++Knz^bCwUKw_8tiHVic?FNWMFVF_SC_2Ni4`D63(~6Q-MK4?jByqay
zX?b%a>rT88cD*Xry@U+u1qE^EF4m2Ca~JD{3b;x4(%ykd>CSr<u$5kT5@{cF*F}p;
zAnuB)BOs>BWlPXZCkh2%HQn_nczPD>%h4tb=b;*YFM)M>0apOf^OMpsT)=MT8GW!i
z;7e$t?lL$5anuU}1E{2*lsh*vLvV?A>T)_06ZMml{FBa*xT@}VF&#R+3vdtktnO4R
z9z6J52z*GzB;`mTSa+2?0Z{BGWn#R!kqJ2Ka*_j-_V|T#<J;q_ux<Bt&gT;z*BQ@W
z7`iUB5aR59QphO+<T^Qpm~!Izx)Vc?n7^MCG6smbQ;f*#f%w9%BnDy-e^Rde_zmve
znieTAXS=KH0!?Qh6fR{-(t=g~XlZmf+yTtI{YE>rO!#y&F|;UT=nZ*Dpy+K*z>+T3
z0NCz>K;{uc+qn^U64{590`$@+g$%{|CWiL0Q>LaxSZ%6CJLN<8XmeTZ<BOQzo3tWe
zY^P|$LF!xWx7-;A0m!$_(th1>Kr-Jcy|x$<3JH*2Bm$_{2|$$fIwb(az7rZ=PC9J}
z=<fK9_REn)RQONI;4yc66_k9Pg@l`TMbZ$HUMDDF>v_l?g0`<?m+@eASTi21PIQKY
z>BK*Tw9iX{Q2e?{h}XZ}HpKL=3kkUYM_pR13s6@bYX{VI$N~d(VX_FpkvA%f6x1cm
zLI!nFv)X~Ka>jEx^G#li=qi<f5nZJ=u+##I%Lb)O`^Y1U)(rtfv8qF<EUf%cDoyuN
za*{K?On%aeSX!b~CzhWm^@=4bN(1XuiAqgFsf$wOSPetk9;3HV_ZAc?jd(1v@J8v8
zS(<~2CM$Q8D%xqxkh&TLKyqwk!lO>ulH-)-2}TU+J*rqWfX!AaHtLnQkil5eq*Qg5
zJ&`ugkS%vP^cb{NF9HN@1tmN6dRX8~y&e{$Wi=VsJAspMy%VsSBZiy*!e6US$N&IV
zy^>geMh__#sHwLW!m;W(#yU4aIY3|^4*p^vtjM5#+qELpZ#$v-Sed7un5^DY?@(6w
zskbW20P!(<s8CQncryS?Z(;>t)w`JiSoO9>1*7AOPx6<_9M!Wu3nA6Jp0$$d?az8j
z9(GaIU`okTU4Yruivx7^;s9N}VD@7TC|NLABC4z$tRt015SE!LBMC}TrGW+lje1qE
zwt&KJ5Z?@_qREDZv0&6WKw=+^?PeDa?N%o;lV<IQ5Em%pRdy&=`YK};%Yl_a3t?Af
z^Fr9wZWv?bv9g|_I$0UmSimd|a4c{J16@`x%X6L?(4BS)+4)#Yjg~+ZTPsr`La;V-
zBI~u4$&p3f(j>{EZ)LG$VYoDE=D;8ailt_SIhsaUgRYFHtWziZ>XDV~$^gq^cV(qz
zLA<i$X34xV^`fZWZVyK3z0GKxL0M&1X8FD{J+s6g%+m)*X;#*aL^}qp+$<(ohHw@f
zq^bNsNkUi3J<ArBy`7~E%O;QNhh?@$fy9HxeULiL{rona960iCdN^F)ria7%P()G3
z%^R_bK9;wFMIp<h!LpI%^+0LKL!J?qpDe!#OH`I`g=H+u|AIo7n~w(7Fw2j_f|=#&
zVTe_^gR<;q`HK!#<t(ofOLwN%iKRWuE5(qi@>?OM>X2`XMMTT{g*v0<AY&=ga-y+X
zDLiclNV#Y_3?KU{Z`}%vN>=W5Q|YeD4gDC|uY>N%gJUbCifdylriyDrE=d-8J<4s#
zYOv+nWW`u{KT%Uw?om~pg$wlnsgKRg%JQ}4iCxug>8gFH`mMaVD3E(>9$!|`Ew3;u
z?YgpnvKDXomRYSA{^uMUWI;~qj-*Vwv3nK<E;l#p2A3;b#f8&X&g#SEOJ{vz7nC_l
z7?(dDRgRDH*|QXKx%C~GR^|H7^2rq(zyiw%AUM9N3UfsnpiJ`?iNI3M8LGg-&lSml
z;?Tzy?!cI{tTg|XRi?)lA;But6-L46vIw*|zEsUR2)SFG@l}e>Smm!Pcmvh35#aHq
z0@}wG1;Q%Z6)D0p+!am2YTgxuqH^CAsluAz70u!bf8ssQI^z`<gJR^z7CXbRErr*3
zR<o)A9L8f+lnx4`Gm<CRg_=i-_F;i_7vK_$uvdr>i?lP0=ujc|3NvD@cZMdh8oa9<
z3PY+Y!U<*Nk1Y&}mFFu`iq+{ANW}v76>P;{JSrl~QFEoDwj2djDzeK_ETzJ~9Hmf>
ziVq9ERQ#Bugb4%87PB*2scV`Li>eXmsAO8fY;F__3AQ4kcndiIv%SjaEmAH`{75@1
z<j%90M+M~}5^9Uw^9E#_3hxVPKKBqnN_>S0I*MsjEFt#Nu>~AD(5o^aakU%)jTl{1
z%p-@_74LYwcmz~Tq&J3b(w69rahs}h-(YEH0Op|+s-iUGU_19nP6xOZ!aak+xJ`Hl
z@(9hiP3W3DcQdNg8$&iHXE+tL${7NxpaNGH34yDe<+Vk=dX{)VbSwyi@v{dA$pf9|
z4BS#6ZrqxuF<KXt8x-VR^MbCh-?+uc9vaM>9`VDAf?QL?7#|>I5G><6LwyNG@x|#h
zEi#^&3Nb^TQ}@nj>Zwi>vEaN_`BbRz>Udy8Ff~jj`AA8UHg(?vx!2oiMYt>0+dE^u
z84$i+dzqG`i1Bz<#_;&6=KEA(=X}sIFr6;?j9foJndcte&L?<9!1LLTFnLfioc+||
zdE_oD+8$<w3dncwjM&eX0`@UyM?`o<{?nLJxdAlFD1CqyoJ=pE(I>MH4p1V|L>US+
zK~)xm`;ZDAE#^va;DZC38vRhZ1V<0)QO*S|g_W2A`{Pl`8#H5PZigecvvNO{eHF<e
z*#gg8R~~GIm1IK0a;2frhFz&Dw4U=RbtGwQIWX{ZRGJL^FqKQ=&I}#XmmW?~=et*m
z4uzB{IsmWqg?E6gA4h5^@`4VK;un-W<UqNq1S3y-qq345u~ST2@_{Imctq!XfDu=j
zPR^YEi?4r24!<&{oZ(fKR^<S}Q{I&``~KoP-I;H%TrD5WJ{vX7Oh3~xJD7f!Kk68p
zL}Pf4O`5|%5>X|eEmG!<NjjL{t`s&O%r?`lKL(lAH1C0KI%-zRIn(Q$>Euemb7qfU
zf}wOEa#b$hqJ&5>-OmSrUZxb&f#e$`2p&m_Ju_?dk(8!PLuX3(lt4h@nVon9DN{dn
zE5o!}d5(@$R~qV)l4*`K_xRXTCw(v{Q^yB0yOn~uD3O9WI5-G<rFQyc1}5$9i_*rH
zBDx4U+O&(TcIHyb3gXPtp1M$(rLA;ThXJ?JSr;W4)6p7xHmox%TPd@Sn)Q`d>l0aQ
z%Ek2wMD5Dh^{@d~POsw=%=&fMgexuB-y_=chF$sAQs9(tjr3zjy0u;`6M1gRVLlv2
z<VtjQrC3WBo48k$KJCGEn)I`sn}%7~t^{kH14^*gt%2pOWbZ`@^^*zVt{m%<1m;+m
zC?Lt&#RuF*W0Qr6eD#tA<jjqd1*kX7gLl}p>2^7ilpJhZuVkP!lX-nnG_a$UukRC;
z94o8e5wO=Wc4$<>1aN@66>flIhjxPFEYe-r1I`?5!4oV>!aYdez){fY(O-lx1{4s2
z=lM}s2@X?x;VJlhHoOH#gdji}4v_N8v%28Rc$P9rTi!-TtqB1{96?H$3CP8DZU7U`
zjBSBXcpj<%ssJJ0?}cXJIEoAL!kO4Dua#d!dZ0|e18@|&h6BgG5I7tWi~{Lcgye#4
zostVGapCYB2n}Qrk`K~OFPt^<sW?#cx)X)QFMvP@m&6epS=c4cJaWOCEJ}=r5GeUW
ziO+Ix-C{t3QdyMXkI+^e>E}XZSwDnyN@BJIB}b&2gBj_v_y^^=3mztaC`UB5ZiyH(
zwr+vbGPZ9eVhj!MhhHv4oAn1!qJ?_n7x8vvb3kE_0?%2LR5-ds1Io4_coro`*S20U
zx>kL1a3*_D{C6pp7l0_bgo0o@vJYGY+c~#RDeN>SFUr`!iyWF(0URyLH3|aB;p^F8
zk`^g}p!6WQaI6Yz$)V*H9+M+8A2!}2DZxycbRF7afj>FQmk=CkwR6BS&pK231#!J7
z2?jOPDYz?~D!;A`$I352ju+UK!#P!mSc{U-TYc-6<L_Iq6b7MhEmBSZZjMDr@GU}k
zElRMwZGCe5^!hph22^9!uX{ribHw)+;+VrxR;Xl)638V{eRj1H8%+-iL<AS~na9H+
zfzg~;1q4nzf|ST;bqwT9VRZ@+@lLOai|}@|-X!F~v7x>BMTk3DY!Hepz_=hh&xR?t
zC~XjS?f@m$$LfM8h&zf(;0poYE?UC~fd@)zG*-(_fV*0D;M>)r6W>mYPJBC6w_Bvx
zMMC!T8!$ye{&V;s3mq^he(w;1o|SP5W^fU5Y0s@!a^hrb4MtFgi?Sp`S<XRNLlGq6
zqQu548y^88PFf-E9Ki;*=m_*KKt?Bugg_gE62sA^zm33;IYC^kWsZZNwIC!N@#6(E
zxhRV*r{G|n*c8I6biB|D)6(IuE!;~_{0bps9zlrVNYlgHzc4l(WrYfd(*b)SsLn-5
zj3WVhg0z8tI)dN}7}Q~TSd@WwVv9b-ueL#rvPC`tHC}L~i;~!*^gAT@#!;}RByG^B
z4wFd1r+U^+Du7iHRJ?al5`0#-^bOQ|g1Ht!PB8ew0ScQ7*?=o69ZnRz@$Uw#+40db
z4K_}R!mkBs!?<;zj1&%TQLK0sFY?0EC8;oX9lra*<=rV=!(C{!tPA%+5oZF7Rv5uM
zW#~&GF8571t|DFA+(UwdTD((gq9Ii*Fm)6~+R@!N<m7D8H2R;u{=>2M`T73U_Y|)-
z-sJb`c3!u?57)2%`0u~|`<H#4@BhjF`=5Uv5-C`xe&$KL*sa(+hY6ycVnQ0d?4km5
z(3fk29_uwr>s&+zKA9;9sG~NYsjlebUxyX40wC~AwLz*#trrkT{K*h34Ah$i)N&L2
zG9N|@3xF`J#H`<eu-CRJe4GLO8x`MCoG72MLigv1cvl_9g05gvFQYO}M&_=pE99st
z^nH(>c82a(ppP^AvOKHEb(ZU@<9YCuO$jgYYk$Gy^WfR8f!LDkcn+4P5c#<8=5OKg
z{w&0V_kd4(ru{~S@*r=h3HMWaPSsD~L%PZj(YUHQbm?Tu<>Z|nVGB>zg=TP`zeT13
z>Z2;^E<(u|Gv&M?L~)5xfe3^wD#&Po#ZZn?!tKIMXa#PB>OuuXj=BtE$5(%H{}$eC
zqO1yr!C?McQUnAa+*-G?#7_Fos4DD2gvd)Gzi-ixCqo4l-|x)k;-S;C^4*dooG@_u
zEoUfvQIPVw%MftduTp&R67KTQ-<dG~Ax3{8DCe(&f?O<8e%p}}Hq;RmRU7>4j(DC?
z5PwP^Dbf5*M@q1<qbS$69Z`yug8nlN8y}+on~vNelO0Ks5B#q?VnEzTKf{3kv9*5F
zQ9E#|BPe(Kwj+u$ai9JSm+I%v{Y^)1@KYU0ncsC>{>l9u_!;p(pC`j_I^qCnw>t7j
z@ozi64?CVSKbOsYJ9U23VI53E9elgE{<=fFu6cI-47<dBmi?wv9C!$t`KbeNeAlU=
z>?04wpP3c6QGVMIb&&x`^z*AI^V^QFD)Z3&89C#h$MA1D;<QGL$j|Nk{&vF#<ji)c
z{}jGT9rM5G$lIW)BPsWH9arJV{nGfE^$<U<k>7OWW^r^BWuD)5yinvEchb))=Biuj
zHytPbtf?a@_qQFhfE(_-p8-a@-+{mB#4>#7g!c1oCzkBU+w^Cmn(x=^Z@RHK(v5Dq
zmHpdp{o|_sDfIrjynjE;__L;tq}<<kymwU~Cg>lO-*OW=1R~OYZdyhEwj;fAscHNy
z<XWm8zv)H=rLh|c_jlcBmx3DeGw~Qd6q~>9DE-IOk(BGZj*a=MP?LUUwaX91={FrK
zHi;cUQT*9ockJy$4g0yl`kdbhxAeDmsbd9ef7fwdA6nkefJFGz`~JEk)kCCD{M;1A
z@m<GA4BoWJpP5tpp;!K<Bh}BLj-bc`_tzc!{h_7)lq;$9*1zs3^|q@cDbKeZnFSJB
z@XrX%*tO!{bb{*K*=aEO<Qt9m^j*FFnQ?@>zWtkSmtsz{o7D9FT{pzVQ+NLv5n-R&
z{BJr^=^yIISVH@@<LDo6gP##m@cCN!O-DQ`P%G=__RR2aI})B6Z;zkp#`$=S{6?ea
zqh+ci9eVBiju&m3xfVdQ{o_+7{>az~?Q4H#Kj(U9zhBqyv--N%dwaO8+VcOxXSOJ1
zw?oy=OTJf8x?%zmpVh81!;vBr8)|)CWnm-bESqc;QNGTyP5sC!WwbM*Jm{1)jf8s}
zU6|$r76&GYRP|eh!XU|JQN}NAK0iBZs7)eu?Ic<jW8H}Lvk^v3I&SjG6Y|(d`~%Nw
zbW<NDrI--<$J~r`={0B-`GV-TMImPbAgOGOVfLGCvoVsws0!K-r)}2PusTkY{gv&_
z3VCJ)z#DE|SUl&s8(?F~r}zZQcs>oVgrSm+_7GOpX4)P1W`NByhGl+@_Sa@hX3>q!
z20gCLxE%{W<hiDCd(6$a9V<2}zKw?TF*bIlk~lV7cC1K6w$R2ueD{e2%ZJ=jbQO%g
z`9y-ndI^VHB1TkhC}=oslp6|VV25o^k>sC!I7M1HQDWl^1*XHV(#E;DNYZ5SY%Y=|
z@?Lv1qa}{!+N36px|}A#8?S9^0<{2_Kxn^9<4<tPFGbwJ;nbX47G=Zz+AKy_Rz4*w
zSwof^_MrQ#d2Lx1mernRUD+W~WLa6|L!@gi>${e>F8JWPi|@&buhlF0(6>$zvr1gU
zm;8xuO0@pL><P2FD$CMCjN-EgNXgy`e91qc{}eS$l|StlYM6TaLGO0fuWehOWTtI>
zl9#4FgXMV9PPUyoLg8v}er~SzV4IGH3uQ;C1;MLd1%!`q`&Wfwh6Shyu_H&d>J)p%
zvsNu*zfduvb%n(tM4>4gmSGH4H`!s=YRYX5N)|JoTen!DsLvd&6Xl!1mzm|APX=n_
z=oO}sKc@@f%JA&A#j~W}t!?ov17ojv7Q}g1wd$~3j=i3>r^4B`c$NX?E1)GsegVEp
zxEuqnpq6x2v<hm0#c~U3aSZvau#qTEULh^4P5x|sLiV?y7S<-0x8Z_yzUq#zXrQ)*
zv{YSkc0pZoIkzv?CBG`<fQ8Agtyjpx7SaNBpv~=DIlQSW6}39r7Sw`!SGC<E=xVgB
z{`;cD5cB3Zl9FTet=HH}%|{H_b8qG7J>Mi%vfeLxgj?Tw#rjr8AX400lcsRt{%Lg<
zAOgKL+qxykZ0nW-vaMTk?A&?<r<yDl48L2H3hav!SxE-Yek;j1F(P}mZZRUew{9^a
zySHvJB4g~s1u&R}zpY+@#?4?<6#rJ-OO~K%74-sbbx{}!IO*q6m)MA=xHlBP32<?E
zw_tQK9u)CT3CS^6w;O!WVKGr~+jLk!GhXQE*~&}a`qrhTag7nID2i<vGJWBz6*G;y
z!kV(CHopQxh~eR_Aef2k!1Msfu=AENFd2{g4?aD4iscwWfNl7W<xP%NJk#BIFi^Ku
zj@rD0#{W`~Z>w+?1Om4TXPL-ZU6!1RF^(Bj1{ySfI%!`DR&JGIHh~=cCZU<buQh{5
z>6Ge#Na|J*F7MYu%jlNmw_^fbyv&~q6BfQ3=j+MPB}9EURj&xgQb^s|#HRdU(;J-u
z<za|MI~k>2Jv$kt(;ld+twLfD-QG?f_ke1(M~WmKD~CN&B@sk#j{=(Te&MI{%v;9p
zDT+l8CAK>P`B~88r4WBps0`3&7lC32yZciKxhU^uk8Xfz_!vW<E&k2Ho%o7E+a?Yv
ztH7B^4_Ix^FAt<Q1+6ftKb0tx>{=A=JwV^sBVj=e_f_{qIT;?k^rpz10(<HSk7t%W
zx(QGneo-o4WJDDf=7-#1i2~xYG~vNgEkU|4WI21sg%K-|X29Y2C@4OY6OOD4bMlAQ
zm~UF*93>l3Uj~#39|Yq{!X<XATu7w%tdHM{c7&tQWNv4igR$<91K!z?cy}ZzB%}gz
zfVC8bcrf(=mxvAwWHlHtMUNygzJwfexnMY;)by4C90Q7_U2QgFeo@uvVV+j(ja%XH
zD2r;9OowW#Zwgv;)goLKMP98k=};J!m7QK;ip`-(6-Z=n!)x<MO3vEEb8M!Yt^Cyz
zh!ekB0+FS&>{jMKz`N{HP#xZ>6-DH53){uFC@K^mZwmhVr(c^%dv@u40oX9RDt_Tq
z(XS(ab4~cV>l-;R#m{Cgp(>6gB?rdfyo11xc1fauy=a#tDk6I9l02o8$}UCgC2-&>
z%oeW?q)Xbx*R5Rp3b_R8o?VKn#*-Sg-7@nu?IU*S9h%T@cIncJ1Q3(0m2h-XdJY;4
zFy*p3-Rq0Eady#Yl_>ivdY6<Ooz#!a6FIVa-os4U9G#>xf!OSlQ08+vs`iPHW2p#S
zSpDr%7MC;Z0a;vlrkj%d9RAZQB61zDI5r=RHWhc9(r5rTW>Xps9@#c^YI(~#icCk&
z9W`a=iYK>C1%G;OEGrAA=V@z`u_Xu5y;vslmC#-Iqe{At2~HVN@G`flT2PJ}5-4o>
zN*u13<U}iYG7+{9kCsinZ#t&NDxFD6uIQ@6%iPNB*)RN!bk`0DW1CWh`jxdy@dp`J
zSgCFu2g}eVLl~W<36Qz_@u5M`!pP=db7CSJYLB4i@=GW=rnI#qKyM;|QMNsR+*l>4
z0q2wzs$YK*u@*5dvARR%+?bPcTw4nJ(0*92#B_IK^vIlJ?eAB(eUcB-&szr{py@SS
zAoP|mLh_(?Ov@3mc6w4`#|)`{4VTDJkZglSmWOlx5Mnu8Z#+CCqYk~3vgYmDNzLSB
ze}(@m)MIltV-1xN2gn#Jn<E~S=7sPA&B^bA7QxXi*yu%x;S2RNz(&rb5LzV8Y2>)S
z5@#j`AJ`U1tgtdwqTG`S3e-^&%7pV7*eP+zS85$fOPLTk9k~`JyiMZ67<27x#=lYV
z%2ChC%D9QBR;%<ogB~O3dPnBPq7bJ7KrmJrdG9Buxr9FvUd$!?NW3s1MtWBHI)cO*
zLc#?87#{Wb4qrBwjRNV3&otTCQL@aOt|)_MPQ#_)7<8#821UY6o6z2Oz916=SS5yq
zi{Zp|?y{5vR>jJ)c>);QR6b)lVM7o)vH;E$DHBBDqJ;QWU}OTKn5u>ZAWF0$IS4&4
z0Sr3a<|a5nBA^%({f-1di3n?DgPtQ=gqO;bc~P)j$jPv-NAt;G*&cF^LVzY{z(pC+
zCfXF1xAQ7FvAV3il%yP(ggpL00*;!8i$V?<1}2sIG!9H!&WY<V4X?=6Fy#@haKIZ;
zeL$_l!*o#+aHQj5YMok7kKYj3>T_c~Y4PtUBDp97J*cr25??+{t$_IOFnv?d3W4r|
zKYbX+-UK)Mk8#cq-Z|Yg7zWiNZXCETM!>v7z%SN?Ci-COcS9@oPCxaT)U-OiNC6EK
zT2Tj5=mV{)pPFz79|a8h;OXBU{Vwj2_S776uQvgDKADDVG7xtLDz<E4&6~o#pGcXq
zCX{p3AvKwhJ1Qtx6JX~J1z$$x&Jw5A1l)}`s1;&fzCwcnsKmS!nh-h>pJeUgvAReh
zLX9ZbcdBpJgvoioRh}k1P6R+(Q;7BrsFp<{R^mv`2`}%4p4|kuc@J<-kkI-1v?f0&
z!CMxIGr*P?W?l~;zBS=8!@+G$kU|}9Wov?A4o9vDLXXfb)(EhS=Vrxl_Iz(1LE@)V
zV`#2#pI8%tC&M9VO*=RpdDi4k>u|{#LuEP=T1?n`f!-3+2D&B+K(96&{~h6MCgXdD
zb8k`b?ThO#sN;*v&&Y~^YsqdxHomTCL0(a4#*~@bnZnW<@nvT;a6@*unBF9`@~@fQ
z-ec8`lgB;K1iX1U<qPKs9)TuszXj34PC~flM~E!j*@?Ki*+T~l-h0MCCjz)E0!L!%
zG?G`QKIDa|6Gn2X4`c#<0&BwRya3H$@<DVw@q&`Vg@W~4LJ}}sOn!<LoRmtc372@@
z>IP;Zg308|=&*~MB3}EXea!d=*+n3ruxK0M3_GmXW=iG&iiTNL?3hEnIJ}{59Nthj
z4$svKmv)D_`AtGAyXY+ZOuE5~ZW}Br&hDe_9BH(gdT^jn6SjfEG-WsMYrwsj5F9)3
zVa#-H169V9{oE1u8lxw&bsiD~dF-^ynkpgC2rJhSa9kDv2KY`3s|g;J8EU372N@%4
zCcIRHf}835A8=g0NodAdDVJ2Iq0|J?Jn&2~RxlV-op`$fC&`q)oiHv207`<mn5j0w
zaD>_m#hExxi^TD}x?v6QK&}jcj^G!QhpdmzG%P_qXDz_WROomBFN#q3Q|yHOjOVUZ
zdU;3ebCA$xCr;~BCrB3FvPQ_v_fnqG!W{8vH4|L4<AM;TW(NkD$(`37R_aB<9AV!R
z>}E%qk3~^|g_JWIPI}hEFmu|xJ8D^&(Kyka>#w`gDF7-yK<k{z*N}KEW(Ym$P6=>L
zoD!f5HeZNI$){9zW_(160zCg#;s_^=o4{0|0JTAlD52dOk3VVF-qfp-)z}NyG#~>P
zg^b7^c{~7w&`dQ9@SZbyM~TB?!XqUPizQ-f6iVT~<}<c;?rY^C_8a`x<qt4-3%~1X
z<y+Wj^;vPI$z19EfKRU!pWdP56S5$XQ^Me_Nc2TYP8Ed*xG=jr&u^&}z!Hxig3KVc
z#7vq7VoN?L69Xa#4JLS_I?`e5*$Ia6K(O$>2nxo0BDslL%$EKO9=Asf1CMFh`=D$&
zQb!Q@Gs(er>sLhJk3jZl{o5!RK(+B07}%c_tpf%O)$N0Vi%<&zWYkXzc|6c=V{0-~
zTA-pGaU|PXB9dfVxzJ@l+hh!1hk&8o78mFzW<*sW*2yR3+?V_4_Gn5e05rsv00d0%
zXIrbC>@?Ks_#}OFO1Rul0tc5L2Ih1UvWVGLBAw$uFS3_}DF!ohb{01?geP(r@XKK6
zIf|j6xI_)ha=JJS&tpGbEY2Z!PKr%V3F2{f@tc%JHB^FjHcecVU06>m(G-QdA8`o_
z@#6X18Rw~m%*{hX3kk%;*tTGTV$?AQP>c^s?a4eGiH%{VYNgLjm7z$N?i%EBKbLL|
zQl@T=JVpWwV;}`Q1*-uZA7_3Ncu|1hzuXgx!g~VuX@jjq_e~{3)^M=8HJZ9F@qS(;
zPJ-jB3lpdTG@sM}tuDKKqPEBCw!?T%&BDRLQ?rPl0Z49LvMsG6$95Apc<Af44)_ZU
z2Z{D~n9OzOHxz(?UXYbI5jY_5@OI~^;P^MS5%BJwrHx>0llrL2c;CD+S>KhW5L12E
zn-`|)y8_krFhC9ko(7bqfsgx_2^_uMeBrn_z{}HN$ZdC%ZbzOpDR&Ta1dPA+NVEoY
zRZcL$kj+&7l{OD)rwt*`rr5G}b5pANYdY2Qhp_S&6N3j@1{D`mytpS-`}Mk|#$$>X
zFG?!y?Yh(pQ@pNUl>c@yw^)^5T1NENBcfe=-l|mj#pkU`z0%Hs7t4{Pjz<osIn)g+
zNsEW6yzAxaB?u0WCTGRvRw>tu%dJwbSJRsj@_NC1Yo=nY7hkok%zBx6aaN|6CZsc~
z7{${wnN?3(u2ns0A&!?`w3xzt^v=A&EYw}9r*WIy*s6{?sr#z(>7?#^1JjVHIrUU$
zYEC`p8v_68$<NG1nFNl^&Ox`lOlD@ltA6@KQnJcCtW=!r@@T{(Ou#A*(I)R@1dX)G
zYgr}LBe*W?I%u&2o?I&rhh4zn+0ljk?dk*(nFz-TWVhAIqpHz^)PO`Q+f}8&?}gOU
z0)C2-X}Ld4F}6(BF~Q6+S;tz{Qa|-A3=e^3hY7FlFOX0GJ1lcy8#u-bbBEzyO(2Pj
z<gj~Us_@U7f{q&?m#wMrIlySGNv~ZbcEenS8$gw$r4>U4)kZr8jjl)L?0i^e7iDa=
z+eRx!)Ac?&EYi9vM^E2^YM76%P8>^9Cyu7!Ly*@|mT%bB+9=yMM}vDn<zp6w-EtYu
zPkVXh`LNT)zhNINIo$D<(#E(Z;V)*2&#_tend4(kRl}WL4;2ZAQKQj=*I?8*OkwiG
zM6sqzz-jhYy>A93H5T`FTE44zH=~dgrT?a+BLtrw>VgGun!j~Wr)&J!TrSM}kyoan
zW}~Un5%Ydb)sR}&R}6O#N<h>0A$ZM(N{H6-H+UlGFlF>mQ$=Wcx~=K#bP5PT{xV0$
zSP-f?rQ_C0Q$8MDv5XFqGp#vXBRU2<<pT#HO(Bh^-qAWeBXs07VA5JY(MlI7&F`(#
zMM_`#oAQ>8t`m)sL2@xR_@u)Ni7rqXI-#mshu_?^k7zyVrVmYdJNd0aZzow9W#g>l
ze2Yx{^c<VM<ih`exWKDy%&Tb~PSU3D^gIkr$v6!L7h`3$1_!Yzfv2G`n<?kN0krEd
z<^3#DGDim!24*S`*HBl@R6?$WPuMuDB+x_7g*pYE#!o?HP~HyNJ*H%)W2Nro;xo9U
zp}unZ;TvSjRC=#9I8nMzl$N0n<?wH`$gt{Pqd`V70}X{;5Lf_8#v&jThS@%*qJ)Lp
zBF*m~kiHgW@>6)$H5@vT0oHKN#g{M^yfC^BC6o^{0tQ5)&yk@O_zdhbLR~I=n#_o7
zjc#@6bd7Fx)q;MLG7JPPz%x+@(5+EebePbhBkY>i0C{O$dKRO#y0j`d<*W;G3`&Z1
zodoFwJ0eI1UxUxfTzeZXE%Q^|aHF{N5X<l$Y60n%G1XRW@VS_h7aPq-s^Z!dOVy~R
z+Ek<wN5@#IreB`X;;%B8O8e0Ur>Om?Xezv*6-y<pK%rDLi8G(aytIIbuF`$a=qf!w
zVGA(TF>VT_($+HMSetTP8;n}!de*^I8Zl;=079&$SQlqSARZoQ8=~3BxKj~toFn8z
zb+#LDZmr<v8w$6XfD0RNs?2q(qT-ba#ePvD*6z;65%GL^?w*LK7ApRtFisFlimV}1
zx^e>$uCRfUluM+$kda#cXk@T02|FZmi9&@QCz=C+kQm;~a8+%Gb4Ck1L*YFe)X9%U
zGDK}+1y9^Qf}&)qkqt>dBe#?-el%JYRrp|~5`|n2>Cz`on86zfMF?$lv{FxE$%U0!
z#PC*5DAd~_Q9oPGSo$u4Xej{+cR^&MBxG!^YrP<CLuxC{kYfnk@MM&)EF34i{DYEi
zjQA3AoS{ghA!+1Dl7W<qx)O_$PkhJ!1^D9w<rT=G@k3WMb2P}+S!h@sOh;^X({JF6
zoxV}hFsaaLdn$mtC>f5OZd*fDRAbQ>rq9?^{%hpRJQ<OWDW!F8@}4k+E=_8fZ$bvJ
z=XBCimyz(`<&6jZWU7TRl4<gah-8`wHs_ld$uviV++#xbR8T(9S8v#UF7A{?$+-L+
zEIcL`D}_b=&6AXYHqr%7_K0+Wruk<JtCjGqnS;Rj!=rL(y=W37PD*CyoJrxx85?(X
z4IQB}m!lQpemPgG=g4@_ujCy=2KMWS%$!VO7-Bqf=B}aP!xnrM?kp?|$VQJJf~E12
zBms89R17L|e4?G;xrn#Au4tTGxl24^w#_9uVYbaJ9#ystK5_v}IRL>Pk|Mo>4dwwQ
zi!Nr{@FW(f9j%(L%;s5NzG+?I&sWZoF+l4!v@%bO=&TpiDyBLmDHG6m)Ecds%9yeX
zd2CIeNzLQPJS=1UmP(wF;dXa@Coc+BN;4WeZylY6k`JbuYg})okrig2AZbw)0%*r^
zP+hQ~+*31vzww^iFK4zHMFDj!){c%Hw3csZ%fBSDivsCDZc&^aU<|G);$SnG=*UA0
z-SAAhb*><x-kwuG%|y~uKi%LQdbH<hSrtyWC3w*y@Rykb+R@7V&(0^rI&bXh`YcmG
zyFLr8N08?{#TI3toetl}H85yFkG3>zvk&z)%QW=JEY07At@f~IqM50(jQBK~ZUy~r
z3|CW$NFL}GWh4(!m?{g2nVA%-Ej^hOsx6HIMsY1>`^Z}}r#G1nswJJ+MUR#=fSTeu
z#_X8#eI96L!t|-x<s9PP$0+i`rgD&!%$YU>ZWy4Qn(+P?B|pSqNP|hasUGLLee+xC
zfjt%>Kh?yPQR&$j&iIiz-Pl3O0!N68r4{=4qGlE(scx^-14c{r4g(=lu;8MR1g`p~
zrZjLJ{mKHLXk`XCohF8QYl}jj^aO`FOHP3H#agb5kc=!b0bGWPN<@~{(#}HR#smP4
zao*|%d?{6_HAMauA^;#n*E`@qGpG1S!hqmp=hh{rsgk>fV8KPXAPm60P%&Ra_+UX8
zSO8-+)(AG_h!+lmO(I;#$-hYX?WT1j!bMlN#4?g^)-rc|0aNs?*8r}=`geZVw+=aH
z*FvB8ZVD+v77Jm*VBl|Z;4Ml{m{wRrdAcU2TKrG~J4ir&#Wf!Uyr2cdG8VEi{4n(5
z07;ND%m(2uE_J#AJaMtt4cLi$>oh~A?B05XD4Mhf6vu0F0WC^0>)CoGGLsxQhD7$J
zuwa8HqsjeZsIu4OSus?2Jes^F25(1Gc(ehKtf^!=>kqWX|DG^1g4{s5qD(kRNgSDu
zR*pm>1VpnY??YhmF7OpcBNj<MghgqIF;jmZM_=yoG1HQTKSowSlUd*3dTGiaU_xb6
z-hm;FzR4nQgUChg+PdY?uB}^35TELm94b*5(Sjp@ufx_#3;<iyN(^v*wh{y27PW_`
z!XRu>^+`ymbL-RcPavfZP$iusSpfA25<BGsxY4d`a3?hxku7unn{3AMiuOcnO85Gr
z5C^I{C5BbsdL;}LO}%)ox2{UO2B?6h+$W}^hHaa@!WNDL6}hQt9Y;HXtmx7)6qgMn
zJ5~U7So&0_5v}S$04@M386XK32{%Nd3b(F%1sDa(kI?wDId<GC%R<qFwEIfK$dj03
z=z*hOCH5>q4VtR(8LRL%rTiJZa80($%%yG4|C(@Uw*9>-0zhXUK-1$lV<Jj!49b}>
zZ4}~!d806%`BZAkskA}dJn9vLz<E+DU|?!qtIgZSy?W)`#@1^@yZR6%j}n4Q$yEai
zmagVpaAM@ulAoBf>aPr3TeA3t^{go$mpQ|YM!q17CePzb7P#gN1BkTZxR;&SGR!n?
z$~ZP>;hJab_5mTj2zgHoy#YPzz;JXaWo<O}z%8blqd{4t%fh4wNK4#?o`8UYXrpUz
zfO;B^R;<s^>AfiF%7&<@Mvb&XAc!wY*JxwO1{^6tIAeZQr6d8PR0`IB+t|t^=D;LW
zmOV16gEBb7gvZpwAv#DEgin|?dtS=GZbSQ)@Q{rqa%lu^LmStx<YX=3MR-!O7I!w`
zd0tBGZc~47Ch9493skD9`#NALn~DZU`v^kUSQDwXiAey&5?TSx+!-qJ*{0b7Uhp=3
zV^m<y`o^bNj<OSqGT_>PjXfyECsK-0i90(tPQ{wB9`v!1uKa@t(-D`VMGiq>DVrip
z|83SSy^$b)P-@DKxKSv7c-c(^sB9$F=eEQvX_qVjBy6>ILJY3Ggj1domx(8MGG0wQ
zA*Hjmcy>wa62<pPhV)!slT5<crZl2`>sLm^!PU@GNfO2koh?<_3!QE~0MMS>M?x&_
zL7%^>R@H$3!rmza@UG2H%BAZSparc=IilR#6hi#(dz(R0a3mkwq@HaOK~c>$OiN%=
zY}+Pg2~eiuZelnKz-g7r_Ons^W9^SBHYb^Rx^`nxJ_WCAKqN4WT*CVJ#+#7w$2Z<2
zWo)Y(Tjd#bY+;L~$){TThJ5CBWX0B1H9+k6y=0&c0b-@;oKWRKoi3_Q$RjCDJRir_
z^Xz9GC?98?N+j}pR2juXhiKJW%yYNOG4ibLWx>H&-cQ>Ow%FHI`Vp5xm50RDvK5fz
z^;1PAc|{#niPGXjzTKvFwyl~aFUG2P$;%T}F?lrxvisaF&mM!BbytEnQj-E1stR--
z)Cj7Ir$HZ5rBA95RScABMimT&a<W$yr3O=lN2%mwVN!#ZRfS8bC84<K0aEbBYM-Lq
zcv)8*wP3YNQGJ{lK1Y(CtjOw8(LzS7c4-!et!ow~%8l3TKNN>GM=4m}`rN0f#4MH0
zDnV<`La?JAE35=t72jA1cIfSq(yfxXP?0;WDTnmvuFzrX+Fe1wsf|~CUh3;r!xuXJ
zvDNvtz*MVRz<L{Gtzf#DtCFw{R2t5hXCMJZy%|10KFZU963d}DQa+P9a={P2rGoPD
z-0ID?=T?lYwe9s3qf;9Ev0imusq=jHb%kgW5ou94;n2!EEFdVO-n^_VsH48wKv>3+
zPs<#6*+E*4d~6*;dFz`Q1Vz=`+@Al*$ufhaxc1EolKF+bU0bgl@Kr{G9PYin|8uza
z)+vX4Z&rgVYlT;**x>Eip8q-Gr;HjgV3w&lWasD#)Pp6YD=JR~iatysSs=Z-L`X{S
zwsnd#smp@~%T3=*AuPPEO+TR2tRzKt8yH~OLPid-Z@qGWzI7VW2Cq<QeY1lM3~y{*
zf_<`upwN0B^3t+2N!J;V1ne$bNNQC~`b<hJu42M$K(pxx0W;uVc47E1OrZ<<CnzyR
zUDpU)h_qE)L3p@T1r(Yndw;fW$t&5}Ve4F3vwHC3_Vsh?79;X=>lP#Ok_yy8ub3{H
zXuDe(e`7%2wqC&?FR{QK2&|~%izegled`sgwV6zCf0fAuca@<04;Zk!>#m0tynCG#
zaqW1O?tH+CIx8OBtv<F+`R(+^-~#dT+TptJ^4j5c@asTxL=HIJHz@Bdv@-Y>m`VPU
z`=R?Sn?8ILy-X+oyJgz?OU{nYIuGd#>8b<)cgYbX`h0MVGvbMEmoB`xaMmnlk8|_*
zEM5=O#foQj2UeW{7Pu?I$p9VPhYpRI&bW>v{S~Nz(WI9MC$5n9=(FlWq5;2FAM(-x
zd9|vq!e2)Cgx6P<`IX^w=D|3y*C&p}p<*+J=X@^<3Y>d=5I=$rz(tYEFh2z6#Y>Sv
zi^M6U_;poLNmpba{C9pucm70NYadeg<`m+^OQA-<#7IJXVaop=u}3}S>;NG?GfgZ>
z-L_9I=@tJjA8~%8mh;L>x=-zPqzo+z_;KMY<yV7RKg+QOUiDdyH5@h5(Tc@UK^{Xw
zQ^1~_{E@Y#rq=|a5m#guEEpZInBkFM!Zk}ypt-`s{5ljG)m3xIVB}a7L|UAJe|crB
zKy;85<~qqJodB?k^r<5NkyCy0X#hJ(S7D`yc37^pUQu3YJLy6)wF`>eq?*8jSeG=!
zD_c~sE~sQG0!3KYDl*L=t1eSb)<@{5Iq*6J7~8LkyTNY0D((i_(j|dGnTLKsU=D_1
z5sWDRCKyo`ovb;Lm`2VxmFy+(PhjT;iBTK_-SiklDdB#}+H$eLc6nD(KO|6{PKNqq
zH@yb0*j~a7HdI9E7Y~LD5Bq+}_y!ayf>0%8M4R8i?zv=dMctT%cEytzK~alDrs7_{
zBm>wkcga9*m-{4;fB`Rya9l5iY!R~SrLeAk>&!ra*P`%9zpy=SstNZQ=wS@w!}WRV
z8G&f8epe(PA4+$H^5tDb?6Mbwz!pKFZ>#C}cQ7t3aR*4jxx2#l8s?`5B%<;Ny!QIF
zkhgvae}s5IT$eYF70hh48Ow;v@t)FNvP2hv;qW)fe@PkYlr0LG(7`FmStd0fLD~Wu
zV|=pvBIvQ-3W|*3@t^@m`YjMDgr^079-}b>VNao$7@4l9JFO{;!qE?yc<zcM#ol@p
z1cHFJF4TDgL;AA^lIHFANa}7@KxFJFuAPTru50j530PWlo~FC~hMxN9kU_j{;2>g3
z8J!j2iJ}DiAEf{otfGsA31D&o(kMz!NzW66#R2Uxe&{ifbj=_vu9vy+X_&UG5SU|+
z=rF`I2gOf1yAUSksyY#s8RAc5GJW#IamGR&3I$svek&I{5JoYLG!*(-f#5lLM+E%q
zP>{EuN?Alen4fzf_>I3|z<jQ?1F|E2D36!`SJfZQCn*e=PhHkk9|Y0ue)0`>WQ>@f
z7yj!N4MxkSJS@T<UC&aTNg4PHrez^Y-xWl~c(FyPlz@)EA*&o*xRta776r5|7&9>E
z%4isv^On)D&~m?+yKn?{u96w-*=y&r5PfuiNLef}r8vJi<0kbWk}4JpOu5Uja0ZC)
zNlI|QvXvK-n~5KAFD+6feZ=%l8A334E((W+(!YWeiU_l4Ghr;@WL&r^4OPuu;3fbP
z_JSa>+<i`Djw47RfCak&$YL*04UF9j9|M(joNyNrV;0S1KQeio2o)Hm7Xk&~RJ_n7
z2*B(GD1kwFK|`2F>tgcKlJLT6004%Yoc>I33M6X$1Y}JiV-09)UJwe1Far?w0aE_9
za14;N<po=S#4fk{s}jFlScT1C{C7o&t?V&3rOM)8ZqHX`pSiFYnW5$xD|UP-k4^C5
zmFwoJV#Rzo7ZT;7gvhm1r~yc$Tgc`wRo7a;=S%`jS#(8?F<;MBcMC~>N5HJJTZ)m(
zc*@+tMNzt;;M}vl`01@H9T+K!i<AO}EJm+{cNjfgxTws8^f0g@Rq{wcdJJu1Aj)Jz
z7N)DzSte?_Ot4Jl^rq)lLxQw7$t_Ysy$udGluj2gE#tnN;I)UcPZtT|gzQwWJalBR
zF6e&DA+ub)Noi*u>>@D_HfO0kQe@M*>d9rot+xyR4o|kL03GANTrqIW>-9=7&rD%g
zR2=hzy$QLJNyM%|Ip!I=(2QAF(1m!+;)C9#r7@@36;Q{#XBWCMbE91$b`3eZ-t>g1
z!sWUI5FzF)4wwOAzGZ-8+jl+}js~l!GwiORT7;_z;i4?|$oSll2<t3dh>DR%P_RpT
zPS3kG7;;=)INA+x?JlhC*5Oj}9!)>jzqT~`U}hJRh2v7_*p7~)p*KODc#P3y;Et#<
z^dU}xfsx8SMP-pi0Zc*5^;;C;6yO#RA~_3%x=_obkZ80Er66`-_e2VC@Lt;*p=929
z8vz({5%^u4Cq4K1@lr6EcWw2o%IcLZj>4_p3HT6OK(_Z5&h;ZG`0$0*DnN=$oj76C
zLhpr00jrSrLZrB{$c0Ej(I`ZUYzZzSJ8WnaI89*WZ{v)A<4hQo3*CW;!wbs8zX{FH
zRg|<LjL<7rd{8u$D~`e+ETQts+QD&6D3X#9X<iBBa8$Yc2`!ya-h}{!S|*39xN0Dw
z1cP;;q$9{H%^Y#HUTNm=;CQbSCQYi|b-=*+;{DcehI(;4Gdn%fihy++b!i^{P4;>;
zo{PO8ByeRc3QRf;ZVIoA_Qd9Oma1i}nybJAW7XV4MIH&4;;ISJ5KiyTlWsihAVi<M
zT`EN$W>r-0IY44B0{R$x5zoiei*Q3YE<FEx!`O5>A{W)2rz5g6+@*bFwQ+YT)<^`2
z0!18KS1+&)mQ<%Jr@@fwm7b5nK#LL~7O$+K9=(*YkE9xRDLM#Vb0^LQV%MA@w1<M%
zyt4Y|6|I7qVi%70QV)#xUgeaO^^c4vSB;W}EGbuHZbSO22BOfkV;jiDWyCdbVG#uh
za&Zv_W^|dlz`W41?kkE>fxup$&|~}f@YY1-mE$E0vqb{*m}dp76sXJ9gRo<+4*B<k
z6|{0(18frN2=LgPjy6KJu@cuyux<`0gd<7WD|E^W=evA!4JFmwbsMD})K!@VFmy+d
zI34JV^5_xI&J`9-%sVfXg}}sf_nPFRPQ>{;)hQ>r;P;|QkiRr81|`0HG?+NOz#EWa
z>T)L%3D6ahz0d+<;S2f?_zsH%Y(p-5LH}{#bwA!*cWKIZZsEgGLx?ek(Z*<8orw9!
z<>piI=4va_soh*}!L;05Z{4!U31{)Rq~ubmMhuZ5U8Ru-AL-8P7>JWDUn)^4-3t!z
z=6NjSikk;AuIz`Wub!^J$aJ}61*GW(cLB6bl+AkykJA<UPRvd(M2rWoFP7hX3H{Tf
zkQCuU-33hbK=JyZBx?#*1GYd{ko}@0bEGk#kf|5+#)Es*FPUc^T%<14tLFlHV8ePY
zFo$iJ{|dk3K`}U%CS0WFvjtAkf7Or&>P|&v1puBH+bk?vaH^1J;}lTa#Jt>zokl)q
zO#0DL3Aacc)pA`42t93jA8m3aS8c@%=H<Fml212U$)#*@cc~`9IX+wY?sZ|7^mD2U
zIdXlrz(W>TIBzhFQ9vE$LibzjfED(Gk_=Mi2IJu+Lt-}`UaCcboW-5u`aBpyOHNYq
zhpvD4q372hYNvh(BWhNo#)z8LuyZ0Umuzp}AN&Dm-v^<Xo=k02TZ%IFMQKA!FAB$x
z3xiQ%u1E_;g}DmV^>%4WMd6G_B60Hoyn*@6<4^T5*3&)O9h|#0Wm51acNN47baafa
zC^trzCq;+(<Aab-0%qj&&LdJKL%K;|i!w3dJi>d=(cz5my@{Q9wDsP^PHYVtJn#cL
zEGcC@Q<ry29ib4Z?!TM@4EEYiiay9Ho+dPG>;#?ykdAyA);YEaJS-^=eb#x2DP479
zqCIi`U}gJ$0{4W^JGPU%(}tnbz0-!_tSW_<PhAO7*5HXtpYO^Qvc+Cl0k1<AE8wQ<
z8XSgJALU=cKH4RC8+NGQbzydIx_7}X$75rPS>AOQgIV5n7lS$Ox{ARdcU{H3>RRwJ
zPImavUCg<2pH9u4`*bqerssS-g15SJ*Q#QPbJx<S&>fnoYM8h*(;-gW>P1daGaZ^Y
zHB%HZ@zhJ@;p@nWa|NIE!54`tb0G%H1rXN9Svn@G!WflIEI5q~KG3?Md}Gq%|7Y!O
zdUnfk?Xda&6=!(wpgR)vL24QxHjoSg+c%>i6B~AbpnG5kMv{M@N90;-zg6yftNOH2
zK=&)2M_V6T+N7w(MOdYD;fy7#lsQc3W{}Z57OhgH_gb_{mBVDsAM?#WIS~2w8t?<a
z(bvcy>+30Ctfd-w$qU!U?`dMJ_eg^EyncBkDGAOxc#DYFex^9x#&Xr-h@7=JAh;tZ
z9qME8)r&HIEWUf3%EscWSF(|HR0~UW@l=wjMK<7>?-6nAI+G}k$fjBskw0jJ-@|C4
zv+x`Ex5l>jl#2&(V>7|RHq}CR_fRG7qfPBg{PzH=?sX9iM8L_5FaVj8qv0VS>&HZ<
z&rtzz>A=9am+G*?OI5H;_WqS;By($(zXByXUpSloOXthjF6Rr)(@n#eH=Dp-y^fv%
za;?`FbS11*(D{qBLM6`TVI`Exfv3D>#q&J{+8vJTr`NAV=+*1|$~<bVJX`1-T@mu3
z4exYKDsLHF5kqOq=!%fPZqOAWF3I78Za-M2K2!-y&xb1Id-d19h-bY1MdL5fIav=*
z_aX}PeX<*LEmEQL_gnp9ovnVc4pL<KW)=2}zDO#Xf@(cqoXErBi&X9_r!P`!!|95Y
zlJK&l(qYZcgsSnK!Q>nI<U5YQqFWv1(HIH|91hJf-einT?*5vY@@R<VH8ERo_Se66
zd~gPD`3Tv{D}!n{x+>w*3ux0E`t$~vzNZlTqo7PvRJMuHLal}Jz^w?|9;|{Zs0*;F
zO9CZh0(skeyE2gS;k|(wvECb+%AlEc7cOzGpq%&03KRRwHBh3ja1F#p@m;A5Ne@J|
z()pDOtPY0CjNs~^6LthwM`s-60E5<h_XWJwk12xWK?jM#H8QIy?$r22jf0!Gg&)*A
zdo#H<%swx^uY~t-80KkZgn!BH+Hp^*)QLrHm=b(~4)6{l=eU5YTVgI=;2m_=m^ox|
zv5A#?>eC`#?13;%=5v4k!gRGMsx1nxuBo7!OnO_Fs(37~#+AsG*s7^uoh!oSEFQac
zH_QHRj9H2Mz|D0f_~sn1TV>S1*+79rgZ`H{kLz*WJ+qy_;YD=oBdNKjf|dr@xiTAl
zmXGe&`J#{R*J&D_gB$iAl~B0`Lkn&ad8PcUvk?J-Tf*6jpm7?xDXyem5RI)XDO3ba
zt4WWHi1q<Ddn$?jGKjKs$}CQ_Rnq0m#%poz?klP88qXVqqfKR2y-+hN-~<LR1=$F+
z3tyYbDw)JpAzkW)hgDCyM$MJ*CLHHVXc{$vEX;?RfUkUMO@oF7q1>iSOFlc{`x87`
z&lTZ0fHf%zxnNC7LXObRsk|B!e7>_QFS%e%%1lnrkn(=aWDcIn6+*DpB*oJ+kwI%J
zkLE-Msssk%DX<}wHf2_pqp66=SvmeD38yAf0=<}|iR3<0DP<<8v!;SIXXSgm|A!&2
zKUcBT=|oza7d|yXf;AN<$`<+bzf`ZPA?*xwTxhOIUs%$85$^Qj!)8Yo@fSqKS)K}f
zoq{%*riJh(<GdW$5lAOCg>5noQm8kK(OTi=7D~WviPdHz8gweMcOt9ri_+ubFBIQI
z(zw~Vwhd2vk$@Ayp|g|8V<K6|3nwgmQ{oL5%f1LntiBO+dDJ(;E|2;~*risxy{OCL
zh2kgcN~*(HPA$|s97Y<wNcrtdge3LGLwM3`THLmX62)7rbQk<0{6+d;Hab0^Q|eQ5
zB&ty@&L}iRTYqM`hJ?E!>bu!w3lb1C+td(%q-;~K1xu<;4g3g~3tt|U_-sRO2Cm(v
zB@GiIk;0PH<QVNEnlD#`*H>U3Duur!1m`LZ{xcxCT6kkUsqZj#Fh7U*DJNL^Q$0%p
zaCDZO%Kff`QRwTMV;~^L(Z(JxuKSe~u3Ou*4r`ALn7{lWVql1hl!wA0#)>(K>(*AR
z189NQF{$9pABP8C9({)hGwQT_t+dcDyae^tn}v|CRRUMuM}U%$_%*%oAY2IsJn{Bu
zUj9YCi!?zGB^3-2nu1ywSAv}}K?a-FEry4;7usX9LhVB8V`jv0IQx&-o$v=m213*;
z#BJ&j0}5|SuLMg7WcdRj2G3vQ(c>ZDFLD#&oB&C7P0Awg7)NMxk$@({Mj&7q33`t>
z-QW?4Uf&TikKjtiLFj>~dZ#rvD+GoMCln^bSwqZ%0%vfmkzq0@R^UfhyC8jFbWTbt
z_@k@YjFBZ(bP4KpG_6=LErdSv;0XIjP^z#lnlG!47sIu@3N-a4l4*ik?TvQ2l6s83
z*X7vEpeYn{&KOiR$tIw<tGO7u#yj1)7`nEJhnWaCePg^P!b{&cunADr8!I-EBOCE#
z^`QAB;%qXs-n9~dv3ldwCgbK6%XTH{7I_2SCZpsT6gS}}edFdPNE_eSx><Z-2)}zE
zVMHEh7~wXqPY<KuU7sEXu)8A2=VD-}l=$*2ao`9;-%`#C957qoj#b%s$JVz4Y00h|
z4x>ca+IEdH8CCZCb`hkr_d7@|dT{H{g(WZc{VS<hQrVCU6yJg!Pq3AZEkkk@|H$T3
zb1FC8<8wnDZ2G$A25oe@MQgs1(`{^^YbHa%w{#B@!3|N6&E4sueX59Q(uaUi-<wCC
ziu&I4)XvQq&@Q6}p5iOQ_;!}+FGUY?aHjBK4$crhOglu;-Q4pE?v|Fx*lv9R;A5uu
zyd)JCyI`<w@M0)w!`wsh)f_x1E|$&}z_N{{TdA3x%VTMK?}-O*lqv#ViUC+RUPoNX
zLb#@=`eu2q$9k6lV&2xf1fYf1y8>!guE8T2R^eFh3cwaz?+QRTw*uoQ<GGWb^RCwl
z=U((=O+f12@cRj}?IBjg2|{i}@u!4AsY+)u%W?ja0bD^v#?#zjjJGHmCxg7_dEWq{
zyv6M}cYI+km>WT>x|pBkdw&@aCOPSb{=J&@FEy%J8S0xv5{?px9O&|&i~tt`X>PDc
zY`tc(NG!c)vPjfhe&&8@B;HEJs6n%HlSD#m!$~BewNZe?=ViH=P9g~{4sg@IWEm5A
zLx*mPt|Zwcl!I}C_5LO1m|j#KtkE$IvI`JLK4lg-5}UjvA=8UoqJ61TJ!xMm-Ja-X
zV>0-BfEoO&fOV{BPwI6zVrg-$Fzfna2**4f{L4ev1QS}36fBd$>chWODuS5(rB3x@
zvttOq6*caJJ|6P<Ur7<f;JgOJ=Ai5TDbXqRnzvG}TX^CpY=M{G=1LqCII2<+uW+DG
zpI=CHCZpenj76X5nDO`Mm`R8G%lpH3L*5@&sc!Wz&G=X9pesPP-X(w!=XjR@2r%qj
z1F&X9Wi;y==XvRlCV;7lh*2%_D804Fqx9BFIzX{6T}kpN`Ikz?qvT&Ik@*RAwuql-
zoFgg6%NI548fn;iD^-VOFd{?9l>qiWan<xvS4|`q8H%-<fYKKK)h!jr*7#DRj%u$T
z6}gyS+N}xu_oe2Vb%XV?cU{4){tS9SQ&c_fUuvxcbiI{wCz*}{WF*M^w+|%AV8-js
ziPSPz0u=&=%%KRr>5-ggtO3Nuc>R>POdI{(_@y8EyX`^A*SYOOjBHx;X+J8Uagql?
zsiv<aUx=9UCvwmX##cTQDCD6$+!MEW<8?BUJ)u(pcon!f4o5h(qR6%PzG`soy)PPc
z3;li3wTGVZ`U1VE_1+f^Musk{-=VHLq6kuOiXD(n90%K;)IRPUucWJcX}P?vJcp7)
zbn-oPU#^GOYX`oGq0|u*7ng%RI<i4D`Jba!)_8q%ICfqM<{z{b$-UV4++t(ouFeb5
z1Z84`NVz_m_B0N-qe;^T%yUJirzHEge$lu2wo+Zwn^xE6mu9MK<4ZI37Da9O_D-)_
zz0;dk@AR(GyXWQFyrQJh<hy3MeR%^#9ofFj_<ga-`-y{XG!U2Sn;oDIMJqi~!<YnQ
z(>S3?=wvYs%>tOzk82iQ2`8bb*Od<Ei(s&0AZ$PKss<8%oTVvvCB_aWt1T!Qo)XO*
zpib{!BwZZ@Ypl9gWj=Hjr>zuo)LVGjX}?M|k40AeIt_y~_NRZDnxe4nU#6xc?aSPF
zk?sz)bp>&V-krG5H<5C@5`BBYW?~UvCV~=N&QAn7B*tI;Darma)Lb&JmrfGpzL{~K
zyY!bF&7g;|7<^?E@C5qre*BxK|G5ACm;duerse!}WKm5pn{xS*{>y*-@t>Z%RokcP
zumAs3{eS$I=TrXt_b22%TR+xyt=i{#{l~xj_4yzE)1TU(+NZ65`A^UP{!jn%&wcto
z{g?mxAOHFP_?Q3r`JevfxkvvMpAmdsMnAjVhks62d;5=n`>%ie=TE)+@cQ5X@Ym#l
zy%Vvn2lU5ZlhEi6uF5sEKiJzF$~C|1?LYmm|Nj5}=YRRXs+WOB4Y&1a|MM|!9`mDv
z{$@9k5t+Tbfpd59{X{QELAJl?<^T4-{44cx-l?2-3dgz0Tt6SI_L<fGH#<qIg1sCF
zW%}C7|F#m)2C9U>>F+B6-?7s3`_~^TpZ538N8M<AyT<<2Kd<#q|Mf3_`Eh4P%j|HO
z^?l#m=Z`ge_x(4ghBx0F<-G=am)-Xr{+rJ$H_1Xw?B{_60HEME=8e^W{J#CDZYbXQ
z?^*Ak<KJxiF3Xz|`fo3$KYhN$T1|id_%5Zzm(lh8+iQX$)JRIIN)-G~wE{}LwF3U#
zZ!3YE?yV)Zx^JuDo1^J}<2?SJ>Hk;+KJJCu^}Qeejp_gS$)Dg<ct@vXJKv737@ogW
z>qO6eS8X8lN!2L$oocWj-fGdmEal&<wkP(Xe8+$9*Iujt`oMqVQ~Ia&kF0*W)84Vk
zzxM6eisRv}Mb3wBD}g!ZttBd*@2VN-u2jv$fAwuO96s~{DERwS*+<^}rq;c-N&DM7
z;79xU7hv#<zoXmZ4=iOv%7?ew+<#yxGq2WLO<2Bft0ffWtpsGscU5{NMR=#5g1>hM
zeDv?|RUBo%HU0m{4geLR28Z(Rj1KoHZ>`<`z*1%^__vzEi@&V~rkJ;ysAImZ258Uw
z3WW9fsU6TS6zXq(gns-3I^fJ-uH-ZSz(PiZxhlE;fn}T_7OJw_?<@N8D?LB{z_+m+
zi|=P=zsu?GUiFvk{Wli<KV<ZrU#{Ns2iEQvJCK6@-G>U7kZ&~!cxC-}%*efapX;M9
zeyoogoxf#>{M3}Blkn{(ir<dylz-^0B*C}UdawJsx85uHz9JCSUn)xSeMJQEf2k<R
zPrQbHqk;D4YjD1Q4?po1m}d4%PbK+&h;VOysVK?!6>l{C*J>z#TZ#E#-)gVq`-;HQ
zeW@tPPrQj@o%`J#@pGDyj7?wqD#`bQ+`l{`{`JQz`MzSgDZkXC;QMO8+JC7h$+s0N
ziOgG#<)3&HnNcUkI`g|X@lz&ZhG_p{vAvS-hX?f7mx_{nUlIKEUn)xSeML9~zf_du
z`-<g8{!)*EpLrLTBDjo|Z{Nkwsm{KBwb)+Cw?mvrlJeD)Ldo|Pfu8uPdMWw7BKYgS
zRFvfViZQ-c%F<7~hrHbS{XOwhM&miZT4=B2+o7!rJb3F#@O`y0e)ZO0$@djk`_)^2
zCEr&B{neL>lKhP6bfIngclX54*-qCv`pbp(N`7Z)|I!ZqrH%QQAHRO^Z+__VRrLOT
zKGLTq!QW@zd}gZLT|E;!{f5J3{>-PG9R+axe#-MkN0Q$gVUfOmsYe#r@2gcL(U)rN
zd~>{IwRZL|TZ7>Ds?o!Vx6r<NIRE~a&|>}8@#jzDA9x9E9~_J|ynVjcr>KZbQ(r1B
zULJp65g7e16{r277QyZMrJ~qgzpn^_=l5Oo^%DmFmzQy&7{Bo{>>qg<t>cib5w`x_
zF&h;R=*3izg5RkIpwnB;=O1ZpcQ~q9ZTIgS)vN{%ExrYofAS@q%SQTJmmoj?4h|T2
z-ocIeM+OI2&|6J7p>L}-hc}DWnt$ibLbX7ku&RX;ynb6vZs2+Y@iSiFOL0|ZW&C&c
z0<)KU|7vi1|B=D1@ukWdzxVSC!~9ZVoNul_QN{L`3budm=WrBbuD|$+|Nfc2k)8h?
zy^ZLhA6|@MP!xPWFh_!uw^|Sl_H8xft$wR1k@dILz&i6*Tk%I)1LY6rpXHx?1AZyG
ze&Y@N17Ca}yiVib#<$mLtk#`_L$&T-M)#Z50L^-<39I#8wS5{)Q&gkicd7wq$v43A
zPriYD;V-}OwfP4OpuNYh2DiVxh+{RxdA-$E`!c%UtoCb@cmE-acOwY+t)?up-&R9n
z6uki@O8L1ra5HrL#vb^G&H-OMGn9OLU;+^8OT}066Q{xpO|Aoa@Bf{>Rvp9_U%L85
z^gF)XUrY^(KjWyrK|ve0R^NJpe&$1F2>$=l)i0vo^^pE*0elhtj3f9)`Te1h{?u|s
zDx$CJ^%Z^Z*h3WK*Q&4RXPkRCinjlek?x=ID}f2+OLxDBe#e)wf8lfZ>yKCRGtRRc
z8}o<889(Jet2n~1y?sT$;|hykFNQCopSsnXe_rGFzd}D_?$LqtwX?72cf9An)+E3B
zX#eHMfAjP|GVUDnpYG`IJ$#KdE}vGt>|YQ2|GT69at*)#e8QrSPwmT;E~WHO|F5R!
zJ6P(y?f!p$Q?CTj{i#;&Vh9Fv17jXeh#LUp;dOe5`YjN?0Ck7cp8~-471Xf{IO|X(
zI55)TjQvR<^OFL!ST_mb6*K@+vT%kH7wdXBV@1L+reL@#qUgg(It$MAD?purZZV{w
zD9XZVs|47G!wF9ZWm$M32BU!E;fyT=fmt|QX9*+?WD|X|ymPLIWe4rR6`;+P1vIxX
zwH1993nN$zalnZr9Ju#bm{>-s#Ht|?a{})7kO!pr6rPmS=@aB<;beOQ7koIQ8H&as
zoQLsnOuo1dK>QF6hh^nwyhU`&@p{RL6M=p)z>QG!aFStyg5nC$Y~<vUoCBm4;fRq&
zCd+U|#6@6a*}%c5h~kM;qaq|9tn^oa22KT)hGOZ#vKG!58esLq87>Dtk1J4>gDU9N
z>F7wS!tI2@?oTy-1=XulvAwYg@UIYpCnadJMiiTYxTgyBu|D<H{s^j&D@xgg4<brq
z0}^!%-U@OyoI2-ko=#6;*FJ(ORCjSsdw#%U6AbzPeE4IN5&2B?h2j1H0)<j5gTp2E
zX57+w-6wcp^@ntji1-L4Z$5RK8JlRi0~+ZNVF0iku^A|I?uHA|2LQ(w8v$acc577d
z_fwL5t;jQdYRAWBR1s)wLYb-0u5Kf&=wN)YxiOEU+l3*$IX$z04mx^7hPLDA(qKdn
zk^saeg6RZ0RpBfrYN;_G39&pOFycW{pin076Yx}V+n&HuWBAKC=rx0y&cX7qin>K!
zf!O3{JSPW6*EnF+u?Y(9NGTATkug_-jxjfNj+{}ey+I>wrMGTSNdSO#<Q#}%J9r?f
zb=CCDdP7YeDL+oUN!T0I5}1B(64gpR8gJTma3sZIY~+=c^X{;v`siH&n;M_dtx!7^
zZxkX@=*UtUZ$9}}D<M|sA+vPhM}*?-n5!ET-5`#xBbp$Vvtw1E_U6;Us`nAqKcWlD
zhz*LpD`BUgkJeVJt2F)EYIULG+@BpeOe47)I%xS~DP{Xj^_peG_;;{!#ae2nboiAZ
z1#W|qT1x#40<b80hX<nj&X;n`Hz=w#^&DubrOfn50(&LM;&VmS=ZPQOhbpNs5~0Ro
z9_t2GwT9Y7LWU4&L`PzXSVIk$#uAG}2c25Eg*#$2V~M!yit3#kTRwQ@O2pk;me6Q#
zc;(8h%sjCn^Z$xgmXTN)tc0<c*0m#V?3DnqKu*6@yA_xkl|}7=r24Lu&mF36bv?MF
z`$|s^2E0i6p`7|&C5{H#Zeimih&JTLx{_M7P3?kv@`~7SDZQz@*1br)uLJ|CZ)8ku
z{9;4Ag7u)BT~!*5-e;9Cu~3HM$GDR0EYeH#j5L0-%zi=HDYL@obb@}ko?9v>g!1nl
z(RqRF20a-SL!=tFoG(y$2|73yLrDler?*dOGw`q@zB-Vxrz6R1h<2kF_9Dpk-!q6i
zz@2|f84?*H-RSVI1oJ5MUK&eDoI0|}#+({j#WY3{);|#Cq7g4gM;Lm{$p=GgiKwF^
zZaqLi|CA{A^wd7?sk+2A-$CygWQp%qx+6s8(Gf%+$qC=>w#lsBNH`nfXzz&9|42}(
z8K%M7NzZsi=z?|387W{o_y9um>mB)QL-gytm{gw-7f1)$YE1rn&1zHA&|%7b*OAO6
z-UNBwMi%iYLB`rhj`WUfwf91bkF3+zIC>(FUqcz@L81`i66r`-`;nkj*Ic2eLZ^w?
zyx%1xQuA)mY08OsB{}QLo7h1Qc_nNWhF=U8v+KN_xPn|^q%rTHmAC>n3?)~|As>ip
zbgq_D(<#SfM=IM;9?C1p*E?ViKOMXmA%gS{7RoE(7#$<h?kqlyE8v5jv%fSdsJ^i{
zDri2@pLcLo2KZ8X=D)cmI14(cD?{Ap9RwgTmYT*nP2}etv>{RC=TAxUMQZ0GswF_W
z(!pUJVn6R7y9}|P_u|5SQiQh0NBs>N)g5@<5c7El^<{{(yo234inRQJC_87W1?48<
z@{Y{50sfYbEVd!0@~00JYi0*D+2C#BmDFqPY6iM&bTva=2GW;~YuX`W8eHqabi5sj
zY(uQ&y%O2RXzu`doeZ@KBAZ*rM+W(PLZmQV*UQ-8Pl|45L^s~?#zP@W9jhXY#`3^f
z&14;qBnA#8K)!-pV}i|e5c-6LTH0A+D+QH|q#u7E$;lP<Ovmo|NKmTLxLPg!raaKS
z$cUa4q3@2qYeOS3LWoPeSMr2VUh6)f<V?BUJ3e1^Ip6cs_9@6d9?)-M7VpSBbR``B
zVdrEaBcXEGQq!s6Y^k?6oMANeYQrX(>#islljv_cI8;N7<h{~pgb2wybVwv0PM@Hq
z43nOnJxle?fz}EoK<~+%8oDa%NJSFGI{rXZT^%S@FPVv@gEcFRc5!LtFqy^7w{k^n
z7g|viJRP*FVcf(W`AV+@pNo&?4^ygv4ieTYLd!VWSy$6goYvJclqWLMKPAdVAnO^V
ztRXh@Ugl1axxB+53PE@}t)?rgpVaT!b?8bF|8%4=3bL4Yq_4b!&AG=Jupd6NfFdM1
z??}}Y;tJ}ZW{XY_@^eM`B^HHHhh>=(On++2F8di-tgd9CoW79|6?#X)tPtr?2f1r>
z8QDnS6<tR5gqJzG3}k@qQ-aA%)h8yR4!b`3R{x;+IvB~w8WG}0?-Poz(`ufj_e5TF
z1^E^`T*^<1a$)wRwxRm^QricU4n>W#&Mo6Zw7^vto%S~lO(71Xp2w=_^e%U#&b|_~
zym0dC?;#uXgwcnp;asQS;GWIUzs#Ga5Y2jLBJJq3wQ**>0(K6r%RW%5j@a7<X4~Gb
zLHBi2)1~{msb#o0JMH!b4=0YA_XRAd$8PvRegnkT-q*|$K9TSwgoxVvLV~RnVIFac
z6J1jWbLExbvjF!;h?~9BM-rXXKOJtAk0eVUH7Itc4zk#2vcch$NlAG+uP7(F9kmNx
z*pAvQUD#x%Bl-77k|i*uhghPnD96{}cfNugUX!W5^1#?+s4qA;TYYEX_=+YgyfTGH
zqY(~7RfzfhO1yqi9e+A<hhGtPHt1zTki`yq*=SoWL3NUg>I$w+(qx0fAsC{I?{FGM
z(`JWbF&h2Sy_}ErAT(b7$!N05!Ppw)n7@Kt22EBuXkM?RJ~YTQ7Gk~XyDG5VjuFZx
zPr}(C3s&DedNvv08#=bZ057iE5G&RdR7YiAgWxtLa07v4Hrmj0p+eihb4UKoenWq@
zp}r4%8k$UWaPLN=-?{^UaV7Xr6=83PjjO}8{zQX`4wBznX5*z%o76q1fuqT6-_V(@
z>j(tG;UHmGuWN;9a$w`)A(|Z6xS5EC?f;~x-jQr>P{v*f9-IoX$%75bSU>V$lUCV}
z?DXwf!Uq7%%vXYEIzW|jR@c=IK$Q<98KHf&y}=6YN9Ob{<>%;nKHiVK)5Xd9q-f|j
z_aCnWT{+dTtm%EwZaSzzzv@TS(H#lluL$D<|EeE(sPAQ7meH&?bR8D?lcJN8lJ+;K
zRsF~SFKX2*U@P@$zY?|rE-^o{zrE~8KQf;0RcDoJ&fL(I`K3;v4jrkuQ}si((T;1^
zj|8RcoOCS+Os}LicU|m0DPhY*&dTa8#?qAFqwh0IY_ytprqeD_ttDF7PJph=>|!8w
zk*8fjy;6H;f8o7q+xfz4m6Z)vcRzALgG=;E;3xr6=#{Xsoh9sUP=a0w+u3+S@<<m2
z=$$H=*}gF-+S$HqOfs{J;4>xl1IK`xz7YT^ToK!LEL54}N!{roW8BNZdnFuUc~Gwe
z-w~i8JYbA_xwLMXqYj{-WoUc3&OBsj1IXdZ6VZY7@PMhEND&X&(14P7xIPko&^dXk
zK`wbEcx=?C%fV;WlZ`Qp)!U~7%yLDTD4<z9WQhaM;z1Ib4nT{G%kJ}_juFT_k9zM{
zvQQqVgiixtDXx4IJ#i^dO0dy^Ou3S`R&|heb&O9z7BkXAc)S)fpet9zr`A5a5<Yd{
zy-ht8^E-(?=}1`NN?g(Lk5_`PLDhF<vgk;`=OpTTuB2v9rgmhF`YRWE&^ktTjw`^2
z0T7gr<U#TNUjFLXXinB}Y&0ihI6O;yAlP3oII4;@S#nkfbXdq)9Z+H+Yq}6BUOb)E
zvB2wZDCNs{8OyoU-K8n98B&5-sWf>X2};=up`bcQ8lChry>_lEKSsyqz7lo|``?u^
zqvIRlF8B0-QgiLU{M5J$meGM!aVFO2K&rUQI0jV3og}OsP?am8y<C757pSU(($bx#
zFyJWevV~8T_)y?;Tqvq58mPjjrY3Y*!AR2ME;ASmobHQ`{sTqmvV#v4A@EeaG84MX
z3I=|~otE&^0bp^LDSQ~$A@?+NsXNW%kEV4&ta@qUCq?+@TB0uBG&H)qeA9>FB(k3i
z>Eb@*JOb9m1=Z?Eis(u|(qV+Sa*cG@DekYs`eVqr%M?CPd@frUwvRhZ;R7A#Qo*N^
zCA!P<J<xIrf9Zg<TnSr(nsYg<iyHPx(Sl%Q310&sU)*UuAIEUyug+GRF7Cki<}Pa*
ziKkq+tqz!qZ<)aWsyL8WPl;9v-b&e(EpIifXy34w4Ys!{Pl~m=0dzsG3<kV!x~mOV
zzHhp#ujIb_O^@{z<mtqBuqi08O%vOYZp(L|R0DD~+;comJ!3$)_;x-M3Qhnm16IZN
zR!>HiT6GjoSKnJzpuP4+Dd%3ChK8fwm2mt}U6m;Mf#{&x#6&`MDSwMqUP#|dEl<qs
zLaEH!J=HXH8(~-m2+S31OybHC8(rxAyeq<R#CE~33}<)WL%rJQ#89_3UT<y5r$p5e
z`|_abiLq;*1$L|6$d#~bUPpi{V$)E3LRT4FA6L>Af0HY#t6}HL>TEf%vbtJ_Zrok1
zLq7_oWr=$6@+3SE)GKU!?!g$Eo_nxV$}+Z!T=(77TV!eTMYGqCC)1gh#=u|h!eAK^
zXI=?^v9bhn+kjZ{MHjRIvEqv^=qt(YuTaZShXu=eAi7I%g__364+(D!pcY?rK^q)_
zR|1`5@DyGV8#fG+K4=3&yf4>-paBWrvh<DKxuTV8aG?6y>L1kG+J9!9>W%g{oU&I^
zcVpIPmhhDUZpGJ9*P!0kQoB%Z%D;0Z=}>fGwhT_=D`C?UQ@%JNsJFG$`l<<^)MW+_
zwy&wyar9FjAM4O(YpBl~JsflvSOHdi4RsJ2Z4Gr08f^`B5DE>B<d3Cg$e8L0%Cbbg
z_@Wc~mTSIEeS<z*rgkGsKq?v%w_Xt%g@O|z>q=@ghEj!?cD0Hl-Rf!;2e{QWHmJl!
zv-?Ww1+_1=a@t*pE3-PHDM;c9sxNdw8!nta5|lD<^=RU8W#t4{nL)M9qgJ5WCY{iR
zyD$e`&Qqd#FxxFF!&M<iBRrM?D&sTQu9f@sO4x8ty3bI%IL*yaGxaK6FfBv=<HyAX
zV94!pC4A7x-n!-uYEdApE2$nkT`E^pUEUf5)Z*M6L}|sj)iku?gbDtns0Kk3+;D^I
zbE|czM&(VieC$%g$Vu&UvE|atK9`z?`UL9B4El2}wOi-MxuiCLrE#TRGTRv9RNK48
zNHvb@bSE(ENl^`PqG`{+`ADeKDMb#@j8EFuW<ct=I3W$`T(1NVt=<m}2cFP5G>uTE
zg$a8gs>MwAv;jur%J^gnq`76bjML^cv<w||1#G(>S>FgNO*;FZS*(6(yCYNll~_V-
zEWsVFWKf2L^jCsTAW@J{+R+Ah%#|Q@mH|iN6JBX6q=`?ur48s9A9PC_&@ryGQdg2z
zstX@>MS*H;z3iMTK~p$Lj-$5nAUWi#Hb8P*kTC;mxepoA14?q#s6Xm&xZ335Zn&lr
z`fpGX0}SH=av5+-9|=l1k3*j7E6Rx+Tf>F!8(U46?i*6o1F8?;m8V1%aKG_`+`~$6
zWgoc@8Q#FbxBy*OQU;gOTN%J-KDgVEb<2m0X3T{T8P1rn#|LrKSF}-$vjWvOW|r;)
zv>yS!yOP`LlaiX|p=P1>#!$0ReM9DWp=DgTwH^ap#s%pz<O}ve+Z)grAF{s_8skIO
z_W<C*hpcZbUKgaxu;hKn*q#kzpskI3!q1i9(X$k!AX`^Z9qxKC6y%^|+K?W@hZ6o=
zQ4NCjcYX|R5n}>y#)0ZGpk{8FEqCbq(bP1Kh(k7deRJGop-;F#jrttOnJWNF!~mVS
zBK{<of*rM8ujfkGbbVAE#He>o;LGbmhgp7_U0KEqA8$9A==j3B!9<_PnC%v7sdT8o
zU<T}ro9yuk6>6@QN`*dG#HOG_&C%4#zd6D>xH|D-26&B|OIHA3<F?f>bg0S7F9qx-
zBOe5?Ze`>@mpQzn4n7?d$4!%kK0QnL)&Lgc%6?{(=S`z^K1=(V4DSi;CpehFCUTp4
zFqB_eB@aaP5+@&=%Fm`|Kd@M2z9SK`3pDl_WBq^)!~04KHG?gA1$=6$$i#?QB3s;y
zXC5G1t^^+|AX`3?ER|9-`mqg$v<tOmOl|DSzGf8<;nwv~=rpT;#;MQf$~L6`yb?NX
z7Id6oT$U+A-I^MPBh=E~#?i$4(L-@gB#O({yoLI!Ub|pdSCY;3(2s9xT^911_!4&6
z$T*654-FjZt;=f0k<Nv?vO4uWFX@ZnWOyZL8z;LiyBg$dSHi}j^Sbkj)Yi@-Ha7q*
z-f1xd&*EJsbKzNBN#tx%Eefh-3u>{;Vy=Vu6>vmQi(N+ZqFQ9`xhtswNChuwML@M|
z)f3n(^kRQ4W@J_NE{hq+7w@u|7ZjtAT2@$?E65CsCCSCuVKT!Pa?5NSin33Q8JbdA
z?;cC9iwo^#0KQxaJ~g{#Y1QB8yewv<RDN90E-M$3cbUf<Dp7g!Y(pi2kjemQxn+8N
z;Hz>%xhz30x5#Fo5S41r0CKq!TpSvbFkcayhDz)(whIa4!gm>vFwXRRRzR31C2SiC
zu{X7C7^5t5I1s(dBCp`hCq?)WZ5$EBiemt>xL{sZKo)PZqyc1kyd8BK3a-((h8xwJ
zbnRYQ!e<43*el_;3clJaVnfhpO`h#t8t6*UPPvh;02i58RAZ_d&}L1Z?Oo@=<{BVQ
ze@#aEMv7n;_{)fOX|k{hb`fgJ0Cs8nOQmv`HaWaElw8{=<tkIoL4#Z01<*3M{=MAG
z4@7}#Y^i?0M&LYc3#FP^S?LuH{-ntH8`5L3+0uATRyy%9ZK6~?*Nu}A>(b=RMlie!
zZFMCzjq+t9ZSa*;_=Z*5;445^9Ez{WqIM`hWkWRFHaYQDPl~FG@@E%jrpdx4W~R}?
zCS*nl6pa^Q-lVGunQ1b*0h?*Exe1ABG^dG(X^mJ(yO5X$YZ_O3x6DVT=4>*YabviT
zEN7o}s^5ZV8K@k#@=qDa9`=FhTx1aY$Z`f4W}hP!0W{1$a&P+r>6vyj@G)1yws)4;
zE&>v+XhCq_)Gf2++Ba9iS=%66lPO&n#rp^uawRoHnbOGhv6VRTN@@VKmHqy+OyIf;
ze^SKm26_iicipLH8J`5)yKfTTT3yWVispYH$wVSbMrlC4>?3D4h)}k&-x#vG?(^Pf
zB|zp1*!ID@r!ftn!9H?zNBfirwYF#+p)@#BlWqaX44{^Mq<jHt*@Ayr=D6HvsB6eq
zxsTl3$RW88jc4R}+(#N2P?(PdrE5{{BR@A_FjvC98D?94?xGI90=8RUkY^u#17e{6
zhEh$eJlipHH1cc5z+n12zJbwbw*yym3IAAaiUJTHiC9@;Hx_4KUTv_md?YA+Duiro
zK!i5ISyzy~2qCMlC}%a~)Q-|@SHgyKZC(MJt>ycXpp?Vhf^QiBHCKX`>!^1H9Gho}
zjg~^(5saTPAZWG#U53AQ$j*+ao=KfXpl4-iKYvlm(JOkNQ@xV|I|ALKIUe=T?CZhI
zE9<CXcCG|p2h89O+2X+3?2s{DZ{pb@V;pFk9kj)Pwb{aV8L&1xV2cB3v)_cLmQb53
zK+6Eu?2zpZV9gfh>t=oJxjJ5d_30QCjPJrN?vTqG(8et=mjV8`LoVxrNIogz2n;=j
zy`9LK9r9QMS+hg-H;^?uUXL}PH9O?7#+Tqq*!HOPAd4K|lPf7N1fVrnz{bJ*NcdQ$
z;zb>NXm0x6PZ_55!C`X?E@t>1?x1m9pVUjN$(}(UhRkN*a(5_r*?^nbN=IwJ&Fr8f
z`|K>RV`cwsmlvB!jJHdBA1Fk@#tcxJ?Xtb0#jb=cBhG$1ZSPay#_e)!mm=IQ^$p<k
zb{XU-!J}~k{nZg1K$(vOCD56&U(kI@yk%uQJSD;aq5NE~ZrC9o2}(KBzSXOmiYwtU
z;XwB}4e`-hmTJS_MAkKn8>N~-I<-fdWKT+JmIvT6TUf9G#_{b_wV>sQ;u^)}a?5ZW
z3|Obz>9QWMU_TO+a?a?r9<YJ01kW6tvZ0<prTNhKpw^sT>yg0^x6Edt)?Dc70ffwU
zV^b4r#MIKP0ht<_SR+DLj|N>RXxB}IzP<CI3!UwH=t5^}OWyMRtU4{{OtzkV?e7yY
z({xu~Np-$y=0KWuMQFNIpI}@_^_~*`pt|1FG<2UgTD}9gn(a+(f3)8|YPS~d77~m}
z=&xj<oErNI*iN1bw^9lWfM~9St(3vLg#;UQz};Kuk%2?--k~8vVeUZNP>ws)(y0<&
z2DRgMH3RLqT>~oZ*xNC!r&5nsgyJQ$Y)65rqmVZxtM>umO-is90KG{OmKd-%DdILt
z{7p*GJRBG)!hH4ed45D%61}tE?R`{d$9W@hMb&w|;oi}Af#nAPH7P2*=qS%niP(9|
zjtU(=;9p7+n=6f%BJRbG?2Aoi*nsmYMVP--kSXBwm4-|a`cx`1CG5he;f0m}d~F|*
ztF?(2QRw;yGIYu{F^iqzb;2k>O-is_0H{e3u4@J$H7Q#V)a#PTHTp&ogDd@*DLxRX
zI)KAT8C%;m<uthl;$>5`AP82<IjIL>Y&bs+1mdQIJ#Y+dYOv)XO3|tZImba{{eWxx
zBO2;c;2jVfG~ggl5$-VtFf}Pdrw(7sP^S)O*VL=S$+h?89rlz5r~wCliqH#dRYcFN
zamo#s`d5S*r$sezQScGb%{g$FkRoWug6X6LYI*>Kld>8gKsYJE)&{8NBWmiUv0I{F
z8wjE=S>w+pYw}^nel--cPdF<-C93xz3v1ZGYmkX`Mb&fHRtF#_Mf|uVBqt?oe_$;-
z>(ok=jWuv3l_Jnw3|w5540AqfDSD{=i5KjFV!d3aQ}Y?NI1t=_T*<03=WMZqu0Ahz
z(osxX@>AxKYXDG_B0PAbe_K7?Sf{TUW;kr7j2+k<##RS5hr+YhFu%p6_7TC6GIYSP
z9$t$Lq%|pG4;<^kmpXtCUdr$#0`12~G*vU$PhMsWLy>(v>XghmJM0zhIioHW;{J-z
zsXAf}D;1LhwZ&!1W7Zf{r$XwFL3QeMrH+9Zv640ZY?S~#7>$Fgqt+GR74WDvMz136
zqS3J_-PC;NX!T(jRGY6c2Y5q?>U=mx=}m9yBK78Ly$$M3ns0+j(-j9d2DPT+&@~3M
zrt{!6fcD6YPV6T5)mvF{d{llc_E8UzTDj4(8&sr1^p8PBx(^Oc1B^nIK?+@%Io{W{
z1EMEIY>n!72M?J8$eWK$#@V1E-MqXQV^<L$uR%q+U7t@7Ii(EqRC;u~`ba&x9YyqT
z>jN{WMfX<QRHMpHGX~VCLI4KfJ}H8p0p2G?_znyz+YAI4gPK;603(x5DGXo~z~?C$
zn+m>c?f5~}D_s8o-YZ3XSiQd#aUfK^!uO9s)w`!2PtCh^=o`SQUfC_rt9F%8V@#^u
zP58l>RJ&WpzDc!P(diFlShqU)P3T>P4-CM6t|*J0i`JwCCp9yp2gamkRtUjJ_)iKj
zc;J0f1kc}?Rj2;suz0z0MHm(j1rsWHcMSmalPTj6sFJtr{YjO)W$#a_WJU~JNxj3S
zK~N*_reRPkZ<!L4T6yb~K$K6)*av831s4q9d{TriOstS~)Q5@hJK_t*EVaC7=}&59
z#RXhZbrOLAV?yIDF_>Qw8kb!^H(S>SV^ZTT*TboCFT9{0<yFGRA84KwaXzSUmre(h
z3U`U;aezfKW$b`sauGw2iDz>audN0HquWwAGdMaO5dhWB6nm^ljmsE-F>y9sQ=j%p
zZMqn9Hx{+&D*x$N)TK*?{c7yN<hOk_&M(16V^NtZSm25<zx1?@sx)*!T2!YBAGjh+
zCyxV*hu5X!z{25mDL8K|o?e$U{-PRI*uWLx#mKN<)UZ&di^^26{{b@D6tSCBrwRoa
zi|RB{PJCANQ+s+*o8mFlrHkODE5a*ijHw%o%5>>?uu7S(rsgMyrVYKQOf!a{GLK{r
z=TU1o$W9#u77wyh2Z6<N>^%AiFKS>#4ve)i7`%UK+ZlRxsapmLJSnMOD^_4E>f9L`
z2vx4)2gahxt($<cpl_#ZXw<ip2Z2R(s|bU!sBWjfL!-`Bn88?h4jT`w+vzCQ`cQzu
zScpYV8CvHFSwRM4;e<SOS^%AOirDtyH+afQC|2y0a3xVqE7o8vs%gd=jNPilquZtq
zo;n3=>R?3@j7=S^P=c|kg7H-^QH_PbiLt4I5lt{QmGIPYVp9jtsc+t<7FOiJ*rkOP
zcyI-HZ#-k{&bRh{Up7y|Q%8dh)vKU^v3VF)+`!n>yc2}%W7i>f%Ix1%sZ(bErb?Y%
z&!$S9{p}PFx(G8E8wz#G8N8`brw$NX8B^Z_L<MAiL`_{-oK74Uz^$JGKD_iUA`L!U
zXG5tX?cvzes6z(+rbcDZz}Qz;j?h4LI33d7+tKzQkm-t63HV@Y$`N`nkERMO7@Nv-
z$YHywK8H5^hWZ>j6KsI0QijI|mdTLKzw62MXU*u?{5h585V7QNYRwE67<K6Slw_eh
zRi<JFhErvZ`j$Q=t2I1ixI1;`km2sAg`MwInPZ^{>tCS<!>K}t?0TmT9kS~kI#kgI
zgXi2ULmBT+M!VOMb;x9QDpbW645vaJugUJC${f?+AY`vQb?g`@VhpCXN8Ko-toFP^
zzbfKjIQ6T74u(_5D(GPN)JWyrck0+-DCU!8#XI#YqY#Gk_&Pe#3B##!6`3%cT6f6W
zcWB)qyTGY+D>&hS4C{lIJ)A));ee@hhfI4ALZpZ;0x!+0_=Dk8yox{=PQ}X*gyGb?
zcHR+E@gfM}3UV+CLKsfXt0;uwRK524|DC$m<o|c7UgN32qe}RuI5jWg5T4;wz9#3t
z^Z2XSgn^t%DdG$ShwHk(ajIVhC=BPx)@1TKeaeb27}2UoV>_r>6<;udniT;CS5TYM
zbQ=&*q9!oa71cYprN*d7O&0<|J*v=z5mciFLc0O}n3Q0uf_jwk2_vXSO;-Yu#YwJ+
z5%f756njw5nvM;@ld8%351v#j;NXF5l?0!qpkB4{<xzN1JQ4&|sJ#b(n4DgHF=Dcx
zIsk<7hwC~ZphZo=!viRkl%Yj>l}!hSpsqC*F}f}fLzJpDog{FplOjBrUS)+hjNrl4
zUe7;nqe_P9bha<ge^BFQ5W|Slwv1tTQc|<qW$%MoDn*<Ts@pEde^A}_*YO|Fw_PWI
z;Ayq9QmwZx&wtRPjD!PE$!fd`j~IcUuyy*6d!Se^u}k*{y~m7txDpIP#{Pk(?y~C-
zHFcM5e;WPu-BCu5W!xWXX$C`#)2qaWsHFRr3Ow`^cUks_idxYS<4{p69%39Q>WYWp
zvub@ZAYvSzbrlgY4qeV&Hvxwly$gvoPO0>+6TqQLS7gKhLh&Qg3E)tLlcS(y7$Uw4
z2l`oY4&zWicbW2s`Z@1xABfO(-4`6HXM{kEQwqB4w%|}f_o1W2p^EOhE;!WCU1x$r
z4Xsd#aiF2=D*J&5YX$cOXYpO>zThkjSh$cwm0fq~^(5+Sg-nb?-P>jHA1YskJB$NW
zTfq$vMCg_73=VZ|$06WQ(RLjI4i#;0bXM>wY>S$<>B8Vp)hbG2B&s<DfaHxsP1|4}
z9O_v`NsL1^%P@&?=!-@IpQmIwT7^zrNp-X7;Bk1!ZS*qS^rYyf(9*N<46E>m*`RA1
z?+j+6s#O5QY*e+)F;BA?NmEi&btUMQqlhkTwM8`xtj$xhdIgH4m<>fXPG54vabz~S
zk{L(wqzpsb_(`qGw$wV#yb7+EjR)MuqsKEFHMW8&X5;a-O?7dyPdqnV5jrId*lbk2
zjrRewQT1lr#B5NzZK#{nx^29ZM7`U1zL<@Aw+;1xy0;B=y;LummP&$!IZ(v1G<AU5
zx#55@8?`fL^(k4se^c{39XHcp>2Frd#RL)ZM<l$^Y*gzEyttB8We$WYTR|09gs$tb
zFdKDt<ITWq)Y%Nam<<}cHBBZpb`z)HY*gC{!kCR}yES!!T3ewRvz;FYVHr75Wfxo#
znlCr?6|nhI><3X969}uLu#DMoH+c@v5;H$p9|4XCw|vKN6m&5W*L4tcF?;>Zx#}Gq
z<Bh=th4@i0#RQD%9M?lT`sRg#nFXOb3b&X*P@UuIYQ6n)cy^f34CnCZ@Jy(Wqri*_
zX7!`Ej9K*SDOo57>ag+gWRWcojFI;S6B_rNr79D>gY7?4Z=a((gNZoDbEY~{8ud!>
zMF3*zO7PtRVCqWhqVq}yYOyy9^UM2!3Crb5I1Q^Ncn~BqVJIEOSWHBg9>rM9ghriX
zdhEs!w9Pwigs+H|91~up`}3~x1={QyU!c*h@kKUD6MiDS!bgHq%~?|y0&~V#irL}i
zJ*TPRQ|r8`-GhbBGr)uye=?k6!q7h<mZ14L2%Mm;KXFnxK~sO?IB|sLo8T2XL7ROV
zJdP)%V(a*F1j@UDfm(b{P2iQFvp5DlC+NkWI4gZ5S-O8|PXYjS0v7!Q`ssj|^sWb>
zpN;}7CcsZe5f-!XPbXZB8b-)X`Ak5a4#O!XfKEpt6*FN@NAVOBD5oo7Ltw=^LibIZ
zS;F48i4iT0abie|?M`%GF^*T1{nxg&iT*D&Q(E%GQd0{9n))2$(0^jGt(7C18sWl-
z%6gyhE}WQZ8L+4mQ%%?R<tXH07Aoq*&>%O~#$dx6gOsO!g5TkUsg`H&Xpv9wLmY)l
zO!#OHLM0~h65TSp5@?xr_5{f3MAvg`QJ?5~Zty*JJh=XulK{0A(#HTirKIsUxAV#c
zbp^TMqfGKS8m3K~8|b5>eByKTEMcdXukc9`t3Ycp;9-_)@+f2Yg!}Tib}q0<R|0&^
z6<O8da|;`JJosGbBd16HN^;hiIQ&Ub4L}z57+GS=Wv(4}KDA7`qtxPa)Cuq;2yZ4{
z=rBw81RKy1W^MvMbTYzW0y=aQ;qXkj&5uGHCj9Ehm*y3U$d`r>MI^XfJ}4)4sp*A@
zt*&iM>eSGosC=sBT}SSt9O5(4M@MkG31rd9Fo}r^isLen>k{L*+-DP*qN6y8iOY|p
zsECP#dq;5*a|F6OP|D--5q|E9ayK$c;tEz4*$VWVf+Qxcf{vTc00T<SWfcQ)bcCLp
zb)R&+t7+&s#8Nydsm0gTI<%g5wGPdvq~mk8EMbRESht695)&YzE5K91;dPXjeBxg1
zC{$t=@7Jjtpa+uduVN!6vPzy!vlodckFt?ZWT!lU)ID=nfvrIEDN<qrLUa@<aV5EI
zcc@)tu{+F4J_}}agsz*o20aLrm_Qhv9cmhia0h)T69A*LLv0U?P`VoFJ&zE2b58Wn
z->HIb+cbS=QPEw&TdO)K!xz`kXKzjwG~1Tt3tqgl`K3r?(b=+mfh;<Eso{lF#a?Q<
z{_*UkrlH!9u6!2w=m=&vaczGk@D1Q<|4P{Qt|3k}?HG_uYH$}GVD6q0RcB-i11@xg
zmYanZx&nMofEBuu?BJ84dQ-HQK>>7>oV*4g+jt)I#ncQ4V9z!+l-g~Z=HXy|jjfb_
z=qNw=mDGUBEL~84o5=Yq$<feNJ^_C@OkX|$kvRm&eTD~U(Am<Wg$z0ZwN2oH&Zd)m
z0{Zijpp-_#I_e3u-;&u3lF_5=<P(UZE5Wy-$V%%$Y<gsg&Ei0|4obP9m#l0cicVod
zo|5F~maOc;6P+a^8(^Wc0;SvtLc&eb3|$eQQ99~M_>h$)_8K}<Db25>`uc8VWDGxR
zt0gGSMGJbB%3Ly_7gXjFqvix+=qRiCT+o|KCNy9~XUU9C6wz5SqSxjiX+;A<bk<Vi
zP_0UJJ^>&)Leb5F5S=BCpb5axSyOF!jfyrjrurxu`UD;E0i^DhbA8D^2E6es8OX?3
zf0*ig0tIvy-QN>g@1HAL5M*bEdJo09hGq_ma}6~O#rY;XpIG-tu(|o!7iY=H#=bcV
zMmBcVS@d~dNe+-M?<?4-g5AHNB$tfn4JEm_yZ7yb+}d+P1+J!!Km{U6`2-^O2mv>N
z_BjhE_-7W_=d7lVKmktrv?riGXC93oDo{zv=SH;B5hQNnGkhjZZvdOmJZkH6_M4%0
zaQ2(=juD4H;p66pvQwt=2|&*gtZk+?y5;Q2lY*S?DW^4*+LfSl&}~XgJ^?sC31FKW
zG1zCyW4)o<=2qvR+os&ryL8)>!+O`};5p1+J~y<TplerBBibnC?w)d1Cq(F$Y2(7C
zILdiG0S7u$j%ttvohfr0WI<=@dTIjtbEXV#m{V862SNW$xvgQAeIzK|#jf<`6M+(k
zIJAk7*fV94BjVyr`Ku9@@ti3uy--AF%18%@=wuS~3H;CzkZl4zbkfLsAgS@mO!un6
zR&iWZ?(_)*`UuuG9Z;4tWsxHh#g)_uz0QlujD7{xRoUAPjX7TjwL@i2`KKKR#z~v}
za~?TU_BhTfN6FEr4=z&~<iH7C37dx2oN`MSO6Uw(=l}^lSA>?~2~`sH2_m8cP}~GO
z=nPrui4ZzNbU_nmy)$H_XS1}%ad<oe$W0tD&wx3OtSo25`+)jhDQWry-X|rPeW=VK
zPqp)?IUEm8jXC6~2KeU;IjVvEIYPxvV1LdKtbO93eunJzI?JCSa~)}L&VZj9iE@r|
zs6Vsf@(v+()AMYJT<8-(og+-#gg4_1da29Z@p*ew-GJ^>qVoyA$r0Xd0>^VDd@uqc
zuc)3JE&m-e01VF=a#2UaB9K|0{+u)36M5jwIB0RhDRhQB)D;MNhD>nKavWmaJ|A^t
zf;viVekHY7SjtJ1ml}?<GvuWv6UkxH@>vnKN2s$|VYpX<Qq7s%)W~mjMtjExJvZd0
zj+rI43OzSufdhr}k)Tu`7?Z(W4#{J(x8bxrrrn4@=cDxH6S2_GAyRC{&VOeOC^(a?
z3`gyiuxHS5CJvtofA6tCDSM{f2LhgB^hv{qd`$LrAffp&8Q6g39Fviq$eg1L=M%V`
zBaGPu2Itu3=N%B7W3s3VfO7?G2q!@0MW2A+96-#T5_#2PQ-MLrq7LXqqd|?>{-ZqT
z&&=d_M@X`X^m)hRl@4e^lUEv;oMW=54|2C2qeWdHougFf6ZannV6%w}l3Pa8xJ9`V
zev5I{az$wS+$u7;aaD7eF?|A_b4(_8p>v)T@h2N~*l@>qWMSh<>6kY6DQ#(rQlFsi
zx*|3Ob!jlNaaVPeB7L4wB}@r!wU5cM4eZS^Iku67@|Yak$W(a@e(i$i98=cS33$#S
zJZ%D;b4;#nU~`T&H9aw&a-cmW+V~M4Qv=d>0^pg`Wn~w3<_Ly14**Z6%i|5?%;_|{
z^FH(_yZOY8>FKhmajSYIba><L^@{jhXtqv|_o=OV1spdt8xov9C8{yVI6tM^x}4tN
z^gErVIB5TlQlLLGZ>dkB&1PX<4l|igAYM+F{S3g%M}ksLY?r;fa36m<UEB+o_D4Xl
zg`54;X+f_fV7z7cRu<Cgenj}^nnilJucRiCCiiO4be&swwTgr~eX3#jLi<FidO!5k
zDtR?pN-k5AuLh{+5pHX>fd-8gO2Ktg2cY1(sRK}QU4H5XxXEE|@|0A+Xcw>cQF6Vj
zVJNxY*)WhVr*}0Cwb#3vhW}If%2#1vjxb*f*p}z?#wWwM*_$4m2S6n>UqJO7fxA}Q
zS%T%gfE7CJsQ*xf?XVSS!gkaO6d_Pt&#J85x2#s`ThWes4`tYnrVWR^7HS%)>y98?
zD<LnpyeEH>E3cJVya0DOEz~rWW0RM90qk;GsO{2@jc4fvtjlSxmIH%y(m5~m{V28h
z!uXExUMuJ1w5`WL^);Ho&jLd3iWYuSJ*FMJfV4Zrb}hhK8r{~b1O9s&{nm@XmPWVr
zmE_xRbXzZQ0-aVC_3HI|Ac+^jFKw~ia>`r*8}2#2saA0UR2uVV0l9bt3|mB~w4ts+
zi#58e*Jmf6HdKRJtP$#cMYS*oI|r4eq~xo<4o9f1MO;fWeF6z=X{NSjO|GdWD6M8}
zX<}-jWuFw)kPJVl;dHgUvc$pRG}pS?z$N|>nrjij!W88xsp;2-E(A+!U+UEIYBW<9
z*nK{tEcuT(N4+YmGL)Wt0q-2bU9FC2$17s1rOd8`?WQuj0(=(1F&}tp?X);Sw8;Wg
zCJ4=1K+0SJTfUn*PN>=Pkm2h<6if)3wE%I6<LcKzH)uXDYv>Bi=PSuCLmYajuc-P0
z5A{mpBo58#Ti!Www5Jy=njlAEiK@SJP%oH9akd&y>nYAs)3qd`Oq{#4fR2f?)OyD_
zrKACl2?4g2Rf!E7U*hD53?q;RF0(Tw^@~wmo9gR8*F;~v5R4H5Vl8BdxDtG1kV4{0
z>bW!jW<Qbc=Ze_bi8VOXaw*6VRBOTJk7H^$NA|=qH9Yb14Gk~6dQ;;Ii_p~e!kafn
z)hy)fh||^h#<uBt&_<VG46i(keaawgc~VlnY3iS&KMnnJ^oEx20@Ni=<71P5AP&9M
z3s9Gcqt2Deia45?Qfr~C<*V|pJSoDr1xMX0VdJ&&A`Tm`op}XpJvVQJvOg`vXN7W`
zFC>!*A;PYtdMI@Z$jg=R`!I6ISAq`0Z*V2(Ap8nfQXK?MPY}QLq$n3(c>du2nttnr
zbUzXFTQ8&pir8xP>bEFP;0J=5aGsm5q&mN|R5~GIsTr%0EVY8@p-@uu1=LK0b~GX&
zBV;oJ6ca*WtzzJLBBuH>&=>lo7kpG72};=)8PRZYMKGXZ!3`EM)Xc=R4s~u~R)-p{
zr?OG7IY;I&UqI4?5L*jKnh2WX0MbOr9xohCgc04g0G$b?K3{;&gkW3??!^ch*Odb-
zC3=u&kzI!p6iDkzs=r;2b@aDs1R$-9p!q#Y2ZpR~cw!@@uHmhXko`TN21A6J|L(`X
zdG4ZZpQ@jqxvfv#kJ4%$b9~N1|Mp-1_|HH3kM{Ym{`Wup^$G5cYU!^(K$RX!-P@7&
zA{I|39e$pG=eJKxP#A+>`>LH0vdO#K4;Mjtubt;FXK%}70egw)y4Tm}OJYo91@oa4
zGazsHk_rf<K3;}?J_w9(`zV1K0K)rav%`TSnJUR0#z>zEtu1aR25P_jIk?IGO5ETK
z0~w0+2}aqLH-OP1ihCf^7O2Lrc)UV{5ds6C2d%@redOI2o%c>3uKX47{PfUa-DPaU
zL9md0Da6%T%W1C99+{tIG{>>NKYw`ZpAP)aYWn3$swMk%C9U6HN4bpP#`?OB>YZ~P
z)xP+;j%tx$9lbem5$XT8*Acj&wT{HI|79J49NA%kZrMFw*U|cKR#CR~Wfi>?UFQo6
z6Io<_XBAb=U#y~fwXKmuu)%Zrt|55Nw1$Wa(;9N#aq~V{*J$q&dL4{hLhk`uO9<Lo
zD@d#7bKd(bpU<M{`+kK!f2`TN@84fN;HV7ekt3j@9qxpHes-QWqJE7}HNMgz#>l|p
za{3LTzGopSNbqomm>`imA)M0<KF=$tF@x{(3h+=vFL|^GLpL32@}t<o`2~aG3#S_&
zdhrTs(?E4z0h$Cu!IhxRROTTPNr0k*6p}zqhZrOQtiFQkQaQQ9={HDlb~sNTV8;)A
zhhk-+p1v@I#V;<>FI)+J;PrcSccFXq&jY(2PVEq&rV6Jo0Qm&MYmq0_ZHO;2pt_w)
z5sbM}H?B`f^3&tIW(&v5=J}((Bq8!hSc?Jb$TBCNETh%Z+M<m_P(e8F;3Cj1o*H1<
zhBKF48OY)M4#0%I0(9bFeentoVHQ_VpA&{*TuIuppWPQuM>=w1gwv0XsE!aH<Y`!6
zB7%Yn45#-1NfLs@j|XQ_@jlksB}DpIK`c*7YV(5LI>gh6G$J2C74A%Ks;5(5yeqha
zynU)qc5JxLapb$@+TF-#@DWrYXKmAEj^Lgr#N>#iD<Lk&GqX^WdM3I{cK{SlBw^#h
z?P7?pvChUJuEvA&qnH{G4v?Ft{x8ZA=N4qGdDSHn+r;Ks98p#w+~>jBQMk{8TzFT4
zhv1~Rar>NcWg)~T0?%S|)gv}7l8Wfba&>~55!r%*V9yiv?z!ks;6+e%99)T92^y{Q
z+!dhFz{{W~4Y`m)=ugDu#pcdI>|O}`nZbRrdD2EsrjUw7+NKcpv$w{MadTWz^^BL(
zJ*#jd^wzO1c+T!{x?M?itRr*Pl~m6<(pyDhL3;&ZhM=HVP*%}V&)`A`VL^L&5Mv!R
z3{@l~Xm3zGi_ge8U2>d#EQu_#5vZOOY6H4Q$j^^CQtx58YT@=Xg!Sxcc!aQ>w_N?8
zDbtY(?IX$3{q-gYp(Br45YyQa85{z2_J%VbL7gedDHW#kxgxJ8vsLJswX*~zBShzw
z<eDO&vo|1GLWs_up7ju(v%?)9OQ)j-#j>d0I^w!x2^7{F+@4EzYo#f;0?rz=$D$7F
zxMT=`I-e3%mxl%c-zQO>J?}GO4UGUwXbm+Da9{}5*%AC6f^~L8$cJE^y`t!2nVPP(
z_*@a%hPGO!)}gKd?7Zb#3HF`|vV<e-JtEX<;JLix#_7xPGZ_bB!G7)FB)9@x9CYMm
z)IkH}2DgmyRldisKd5&`wR$D>bs%`O_xk{<&5nD#5O%b8s5H?hc3cR?62(f#tzi&8
z+Ur^|gdXj<c?_XPJ7^_>=+P%dxBDVgyn>u)LPa}nJ3~;>-ai^nP|@D$J)Jz^bntG(
z3{`>J!T_&57X*c7IVXPlJ3J^cks9{Tkuh|r>9}EzM1*#bl!O4Gom3_vL}&-$NeB_z
zix4HmXV{TIHWKZ5OSxdCRO=P36!4i)ds7=7xAZZmx>Dc8nDBc)9oPLK^1+T&10k?y
zN1}lc*s~+iKnU#lTv7FK;s>{L+R^|k1i_wHP?M@n-A|qRLTJx!wSYok&nvNdFeV?k
zh?v^b2BR+~w=nV>hv1#vdY0G>G~kq{2Pu@Vgqs+NmP3fo4tPk+*N4<GC~jk*Os)VV
z2pw3InDiHv5)_4DHz+}2LOU3jVs<r+8@muDw1d1UhzadBvVe_j(2SrryyY69n9i=K
zM%dKwz%p%WxQ=B)gmwUf0@>(uggA)-0NMdJ3IRYn(sRc+Y6<#P2+*e^ML`U0?>kQ-
zPV5F9D^%!}<d}d8z2&lLN2r}rs3J)0fNq8O5j)^rAx{cjI!_2FdPOxRm)B=yi6g}6
z?aROC${7AmH<YZPq}_0Q8?Nbw>ve4P4hnSacV$9>j;%qZz8p&ffW90{{l}>d;L&cl
zv$z5d0os!2(JQceEStf}ZcOzK%5sPZp#z*4LYQ{o7h}}9w~v;8Lq{PgK@eKn$;B7K
zm-fs^5JH#Ua*c)-|CQ9_^3J>u+!Bu04>xd4I2f|kN0nFw>TsAk2X#1%oii@6uFjP5
z8+2!OIGke0N(Z7f1VZfvdX3Sgbp{T9#GrNzB?Ln4Ad`&2N7QI!=a2bhk*(q)QIOLP
z2FnoSv=3YXnvC=T!mBV|c=ud1VdqPwTwZq6v%2p2NV4=%m&Bhww^-9^GTR4qra-7y
zQeIP;?E@;4Ak=!$ooNd-i%UhT5{`-Hnh@wzf>1lRV+e)XbH|1ts2v}Mk0eVtDH{D!
z9gM6|;L-=8jUVwLbu%b*X-86lFj@Ba@&!IWPl>9#GVk#T4Z=%%eq+O=@(1*+;HG_m
z1}1E&aojHoaM~vntpKOJNNz)T(<>;;n0V7G$ptCE>6PSyG?@+)s#lQHKC1>lUWkPV
z0Ze-;#vr`3PiR?_p#YNL0J^jnkMNTMHUcGUJf2@kj)%wdE2#IT?LG~L1Gx*Yq<YT-
zd7mGpD(Gm384`kyc33K5N@LW)#T<ft_R0egrj3d;0AbpzNCR*sh-~eM&<P<yJM6kJ
z+TF9B%DzHDCZ%B~d3AIh(kG6fqBQKV9YavkUJTeFAZZ6n_7g;sc2H@D*bJ{E7j8c&
z<)Rgr;gzf`YmT5Ub(wP|`I1FtcqO@Nbx+V?f?o+P*g9<V=z&rVM@Ri)G!HQwUO{fe
zt_?pycN8K!yrLS9Z2pNOYGO}s={{5z|AfBngrN5ceJiHJj#Eo?eI#(I3DF$(I`{+*
z7*9!Zr6h*6BdRXCJ`gxO1?detau<Zy4f~=#?K<ygWMGK3u;cs}A}#DVBVI{8w@#3^
zJb0^x<7U@kAEf^w62p%Bst||amE;;OaM~RrO6)CkaMz(=K?jS!@JebO>!iP^mc?G!
z5vCae!S)5cOb~2G0)r3=wpS{JE2!7FKF3W$SNnoPweyVL;rWOT+rENbZ;_pt@MU&=
z4B%slu2cAe4i+zAN2G0lmarqOK=jvmUkfuU;~jYhLd1l9ee|$62|FB50i0@IP+%dT
zYA^RykZZ6b!$$~ldL`@YMJAGjTnX;1I#P*T5%1BVQk%^31+^*+>XqD?hX?5?N%fb?
z8`0g-w3#acJev0Mf|_kK%%8rXA)9vM!ci26)4ogfHKNiwJfqRH%{JYvjr(jv^$AVd
z;cpF~N&D{kH>MW!{m~RN-ND`;P5Us(`=e<WZs@`$$N_xAfs4|<>1AzFxWz3Hy3*`$
zKu6QIgpWF!ENUbOdZKAhZ5$69z2aAr(=8>taTsjUvY_n0lG;J#vk$>ZI~e<eaMBJk
zhiFo|$g&i0DqqtNxtO9!^X`=;whP_YWMOY8yGDC@^K{s{8Y*Siv^h6UhfSMvL)kT{
zYA|j*SH$O(Ch()pwmnPG55@VP5<aAKjaQ7q1JUiUAF1A53*8U*<Ib(%NA582iZ~t$
zP3A|M7l~c{$o2+<i65!n<T&vYYPNQ}ALe%Ml~Xn)&>%=n=BQB}@*~ST)0?G$&0?T_
zT<x41jnpofVO((4jsyZ92}<|(TT_PYZ!R2a$CaQT=~Ubr`jO?0i^Y!wr8`PLM67jO
zOZwqn$Hk=!f_f!8r&VURgUkAg*s|ph*s5U-ER^c~Yp-X*04G4TJC3biU?Of9$txKc
zi5zu4YTl=stz+fm0<!jEMf&`RCO3GK{74J?%o3ZK==zZQ!M(R1sZLytJK&}r=@MOV
z(+=J!C*1T&(LyD5ZlQB>vVo<_nJD-oFZ^idJJL;D5&judD-Rn|OkN4TZ9oyY@&ot6
z8F*y}ejuqK>RSN#f&;PIfp55Fw&Z`Vhp-(lJb??4bVa#Bg>C6z26I7HJGlE@kk#(U
zUFQMq4Zw#haqyMg5eS}o1v!9_Lk+MI4^b;zQI093;=Rm)D_JP7EOCt0DGyv@cgKm-
zLtZu{t#@HuJ3w+C^0HOldk^{80G)X};6wv_#)Wz9z|S}_uN?py4~Cp{pcXw8jokrl
zbmbuK;HYz9Uwbmxxsb0NBzGR06hR$KcvpnR4P#mwrPY}9EdkiZ1%K^@ws}&-whW_M
z8mD1c^u@)<0>?P8KFWdy-o`_Ie*kV=@YxPL>y@z8f#FO76t3u?8k(ILp}r?*!(*tg
zt4f$zfFE6O*bXR-CmOaFlE#%}xC2V#A^$wEG#-jP>mZ7BfnPh&G#?2{_o4E^;l+B$
z2Uo!7r$m@W&(e#+t2raKv*t^O_JYbd0IzpFK({KzaK|Qjk$gQj(Tfo6*k<n9{oIT0
z+Wy$EE`r03P3?}|Uzi(rS?*vZb!S@94(k6aVcVr|U7rJdr`)mA@f~yV8$KN{8F%f{
z!pXSn1`TYl?%Jhbgmv;4_H*amwfg|1xe~k_D2XfKQ&SxZaM%&o;7M}$K$7d%<pxK5
zguC`5$ZlOshrRf49ctz&NiG%VUIVPgUHk3KTdKcm4!J>~zul)?65z=9<R<LJ80?}Z
z>>$T?9~wNApv!lC5ToiY9Srlt#a7rq=8KD|u*1CZWGd`1f80&ihp>^{<@`oGkBh9Z
zSHO>ptFVKg`6EFo^}oCJSweB#shR=BaWN2fn1n6{!hY)CxwBzYy35TC^8AkkrRukC
zz7QhiWGL(zMD?VAtwQyQp|Asub0wTVXg+Uh_;7sE)``e*Q5JSUa-5Wf9grLsWnsr5
z;7V{LHk=f$s2aZ#s|OSE3tcCcLMtwECr9C9VA#Ks8kB+P+{H?GB~_>TZ#W^j2nelC
zP)~~T!G>d&Z$Z*=6!Tq**y^n2+tm!z+IF614H1OCU2Q|H?X9+<*7j!8BMbFuF;dVw
zC=3l?9v6e5fyq9x(U`b_5pJ~$#kQ3i$Z*hg@fsRH<F0JMS7L?U2gDi}Am8<2cv4dR
z=a<1+)~LVgb>Yika2~kQ{2Ck#AIXDay}Y3wY|QFV7d9r9p9TY6zLROIMAfUI)#X`Y
zyEuJje&1WFIW;wl5Jwl4p~1!C0<&3pVO-gL4bB|jhEjgO3)KHWv{Haq4W*_`z6REN
zR~&+Y_WmP53H@qXKu~JT;A<6^?MmQl2;Fw&@3oFIWbv^*5LMr~^$h?WSMpv<-<vCS
zufaR#%-s7JJb13my#_Czi|o(<+HoP=tUx<gfCb!fb>PhJdnNfoMQ3OTuXmx^4D9$<
zf~}FsR{YKPYaJ?6B!`BqExx$*J2a+%aMqzQS8e^r3Z>&p_Im}nN|o#PN^+Gd)vp1`
z<6=Fu4$5yQM9%um0``8#852o=tsKo+X1jIl^*86Qfj_~;cxWKqcOm2qr28qs8^95>
zJh2Z%HRHV5zEL8+rm8@@Dj~4JY40E}v<`2o3;SjT@o}a8HRMHdW&XW^9ra#^TB=!n
zT#SYWbiD;sT+OmJjJpQ+!9BRU6WoHk5AF`Z-GaNj6Wk#X+}$051Sh!slUL3?|GM{^
zy=GHgUES4P)idl>&vZ3Ie9-jt2RIj5xSL+vFgDb>0JHw3Y1q0gbNLC;{>aX0hqGN-
z0%AZOfzx+wz~$425D2t*`i)vjv|(rwHn4y!ICe<1VT~_^MR_cz@U7EMluu3V7uOOv
z>sV^`5h@)Y<b>?UYKAMZ-H0EaYN0wd^OV_6YbjTv6g~Hm{7G_GCtDwG%Fm+5L^PZX
z`VaC8B?El*;5Z;Rha}7`TN7@}Ut`&AYIJ+d>-Kfq{3aw*mKi34=?<dM2?`F*%Gvra
zOkkjCbk~wKU!gMLc}{eVv|s>nY@cfvmYdrfr{T*j)<rw6FYs$B^p4$QT8S*4^eUh2
za2h8ZD9@dNqMT2PI2~Bo-HM*ewM8Y4*KJD4qCM%JDJKT9L+B0Wa_&c}-slclpf6ty
zWE7O2eD$dK@mzu-Vk~@G`{emBr8{4h0_WJ73C~M_>Zlgu^G-lf$`uYUYr<YO0wqV$
z9IfwGoembLPz&B(!`0I?D46L1Y!jt!cmT#&iZ)srSI)K6u>COtDbS8G0{$EQPj_yY
z<KC2JF{t_q1~a3q1Yw~jHF{#Ld2xl!`8%P3jmVaSIE~{7G0xETE_xpc4_7(-ZL@^G
z#j$XkOKv%ePaDX5vj$t!h3^oW(fjcWo$Fw9z*^e-G|(T<Y42&->vr-33E}}eW{EA>
zGIu#7@&i7}Z6LuVM^3qCbsk5}cqb=X$j<1vb??%HrWM|hm@*o^<(;0EXSHMss%Slx
zQ$_Lc2ZBCFC6{0g6_a#cMR2~o(Hd+2$<~BZZ89_6bQfgAv2^MCPs-IP0VMM>UyY)%
zevKD+LoZ<Eq{X;A)-bfg=qqS^(4!A8p%1D7|8ZQH1J1~vbT;Y_?P@;FVWUl=$5`5|
za;*y~GYF02jkE<pa_d9@VEPD_27bLO)>oSNwU|AG1ahg19<nCjWHTLX={o3Wmz3Ry
zm8i|$zD>P7VM|}xO|i}1R+M^0IZT$C_M#e`_lA1~33(b%<3tD2Y4GdgqJO62L06O3
z)V@3FZR^J;(V!eh?|y4pO1#(sK%e`Zd;?Z;ZB+WS@cpTbpLOq-4qE|iI++!F+gas^
zUoD&h@8(O68LD);kT8StSKl#e<jnJFm1|@uzc;Z$>jE8+r*T_C-11KcbRR%J&734`
zh0%?shpwUI9Fz}bAJ3vU>UZz)FPt{yYP;USx1s0CDY5`^77uY4>aHhY4Pm2r+F#xT
zKAF(z>P&wbe72Fr1tqEavWFk9$s7d#Ovyk(_+%HVau->{EM^ndqr@x*7M?k7;_#&d
zxJ4E@ApdhWn#~cEAy7rhJK{ZyK+l0S$mk+45ig$6ju+?W&h{sGg3wsm)@8;6Vs!2C
z#c>r|RzrgtuwFOFux|R_)dyO`9X2LeDZ0We{Sl*lUvkIhI-2hTZyKH5Yp-+ZcFwT&
zz0sA%{bR3)dAA{n_Vf-}rdc)*@O4NiSDSXwoest$tr6uUKmJMs7uowBi}$@lcbcVg
zuiBj`){(|fSIe>b=q8)T5qbadqh%VY`b0<bYb3)}Z+jk92vkSHI;VIbo)7d#inPAm
zZQmUm17g^VQ`_RjI;Zv3zzQtQ@$EK;fFCtQ3>*bNYD~@0bFuv$2#@WM(Xw<T$2!c)
zQ&l&&(;Y=dkX)WNT|G9ZGXn$gggH^D2UQE!Fhtdn;_)xO^`Pq=ORHP^FSj}^;EQl-
zsF8$yUtVVwr0iX8y`IO{wb%rKKG%#d%aF=>+5$N3EvGL?vA!4lLiU#W2kpKLd%AjP
zY+|NWh)Qmh98^SU0rifQWle$0pa8suX)QxN0*d>n0_eYh0vs-zzg;i)m2eV9O;rQT
ztgrpm!3gZagK5@zWX2`!NcJ^$hLh#eAOg?EsJ1nnY4-<Cxrqw#W;aLPQ6uYtWA>jO
zdD@vMBjU&GwfZ8}bOF`ig>%i?A^4x0waIB<_Y>|h6x9?GePe~4rgWQNB>gmuwbx2z
z(xM@kJm<jiQju#YnwlMBZDeD5b62rtR(?Nr^INVC#>fjR%z>}wTO=PW#zT#Yz~3a5
z5l6ehua7{rNKPwYv>}V|#Yj0ynM-K6=|Fz!p>M0+SscmK-Ew6)kpJmiH09NK>>rD%
zGpW|BE}cbnvytzY8M}powVqVI3O5PVn+icO|E>+mSvnF7%Q=K@>$?Pg4ps|CLQ>$G
zG`|S91Y|vB(v@1VnFwfhH*esGmuvmDqV1&Q(O=(PBgi#3g&)t`Vb?(%Za2hvJ(Y3s
zl1Wr%))9xvqs0Au6n_R6wLU6n?Z0DVn%e}i^NXC1X#VLr7{)+2&R4X1qTPH`%EHlf
zb`7?f_xhLZK`uue!vfWPyWsjTE@&IfIx8oG1Di%5ojdm3SH_skC*MUrBiNXeMnXne
z4=RsLPSsI-L#XHBq}V~cL=I%HYQ_(A^!(oic}0SXP7!~gUNTK#D~yBrgHjTnK=s<>
z4<Lc1F-5EP_WTn2#tsQ)j!0(??Y~0C%?@VR{D6#1XhGnDs~F*gw3?VFvliyf3bX02
zu&Io?-kZ5`O=CrVd?q`WYu3zPm(fZNZoeX$h_}u7{3AfCiq3c!TR+o<ew&e?tWKu}
z{}=S)05-$8@JNq@sii-fZT@!#PLK4WJVf_foBZ!c+eOGqY2e+BViq>rhMZbR$S+^`
zV(%0mN^z}PFxO#T#=wGCNH++Jr<;5AutP96Al&i%x<bxbFHh~2@$qTUTekJEi%QA5
z#|qxE8`NMUh<KHxXxkVqQ^DaItoK2W6;N&C2nY>geEc#qw#FSu{#`Lk4m}edUvwOp
z`eir2dux3RWNb_ga5KjkHiKOv*0KBung0d?aoyzKm;j{iN5M#q`wD4`ke^)T@j>~6
zsju=6s8)6b*z<sH!vSvFIh*;F=Don?Jbf7M3GDST1ce6ZJ64BfAN6D5`pxz%EC01$
z(`Ibl%sTsFp%klpn`@>%mo;T~cD`IK;Yi52i}XeYZ|{pWB^IgcW#`Wt>t^5J8ubq1
zR>{yQH1m4vL~VrOKgeK1Nxb+HYh*h=Wsj^|*lm)Mo9Qp{+of)t3x2%6qBUGR{4xd4
zQf#~|Qjw0y@{6TGn9JWvh56U^LXqYww3s}jz?#yG5O(J$(gLAWw<$n@kSxqEy0POJ
zTmvHZWB9=(S_=d5$CGXKsp7K+f4`$7e$6RaxTL<ObQ$lpzMAwre^&=<g%$2=JPL)8
z5Lf>fwb(Tj(oEVE&9J*S-Ir*jljkHVO;`cH1WNP!?2z`7jozUj78`axy}8B-ctv?X
zchA#}BG@zn+7|FF1xH;qspZi}kWR~J$<mFgIV339s)k}i<f-*P{>sq<4u7f)Zi6wN
zplBHHtxPvg(PFVabmD;Oo1!JHH>voDzFVDAq59~ET)ARm#1&AJsMcgs{xNM;#s`yQ
zLby1+paidsy&<I-M{a>uRaJP#%x0ugwM3tnsv$oKC$qBBZ0OgK6`pWs`xE!K0ZCXp
z<t1CfBNDD(NDx=5ye8@&u2o0ukwsRZo`2D)%Im%5y~N}1(qCs9XW)_b)0U)T^&QG!
z=zy0*TA2fuI~i!QpJ|I(`dP}-(Y1cp5I582q<^;Lw<t5(J~pK#!pR@E^I^~WK-f?)
zC3p1$={B9VJ1szP?!5OfEP&p*OK$zF&UCB@T%dPTEQ8r0eoYbM9BBP{z@0v5-*0tV
zbEBfskdst#fF<8Uk^-9k22OHi@gXOa@_`ljJ^7j3C1R(yTe(BF|2(i7HSNSM5G=8z
zbaz-}HNcp&#}#hV0fN=mWrXFMw>3YZzTLSUe)I5b@R|IWZDV7dFP)1WwmZtIeme<D
z{-QjLe^cM4Q`k*fMT6{wY7HA@5wdu?hND%WVIjM16~|a#IZLLC!|2aX)Sr;Kso(<6
z^T(LHB4Xq#kywCvYf<i|!;sQMB{2#NcOh$;FcoqcN8<X!3xX&FrN}5Y<DY=a1a5_M
z;;5X52ZvOpO_A(#;;@14>mI)iE#x#%6>1BJG<z!jH(*b>atMHOBp6xZNM_l_Rhizo
zp%;)q{7w~lJxOJlRk@69b`Lh-_p;xEen<2rpW7*x?cQvX0*KiaqC;yq6c8zOSmSMG
zC2@GYtL{ZFTy9e?B&BF=Ek=TXEz5VI{OZ60RTz@GC*DveLjfijG|O3a`=lr1WSI8-
z)>N_$0vdK81nEFtXkxQeTN~Bk>=?K)G7ut1WQJ7!*H&+ywWs-`$c35awNc%eY$5aV
z!H-r@lA22GpaA7Ws!pw^3bHQURu*ePu_k7mrF|tvxlW6S5XEZXY%$NTJx43&<)+CK
zf;~a@kC}Uu#Tr|`#tMUxMG{QJ(8bQ302Sd}oZ;NS?`8qz!0%DW;+d(RWGU!9Fg>^O
zW)n(EwQDxx7{`vQQ=}y=eHNu9ZG5mlN!sXsh~**|uBkZ;h?~-eC(Je(HU6n<4e^;g
zIN{u05)Nx?E1@6}rV~b_m#2gwF!6zo4T%kMAYs~m`biP77E#(4`*SEiA<%>guH5*N
zMAeh=!#hjzn&}mZY<FtzLNdB??(byu&k}oF<Q0*__MFRoc-P={PgOs9(>`J7;-=*}
zkHL;VHO|08)N#L?H$=J^8W-?a@&?iDkCnJ)qkoln<{~Exy0?cZ!YbWDV)bOo#0CR!
z7X$0{C+r-bC*T^l?=sKmE{RZg6<3!rcB@)nht$|itO5)NR-S4Gq7H1*#m?-<FL<W?
zwgt$lwdwJ-w0n_Q$Z-{`QKJnRerP*?ucfe_fbU7nWIyy*hhNIT(5BS0R<O+W_oA*7
zjQ-*bK@V*+fv8bzXsw`|99qru)ipBGa<g)LF`|O(jllF~Hn^D=wo@5$QpTG}eyVty
z3#<bp%3=<H_q=$SJ|)ah@e7LUOLA)W0{ZtGwE{?LVb$`T<?u#wwYjkg(p&eiOqCiA
z>d9D-8i~AQk7}L(H?;RI2RFF4Y;L{*LH=eZzj$<;?GMEff^y>uv}@WkQL_b}%q)CE
zC5XYlK<!2EmT4A)xKlQNbytiJ;@CZIFGe%DiO;?%v?_?`-e~)GMry-zi+EVx{D}BI
z+sQ!<Cwsf-g8{F4w>XMZjUbFCgCT&zZz~oBL9HG~N^#peP810rshfn|Jo$o4-XVzl
zj<Vztpp(@6!yvyF0bZ&6t!U^a%}Fjiqs+@1GLOGe1{dle|MPbMv+Vq08UOP);BTSu
z@%g4E<z5CY9mq-=d9c&~9I@3S$SZHlM<HA)+3m&co3Z)*z=hUQWI@~^gVPXjT@r0(
zB*{^+iwLq02gQv5T=Bht0W3%WAJl6Q;56_pgG6Hm`*Z=yrTQIKWU>Bj2t1K}x^zU@
z-AD+fvM54OjpCQ+o5;GW-FIS)@A_MoaU!*d2e5U^(6>R#wTMSy1^P?IU(h^#%fD<*
z&9cCCm0MZ|)t##5uLI5#9_{~-El_3j$~u+z`suBnEO4DQuzp}3uF}0QjvA#<HfZj?
z4yrbrp9j>kgN-zNgy8!>zT_YUZ7g(+aHmm2+dx#gs`OIzX^XaT!Y`g{56SH|(GTVZ
zTf6fpdocFt1{HZ{EO!hNl*af+7`MTV7oS(li`JmvEDsQitimvqiEH4#pB(wiLsZc_
zFu}}x=G4zZXO6{P76+>$hvCEnlij#WLt{No>#P5)5qy>CA5{p;3Ext4B$(=?p^Z>N
z1^6J-$QcpG%W9YiHo^wUiTbdD5v>SQ_aTFW&_^C)n=*A6xE%ujwM5D10~w`|H|TJz
zqkVsQm_}Y~Lk#e0f%*puIeZpRR$UHXw)96x=+i{uh(t(@6{}cjfkkZek8u#1X2TxI
zP_0qhgAHIBtIV;Y>p#-ehd{p&5@ba&D1(e`XA~{m5!&-ycm&fy0)p&@O|G5&VHoiM
zlT{!)>Z*b#vNhsqyB-0<HM%$Q#JSJyMyfTcgkA^hYEuL$m#TAyZnhRNKUx8<0H-g0
z2r;&}9T2TQAiDRqZX9gAnx_-(AP?7tyOTkD^VxfFiWE`@$<cGP7n^0_HkwJYHPph#
zacMc{wGH}+LtsB@riymdU_gsJ{d;^Awfy$PGTA&n@ylnpiaogI@I1ZKrys+hWcMaE
z+Ql*1q*c3WfsFnYD3r@&Wp_$wt+?B6)xU7a*K1<BB(lyR?wTsgy3s8iS^Kc_n@<J4
zg*Rqfd)XkAgy?8Q0al?;5CN;H#L|J52JO5ejZEFeci_rI(slA^XQs@nRN-#bXIvtU
zLLEMtfYr9K7VrYzbVCr?bkPD|pr?J`47$s{fP}qvehp3@g*3nydWr@ttyW1hRcL<s
zE^&Tj8)&%{x``d`CdE^kMo1cb@(^GvYPn=>%qDp@SXkQ(pYMs#7e9LadA^%Okfta?
zY=`iu2Fw*wqyzgV6K<6+5?9E#a1E>0P4LZ|Ec6svLXJeBKl5niq7+3^gG87M_X23L
zg_Av_zd=>zCa}^W+yrdv#@QO;k1)*4TW!>6fv@0=1d$bUaLsu6oYhNQBFRI@HW+Hf
zyw(Ild27%WOZEA>Emg-lYvxC^MA~c7{H__joMejTX&+VV$h1+7Yv;}5%IzRf(KPd*
z+N+^Ont%~RP>X5_0urrdzg^MP2%MR8z*Jp>djrvdbE(aS;;W5lsATr4baIH_YZX3d
zV!oUJ0-(iIh$*<S*HI}8>g(tld<$w(Ff`FPi|MUJ)@|Cnx@TD{<lMu<5~7;`02Q{y
zK#y=pD4z9TaYE8MFya$9Q2QCG=+F$qj0d7x3RnXwi5Zdbc^(Kc(KB{rT;@hp3aNZ^
z3^G_{)sseSad{%5I>0=KnQ0SX@sn0_dqE*2_CS-45`lPgLS`38)i?`j&DDc{07Djb
zQ}9)&pL8r&-v#z8Os}F$6E;*2fhIw4_w$M{Bt5Ndc25O-X%LJbiGOFC{(YvU2h${2
z4}2J});5>XSx&{uHU-InNkF18{gb>}$Ime9KKb(^B8(TP<)@er3f&JAUF-ZJ+uIF2
zkz&=()*7V<FNd4w0yN_1T!3q0t1MhkRL;o>y==zI%*+nY*6r&|zK)i$0EpSO1%Bll
zw<d{spI8iTln+HQ)#yCwqPH*rncs`{cE2|VH#B?Nmb{%+H|=*1C*(bQBC=a{c0;mS
zpjciH)oY<#;^4Dc<SEZ@H)UkJoJ;Q)YdW{WO^Pc|x#}OzFa4!`Zix1{xV-G03Sxl`
z_<A(aT?94#b-(TK9m#%8=y~>_$IIX>+1s6Ow)pHHp8HzwelWB*i@VN5^WMthe}EQX
z2u3bH=5+}WjciX%<yOkzc1JKKPx8QJDvK|u5kuxHD+8Un*)bb<sMC(+I^$Mh|JK^a
z@)3scR}oyw<f44AK7>bHn7BQWj3DWP4lG%)nthkZBS7Wu4pT~f#=3Ap<x+F{QJotv
z-(9kS!3elBtr~~f<+^PweY+U-4Ktq$98Q*WM#p|RBxV{CsX$q&d9jZc0XWaA4xQfs
z8(Z9urBd$7z^sp*G>c;w%Y#iT@<Y2eF&@}kv7KgxE6<3-K#Zs(n1^d*)y&M|fVmT*
zqK{dWTHa6|LhKsTUjaY6ptP|uJpyUZBPXY@&Z%qNJ`if{fuKkn%up^!n8-QAvY>>~
z9apT|#i0OhVBbu5a3Y^l5u}I7UA>)$9WqJJ{Y}hAx;vV!FTW6O^MXFg<GQ{KHA~E)
z>e=M9Ps|04KWy8O_=ht}AAJcNk%YqlQGLs5HBo=O_F4UH1-k>Rch|5eEH>d#ZBS&>
z<`iYh$JHGHjnhq1eth1l?eI#`Fs#^OuR527>)bU*6j2p^l}6CrMqsS#l8i#)bov~g
zNaJ#!;Rm_I={5s&96e#bBoXI%soIxhg8{33kBI6YZ9&?Y-gz#57gm0G90K!(h(8v^
z<jVu5(V?W~Nj#zY_*A?yc?BJF<%n`|XMUESC;#+5%|A!%H=|ila@BJ!zVPw#hW4%J
zlUblhT|&`Ty3`D~ABOOTrdch3<=gi(KIIvoD4H&Z81hrSR10w5j#t3;K#j#NG;bj&
z{E_yk>7|E@h!7tdxYAElo@*QeGp>#8sSHR_K<4%k%n#m)W&GZY4%VVAFtA#oT6H>&
z4kk5Or8MdwrBJOj>A*#!9wKdSmqN+kzRZZ6h3;Te78(o3?WSw;$$Yk+i9m+%{09<(
z<2+$>E~ppS4eBJkmuoo*>`~-%!{^{wFz)6up`xs?B6$Eg=p?FDdg_Pz`Q`ROFz%-C
zIG7|A6$d7}NkrtY*e|$}Z~j4G@hZj+u!__vDb33_pzWa>u0B|B2Qc?fPG~YH=V+(!
zrm*g4o}w##Ot6X6Nq`qkPP+Q57zHbNM6+T|BsV50^&WO3e#FcquJx<0R7u?HB27Fg
z0Zx*ihI(hfIa!=rpR=LaA<PwM+*^avFkFuw0?SL%Q@%}K!WW|orNmfyyzl9Jp1)7H
zvFg3AQc}1w;qg^dxiT3RR1hhL%rd`RizH_<lOrXS=4KheyLvjpk>NVuUK>dAXb5t|
zkmLSCtJxs7%a6yXJbs&xHX2BF0X_Z=B)hI}Gz>V>f^lOvo*Yen*xbgjGNp4G;#yRq
zbE=)H%h%nHooZph0#iL?l*b*7tT9IMgn`Rguf8^(86d1+ugA}h)V-46I~1n%ohiU^
z@?gPg7G-5B;Vh3W57kaP?yaC5za5~1AK(?7?qQ%gfI|L5o(%2t;%eE&f!mkw?-T`0
zK<tzV6dEXN$q9V-R5qr1KpN_eqWV7ZamexGOWLKju>O|G498AYFZN?VP)40Te6V7A
zKMe5%OWzkue!p6kiJqU-zjLo7^Xg3H&V3(+(>Oy`@-l;q%!rbb@*1mftSJv)xnX~0
zY4XLzzFD5}d$~%-3xGwb#R!Co{>Wco(_~?3_Mw#~(7q4EaAv3q4qhE%Hyl3ZfSRQp
z!XOLe+4nHEq(@9D!Ii!E&hl+o-9Jz%$n~;B)T%DFaaW`w4K<u+aGJL@A#n&z6g3Yp
zpik79j;1`W%oB<-@7;uE?7{QE#4;GB&7%R6+D_?05M<!@F$~vE`gj3$Th^*JmXsfx
ze_Lrq0Ncm@j_}^Za1CxHw87Rt@793GCN2K05>;G?<u)1zhbmP42Y?FZKrb%;Jfk`J
z&{rmc2+%pOy+k&(g8#wIHJ&OCx<=7(4Xl4I%F44C`hsejr7(-3+Z@SHhBvewM}7ig
zNpg>i4t9ug;J1^KuCe70fyx1O^o%~|P_u+k*CXYyMk6BoYBbgH(;sd~Hcf_?zkjXM
zlw1(E(>cTwvV7_KDwa_j%jKqY^IJw0g%2OBGvfCF2HH;@4Y^W^M=zu{7ert;FZU4X
zhz2Y@6~*&O-j85z!<?$L%i?5!^t8yCMi`jlgUX(;0<h;P>&PTv<8#T$-o7hUJC7?7
zpmeYAqofD7#-<>(cX<=n@B!&{s-j_Os{smxf)Zdc(GTOTlSsG+e&~d7Ju{xaD##0i
zEQ}{bM8s}6xrD7=kKTi!bT-f%>^9h{%0wQ!2Fn}$y_UV6*02KCa7aaOcFd4!w0-du
z!?9>>PBxE$#xOS7yfx)#6TZCI#s>z?{x;qo!pc>L3S*u!KGNN^pf-%Wn8%8(!mudZ
zQy(+`R*ah80v>#%+UY^f7{<vw*zX$QYHo4?R<1_=Rn}kdEsRA+CVjP19&*4*sEbri
zxjisUBYB3oNIz*aUCRS<xShfGGns8!$hQ$_XL$p^q4kZUw?aRfrCJ!`Bow)3QG01A
zjc%r;+#L_9XM$<Yj1rOp)AS+2ZTcJGrk1(Ja4n&}Hs6jySR9&-l3=#We7?i2&`aQn
zD_&g)^sYt-D5g7wdnYe9jXeuMOCGNeK~qU~wP7oQKCN1h;D+HuT5oK3UEaqO8;^Q)
zLi+8rd{3+U+d>|CPM;M8HZ<KYyBY}H6%be8tv945R-C;bvpsdYy+gQLzYV_yonY)k
zB<2SNuUdqJAS>;%*k=e&N$ZZLDH<{As}W(K7LQ4rR=myyAx%5Un?N7pnslOo(Bs_y
zO9oL#g1<cLpc`3WKC!jhi{>^|Z5T@>-}NXWcmY*k*b1SdUc-Z-bzxZv32t8BjBd$Z
z?}MQgm(0(IV^RC8jhLFBZeqtmMT)0}L&4v&_~2Oc`G4lTq$#C1Z-LF~>nJN-MbuEc
zPcazjW8M9Z5q&H=t2Z9e1&W3YG}c&Puky_NHiGkBB#qF5{Y}|kwu*8h>+;>j)>{fk
z#>9d@sdl~Imsn2IuNe55QNckN*ZC`-TBzvCu)zI0<WoJd>mg^F@Oqya4@_sPh#7oY
zpV$1>5uqi+Os*c|w5F(W9SW7Ki><ZD1Z_OiOA^-!uKpR?$MBjVE-*H|IQwHF@udd*
z@B>}|3+|}vj<IHnhx~T@Yy_VmP(q^-L0{%}aEXtit-u<Co^Y>3zRDpwvwKMN{ZzA6
zv)7{Cgzk&fTZ{!xI&IL%08s?J82k?b2Pdiwr4I&>g~0a;8v6XKT@)`FW`owCoDXM@
z^NGKbELXQ6cqo%t*ZbrnO2Tnid1ufrQ^F^cVNlEk_+~I6VU?<A5n>VGGdYVPX~W_o
z<iT6;zv~ZANvJL(MzmWZc_(gsuoch~=U>MB9S9;TfM7bAR(RVf26WCP*v%XggAZxG
z43>DAMe^QD4^+gqWyig0w)3@k_c4Ok;rsRMYL)jl!p7^CHQF&jlgl2MvfH?ti1mgh
zHvGaso|Icp|7j;A+*)wav9YA$8yu5ea5`Cb)k5J`bE_ujZy6cT;~XXpSn!;FV8nSw
zoeWwKy&Pupd?mkhHTwM<78fG(nbwI3;=e~P4(H=dk3|noyJHGbYCkK{Zy{HY@C|&a
z&R47QcN<HGDjSq`_aAa*urV`Kv*%!I2=3|y@0&@5FD6{%W4{f*vJ3tW>Djo4(xk0*
z0lG(motx9<CTGrEg0-AzE-!p9(^-jvfunM)MQy4$kkCLVNJ90=3o#VEJT<FG)Xb0G
z9#WZ9F7WhEaAV-2QiWInWv=DozZhvokD#r70JJ~>f50v~l}4xZF|;N3T5hYu%tfMF
z?g!6Cq9!OLfuhr6OpNie#3N8hlpjc>l}ThM1%*kFia(IV(+Q?no#0Qip*WOD9utMB
zM4*09EF0q;=0n%8V)yAprmaG8kWJ$9iPs_XoAbw3@ZV%Vkw<r@?z7sq{h(q*<gquf
zv0&>Dzz8cXez9KPA+$C9iVO+U7lvO{Dedp-U-RLEAyJG@)+mLbu$D5_l?X2ag*xmA
z&3*ML70f0k6`p?x<LaCxy)0p)Hq1HPqrO8+{s`|d#U>d)@^lOrykg<)M9Yx^<cA}^
z<_yN$wfbBZda(5bJ0h@+YW7`nM^E~g2QVl5+0q(tgt6G_!O9uNvqcbDU$=Gqq)vA=
zbBX1k+UM%e+#RGd37K`Bja2cKK9A9EzDz<z8%+$ks)&<P9~N6j$Fm<6+mw%1tuUNg
z2dQEPeZ$tV3<gBw*A*r}7D4wz@xG~VUd~hwaIqiJ^1;ZsPU)SgTecK~c{3~sh&aKv
zI7Fp#ICvR_F*gzTn9%UITSWNr5Y`WIg>i+dc+MVVnmp~S&6a5zM#*vTHVd>IsX>}1
znHY^h&efjkBgyr|s{ED+%Y;FRwMnRx%>MWZGBZcZxDrDT{pD_CC?YooW|^7~s?;#g
zCZZ$OG|z_eg_t}4=9@0fq4-*$X4yI+;)S>Xz#GxT+ZOzyx~QNKVxminJlCHwS^_1x
ziwkzUlk#r!nlP=IlAKdmZN+=+(cfOw=u(Z-bwF}P%`GBauTGO!468mM{#_IFWWnH#
z7$Rc6f)pKhtcDJ^=d!Xnu+1Bg0)wPVtg<#sO0c*r6~H{qpmSmb`Ap}nvCcbwZ66J$
zN#}jqc-hN2T>@C{Ri9zm{vCc+WU|9_ZQiyH2J0z{V3THIs%PtsTn&UHoMd|;;>Pr}
zl@3C-i8`~js`%Ka4)bJUWtPX6&E5n~HI{;~43=nS|BEH2sN9Cu8+lr-xu~lqz@(I5
zR=;2UEe40Ane5)KlWbcqQh!KAaT~h^AIx^ksuj(43*Q^CdMG$o7g%d;57qJha=@kW
z?DY1y_r(vW6a`$)O4^sH=6ZivW9sQp=z4aYA$fcL{A%Cbp?|O>)U#@!{mocEm6w3P
zH%oVS>viYpbnErxZ2^=Os$)y<{VD3gZ^h?zH}1>R8Poe&M^De&UB@ZE(jG@$ZPX<8
zjiAQ;<I~pDwc?ligC2w5lMAQs?|Y~kkl=+)>&#F6se@ua%*r->3;WYK_pAGR9)`ZW
z=NkCk8yp-BHrf2Xvby>m+p*;4{liA+kXChVWNuXShE^)>`<TzgQO`?%?Lk>C_;0p&
zZ0gjXuNtR*F}BajLdane`=vWs_ZEZ#N#7qLXfIC<Vy~ivUf=EwV#hL|`?RJH@fMay
z`VA7D-dd+97nxE=z+S0R4RCA>-tM1nqIM09#Ae5rq~}-SN*FS}^hsyAu6k{>uz|-4
z4##aZ8MN80YGl8*7v_D>)={TMwxm_;(XXEs^(`CXR|XyVh5M3^zqi}6aIXDXaKY{)
z+m;4Be&u;!5uuPfhKh*u>w|n<t|JDG-(9|Uf|&P~kaVq28O^8Md#tbUH)0Y8gP`Nk
z626eo-Mz{)k}3F{OOWgRO61xLRx@bBd;PhN6x>YWRc3gvhYDFKynx7vxTOyH^>;ay
z`RSTfULyYj#r^MQd|bp%MAV=iRW4E<G6PTgrm3x<UeWX8tj87?6e+SCtI^H7W_-8m
z9IMqqFAZC<bb|%UhX||qrk_O132pDP*hICwwoNggkK%-&4bG>w0+5qaOP!tlWPgVG
zmN~(FzW9>E%BBciHrZKy9m$i6;QKZ|bt7Cqh(8o1#5HT7@jmqPDK(d638y(`zP#AC
z$el<B&C0LhQ`@60N4!{$Ri&@2wNkBDMa(N>bpZ6hm4Pv|?+HrQ!0J^p-zD4T17hx8
z?&R_F%i5&T)<t=VZaC-+LBn%Zd1}|K&zaNa8XWk31^BUnmni%z<btlS3JNICqics2
z4E|JbtBOAdmi^XvC@6d@VxGk=y0y>3WH%q>={Mnt5=t|IKW(b_yQ6G?6Ft4J6LD`L
zc3&gCRB>;^YnlQtu!9M{;Vb?anti_x*~r(iCD^Hb3VV5chXW!bMWfdEF?XGr>TD6<
zV+zf5%~5B1!fxGP)C%5^ojzc{_bs57v<Up-ez>eZF?kYKRLog^D9Q1&YTuRJ8+v?7
z+q|0>{_(E)o5i=FRI1mt(f;`OMO=}{;JaY!bKh-qDYwH-eF;PE(N7-I#qRRlXSUbq
z*zAI#wV~VQTnmkB*u<TnV+;WSot}QbC&t_KgH5o{7ljRR$FJkBY!r`uvd{MhZ@*4l
z%eQpjVIjWYr6HKvnL4{TnHkysq3n&V5I6wLfIoi$000LMCp*u-e71l1{QQ5am?S)0
zq*PsuT+9G}Gyd?5m_Y>qlb8sA1;Aut1iA|f{t^EB&LnAX=kj0D=8VjY%m7YMw<`Y#
zf#m)f1nYm40hrW09n1hsN=6oD07?MMU&@t?oXkLdvHaVXN#4v9Xe4Uy0nh=lm_Y;Q
z0kE(#GXwPg5*Gt02FW`E*#FZ&%E{i<;lBp+x01iOf0}?^OsXK&PDXal4u6!Hc>c@&
z1aNV3HT$<D29gpta|4=~sYr?bVg55$6*FghS0@uQXTTr3sUZB%)VM(9Klc4&DLFGc
z3l~cO_kV^Z3AAxBa{@3)+JG!8Zf0U{`j@7E1X%!F>^z)*`ufLZ9$9Ca-X53|&9x`0
z3j!Mg0&@cC@D%A37zw2CwZXw);7RD>IZ*&`jP*JZWAP+JxN9^meOZ8isKxXpJ|!UV
z8_PE|;?tAs4`S->@S9^;I9N(9<lpo$xu}x8y&yhz+&jN_ZM}A{aeUURt>LYG%2pMl
zAr&W&f{X7hD#s}O^6;`KgkfAwDvmD%ysHB9WDrb^FOw84qe*`|n#U6`S0o(>v;B5I
zLw%U+bFQBm_ge#=g-OxR)VO|!$R{-Z=x2THPg78$XZqr0Kaw@t#L~%(XVYR9+%>K`
zy_bQ;PZ;n#GjZ{5cle2=3R!&F$)jv_uh`9ybGbgIUIquXnzr{Wq&}=)r6bA=DLWC$
zKTF#TkN5$uQRn+`WTH(8?Ja*PjE4?}4vy2%k04NKeWHwJp9*e0q%RP4^nIU5bmGk~
zO4CommXUQtJ_TDLW06Vo+>zU#8!w|UP^rgUa+1*24q-@CgfrTE<VjMZ*(U%qq6&F5
z4hjA&RqzWoLE5#!$fJpm=^af0<@ZNR{>^A{Q+D%>x)EGKs-8T^jSCpAL<Db2Eq>}W
z+Z~iZ6bz<msm<d4jLN&ZbTO+i_UtvWU$24##w6&Rwy+~A5rgq}<2E|14I0f%kNpi6
zA-$e!+D!GvMf5pxaFh+2Kj=92O!_0aY*O%4(ik|^=|97ty{JJ7&B*ce*_8BG7T$zv
zc;66<YELY-c;T!UtTi4>uA~pu<|BPH=$^6kbDO{%ny^lx<|0Eowadts@X=40&o{AB
zfZ+5xygf==7f}}sOiOV{efcQQF2NpNOHG)`|5iO@;C;WbB-xWTG<Al4x^CwP+9DQd
z4;j#Yo(|h=!xKM?{+KlERMeAYK+Ox3N)S_aS{D00*_5+z_PK`-{H43~ZumE{PA;dw
z5-SjPgjHZgi+C(ar6JrbVIRefwtDrOEB#xu-D^O_?jfpBc&6Gxp?DW}P+N|<$%#lq
zzi|l-*4PiZCx&dP+>)u)Z{4!dCWu<-j&q;$10uy#7<U&L^vDO!zO4_~YAOURGo|Jq
zXUxsI+WO~LQq4R%JygpIS+ygTmW&D$+8r*+uYF+0tS2Wk-oUP8wC}KsdVX-M)T^05
zTMbRNJ}7XQ5yVXVQk)j6^QfNvW#J<tGPR2y)jDaVp}6%K(wsD>Q*{37>#DR#C$D~H
z0V5YS-YIgNWIS9ppKI#5os@6Fh}@>a&56E675!qijEZF>rXhIFxwLAKc4W>j==rsc
zw+&LADM8G+NG@f>+gjjv&g7<K4gFF!a6?R#ogxG<Aj(e>mK1N|&nrz}gXD_r8dk;6
znh~2a_??C`GA?n5ZjTVP0@cdocl{)UMu2zHXHnUrkyVqLp>>HxpCR2PU3WaK@{e<=
zJY&(U8tKo_u7%w*TE`VG8pod}yK1`5txg3_3l^*dRHPBwqTEV&ERA1jC)9z>jeh%~
z7K=hGWK4XYZUrQ%mDs<z=hP6YWDH4i+WS*W@2}tfaOOpIEuRa>e{Q9uXKnDOy^CU_
zQ?8?kIKiHrXZT!rC%c3hR-la%#wx6eYld>o_i>}*6UvIGPWE|cSg1y(n~?-2{Z_sv
zPr-61=Y;vK^|;kNhRo|wbM@L!j=@IF!#Q3n_xkfy&AYsW+GNXy<2jpVR$1>9#u<IX
zwG}F}>}JU|2?L`ZbG~FEZOt3&UTzHzP#|u-bnxVO`YY^$f>-a6m~%ePMgFat^KUs5
zn)M;r^8VX+W#PdYh;lGuabK*w?!j{CCmNFsmeh~zoO8&d`r5^61Q&QXG3w-yu6Z&e
zbU#Q&bFrd^j&p8y>$rV#x=C~R73YAw^j2-l*PPX$gYJw}8q-9^lwqso%YvBD5;0jB
z_7jR@Oj!y^2XfKe(~wg$nF@pL*v-vUbgCYEC{aF$x^jm@npyrn(L;+Qvm#?Dr=_GT
z!B;7*T>IRFX7lo?Il=VKb*!m9#X6i${-=k9&d)IT03#d0dTH}v`cs5@7tQmE&vA4a
z(PNuGSu*3e%y(+wNQVd}mo1yWsLkKeL}1U_VeX8DAzD1!I7HdO_J0U-Te-f@7xP77
ziaI$AdnK+spGd)1Z>%-_@DqJ}H7qST?pXqz>6qX;NTyff;NYWmlVqHib#~~<<q0_@
zY}=GYkcQpbrpJ05mo_nb^y{3D{iDMT4gK1+<QgC{d7ls`VfO2JrSD;SOzpxViqC6#
z%U1ryO#f_6O2k@Aj~3;`JL!wnNYQECT8R<NY#kc#GJ%^_AW76mjnTDgyIX@sXun8m
zmE?M!SL1olC!zl*pr10%J6;H)Xz1%RCv%sLe!mMj#CiVh+tu7&|JB8iLEO*RPhVCI
zPA*PKhB|2QVv(AnIAi1r=Zb*cKu4<`q@)ZcT8OtUA8F^_Py-i48Sx|pon_s<Dk1KJ
z`ToSsFS_e!rIubdrE2BLZZ&26`w3LhUvAXmh@W{~^SjC=3y*}aX0GI)?`<1AGgiDJ
za(nu5Y;NOYY`X!2*~lz{b9c}a?oWX_IwtA(q~x?Jq9@QZqC4NAWh73aSHmW;=m$PI
ziZYbmJisZ_*Mv`rGZKlK011gyD2YM4+TE_ustZs}R`F)8jFRk=e@SS+6uHyDpzv&*
z<ll8KoUgXZvkdIvt#8uu8DB(6MSlBcC;oD6Hec&`t$i3!5G(<|10~EOkyXf4V1j>@
zebl5hQZCrY)p~v1?#i^*cF-nRJ0&Ehtur<LrE4l*Oht0zXYP_w3NcL%O>E=^3sJUa
zCqa3>srD%)cZioFWp3CLp2A3R+$TAQvV?+|PjYg&dB^Y(<5Ds}yqlD#(N&Uf%lU@Y
zO}vaEa~OM=*TPx-#oV1lFvTkt1^HL3RwTJPWLR7JY&~6vZ83T^wP=$`(puB`p+zd%
zxEUu)FYQ|^$T0;`n?F`G&MJQ|JoEkrgU@sSG&g&zpp3VPWKeq47~D8;E9|8rV^ywR
zk;*HJ92Ya4Kw<q2MS-~&+K!nN#+Vf4g+X6_Li!^2E$TMpIBIsOC~U5_v_%RoL&VqC
zVxAyd8l!BAo_Y(<$8;Nh@^}VA@naQ!o41eFN<YC9$(HAh&>)F-!T$aLWhKc9!RqtN
z&=;DOsizBB*|9N1WO*l7uY8-afc<?gXD0+nR1z$gQXAcGXA8lc@5(`(X|c;@Mp-y#
z@eJ9QF*OTxTE840nl|SZ&qdhlH^2e~>qXvEL?nH91k-PYjn#Mp5iun<9NX9A8cOW8
z>bEW`F>q$yYQm#lbZ=CbrgFMaDl@)({1}dENu6Ol=YVgrPWx5!=2R)8f0tE*LF>?v
zWs)MwnX|W#671Ug^I_5mN>Su-Giky5BlUg%xdR{4hI|a94P(uXOwy+ca&4JCV6481
z;$}aKW_ui}OLQ`Evbn7Dg9;Fu$=xQNlTR?!hqX*Mc@H4DgKsJ0Exnh0pdh2Tn0TM$
zoFw;C0GAZWDhe$NRSZ3IoaFQ2<?-a_x=11FRQiKSnPocr&nUh2Nf-{IkM0k`Z3qT+
zl`pc7R6bMhRPMA{0qv4sXDE`Xl<6ODJ7zgYwRZvPK1&I&ABC1ws3w4Tvp%1^YKy%y
zYm^ii@D7R+ZsVmkhskmdIbcf>cnM0HJ`D(_qc@g0o(_9aM8~uy%rSSHwX;_gKk4xa
z6MZW!PVG8e(;V+lgemG5`Sz&*ZdYh<gS3C2R4@|f>iC5>wY+*~zs1_x>|zVwcAQ4i
zt0JB_0@u`$29);#4a@`#To2wEA?owVe7J!dbLm(obEo!D-uLj}4+?7u_)qz%ku;Z1
zkQJA1n!^f(PYP>aMX9r0$i$?<J)_4-=_5YK^CiYMvfUPuAHPmM$2c|y3rggMn$6ew
za>)nUxLA)gFO7q1NvrLLJO5N@k=yP&lvUcw>e2}Y&eVr9v;a0I#DB?)+0Vv26f~-E
z)U%^u-QgLzcKt$yU8Jr})_8U+l6o$L^DucKf-E8FjHt-6%MI(<qM2_-YXJ|5Z8aiC
zgxEV6{!Er&<1Qv<<@kMIAR=IwLK1<zG~=~Dxq$Jq!?k6&{%hh+U)Y<qd-(m21^CjE
z{VulO6RKfu=X`aJYq39vIv@AP=b&?ye>$Vd@pm5<+6VTTY&6h~era-C$~tEIS?aP*
z0{2pXnBK*ii&a)=G+df%gIGK`Feu_J1QSZ(R56ZIjV!s`k@B@pTu#0qqbD2QsdFNa
zY0CUMe@$0Zr*r9HQ3w4Ce%sFt%NLgYJ%bsm9=twz{89X|!7InnxnDp*K0D9o?{HB@
z^$fAk7GGDcRqNUI%pX(ZXVWO_Wp`5^+!Hq(u`8IuB{Sv{Z`(898gMbwr&*8B4$(a#
zMsgk+Qf0q5x}DD<KWdb_Pm8ha4(14WA5J&<me}F*mKyi=vTZcfyuJP8D;<jJ5r5I<
zIcX!?HBpuJqoI_ck}OXQE<C6c@+!r1OL5gaH6U_vQ+j2ASN4;ZiAF4VB)3l`7lbHm
z>8WJduO@eG)UOEhQXe`s?F24TNQWHV+wlodbRl<Bw)(o-MByZSD=4nOT5GB8m0Lj1
zl<IU|+-NzxQl!CI62fBK#V3;3le7u#4m0q&8vcr7z{@aEDSu4Ujcy>MNz?r{X0baq
z42{y|3e^%&CEBen@gPHmXKF~ZObps~*AK7PpVI_isp@Xp>|Ww>{jBn0hh?Aa(d0t?
z!)#Sy`fim|ti_gN_FKRU3RPfp;wKSmlPDqMnh_$E=`-<-9Djra_3D*2=ZOqGz8{m6
z)}KyunIfB_md?<)>^CvFDnqOE+D%`dC}o#qsOeIfYS(q!JDqg%%x4HLdfo>MGK9kt
z4}R9_3mEt%C}cI6jxdZDA@BGvzmIamCra+}f!7`h>za}Ri%pKic~jpKY7!M>a3F{v
z(*pzpG!l6mn^)gc<C%T^v3DK<b@r6GbDsAe6ooMFTZQS5vD=YVAJlmxj)|U7V#nTh
zWqT6}LnJUrB#V(uxJ6grqq_Ko7OQmZ_lAhEcwWnguxPX2r*T}R^vLZPeoJozxW~VL
zc^eXQmS*g0h}yJ6T@iIRs)XvWFjUm6ARQZ4U3QLMBprA8(XF@7%M-<xn#jA{4@V^V
ztv)sWMwg7sl6WP~dS8WU;)f2W5&4SW9ayDVZiCls)P(8ps_==TmCFw#L+(bCAs7j;
zzV2k@#W*8!PPpCvHr%7<W*?o<PmEC80y~&>dt#Fk=~zjCSF=FVe0BpbFmHt`FO>)&
ze(X|Va*o6a%3Se2p(k+~d$3L6&-hy2Ya%TK&skBZFq?9yW1$f1g}wV^Q!4To!iDg7
zUK0|PIBx+$+P!>wA)HT3S4k7po<%Z}_cauIADai<W=tBD^%cMGGrSO*_lCLP$(nbp
zps8$9fzyy3w7M0)#^{RvB)xFUu&@0%VI<*#`WT2si@LW;Z4>J-^*ReVtPIZ+=^1N7
zrs#XjN+Tw7HshgEi)4cLAW)OXAY22V4#Q)Luy~m0TNLUNf}j#hFY%D<eRXj;#`p_k
zzb#9U-dE~mM?XP9W|<?2gII12l32}jQn;W<wzn!JP%Nratndc%0+Yh^>{@ZczZ|M!
zq|C}hKd-sTRZY;VI?(F8HZ-p=13FRYvAj>Q-3?EWPDp8k^=MP45{0fE=Xr47WWmme
z>khS@i`Cp-dm`w8KwFI{jh&}%RyTd!qWDodw}v9ne>Qkk9v<fh)B0;SWkhT^a;|{T
z_2Jq51Zsv<E5bbDfZ&y_fw+uWMYvQi8kdkI{uy2C!uvfn3}d5syLhB0-*rS|q)+&T
zZCa{Hc3t8A$8q14;zcT4Nfc+)l_C5QBu}XHk*<B_Q@N5W)KAFzsfrCUPTHfC_IoXN
z+B(b{h98GIPZss>jdNljO(>9njWcTaGbwll6jEoS;lOJ)3J5J3$ZsmakKRy?KI6lg
z7*oL*r<2HV$%XN?o58ItnI*5e-oYKX!{pf`rs7gahQo->>}iUTgItx#*df|q(5Cl8
zdZ2fn8Ctc#x7xOKz`3AaG|;*o`wZx}z0kV#JyGAadz%m*Dj@JPx0&QGi~X6NdKbVi
z+x(}#ZI2$XyvRW74o0L7^%g6#Jrq+tutN%>U)K9aX<b?{`KW>8K=~X6yz7GfjO+aZ
z_W)M<r4DS81L^Q5ws5~8_j4(?pL%cZ?sgo+CeCG!zYttmtv{P9{7bZdJCp|(q5>j!
z+xRZ^s{<K+EFw46_C3TV_GOCy7QBaQuRSy&=zy?ZBSe&Bm`76ZCfK-3ZE#pr%<CYj
z?QJr*Z7vbNJmz@>SkYfxBFjwMF$iVom+k&m;62!NwYd7ueU;upFAK)Y9Yg*1Fh+5(
z`XU7ez`zX%ee62fUIkP&_~omFsEgsiRNYHsmS9JjR)}WA<>rNv7Wn0pV8%?7hZN&w
zUEuWuixTiVB0fKpp=wAU7knABA-P{;Jp^Z!`xP><ZWH=6!|*JF+^5=~;~>Om0$sBq
zJXr{5{~$z(*mw$hM+>}C!*#C`y6Oam{_8~Yz3>V`cB-dQ2+CN!i6=`^L6J;Q-8d*U
ziDvu2t}HY|y<xq-1Ozq$T+^FVAH<t1I3jj0+Ye@;siB{+J3#OosBzamLhA9wZCdb#
z3`27a{uL;;48wMRAjF$|FUF_KR)5+>FhMgUek#Lj2oFpGN(f?fB?iL;|1fB|Uyu^=
z%zf}75X2vt^@T;c2N5#>20^feCJ#Yc%nH4l>z=>BhHv_Ct*%+lcEFjUiLrl3A>tPI
zzd}g9jqj5~zl?)&vxV*rJAn6xX834gBE@h$C}D)+GHdqwVlkINoMSO7os7bA_W6@L
zOgX^8A2Ds8cksX1F|995O<Y_H_jJQt;8?ke8Gus44r5Jsq^9261?mgPZ;l}fIJ<1l
z1rri^Q3yAKYi+pZQ08@@q~q~Uu>-`y?DRfwP6XG`xr_u(W(RgUv$)9IUn+=5-wSJ7
z#g}eCmWv$W&U;F6LAgq!$1~&w5hTP<QJ_LalGek2hz|)i4(IBP`*4dGZXLJ`jusSy
z3w{=rPb5>3?Qi))!wcgB(Fsui<>3%0<sZ_i4cV&;c5dtd&zv>0j<!9pGHE#tZAn!I
zLC8HpDtr~Fi-ZJ=r|pkghXYm6Gg4e5EDwONWMtI8V>o;HvP1g52K6#V{ni7X6qmvM
zzvJ3}f~^0>wb_|j|BW>B{O@oq%byVPUomN>|0^E*-{DuigfY7yW;BWWw@9s$sPHhz
zPn5xG#RS;CWsM|YckyIcCV1brFZlK%RLT+4`X4qczlQCv^K;qhl6s;x03Ab&TsXH`
z4T40Du2^}K4-BOmHoJG%<gzv3)7NaZ9Ie)wD=Px`gHTdAZ0fwfIme+QfF-mTvP7Rl
zbksW2SKpnyqADDzOMli2`Vp|J&-=bA5BG`vf<X4?Ui;a|UFpL*zbJ7J8{Wt`HqI6v
zQg%mP#cX4!6|Pmt<Qv}@s_`-G%?9-6gOnnmjKpW&D7la)8sB|C($_#9ECns{EH)An
za#d16_}uU)F;lwvsp4EV*~71FvO5Wn%;F`YzB8%HwGy>Fs<#sJ_XQW}Abyu*XQ)LA
z9{W@trId4QiqFKOc4tPH_F?IF9FGp#Zkf$TU#UZUh-&ILT+k^rUuSk+x2_s2G<^KP
zvnWbX|F_Tn^29$*V`Jm^*Jmt$0{{QU(EpCy|G^f-&74h~fDSJ9PJaUNf58n3Mz$dA
zKweJ!vz7$CxS5rax~nQEr2n6KNh4dJjVFNS?<&BbI@-T0ZHz2Hv3u74NQ(ZAE-<n%
zvoZr1**RGOEL=QnAe4cP^&gbslZ%lJ&_u+}!p021{8u{>XOllL1rICtU&TM;`%`9Q
z1x@A82*r#Xq|Ja9mLMbp)XiTkRTnc`bpZF@?f(>{|1JEPA!s?8u>$@e2>*>J{DDyZ
zw>AFm&ehoEFZe_agjxKt)L&dtBWJU}z?lD+Wq?l3E@GBOPX8J}&gh>q3+vwi%>Uoq
zfWI8__a{ce4g^{N?JNLH8bCV{J7?g(jK4H%08L#iok1uK8_S<r{NEQFC-Xn`oNSzc
z|JNG?9f4~9?;ieeIk^5HS$|)g9RJc>-2bDO6STaz*#4}g|NG)(`-2yO^sxNf`foW_
zuK($S8Nd#jJO^k^{29+5tmhB<1mb|+e}PXR5Xt_t9q<p51Nie@^WTp9-^=(9%Jui^
zlm(jpvC|(QOyxf?mg^tT>%XuhmjA}dl$`8MT}?pf5sirv(8(Ua@{xt(BWQ{=mM$(1
zyi6cK4#c%^GIFp4nmB*7ce0@Ud#Q_o&_5TTy`A_UFpox@mz9~7m6@BBn;GP6R%Uu;
zR%&Ku+W%JiKS<!e;GCEdXzklu{N>`mrtl9m_dlqYhm)B(0yBVx9fA2jF966bY#ab{
zz~4MhPA-t+|EdMp{eOdsnOa(y10w+hki^W*fDwWs2IPPu2}R7*(%b|X!YE>9X2yoV
zSU?psFaTy`G%-_C3k-FpW}xs!)oW&8gl?~ynSlwgvO!a4fkmCA36gmwMTx-NT?C#N
z49=`d1%(x;kO<1p2Sz$5%pn=fGcOGox8QUEnF&lRDglSCnVF@fDVM6MtG^o;0L09%
AumAu6

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..36aeefc8fa67abab03f8c55b611d7aee3fb55842
GIT binary patch
literal 75469
zcmV)tK$pKIP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lw*y^b9=uV1l;&fp%GM5#We
z27(3xWZ?Fl1sMbmY`{2s(8<8gzt0xA)}re4TXovc?MC<eh-a%LQ7RTmk&ETEe*X7w
z<@5haUDwxtelP#BtY5XS=kfaa-+%t6*T4V2*4Kaif0y$5@1Ots-#-8M-<JR5|NQ)5
zef{4{SzrJA>t9~Q9~uAu^Ehi?+ge|}uV1#7*ZXDlYwv1*zy8zfKi-b`|NPh2fB5@y
z#3YYbIls2unjN3+_GPv2M|u7Iz5M(C^0)PGW6Zz*m*wC6t^F^5|8L9x`uC@0+|JUr
zuOnt@U)y<#5YxQvR*j28HxPd5ww{9(*(=)5o!Ys5){&ji{-x7VF_Qlm%|GOQJNnnY
z|26OJ&w1ar^SZET|FW>&{m0o0gkQR~`c*F7K=`FwJ${S^!Y|!Q=V-xxwEvX<<@l;M
zXTSaf{9ntD#ewj=I6IE7(vIv#!Y|$S&wnr7K=`HGR(^~I!Y|$0&e41a*#5&Eu#fQC
zZr*_M=R07Z|CY~xb8#U2vbehXf3q71zjRyoAESZr+^wE=9gT!vx*ea7L{It8_W#rl
zeAcy=y&Ru^9rm^U^$xt&Ki`46ZC|}lf}Dh37WerYt(R^f{L;<NAESZrOSiiH7!8D9
zx|RBspMYrnDfd4DtpBwHdi?|E|00opm&WDu9h$xu(fp;$J{{cA_~qyQ_-bvQ6bQd`
zYwhc7Deu|-LvELkusUzf`adA=i<KXX1L2p&m7R-2HxPd5wzeOmf$-ezT)&QU68C67
zciQ(aJ5$)B`G?&9$f<U7)c*lxXS3_N(Ed$d<hrOYP7AyLVtyTcmh#d5O)`Di+zIVp
z_KE{J*UxE~|M??dzmA&||Bq<*X@ihZC*|SaI7|C{Tt8>NeE7e8j_{2d@F&x3hjTfn
zDMEQtPPgix?d&GPW4FD#Ws}`Rc<gq>Cn~#%@Yt=aVG(7&r2N4qoadMQz6pQwf(~)E
zUKW^?=M{bq#$?!j`jPP5?elTC^g{c&)8{)>FTF^3?zYdzBwByK{IVUN7xh=}|H-#$
ze8jIzB;k2spYt$2CR0CA9y``z{^#tNl;@5go$I`en3U&^Z4Kd_9Yy(ry{I2~zW=@#
zf1;Ju-u(MA%~X`<C2nB>P8~&g?sydc3{D+IdG2_2x96sgqC9rA_588Mr2Nsh;iH2d
z*3b5|8-He@e7?a~F`ty@CE|-ebrj{fV_$!MHbr^v_*we(Lza~1j{EUL_9o>|c4Kc}
z)qdTLKeAZP^5g57l*c8uaY8OjOv-b|a{l;$Cgr)K+1$xn&mG!!mBAwX!5$39+WGq)
z{K>bXZR_RB$@cT&#+kVEBH_8)G0TW(J$C4Do@J+`Ja_!q*4Iy2QvQJdy?jRfo&SHL
zDfN2(_;x1cd5PmpT$d=ybH~2@5c5fS?zpc%#C%eoJ09)Frz|OdvKt?3(th8Kf566(
z5q33szF$9A@^6{9&-rg-_McN!VzTw9Uu|<M?dQDzzcKCUTlmq3j?V}DBXB-aJdNmo
z_dm3}vi9SsuVGQ0+d77C+vk7wzg{7}1$95^fe?l6+z-WD;YEwq1~0bl?x<Lt#2<w3
zq7K`~&DB8}3df*iH&O})*~hQPgL*bUtp<DCDQgMJS}qiu1{!|2-7W0pN(slvAh`9t
z+w_>A)afx}>4P$6vs@_CbB0y_p-j&KWfdp7voaJeJcy)l@H)lY`QT`qCexgqe5pVg
ztfJ?};Ex#;@sET}3^wQJ`qh85OESxxq3g5)r)($uQG@ak?SpV=*&z5pvBu(l-cuv7
zT}2q&{1A$m5R_vY=kvG4NjXw+hw?G4$<OMCl828Jof~h}zDz9+8|Fpbb`6^p9)>NB
z>bC3fI%RPZhYjs-P&jN{ayn%#KPWu&t^<5@`#oF3JDwxcU!Eh2q80eT{80Q%TuC`H
zJ@GlRAH!|aPLtAOaUeMXM~clH+7IT|zxa1Qa-X(o0TztvI=fq(x(_7>jw9A|m?w%B
zP@PdtJHO#fH4V;o4jxCU@ziZNJ}pkxOtNYJ<NR2T?Jezqx47*c((gm!zIPlK<FFk^
z!^C`1*z(oZ5P(7QlTgWdwaNO9bCBYwW78>)7AN`Qs+gaYRSSq+FJgZ8T`oCv$eIsj
z)AVDX%UA!=ChI#kxg-x_M@zE4huB!f`Hmf2#rdRcT0rdS>eF68@-?l~4#XC&I{z^c
z+28Prui5%6u%CMG;v^0Vn9yRwJ_K$+9L+)D1~lKJ55c&L4fj^3_#el2P{@B?cBR~F
zu_N8Z-tvRAX$jriU61isv8U9F?`91jmLG?BGX^CYF}9%Z)54wMJw;t8I8M>ZLoWAy
zTDmj5r>JY*;<DrI8Wb+uz~L>J50X!B)Ak#9ylL4MJWf@ESA!vX7LZyz8fVYI;uL=7
z+)MSuz&%MigWT#V><rxNT6HK8gJOD4jR)t#$G?_A%9RI0n>IW=4ug^l4}LangL&(-
z>fluc`%*co;9e?672IoDc3e{S*sUcfyjeZ;oZz036;-#fn;sLV(Z2YLzIZd|5=T!G
zu!47{?`{R}3@zu|BmgT8V$Ep;+foEpFeyb~^%ggy@V!p)SHQNac@(g%Xg5kQsc198
z!dwPv({qAJMdz@9OR2>baH(iR;&1+-oKSG8=y(*cYMmw&tXiiT;Z&t=SHPZino*pp
z6pIB6OR*S(_=9*xR<I~Fz%^LZPMwjMiBt5T;88m@qnO*EbUny<)K1N4XrkWMWBfh*
zP(IUHKynVXbDEFyqaD+H#_?&#G#x)ZE#&0_k`I1N({XmR6q#$Z;vrkCcTm8a?SzHW
z4o(JIaBVv$Gt^)od*^JR7*~bI42r+WgVgn)?rqa!f))ETA3qswpXOs2e1%}xPON;J
z=Hn-$ZPR>$6<f~7Tb#;)7pHBS&4Du@jS@=vpl~(^7A}o4)b#P7&ci%NK6ck^4qvzo
z!|lMr`!t_ec$bE|9awpv<`WB-?1gvSDe<yzFl<}XM`t^{iSNJ$qqIrx!U}N8%HIt6
z(4cmPQLs3{^psd5^-fp`gHZI4SY$&h&bUeQhS4xcJD(BjlNg2-F(~{+td4Sc`H-Rs
z7Qv2b(nDcs3<|d_Ob~dEf`C1&+A$att%^%-7__P#gJIAlnm1_utx7xEws>nLoi}Lk
zP11RTcHY>E1s3fWweLo4b%SQzq^xext{aq9m@lJEzCZ<TMN(($Sb*d*Y?^VcM9x5^
zZR<3hSimap!v^KFtvWwYP8+Q74a(@J&GQ3gv#r$JU<VBfcMhs$TiHVB6W@B*4^0Ak
zYtZ8D)TTilRCttyp)?5GHK>DjPIDXUSq2G*yZPU_W6<mDWXp$;sNO<>Gm7eEP+U5i
zbX!<ggTjfqzGjE!6-RtfI4?iti<5Yq43j^m$@yj&hw+WD6y0&^odV5!gIZ-NyF-bx
zl-$smOzJSqv_TouTY?mwz%*z`wrg%sh-^nIW|~5~hKwI1ZeYQ5<qO!L&Df@?gf?TF
z7!@zZGDw&U6ctNJ9*WAK@bp7Zu@vOcN~}v~+X@(-vfRJ#*75InL`vHg2e9$wUEN7D
z2xN8~_(37J@zpj4I$1x#1_|KK@3c_@haorGSYpRF*&3JFPq0Cr0GM`z!X<WmgN<Uj
zpYh5tT5}L$#*oUe^hO)s($3GTNiuhQUd?!TKa@S5i}L}~??XW=CR_EzKoFgi^wgNF
z<aF4APS8_hwh_0u48n>BbGmTmn%tZ)7YBv2jc=k!aQ7Ww4P!H=D<=bNN2lniF<WWb
zJ^YI1s`Ua&Oc%1e@BVMj6yG<KWQQp^D4gkr&$SiJ6`wO>mocWKJPgZ0!LjXdPI(|o
zOl$KN&m%rTCV>tEu~s=4diXx7<a6)w?HMF4KYqZSf=i;pr3zzlw7GnI66zVE5TrE*
z=KB4+P$jQ>)71DL#7CggAF&t=$U)-tVei+2uK^7FDk0usyH^SE4xhY}NbuQ70e6ei
z+bg>`^Q(k<n3PW7nJ~@{t(ckoxgA2i%E{3o)9cRJSI$gQ9%kmCaQZI6M;on}nH2UO
zHf-IK`!HFn{2;w*c9cU!vm^ft7?++A7@mW~B@_iM^8gi}o<0s8c4WoJVR2H8-*o&U
zrl*fZk70RgVF^}#D8c|;oWcdIni&sN7@!{tTK<~Xt`{Fdzvg$N!&<BKzI51XwQD=p
zXvG-q#0J9e+)jTJM;n^~Gt?=aeY&?RyTtzK`UzI3Q*g8zWVyP;=E-r>4s4!2X)r+t
zC6>|-9xa&^4JJ^PNzov>D{KlxD2{g1NWr2e^|>8jk{muh)yA!9kkVB~M++%k^~r0L
z(pBHQ=66q3?jRVXPFdNh#!s+9m>t#Ror3Y{B(~T13HJv#6bgYgn4g0JrMJO|sQM_v
z`m9x7#Rik1%7B6OS!<R2g7rB_Tor7Bs&6Ii&q2YmU=-BKGf4B(Nf@4jy?(J%!Be<#
z(EqF4QV3gj3IqiV&_Uu#o2J9#Nl`A(eS^!l^09t0YLzFeL3^*VmtcT81?#5Z)>pSd
z+i?=cW=4eEU5%m}AL0fFYL)w|!ChKQo><d-Orvu?TzJ)dxNu7Ayg7j3`6038579Rp
zX6K-A;c!4!`Ow1bT%3d*ht6H)RBIH@GTvZ%4hlIz?_iYz(26F+<6bl&o`RwYLApSB
zu6Y>?<I_o)(5eaX1%NBAu4p-9iY{y03Qtp!Y1kl>i<FNBk6Ph%M}tHzQbt;+-HVfA
zGB7p=1-yW{=@hj6EiW=CVQUVGL2ork;vz3#n3jW3`Iv&o;FMU*4O|K9GS-N9!ysde
zZdJ_POhtw$Oh>20mRKmq<)B&z!*Ni+1%obJq~;i;Y&m#D48a8DkUX?qvmqa#{uZe|
z28U0PNo(-<ltY5TAZyD()<Du0DM+vwoq{Ps)|NwVf7^l?_;c`I8dF$?gFs&4BDF|`
zqSZG@abzrRD2pzR41Sg(oyy=;DY{BB$j`DTuOLE;tZ9S8q)62=h|sc&SI~w_YF{uS
z2MN5wC0da>W=%^cuNs$Lpftf`tVIf%!KqO;F%0st$mt4u&?y}cf`}|q*<k+-3U~+s
zS)|1o)Y(E;?P7+jpCYRt7T=)oMTASDK-DvdzaodO)iAY-)IAt)PQm;j{w@?Q9XzG<
zD^dv!?t~(D0xUGAV8%r&CsRY-j|WB5)8WWpXre`0WF!GN0kg;50x64=g5h#C!y+3L
zFr0Eu9t(qep>#34o*Eqtuat9gQCCX3nZmIe^pFa<CM^|am{VdIu)3TQbFPQRN=m4d
zg~}{!tf~xXgGuF-*o1m;aO^>a>0eUctrTV*tvJ=vcVP@&DZyifZqWX55*7ukz36_k
z?w1yY7?tK4PUzC)Muimv5-1!Q;-x}6EYhoCrwj_k3z9lPa!S|e9c>H_`BS^b)=qke
zMA7AIr5uwBs&);X6pqY|Z2WG~O;stzCc*~Rac3Kb&Nhdp^BOjQlfVe*eG>(GUy(5Y
z4gW(yD@+45yC-pQ-(i?vC^de<g8<#G<fR65awmZ)6kReeDn-{!iBsnm#}X8djssIU
zI8R5_;G`6dtrxp!a2_ET+C}cXS~Pf4ICz{Oe-MV}nJOAS=C^8aw&O)pP-0#AQqLp~
z&11G|=%ip|p0brK=Xg0a5Dpzwx+{g_#GxyvhN%(!SWXUuQ&-MQ>(D5WHc*+a6eyxH
z-pZk;icqlkIFx1Alaqokj-iRUqE#ac8>h1Dmlm$OiVVT{WG+8Q@k9lKem+TatLH<&
zz@9yze1vEolsKReh8IFGNWR&^ca)UnLy9IiXnbZ8)B_Bx`iTe;t5bA0S60n7DK&G~
zZ4FI1TZWlahOSg7^@Mf%x(vH^{URxsxvwo;HW!Ne1V>hQ87B&Em&C@^zR2bUZM$yH
zTGb^fNY%%Vt~ER1x@JZANgj)}<a0#XFNbX{Uq9PnlE>j(Va}mNokk~nr3y1sruSoU
zLg8x#zEWS|i&oE54^GNHzrD+#%!JW4yk;%}27v>Kz;Qxs)Kga1OxkB@GzdT2947?W
zpl~1<goDJPLK4<<*ODd*M0ZD<Uk$eVGD+k?;K)fS7g;|j>qXYr6F%7dL=4jPqcJEP
zdjmVSul}RW!Q-3`3J2di3H(}unLR(2qUd88=al()`Pm(m{-e#YPw=i&>?Q$1qIr|n
z6<btERxobTNx-Hiy%4J8AQ`kOo<f*bO^0q$N<c}aBtATYazMMmIW#GyJanePdCE*<
z2W1(gI%{l$K%JCF$}X*{fjipxJ~thps)3UtofMp@sgr^Y6&F2HWj~}#t7v2#jY5T#
z=b%U-#rI~Aq=$nEMI-Yh6sd*W_#%}QR}J-)sf8A;DsFX%q`6Hqhx-f%R$3#2M58Kp
z@i>2&IfHUFa|R_Ys%0Gw(riDCHmw|N+mRL(_T)&53g53mf|<i@I;gJD>KhcARM?jz
zO{!2soq{=IXO6U~unotxB?F6_a_smH(%2moxDL>w*8s2IvCEdn9vr*e1~35ziGBm@
z!LiA0fIZmcH6X_~c?||-2~vNhlVG%I%5x7kxeem6T}}h;fP6)p_}%3&A-}u42IP0w
z%6C55r<ER*K`NLrIo!2ya=2;X<Z!&6OZs#MX>$8`n~o_Q>!ZmpMUGN_?MN*d@JaGZ
zVS<)^DNK+8Y!?S9z;=eW4H6wwWFmb<yLf1FOp%B7O8?u)D8u)8Cj+ZIa^zP1njL+k
z&1I8U&?s@Nsyw1(9L=gjjH3KH#3))-uJ12F>F{HcQ6(Lsm|IDQ=*cG+I5ItsHb``c
zl2H_3hZwcWBT7cC@`$=E5hVJ4@e9LK$f}jzVe)F#Y{09XVJGrK57Hj4Y;b2ku?O^J
z56a~19?jSS-Qo`tz4740PBBNvdfh4J!u3Ad2Oi^$S)9bn0q|j`kfWP_P<S`6^Etd4
zK)}`@aXMfH69#qdP?-Vf*AkU!db+l#JEJCbx54~ET!4TQcaJN110T7rQ7W>=mb`1J
z%>UATOlAI-E^R6kv2?LhkutU9?GN)AbwN~_-lR*U$~+}qG*#vtg~h*s6cdUra5vQ=
zUhp!qh!xQ4bS+kQe7*AStTO4Q7BK?>iMoViawV_nDidSEs}Zwnnh)3AG#{RdrulH;
z(D>qNkq_d0cnBKiQ_+gKRJ|OGBB@$9d_{Q^TA2e<s}_!cL0zd13h!#UaOQ8|W|qmG
zd3RfP-bPj}+%z9-I4>h**jFZ1=q|Z3g+dq3mH836lxET>F0T0?-DRKb#=Gpw;p0M5
z_S4P_Nn^H4WdZ~4+Uw3(5g9sr`I_$QnOB-O`h((k0lM|C%pFi%z=tvg4lwOBV+)XW
zitvL4lnoIH+&G4YNK<EUzXBa9gZm>CA~IYH9<ymE#$n)mA~#i07tBq~z>K9bEML(Z
zPKhWJv>2&^B{AM!AtI5!8gVA-#6T6SXp2Wc7HtRk6oD$Ey+;%ZBHEbAnxQVtWK}c_
z6Il^4LkdDw4jco9zkAqCWuUvla+u$mp*zfPRd`R`po%I2s4|dU5kj8t`eFnTb6pi<
z<dmu~qy-d48R57wPF>MVBL|g}<K9p}E3<()uo*kW9N3Jnsu71?rG7E$oKaeflWN9s
zF(EeNyqFN1v0zAueJNh7Mo4+Yi*X5Ev*QvvqubC@*c#d~vqLY;)*0Hy*;9H;17hqr
zBIqh(#}#C^Fl9C)@hU^b8LU?sEv|UJ$f3=UKhL2(5sipf9<kwy9P}jG76FOmKIQqT
z6&Ui16s1@h5{@{=ihythI(nupVix&&+m~V`7Z41wkX!(~e2TfO4AYhtfK1s4+l-?C
zZC9b4gHq?{PtTl<fK#+qgt3wd%rR4hX;loizSNAtF5*F9#3^{-5<25ttHQ1I30AnZ
zKEaB%W=t(|YY}t%X)RMkt|!%=#}u^7G}{d9WtwdU|2oB8LkJMAi0IZ=R8iekGlc|K
z9I_|g;<301a*|KgqBTW2dm8R}Ou^7j@kh$j*iVM>%9DuHTn1i`_8ge)dAWG(&L0?_
zN*xA?x)}rRl(kNA;vdQsNA5|wh-wch%B<ZCNB6AV^PED~or0%A>U8&%D)60oyb&9}
zkkacEKVKQm9pf^@S`G_^SnInHA=b+j#?Or14E1N$Zl(h`1<43l<IaqNm>J`)^_fuI
zwLT0T(p%XJOzK6710NJK-qDH$%PNnIUS&}*p_h3Upu~CIb1qY|hUfgA$CS_E6rU^e
z^(w&5kr=X&<Rh^Q6I3`eI4hKW!ld9#QK=sD9T_T|T33cjP7fI>IlWhA%Tz{zGvo;*
zALvADj}#ux47xk>b&y5;%A6jjL}n1@1yx>|LCh-7?4jC~E0j|UQ%p%nOf-%prOFs_
zB{4DUScy)RLF17NwSa^~r!W2_k||}nb!h)>)!Yzj!_2HqPR{f#r}$V!Cm$9;E7Jrc
z#SXGOl8Iv#klh_$9wnSP1rOf&lMT=1i&&LZhi0rm(mI08l^RzWZr)_`bl49O>$rea
z=QO;^0CXklG4VN*`D(9Iwx4G``-fi{fll%t={~8)_pGHfhRxAZ7#FzM8l^EjK1yF?
zrnE8~D<jsM%n+nb*VYy^V}E3IFoeBH`W9t)l21jsnl&QYmnoamNj|8IiM}$wlbeOF
zqVT3G0Q;6qEoI(yrk_@ZzAHtQnb^o<CB<EuN_HKjI_JYOH9IqAE5qYkpC%N`-lQ%!
z*hI?DW&U>N@G^fp^L%Rye-(nUm!QP^CRc64hgJ#2O!3a7<3VBe@|q8d)$h}Un7*77
zs&f{!CxV~x9J;X@vzPa2La};Da0ccpE1SvU%G{15?$~;{E?byqN&&BpDb3Qrkx`y$
z<O~1FKgEycbo9#jer2pzM))hM9fM+hdQ6?u<2lnzps!2<P?9|tIA!7wE(A9us~hv2
zC90V%ptOH-bHWC2mJfCaK!BT&AOlWW>jXr=y_?Vq1}X41)@eoogdq9caL*xV1fG)#
zKfw=^&!|i@3LpeI!5Y*Tfi>t<CZfZKG(kS_ASWt>Q+zfO(M)RSRTf+zIwk~#zcfBQ
zIi?zHR>4^CT_e&(q}|6;4m~BfWoQvxBWFT%jgW$E3r$0a9F=(zfb5`DNKg-_tnrYY
zKMAx5#czE``lf$N{3O1JizuI(Tt2NQD#^*;xR;?z^=0aXz)qaf;yH(&6Ks<VZuE!>
zS;a}O1Ye<?O?(!Y#XdnvU}kXibjd(q3k+rufa-GSF~PlUT6u5}DzZ!TU|-7C{z~8)
zeoYeF#=kh{@k;y~e1n!3P;yA}$?58<0d`1E5ay2b6srx+Z6WsX3z)Dz{*mnQ<V_EX
z2XonpD8zflmXJa?dQcR5N=#r39n;F=EFQ#*n@PF!VDT}nJXm~AD-RaK1K|&P0f5PW
zK-eK^wvDhuayK-h4)MmL84NhVL4gFkC@3rmCsmmqv!z&sk{Z_WLeiN2mU0n#tH7;h
z%Ap7KgvbiLEFjn9f`HN`sIAJ(8=-N{6#c@NC`hkCaxkuvTnOYXc^9DnC3M(Kkpx6Y
znn1{?NG4F(hcW?~v4v49(bQ7-Ridd~TVj3{xLV~iVzV-$sD&>`sBII0oQH}o&^M>F
zLoTfEWg<!cWa<$S=BRro2;EH4FP2y0*byTmvF<LElfNOb-l`RZDZiz-s{+=`u>*9i
zYi!?S#XTeeP6k*Uba~E{Z5leZeVg_mc74;G<wWAP!+9p;!V85<cqRJbr{xHX{?8&%
zMvj>jp0pyEMv9&yOh#UJO(c$qDBvySTv8}|!r}pJ<Z_{4<6#1A$22%8Jas^g5_;t_
zlMbySj?^&?9u(R14aOAVG(lKi1l$bkREV5YJ4cBlc21)N$mp6TL=l2$5wA$$Fn;9r
zbsC72y>p3v2nAJ|lrlYcoWngOmIzJLi>M;OrdDRm?PYqfpUgc)R8sPkgokLa^Rowo
zcZnfbk$atvL{KcBLrmFaYVu4W-dnh|NlDcR4%t0bBbuj}1x!;R<j#~F$dBsYr-6d9
z<(UtQcHgF6PLNlOd4qe}RG=L2`?df(U<^q<<WNi|M?P%&Nl-3}9-)haG<6$`I{M6&
z<FaT_#207fp$zgQZS(dVDSM)oZ@h2jv0b-!iQuaFoCGCL7by84KV8QxIwHF7IHs4?
zkLfXq3KCK<jMIJ`(}O{vYn1QIF^h$uOhUk4z2lr_OiI3s&dXUakn%$ioa?j#Q4l~J
z^5k5n_q8K9aFS2wEEY(~cQtMn&N98MF6ho#F1UC+XTd<qMed$?c`}joI**fj&T_&D
zvzYLMde(V`Bu(F!!Oe3P9HgX7^22&gq9in$bCxB3SWn|8@0_%m2w#;V;0N`z>qm4^
z)a&%6J!fTxlvJYppq_31q@NkCJCW+FDx4{tM96Xd{GBboX3#*+S(PE>)C&B-oqbZG
z;&}BOI}+{B{!@!O`=mCJGHGnS>{)jSH|seoFL8dhNo|VbvQ2~e@t9Q?5Vqu3?EE&3
z6+6FQTa%6yyPgupmS|GHj<EH9QJc?wG7e%__sJ}YUELLHB+@aN2flBqm%#6R9$y!8
z;heORB&8h^yLL?GK<wH%nFC#!18B!toei?swAmnwO`8p}*rCZFi;SQ1r$OfV5VBuL
zNyB6O+9{f{hf8=~h2}hV#d9xc^hR!m%+RsALAjctBb!4nPuQwXlI1-9g$$4%6xzw3
zZ5hp2_Ciydi6-%zF>{lB-h8TxmU8>tvsW}(XZRpp&HO=0>wELb*2&D@&UkPd`Xj`7
zP_Ax=kzZ3ZonWs`i#~k1HZ9t(|07Lj5W4@FJKe!bIsD;Rv9+<~6QhG^fh%TE(!pdt
zvDv{Ce4HIj!N=Lb<Pv6((!&%FzWA3saj9s!!OPjf6uj)Zu7WdbkkZ4n_ehD-bAoe|
ze<>KJ+-3UKZ1r%Swt0$Gy8D7{+w9$I2hy<6_DKM{F-Xq1Exmier4(QrxRjoy4JQsl
zjIPN+Ap19PX`kj2TuM>4fh8%*HdiJGWpcQ#@tmu}b>yGrbb?K~V{JS0(_)P~URGVO
z!u2~SWd06TrLMJuSx2gqI}TMUTRYg5HrNh!rM%n0u5+GIu!m;Z4(6QGeBua6+U?*L
zh226=yp<I{aK@B%nu;@~@ER2ke^2$pn|OrYFi0H)=S<NxDlQiWW#>=EktvFf!M%tT
zsHAa+VI^Hr!T3R`d_?zVPQ&?8ie}*lbP#eHzW!2j8hbn>rx6TL%NJi$9v@hK<uu|O
zH3*!@iRIJ0iCr`$EH1c<vLa3H#OhN_hN5l7(2B*Uhy=>7DT@wQXO<apxTP^BuEhnM
zWeOTDZ7g%gaA{-3risLYU2NhC$1*<)7lxLZR&l4ZIEfdfYpgeeR8}l_zATLe&zGeh
zif?7UF6|ipdR;n_VtJ>$Vw30FQeStM2MIT`R_5E%Sa@ER7H{Q^@(K!XN(+}Moe+0N
zmI*buJF=1iF9j!C0WXEil+49#k}>ZEH{O;hEx24VC9uT3IkJ#>qaAD9+4A*ez)OwR
z<?`M#nWR^)FT-7GY@_`82o$i)3_&n~Cs#8F;4Au^8A=eVlk|;{1?6ai;_K6ODIy;%
zQa1RYSks|!i8!hm;9}S{h9@HE!jyZlFfwDLoqy|E%QA-o0Uss|AqIt5W=M3StjVYr
z6z|Q92n3*5$*>l~0y3(_f=w354Y&}q%w)iYm?>`|Vr4AT7H~mkk)yyc9$!?ZBsf$f
zfC1RXKpAqgVW0!ytr7n-00_8m(9<%z05L>BEf|F8kYP$LNR3GYxKML&1Vua5F0_Pi
z-LP3E2;hbdunThxm1Vd;0<8ew5Cms`hV~;~%Mi!EjBqZ?ApQ<rsAhx<bfKCNE}{Bl
z#C}KUnq`1K?&VCe_qdj`jJ-z$+n`*d+`Ncn*K=aJGRFHZXpQd|L+LC-?Qw5swYgsz
zmv)ws^}t27n!+23Mn={n_|FhWj|as9GQ@C?qmeO&&?FQ#52#n0!sdYoYZ*2V$XMc;
zeDm_pGEN?$iVlmi@+U44EMwylkLj>2qI7R_!uVR&6safnVB^PdTOD79LCW~hO)=st
z*vptf4`8(^+#3<DHpP46>y+`{#o=-|NWmbIgb2kAj2#B>cH#1TE8^FtsO<O{WKebm
zTNVDX1w@lg0oIVpik*f`o`R=qJT+sdA%8E?(=TEgeaB7On3=6?jg^>`%K+9ERMK}|
ztT~(#B7BGTVpH&Ss4q4}U;Cx$Adn+4&ux{Bf~z)wJALz7ZD2!X5W1h4DFEAr<P?34
zoM=;Qb;Cm?y>N-<6b1M@?~OWVgyIA4ioyAQq)ibaeyKK4vp6@HhbHlcoB(6U^`d(<
zn<A_?%!UEhkY7`Xb;vJMp3+A7Wz<bQ@4<1vI=gT#nNSgPF|=IHTIM4m2g5Sz8hIL)
zQP;SAa|#C9V{Rt7gWI=3;!f{h@e@uTMvzHHMo9$+R?|R7tWa_imvNS%*+_D+49!Lo
zjAeNChNvo2d^RrV9Q$o$ua4(r+K#_h*5<Sw0LU?I=fG3Asu)-KNAXh0y%1M*PQVx^
zH*rosBG_F}f=zS!QS70#W?bkwjvn7`*a9X&i+m}<?|mz$YEYOX23_B}-bUnRSq79N
zf6KxDR(9L)Am%@Y9*+R?<y-fDmJ#NA2}r>>-pDm`3dSkHD{9|+A*<w~^_(_B7k=wj
zFn|rel?7)RfQ~#lpdl_G1*@o_BjJu1ir>n~BhKQtZW0GYE3DW%eTR?%Xc@YWEJ1=g
zek+sE5Y4_Q-Ow_e9T|yE!SEE&`z5c@GQxeAc-99E`H_UC{8kR7WzakFED31&oynL)
zz5G_jrbQS$GCD28;BmX@l*Zr0Dat%2<c>N5C&q>zo3Zl9LA8vPN1kfncsjQz#^u}D
zyXM1%cg=?j@0!nnh;CHCb5iGnI3F$?im9pP56L`l1l|&>G)OU<%=F$c8(AsHD7K8n
z=d~?iQG>MMK}<u&T;_CUJcg{G>^_x<x9^(IK4()~hVbvZro+<?#nR3^?Ql@FIklVk
zutD)toMHY*4=1W@Q2aEQBL9(RZY@*0;Y@0o*$qM6GP4^A{Ko76q`g~a2Ou%tDVPp~
zbLI;m!QL7X{h5VtEfc$4Ic>VXL?S;Sd4n=UUn^+D7pzHDIo4>!EC3%s+~02^3|OOC
z1`Gm=i{1sK_yrLWAb*?UBmj0`OiutDf;9!d9=Pi!O!2pX6^Ld0E${_X4g>HRtjWRy
zhQmTk<Zl5zSkn~-z#xdE{4Kx;i_8ZAN&tJA7!%G0sZju>u*`<=pag5Q8WEFVO*bJ&
z0D=+r`I~4MLBZ5aK+)eq(-@SFb}&G&X9VRS-t@PSJBUa9Ep!iS)XV??Vu(sxzJ(G(
zVC!!oiCB|~3bYZzVSfve#G0Yy>yrTsOcNq%2gQ%0?v??BLKyCEfu$_gX!auP!ZNo5
zs4K+t{uVHcWwr;vTYv(-fE0`{!NSBrkXi_!7($7E3rfbABeDo@#*`%DfHc;mDFU+w
zsO6v>nD9jL4_RiG03V0&=RpaMH?)G=(k%hR0|<43>;%uHZXTh?Hks;(3^66B97jO4
zWA=!oy^@08a?ApF$eQ%igMv`L+5?!d##EQ%(7;z9Bm&8QzX+CerPP=|btD9n5Rm>G
z!6eqG>LQfHnp9mtIT6)<co7g?k|aVxSxb1Tl^Y;<sui2i(efiN1sUK}SBkTLMyHA+
zpXgMDM?TT1V7*@`u?LJuI4S+)&;SM(DgY3J3!@W<jKWW<_!+Il7>k!}ri8iDx?smR
z@D+8;n(h-%sFoKB2j)JW_F|2LZv~uODK#b!&@l=->G~(G^RFb1%xyJ|%x$H#OA6i~
z)@Ar+*vXX;!*6KCnq@*D=)|UkCj^~XlVyRR6U!7R1f5(dK5`fzfYggqCws&p^{mkx
zK@7@;z>#@6P?ye{ES7WA&=cj1>G61M8agR4H0A2KX>gvIO`~_Tx$0<B)XA?F$cM`h
z5=Txj#Qvkrfr(_dYhax++(b6T+MS0+PYRcfqjqR)B*1uR3af_1FZQ1Vj>Cg@YMi8K
zl{|T;MoLONnCI@~NJ)s1_P`gV*xJ#Gr3f2-4Fzp(hnP^Ew{_*mC`pA6C0H)vMy`~2
zaGXh7A#8S<Rg4=!eU`*9y%6}+IH!O@O~OLBRBM9PM>xlof==i0N>tXF(x_t!#ed}+
zJ5w-t%&vc3Tl{%X*x63PD`9A@shq%iXsStxJ^-05QDN>%vGekjLY;J`)XUJg<6W+#
zI?cbd`QLgVmW~TlQ5GQtPfRSGPfUVc_onph6rb7wRy=KR*|Li$9fu8Q&zqhB!hShd
zfvG$lJs{UjhqLTjPEz<#M9lNza60#a2RFSf<<Q)cf+xR(Grg#JPH!qOs;>m2kN^Wu
zeMf+sLpbb|8-&cBD0Q7=4{r6YgmAb}q7k|KLf|MN1&IKDrBH5f1adF>X5h5Oon4A$
zqLE)IeUkUfw=U{Z-t(f49|@wPXS-@-qLJe^;zHrjIH0v^=%nzgfg?*Stt*Lx<B$S7
zUY}Up%U#+Wo9DFJSANL9iC{l{>v;`#rAR|qJ@SedZ>ekW;_XVocLc3jcfkeQ@`H3h
zp~O+FO`0hw@MlSxLJfgg<6@zKD`nE#Sgas5JJd4(VF86>^H^;fo2O`#Qk)bj#XXBD
zNIONFgY%4R96SjeJC4XQib15(%&WUAg#+_=>>3xxVNczZ+rLXUO$v2WZa+)|Eb!3C
zD;IcBFXhhD7VBuy4&z2sUS&OugXcZ#VH`iKAr=BjBMP-bWM;9P2<)&0B-v_c(-PyB
zr6o2|V9p_*o)u4MIr5?}jZ5C^r2)!&y);r$e`U60agBE+aPZhRi(#=pMlV!Wvalj!
z7@K58_9(W*DDN6t^gCcnc!`(RKQHmpMZn@WS4y2d4XmNF$QQvIIr%GIti+Q(4OZ((
zzXwbDIAsB$V9I2;rOyR3w)DARekO;HvEq?w?clG;=|Ud2S9*kaPnJ%jxF(w&OS}~e
zzY}XHrC*9SVClQ!r5F5Lti>dk7r04jM<jn-YNaoY#i8hLTfTLLWm#$5x_p0p%pSf$
z@{%f&3fkH>dj?tDD!qrec#?mS*G%bvjB6&iC>IdO1#*&RnObnel5aH2R1()@mZ@H!
z?Q+ACZ@c`k;2WJ#D&U7(o+TZ;ywpiAFz<BeC*~badXiBN4bEoPLo+;uoI1WHk2SAi
z(x*Kr;S<-9J81r>{;v5n;$PSbRq`{4!BtG6QinvcZ{350_a495@EEd$f>5RXjDips
z1#uU_YYKl%qae(}ersM*#B>@3VHWmV`6*ImKPrE`{$SC*ydvR>^BRT4|CYFCAxn7?
z6O@QZ$ijZ`Qf1Zm#%s|N7aKe#mSx}@FGf{rxba?8h5Z^YM$fo><ExOjRD7ZGDvR%6
zUU%_L)|J?z*FEpe=oZh*H42-!e50_+%Q=X*WxBzmoYXa+q-$OUQb^}@A?jQ%)14we
z2)K6CcO@?-`EAO}OMcRD!O04roDa`H(|ow_rupE_U}lE#?+A)erM|}C78T}WPK7RZ
zsQ~5WuY8tyLreuNuaW6-<V7<T%DjrE4vOpQ1tiV~XP?n6vL2b6psR7J{gjAHkQ#30
zxl)*|x`?Myl$Z51$#|cit{;l$@f%)@%3fkd073^~2WM;n4DdPpAS`<YDA1dbAq*(B
zn^6v|#)~M3U{(Z9aDfoO3Z-Dp-wd~4UEmDKK;_`&g}@Dv7&pSLJQO$5G??N>PWC$a
zAik}q;zqctQ*k3av!~)l__ChlR!4IVdtqVbjEpfvyqhW}!~Qm1LX7IqCa6SKhh}sR
z%SUJY4r@$jj1THiPjNu3Q=PFwtYw|?L@0Ru%9tb8#9lHm$q*ui)c}z!gPTxwJL8{N
znHv#O3rHD7^{w*W8EC~4;2Dg?I^hb~T2xHjgr#XHI38hN20XY73o}HED{{;tHhhXL
zvxp5>^qF-Ean*KWAUHzUtW$zlsSXVC7Wyd5wr98;O1o!79jm`nU0=RYAf9C?zg0qB
zk$c9FZUy(T5Pb#!ngX~HBZ!js8AUh<jP@fV8E443F+hbO1IDmwlaA5nfJf_$PLVo+
zFlvQOT9;s6waXODQXV=5vuXe{u-Zd7Entga=`El{oUil(52BU^pde~#03AXafu^H<
zi9{WQ4PCf<dj_*whfGzt>!4Ic#4eyjFe_`>Dq{J_XEH{XTxT>gB6Am0G_pQrj7HX%
z49G(Y0X6^+Wt8xsc)Wlji47=2a9{)>2GXabhi<BPWdraKBAR`X+nSNkAua%zo3YV`
zh-Ass4R;0%uwH_6o>LUI0U{_vwG9BjisrVhyfWC^w!*M}2~veE%hCtRa7LCJkccz-
zd{9D^W?}iQF#H@XhR#DoGS*pA5*Wz{lV3oJ*mD`m02<1G`$1v!Jl>cMdT96um!KFT
z@K-%&4*xe`4`qgcDULcz?=g^CLJo*TOhg#%n6C`U4Kj||47M3rE*ZyY>MYU@EbC02
zun4Bkg6x1TLjJ`9QcM^E4AIp};xI;6GsnXT7=}}6k>f!wL5;04wKk}+Su=f89t)?|
z;1kIT=^OOgEQh`^kA-uCo~zR504PTW%>q&!@0G2wnyg{YsP3#`&ZzFJPrfmcB@2`T
zEGe^s1|_niWTY_CJFAUvoq2q0My8jn4F-BMg~_(AM5vrhEa8CHXX{FYqGZ^V2*s&D
zFlR0A4T8BGQX>%_p5?m%dY|cC1`wu90ka4gSCZIbj2O?d+Z*)jEV8|YGdJsJ1F9(#
z)|_%iLYg;s-7k3y3#3eCJh^h_oZ{;XWqdKfJ7waXF~D3ks5iJovf%W#D>sj)dxv{6
zOGpC&DzgO*VdzRIw2i5@Ql+;Y`k%5AZ9AB@7%k->l1a>~m5R(T^(?z)8&hjjoHM&t
z6^}P&*UFo_MS5-1CE^C%KdTNilsyXuZ%nXF@eOMrO8suUWXmeO8xv~j`P`zxX)u`<
z)onL?DyKTM8}n=Fn%tO8D^(TcHX@tW7!RLSItR4X@=`vox1G~<nn$d)Y96uD6wyqk
ztw_{yijP{Sc_5*9wDynbq10nzC_R&t2LUoh+9lAknBzR!HS(8D4?!9=c)>{fB1nlr
zLMAm@{gsK>qaEA4<}_mE>okjSWgy{u5RgPZ&4Y>Lng{d9i=Ki+@|YC@6_lH94Blt@
zx)a7sl;Lhb`C<<IG6<1fFHaG0zcQEJDd#ce+Z&+3GAG|36xsF1G@Zz=my>6QG9m;3
zV`_j<0{lS^(Qr%?BKSZ~h~NWwi<vzj$O7BzjA>v%AxqqYK?&waH)Vc-@Dm25I`)Qc
z?3r<}N?qOIYZFw1Q+#@IkL<4XtW1<MrX;MAwLA16phkGR9TTpE1t3~NPb|iy1;?c@
z;G+q+A}Br&-bd~>L0=g28P?8#ra_7mr2D=dmZ5Mqj7bl|;usX*fY35zB7_h<oZ_>S
z1l>(QAml&1f`AXfgZhLpVoaV83dx`Z;~HB&U8%df0p7x<brU|Nv+Yx}Y0(5v$wkNc
zvXlz#m6$BXWDMc93`+1)cPLEJ5dMo(TrdbEW{{kjx&UDshoEMh;uGdL!N(#Sa}O+<
zl!CY@S}6syZJKOwQC9cPi}O`x_fBk@by~HbNhzgF6%mAwQ(P+*&W|yBL|{OJLgb%Z
zH7Q&*;-eFJXpjPhNdga8z-J0PRCN%@(M;h7aSu%4GbJ8ShlQu)lwK#yC1c4q;4&>&
z(xyoVFcUo1yQ3lt|7o-XaY=6Gy%UNpMHvv71vX{C985r}L2*>96lNmO{AFpoGldxd
zq0fC{GAL}F#{{fp`?e5zE1DBBm$9~<z`F(|Hb}nMi9(&3Rr&-K=9KfC;KXJMIg4t4
zXU}a+6276p;yzPU0k2ySXfs9I2#9ZisSU~ux0Y?wgab;e<;Z~BYSYlM)r~D*wDh`(
zvWZu*%juh(NXc~HXSpJiP&E12cgxm{f#;+i$ay<wPvAUlv?w{QOZ&v+BPoIVY~NoA
z>=!NFu(C8HkO7wqg~I|Z{-of_HcuE3=Fb#dJ5V2mW$2{yd?n!FOyL$sv9xp5NL8SU
z3n+2A)@dYBG+#e(0&tuubfB}6CV(L4wrO^L0Es4<gh}7>;%|qp)YRTIIX{vDwwx(?
zYKWTSm=@rN^hi;Iq5{W0J(-l8uj{vo*a^}E>p3V6QMygf0ilUkflw;s;w1IyF@9JN
zDK$wb+Dd?wW@~vR%Bis+>d~g@1|_wGV}etSR+Y<#HC6%0nr)tq|MdEg%h2f8&pbXy
zXs`YAoR7V-?nfJ@-9P`+>t9~wwSN9L{{Me|FS*NMIK2J20r7iGXU<o<?>V(NVaVI`
z7m3|0ciNBpUZ({|uXQ>ez6K#1FA`asybk;#Y<>F9_(pGSk_-V!UGuO4O@HG<Y5=LH
zLf|h_*U2Q3{XS`neIQ_@BnNh6Z?i&wo<h_a6u^e|6b`5-bEdJ+;wZX9h80>Fez~!%
zhaw_3ya5bXTjcl1k~-nlsTsnt;VYhj5UjpuQfLB6eVJ-x8Nl1C@|jJg;#}?TC@o|D
zSy6Q}(*jlAOl;{sGm|hx(T0jEi#8P>^a~q@HlJMhERE_qLT6>sylzDW7}VJ`mSo9t
zq`dgelBNv3%<{9mldtmN67~`Sy?!+f@Zc(qw4pMzu0kx!Av1^yVw**&7u}&|WpKan
z99&B;omtjv=j~JyY6NxE^m|nfoH38A*Dk%Gvh=zl3t6|TNHo<b3oe5PzT8@5;uKb?
zmRB8R$U%w7alDm9cZcv94GIIrE&d+UEkGkquh6QR+A@q*oO{B%(LS9BtktgBx#5M0
zFk2!BOeR46Ce3x|$6RzK$;59EmbXZSs|o0K0z0)R@$Li`Y*B_BGS@1dhzq~FHF3%g
zd>)7|cHmvURHTpTD5K~g-tAPs9rCCsNB=;5#!Kz+j`PZda)hGIHNIKuTFJ*@iOr>&
zvs^NNf|$v<%5fI>O|*^ZrmDJ!-fu#nu<-ZB!-X2Gb5T~-pUzUFn2)W5%kh5`bOdSD
zH33_u@{a^x!rW}abAoV8=(?T75(#tV+?*;5W;wmYBJ;;iMeG7%c&-Px2zK}Tl_l16
zh_X;v!VShpBrCy$S6K*>--3p`)_L+LPbHL8#)v?(S)pgbyp881*s|A(!QXr$J?H=m
zz7%1J@3%q==ei-nfQ~PE*4kjvgDhs@T-|_#!8CcIzyv9DkOaA8=>d(ydIdIh>JIS$
zD5n`>A1g&gwhLN*Xg>+PPW=3$1VzLOGM|0^krHr)n7_^QpMdIFBH&2aWx|~&PA8=3
zS;eUprXqQnAl#NUQo<s;KxMBpFtm!ooLNVLu*O;Lo-t_`s9<;55Y#vRoJih8dKFj-
zlfFECOQ)1BVxCgobqKFifSn0f$qN(a=n6tIQPGJ0C<w;O-5FlYyzEOHLEV(j@OOOW
zH(no0NFaPb)ed*v^5dXQfM^s^#401$Rbgm@z`LLZKmbNExd|YU_nlMGU&hhR@KOiD
zkrHPJF+dZZ5s`lqPKWV${E9H3M+u@Z4;BxE)K`STl6(*oO%g!FZ?zK3<X9D&+^;AY
z$UsN*v%ZQ9ujdDkapVFy*qNP}C<mFh!E|{>6=zmBQ?@eyxiafMf7J9Ne*QCWhB>8-
zwa%Q_li3rpOjkx0E4-1(n!G(-nU}Paz)1E@n)u4BU3vCa#%O0g-^x5pCeAV2eM;VA
z>eQUVsO-AXUvUdO=R_W&7=pFys<kUMj;XxVS*s}2M>CO|5ixa>0{`uA#5Ku$PR(J&
zHwT*1HwrNmm>Q7z8w^gL@(VgM4j4<%C+|3qjAc<AyzH*Vu)qw>&gf`{MiQmzV34)K
ze-(Gi*GEnd%0<)419MqbqG2sfZ?kpAiD#fAL9OJ$Q`Fow`i(ac3_?={cE*1(r0f(B
zV@5eeG)aa7;Dc?n+7vjXc`4v0gLg83hIhJM_^VXzr(g^Ih@l4=C6SQ^84z&r4xZs#
zyvf##c$=&1;=H^?t6%O%ku|w0JZ-vl%X=!_fRPdwOWxSvf=T{sg80vO9(&v;qzB*K
z{`hxzNohLnD4pZZZMj<ue8F5QUD;*w;DkPM&W^e8=bh7!hF*Fw+HOZRA9ZN(dhJ&~
zmJomj$(6waU-s~9wSFA6y*~f2^JDXT{;{v++{%q(E8Sy*jqmg!?z4B&f3r&z(w&UU
z7<X)uBrgk{+k2hd-JuYsYZn~H0rCg=hHOeImxF3Uhj4{8-Iv8*C5d=(ry6~{032!p
z{b10n`!OBBgKjN(vD}w2v=*Kf)UoM#`+!<UJze@RkbB0Z#VPQ*t{Gnueya?PV(D9X
zZoz??0)Im~cFjD?4^vp1<6B`{S=l;b%4#MedCZ(E=J;TF&|j8O_YlSKaX}dQtTLis
zrk}ih-D{a=bU3{J!pAi5uL=^>RBK(48UUtVDz&r-r>+?(3tgRN?1*(AW^QH$xQ)F*
z*2l|MHAxnOtqS;ICDM$VM7_$Y%NHip4O^b1u<Wbyr~DBsbHl<B05=uxg9>j73~_eD
z$B+q(exL*&KEABsP1%)Y8tx7E=)q>MWy*brN4+S8qCy@OW*djUgjvEU8&fhD7wLJE
zt80Z{i?|Nq2P5nO{z&KnY%jy07KKbz20Fo6G}=w7Qvn4BZ$0%J>T$dsn0~Z{_eWO&
zYm=)9x}D{N;RZvsEENVI9Em#7a;sSh;G`o`=u!@DlRQ~?J?KtEbV8}6MB+cg?X;$<
z9F8iq-Axs$I`>S-lLwpwMMlgK6^e>%y#qzG;6Gic^4COV-%mfDSOc$_YGU#6y%09t
zj;!ul<>5mdM@@`xgwa%KAa$p^_kzpna@b$WbXK|jxN#;z(cI`a69gp`mU@9?_E%K?
zaUwm}L?njyBO!mo{bNEo>nHtLg7ZeX@I+??mUvZO6|m4<QqofGa2llrMh8}+A0joQ
z3WE<hAgt#UrgZqY6y@lbA`tyxCMrtQmW7E~CO%8HfWv)F?-MkHOG)qWG70uwwYTS5
zLGoE;xt{)-D<!jzbB@lk$XOr{rHQ9%x^cZd6|F@z-5eSPXXj#Ndw<QfN?E=2_{v(W
zp`HltlGWw*EJBVi_il26MY~h)P{q7`s)h(Bm|j6S%H*S4{WEotzhzTlLrRWP^WrvM
zs6rWhGJ>Yys%+?xeoo4{>JEPlgP_=~mj_GELlR<%$Q{ejh#EP>jMZSxKNM(#6VJlT
zhKH#sXs2_Rp+3WPv>}XhDyFq5tcxeX&Ahea07isV)?k9gv+iG6r-h-1d~0YcWT^;N
zBVnzD2&3iO0T|1vk_!u6WC@g}7;3!r42_ovLPn5(uot}akqnRpDVRo+WgwUUBZ$n7
zz}RZMlxAUSqM3x?if%o9RGByf0f=C-y3gMH$XTM04gZ;mQJd$1LH<T6nZQcJ=rUdI
z5FJ`O$2dh3UZQ}CCDw)cD<4Be=*J8PeaQaiqlwae;LEkbgy+YNPKI>;9|r#x+*fpN
z;Fdy=m-?6;L{*!BV9%d$tS58I<y}S;%!Dd>60cO2q{k_p6J|uh$w8u=L_Co;zOJtc
zeq*H-pEw^Y@qAhUnLuX0-p3IxBo!V(Pl6)U0tIlc6F#L}Rf0Itjo}s5(r{n52+%~x
zTGElr_BEq)(kn2nN=Q*st_0X5T~GK&40)(+V)l3gh*d#=mL0$oa!~<d_Vq1K$_%cM
z7`&-O^JoZ@p}mNA@U2u`&!&g}YFFC!grLyl3=5yYrOcEh&8*SPJSOaTS{_YKq_jNX
zXtK#)HD!Xn!k~#4Pu??R2xn*j6LT{gsM9f&`G?HdQm#yAN|f%?nW9-Uwnv$cGBi7m
zcg>X8Q=%}PSs~>n4-=#56+p%OwZecBWRPXDiz&M#IJn_j!Y?CUVdlDTNjVZs|EXyf
zBclP9**2A>V;<f9Gf*AX3mE3j%!&-JX32n+y5vGXR)*fedAcfRAwIZM*#Ci8)r@Sn
zj-b+vpK%{m2J-MeNoQzhRnd%Kj(uI`*g8Y7RR-AN!vDyiC8(?i*^dBZ#B9x8v^fF`
z*ZIfALvt`{XgH$&!qwD&x|)u1q1<*n<bR@%ie4*w?$|D_tTE#H!?|_Skv_2g(<>%T
z?{>u5RTd*&ooBZr#?Kl%l5z=L`-_ftam9^}=hZoP*O3mps*a=_&mB2poVa;J8tT7{
zxT+&5+jB>|coJj8t8ejkME@Dwi|@%P*`GVw#Zwt0UVWFhBZkqlPiu^hzc8m>JfU&O
zFTT<H*D8Ltsbkm9K6b2=qcz5x9j~{eg~7&7-d5niO{XFk?mJ^Z-JyH?8o{gU9oTw!
z3+m(+o&*Hk#LoiB4b=DKTi%~Km5al9UJqT+zpQChM|rlNJHqG;fA%}C7wF)=9k0O0
zjcy=p?Xg?AILjwNB=`BV=tI@D_vClC=Z@>e86U6A)jfavlE%-vI%dSoQ%8o8_I*0W
zSNH$zG1CPAI)bu2zX1pg;9UY<oQd-ElKRi8I+Aicc8v5?-BsYYU2ZS#4|ors5j&P-
z&O=8A<Kiv^C+>1Pa(}@6XRA7rvORXB7ZG<YaR9EjFSkd|e+I;#_jGO39y@M4nc)$L
z?U*SK2O#`@J3Ern?YZN2xhjegua`%+BgW74c97D4c{}>$Dk`?)dO3A_02(}*=txRm
zpF6h8Rab1s_44cX0L0IX9Yr~xJ3=+aP1;-O%z3wVyB!A{y6i~G@!ZjLQ|F^i_jY$9
zxg(h!HfP3ThkCjFdn<uH?*nf)Jnr;Pb>u~2f9_bO+r?o1eA{@t*>U5@PH{!qo;$76
zz2#dG{OjX~GcG#;p!U|~=ksUUi)->iG*~fTklwPs`~3ksRWRbIQ$KXoDmK`Y>Vdmi
zs5oH$`p^NNVqV_{3$7Qsx9n~R=VeDy&c}`bMB?>uu;O}Qe9QLuS!G92j^~cS5_~we
z^2)pDJGT3E5juElf9}vOH`>9B>mBzk`wOnQ(NUCVvDO)oUHJMdzPdb$0A95tN#s3U
zzPIO&<#Hqc7RprK(cdx$*Lv#6%YA$9hyxWD{%`j=O@!NSIKY87^;YD7F8uzwn>)`C
zO%Pm}f(vdpq5FL%y2LB~sB*Vs4pInST%s0kna|r)bOXWG$I*60KsX<!c!)ceE3M~^
z0E+XmL!hOP3*4BLLM(2V@4s-Pjg5z=<EvjKEBbn&+%FtIldKTsSym`bsZp%)7FBT}
zHy!huoE<mq>|@7zi86T$zcS-aZdqRtTf&Z{Y|kCnIf~`Y2+|B|xn<4X6~6M$Xqf)k
zO(8Hv{rZLSz?g{2kXlQMklJoWJQ#s9`m_wkxfv&Ndhqker+N4};7%i?XP(s4XO>JT
z_>_w&_SEUh?J|W9-7g#%QSXQ~`ejRzi-Q0p%xjKFx@SS=&%HB{iP?TP-Eh(o+~iZd
zQ0^IlpLKQQNiWYG*GuqJ%=8*gb;}q=?yw^$f_eMvj`f^^vtpuiu+}YO;z!Wi*nT`x
zyxuQ6rk6orx6Fv2H1B|x!@}K+u+5=lnAl8tU;=Xw(NUE1xnsLTs=alYm9cBL%s8fO
z$M+QUc0PAxj$seh*K=w=F{VeBWOQQtc<NLYV>h}SQ^eg(hsdgAhluNX?66+q_TEC+
z%t*dlCdALAOp3BUc0{5s!UErd-c+369V_rFx+_I^RDu*%2*+BrOT67JQ@W4DPSJjL
z;+2ijj6S&xZM<WHj}SjE@wPwxyiMVeIi>a}Sg`oQPH6AXo$4j<^6hu3mr%^Rj*Qrp
zvM<W^+_6k?oo{8bFwXOqA@L)8Qq|rbI!)1__$ZWqp*%1pekQ$1lxMwZJuVTcnCK-&
z^`0phksV2S7NqN@6&>LUnc`%R2WN<wv$CTo+jGYzLCUGF7s_o%%3G~*&9LLgjy4DE
z#!N2}ytl0JUkPo4gzdRonWKT<0+3Ur?=4&6S1Y?^#`sgW^%83QR$^HOAKx-XCk7oY
zPt1Ksk5g7CGbTC_9@w(s4MaB*p4Nx*m-A?Ljhnt_%X!YDk?=fP*Vham`L+Cr%D!g`
zzBkb^Df@HBc8T$R3*#)KzHb>5Kch96lt*hY5{>g47tmwBeB&5+Ueu}o{*7Y}CWF)8
z5wCU$SHI~<-MFe_<|sUML>_3W@r+-|aQJ(s^gxtgM^YXQhX|kF@W~w5T^VYBGg3$b
zc9@YzZbsOqfPGBtl>z+sjCc_Z<E^Ow^SM)pt{>C7)$?P~&7XTb>GxiReaa|^iCl9G
zZWm2p4t4}Zc-A)^%OzvsEvTx@VYunYREMUHpeS|xrsFziM8r%lDH6A=K~4<21))C1
z_KdKYIo$%&oG4F>IWLEmlv*D<25=a%Io^nf&Fqd_rgUinZ>EF@#QkQZO?e`359`XT
zk(&;uq}>~7CXe@+m2qX2S6Ynv%50Q-CiEg}<vpdbJYJyH-Q=`8IL#l~E_cj;J$tBQ
zrjI>#L=*~AXWkx4HB)Xob|E3LBa>hHbH`P#Ceu`}$vU^pp<|03NqM{)0_cHKe`2cF
zWT0E-kooLb<wJeyxE*2zJGLLmMmHlCF`petd2|p}-txQSyYhzr-t%2~m+!9cY~7zt
zB97G^)5_eaTPDO$T=uhN_ws+^`?l*4uNTT~N4{N+9Z7k<3aUssX9ia=;+oTS%kKDD
zS4U9nF^q#r6vz+*V`j<&`{QSllBC$PoZQwq0qxBMjLb;8WsN)2^<`utn>}{x=bYX4
z7PjB>HI$O#c-@s*a!-z%iuy0ONqfI^gdVTflyS$4yiCFCkE88#US6=|lBjpP0ku!}
zlp;KOE<Am26$gSP6X9V4cn+hR2v5GOiV{XlC=8xlQw(pnAb!T%o1{Dj`&1NSV!~qZ
z<(k5HyAAO(-U}w>@otb|OH7CaZzjsqR`}1lI)b8dm^U4{WhYIceq1OI+Yvw8)De_c
zpF5UIJ|~!S$?&}2jx!<)*paEBzr69x^Q_@;bl%Jfr1zWQ<DKlrywm>FtuZLgCdORT
zQ*XB-ezvM3DUTkS+KxHd6^xlF4_gsGE9ywfqZeB#uuaN$Z$GkYZ$~VMEn`Pgp4I)v
zGr~aF+>QOwpw;F#bp)k9hTc|QMk5#aEuhuR4!%7AJSON!N-xhH`<!bG=FF6b?Fgt<
zMrCE%@?%_9W*iq<ZQPFjY_{nD$VyaJbbIdDE~(OQZ9^tc-yVR7gOpmLtn2>VkpayO
z!Et&+`(t=q=5QBvBxQf@Sm#u4FlVMbY{yAfpd%^IUn(y^&1uDW{r71``gyV?vJlqa
z);8y;&l~^CTfw82Zv`mZFK<P;<iNj)&^Kkp-yXI2nLgj72&wsY#LTge@#dWS+tK_-
z9)S3s67?UFC4{)R<%Vw;%EO@!q~}u|LD_yeV(SbJ5CdM&0&d6iU*)R+!t)V}JYymc
z#GYTE2yPFV|4K4~gyXRrM`MV!Mth8~*29~+1z~@TuV&C@U?yO+iSRI5{Hn7X2>YY?
zfr8Y;V|Xj3IuROf$7B8tI}+OA@zPH~2fList^GiNxP5()S)`7Hj(B#HLmdx135=)q
z(`f#q6`k0AxCzaXIzm=+tj83#e0o(!QjW)th;=3qMvQoc#<(4EL#7)$l5+mGe>2d=
zTjAgdy>UBY{7jx>QjTW@9X1Ll1|fKX_P7_g=Xqfc!Ds7J$Kse8OdtJpTl)n#<gZ5y
zbP=Vm5^dyBZz(hx58i8)tz9U09ciQ<MIA|byw@tVT@X$_9c}%Ad2-W{&?rn&66JhM
zvn-5;Ihit47!4y#m79);eK~e@BpAzMl2ReC^odZAf&vJFY`N(MV3*@yHzK_}1)UV4
znxDQ6r>S*&yb$qqoZbPg^IonLf*sS_gP=J<%-nQi5;wg)LZ*52_5hiba5ZoD;9LQ0
zZaR_?vNT0`wlu9=;BekD#uFgtrXz85iaL_=c$llPBvYyo<wE)G^L0vz5akyw;+W8U
zpfpbCKKDwhN*TQc33NVpT7?tjir9o2bf<*{W(qo36f1lFTqX9<TLvPri0(C6|IwD3
z>>7pL9@Ux&)d*%mn_!Oat%4S(KuQ$xMxVNwrj$0_OnI>B$bi&;uK=j`R%A;=ruT%f
z^!%;~%1Q5<D8G1h8W5ktMke~xt##~>88nXu1jiH8XZ)yl;*bkb>elLypP5u;QqJd&
zWHPt8*O~C(Nr_+4!AwGVK2&7zAxB}oP@Y_OEs8%<^I=uj^4yVSf%)a6cPi1g9=%g6
zubJK{uTA^(X0wbhY}DQ^SYG$uw==4bb~<~`Qy4IJOc5%W`!Xktusc7dFPk0eR0{c)
z?R!@Y<2y0Ko@0~<j;|0U5}qTJ1kA5Ug}z-V5B}izSye|;o<k#gnNiZh;eCNkyY+X+
zuZ-PDcuMA?3zraVG29iD?RLEQneHe_sn2(m<h%Uj$JBnfKLA1zIz{_2A7U_k#*TYW
zxNy&r6$G8j=nBEmJzweL*2$El#9OCCt9!h4A`E!mI@xnt)R@?eefOSV?H-LGf#wyN
zUxLwl4i=kOflt&{FO-K7$$YxVNqPRZ@kCacn4A3o^ZV<L!u%`hNXoNOJF$Wt`-O5l
zVltl{NqPR5AfJ`cgKvS!BpBgMM`9LAn-t|)pWMm}ZRj2M3+1*WF%fe+K>6(ozD~%A
zZ+CsoNQyU|0&Y=PN71(Ds4W1PnLe=Fc?D^_>4s7$`n(d`@%ihzdBK74`@I1A@#cpP
z0~bqoJiLdA%)pWF7vq}jw{VP8r!50OqT?f~MgZ;rn9|3yseRWepx0_fOa;2-bG%gS
zx=DIOIc9s79e~M{<UspbZUAG3SeoxBjMQgz&708(!dcXjl;`V1){D1{liGivciwa)
z$Y;h$k@6fT#Y*U=7i2%K=%9BU2_h<GO_b*sl9jt{4sX1IkKS}7Mk$jmlJXoX1V=ET
zOyBMvyMmkEbR-6<!o5jpk61yB;2SBPZ<aO%aOzD5Vyn7#!d82XWS!wx-&qaFo<9`A
zZPllVl=f_O?56-Xaj1`eq1=vG@iX~bNomh2Mif6Xx~V*rTVS#`T@3Fvx_Glay2B2_
zs=}pz>{I);6LeKTe<ZT))8)Zo7r5KEiV`OP?oCJF<eK7Vg`E2wKa1#Q6TS<JG}|-6
zi*R^_@sh~A&sTS-H%zqNw~AUPe(z03V0GFdu|VM8_S|v5paH)l-Qj`{{MQ``BaExH
z_XI5bnE1(pbOgYCyPNEaKYTMHKf<Rv61ezTEj-s5&Dc9`7s_o%!XV2+7Uh>j3%;TT
zi|IVB=*c(Th_Sq~8wuNEH|`kj;!t((`E?R}GhSS^pYGzK44__|$Wi*Yyh;Lx*2^o(
zb9mml3vJmGuqN!~zw8j8)5;_D)^l|ANpxjivkw>6Ot~E?VVBvFl;@jv)LsJY_1k?|
z7aZ)H@rahqTwD<z^KsWAL6E77SCs9Wj!mM69Z7k{!9zjEdBpQVx$Q`>?;MeoUq)=I
z%EwI7^+LJr2-Ir{+@$Q!9VcA!lWDeB5b~RjXRZ;sk7us&sUs`&<%sqJ<ovHY3JYB$
zit@{d#|1JyGJ>xl>Ng`6om6%#I;xKyDX9S!QMRdl+lew6D5h#Zfl`!m!Fqqo<Cf^}
zHysHQFC-jMo{?}$Xj6hWF6Y#~?Gym?MV+Gk45d8nQs&@aaqDk7?%KD^!{@#|cFgao
zAP*+OZMRe3*S(V`_`E(NCCmu>ft7H@-2dy2g63ClyeQAP@#WN4t`Z620_lG<Uc&Gb
zY(XErr*5-$WOe^dGxB-@(u$(Gz@tV)?<7kOIAX_-A_O-byNXe=BdZrY`W;yE0I-<0
zzOuf-O@}>n%ZUm7xkFc#g!fbv;Q>2?6$VZ)0M%FTJ8YNA3xODOt;KNDk**M7KB|br
zvx=cf>4mg*q1<)k@-3l(ij<mP5Pqi05wF1bnJKp;R#{o>m}M^>JC^x4**=x2xarVT
zg5n)@Eq*z)R%K}ucjx#~{^F)%m+j4tUAFgQN0T{5;Hhlic7pL|0PC?d1|K@H^eg?y
ztR<U;JZ?I&-Ut22qCBT|7?3kj7UV5MQFTIYy0MxFm0l7;I6h2s@AG~)n+bQ_;)~*b
z%|@>5{r97Frh6w|R77rOg_E1{Xq#4btm#mC>bPF&r375vwSvk`M;2O13_wzT!2ryn
zzJ&7Ie^h9>>BvGZi2+E;uNZ)IcCzDfq1<+)PgG#jEsHNbcC<@5nbGmQP;NUy#8-WJ
zRGH@a>%%w=lj*`Z4SNQ`WmHBL;I1m)JR3`G`^s`SZ{TzOatVYQIyHsG3HSeFr+qH8
z<73%{a@Ua+dUU0eHG7@`(Rn^l$LB3j)vWAuGa?HB2}qk1RkpunOmx&Iy7vp^c0?8!
zQuz^5>{%)3Fv6+;(ff9x+;(IEBfY?+*fRusFLRwE@3>zmw;fp^$<&dQ^SPs4$|$|3
zdf(3|<Ep<TlyOm>p$)r#Ud*$^EmC7g<M!u!{DR!@#y!Yj@0TJ_@2E{aQEofJ+f|qt
zll7#Y%OCVj5ezWixB8>()J?}zF%9UbdR5Qv0;J#&Z!boiDGwtubcG_2^{}47wRj4P
zgzjcPs%HIlM-|uF)De{WEarhGZ30H!+Dy0|kKsC<-HJjS9=i2&D)9AoMD@Ag*UeZ6
z)S*SaDRAeh(>j+9dpk`0rIy%DH&h&}>ITANnwT+$fxw=OV0a2qGe#>Q7%tn7!0&Y`
zc=mQ&|G5C#O(#@Iqw&r5qwS3vHY}y~R?&zou6EOrVUwpivMSpz1r=;6)%I3d43=)Y
z9nF8V5<H*v-kyL6$?8>K)qTBCZacDioW82s>gTWO)-E;X-cx<JUy4PrI9-;f0Hr(|
zzIeCRh=;aF)M81yn=UAO2TVscAHuE&yXVq)Z?8#mEtYrFku~+II7!MQXuue8F1;5c
zUW@VFju<}^)}<)VSeF~ZlvT{gruJPYk3kt19PET(=*LdlY+h`jZl8(>-j2l_0d(Wp
zdb~#2jxQA?d`G#ztWS6|5{m}!JXFDnCrNx<>Kwka`q24H<vkWi%*uOkRj<#L_cr7>
zo+|gT_Y38AL?kty0v-g#feWAHf8=mZGwn0sVLbnps<e>s3uD$x4aj#CmYXQI9a%h5
zcB?4QiZ-$}Sz|IryjGpO9kE3&(o~iyI`-enGDRwu{C)d&p*)NjSzRe;nbq~|@8e5!
z<SV=VD4KaYV*G5I1O&5q9y>B!@R01>e-!1s>B!ohDRi55_OWA`OMJ$Fmztlq<HfHm
zMTLPgzX*%2`k@$ZraX)nKg%MIq&%h?8PT&2fy}B{=QGNz>Y55>R+ML)*}bUzX^fV|
zP;W<ys*~Ke=<s`$!K{_aDuch(N@e2nJ_}y#V|HA>&b1$(8Goe8w(dv!{G+#0_U-l0
z|MdEc$FksR&WA-=iEQwpcng(~(PBwk-;rf1yqYyuiSp@`wNCX%lfnu;C`PzU^;ENT
zDlh3i6i?7ap=7l9>nu6CMs4pTb+m$m#QK{loGHLmch&L^%HpxB9G8!!`8QLpL#Yt-
zM44vCJnnojDfwWQL+wA>&bP%$jugOQyn#G^6<pkjZ!uGHh1kNP&46^?*J*08VQW75
zS~isw1n`1@KFI}Aa@U9;z&!?K^AiV71@<1t@m37M8mTHnofNbJ2jGZZypnc4;{av?
zd6X2Miw<OqIKj)6M6PurL~tp>emFF_C}X+j*nOF5vkroPP`7;=+NHB#E@le3*imbG
z+o!Pu<6)Zy_YC@N%fU(5v;s%e*uMI5ZF2)rKW@v{PPI-it*&>h;r-dDB1lYbSqD2Q
zS<o6F9bB{sbM<PU3(H&kk=>fso0MHYaj=&*aXW+#5K?Rc;mB5H?>JaZvQNcqAt@Ir
z!<${#@06d*w`uu4lxg5WSYAY4oEK|4Z8`eS`KXk8GQUcEbM!jR2S_JBrc<Zs#NfkS
zaj6`>)oD7x+<Ix1i4TE$Q*t-FWc!uUjtPusrsx-Vtm&~U9?Jsody6I>ffV~~6;qNz
zo|r25@<lK*ZWUJuZnI8oiLuu_wZiAS4y3u|NNYZJoDXCzO#}6Fo*yV14}aiHcFI8l
zOr;!zp4?BKU%<fjb7IZrJ0N7I>~-jLu-h>)f^}+htnRN-&kwvK8uyfqFcdml0Y<h@
zi*|9<cR%@{tYxa)J18|ErD8#>*_%H|ihi;BymswL*knCLC(FF<Vhf5j^i3xw9Eg#n
zhV=#7)h0Hf_)p)&CLp!-O>BZe8km&}AJgYz!F+I^1|q^(4iyiE_*|wZ_j#<f2oNzS
zHJ;2ZK>^23UVYZTc*5nOXZZQ<5}<*t#&?9(gD;ddI$#f@v|LY#S_FHBQ;CWNy=hwR
zl;|ly{a$x*(#}4?0Mo`7te^T9z+!spU&NHN{C*UnoQ)O?#$GuJkoJ4kC_u{URL0hj
z(!FXFR=ln{UcgJ~RmY13iHo+}ol8-?clq&??Y#aZr$RKpriTOzAR3n-twkx;@uS)W
zuor|t3|ptkux4{`#%<|12Ww6z@BreZv%;>x46_8XWZ?$UHAu1Z8;Yq3SI}!|k2d}-
zs69O)APrAS2%-=-qJ$30SYLxw+)!z>ozpak^r%^c2GGuF8rL$+_>og~^qLSD-6wVi
zCL<;WCs{i*ZbVBA3dTJEt9fWx0w^AA`Rmwr&B7ggjjE%HGVjwouGO3eh4_?|INJeC
zR#{$g=};94nbn1*I&O)zc|iRoAaj!l+zxN?P{6EJ1fo-VJOm<X3t^wdptH*JOz9Yh
zj3Nr7WM+V?EiabD2FV%T$*zDUZe830qF(D?{6VY{y0nuLXqBF7qJsn_7R0~Dg1h)g
z(@_wpxVNf`-d5dl#X391=h4K<V5)#CgQSYwSTLbNn>Yt(<R*o63!J^kX;?rBCP>_R
zJ!;c@VJuC5hi$|N*tnTkUWqJgTVl=f7cAz@a|yU>hM8t*@)XY-447tYtpV(N=ozem
zO<pF2oa^|gDW}Yc2d*?A-jO<d3^)fxTG4P$aZRGJ87q`}yFnptRAz~>ty<B85^F4>
zEd?nyt%x&GG+V~`^oyLFK$X`J^kJh^<%=0{!P+{_FHZNW`FVqLbG>wVvFtQ&s;i<S
zad+wjObxnXlQEAv+-opB2tZY4s|NrzXJr6qKeb~PrKmAx#kB0ysIlFH!cn2YSxRtd
zaCV3xQRMfK{tV;Bk(N3i9AMHi`r~%iLF_u8OU&*uwu?c46<f>~Dv@FoEsPr{VE)j6
zY!~kfM7`~rOB4i$8VkhB(KbD##t+B?!jSLDdz3`5-CIEA5}dk+6!gFm$B6(0zPtfp
z4lPdN#GuYtN_Ex`myciqDCg|f`218$A&y%Q+t^wII-Go4qZRAz&?h{Ebe#AO<w4PF
zEbmTfts>)$He`g(hY~Hqe>t-{KH(<8-0{U$hP%NgswVdV;AU$ie)B<5w;arXkyMQe
zub|DP@OFG|jW-%7Wu8CSH934)5LrTS_n^e&B&fqITAUOc>}F9lc`b=~ZgNBbt+yKU
z4Ge}73dS!at${3$CGAl$T~EE%P-o=Lhk{m!Qj;i$8I?5}oZ@51OVPb#lSvsTe)@+J
zN|!1D$ZesT^~B?1uvJyiT$WKU`X&Ynj7l*W(1NQ19#Li7ir5B+oJkuGvukk@XM?Yk
z!sncV2WvLb!V>WrviMl2{<?&EXB`I$^^Q-BNw5Q2c~D%3`1Yu}10)_No2rg52+~V!
zVCt;ResUa~hFay7?I^V*NzPjLm8v$twW~rMjo9+_l+^01%gi5iFL%L-u&~UbgTi0z
zJ%6x7Ws=4|HGaaA11Vl3XnnL<JBC{Yp&lWU3rI2fLz9Ofukvwpm)dpLI|-|lby=1y
z0MEMdgHWT>rpLzYq}F%Vw!!BhY_%mylw-oMOch~iu+;{ovR5!xdVgOrU0z7QT8nBm
z7KWNvQsE#|A$kTL*QyT+3^UeV35uU9fz3o*ZWS_5mTA`)rm?ilCYjnG%T>V00MuU<
z-^s|@DkL2X{PBu!$P)3#XZ$31kAUPX#bf{s928C`YZOJFoy^yl2N{*M%GHAW!$GO+
z)$tTCA6DDqB=7=ujY3G7c}I}VZ>GdnAru+W6l>FMN!z_ij>9ae^3t$wyzC2L)j0)i
z-$!|ET2{&82C%XZKWhz!M3wmg^K3wbq8VJ$C#!YVR?-RTs{h3k1iPTZRT(71gSa3_
z)~fFqVcn~~V=%$IdKSL<gj=q1vcm`)6s)SL<`(zO_47)f`@*!!Q6Vb+T%#!4sc~Z_
z`q+7Cdwu8{3zS!SH5y6^$urehzl)wJx2wGJ7&r~Ry6WTTcGcn(a>O(bJj4IZ4X&C6
zH@I>Z@c6f?S#X0Zra{*57cz?Qi=xF=em3}RZIuQ3Ha(=^AzVwe;^)w>Yf0e{3U<|Z
z7Rk9z!LS9>sC<awAzVpW=D))eSals5Mw1gTC&aU;tbD)?eA){d@xJK#6p;4<vGe?x
zhM!=T>njT}TG&WSkYW~qmahbvF;vH4!Fgt5jW$j_@!{*LQ*RWea?QbR8kArF%%(vA
zgNRjLW7bQMHarJRfhiTWD-C8;Eeazb7<iFhVdG0(WDOdtO6uYRsauuN!Gz}VdU}{z
zNX;dS)H7|zDJ!2`@EktIrFuEVDd?yXnZ1B?V7}xO3p>jiwM`QQ?=}=QJY^!nR;nnw
z9u#r{$H!P;n3IX=$$kyPXo=E=U|y)HMP5o{p<O9Q78PZw9Kl$s5jwws<a@7*tOIMv
zE7oHWR`8S!9CfvvfI%AU491uf2g?h~Vv`^wi*zMJh?9!X8myazc-7y^-}zA3a;{0i
zvaDd6Jz_s_NFh2eU1Dys(9KlhmyBdN<XzrQ;905Ey}@|NnyVJY)M}AkZ!G#vP0lkm
z<0p{HRy7+wm2=^CKv^x)^#aUmnQ9UnA+d`b1Xi?gZb8A&+yF?yk{$!tAz7Z@jCJ8%
zBP6o7TCp8c361`OBAwAxvlKIhWK=zKPqp$Pq$Ac7!)!XHNGr~w<b)y2!r@j~r&y{a
zlHJgY4>C+TAEXN1c+jE2I@)_IqT!amvRt>W_9~^_OyNk_C72FQSqmSuV$SjE)U3Xa
z*P`xXGd86nzN&0!^<`?rrph&5Dfy%qS7?kyzVb@h*L4F`Df{GtAq;<^_FO6HbTL^s
zjoxE<n+C^muA2rYpSlK53dc6wK-I3nalmVcwz(a9O_e)zZ?B4t+0hp~k($QFTY)az
zF-pH21{z}NvJ6=xAxEb8o5wM%C@BRC;s>?1%S0&pWFFMe3zc<2VALO!cmZWF)Tk^x
zw_}fFK~ze+3uVP`cphNP7x~Aa!d@w{NxUwutctE?Xn#e<Ng(ZB3FXH#E`O$=YbhE+
z|0^<YDn;K+X_!1;ad=cgS%SooDL!C#Pn1=|ceF7!n|-+qvx>Dz`SDC>Lq90)JK}Sp
z+05-26)zQZjVp!2P@5_7gE*q)(4Zn<B{-nv5EqjY_wYrINqo*PlxW3j<7;^(@Tqh<
zlpTw~87>rIZZ+adk}ZFpOvn;--19!GPy{Jhvrv~x3MG#0&O(V}GNK^_Kmw)4U~w{W
zzAl9LI}U3sdvQ|yz%(%T3HKux3Pyo6Ebx()G+ay7$m~_WuAPczpOnJKz!z0`;$=t|
z`0_6l17~o8*OPldrDi=f9k6OWHP}R1>&)}@$lpN9ul)FF_;vd^p>-pFIG-;5BqgGe
zrd|}}Go|BL#O|$4GXx=bi-%%0b>g~m1Gz5yS1YyTGlbS!b3Soc*4$<cU&VP5%FO1)
zGiQ$LAzh0e!_g@Y^_=qa!6oio=f|x7>cK0wozKm)k`#}PonEzd%{eFKy3RG<Paldf
ze-q=qh)J8-9Mwav?dyv_D3=$1@k|_UX$TP3VYyN$Y(r>y{?3oKzGETw2!nW~Py&bi
z97#Epxf6wg-o-Er(Od{Iwt+X2juVAL<ATP2gs+={JG%t6DEvBj3y};LO2h{0qe5`W
zD}^7{jy4C5Z`q(sU)7l1HhmC1r|L)B_=N{2`&CD9@W}O|M~q}3swaB~f!c`(<SdU_
z({c_nu4!-{tH!~3s#@wspqP}z61oIy@T59Ne9bH6swEBzwZz)vyqdH`9EX|;DJEE{
z6((W3XxPYG3dNTjS2dlaP=Dq~oD8?JYBJjjepNQTRWvznT@fF+QAM*$ie`tcDjJ$w
zRWvmBWwwYMp%oTe;nY^yhh+FFqm2w-Wwa%QM%#zsOHgPY@`YPpY1ECJDH?2G_i@r(
zOadGvv>*p5egfVelwLE1#v<5zoU#>R&5r!3$x;S|)?zU8pg5z!Jt(tDz6^qFax5w$
z!eqvKq84}uF?qPV!T&|C-M*j+HwZT8*wYn(mF)6*U~i6Heh+xfyp9{35pnj9T`m~x
z#IdE@0~4p&3UA308DDUqkolWDALJU8ik(cOmAZ>*9oIhc5)Bf^BA2L&?BWtGGz$Mt
z{~NSlC#~V>BXdxVO0KezO_r`S2XDsgIV_R|reSH4^6zxVaZB328g+8V@o+UcAvv_%
zaoiGm<PL3#$p<-jynF*~J6(#SU4y`*Zt_9$s9UtK{t8!kIkaKamJaS1rQV_KsaiGp
zRH>gFVpOGH7%h5*$*3Z)Fd0P)^vpdh@)PHe=qD!Y!uxiTakvJSBiRARYy5;~nZCDE
zoSQw?UI-IjZZZ<_$ntwL0Wy8#fu5co_R;1{$heggfl);y{&4JnTJH1*hjv~A^BQ1K
za7}^pyHo!0f`O$t{SIQ~V{}o``54_(oOllZ?z7tSP68a+502c?)b$7^8&|@-K=FJ;
zU9y~f1}<uLK7^Me;Ml(Fb_5*Tcg=(>+j#@bF1Q)t!P|M)%fH8!W)WL=B**9yidm3(
zZB?0d$eXLm>_C+Ts>t?R@_x*V(&9Pf+s4U=QJW@2R>kLR$=kg_!rk4WC&!%@{_K~7
zTo3|Ds}dJ0vg352$WjrN^_K>rPnVLFiEp~Nte&8@=vtGdbMxY}?uhrS%&BBeS>2~r
zrbN{$gM;}^y0)#%U((fXW!iK#EwbrqntBLRxpjkFnKi^q=E^i7-9uOA`^06nOHrob
zs8ke-@#Y;jvrYXT9BqybTir=`47p+60w;J6EMpA$GF4_(<iae|MSdiwj+=k7p(<>F
zGJ$bBm){_OfFGQlaXB)On1E7c?d*)qks-sJld2fJ$|Ms-I8^4YSJ@dme1Zy;sLUa$
zZZa%EDR|DI!59s~b>L1!ksXy;BDG7GVG@X9Mp!Vrswx(fWHa=HNwOZE0>fhDT~w*X
z8)dK5V&+}c4XutS8SF!3RYZ&qrb~E@iYth^{fxF@5pAc$^pWwfWF!yLX=~-hN@YGn
zr7F4|nhvMSpM>hDA4pSVMnmN_787ti(g|FE?HzX?c#t>2N9G+Uq6+D^8FW>dWS|;V
zphS=rXS-`MIQUF55Oy0=ay=-FW4)$0vdWwR1)Cuqw^rW3){O#M8W3aq5$3i81tW6_
z&{-8MH!^ZZi*uy_mU6?u{d(#wPyka;VVr)IR>DC2Dm?^o`iqDDflv_DM}AWVOYLCH
zeU;j=Q3$8rv1RNc$HKLV;S;|>mYP24$i;QaU`!;@Ms#Dr4<cr=Xonz36^2<As9to)
z5KyCVPA1}d6e!v&p3A9JhHq+*7`tBdp;7R<zM{y(Rs3mX7`nct3PZ2V0H_K)*OyUo
z=J+xqsWu~MD}v0cW{13lYWy%V%v>Khg_-MXrYLiM%@{>)a`+&tHUp2DRIAA38i0lw
zyv)LN3UFSOGMiD*6)=1mDeWn<y=Js^4T!po$5sk$Rk5zBSaN+X5KAr>6tZfo(VNsy
z1##1NG?Dllk3Q#I8DK7Vj{?kjxfnGomno>-({S6txOXMtjy5*2LqeJyDjf-45k0?v
zRPY$^x5GW@;rE_~>s{msQGmJJ9uZ(3G5nm}u4I6YHu48BH^!Iq3!w1wE!oESa(Nbz
zt9zv|+d&UjwgWz~eP_0VCd{bwUGv?PozdA|qfcz~QWc3#SAYW1^%+1Qx;_F5MAt{4
zZ!jxNrgPtvN}|~@m89u8u>u*!eS1wQE1naKfiO3CAXM9nNy61mwtNg3rkz(K%AOgd
zI6xBdNExms`K{3PQ-_Q`Smp9mk6k~-6(&{5QtWVCG#Q4GSB#9J1(e9ElF`@U%0OO{
zrxr)z5~jxdC>m_NF&A(ZSMVKaoJWlmtDHt8OVNz#_^L#pASQ-->fe!?9FG$>kQ&86
z$I5{ER>Tjc$Tx}c&g3YXJIGef)U=AAdS$O6ec35=!UBudNu17<6;~OD-(<KT>A9*(
zR3tq|4j+$2RSuu&IoB+{`8V7R8VAiZnW|L3oDg&Uaze~q%n3#Qgwh$AQ(aYBpfZrZ
zwP{ANb1BMe<W}+>g8QaPO2eQ~ie~<#>#c!_(Nd%D5p~c~cEjb<q|kTR98C&+<Oj5r
z)MZLr)nnoabRAxJ!&RA!>D;wRhmU;j<@%#3iI(ZznR@H#-M&isq?tnyDZC3vzDnuz
zz;<RHFerX1<SUM}0%a4c*mY(cv%Yw3`!pR=ayraYrtyl51XcI()bTT(Od$llp{00U
zmAlRDT$dMXmw%e=RQ5LBI;J)>$>w${eH$meo%kF!Y2eIdxctb_ElyiQe!9Gr4bf-N
zcw45Y7d;}TPnFy`DOuf^dJf&Y9ZWfv@NP^!KRF4eo=bEyc|xi9T*IPt{Tk^MO6VtZ
zV!NXqhy?32a3B(_2yI99JI~&?cA>_ZW%fmvXvU`1UNnn^@6C_DcReGp3M8EIM4VR~
z47~RXNJM_X%fpNg!8jo69%2auB0YHcF-Yx@#QWCSrJxK-e<kV!&wK3@*9)`vDYxTC
zM7PKZ65k>x7@VYkXyN<D3i0^S8V}+gL2c@mGkhiZMvW?VjtYWiuu7gCr2q39`z>iv
zyA<rU3FCv31vmlx;DZuMf*uo`kzj6{Ku&1(Fb$<ktBwjpuES^rKslMF6MX5CEXY-H
zjSAhMZ1s&TA6g=p=`5XYlLl*Aa4!_}2?<kC<)L;7RKO7=unayI@t{Kw8cWiR8k1rK
zVw1nH_2)0>6hoCESJL$uLhfvO3?X-t4S?J^dCH*+cF9u!BK-ffy-lwzJB}qbk6&?y
zRf9^0M14?G1MUXwfzjRRk>N=<x(paM2VF+P_P_TQxz<wb^WHo6=6O|_K;{+C4vA7I
zM2cJ_H$_X4+w7dE{eyQI{XNqK4fT=x&>y^z;*U=9Z%{6~;szt5LQGHRWK&)xzK^CX
zO8f;<D3Pzmd`PlWps?S`&P3IMmrqdg#)`SX-xilzGM5S4&gpq5<R!DU-4A9mIU5w)
z$o^1spu<WgW0TvUoqSo`8J}}%Asxgc?-tdrFe0$$50;oeE$)0~wW>^o7rI@{MtUm4
znue?mjp?(_S$HVgT*gFbMNcv98D8rl@U=qM9<X|+HhSznNy^+~(m@}TC62ocO4-i0
z*qFQv*(zw3N<zMX_Lw&*XWsb&8f|wB#Tqgzi^2)y>*#06KTak*wGs_Tz5Zm=ds4X6
zX~iGXGY^606<i-!B>u-6rKp=+YMF)^^EF@s;JxJJ6l69Ir5$_{xZT2mFy>?APFw2r
zWLH;t@irfmPTuBY(xf<i(PG!%m_J7uS<_K=2xsKT%;%4RyG+^H&W+=b#m<l0&kE$X
z?My&$Nb9i(vD?;T^+7Q8o0|=`*z1inG^N~s>kN*>oowwjn7WlW#+OW)U0eP@6HX@w
zb^tC=v%I&|T|wm1ln#dr);vlZte5jBZHIEkNteT{dRy#B_hmf>qvxZ|cY(WHW|_a<
zNJp8<+nutvJ_zsKzO^qo?%q4)0YgeV>kyr`&!e<A)?%RkTuxBz(@3%!iZayeCGYHG
zobg!yO!unG;Da)>*m)zE`i@~yp7Zh6;%k}n@z!EnPdQdZS+e>dw+&$d4~lD>-SL&V
zwhY?!`S;khPPMtvSnXWkL!nu=3=TvEvM`b4CdE7p{6+y}iUoX9@^u%+<T&r0q+E%&
z0wIR-XE#CNZLd@&H|N**q(GA^6(Vr)rgbO<t^ImedGrB718+dqZc?siq2+DiD}55!
zMknC@5U^Vdl=naiCSwl@UIDFutEyYJN8$p?g0W)71FHyncv{IKa>o<9_)Y=TdXwUS
zTihy73f>j*g^PN}lafHdf?Vu@(#)NVxEnw)-wD{2z=XaYI;~4c&mY2rzV}KBwmJ}^
zM3sti348j35Yf8YTZ1PhT$a(rZz#B&*Blg|X|$vaF-~pC)AFETD(UjPf`rc)UeEyF
zVpv@9m+pNJ3Z{~Aa=W8gRTOe0g7=+*)7EeySh_5V(sf1Hk*!M?MdQoTP4PkLXeal=
zvzlI@6e;8DlEKdSx}-?KKL30Qg8%s#u$+&_vPFKgMP6YRTFR0^D}Nxj@A`?78`NNJ
zTGG524Zh}SUBZjwNGBTnt$hyoI11mMAcfZ-2$MA*5-Jau`4B;InmlC*2#9u&SX=Wc
zQseMA3Y=w2dVj8xKQ;DzgZ{Wb<f0snj%76baaAGZsO<Y-U`RnyLa?p%xV(hkx7NA5
z#I0|w$Ka&ss+jNWTvC&}=PfmPS?Br|U;Fcl8lsi46(T7h1C(ABwE@a<MRp`5cGo7I
z+hfnR?w5Pj7%{Rb`9&aN1cZf3J=AuyWYt|BCXM9p=#3rxm4{Iy`76idh9b>(c^Eai
z!eG$uMWHfD*>l;Hd~??!9o3Rmuj<3BmD7@kodr#A+WRh8pBT)OzsY&khg~b@RiAdP
zn3p|9$GRVtG^%3W_AqPZyr_Z>OyQXJP<8P(xr!RAYtiqXsbEg2rOK+Hw+{No0!>g`
zw_Pz>T!p-~ML-qWxpF$LVTX($EE!MZoC%V;iGoV}cXTNa3=FB8Qu&jdoRW3IL>uv7
z8aL;{z=C#)Z=F$da;Yi%m9@ZRe9oE4X~GJo_jnkf^KFhdEBJ2H<pe`{l%-NP9UUJ#
zc+T%!fl(>+p2Ek$Zof%~pP2G|u;antIaeKX&Vw~R8WeuJ>EnhIg7J5tto5j72LD4u
z?ZH(JC&VU^9n{#q&)Is4fOYkg-S8y=9K1=cZgT49XhrF`dp+3UZw|{Fw)g&<Tnyox
zSS<Hm50-OzbRzdVYor|)SZ)HHzi^Ul%JG2}uy=f5DA5-wEs_#jryTEhy1d>gs_Tbl
z&qu@?7OT)3j+)rzesDLllgVE=#yz~nl#3=9pFlbO@Di;`|7gs%$mat0V-`C60pCo9
zladG4Po#kn4x3FlUd<@X$bZL}Ra+g2t~W_+<V5R(joA_Tn$38%r9QX_akEKaqegt~
zaWTi6Ey6OvpBz!S$HTl9<8&{O@<mENNBVD5a4DTaR-QiZtn0{7M0nFJ0-GyK>z??*
zj<T2nGO0~3CZZy&JU!(3W)IrQqIJLnIb*5gi7&9C<YD1Iy7M;&xsWgKV3|+_{)Dcv
zZt_Ws@cdENWBd`<$*>5=|IMP2UAjU?&CY>FzUJfmHtb(IVtP~I)F1RzT?iEiA(r~U
zl(Mw0LZ%+S5CK0BY6<GpiH8CX#ZHt{AXQ8WSm6E20C#A#EdG3Alk!q+$`C_`7>mz>
zf|2Ml?D@!nyX1--uQ-amp9mrN(Cownb=)cK#QOjUWGB1_ZZ$j6JaDVo3Fjfk$W8<g
zJZ)AU$fbPE{$MfZ$&qIkg~b)({P}@W%4LwzsE<sQa1*ALb3T}*k>`t@=$G`~F$Y5u
zVuB~Y1^zrc@hpIZU3P+1;H!I5X6A#)f9GPKz!L!2EaOfHgxjo~I1}LDm~`R?y?IJZ
z@k7o$Ca(YxF4kH>A#m^62?|klY@Xl_Zq6?}&-4=`(pk=3ns#KmwW>4TH7?nOzEUee
zh&ig1Y`FI9M1Zh<ah2NLQ=Fsl@%4#x5S%#ydEV0vXea2SLt8=Gk}FBMc!nP&|I)(8
zjr1u$<o`2;Qt+>QeFO46k{z-}4AZ>)kk`(XhLHtnOt~E4$Gaj6%@2WXO&KDA$F-_+
zcR+L^J7swJ@CemUm2zfEAUgI;sWR!@GlUIfQQ}9`01~$_pU)3@`c8p$div}UBvA4G
z2NBZDE0m0}hPt$1K&nmYLgDr^WfUbcn-5(-1mDi`<`os5AK?Lz7)q8}N6V~9`R^3)
zb)Gkgi}52CpkV~IVgwzE@Z;G7(hm#1A;l~K@Jt+)lpOc~_;K1Qw=JA}Oh|Qsw8ws8
z_;c0YF#OT+1H+%}@#wth_G5yqAM*N{F#IgfelYxbR8}3Q8I*7Zi3|^Lrw9ab$Gw*q
zPSaruCty(c0%qn3L!UT2O<FKwEKETF`L68|1OV8BDGxFog~n9L;U{c4@QLpLZzsGX
zR?doIJ;#0``Eu}e;s~;M_alq|H@`>FfI~JaQ*=ck5K}g3Iu1?wrWtNyCnO*r(5Hm+
z?-4|RGx8C8@c0c@c9CDYM-dBTCfI6}WU)u+0ZvKNA<nYiN~wJ@F3FU4yRtO%2~R*x
z8D_xyArEBa$b&g0t1R1z+`Bb8;??rDV=}nIFUj<LKNz63mpqPn)B&;+(|}q*rU(Xv
zhA}bV4|yts0wILjq?^Qty7CR;?-+;7=Y>Tv4--y9<~97G=r-m({P96&r&(hw*7|d(
zo!MI$U9$fSqf7Qr7#)sglNkq*e`b#`IuzozcESmh7fsT{kD>|14^S%zQ#57Puc#kp
zCc%g5WoEi`z>#VSpt$HsHD&Z?B&D603It%D#~7q()@8UrB<K5M`7-5H%@TM)=p4(@
z5BKX<kQkT&2d$mJj4YkVq?|wGpGDrzABb+XN0<iUUzz?hDY*=~?jVlVPN)XzWg@BQ
z1yVsrCl1)q(FyuBbi~-<j&26fb*KVrstCaVW2QX?1>KzZ=-ehlmix&QTW*61<@N-5
zAR^kLTt!8FSUWKv6B0T|;D+b3?pTP;wi5+1c}y!u#DsgvPGHD{6_0@-kB3gAc)U%y
zCngMi#(H%bTy84#5#i@8f8iQt=1(|hp6mJNwKIh3LN<9|%bhWCVC#Z5VQ@3TRVI&T
z90e-}eD;|uc9Kin&khmke>(KUu$gM0M8W`c!L$T7CJJT8Z;pEM5@4Dqb4kIbJ=qyx
zR<e_vfd?~Nxj&xC8PXbNZ;2OH{^%rL$QeIUFD&%KoE3S-UUouYJXK&jsTX+8LO*hz
z#3voY;}=W}QN=RzF+fSSlaC?oIw!Kms~84e%q?0>*Z?Kjq-AA74Lh+n4vS5@(c16f
zvJ;9EDLFWTl6Jfg0<O*&`3fIdA#nO)6c|k&gWxP~0!AVciJb@_2O`*1Lnv~Wti_Dk
zKa}vqRCs7p7W&Cwz?jkQv-ElTo;V?g<w7NoB3lbMp6tfKFb^)rX{$O)J2ebut)+n*
zNY$4j!Ax{i*a|)Q?FVtz>IXSvUF(s?#+r0XhZm-mlb;3WtSUooN=%wJf5#!KYEqlh
zKegkFWKQ%XP5cJ)gV*Ho6dWUuhfomdorFbDM^J~GbYF+ffRR=199!=ZCW0pTs%H;;
zi8v%rES4{gi`R;ncRS%(zBDdh>*C0Kt4jkjG29)w=pRX;EQ*0KX_TGFu7&Hr>W6Jg
zzHz~57fe5<vSUnRWeNyeFy5blu!W=aLCIZn1u1z4RK-r%*n&mA!CDR|(6gNjQcs$;
zR9Bk-ysKzvruVAvEiQ^udjUykD%uu50&85>D%K7qnKQJKH5E<=;D#j)l8~$&3QXNi
z#(m^cGr01RrY&EbysSvdW~@s`6po!xIiPSf7En0sN5e1l!{Hmg)-zUGl|{Iie(o`P
zn2=8h9w0F96b{Y(K-<HK(*x+`(Jv3f(@*C}=%t^Lm>jQj)lauv^^-J^t9~*Ba%lSO
z0b(&!2V@dKYjUUn!SYVwH2I7s$)8M(eJC88TX<^dL&-T&F+m1KkU-(s+}BeRC&e{5
za)%%zq_IpQ0Vmd;nI^fn9=Rvup@tSFnN7HDPmpBdO5O=M#>rI)8z({kNx~r7n{bqh
zV)y;%Hb5h9BX3Hmg{QRSeLn{R<$WAtM4l8p!L+D_6Ut8_z#o`U<|zgm#1sT-H;=AH
zw+hi8EX@+RQ{P)S3RK|cuBVej$>Ui`m4VoJFk@O5GK1^y8>Mq>=8$DCWT%~OFnBxN
zh|=&Bc4`1D@Yu;|J9985mF-%sLt#IuT@nmIN&+B0^*i)#4}~k79bbeTJja^)5tGP%
zYUwpFgDm2C9-WkOxDf@LggJ`qXNF4(?Tht$e#mkBP9ej2U@#l=I|aHkQ*XDA$G^ot
z(=a#9_)z@uCa=gN{d}>{ALJsG{@yx!HJ7c>zxGDrxJc(c-WuuxpH&&>gI`LV&25Qq
zvrK)AB5+sY6E8e08&jXsEBQDpGF#v~0n3aQ`amnJA?HvuWb1oUmSibYdM_QWhk{j7
zdhR8`ErL@T<hs;b9Un@46A)H!4TarSZ=K`VTJ_dYhr+R-U>TCZ9f9@y5w=e)?=7h?
z*gcuY{`y3sIK>u%%kD_~NRbcz4ke9|s>oaGTjNc6`XLY9CyKNe77gg1eldR2i!>)J
zW_{P3E_vjRdS#h9?I>leYVb~pU*O-k<*-Su8XKy%kE5f~X~&{iNuh@CEQrvgLE|_>
zwlP%BO2UAyD+2X<<R-ET6&sW9M}-!pKDBVxxv*2?I8%sSpPr&Re<<^FKmMto@$u0A
ztq$?h(dHU(I}R-Y_ukOBw(#<X7J=JwXcf5m=36II1M`W=UH&9#Y<8mM$DW-UnY#^v
zVCNRLU3zaV4b7eATz~E>9$q!4$6GFc%^NOv7InNQg|~g~H|Mvf!f6#hz|@v*`q)T|
z7kwU6JpT&am@J2L?#hN*o#!sivO4E#Pfr~vSrzEk=((_VYcQ-^c;b$=f^N5C(YRPG
zC`}&pu^p2Ld~6@bu0lWBvAvk-v{TtN<7vlMM<=IST9Zz<G$-*}hPz9KAGx<=8=~Xt
zn2)lQ(=jkzbW_0!_30t(ZL4As8~O26zJln8cBsn1$scyInO2Lhz_eO?3Anl)lN^g*
zrOA%Ys$)2WZ|a!+w%due%BX?`O;rX>I*@1=O<&QmiqbQ5EUEAVrPY>e&}3Z1HiZ91
zR$KaNj$xO+ny}h(4IV!Nd!0sEwEDxqOlOUm!Z6{SVZFN~&|=QLLFWoR_nQK{JUl06
zbgrnnxY50WqO)+sJlo`jOE>;9X?n-f4e`R2o5xm9U&%4&Zweg-&|cv42ojcP{^jW+
zFr#1mluVm+TjZ{|=mt3?mhLm9$>Q_JA;K}uR6`9Yqf-jqjw6N}j9wM4qsuYGKERyu
z6}njADm^_y+;>=<AK1IciG<yKX+eMJi%93x{(RzH<kTDe)~66|DvfY}T|aaJ9KTuG
zu8(Jp2aDWqJbT`Ml7QAzjsV0!JHNf9FRtgm#Rqm!qXXsC%`M`C$9to1Th-cI5i9tx
zAd2jiZ-?}<EZ@$M;r+E>(?DX{so@SWEB_~D_i>R@3Am0MmHG)CtyF1_AC?-}@zqk5
z!x53QG_jK}y_vY-Bu(sal5}sYvIDhhGj>AXHmCjYZFhD;-!>P*cmndu-RRmrHG1jV
z)^!!PH+tiF`+GR-dF^Di#iR_l>?@xlH+<Voj(<(Ei5(mYjpy;RcyF@vEZ$2Tg|>Yc
zl7id53rWG5(&_yy-b;%0%8r1Yz(?HZ2G>=hjcj4H#wVDEMQF}m^i!G_hR9QgK7(vd
z6?z8MoGSE;ph>ZPfkenj*HFU0sAJ(@uv%02mkcnqMko0xs7qjz)X~P{o2?Fz52rLC
zGgM!93OU3XpoI>hzn<FmEf3sBfnEBsPla8axu?J`kK9vHHvvkV2<<v{>g6thxXAkw
zjEg%8(Ia+h<mOSWKr(A|ct3vv6j!bQ12~jK))=lqMA?;<&oMTp#OMr@&Xv&_CjF}O
z#Fl#1Z=$=TmN7u%?MDfNmDa_84B_SsNIXBa=LN<CFGXNHFark<@O!)6fbh#%U&b&C
z;Q(2|UQj{ngpW$gLX<_7M%8I3sQLHAJ(6#z%~k3X11KtM&?40zFGg3AI>3>9LzNKA
z%7>CK6`lQ^Uw|!DnBB1tO3ZAGYp7H{7}ijweDp9G)Tt{lgAuAU3FLKrr#Skp?AOsR
zAlcRva7s=HIhDS^Xad1pjnM=`!fr~xbi+;p@wT09bc@fFp##F`8bb#X$D4C}B7Kcv
z0RaTIPK>H*hcY5SImm;OC{UFF?TJy92q*d<AY~)?U)j)&=>B>HcE<s(OzS~eiI?Vw
zGl;p?N)oKk9PZW=k}AR42}zZW7b#z9(MgJ<Um#{p0DlV7!1v2EDullzCgJ=Ijoda0
z#WbPvQ5&%5pZVEARaR+%pv3PbzPfYepQJ9MTDA$f?`+2`B$(a-_sQ7-({on<OfNAb
zFue>GdZ;kW@bT18HwqzOd*w6aW+9}2`<0sbDb?PWq8Yd{@Ls97h9L{IsX~YKML;&i
z0<uZlDX)%%UJuISH`pskOC6yf*esd4+EmKKkmQTSKS7C!N_GqYSu^nDB56-drOpQ<
z_tt}-41QV<eiRl1_W}bAPK|N~8l3v$NEpU4p-IV@Cuc4$L$JZAFFuOGf$*gdhUw{w
z$^ZnG2)c~%2dWOv@PkteeAG|DNI{9k&?R(WgPyP_8;rYC32sIusN%LEnfi&avQZgB
zsWY5`3M@5c$kTp;xi)1!V#MMXG4?4fJs5qb+u06yI0c~@@1ROz#&`$SA2XzxXVKE6
z<f7|lHBLMpUrY$DQ-^sx0_||zAS^<~+6<}C?38965L~DH@nC2j3(^_VquHrSJYW(k
zovm0&oydcca=hydxI#@8{*3VztZzFqa!x)nMr1tx&fn9ksz)k+f#}KypNOzTYd+#J
zgOGPJ)ukK^v$F@Axg0pM8Psu#tPV!inNHJ@2K+)#%3uVYt}2Z3D27(fO_!3PcslwK
z81$i7S7XozqG4@x2FD)G7#<7f%wYVSt{Y>=&m~I`zC~tl#)Bw=*TzuTFTY2KV+8^m
z>Q+Rku=>gA>CDfVk#g+K3>r~DvLTn;rW|$<<$SnNm@_V)V<<MdfBMN8Iv0h8RtBRe
zB-_S}XzTo^BEdN*Qyu8Yo(cr#3ZxovBfW<)Rz>mVhMabrQrSty)k_I~{DfEZF%d@3
zLxCw1&S}k*3FowC&IAS_U51dCTblQP`}UTJkwGxGKiJ8n39=!MNSrVq%w$mgInVis
z42C<9<~~O`Q!UJMoVt<{aPL3`Qn~{}#Lca9oB0{0oQH!68YX_ATny@>M|-k|*_F=0
z7>aX`bJ8%O!Z?E>hlG}61+0Rrfl!?LoY%Y#-{;6?3Wjq)BjLh1pP@e8Dn^fRohuS$
zsGpqRlak%=RlqNFw+Dl{QxpXrq+sWq(M-W0y?HRb!a1jzUZK&ZF_>OKnldAS?l_0%
z9e@~L?|+j`34f<gi$O!TY(<mF7~~{p7||_T(PVlC)2(Nw(soO|p7+VqlFUpfZOYtY
z$cGrvAl&RSK<UP*tJYy9ms(aI1~A?7NzNO->AOC7$)%RQjWDOXJXp!K*HMeWr|YD`
z2~x~JXDy0V0cW)d*+)5j-~kAU#{>KgR7d6eF-BA|-;W{pBa;SQAjOoVHfJ`-$UdZQ
z@(oCBMnNuRF}jkpG8@uTKmFuFG8Xz$x+I%SM+M7B25wy+tQZZ_S|?AFP2`@E)q_RG
zl<nzBp&N0YY*a%t$i!cA1F?RY(oa2~qTS)~*!dA31BdmI=gL?oZ9Q6<#f$F<Sw0u7
zAFQ>uq$wk|Y*YA(l5(-0bdqWpvN8#o;!2vbC__ty>JCe>zlIpKKzeElnOBSp#kOfu
z`5MP#piDKp2Ad5@)->sStvY2<%x?9^DEStZPWMUTQsV{n$H>U%_SR~Tf#bG$vfSCO
zvbS_}qQ!M)mNMbFSfy_%s?S)<Z^^d*pzviF)Bf=!0YPa;HpOCgD(udpflGSsgVNbv
z$Wf@FEz{Rgtz|JnWl*%pje2q{o?q0nCZcHP^P#ge***)CpSP6OLqQ9BLV79-CoY=A
zCo^iwF!7+AaYt_b@)(*wI;)$M`#ILi%$#R+(b4@_-q?h<Ru|2)xVZuEv$iAv!yBai
zihMnmmy|P3>`PydS;Z;hO1=6ZMXP1R1!mJ2kr9pDr0!a^L!ql+B6*$5PWzy6)sVi<
zrB8}7Wemw2xhKEsgFtR#8@ulC4@wb#p|de|MkK}8fD(%|&OAvt^9<;EMD08X4E#w-
zS7^{_%dg4Wp}QP(%0m(G=S(MiPLM<4`G-XG-X2Svg3Rqnij@?cPL%ri&CJZX=O=Mx
zdXXN@9Ve$1$(>amE0UD^Nr_dv&!-I1q|@R*ef)>3eC+@J%m4XN(r@1<Ve+XUpak^4
z{MV0vzV`ONUp;*O|JT$1<6o~=`}N;{@{bb7=SSb)Q+@SUKK}Z*>woy?f4cwaehu~4
zf4=_rfB5S^mNx(4U;g`l{m1{~umAJ)KmGOEA5!<%d|wkNYuvl@HeUakAOG>+fBd)C
zbG!5W-~aNrt00?wkL~xjkAmw=$9CK^`$cZECc+oo{=@(Jpa1WF{OkXfTspdXNtFH?
z@1+Ob)7!RT{2rSu<VZG=-RT=#hST~>F8{ax<==_RwwJQ)CA3w`c>QDEuT?F-%OulL
zkx4>io?QO+p|Fzck#KVT<be@CX?P%7IC1}ub!fYM=GS}c-~D6n|M1^`{P@@_qV2V~
zy~@~c?Ddb{N}1#Lmn5}UPOsJHZu^?w-|a5Xjt-yZo_=)SX`%i*7GT?+=W92-Hr4i*
z{r+C~r>3p&_j3u5%-#rbPILv5|Ne``W2lvU9#iq;FCR-w&3THJo39>fD{lIF2<@Ld
zlySXWd^Eqg_HCykpTEEM_WiYQX<|4N8|xP)2JhW@s`tkM|A&tOg?k<oEceUDfR;Uv
zDPPW)k0CRimS36bzPJ9{cku^%zy68!N1W1`oYK~QH97OV_vtYbe)1SJi1XN_ap%j&
z;2AoPjq)p_AwetO0NdYu1A(LXgD;?b{|ylIbS7tX7<@T7Byu~CDYM&`kKOarX!rbu
z(U`PdkDV;;Uq0q(HsKp!`|nd%UeA<S+(W0lfBy}9+~0o#EOvb+H)sO*a&kyzc^*@3
zv@aja<P49;Z2ih;b$lAFj$auqyfIpT_-4Mh`a9_B_fMdYKe7McPUN4T#wG4A=K=3u
zXkd6`J~r-d{N(2-XM7&%bWMEu7!ZqGYqr0++GVGO{)4^#C(iqVV1+X|WdZwga&Us5
z$K)0N@-c*rp2zO?3!}l9p{Hcr`0AmV9vLqGq=V*LtN%Ku+8=E7KcVcvyRCT*`-OP{
z1o+Sw9~1jyi5cqqLtx@o|MkffmWju~1jELc?}`J(s;|c|fB%-RfAK%q@qb3UKX(uk
z>O*<>)!XR4rN7vGt^fA?|A89t9X64@{je!Q`ARtjUgbO{!k3RBnb&ztgfAcS6jA3f
z5x#t^zyWriJCtv{gzYW)`AhiD2fB~5`)z`U^7RZ8<NJ7ygs&fq`0dA2Xn*}s7Povn
zMZ(vQ&F41B);AWvZ2$PrSN}V*sbra}2a_axJ+YNm<;QcPeEDE4>9#lz9?I7b)->Zj
z9u(#42V4469}kN1jdxLZT-MLu#dowaCJ}#dD$3VW1X$wnpeSEI=;<eUJSfW74<bR#
z<3Ulre2~bOhiDMxTe9J$gSz$AzIq$qyP+WN{AozDUpeO)3HEqUl&>E|?d->cqI~@z
z5OR+PMfv){>7UNtL;23z*lrs8>D&0$jb)Wj((_QhoMOBCC;53OUq1*0?c+gFzJAc`
z`B1dJejv;6Jf0!p8}DEn*4EG8!FOaui)zIWHqriia_PEzJVnCSkNNYA$kvw+bQsUh
zLx=M9gMh$39u(yp>)$v0@#pLR9ZjhtF6Y6iC|^$zsV*K5it_b?s8s%VP?WD91bpi8
zpeSEIh(wZ)2SxeL+t}$!fBrW9#2rVMu=gv^kB`qY`PnW1lfOoUZ<<VB&;OfvY)bj;
zvJvHHGt9ItkLRlW+~H8lC#MYwKQn)Pa@&ybv&Y^YH*A0RCEWiuuA6eBEc9b~Dir<o
z{670{MER*XseT^ums~h6g~>mU_)AWlawGTEc^9RB<L>l$89U_UU-9lFMghZo%uvA0
zFYPy<Jvr-_JUQ#LCujYVCufcF?tUQQCy$}_p3F>*kil=ggtax=KRA{Cge7}@_T-T8
zlgWMd<g8!v<Sf+bdss>5FE|7o*+li2tH|${kA3pw_@DFS_`i)O$3J^={FgjA-tF;7
zx1aqyl69O1kay<GN9uSy5Rt84{`}2r<A26$<Nr2Zn+X)MCN%|1{?bVA{oNrz!q05`
z<<n@h{K{ybJvsB2JUO#9+Ue7k(AvXJ|98KExji|5@CN?Gi9eAG;Y?1+5x$%pYP6ll
zRJ85O#}Hw09#hE0SC0*(lRhqwb^n4VVxTkw-vHa+d;?=E;QxwuAaaSaPG@q%er0m~
ze)qGG@RP?rtGwfvG~V$Ur8IsCr8H1kRBu3)M!)w4wr}STzJWh=5BTidc~QQ0WaI_#
z@!+9+<7&4HmZasclz(N@UqPX>2dfX#Pc8n>$Flh?oB!)0AL*R?a(;jL&OufYM*U#*
zLHdcY**<T82kAQ&_16Vt{nAXowO#Lw^Lg&qL;8t5Ht!qHM-S;c_R*cOr~JxH$9K$g
zcSdVH*nN<G#RB<!Qk3u5Aa@47Uz(?XXPy}_^2Y5UeQjMrg1N_|57Kw+OFJEx{rnXA
zj=Dz!(v#Uk`g-U7Mv{Cww10g3ruSc&cg*>p_Uw0bcFxsznVWpspQru*?O8v3HRCVK
zs~6iIUVorG{^9@C@_Yr%-`3{;=MUwI&jsx&qY#1+rW;Rp-)`qM*;5hPg!p^@77@Ol
z_{L4i6-FJRO~`8(N)h>Fs0>0Qf^g#(I}evnmcWHq&1a^2M9Cqa471LHLp~W4;}vsq
zR=x0wNfG>mun(UM#&ZK(L=|QgAD`4!vWU+W6tI;sJe$z7Sz@7>FwoPBv<VeI$PN*Q
z?rC`N$!KTK=n<bx5ac}?7_MV!6FBA_Gf?y$ZX`YteCHht%h<bgPWvRj3o$n?3y34N
zkxxe3A^gWDL*5V~<da$HvTlw~UdDZ5@m226Cl((D%Pf-PlhJOdk>iu$ZisjC$sE$|
z<csld?pRyqjdPF1WzGh7tSu56yJKlpCfyw~ivbp9#hg68a#q9?12*E5R~26wSnZQR
zZtKSKGvN)Q)_gK<7m;l~@AJsQBj9QkFmh*OGcgEGS~<86Mg^@5*!96wW(z5deK2lq
z<&1nVqs_`j9@Yp2d=at{J8CcuLWUAvL5Z^f<z#jn<K;bn@OHWqjqoC5BiWsdpoGQ7
z2O?=-2fq)-$7Z}{5WrjmKQs>^>eDmR#FZ49PtalV!}zn67hoSu>$x(N-v{%^EL85^
zlspMg-^B-Es!`s>2lIHrRqq3-I9GnHK9n$K<p=E}zf?rs`e1IDH83#(>(@xOk>+J#
zem?kNqCSg{OyUxSS9~y36=hdkusl><@nH-aUK1=aP<1(&$~e`GjrKw09HOT;0W2cI
zdQ&i}!&1f1Hlw+NkY~kO;F_sc*24Cvnb8AL<USbVA93bBXc|W#x({a4DmTQ{V5zKf
z-((DN`6Xt~Aku>9`%OtE3d*4P$dIPp&TVz`#44zZ;+dZ+3Gs$*F_Ly1?+hX>H^dTB
zYQ47mChb-2OG864bt0!rmP!c<M#@8P6F8K;X4hTgWPGA`*AyYlIz0mgX(7D3I%z2j
zUnDd)V^eH2utD_crX(MejO7C;1X^y0qdxPGV1aneg4`S4hnRvq>O-UUl=OXQ)DFh^
zeU>}F%NGT$*fG6poDnnW%yY2`v1xkOFe$?~rC|*rq<T{~6U?>KQOc>#EV2a&ST=?I
zKvMN4b{*_CW-u&B2lFD~2fI_#z>riOxsx^_xiyW8T1K11fg!NEY2cJtozbfW$e=U}
z?^YbWz4Gkbq<rU<BQLyi7CI>9jur+*W}i*Lpyf`*&!zsC$QZQSc}nbd&W}Om1!;!7
zBS^MnQJURGWOYG?BbTCHkOgT|*l_{-w>pNb>o*b@mXa;b2GXwM!!HncGGlE@ZrWSp
zB2j|(TLY)iYfIy15(96G6UsAk6Y$|@3ad@%7uvyUb9K_Pg@uJMY_1+44V#1cmfucu
z@daVmsN}wGC*WhM-xN8nh@z4i%dQ}G5PGz@CXjb+YE2;V8g=E@?d{bXtZw;g<}$W{
zE>j+R8|pMAUW019L94sj|H4*8XKw-y2H00N1y7{JQbnYKJbJE5Mw=3QrZomu7o^{F
z)ezbg$7ARiQcIP3HYFF$nBQ-c;+t;zj!TFx6~Ec-5D+W_Q;@*WRf(lUeVjeZ_(JO*
zv+~D~S}Lzmkl4{%MJrdB3hSm|&8V|(Qmz@Z+7x7=bk&tCNL1;nVzDVZ0g<ahMM1_(
zZ~S|%>aC$6!+;D;N^Wn3w3lkp#8Fal-HKugB~yEbLyBGI?MsziHz9Q*l}{+hFzTvd
zP>`3@ZK0KJE?2LRX%Ro4T=i(NN60kQ5hxXM&0Na^xuz<>r9$y@V>4K%ccLHztTT0g
zK>(C1Q9tdYn}T!@o0PMg8aX7LDmd?Ue3(Z4xB%1Z26gx<71uRo#xGe9CMcZa#EkTH
zW}aVHDeX<b>UYfwqK_HrHzDWHH53FN($DX9j~0vtn~*c0BD^WFWmSWGQ*usCBSZEX
z^VF8i!R*QaUr^G;k?*~ro{KBFdqFyAS1$LG^<1tXVQhPeKb4a&$Y$*-IbV=}+m$GN
z2PGwMRfnOabW>vV0(X}i)#8HED{kp8Ehw|H+sWKj49#3wq&asbFW;1WtwqB?mMJ^=
zreLEMjFXbgq)a2fyBl?BB!zb?8agFePW=KUml9$XS?!%E!e10z-0Bi@bT8urzk;-x
zsZx#c#=S1}19`@r+XZC{yh=OXd+iDWzIhZ#aKUB@s*-qhjWnXgQ8Hbl*Q~ISlvvy<
zbsAsKi-K0pW@^-wZ*^+WiF+n<T^E$t@Tw0QH9lNfs7sb7aV4QHsAu9?VCn*ip86k5
z4dPY$F^Yt{QcM>V0pAqPe~~$9$SCyTwQJ}QaJ7qDT+T3?e6^lO>;+P6rpiQ41@(1;
zlIxh&K3wUe3uK5#?&rcfLtZ6kTZvYlIgnajr5HywWS6V3pdQDjaKTWJ<3&O%xn%OX
zf&x~Xf>H7sSEUwbsf{a092ZitN;gKKvQ5DWgPLfYg5%;P`Mnlt<fyB$Nf;S7JLQ2c
zsG8xmXk-Y_T3GR+WR*Tw;^%^j7+$3-r@G@z>0F=?xgb1+TGJ-wPxAL<9kQ}W4Mq(M
zXA<Uu3KpJ8m@kkLC$iXQ0!5fkuAnxBmnGgIEtPNi+N3y%i?nBGmR_VmhwkY``g4P{
zEYP1D5~^(i$A<VUuCXU3DJ2_aC0t>orNPR)Nqh{VP$`g0XzgBxxP#;?L;OMV?F`5l
z2+57aa)aP2)S6q$y)rZm<Q@|qUqOnES-QrC=qp`gFDyC)HSRjQje{sJL|2e1f0HXt
z>vD-}l^0r<3u-)U3Pwix1~2E5jlv3EOpoDSSM<rpFtjhz)8xt=TsqQQI}-&L+*w_T
zf(!1n9*Kf?D;cS046JrNtU>mbs-aW%DKl_E9Rx4b+dC|rObmPlDd$u1gE#|<6!+eu
zg(DJ{1XqsV(ov(vi&S*f7VvV5GYG;W4IAc<O*v1caab983(P1UNqS3viNRYcc!wCg
zrGvvL6O^=cZc;4ty)-Ul;k`6&%EDV}I_d$uDAAhuew2Q9lVW~1?9Q7I(^K}{P3h6*
zurP4mdCtJ_<;t0hkVC(zgac9Kx0LXnqVuN09dV1vsJ`qD*(u24rX;UJBSCaBFYYF6
zo#d7d4ujyPkbQ{HTOT_Ni+<BCT?SIvZ4w4g`=sB}%8@PKZ))WO?mXqjEy$I>DS6N!
zGyW!E?2!*}+=3ZOCm$hX@5V8B^;E{&P0IN|0Us$sZ>iP;cS<F&Eyy+>6qtdKTYi(+
zFGT2V=-1-k<QwwyHt~*R;;wA9o0Kn}cIyHFhAUfb$&BxQOGAfg{c@zMElAz&N>95f
zHJ{<w5UID+_5qoB7hQn{geJ4fmUJulEdw?j51T?}AQ4eEd>=CKUidAYdq5)IG+{@s
zaKB~2Mq==(bg(5;dS5}};4@k{07l*vCv&|P<jI~&_FB@lGg*E;DVzVf^mz}*$Wo_~
zDtdzT=zcC)r^iZtYm-dB*?-&=u(EPsY12rb{G#j@vLDYiq@N<S@g`w@GiBOTCe;#I
ziKjBDmdrSu6d3uD=66OW)q;e+Q<+ptChMI_q*~xZoXVtHGV$&eBpe7c^~k9#s3nrR
z&L!0uIa{Z4p%!Fco#{BcKuYGAL%P82`l6r}%t_WFU+Jdg$32a_$sRq4oR!v%1e%+I
zLw~ktanKxoQ{a&=NCY_-wd_fNuGH+zwm6m1v>+|wWKPq)`W^38pWW<ut<tj7MgF45
z1U)-;Pobe?cFaI}^&HW{*F6VjAf0*+ydhbn=SWFCmG@(la#GZ@=g2up&7K2uf|fle
zCUonJ07zkzIQGOwl{!ARJe)3Ne5QeSQ#ix4piU(@EkHwTN)DYSt=;CV9q4B%+A~dO
z)1_zw$T3~2Hn1Mkp=t+GWGahk0hDC=)FCk!n3JV?E-)ucwdc__k=k#!_uf?+)2jf?
zvPoDdpjoCen-<_%rV^VL09vLJo4z_Kn1R%D&-Xr&$8@(158-G4EM+QlY4NNVu_^e_
zflS$y^HefOz1r>7kj9K;q?<yu6wsATVz2ofP9;3ulzeYZy<&Y;sBn{Vfu(ulkDG$i
zAfMj^974%QP_jf#LEhC(;R?qS`LEdQPVLw`wu-FUfS|l67n=L`vRC`SaMFf-U^pqm
zKBL7BXWsKSI4YaDSTa^SWSGlX?GR!vZ8{Mun?P$U67If8XvNE)QkG+@Po--u_!xqM
zRav<i=0YpD5DIEjGGc%_Z+^LR`lE+fy{VkR1>gTBVKs0@%qjCUk|WQl?=Oy;IR(oo
zK&os~jt!*BCSY(tRW=3ZBcLjqLVY;_D^sAVl6aICg{m;%D04~|UfE)&z~@Y%s5Z&)
z2zw1lIHd(INWv*KctH}*PD4L(X>SS#h9Cr<s$@Fu-Q>U!g_D}_RRCa_Q>yS{T!+ll
zkfn1{J$^~rDTq~JTJkxe8UyAsr)<-Z=yS?8y%<g+{W*~?bDE4tz`9I9wF;81&nfj8
zO30kjhM}j-c?{MsMP^Q^!V7|LN*9LiGbdEx1sOLbf>%~wo>Q9df|OJEO97;1P8qC`
z7=KO~tk+B#I42C&0eqPPVHF@>=A`zFto?J!ULB*}a@;Kk^U|i5W3~191Ew;E)L;Nr
zCXiQGl6nx%L&3_BwHjLVWM<F`-FpsNtLvQ}z$wU8g#y1Rd6ZOW`J0kM)hrgV2|3ax
z#O-7b=THz}gDUo><fI&}oY2(3CFV0JXDSdbb4>OL0VjY~1y*H_Ax<n?cQOj2>l{Om
zKzfaVR;>N#V#BbEUGs<NVkxI2Ej-q+kPuy?YwQ$Vqif`bmF;MyT05GChHN7Ys{#Tu
z2X*dx_h@m@4({9D5fxYLDHvA8-F*%dR|8C#*cy1f`AJ?$N=E9VqvWKLwHXbvm2YH@
zD%NIR0p_S08iG&gstVJ`9MqI+T1Vz68hCPN6^`uKSw*8mHjbjvAs>a(s)2f$X-T+1
z$X9r?--S8c>UUwQq-I<*a(#|l+@b*B>{NSefk5m~dp9AN69%gm$itpmZw<i8?1C^?
zAXa9l3AzHYGCNJsn-c7I*T@iu3Cp@b+FP)@hQ`gWJBCh0XLg#PD-40N(*%80SPD0Z
zgI7$FHt33CX0uOq1PMs^RxMc_Z+2?A6$aGVhxmhd>*FtcCb`k~4WsO)q;IU27A>4I
zz^%;Q#Tvw0?;024t#^&v(x5nn*{U!a&)zk3!;*K-2;!}Gjox#?8)aFA1$*|U(Q)<b
zyjWM%6rA0}^8klNV?j;8%IqcvA<?>tK}fW2WDo)khUAx~RZ%x_1}Lir>ScBsp(~0p
zZVGvWJnL2CdbEI4tSAJzNf;CYPKc~c$=Ou2GQ_lKR9xwL(Wtn<^`f~!BzCIZo02c+
zemoV+K83idHLqw2lBg*Cxhdcd4yP9dtq5FQT6nmuCc#w|#Y<;f8U>=Q(Fk4P3!5m5
zeI+S7=D4Y4Og#{@5gw}oDl?mN+?wXsP2s??=$pWCahq$dVe(Z@!L(|6B40<UasgB%
ztlSiKWWnv!x<M=ogtaNj@uW#*lal43NkA;N!AYc4Y(qmsDmJL#SCDcNRKY7exU&t7
z4$;_#rnS568n{F9x6YAMGSAjEG{h%RUlm1<cbntp{jqh44Pa?DiQ^7Tv1#m)bEFuD
zJAD!ub_FS?*f8{rf3r)7(<VU<&`eNn{w8fbjmq^VCI7}wlY7&2U<qxeWrQ$IOxOid
zZf2UND_}I6!ofqDwyKeF+iVphLk4XE$IdSEjHoF|Tlou{$(KHNR9xSbEJjxY+%X%i
z(z~5QQje~vB0n4T=n8nurewcY1&(AkSfy(sO=hE6x&j?Djb`Zzbj-A+!4c*#g%8^#
z$738l^_)$?P`F6i(pYhkG})>vAURWzv1$;KCPmsHBrRwC5`Q)|CNFn3wUm&5MnMcP
z%oLET0=M*{pcU(AvQ%$UETj!h7qZWWhECaM64eIL2k^?3qzt$p_(6QbCguA@pC-i{
zIG8Cw*QTVxWm1{}KAXm`%^>tlN;B4CniOX&*fou~=}j7VjH?3CXDwR01AUJG-)+hs
z^$JQZvuRj}Ju?jp(PvV}6D_j|fVEe^Wu_oq)gbzex;LOP)1-d~G-jH#Zv)_AnzV0h
z-YG~|#g?BYWxL&&19k0&B7jr5t~V(-mS)``AFZfk2uP!0x}rePw42s~P0C47|Bl08
zH!&vwXC_cx6{wlr=Ew!|-fj(zE22q9&ogIMY3L0m&`Nm@<jf`jB~k&MnH4HJfHS+z
zvGeuJDjgk%>ZYLJVa3Tig$}E6G|x)gb;aR5t5kHH@UuciPZaPK1dfz4RA8_Q?98mv
z#~Vawof;`c=(R~43No}#4AtY`oMB#EC-Gtx@S2&B&I_d2;&o_X$j~Y+KLzltQu14>
z=Ch`ff7J#FD%jbkBxlml+l&^@8o**Ug-`IlS*e}3lzvr;cZ2j39IQeonzgB82*1=y
zE|BsiHg+7suQsi|W3xzoZw~fp$9~N*f53rZePs%@3SDwmQ?Dr^10z-g*)l83KUW}I
zHU)<jkS#Atv{I;5+OaDX=_%CKrsS2UN~6wrh*^s|g-omYXWaTKP1&20t98q0(;?#o
z<Jy!SZ4L}WXbpWESCd(mI>kMaD6ZPuZsfo6wF`C?8Fu$@#r5MoT9Jm_8&1L^9T``#
zSzHr`cvDgPiYwg|?yBak?>b3eDsG0Gg0XS4Qvv&m<ZM#~>?;5-n*tYU?IW7_xB+OH
zELLBEXPHGRbK+TM8S0c`QBbYgAr@7gzUD=IsyKZ`sMRb|nmff}q0-zT6;*nEQ*r`O
zntS%ZVIddG(U>~~W0A%T<jXA5m^%cckXkjdFcW3wucX9gL>>7GTgWU;gF{f3ra41W
z7OK`)4Xeu(+N%QiGF2(QjyqaC{|)A)F^}BH*A%p?rU_{lsmB8%Q6=8%fJj6_stQQU
zZqw=mTh%0#s|LtrH#rOhVxbAU0^~AP#r@i(+{#5mLnIa`+lhpk!gp05VP+{D7$rSt
zDH<CB5oV{P<Q%1u!+<!8H1dI(%~LqBO$z>$6{iBoG6nOh31peKG-&`?uBpQ7n-t#~
z3$It0QKzb^*U_VeV+D5DnHAM9kmBXuGHk=1yD1zeCD5i|oHQd%)K9;Xlyk}_AkA)B
zwnyFv@2Lsm_NQ9tHOt*!Ny56oTzX5xCfG%&tqQQqJsuCGx%8I78`arg6trTOsd#yX
zS$_(kRbl#{X<oiSay-V7@&_CQ#?!l_l?y8^J;TATAWi;;>9II$N<0-hsl>-bwed=9
z%q@>oCD!GZF&n|~Q)sJA$z_x+8#SdjCBrvrR*c>Ru!0)SQ`NvLiZpKu769I+Nxan+
zq-0U{?8MC6(y)n{xv60jGIPtCO-I<gC94UUxutXiHgikoCM1S+yekngS;sq<t3@;a
z+`zrG>2L?mTZ%J0hGR){o+vRt1kb8S<uFvSyCT`cK*jEw$smU6byt94###~)K*NkB
z^Y-jWdZw=#_?S)M*dtmT7Xb;I)Ir#9YPUIZem9%KRU1gQCRI8e#bXH>vMD)5snV#B
zGnRDaIWYn1%5(o&DscM3uON|K2Y0Y^r%yfFI1=D@A545((=k6Xn*RdDgAp0KfqWTD
z#%?4+8B3~kCQAtl{aFE!8B5wU05XGRv@3uHLuIt9->(*-*1J3zW+(~nH)bex8=#i4
zBzysC8G?UpN{=>K^8!|6=Ju3!gXOC?A>WWBGN3Ro3R+vE97}d?z+i^TS#L_Nw(Q)Q
zI(QQ}Zk{05P(|w~)f@a*v~po(*>;QB$gb^%$&@oc!))}m16Q*X{_(M<6o5D+yhn>{
zbgsUv+Q`oGqM-G9z@=jYA~Xoj+JxZ3g{<DBSXEV^j*`iHjeKd~*qfWcVRQQq=L0d#
zA^27Wpk}Z%bp@Vgs5Eu;87&T)0&%!Aex?FJGX&^jf$HJXv)z+3iBorQmYVjJq>iUf
zKgpd8*zRDD>bU2h$?L+(yJRv}XH#%GU<HRtPFG-UhKf$td=uAjDdRxf45uy*tj!R<
zs{(5?P|A&E$akAsWk78<0V4xgGhDhifHgyyuU#a)#O^ruYE)7m4&^&>i^FBI2DEVq
z%vAw@94?b}LL{#saRwC}L*EW$&2U+)fvg!W{Ts-d;m2YPXw7h0tZ@=-3dgqG57NkS
zo@`25Apot}1P+e8kA#nHg5wz+G^+)_P^}j(n?rE1it}(&&_~Kcm)eX|cT>n3#NnyO
zU4fe!eyd~1L#H8ojcAau)c?km6+2NgSCBX~1fpPL6;PT@!7&IawkaGLarT>pp%dJ=
z2^>BI;g}NN08VcT&LFg4(O3?Cbp;1d=0!mZ=}gHNWS`2_)zluYBw>OOep9Ay=pio(
zTCvh|h^t(RP2n|RLH125;&$KB$`Ah4!YU55as_GBwou8gpyVnW;4(v4Fhj=iF;ztV
zhLj_U%QBbCZo_b3&`!ss$=aa7z9?wLn$c=)(1AAveHxd{#0f;&G|dlUZK_gz1V8LH
zhlN<1LRT9QGGkT_)v!mZMrt{ss(~8zh|tw`Llz3!W%quB)$I`@GN!8ABZg!EuoV@C
zUdQUB=DZ2XYdJk)rD?9-lw|(a${}gmCSm9leS&crkTql8f8h_3^;<(j_RX7`uK`yx
z=B=?`(r+w{n;Uls31&diY)VHvB=#n7oVXPZl@u_5Xf}nTq{2Id1hc&0jv@4j;SxNC
zYl;w<!!b65<8Y0%vW1sH={Tl_fpi>G6H4h=?p3v)Qao-Fnmd{0y%eZwiM&Z#z7GIz
zf`YvO=uMEY#elsD5<jEB-vkB2!+;SatXD~!=ZmB*Q40CKPgjME(<8A-$-LfhDd1gT
zc>|y(NQoD<v<xMQ%-3L4=y-#DDM%bHC0>yDEtZsvFPdw>6p%r}`h|cD0+%l(WRSp9
zipZdl1<UEVwg7BxFVfU#4KE_m^%rPhYHDFRnW8(v5>OKqY!?7(f&_Ps0a6pR4nn>z
zsa#eDnwVV5$0+fENL2$4CukgP<dRe6GQ`UUse|BrDApu9!rX9wG6doVg&a&wt!c7p
zAPQ2?jwa_pWWB+({UVuoa=Zg#gA4}pAi<Aez|;f{Of9|^6H|+;TgBDl;@0!>7CGew
z%3#0`61b>$Ho<wlx#Sg2{Y}D(Q=>9C3SK0dIa!}ONRW;R(+LX1v;l+@w45J6I6=Xu
z4N%RCbc@SMwv>L&5JaD}n?GxOlATrZb)y+P;jVloDc^%MtX+jJUxQSvC`=cePkrhD
z<OGR_OF(jh!to7zaq^kmiPEtQE~y|P&4s~nl{Bn*%dI$F<2StE>1gK5oiu7*Ry!vG
z|Hr2EY;(;z8Jyy|lgWu@=#sBCuUrN|O_0#>0DnUq5A4&UhE-fPgGL4hr!mC9;8b|`
zvO0IOYkWj-1Pu&K?1!VVA!$vJ$ic*Zm|YCuzzZ5qBBcFzk(!=#@=0fgRW!-t5>ry=
z>LORv=PG5X5cit|rt*qqHAPGiG#0lhuUTdkr$XwRQJhYiQq2$}mb9Bc>q!6yc5`xh
z)!GES0$#PuN;at%S;0p+tA;O}tqumG*gVP{;0;O2`=MFN&3TJO%FUy_8RaI`H>1#;
zii0zw)SS3<nL%n!Uc3xwkErNGHj!WbPA!gI#bGg)I54~fYIa6JDn!2-1?gD0I2keu
zWd$j)&|<zvw*#UlNF0sgcQ`MZ2IS3)Cgsd1NC%x4W+R(8yo`c$OdX#{<P<clQ_9gX
z#UthDm}r8-p##P!MaR(C6r-w6V+Jv*5C8+*CrFSp!21LV=YUbzMj(J0C9NU>EQ(Gk
z48RiLb0v*KIbXKEc%$eQuHS(73KBcZ_ZK8igrZmYelv>R(bPR9@6e^sfK}bJ-ELd#
zs-T87irqo@fi;TVp=)2G*v;tl3pDIo-TWHluEGZl@SjbJX5pr-l7fwrnb8B*D47*P
zU;+OL0wxc<Pmo~wvzE`~KRGQrS2hXL;-#QLB#)vAApK;}I0cI2A$`A5BoFEPjUt&5
z1DlfX@YW<Kk;koRP%00p5{*)M=$1f~PteE%q_Tnw3^<=4frW-0(wBH>INuRpU@gUR
zr>5U1l@%ATNy#Jv1FS*fc4aW%Bn&RSz73A91EW#m_NmS(aW}jmyPDa;;SV%VkhmTc
zxLvn{MuFRv=h2WwGH7IAVsQ~eV9oLM^`QYBvl|jP%{e<=5dhVW5_^1*5|=Rm)^IoN
zO-Fm9H0_MJvrcK+(|&55vb0OF?>9MUJlp%t^(ENII)$l%1vUxmOG~TeL#7K-r#Myk
zz$Rfic^&Ayymnm&IxeqW!Fkqsd+n0=onlyF1Dk{wBgMW`!a|sK3RA)U4asDKL^df-
z6$)UT;xtfB>?`@yH{B^s(G6v3CwOU-@Ct6m)LEx6?YbWH6sG;w@QqW`2i+-5BZeR=
zj|7KpX*679n=S&K7ulwZK<7QSEgiz05?GM~)(0ko_fKitTz#jwWuU+nl;m2m0@f*W
zn`<Hzxr!gKPLZ3Q0PB#qZE9+iw~ZHpPI0RU1M3vGZJw!7<|@p<I{M+@j(yuEnz=s|
zU|=1w$U(#Cydf*dz&dWoO}7Q4vknr+UOa=Fw1mux9Te^)ifP3fSf`j~tbvU?TfDjr
z%HXD3z@Q9PB!LaeV1*Lcpa{mPo}`=$ffF_;f)Pz%gF?9JIx#4NThp00D1{YyU?Zil
z0uMF;?~QkiQTW!*`7(GDZn_!_h+YK^*x+SYaRW9ec^eY4+sI39liEKhQk&HNL6O>u
z`ld*2<uJvIF2W3KK%h1mg9im_(*<IvV(Pg-WI*PNbc=<~<-~OXx%Gp<&QtCp(%|*!
z3<y<}J+wiIYEtkAB`SjkY;0L+u8Hb$YLeb#Vr(OjX_I;q*fAxgxjN?6RG|enC_GID
z+d=VZ`rrq|r|C{G0ICWax_4|7lg>Y~=lo}`s15#{LerF3(k7*5gbP?+x?U}5=#wH-
zF#|R!GA+;2D`~lhO^W-Z%rq(P6HnpGpA?za(S-J|&;y$kp(ee4QihuJ`Ux4T=mX<D
zchk_u`;*c>^U7*c*(U|6;tOn2pxRN{r)8USGEPGJ`lO6CLlbkT8r#yN5VZW}C*-Rl
z4s24sD(Ju_Wvqe@Y&OkQ#{EedYZcAtSz7$0d}S1ZO<rHE5S?I?B3F?KHYs&Y+Wv&p
zHR%PDQa6JWF3_+)sM*696ckRFLf53)BOyePXd;*?c@=+PlY&<f2sSBr8G>Mwa<{HC
zLkeC5A#6fSMnMQRDR~uzV3VS^9{c~K?5(o@Pm12kTfy{f;Y^v7yof`%Y*P4E8UH7*
zzlu#T)JzHzSHL;lDgVu+_*H;{P2Oy)RQ^euvf>NO?`%@pc1l*o7noDBBEVo1@}sQs
z1~`Oh6_{$1@}1YN!6-+o90E=`s?Y>;iqVRMc82^hLBUcv<tXD5%qd5!Tml}=##|BR
zv^iG@cBh=Jx;8j(s#V&*^QM{s2N!5PDL9s#a<$r{E4(OP37jIdo(q6CF0W1uZ{$-K
z09XBRxdR+hv?_SmfI<lxMx<4_>f+#(wUtfGuE@gRDQc^367cE-2_4g_tndbNUQFw;
z{KFfSG%V-j__F*vC2j;Un5VR548s+aT-_plADN|s#1)~qEi(K&#cer;e}}v+x&b(E
ztA!8cek-#4J1xp6IB+E`=d17tbNqy((|%kW&3uVPvfpVvX4J!`U=mXH7bJC&UcV@*
zi*);S(_UXD+Td8q{i2j+Fodm=Ee=E>U4}&9qMf)%vtJa{iiWU7L9KWQTM*P455c~2
ze=;D#7Vo->h_FSIbCD-tQKA<iv23MCFS-FNigZOr7!Zmtl5PNtBAhu2l7=bbTv(9L
zigU0<`CO#RFUsfe*<K)lb@>Yx#WO-6Y^8uM@)j%#=wiA`EQ;tNcfq2BF1iyeN@#^j
z*n)&kSM~)G_6qz3tMgsSU$8nREL_N<$WC8+_C%SjkO^Cqy+s=TqVQF?gDr^K3~snU
z0$1`GEXvw~OTeO_ExH6O3fgkhSixR67A5U1hryz#Rg{DUsyPUN<k_O6y`dj0%2`E8
z*rJ$an1n6bqEW!-N?OcTp%a^uY~H$fEM9VNS{ZhEQm`qsbh~+nRro`@A!~2?4BAam
zs{n|0Q`FuQ>(nwMX;5;hHU(@=G{Mr)SQN9s+FVJ?SD;9WcB9F`X-mFw9cedB$&918
zf`+LL{3Lhf-8DMyyb7*pH!rw1uO3&sDX|qy(QaN}?<N)-dE&iclfaZPVC|;pz3C5V
zH$`v6O|%<g_cpOfse9X5B+A{J_ltH@?%pO2D0^=c>nVDfX(=h#n1&{{WfcRI&NnU?
z?WT0bs$NOU_g^(UZ^w7lWNB|!%tb>Y<QGYJp>|WOGw@<ldbT+cifjc{Y!X=4Wue`a
z**84{?WW9T@I|{JvF}@pNr`<cr(e4%wiSfYZi?;u788`(3e9Nu`dA3dh=oeMV3RO>
znyEK|!>3?hh{|X{SS^KRv>U$3wRo3kab&#+xFYQKp2JemMMGTILd-=g`ERaODPW8q
zgN791OTiQkFsiktIxXOBCJLq{glZ|=q5(m*))cGx_SfRwp+PdN#jC^BAU>7?Ga53h
zFU4iFOurtKj<(|&4sKU8IkI7n^cyrt+_kzMY2XgJe+#+2mV5>cagJ*>F_IE>Q*a^x
zF|{c;w*Z*hlyr1%is318)3Ltv7c^)to5E%2xxhw{NQ0uZ7-P{8S-KQs(E=K^R#mqH
zQ_yE#;1S*=J~Xl5+1fuZnxA9LqWL)nEt;Rlpj6=-$}7AmXyuySV!^RyjHPG=R^GL4
z4ZL!n-x_yeqw@~XpvJEVr)W_0mn%z9dtC&UQ`c{}DJ-X|-*BB+Li07`6<SW6y;WEo
zmrKOv^<@c^w+V))*iSCtrhr*ogRbSY;y2utUX*C<f9ab90BSij`UdpVLSE9nAAo*Z
z3b1GZKP^RAw8TFxpBl7chWse62B_0wI7I`{X(^<l1<YwFo}vNev?&}2S+SPTeXX`=
z;oGkbGwPaS!<0J5ZD3z9j++$x>$9y5{C5qLQgV6MP#qI$I*xJaU*0%Yj~O-1uwzE4
zy*F4FmN$(ISk&^Sq4RuM3b|;Bidt@(<iOrA4m>bPS?U||J1nnyY6f@I$Q$xQEQLxm
z*k~3)B^v4y?KW9)j7&Yd0pzs2sNdYw%ZvJTzQ=-&^Uquah&7iy2H+_uH-EF4S1qVb
zh!5UVC2w|P+4OM(eY8|hyjh7BzSOi8UP0m`kXj6QXla^Usu<p2zFbpZF0e_P0({LT
z)qINmCN^?SXTOj~lNR|+iB)6a@GD3;0cqG~(c;LduB|!QYpQfhrNx`&4R8eruLWLc
zu}XMDHlQWUTmyb+MTA2GbZ9BU;c76OFNHWX*wxqUT2~07*)@F#BEjXNqgdFkp*t2f
zSsPf?rl~_v&8Cq@Ub&ZQh_^r=Ey3*?kVPxPBpMtPYf3>*C&rpGpEY2Lmf|EDoF7Y3
z5e)_Rmf|9sIoLI{;<~(qpWCGP8W|<A2|bz|1@cWn5)H1PHLLCb1|c`46$5d!gq~~Z
zPg=8RXvjFkQd~jF%~v!!q~0tV9g<H)$6LFjg)g*0yIqWvXaEsy0(wObucfl&4Suzy
zP>Gg#zgBvHE>MDB#YQw#m0W{rFA7gCRU>bxPPqW7yIRWzM}g#1q(lRRXem-+Q)1f=
z*SM%+w^)_DCCq3EUDx0ST?mwDKp3sz8XAIdIBh5m0HZZrV;g2DS&j0ZO9;Kz8u*)M
zsUX`1Ro|AW=r-Xzl?+Ppg&TT}!KH#^8`6A{7jF%o6oD*SLz*v;MQd~o+;OWIT|?&|
z*XSA=q7CKBTY`_4V0H~|`%Qsu0IvN_;n*Xm*fjLSgrrg<ci{r&?n+WJBV8D9p(V6j
zOSI4?;5Y$RXj6j0D@ggKs4pW0&{A>ooPc!Ww!ll(Fh~HqM%6$e-A2_qEUa(kC}|&B
zs!zTtIiXZbJH+20a(+`{HZ+wtz+V>2mp4FU76Edv=>ZzFhNNgBgO)&T4Y;5+Xe4id
z{=6t?h0@TMIDz!*Qk#)vbg4Rd1EOeCa8_ip((H&sTeLVVE@XY76(4k$mJLMFN=(R=
zl$c$YmYsN_)um(uEVR0#6(53-aE)n(Hi><tjM@}-(xXMLAv0Cdd{dIw^C_cZ`07I=
zL1=br&^<+Fmjc}(GP^QrHXw$Us+zYBx!I*c14gvE)aXDFtu7_H4^EO=G$2H)cMT5F
zs#50-0HP%nT}uej>dFz+02o@mX{?#Eq7IFvUMhy(kdAl(Qn%Z&zoZ`n-nhCHWK^tQ
zEOp+10$QEs?}n=P*Curkf>{&y5S-n#auA%|G&BU~DR$nl@0Vb6?e$%(E+re^&FWCH
z@nx+}oA;)~1Znc#gn>u!^$!TiE+u+ENOpeRWAh-hb{i0Z{T3q-fhbbmfXH1!z%`(K
zRtF0HY6<pP{T3q-fQ>fo2B^<!OY?^aRFU#F5UsQXiEB89SEK3;VDoBAW4-Qv%{310
ze$CGuarqNIt_=t~RVr@)^en;JT1cba4o<Eh#Bw(ots&Gl1<XOVsW5p1;CuyutqsIr
zuO^H2fNX0+%t5v_nX5<2wkCu1$m8HztY6*+q@AE^o02mcXvNpvWULN|&~8)5g-)?l
z^Sl8Lw3-anNEWo3)NLdST21b$2I$XfQn;Z`Z3;Vr{A)5>LoItz(At|_<;@!cB^GgL
z4I#0sNhL?b#cHxwBP`=uO<H=Qh*p!54iM3bBIphHp(P+&1A1tMl6QfU^OKrB^9hcM
z>!NC>Hz?3cu(mb<Wm!!cISNs1O3rZReNmOsHz8S-zC9r^+c8j2h|DJY^u&d+Q73=h
zM^=+Qj{C||ar8Eg+f)iUa6+5Hp&>P!%+iSxS|$x0AfaoMFfuHmDx%(yh-d*6*8mS%
zCM`V>Ld%pcsNt@+OiFqTOKlvN$0dMV!v%90)Nxd0S>~sMJg-zVy#enN6s$f(rpZ!0
zdDXOujzeOa4AlVtER&%c*q<d-Tm$xJnPBY=7xiV**YhsFOzJwy;4Fik8ijI}YN%f=
z<MI|Ec5TMp61C79fI3T<xCU#+GFqwA-0^yQO>98+snB_Y-DC;x)_~*L6n2b&$W6+g
z{f@t51%TmMCKI*a*aT9`!=AJ3+{hhwMx(|JqtG&0s520BnN)D3<ygeJy$*F$f?6tV
zzA3p`*osAzl^TY#WwKH;6Uk!H@|F>{OQ^G!VYr)uR<4=M)TnQ@>^}2@oHLoJy+w<o
zLe7~qaG-Er6twbysZzMpAi1jaZ5S<A)z^qX=cV%H4YAPIB2ujRh`;j*2)HU;8HU<T
zA!m?rRXKbb?7gcxTEUsVJ|y5-l{RVEkXMy{?I>uzsuXO%a#od+9mt%e3g->DoF$A|
z0|sZ+!Q&keoK>Y!Cje&?I1p}ts*BzL!C8QqT}hhx6o+z5N*c98E><eki0xmhgMPIr
zj<<v)Ybc+$s;truNmyl-1}0}!>C+3fTUVt<ogkg1Qs@o-j|H$<gM(zZF*Lj=o5Hgg
zu9i*0*lRx`l^d>_#fs?-@SIhpawj_H3KD-Z@C*kon2$7UxRh4a$GuWoRz;~dr0&`z
z4h3;pp=85XwNxU#Ez1^`1YYe`W!MJxW>p!sQH63<8MaZWa#h&16P~lGs;)M`a~9!g
z4d9$rW!eTdXVqInH_RsuXjhU3e#CBaLOLe^o>@g&c4B9iU}$Xt@U)67-ayW*LbW^m
zp-a`x8$70~NT-HZbyH~YhVONg*e@hop~ZXUr@9H8HzXShoL@=GIY>EQDcg#S-pJ{<
z3RQ8W{aY%5ezovYuRxo%#Jnt4GH*b<tRnpxfR`5qtytJ1eYwLQzY0y<9ZvftAXtZI
ze-&!bJrXePHf$>$Wp!U9{5e;V7Vb^SMWo8zZ%DerPq*J03AIYoz_5juhE{TK>NQ(4
z2TdUtrOEpZsOJ)HtKWtJD<4P!SE?9*fGbrDK*$x@sXO2%i?zvvl6+Aw?)OW`m7;+m
z<VxYdK)$R}G&ICsDH<B~Pt_~$iGf+de05-3u2pXK4C7|G)p1+^RnWWx)w2Zd>i38i
zH17_q(7KoShbX)kM}Z`~mqvjg1d8kGS+#q&HA<cp_Y(IIhWFC4;j(wThDPbSB?wm!
z$jfez#-GH_yHhRhfV-^QH8h0dEh}{g*k#?Wu~RzUyi0drUDiD{vSX5y>6|-wUn*_h
zF~23eSC2JW_fR(weK*zMs{<joNgY2)j;RNCAng{hT^+ENn`Y}?0RLS#?be;ZmYZhl
zO^LUE(`?<56KLJ3QTLL+2a>oG{Bn1Wn?{*U;J_v3*EA|_fGT5tbs!g)fMJ~omD|J`
zq}WZ9b$@-y>oz?>DRuyRK!m>&>b*(1F^$YYWT_~5&(mQEwbhAhxvP#q0$c8?v05%}
z)kqLpcjZV8OA9G`1u3Ug@q?UB(a1eooE&a*chMMd;xD1OIsq&!Q67|Betpo1V7c$d
zGr7HPs;M2>eO{z!%@1EoT%}g&Do@^lcXr{fdO@_~CUMjhW}CusLzry>jz#2{cl4TH
znlC5XqysABgl2UhWj28$?~mG-YuL1q;dCGh#s$slfVlXY;%k8os?WXNV1?@Qro_qM
zix%olN?u^0?xCFcqB_0XBNmSObcaUc%u$%6<d+8O4%Nul(BPpx`RW=vw}hvPv$qz|
zF}}J+FPNu<G{7+~z*eu>;=q+Jv2jKfGmr#MwKFLB3rp6Tcr~!5^wk}~7%m`IM}>$@
z!6AbZ5}T6!w)i*sM7f_$BC`#9&@^%iNEcMAL+AHZHE_)A@>Ml(!^^K2xZ~AV4c@T{
ztH$nl^OaFG9W^_A6%9V{*%Wm&z%rEK9(S=<8wp#kpd>f9_?zJ827eRWQ1k78y7;=;
zZR8*DMJsg&)Wv;?xfEIMODmIN%~iF$XWf-6NH|+?)!h^ho*$n3;^6sZZURS-kJnw*
zpE}~RT(!+RipjVTVVja1O56hSvMD?tET+6EU=VhLO#y?jD{M+Kh%`M;{MHqu*nB?Y
z2m9BwTX&TEai`t7qa={~(5PF!dFBMZK*$B>y?IlT`4O#@3GQ9P)SOAzD2N_%6*ccb
z&A97}Mg*k0bY_5JTqvxb8F()DCSDA@&?ensqk2)$3SOi{!^GvzfQk+?n7e71hGjJ|
z*RZOlfwNZ*ifqmvHOxDZG%mze2a?8}>NtQj?$XB-N8?_JZtH-~xJsXQKxbSqt`75}
zyOis!0TvW>G^0t@Ap`}|+LYwCsM`sCZ_NNnE8VGnTgpI}_6<v{yTmoDweHft4Pwxh
zQ1d^1{D*6A+WYnB>u0m}*RwC7bx&{hx(ofsfB*5{KFY`a`fvX4fBD-5XqW>K_O}l#
zh|koE6He!ZQ(>36N^pDXtCvseU-*7qIG%Om86G{zb?M5{1R3B5#<8;izuLSwLI^vH
z1E)6dYV%YtP<31>Ys!s4W0zCDWc7sCBp51QZk*8a^Ogv~2tuxN!L8zQ)fz3hCb`mb
zl&o9g%8F4?W5pZp`USvak311qP_S22ld+Wj0L;XNib7Mh@S4)c<*O*Qz2?Vg`BL+o
zaN`xGPzo3;!1G8|9CzW#XG)e>fXs7MODjAIDiyhcZ%nbTh5J0k*RE?19F{ZavjF?#
zio+~$8+oN%EpUlBY&wM)8ZQfkeUJ07V-#cs@xm)n0er({3n+k9ct&)+*aDit3qR3<
zm+!il7P#bHH_DQpaK8npFW70W8Xg6%VOM-e$)pReAdUhbso#WTm&{FYeN06o6jl&f
zybG4OTfCnY*3nozstf!^b14v|%<*c%a!`PeoXVbBPzPZ$1!}>GH6_xD<Ek^A*RO(1
zoKvTFL1gLlqTgg$7N=*d0QG%MWymfIwM%BYjtX?KDd=NasMDxS%mqokqwsyq5MdPW
zrQ@?IeD29d)pe%He$-3{JOs7K--?%?!r{objU2*rsIU;~^QhGI^{6+EhhRc_mW9r(
zf)dF=$?7;gio6s=lFhDiEiha@EB2zuOVcc?MIBnCHLoaV*-oX5nwP(4k=Cq(3P#}*
znN6h{jP(gs?7)!SdYVcVWYNhfKV3!j%U!Y(6Gn24DKAt_XXrf140a*Ic+-!ng{b%<
zuSyi_yR-Tpe}hV4H46JQ_*SND?-fvsM^U*RC8Zt}-%zu#Xp%rJ&2kE$bW|&P6d*&D
zJRLC=Im)JNh84gQ)TWA#5*#;+a@dc28}nBE2w)$cm61?B3{iGbZz&btskpQ#>C>{T
z4i*`(+)e4x&KflQJ&;UesbIuRi7}Q6C!xX#_5%X=pLIx1xsT3b9;p*NOLJsB8AV&X
z)uG67a32|n7r1_}x<bx$2wz_jN;`DMJQMXJ+M?q2zti6{gLi&J<77L9l_m1ZgQD#2
zF>@qYzcR}@x;bgf`OrxXj<D!w_H8DME=<0s`_&_-G++5M>9dkIBcx9%KJp+(Uy(%R
znMxQD$j@ZI811CYJ*jRxGrOF8vrGt^Y*$9wo;5P&5ufo3LsHO*bd$y;jVE&_gPKoD
zOok)^achPoRjhXQBNH_)<Zfgdyvk&f3Vm+OC3?~cc4kdGSwI@|i3kK}jS<6LS#Ubz
zcOS{*7#-Vno3JcQ{}D;hn1-$^=U6h)nKyw7pml~awxOh>g9&>c`K%aFk3!aw@F|vo
z2$smL)R8AC*L)ykn=lX?jD0q3qsc@dhPe63Fkj?ajch@T#We+uPe!z=qODCPD3m^E
z^O3wH(k(EJd>qi`%n4AH2<WwQGaW`Qv@;J))qZt^(7mOIU?T66w_zc~`jPUWGF<&+
z5>SrGa0;CmdL_(XOtB~@$Rl1{hyb{#u87QLd}$^(kOBP>zWj_QMj)$jQ{j=gGUOH%
zH~|=_N+bIc=<X4-32!{o%dd6Z(x_><WJo)ahkS($`(q8H28*MD?XI^Vw-Z{%Kr%);
z0rRH|{xgD#09-{boiL<~Cz_1=$uN)n6Ch9%*q%q!%Of5oBQs7Y$%*G6pu7M8FVF9Z
zQ^<^D4GBe8<iLI6@QV=hGokM!AddK8(mR6|htMp5xUMd5abR>;m;1KEQ`Ut>#NSp|
z<*$I%CPEfS!ve_ifwJNmLC%5fUrJwi1pqT)kX$K5Q>><GB4A{L0)c!gMBWYI?9wUP
zG}eTd(G(bhyyH)_7yM@gUBPa$Oet-fTLOWE>Jk1%*qKCx$cK(%SF6fZoq?y<8{VS`
z`#>+h31PtBGy(zWRZs2pT17tf@S_SNo)P9tXG%wn!lfdt9km$Y2~L+G!pBrRwBG}s
z$n@DcJZ17T-0-&FGWBm)*>>=RAr948m+C$qpV2K}%z)upwp}?*q}m=2hrETgz%))#
zFH64ccSz6#D|a|E0TpuTea9l~zcJJD{`|0pe#mBdh56ARc0qzs!a5h$F7C=ScD4Tc
zP5XHL<8|nl@%qP0>0P7z%+|I4|IOBwOG#@Njkw3$^&wN&wsheueVDq+XH!=$;KS6F
zo91Eaf@v%AW^Gd!tYyd4g&!PS7fd#?b>S?4sq4k<qI>0O>cah5rY_oo{>akhj1ahv
zp^FoI7`k9_k)bOFd04q<(?YFh7dV?{E?n9lb}sx~cCNg>l<oE*(Dr&WbAbn$xnwYr
zor`wzW9MogGI3pD<BBn8;WBC;vT(_0Aqy8T6vx7)yY{hhHJGbt;j)jXb&FaD>|0^)
zf+4M?qelA8)5-+{kgQyJvK|{(%uNO^8cJy2Dil)3zI7~Kuy0XH9rIS6>(|r1bu3=6
zZ|T*^zQx-T>|0^+g2(&Vw|HGj`xe!VW8c!weAu^W0~_09#`9eUE+s!W1}@%0j)jZ1
zl81$haEN2!YBGb-!lg;l!lgON!ljBS$HGPXnoL}Ji!yQ1*LqA`MrYPBa#81ikxTU)
zj*)Bq#>l0x>0{(lJ!KiWWE7H-O9cpN<YEBbt0P#sblW;sF4=`-<x(9<TDfEwI+iZg
zN0g<jeztV=TV^W@yB9i<rAu{{j-^X>jIeaE?6M49njsBcjpoaTp-aUBY3Pz=Plm3j
zqbDQRF?+$tWnxT5uKL-?WvEFk6IU9%Xx^Ims|;NIHwG@%kcNRP%D&RLRW&ghx2iB(
z$GGLcF>Y~}9^;l~C*zj=#<;~>xr|#yWn5+4Iwi_!+?qULj&Vz~lyOUC?Pc7GdCn{Z
zjh%l?TPo@()0XNUhiOX{O=;PZ^;ecH!R?P_OK%UBtw&8-TDH<aMXT1S&sf6k^C)^M
zvzFeU%vz^#C(K%plA1{QJ*Kj&%dAC9gRELg6$q=AifyTMpdo3eY+9$(AZ%KbZ;&>v
zDNU8d+$NLe9*dTrnuBT3+V>$6XwNFjV6D1d?Nq^$O-nJP$EI}(e8{GCN}!}oE3HlH
zY(A||vT4csM2pstiOuS<M#-vm<=9xFW7bmY&12V+agdg+p2n%9Us)p}-;S(WiawQ9
zOA((BtJblGP1-cN@&F&JRwU<?MeCTMXwZ5jh|kr$p6S?W&{8(#W6;WHWX+PfM#iiY
zt#qte2ogHhtdq$4n6tFnvS;mY{CZfkw5w#zI%$My&U)nIr8O&^lGoFkrBt-Xm?fj%
zL^@Zj#j$1GjE6i1ErP_;o>f#DNcOCvni@WjSqeEn9`>x0JMxxkikS>)&mxo-=B%_#
zh3fGzY2C^fN{g0q?L9173Q~YYD=bq)=+mO5#8Jc|FWvWH&|2#xHVlNVAZyn#XEEwR
z_AEs*$eyL}0ok(@S;v&5kIYcCXQ@=R>{*JumO)EFl(1)AGEF@UTCzdVpmp-!(4aL>
z&ZyL1uWh4x8njMc7Fx7UdK6l<l!`!hEv4U;U2B}oI<RZ;<T_@p{@JW$N|7VGR#ip`
zra^eOY<10%maWcD=UBE*sC}BT>^EjC#b~F^s=e8(a1p#77OO{;E-hAysFT4;D<^|h
zQI08Dtd2Pf!EV&hV6qBp6oVXTvFb8#%4DT5T$!w7cLOeFnW9c<#;Qxf(c6qw6-_NO
z)`^dz8A}N}WX4jWjbp~rddiHYXjPiA<g%0*OJSMEjHT2iGG!_H36?BbkYvdc>R6Vn
z`!|-XTOdAIvZl;mv}Fl6E?ZV(wh-dJ1?ZAJi<&C!S-uoXAbXbUH%{oS(73W^0g^6j
z7LPhvvjo_dHLD2XPivO)**&dUKr<d=)<OTJF{@LReWLJ)1WSV!v17-em48oz)@$uv
zKl*s>?6F~6uYdGbHkjkr3|g=ZF;|zv=pp2V!*UQsGd)dTxN4$Ks4I&XHo8wPdg9=M
zkmm-Vay}XC=&9vC3~Kq+df4`1&3pW{f<4L*uV7Dga$cX7tEMKd;I4|Az@d1g^7@VO
z4koZE2qxZzGusz(&TTYXe!G#B&gJ~Xm+Z>y<w#oT%IxL&d#pzXe_d#~WRKtdyFIZ3
z2Pnaj3Hn^=ypY1rC$&HaMp4<iP#V}LL6|VGx^i{BTP>5YKY~eDKD3fes4#Ped2<sA
zy9l<nGUkD-pNMC02S2>D|HdLpfUm1?B{0A)QJ5%Um+uB&o==!JGtp$U;WvP#*>yMh
zt=$zyMb@eWn)-o3yvf(rlVPp#!An)5v3DB-05?DIVJ)EM$0A;MMeF1DOuqTeyTtl}
zO;9Pb77S|xwWe3dbXUTxm4~IP)HvjTD_a&I@UB|p3vfPHvMeMx^^uzR0=E7bqFXfb
zJpx+hQJ``m?#xx65~eFxaZ1Dj_~4}?<&qO;^?`tb7h#`{u<W_&O$zUcr&GOgUB?#8
zqz4g-B#}O7Jwpy!AH2gXAnRq}g46V%NO9B;W$#F{fU5{4;yS_@-(j84g{L_JS$H4j
z`boz4!9o1`pc7?zZZ7ILE6-Dxrx9ZAMTo_6yf``le&Z2Xuy(V=WS9tjP}Z!KRuLck
zOc!wU15d}1p<0p!wpwQ?$xR53h1%Mb<e4|m-|<QSj++M28{%aM`FIy@D*^bRhq!Lf
zo09M7R<HSr_#qd-o?et>3_?b!w#p5c#nSYEZzXoGAcAWXkYK*t5KX8fSzuG$ZF);A
zS}@%L^SS*k90i4mT%O=f+PtIA<nQ@tAfP%0YJuI$yMhomDL$UgkAG8kw^Ks{cHbu_
z2#rcMhi!j|=5Y?i+YwfAQ{q*q2IZ!tGe{1k%p~H<zExnib7tS#h7inXXhuNZEBRKr
zkx9g5|0tnZK2g~ad`!Mo5Eto6zEuFt^{%A01;Lb07uRomUXXrWMtI;l9CZw@B*lB9
z{jA*ZrXu}TLC~o8rhY?Cc7nNYBxG_`t}HNw%G*|;S9>>2DJ3Jaag}n1CoU}++c%f5
zj8RJkvAK>cS|utoxb9~K#T%a9yqj!gGo_viP!^aVo<Mhmly$-=HzhZl#B;$l!qG_$
ze<8<!c<ed{3gqL%r^uKyRiZ2~kGOJbZOUd=DYZ5sm{pa@0%PRmN~yI;!EKXU2w~yQ
zBwM94c{3pek<W0S3ozYm(!{T0Z>Wr90Y1P5!zd_m;%ep1rRjTxZQWTzvV>#r=|qJ*
ze51tvZzwBU%7_MEHR8+~(HI5jC~x|n3&f$oAtgbs>8k}JDG-|g_AuUVO8x)>u?-Ck
ziP%(MHhjP_zvBW96u$~f7TjN5btN|?C)nkTPO+(cTm_jGTy-T&f#8%Kvmix-3;Vn&
zVNP<og-U_=JU;2NFb9PZl!YlYjUGa_wX^FN=Free{!Kd{a<=i#zg^$)#Vd=~rtDk>
zt}I>!Hpi!X9GAK`N^aqBGS~g<`v14~HNCd%Hg@y+6?bS4oRlO=6sG~w0g^$`i8Bf^
zNzff2=pLklM*e=b$hB70vEMs>eH|OHuXuKqK1vcvX>n0Eh)DT#M64E$o$30tL+_ey
z8NuhVO$-JNr|;XUrO>lRGrm<Ct1aA6>(H~h$M5hgl!LM%XVw;}S3_d0Z3@rmBd`DQ
z`8s?+6OG>yRqGKm(g#2Yx2h?{EB>wqoVZ{GpXmh>mq*k(bgwwQ8rWbqDZP#$zm6!q
zjwH`<j!02D)g__n+Zm@J+W~wxo9N9%I3yTh%ib!IoHynHs#a%S4eUFcNiG|1LpM`g
zUMZT1lfWj5#Bp0hU#&y2D!=7HR}?hDH93gsV8Y8*R7G2{01a$LTclkLIq^0~yBdz^
z_mF$ukX&z*wX0?Ry;CHt1ODbvEDW$>M^ZIkN0jq)OjQld`k+C2X;$%n9YMuBX?N+t
z56Q@>`iQT{sVrfX#*OZ16Tzj@uH2UwL^B1bV?ZP81hN5tLYNBTzz2`8+Q7N&9yA+@
zcxx*)W&=6b9@;}d;I)+-^GF!=#qDcAX%EGljh^@z)(pkXyqFD{F1PYxwn4ouR1F;4
zAseKgeutKIbg`@2QtYEKP;Nl64*@O)ZW%`-dME$Q7eH;lusp_w-Gcipz<t=T(&Iy0
z#DE@GT*^TN<qWR#zYC)LfJ#f*aIf{o4Xuom!-O5sx=1Z~%B6FaS+Z5M-tJt-pwxQ<
zk5YYpDOWRS4PZSV0VX)s{E^_Ta7(*DQ?+qy=9|1yk|W=>t`YvTm2tAwu5|>Q_kfXg
z-i}-iWQDtPVPo?Hate~_<U(m?<RI4?UD!Ug;Gkgp1Mz}_?ON4#D+Cb}zY-E(M}ifH
z8`-TG#hh7P%iN%DyOz2^-JZ?AKwtF$Ll~iOJI@FjNGwxw^EWdCAu%f|zw=eGktu+B
z6%E*t^m?ZA7uD{em%@$h<3h2TDaHS>4|dmTh5fL*q7!lJvW3cTMkls+jTf|Q=S%YI
z%L+jD>?5gd0{OLpdAlI$^9u?NvE*H+39!X>m#F~O)guAP+!0j|we)Q!lnz@KK+Z?v
zj3ymG+dcR@bnpo{t?p@OFaQA`gdSAyO9C(V!PYc`Hf}N=U?Lw0T9eAS$#j5~y%p_n
z9Z^p5rv1g><~ErR$QZv{XcT}{Y&0m0A?GhtVQK6pzXk5dk?>1HV>gznLrP?OMAaku
zEw(E-S3QEhZaQcHK4B|6=G8!7yp<iZf!=sG`6}g{y&#bA-*(f^R6gES(ZInU<&<gK
zn+$hEjeFC<QdTFqHO>0)*Fjf4c*~h+OTs6iwwpGi3AHUcw1(KAloSdRXUqapwZigm
zCB<xTv$t|$Hn`%uDKG8;d*&Q&+FmBklbg1e3B3zIDCk*4fOaIc-H-*X&4Jd*jF_c{
zo2-Zl*EyNe8ZLr&6U%o3Pjgtb#Y}k1NM_lJ(R_>Xtby}<D@WyZ(5m%8hz@Evn>iAO
zdBb6D(Ek(I=BC|Zf~szd_N*b^Vk^^So9hcG7Cy5uYYm51yWK>5H=Jy3#c?*Ae(lB+
z$~qt0O|%05LVhG!0?EO?bwUYjO~P?eGgSVqgNvCeU)e2Bxp1{gn%!pU?>kV)hQ31B
zp}KGG3Y7$4--6*zy2iJ*i3!bpYoEZG=f1U1;7s%d9?nzKQwD<W2nrWW>jUSvTVS$=
z5Sp#blx;P^kF$hxlUt_<3#2QVlk${KrCOy3*4|1;c_g_I?x`_baB6SfG&H1>*aFS8
z$~duanG6U3`bbc!jpvrlfW#JGxdEzoI#F07ON{x4GQJhY)o?$sZ{8p`+#qa$caDUV
z1NBW;>0<_-T`4IbH!O<<r28$);)UYII6)o1aNWi}4iu|5GA&lo9I&@gykCe9sx!}d
z0xoy9@>w?A|7^V^yCTzKk*9&C#adiS58NDTS7?HUEH7JOb`959`({W^Tb?BzDBv3G
zD@#K)Uk8#4I`-B^uyAl(mnBz8vIn}W0GP!Um(y^A=b>XvT=F>~tXGN({;u61bL)6$
zH^5b*2M;lE+2|oRWZ@>(L%ztWKYDBpaX#;{)$yw0h1Flxh|5K<)+z~+hxQ2MDRO~s
zTO~6}2~qxllg49DAO(^K?TJI}kVVD`+~}t43E<#e`7y5}N)WLUWHtvF{}p0TFm~~_
z9YOVzC!dbMb{BP9!wt17__E;++e5pQSBVvOL^{l;k3GA@dyH4C18YH`z$^NpqeC<l
zK79mwJY*@<^}UDgC_u>LAZ2U740veIal48{1dT2A?Mk1SVHeqyC+q?-3tuF;m%51D
zjwq)C!%vT(rUSMhum`!g+!|saJd{<t0af8jx>=Mauq2S5?HvLF$b0~s(0s9F{dq&R
ztO}lAg4dPc32^1tJd*knw+>SQ5Obx}Yyh*kGHN!UVLU|B16Bej#;Zix;VtX`6|nL=
zHs1j(z@j;6)vhDS7K&HxNV0*6LvQ;=?1~on&dtdMrEL3V3=EGOfDv*f(0n3iSgNK!
zaWoltkaXi$6|0>(d_W>ZC*RtMyvb(Bdfy#!H)1zEqKq>Tr5fUOQo<J_)a4bxGd?9*
z?i+E1zI7OgP-Pc|S_5C%k?^$x?Im^5wra1E*8WnU5Mpe;NUC+F7uQQjo&&No7wK99
zWXO}(p%oy=w+NGf2y(?+Hv|+ods?FUKu^RH;$o6i?Uc?-b+QK>o0C$l717<563ou+
zSz@J*R!VgvH>!((;uR%@V?5A+yyK>z{E!0kl&j&oZrsp(yK%}V0LhgEvjKwSTgn_5
zBp2~TLmaAa-7s!Yfcn<5tySd;QfE|`ZyNSktFI`p3ZM5a&eS8RPU_S!pywFxegxSk
z*V0cK$5W=;5BSm%F`f*1&gJ$4g5*NewWt#7MVPe<xZFTr=}!HcyQ#bMD;O}{rC$}c
z=9*rh(tJm<K^wW2bEQsp*C`>GV;o`q*Ae7uaa|k&pyWj7H9(Y(fV@$b;c{OB=&lq^
z2=W8HBI-&NiLUMlDr80Xfrz^C)LIuL*?3dqp^6-;G$z_ERT>j*H>v2DXuZt$SQXlb
zdSAhQ7__n?T<E@5mc~^PHs}%JsD$ThWwN}PvK%vRpj03Ixf0Ce;_fouk$&7o*_UC5
zc!)3EUxE-Bk47Y5gYoA={x#T#F63W>5$P`1zBqinEURi86eH1p4ZLXXTJnm3<ZGex
z9HDeK(ml9RYWA|pop8VoJKmRq{3?CDFWTW9DeisY=($2IZ#*@B{Br0e;t9V<a%^F1
zXD}wT;i`&D6)r^=0-p4hwX9mZ*?b1BE-wBj=(9@W3I9B$nre#<dIx*dk&wRW9%!gy
z)<ClDj6OJmz*FGVy31Dd#0j3#xxIGb1UqowE}-BqMWU9zd`o7QD&1v=-|b65op8-P
znLGMjN^;HTaeO)Y^!<jT_)8>jQ*T97=PM!>@sZ0kDHaEwn?pzF+>z8EdH$Od&(V0r
zFCyIWNEnBCLwPcYBPF>~l$x^_2I&Y`?-Q<@J8B0h{X2eli^z_ZL!XLLsV7j$m#E8%
zA^$4T&7ag~@91HmPhAy3RW1ccBC_096O~#8FDaNf1!C2!<~4YUi#G$EL5IK@UL~qN
zh{-L1POkWt4xrOVf>KRm#Su4ve~+lbKyfB`1guzr&X_~MLcK$u5eU1Uh+2T5d}?0-
z7V1bC>0E>4L>s20;i*|s)=<<!8}>Xwb>R(9xx%Gs`5#GsCBY4QLvE&bZ1x~YA$tYA
zEW}|4Xv!4})PZ@rTzJ6_^1EN+HuTqHIqt7GaGYX0A%wj_`3geVD_qotAUuL<;Zjx5
zoKwem9q1;XWeN1cE%~J0@4zj&l5BQdE;zGn_J(j#SI}h#aLIx5>j_(Oq5L{hu=v#K
zMwS+z&+2Zw;@nX!{KZ$~JM<)AejUNEF232`kR8{B_3Mc~@=5Ra9X|g&RKu@;dH|4o
zf)*0a;nafcr6s4<W53ZfMUms?%yCt5mB{NU%phFA`P72M1)bv^P?CZG9?8)guSowU
z-b;k;LuXDcP{5IVYJ~!lbh&7Fdts8^^qEkuQ`CXD9zDbYs0y0Ybh1w30oDU``l2Ej
zpb>bHa-Q#Fp;`vERom(#)GMKc9oNA}z&=8~T7d;l`E;l5-7ZM7Kc>|RNRr!D-B7Rs
z9CqApf1ys8S;X|h^|&(wXi9P_Fx_VdNXeD%v-iRSyNNsiASE|(gyO>AmGQF|Ccu^O
zvjaD9xl(?1fD7Kd4)9q8A?(P6=E4Vdq)WS80Kr~3B^N%h1E=(b8@1-@!x{lCYIG1f
zpc*dLzMg1~Q|1%(WwkBzdY+XAtY_1<fS6KehR+Uay(8c^fl382V6Vt$kXc-iRA(N3
zi`0w;$G!t^bOd-QFfvC{zo=wNu4J7Za3WW(&JH-yn>3?|L3ZdjdE)5?JH7+pa|D<#
z00FttlJCF?xq`}jB8l9T8n6Q|<VI5-DG%Lly|<Lyi@*b(CDLr3a-DA|&t@N%CA<>a
zZAg_O=c5aM*O3=8SwSuc0uOOi;3f)gcO=yi8RBDQ=^+-Wi6N|Aa*f>e5;P9yoFY5w
z11=%xNJ{mMMR)H=a#{?nIfTU?32TPWIJD-_1RqLE(t!#5h)~K+M3MY`6!|YJfu<Ac
z?nvr1?h8Y3^=7hr(0*g8d*vezktPE?bR-yhxQHSU==k=o9GV@|!v{U-BdL)UpH~O7
zx(}&dWQuiW+U&)`=}NTO0ZsMfD(K8b>rAtmqH1ne&7@bB`c6EM4=Hbh{;Nep3YqE>
zZofJpLf}${q!+m|G!-yHPTqtoMfKIBYe6u7BzQ5nV}^7sHk5~~CV4|#=(&zv$_1Z0
zl3E{cTIcLQ*Sa*2a(b6>T+pB+z&Zmo=tw5Yxu}G=>i`BF3GNQMk?Tg*F`z)+rGB9&
zoT)u~;e4E#JFk>fi=|u<OYdFEwUSV~vUhf9Eob)5PQF)H`pypR_t5*mhwL(^&9lU6
z;WJhym<ys}2$E_A8s|+Blv=6J*DtEt$vCHu(1s(bmeilw3V3=-w|OMh5^2z~i>@Rh
z;&+9n>hhb*xbiNq89*EdPg;jP1~#J$qM|T*h_>PRb)KO2MCN$s@p%U_=OaNW%^UAL
zQR{%^I8$<Vz;e73_|glO<6Q*Xuyv1wJK=2T;ZV&`U0rK9!*E<!x(?&r38lMIR2)uK
zap|oWWfPpUFOr)5QnVAqG;d;aT;%mzy#{|;m&KhPjg!zM%L~sKsn5wsb-!L*gC}zu
zK~f-<f+VS+f^-c>lD#1Atply&%F5X%^dgcxbU<}nu(v)B-<vRR9mpJSTF!77U0FIi
ze9C0EGXCZSPrdoBpc;jX>xg%A0ppG&d!$WZLJc;i^5`INbs^vS+*#sFp$ePUH~ejH
zTH_PUPH*ll=t6<qdO>zv2`@V04ZSUl9IhIhQ1u;$22O-q$EkvgnWpE#gA4H1aaiGv
zw`NygcNQ^SkW=N&3I=W3sL1PV#hdnkI)AxRgw`+kh0XM0D9a{Q4v>#G<BL;QHY4X^
z2hhixj?Vz}0Yw=kIdz-NY2bXkJ?g)JKHjAL0rc@k?Z3LX&oFd=`Z$hX&Z@>?TIK^l
z?NG5zCIAlUj)Zlk$M~X98#tt5{?88Njtd9Z7ZVmpnXk$*z<Qze+G9WC1k{_BK8{J>
zsR<?qls5L77|)wAksVBreoLD#=tkk%`YPQhSX;+2u;0AF?l>xb)53X{_zIk#-dpd0
zF1%%DFR(@UtrK%#as1|qc|mdf-uiBE{O<ZaoW5IW#5!>}x2t9-*jx5G4(&-{SCSPX
zN#l#Ei)o&(^GBVCfj_{>+0@C6dFw!IQNP|g5(5E_3mn&hz`2P$>BQT-nDk1WUSCDk
zA)rxu;caeWQ9AK9LdSLDZSE;uNW6{kah-UZTSkI|%kh?*?O;T#?6g-&s#o%=y;ZMd
z05}NeUTlEyDsd5UmLE9m{ML5h(9Oyk+6#qqYcn7W2OzobNTlt`8rq4%Vb;)249=~+
z02myl5$zz^I1-+-;NFh(g}CArkgmH`32!v?rE3TbXMwj2i@cU}!RR_JE?uvvFQ#KY
z@BsSFtN9Ls62Ik26otu~S`k|Oraun~6h~lxjy%*jngu0(%M3XH9%1S_=$Bjwy6(L0
zR9eyw#7?Fl?YMD%vpbd(yo8MFm8on+$c_Ow?DIr29SZZ-eP`+6i%d2}0p7Zka#8rU
zBU<+tQpw_ZU7`KOOEIsI^A8lzwL-~yaGSqE2X8<Dt$=5c7@#F|TL%W{NN_y{BFLp|
zQ6#uTwHx%1AtM6#g%=6t%^u3GKrXr!uq!H8-4a)L2W8q4*sTL4v|`C;1ypD$N$HVP
z|KyY;_+!OX%?&+-N3xMaX9*D3kqPEa+SxG=<fs(FXbB+KfiSvOXb%FsWs#t+7XoG}
zvuOuNW`(w(J<v<jvD+T#rFJE8i0a61Cj+Obs7|?hIf(M?03EGRVx~RN&nNAUp`YA@
z3YfG)en?@B&TtJBlg2Z2907RJkzmRLrnH2m>w9L279@C$R%pusOzF*tI<td1Bn03p
zC2*$!%gUTV`ICjtG=11ry=fZAa;BFOSM&{UdWB96k(YBRKWg9pg`3sUeBBfPzl2mp
z7etng(+S3Q%ntcB1!-D4)X6d;7Sd>3$pf3yL%6<PxVj^lC{Fx<_0--2>evlJt|iP~
z-;pJLtvVQ9#OrlbwS?E}7>Ko9HZt%-E3=t)jNMX3(+<?*5~tab<QNHlcO<n<2!D4(
zRX2SLW^d9#J!Zs8p8t;d0vg;4qFg;&djw!gYtt-An9|xZO8`?^Vtc$ga7ssnxdfQf
zkzk+!Q(9YlLM@|1!ON;ao5XxnDXH)E(DV*`ueYT7s9gdJ|5{sjh1eaAgzYi(^GS7O
z*-`BhVdyC7y^f^%Dbodr-?d@7h(%bJ0EK5-n<#**1JLwl8lLD>*IRN;ZQb$5$`U>^
zu(eBIzBgAfe^TvwxQn5zzeuW<TNs;cmVA?dHWn(cLkTaU@;VgtaycRiDtc2SchHs|
z31@dH<0TMY2k>YKhSvkvu1hey4m;yWIKS(a%lSxl$hmmO$8uR^99+fKoUMN{a3Lf6
zi@h0|*J(<Of+j7eC2<V^j~4PL4#1918I-YLMOuR74G<%}S)qH{5X+Yu)6p2EQi3VE
zoD2F$vNhr=29@LW&Z`C`=~%%epcW4;Ebk?x-hgcmlIkL*t}}oonB4$)=twYFm8^|j
zd}yr~8aw$3kxlDPHT5dhD2aUchE8(Y@JDi1kIRG~017Sds%D{G9q;{fI&H5KMjqbb
zmmgqeh;|sLpyf@&3XLTE+$dDg_0CQQmE;Xg+31j{lglSQ0#*&~a&O#}-|XKU252cI
z9vE=aUku@Q{hiY**vVV-E6~YX69L-HZ_O{Lvn1vl1sYmK%y&VO9bDu>254w4E@d*6
zucfqMzzi+8*H?+=7cz7Dx{gvgFVv8u!7Hz>w$hi^<EV=bT@h%5NFVywgFqj#GmgUb
zxK5S_fjvIdFhXz#N(FZ8s)gv=&RRy@;R?<<i1HDflRWM2O2Ag3pe`!MBgl3A=5i;2
zrsfW!P`A*TM>3OW5!0lRL{oeGz?t9%U~>Q$w1w9kzy*oF5iIf#f8!`v(3KR7n4&nI
zd{fPrR*Six*PKyHqGP;gWo|C+IRFyHRMyBmS&b=TZ=Agz3HDkX&&I?R?KN6yx<j7K
zwt><7#d$9_aIwdO);dKQV^y;A*EbzFFh(gtx9}eJskCOMvcsX|z<GAcIB`k|RmMBC
zfJFQ{9vlt)^-V<81E=n!>rWAR%mo}6IIaJPluNJ$`fN&!dSr_~n-Em@L=!anT}4!e
z`-c+Msn6(Qx_|Ork|X|=K>*z9lLvMKV5Jn{#BKntbYv)2M}%Y>fH0+~7Tvj{sWKS$
z1~5!1WAzPO>rWa=<usVmuw6MPWhIYJcKcWAgN`0AUTF`IJCx|=ud>H$@Id6`OsM{>
zfnxPVe3B#4ODRC-2HL&2fn1}LT>q7Mfvofk?!YL(QVK9P0a!XB6w{r{)C;WLFeBDf
z#|(2qDBpn_$P}@DP^+a34VdiQ)bLhngT=qsM_R7gHQ8BzhJQYt#asrGDMg%cOTESB
z0W4Exnz$gTHNKW+_hNsQtg|on_Zc{^UT~-Cj#;v%>Srp0C)0&<LOktuc5i77g1r1o
z%lFg02?0CD;oeW@I(oOC-m%^L`I>CPe!eD~9;)gr=3qyj5ed%r=gons{dx-)bKPKM
zlK?=dsRKb{gYX63`9C^;gjeIjV<3UpmmDGY(+@1?ftt{2Kru3tNSzQ2z%^2YHCm94
zl<>`s9g*!jm`dXTj*r1C6t6@jmAYZkLPjovlwbjj&KY32k_+3CTLjh?sH3=RK%}jO
zeI43b(iSQa+MQbqGRuBRnqt~~s3?#eA$J$BT#QUoTU*l2AE6(zx&gsTQT26l&USLd
zjDdX0OUCy*Z3`ykU<#5Y^*orrV<|Re3?^}1O(V6c$kAV1lue_w*gFwq9vRk~)a+n}
zVj<4QfX%REEf3lZ>ruvoMgu8w$4K3wB-4Y|z@+y(291FkGBgIQ0i}f)gVw+dy&C#6
zG@7&p=GN9Um}R7L-W0Abe}Nr-&<>bNm^=dAz@_(9vib(Xs~=H)0s+>C-BrZwHW~+$
z#Zeiqm4S7b@;n2hGwfw5U{Ts*Dm;>1`G_Bb!X8sW?UA`4-@;@rIEt_p=+xNDRzQnh
zrUL8lUyKQ(NdU{?Dw)xm!0NKj4>a|n!A4_Cw9@y0%U>lygOozqXar1N=?|j~FnOgv
zj5fd&l4lsKfT{frD6SMWJ?QumTW)OmAna)vwLWQck7QPv<4=`7wdojD`W)IjjVgW0
z)i<j2scpxg(uKSqMwLF1UvU^!x~O)CQKio(Q8`t*=y!)5l|B_AGmQFs%AGgn@Oh<p
za`sPqj8UggC9*h~pwKF9C`MI0<!Bj-9P;4exlzR8F{K+bDq`{M4&c2?bn{pFHHDfV
z1?Q@Fp$uO@+rm^jbmlRiRJy{%4^RnT@0?b62E&TDgO7+OW&=Z&B34G#Y@(?dle$^B
z_amx~$laUN&4j{#hLX;Y4&2979(PBvb^z0X!Yobw%ELuf4RYNvapshgp{HuvnoJ{b
zH>C*Q5vw6HdSUraH~=Zb=u)Q}Z{NnGE*2nu%u>asRbPw!D%tZ~%|Kw_$AsP$>U~V=
zT^sr=lh(iK5N}fP3i&=J_3kSj+2WAvoMbLduz@nV($y6zS<@-Ugpz&yRyg)od8v93
zGqa;87Zqz@!XM?g+>eV&ziU$KnilS)(zT`rDHk4pQS%SezC=M+7ax)e*L3<ep>!X2
zc*^;HPGTmtF1T~YlsB#|V#*(<fwAr?HF&y<Dp!#Ev6#JY$PQW5x`VjCv8Z+vnSYfe
zyE|lrEIQ~S%pHqLcQC$YEGpfxr7IS-u5kQgmF5+Ue<1cSMH7O}hj76=7Rs!i{`uId
zp1N3A|FNiwhk|UzqJOS*c<|1J_aBSunt=bYsIAAdyDYl!Lw?<&8!r;xu}ZCrgLf=y
z^|1(g8;d%eth-}Tg^PH1ENJjo);{|2V`}?^N0Tyap9@-DOuJ)Is}u4+7IpfVvXJ3I
z9T|$~oT&k&_r<_F7L`210Irmwb5CwTD)~VdX+g&iQ+KK3$B=Sf)bffc7>in7K?P$`
z%MUqI%d1F(ebI4eOu>;1KExJy^-i|QqSj|lM5=rR8jM9RUXcbTb0Rw1)g1WoqdzU8
zBR_N+yl5(njv~6%R2vd9vL>ANr;Jt6jeqhsE?N&ts5Ta@hoJ+^JloHA>Hfj##t+`|
zk2)Mq$wV35(B9=Y70lq~<#gH=hcLWVu{Kkut<Yt=IBkU<+7ujyLDwGSGz=7EFr1bF
zqYQ@AF6bin9!}!`q`<?=G!P~5aGD0M<d*c}D;A+%G)~!7`@l@=L>vvLXOGZ>;j{r5
zdvK+!x~4NRr(fS)y`^v8wFNnS`~Dm)ISq<V&&JE1=(2m9u6>tp<1{C_qK^h(Ybk@S
zbUOT9mXE{kP!z;)+8u~bEK#lHE}zJ0c61%@;65`&SQbvRBh!ao5TS!gubU(%DZp9*
z4@!!#UT`s+B5uXbV}Y*S%4xB5?p6+iMP$Omc`9(C9<D5-cRDL}-Xgq`oYIErva@_w
zF_-Uo5sjEW)E?R}<RKnT6GlYDM}+QnZJ*A>v|YZH(~c2C@o*Y4UHg^8km=8U<+Nm;
z9IZ}6rpsn?nlfF7I-4d)f37;WGRbPM*)T%-{dy2nLA%eU5z@sDIySA4E}v`D2vHct
z5lueX^fI*d=8JH}Bfo2-h>_YfLc||DHm!>m(xV#&#*?O&mV*K%#-`=abQ-hEa;SV7
z7bNvf8$s4%^FW}{5!<vJn#>@uU8RVp9l*(aNta90p~({3Fdak{JT^^-_T1HM8V}7;
z%x9Kf%+r9T&1KV2z-3?N^QEECw7F~=3a<>luoM(2F*Z$rOxbdk1fNbO&t_I=21krt
z>RrJRM}TIUjPp$uuYAErgl6j8WK+c_+3(m;?;!iVN`#w6o|$Z(4T$b{Y$|*a{*Fzh
z-=6E~ji0b`o);u3@G0VB%jMcs_)mi4jllXp`B{Bz?G8KGRUN$`t$K<k1byN~(3C+V
zK#>$9c&yNL@)A5(5b^LJ%isHsHgFls`gySMO3h4TL3gpybYDsx7&Hu;c8{Q8@LaS8
zEdvE&j8K;8o9ZUYG-$dA51Iyw#25g3zVk(oD)DYIXc^qHae_w%H_=WbXe``vy@KY#
z9oj(y=7Ok(N6=g#*YF5h3t}4{L2KdOa*>19!Y$J$%3Kg7@d(-hchyB3fb_#x%5o7X
zc4GvMfLq78pxjImU(FQSVmli_Bj7=b1dV`#iU0xqPP|Q%0N{|TWJu1<x@Z$9iem(A
z0>yERpf11XGe}hCw=S@P%KVk;dsmT-rY^rHia6O5Yw?lI5}+H<ytko*cMg4KD&6}z
zpbctW1zXrnt$Qo)_f4g%SP8qKbe~uWyQy_=ZUJ^v>)yz2UGWIaUJl9NQ#cH@n=1G2
zY64a6-P8nX-MgvnC}K~xn`-xNsGpwy-P8bj{<o4w-&D<aqYrO4RI_M^?WXVlO1w_z
zU(CaHQ-j}6>hPN?{DzxjcWH2O58F)zp0N~$&l5od!*2Mxq40_)?R%*5Qr$tKVMDae
zJ2QM~=_?dMVF(0@*ch~<EJIwtr<|CYP>yw^kdE+YHXt>-f+Y-Ky+E*p6;$t?lD_=-
z5MS_Rfa)F5xcQ?52?ZCpAwKIP`B8c8tMN-C1*V{21cf07c8DzaNM@D|-`3F~Wk0`>
zY&_O8O_8ZPmPTe*m!<}0qf1j$bff)snR6L{d7*#_yX()KjDfE@RZDI8A@*Rq5kC`Q
zst0M;87*-H8&9#*fiCf)#~3jfK^w*@sxU%X*P-t|5|ru#ahox~lOl+MHei?{Xueph
zCs=Dk50yr~A!~bR3u=u$?5e1thcrU0VlN}K{{Z9{;2}0Z{Gv4V1yRf9(f~17C!uJG
zBdJbm?`a)fdiI)+O@(5W&?js>Wt3$ZUm2ELkkZ)7y1P<>U7$?BQ1FBSz!!1jwT8CR
z2(bk8MbH8<0Qy345eEETAPnLoD4iUNf;f_FEzH5IM24r>fmFXoz!%rFkFCw6)yg;$
zui4&8R~`xLD)k$RnXtm}ZAOe5F?@TglQ^*mhE*8Cuw!qH9Z-FHqjaY6=7o~Mb2$<m
zh#LHx*xHc*=L>No8_;|~Ze(lc9ZMZX;@2a>;BItJd(CmvvdrmUu3ab!<4CGALX=qx
zv~B9KK-=DuY8$Nz>vxtgvB?$?43{uq?n1#4R*<_;Y=i-E7YdEA-Y~FAesDy+p2AcB
z<3VhmX;|-BszC#0F2s3k9hn9qNsp~?aItx=a0Jy1MqpbXm|I;<9XYURGaJrHV)KN-
zaJ~||vG<k*_8i)CH@(l;rltXfLfuUbheq8^eYa}+t%|8)_syE2VfU@tC)UNS+9xK?
zt$|NHyzgh&p<_u_Y(Tk%;v@`^w(!un)kKUssrlI7R%d;oC<*J(s9p_$MpcxA;iU0M
zuw?5v@=6iESgKUlnnnJz@U6jwO7;3Xw5cn@fB}paF6|F2+L3Tl*WWqzP?oM0*>Ncz
z&J~&5G@-x>1A9#<u);uab0kA=six|H(*`u36ZUApoTa2*J?igh{D7Wwn)ye9#!VFS
zLy%v=04xjFas)3|xD@orD4%epHZ>3veMBf#JGB&X;Si!JHrz^tknT3dl|@zyWtFIQ
z1G+4PYPSNH1wrkWfUr*y|4tnl3XL#e!NQwf0Hx$jZJHRZrqO^?6=WMel4^*SBk)_{
zQiz$s@@u(1_x*fID31(cFkri4$=0sRy(3`Tpgfi=?Ez}uP!xlKe=An#Q<cFSODhd`
zlCc7%Tvuz$jLwVBSg^!#6B;5LHe8kl$%d`qTd{bDV0AZprHIXkGFeh|z;1=;gbmQG
zAUM_R&H^VHfLoDV!UlG(5SOq4wH4wLHr#fHn1hX3VM8cY1G`*Gs{LT83n7jTOm?w|
zgD?Z?FMt{~<hc!jM$M{(T?1&W5PPrzixo>r0}Q~c5F4<8Yb!+kYv9@nQU4xEwQk6;
zKpNs$a-Wf^I0WLh0#wD4#sj1y0GGTBV5$(2uYoBsmTXsp(h#+;CEzNSmYxA?dqlNX
z0k?`J;}u}5STJ6Jw2CF;wSZQ!1YkN6!!xWIibhPohHTcc<S--SbriJVf@r3I-yeEo
z-LKbFgKw0wu~W;nutisj(8co0gq1vkoK#b56KJcLff6H6a15TE69Ce{9eO1EUS$}E
z(2qwlE57CCFKXxoe>CJnkI7P?8hp=rBQ!<M_bh*GK3WpctROtn0L%(uAq~K+jEh0J
zx~Dumh6h-089_mSqXBF6MR4Y;@QyaYAsNCv8nAPr_=zLw^%MpG47ec#<dK}VUNI-D
zf_4%l(&oq#tAVdIrD*}Eg5-jzdL-owJXMHx*b1c>0#O=>fMXI5ZooT+SceU4!Xdb%
z0hJX~IyymFA>LslCMyJ=JfiBP9O*f$RFfL*jwz*$?#2`)l3`3jWW<Isi%HYFMm44^
z?+LGMrfO#pOHA!d6E55Asu@aFgvLiQv&?E4cJ(;gh^~sMt!XmuN^W(*yN&>xDbQU3
zh~-tHn%&r(YTBP7_NECfJ9VCi)e}>W^`xIR<ys>SEhbO>4alt!;L?EH3JX1z>h=l?
zHMusKu+V#;ZY|Jas8;b0+h-?3u&`m93*jscTVW7pc?2_yn1QQWd?c8Gi;C5>`79__
z)84b-$EkFNUaZ3gn0y#{(+oKJFzqYAV||rW-&}2}5<bpCo|7=`H9%v9$%+RUD@;~A
zpjbzOF(?Pomh=XoSOGYu0f-d>V;W#sAuQ&R3_Jr?979;eM}!|#2X&%{h^`<k)0Sm{
z{Vy-_3e)zqp#4R4Y=|5Q(_REDR*34@3W^nF1zeC+2kE^7i50?i8VsBOtkYoroHF<M
zw2(qv#|9%Ri~t1#3M&NiG~{v!VLWZY4+_v5AA#W^Yyk`E-?;Ovax;YrJ%Z|x(umoD
zg<v}PL!?&-7HYs>1$mM!(O0L4`!WOiDojTMFo%zXlL2Off+7v*s}Q#Iva+f}$Wnvh
z{Z&%)MSB*&SYfiK7OaRs(4?(EH??Uk*b@qyJd*0B4600I5_S`%VF;!Tz(Ec1wqY`r
z3Uu`mppcCpWJECnu8ye2(pwhrh2U2m315hlSz$R1XsdXjoCa>N7+Y_x;TPMoA<aw-
zc`}H%kIHL)mSSbAiJ>DsWV8vvHjgAnUlh%TJUKDw?OX;oHN@O(A2&7x;xquSf*4M7
zm=8mD3=TMU3~f??PsNaN1Mt+5;2S1*>Xe^ns&VrfE9m{f{p75Xq5TAB1z#mKxY|6t
zkWw+Uc>oI)LzWDnP)CAlQezL9C;&ahcuw^IdP<S;E%nv%WC3WW7&1}{?Gyr7nmfl$
zCkvI%>Ihgf^!1QQg0xtX;K@^}fmTYSBdU?+7U1b73rT6fG=+ea21L`5@Nx+#q!299
z0743pG~2$jgr<U>D+GtMI-R>xgu&mbp2gT~$YT~{Y&N7i3o$ku(xDwmsaj-A3t=Oz
za;k+Wn++hOAQIAmLOKFK!faO&^Bf?gBdK}5p?SNOHx5%j5|r{nJi3gLLMTO-BLvQ^
z=vvylkY&-ewCmhA`j$1mp?JHj5oFDauC=|Pdj*FyoF*R$UF&UGWYsvs?ONLaG#v^0
z3{5K>r0vQS5M5^%KrThs*#&S*(RFr#WA*4-{u}HiA;hC4z9|HEG{Boea7P2WDLR+`
zURj`3gG+%B&hbbFo?yk$z2bc~TsB0VGxJ6H;j|;*(juS2EQIpKK&4jgI*TmK)0H9)
zF0?Aqjt0O}h~n9B9}`LOY;|1|eP|`)PUna?)KI8jBwkOkDH}~6x}L%<RCH}CpzI2f
zJ{zvCJ`$A9OXcQldgsD79#QqLYoS8pc3BocIfa;`Eh?jMO6t|Por?}aCIiMPIw4L5
zh*Na=LIEGWi+sVNWf4{d@J-QSQ~=x*Vw<*rYVJHQ<#lCrc|u@(3*jjZx17<nJynv{
z5GK+B?0iRrDF-^b5Vy2}vM!p;4IrI@+|m{!3!Lo0IR%KN4Hv>8Vrj#rafn;maH*WX
zDRiI}!YP_|HC#@ABw2zB-?XU#+Z2uVN`RIx#64|s-dJygN^WwMz-)LV{5EjJGX+t$
z30hl#NdxRC#13r<Itqay4Va^7>-9|eb!3M&@ODL$mjm9eXtF{8o(Lf$4G4=X1dTML
zZ9Wq0ww2d8#42sTdql$_D-a>krks3GYzCo|M^L@gE|aK|Xu>W8RCS|e5}TdW84HqN
zN7ES#GG&LrmR1;-5Y*BDf%<gPP|OM1bie}SOb}>kK-YwDmh-;RMe%V=0Dz*=w3x_M
zek9epSum#~sK!m8oQ?#+zY`#*j|e}gs%eYNyGk`hCy-2E{tg$cH8lj<yEQcgesgPT
zNh$EgL)i&T*JqgO@6g^No|#3V8={?=VA)N{&7V|X?q`^wz1yv}Kzp}aZLut|AyD3p
zJIK6|GBk*coWw5)961aB7D7f&0GdL;$VoiYt&|fJ++%Tv>Vm6$Ggf{U>`7GDr<^^y
zH#ssV$fM$Bgxb7UmiR%Sy+w6B0Ur!fUC)Feo-WeLnZz>*4mpWwx_OK;Z+OKwPf_O0
z8`#^`fz;slQU{=&?>Zrw#4p`TuPyz2lObdhzjQCXbmI$5y|&czJ=FoIXW+zgvO_)J
z6IDYM-&5^Rb$n0NgIn3#R8L@ExJ@-d9p5|wnLscd$wWDO!~>8?_|kP<1z1#D*CwS)
zS`Y?lsi8qix*G`rk!BDW7#fKIL0U>ex)D&iTM#MfE*U@?q`UqZ<9_#k_xsOz=FIH1
z*WPRIwbnWF%=?}>+dgnv)hx*&i8~I;=%h7>s^74&s)CZ>kjx?<FkBD=k>Tw-J3wN>
zpe$sD_R-00VtE|OYwZNcdmpZw2l$E02#aB<qO?J1NMbeODm4@e3{*>@YRyj9yrI$!
zDPIU5l4kZ`k!acL!+$XcrFdcFDYb7HU?D9zY^G-I;N?B?BwRQm8owBk8--Efs0z=1
zy~`HF)Dr5JjK(=X^8{)*Lv+tyt5ZIJNMZK!t+Phy+f>?J%!tPZdm>V!@2j@(?>!*C
z=Mh}<Hi2ErP`?lBNvnC~>Oq;i&8<y(-o=ai5*F`JO^UoRqP(nUZIaz^a$BYrlNr{6
zQYd=a(8mcUf%a9O$1i5i+}QbBYrd#bukf>}S>nhGOH$SZ<)$KW+B<2gBPG_<y|*?9
z(F@ZM!R@=h7yc&mbs`2G;>)~MFVP}G1r2Qn%FWY<{|!Y^EvZ+e$`9b#hrdmGU$9SP
z9lqYqK!RiA`ja+Mj2aLQk?`U@JGuwVbHN-k-(%QCgWR)sz6Yg|rp3on*9=<A;7*dM
zKy*_l$rK<D$hH-LZ&2@VZyr1+FAqjysqO@dNqn1qQ-TaUDsx7{y}uo(td5jd1BfGj
zT&Nnh@%DQ|oFXcm2)OH+m)p`%6C*zCOY=#kZq|@wgjoFijuPZ#q}-6A8!K>>O!x?`
z7eq`dj0|~%B2YTE>ncN?lw+puxz2G;>F#Kw^l?|!+F}X1Oke2#kg-V?AQm%Xi$f^P
zcE-o}f!RHpWKI#8m#DKLG$b{|WnM~VK&k#XrmjVC$C~Pm_Ztt3sHzmC^C~Ql)MdF>
zmex9DKh!EVh1KFKXdN|bYPT`a$agK0#PbdrvhEicEz4_+$K*~(JixuMvAHW<v$}3W
ztmoyQT@xKmob<k#v`XAbpiUMj=Hy!kcK~w4jEu?vcLg+5Ak(CFFP3;M`DIEGCwikS
zqnHy#Lr`LBP{zeqcKdszeK#wDuP5-Dr-vG{1P9p{hpd+(Jit2`=GmTe1b2>>6BPY(
zRwGB@zX65k8#etf=o26)?$tpBsiBQCQrZLU#>TAe3AzRZ+U=)a2~*}Qk0n{7a+4R*
z#UDM|yU}!oSuHmum*Sy3{?J@5iHl|l_UB+O(|>swxGZsdHd}lxbbDQJd!FO}w0P0+
zDW6ug*6qfw@71-dZs&F3iu&#C;aThX@-eI5&1LX)4rAK>+7s*A%~AKu{Vu<zo8yJs
z#hZ@n!tE$Ozw60`>;2RIEBD)@LBG?>+mkN1Y*yl#HQvDB=~<IYwf?DR<Hte2t1iC_
zcZr+Rwfe)8i-p_$D80&=5yL+1X1}Z9ZgGu(&3Uk$qgBU6&8ODOsN3t?tDC6X;(HDI
zC5t}3wpVtaYQa>r1y_kr!|aOHm1C@TtnVdP=`RSvmmv>s)s)`BeV^t}Jv@7H)v-G`
zRbyhe)}|RaBkWjv%!?;hHgSfd4Fmg1tnJ>M)7~t0fhw#d9m%R(<&F=dKpBelzV-c<
z`$au6GPn6me$S?SuNJljO~N!_ulWWtV%{qh<~I%82E+)}WcjtszC*(Je9&jILy#YJ
zQXF}G{5rsC#k(Sm^~KV2VUFu#jJ`TAv99+QyR^j};gjZ~{bwiTA`_D{fHUQ&@h>H%
zj?Ou^^-+!)AMkJbXicw3X&1lvoEE=idq%ZWDuLNvIQc5Bru~#)Df{*~v*f1LkI>z?
z6vOrM`1+NjdIosd!}2nYcG<(N^?>`r<d7S7(dzZS1G?))(QTT&CZ(v_;)9F(V9?y5
zHBSH*pWa25767J26$mw1{Pgg8OkTlbs&rdvXRTEd+P}V$x*plGL;b@hy~_o3xMMD)
z;Z4)HapHG6CFe#eCilt2!*1cj$5H&34=+E;b*;Tywco7(`+1UH)%o4v*tLyh3}6-9
z*sra6h{aO$g8kCRK!d2=PB%OBKFu`iTU^(o(`0-TuxDrWG2-N6t)i2DSESDKPANHR
zntMK7)cy{G=3(BKC)|L@^sc7sgc+n|UmD_)%h@jI%-UIF2&La9&KYv;Z7=y5o7>e_
zAWiB0q=42T;W-cSs159+*{*2HRnP631&!Hu^g5ax7?<d(t5OG7+kv{T|5wW+w#I%F
zQzVWyg^U4K?Y7!9RMPFkq&m}9pKW#3Z^tR@-_U`bhe<=E3*xU8oPGR7p2c7HwYG&;
z-^BCp>764-bv#hK9017Z7Eiv4%DwHwYea3EHGl1sE&+wzMm_xK8l5Vt>J!?sV{ynO
z{c1_wW%mg5;VNL^bl2qitK0<DR6=@wi_F4F8U5^+%VGH=VllDv!DYeYqk??45~YR1
zV<Ml~QU9cv)10VvW-qU#V(Uu|F=L5gZPbdT@wvqH+4QHK=uH`KzcXKW2GGueH`i|7
z`7S+MnV*qAvX`(Po@=4?3H8k`Si|&u)7pe{9Z@gn|HWJIgvdw2`Bo+Fswe-NK;mY5
z=eVe~`G)r0!D#}vrGtgD3&hgY9`OlmW{b@a00I#2002NhP#6e*w)ZbN?{B%ND58o>
z*26_!+r`wy67WlakeLGE1pt?{B!C;hWo`;Tii;zZe;v8xzz!~d)3)LOasUAW@NTt!
zE5Y@C8{_%Q7=TO1)6o*ZrD1Aq319?p|1_>)3bBOu#r>x(m#U=&$W#jK0WgG%fB=4B
zVE{J|5C|~-sV)sS4A*xC@cq?59s+iC{M%rD8TlziG=Xni+HlhlQwL{9gfVl^KVn6I
z3&hp(Pe~fCC1dFZGPl%{mqG}C&sEFP8SDx%w{!*|{HBHdpQ#DL%LxA>Jf&jkVC`Z9
z5c+Faav(bwO9+5V&JONb8B24p#ZODW6}bU|Ji-EqzJ7<yBXvjrr8miVvxK$p+Sl!`
z+vZl4R0mTGRI!W%G+0<zXga!tD^DWsMn5-y^*Mwk@p*IsNnkADV^kE)ju-Jz3ie1M
zI%L~wKnUG<0*piNX%W<nD#lCGPDSk^1y6tGvi$bj;I;RUuj#yNKE8vyyQz$C3A1A?
z(L($#K7cG~Kh9r>NJS7}#^kGI2u`Zgg!a)hWYf~=yiE`jeKC;f$&0mbmbUGARvwfm
z+uKH%VA3hv!%LH_yR<jwdiT;V%D$er>{Ge1fucgL|M7Rq%2m#!>h>G#2@KQbv-0WD
z0wTy<@NuL**E@cDNlHW3!A}>p`lpFvHyYExl~Vm}Qd!IlNd~Qlw)(84(zc{`iK{Ai
zL$2;u@8{j6r<9+a!ML0AvH7DIZ@UT~YN(YND}CAu;jE|T7|Q^-)yqhY{_Wc#=MgOs
z{E;<3m<<`^uy_a3an<`H6pok@6v~as^GID;P_(2li<b+^zXR0Km*1mOqqT7dKuZFJ
zf(mqOCqvY0xEn`>L`o#NC?;Vnb$&{`<?gNgxn(;EIXebc-yX+0W$h%Ku)9B7tqavA
zd6lMt>ziFBh?l>`kQTud^qq(&;{%ft!;bRBP)oEj^HAfCy9m>$)&-g|8e3sb2uUFy
zQANKUIQE?d(<+pm;UVPn#wc?G4a|SwaA@XTvtgjkJ`o8eqhZ5fCB!!<H?{(Xv=lk?
za4ZnpPo{edvyjTdq`Q?4)Z8@DNY61sF4;!Bv$ZVf4O7%u;mdJ0l4ht_!m7-E`hi+@
z|Cznu%N067xyztp@|j3=E~>>znHC!jj?jz*V82Ohw*paQ!7~Eo?RjQK=5#CTl~vr$
z(Ztmwl31@kr2+e?-X<E#*QE<|;)IDbLgJOMc>^#F_*=dEZN9xoddAu6@(MGyMBa%t
zAllJop0))W?G5hNqQaZ$eB;BuUUKHs>9y0_n*AOzvJC$BIpy62QFb`_GF_jg-VT0`
zNJ_0F`Vzh>C*NI}9uqBttD2o$nurWZ?aZugGdsAUGLlN_t2wFtCgrPPzGI*lvq%%P
z&qZ>BZofy_-I`bPLD3HGW_Gjiv!<zDn;;^xelvac(|*Ro@62Ys=4%%TabfE#+<oSW
zmu_+M<xE9f&@b_E%6AszZlB<Wso2CHxviZ+E?iEkXq%1p<Fs+es#WV{#BzQ_k?C!1
zZLN(SOIwQxTKV>e#4ux68DAVnxhHgnwgw(waUV#K+UwAN%5+ByOd?rQXJyEpxobfi
zjaEcuzkJUKy_=r#6J5}byvS_n;Uw8Af$+>43VB@E9p+?F=4kr|SpjcIxrTzj<(P}W
z9~XDNo<DrQU@LTmINnBYoCTbA^g!_wrto(rx=XLq8J6+2FpLaAf!=kQo~(C9bu$h|
z1G&wNqmI_r^{UcJJrD9FW4#RPtE~DaKAz1s9E%i%y;$&JF42r%3)gkJtIgK`#htJp
zKNO-#_YghoHD_-4`Y738ZCH;TD;pDM1Cx+exnhx`QF7snz`E4@@H*=JdC3n^qgflt
z^JA{|fzo<-*@sGJdD;?oLigQN<Nc?MzUEOS1oBm37*3J6D61qG>#xu(%Xb>$W_|rC
z%DelTKF64%W^2Rio!>B9A5RP$&!T_<x_s_LpQ%tRweTD6nfV#CE*;k*0qtTJc4s@s
zI{pBe^|=xeS3R!HcwDQ!XUX!XQ|77MB_y#baf}j&hkS-b_l9DREnbGv&%gU|kn&0q
zzdwe@fQdGHWwZW-?v1E*I@@Sd8X8CgTPhmeQv?5@<SeG^Ten2>2<Hek8?xw^>tZ7e
z-PY&c6{3po>>AaZ)l+iSE65+=7@u3Qa>QHNL<!M4k*0*(<D}vkJ+Y{6&@us)LUe?S
zjkw;Y9I2i>wf<PFR$961^aK77mEDxJuMUTFe2zbI#T>*_N9^LQl&P5PydfRt%QzLp
zon`b#$QNxfl)Ico_l-5%m|PqJyA-B;gR`zVWsEmnEcVnKvU!2TNoGDmId{>uW8XV0
zDfH{`+xobuma`UtDp~3If;6q@TbD+TV=dx#1jjZi=4Q)yct7Z$Gj;Zg-F(ZL#+6xn
zCXqSjS7O-U^UPc&-1OPUC^t5$_o`;6tlCvt_B6(yS6Q8_3#K7E=rw6#1){|tN8N_?
zrnsimEQ85Lyzc=Ao~TA4bDb7(d)+%)MCLa>6?r`(O7Rtgwca*8eS-qk{Xlb5Uu>O)
zAr6$KgL#_Of~{#1H!dZ%z&%?I<#e^nr-~P=QUf_Q?Fy}}yIJUSODSow-e}x>kP%hd
z8Vq^01f#rY@VLTN%>jL=+cKJ*tx}9g_@WeJhW}CSzKeS%zPLQDX7^O4c7i}m0R>(_
z6k2`1P2-R!GNVhi7+c&^v$O+cGkQs#;K(VB*Q+qPpih|DOoXrQX$6?Qm#kKqFDa6R
z0?lL}zVn%Ot<T%ykuY9xN<OW2@r@>==p!SJv$!KxQ9`I4tYjVMr9W(8bfQ)}92zqk
zmZCQsRg+fr;A_iO$PUq6j%-vGvjTGRfs?0al+!q0m?Ac6S5{V6voQ4JaQ8lm*G?Z;
z>Cv-&GklbG2(;Rf{hAzbDN9H|Np|F~)TX$iR8X&*6D+3c7HoUCPRu}6Kl;L7@7dtD
z^&j%Hs)F~v!2iTj+f?Tn_|D$z!N<q1gL0{vV@HC2*n1uHs7ios@14&OgIkps3NZ4F
zjYn(1ewAuZuZ-8nM>h1H*UENK=bEyP!05^;V&Xy*i%4sp%w1xy^t*Yn6iv@tm~4d~
zD+!cFM#RmPXtn^OY4Ez}aa6bhmv_b;+wk)7qS(T5I(-P;8Q%~vcWgL<>fAlpcMB}0
zc*cBZ?08ZJ60BZYcNNJxYuJAK?8rc~Et`Bzc4cKv#K^7`#Ia*nRZElPdG%?7R`g*>
z*fQV8L*gPnMG?Jm0g*h6{1#8|q0Huu>vh7SVa!KbSBvY;mnROD9uIfL2M6a!a0Kdm
z^3(MRcY0sjl$v%145XNUI{wJ5jujU}F+jKSVLjXNggr0&lKs9CdB~HcBoBF=ks$9T
zo4e$l1=*o*^11mE-jooZhTEGp)@4i#W9-jUPV7s*1*dIGKJ~Ux0NzX9;j9+!ZJZb<
zxisQ)YTOO0=&MN*;XbLgwlu~IZo_$RvOKl&^}2JvZ%KL|3c;4Q0_%5;@o?p;Nii0{
zve>9NTduY%xeN=p-er|?h$}WUs&o3<+c;Og9X^=0=19tYshl6$v1I5?pw2cOIi|tW
zcqvLP-&_zq7*H#;9jl#@L<rVqlub#BCX|pGT_#RS)ERoXTDYex%b)T=c*vqeHFEMO
zP(Nsn>V@+|0rg$Y!UXlIYLmx1Yb(aJn9|-p(`OeImv`KRTOSK)w|koI%Ed~7G#wMv
z4>!awk@&)Vy(BJyu1Nwav{sYXpQDBupD2%y(({N?emm+OI~xn+^LuIrQ3}${(wkzV
zcEHJERGhH5zYRlTu4{wZg!t?4l?(AR(%XB?sE;J%b0`}ok|{ODk_8d+1$({p9wUB7
zD2~;uD42o9JM_x=&Pw)LdoosIf$kHrI;XSYv`Jry<8Jf3u6z!Y%b|2w`r7SL%7~BM
z*|)K=fB;yMjP(W16T=f`#^!f%+8%>-S5P+3(F6O^FQ=cQ<f=aLedZ({l!y`N8N*um
zZd4pwFei{95O~qO<FHj{t)HpRKGf<Ey{P|2ooPOUP%{#SB1<Ib=^h0VsM!`f*lOlj
zqMlihb$XNW!+WW>P+RZ0>RME%!9Ja8K@S-o^PVpculJoxo+Mk|`mdzg3BpMcysX}L
ztDUf*S5oo9mKAt~W(}4h6n;01S7j;f_#KX;HmJ(sgI)~14C7?1c?UYP&sh@*D&`sI
zd*o-B6bY0MbI-kls>1YU1(Z_kGZddu>Xh`B6Ml5W<733u@-z`P?y;;F)f>>{*{NN|
zGSwNx`g8*zsieFzwG`*7EcNHVqO5;fSTotK>seeu`%MG>9MiYAfdui&d%}&MZ`n;=
zfzKDd`@&DMNfw^u5OQK$rZf-r894(z_Rk^UhKhydg2tlUbK@M5LFHX{yzODq-cZJ@
zRGnBdm%bEzp^>Y(FNFc0UW3H$mW%R6kVSIdH>mw#VI}l76<TO)spYGOT4Ky4H|dU7
zGvQ5D8MF?1>_rP0R3wp1r4*B&`<mGSlT05B_oQrXx3mQbZS3STO&`{}z4#%Yw8Plm
zfI|adW4Nc9-I5_f!S$3j?GYoInKHkbvMR+|Y|q>0kU$k`Qn$NdZ{dH3PLu0?HvY01
zY~S|H@L0A>{tUoPCjjjOkdwFjh7ldn>g8n?1XT^`7Lq<SzyZg^H=KR(D8wvZyR(-W
zcT^XRW{P>>r9fcCY$dDYT3iD*2?{M*7L4*cefvUxIfqu8v&8#B!)ME6b@MLpYf}sp
zul=Dca+60a9Ck`S=v(fZeA8oSx#}xe8eEj-dtf!?4*ek6G7)&L^nlXB0!SESl-Heg
zc0+f1aaPSL!jrSzvmp+y7|dJhp@}*z`8=h96T<$zilV`Z7I%`}x*;?ay0YH0zCJ<9
z?9HgMnHEt(>tv1;5Ljh3KajRHu`|Q!#%ZG7aO<J=!EbZ={?bhKi>0UY>&I*f;Hfh2
zPOpu$ncm)+e$x2rxa-KiXSc9dlZpHnFKLU#oi|3_ZJN8x%&qjTnLQBGz4Q4(uR|?~
z54m+8Z5hWYHZM0tEq8Ps<wE=7gNw?et=;9pBZA}B<f+ES*^5^H!1d-TipxZ!-Ke&k
zrrk@wv#h!<gQv>1L-uE{OIo}3d=gv2uMb+^ZFCyZr2=y`+abBf?p>|ZY)hB1mlu=g
zKH;w^&ZMK*QbleG`<=B7m?!-BP8<z7bLMX)ZkMx!b3-$CA1sZ<ak!9AD3yES*97Lu
zRm6(=bI9A^JX^UmpXG!ErMAb!=b~>?!f&w<sJRPyt^EBV2jJ2%Qgk!R(_@s*4rR9M
zho$N^?}XBwO2|ZSn1OKr>%=pQ794GwCi;5#jW-I!V)DH`l4sNvi@?TL!ac$^L0%9d
zchfpwoI)m73+|DntjZoO_>Fd4HPmY#bIBH_rxwC=y|4>K6!fA;zk5C(v8jkmmuq?2
zEogyGqM%GfU6H4idn;5j9(MRbQJDUUZ#*RW!i-8Q>ZKUPz;dR9#C_k=%tQ_*^jtN$
zkSDQ@<jQ7^>qIl0U;rHi+ZWdvM&A(2SUzvZSNJ0ai6qX}sBt2hK2fU)@AX3G#O8>%
zuF6)=+6R44!b#t*CCt+~=J{~y_}Gr5)xJ9id=Vvq4|B&hBk4c(>L>UgI-y%)K~%f#
zy6Je!tCF@EBXcFjqHT>>zm|$7`Mu(;EsKg-v%RP~!UF|~DBNSUOw^o6$QdJqJdP1Y
z4UP5n&5^{8U<F}*<L$h4Fg3gNz14!>&C}}tT~LVZBBi16u%Jx;*;Jbk9$^`O+2fHe
ziLrC1Ti@k_f-|ZHxp^m_am`Nm=d+(#^{Z^BB6f0qV4fPJ2<#!<d?67$D;V4>70_kI
zGqxAytCGN?&pdiON_Ds;CE+xGz^}OOw4rUyWYoCdd}6xhVV&hgR;<gs!wq>m$xakp
z_MpUP$|<UH&+Aemouz6>YeSTEvAG?DlYdWzR{6yq$ym5fMaOqtm5!<NANUl?_z=PA
zzL_3sPf^x28c6gpW97MgE>S55vp$C~-AYWY(+_!}+IyqPTbFbGg}7Lo!4a7#ZA$P(
z>pc3IoA6lE0<efC1kgrJ(Mnt~1H@G>340xzt~~>rYNN^7MGm<+9s|DC-W20IlcJ;N
za=r6^&rEmG{9MuBGf&~Ff(c|$b}52<pXSUEsii;Q1^-?oaSNH_lQusL7#s6d^_>zl
zSl@W<As4z)i9eTZW;5!|2(lm9-nm8{ABs5f9*E4S2^eGY!5>FxuU$syR`HI+0&<2$
zTNla=1I&o*Y8ch;y?-T&IHbdm!=E=8c8VhYd6AaWf7IT6e^fbhhg0adQQudoZP#qE
z7Db$JuLZh*Y4g!Pj${8S7n<PV!G)uSDO5A^y~}$~je(lfQKqdFy@><Hf!um`FCS`x
zEyNCshQ4Cr(?j#9gyy3Ld&EIeFT>CLr5&GB&fdyFce$|LI&J_j>5(qcnx3IXqC6uW
z0>H>oP7>M%)Alygk^HLBPR1I~(~-s+7fBf|;_;_AV3x>@XxlE*Y0&#z!sl<;J$kUX
z5*}j)2iiVwgxVYKc&9)=x=mFGCxco2`>XFPP~%nKY0CU`h>~9Hw6}&fCiI+GZAJ%`
zN>J$hi_R1*&|2jAb%V5bGt_ll)_a~#zc%8D1Tkz}R^z_KAQ}vW{9+Op_5%F_B~o!r
z|9GwR_`@_k&*$;@@lzTGD5NZfVMrhN7Ohcq*#*zBk^59Vl-hWZmC?}}{TeK=ZVRD|
z%CMfh`bMyoaMUt|HYsGBRNw;sA)kj-+Z;a2F0@PJxf;e>tRxPY1e$09W)yZ3=nagQ
zxt$)xirqiBT<al>4w(@pAIC$Zttv}n4w+yoOQG!=B_Eq5HG97uKPmf@Pt5RD3wsj#
z^SeJpL1-i%rVsefKC{$KqMk-X!cH-}Cl?)%iG3~huuyz0+B}e#%dAtO<>t8J0w`ZT
z3!hP-%89@@k=-ZS-osZ%Z&N6gpq)mh$N#jm3}AU)2c30rJ)9MF+~VN$Ev9myT!q!5
zH5voIB1@xx$D-hw>IimegBiUdIC<>wX22P*d)QP%)ItRCB6FY;4R?%=S9<Loe)o{+
zW50L;U}h`!bwwuF3wp}of5a!KPVhLHN=q9>^w>=S>v0Bj;Ia;oDO~|&KyEgU4)JDc
z_+)~Db)PVb{d3~uR8(&k$qeWeeh4M<uzn~R;S-c*4XtK0nWfxrn?3A3%n(A@7i0%y
zrUTnINak2|N^PudrcvMVk=>~6qtJ|@R?vrSuRH8eNC>(a+sfjy&^?e1B>|gMMw<j<
zNDrU_!?E$|qb;}OGzYD!ZLK~_H~2H&8sL9}$p~cgH<--NBf$Fy-WC2g2Fi`VZGQs6
zT>lFM{X6Dq9NXs*2*i~=J;&xM2q!8<&c7>Flut$G^S+7}DKtxgQO4h3@3eY(SZ5Q(
zJ9h4cac3xJzq5G(UbcJdI+-8^(+km(zVR1<G+jMK4CuTYJ2lvTV(x0P77nMb9rfiM
z*+tmd1dogaTRRqe*u}(IkV3vSNlHu;;hQAt*31+;O9<u619V;S?qJxSj?_;&$b|%)
zPf<L|sJT|Ck?36eK{!&T#t{1qx1?lrT|^|iXsPbCEro5+#FdCLZ~4)yn;%U@TGAsz
z`PoI=BuUs#OsU)j?X1oZQV9#nJ<Pw64<z+<wdsTmwp%Y5U98QuzD;L5Wp`dots~@2
zQkQ=Iu!`&A!8)U1&opFsO>!Z;#hNn^=frm3b|4~_Qn=EFXTl;j4%=jA$L;LGW8k!Y
zz4(+bc8{W+-2*$W^YW!rxH){8Ol0(~oVI_5>t_&t$BUO2_$OT42%!BBX8j8(M_~Cf
zmd@r7kfRG2f&jjM!ux8b_He9T{;7(xj2fGarLC#1t2P`$|Epfk)E;E#31InE1whoX
z{;ISywT5HmJb!6Q{X+9OxPd%C00*A{4}e=xm=})f^YZ*g^%Y%A?Lg*|4%T*-0N~Gd
zlFsG`T0j`SE-Yd|i18uH96Y@IKLygJjtZ6_Ya2Lo0Pp6fNZZBIUKb$rt39Hi@TY*7
zAv_Z;c>oB+{_hArg0lFxH-2^JYUc8juF!#V1PD+4luDU8TmB?J{y)!vAkHq*Hl~n2
z4p1@uUFPQbMR@$v-GH9~`E|0$I>1Q+kb^aVOAq8A>EI0dBlu}q4`ktD;|ym-c)1a?
z_}@FP0PuIc0IvYxzh7{Q1}^<`{NFvm85cnWZ}e*y;Q#YkQ0PBa1>ngg$cxCN|Gf+F
zBG?(Y9qvD^f9dfE{-+NhfDb-(et1S8#)Dv15L^#j0)PFadf=1|_=y7u!J7aO7n#3@
z?cYg^;FNylrZUI^;Uxs^r1ckR<cgq}{>I#J|DBc6fPgJr&EZ@Pi@7NX0tRq%a`SV-
zr^sUC;^O#-3r>H*rPdHrM;nm2Gbb2g&H5|RrQuwg3kd8WgP_h>WFGMVd3b<AJVHQj
zUVfk;8<2+?2xR@c(f{ynf2c5NQ+Vcst$zmi=M;VuVgKQnJRp`<*gya`A2#r>4FC@d
zFF(Kv@JlAhCnNxOEMfyV{FVs_ar69J2IPic#s8rPFCc>S4;h>*6ov=zA2LBcKA!(>
zD<H(n2T!Me>hTH!;nVzY8PC7;__z^C@=rZJZvOusvml=^{3`KZdi+2>ct-qb>jE)_
zpWBe1ESxsT%M#%$#5F?;42B2&7iWhkD>_)gWBW5Ne(`Rm5SO3c737CsnXnldW!2@d
F{|_8o{aXM4

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..608e403453645f5a6cd7581c3f9da443e2695c57
GIT binary patch
literal 76717
zcmV)uK$gEHP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-knx%#s|o=dU<Rd2w5;Pm)^!
z#sCJq&}eps7lsT85c({}UP%7;K9v~}S?v3=TJzi)%)C!UpJIJ7nU$3pnO^(nfB%*~
z|1afzfBon8_OILimD_%uub=<@=YM+r`~Pcy{n!6@ORxX_`M>||^MC(s`#=8A&ky$3
z|GlOC^}oOV^_A?A{{KIZEA^}I`PJI~Rrd6Hze@f(n#$j=|MdEgk1hT`|Mm4B{$)G8
zljkd4U;QYxoS*9DtK@c^>Gdz~?ce{GzwLh;ZT`!D+5X+%>i_aD|84tU|7A6d$6l8H
zb$Tz$SHCU+-p$8qxo~i(2H=-!`!%K_YI%8Gsb2jvj;Mt4FO|-Wmh8VM{^8u$vwa=M
zU(bE{^SQ76x)03DzYMH3`*G9)@JqFtztXK5fM2TR^G9m{eyNrkTl48h`A_FRonQH3
z@8^GD{`d4_Z~)eWE9d!@>KWAt{8H`s{P$K3z%SK$`q3JIU#iuEt=S5&{D&)0KEkU%
zyaDOYSD<|Un?C=I!2$SXaCx`?Ml}GxRNIdqtpQk9%U8L#M&Orf=jS8QLjJS-Z(4!R
zxb}3U^YgE>eC>a|0<ZngS0MNP)!HP;3H&m+&(~<bRRi!#wQ~Jv4Zttea{tj9fM2Sm
z{1u-7Fa7E4e*{?jYYFuF2loF>BL6Op)8{)heJ{NDOO<2VxTEmP&)fM`>)a^-zf`OB
z>#8B|S^mS>P9I@)J?!;=K;Ea4ehd!4FM~@52Zw3^eyO(CAFTmcSG)GF^P0px%IiwU
z@l~!6_9*`0?0@7`ec0;%fU?ueeOxI2rY~|_)EB3LJ%2I3&NfSVFaIW)zRFw)<zLo{
z4cV+;Q#1eeEuX*6haLZqX!mgjA&@8K;eWE1<@0g<?D_PW|Nhy+4{E@lbhDl|%h62%
zX{DU@Y@h9@CSY0ZXm+xRY66zkPX9zjH37?NY4;OR)C=Sf7U8<S%I}NtCokv_XZvk{
zfviXP*%;Ho_EV3*y4vUCaI1y#y3*%6ly9{Ntg9XKHu2IQOn&O;=SBT>_W$JDG(O_@
zNhGiy*k?bCkI7U|$g*Ni#r_->16f!6=v>#W#X!~->+ZrkDhm07wa6cNe*C@`f1;J;
zR_*&T^;F1uh}}<sQ$-=`if6LV;8an_y5iOBJU3MovaDG4>&F-a`J->cM+ZGiyXtB+
z{_KSE`3B#`d?4!~;)_336tb?^_Me|kA?u2tq2E7bfvhVY=MUK%$e*mnQNMEebv6Fz
z#B!w{U(Z06L#$(m+=dv)x?;M1d_V(PS1e_&WTkb5+V3)0z#pu^Fsxm_ufd;uD{9|w
zUrv_SgByF|R*S&8+BwSzFD)xH7|)_oAnS^sv-SN`7RVpWe@mZMf1m$9(Ue-getbIv
zSr2jSiTe<RtSh$uL(B)Vu6XP}#C#y@if8@tDGTIJR^xM;EWfYDKXAs;A?$wS`F{Nz
z$^T5ht<QfOz5nc@<eklD{;J(hX+Qh@|BY@>-@=bRbbdbIAA$3c;&F)ncmG4fOM5%d
z{2C{!tM8-v+CTqu{PhU&Ey%}33xp7wb3cfc+=}L<4l8y!%uulz#2>irB9F6=9ajf3
z6pn#JH6jU(9OKvHK`n}(QpI`PkUcrFryEkHhK3#PuoL!nN8B(n06TpjWqOPwd3wwk
z`ani+wi_}%XPoLk$n+c_yJn)<RJy{22N7}uuOU{B2Yb1wGu5V(FBOn6RkYj`*kcBw
z`6JLZ!Nq2D|7t(VDJHAfgznP_4Cxo_Q3Lsi_5qw4HUMkL$C%8{d#NRsvw$(1A0TNG
z966_UK7ZQ`ik6ZYl+S5QwpTw$Y(65|H&)7Rn@Vifj~BTgYBmsVhVEOnAKJWzYzDDe
z*Zu~=X8n@WkUjlCxaUm=_~`aWl!kRYTBf}`S{9-a*v9-IwkPgTv`kBUv~1h3cday$
z=7R%d0Jap1(X?&M-oE&E+j5_B(Ey51RMXz=zUw|nH0)cfYBNuW29Rx{s#d;ZPgOO}
zay0H+s&dzLY@g~oYlh0S{=R=ov~4A=fR(uH4btxeaoroXOJTDOTcc?5g|K9!%`N~P
zvYn7Q^D1-d8}>nnqlQJNINA)d!DUT;AiD<OtDZFZ%~m-@(=Ka1NLTlLozqwQQRdV)
zEOLrD@D)ul_07e`u9<IG!Cf;SNY?;-O?T_|2FS*=Pb=U{xNHA=L!ADKSA37sXMpX}
zd*?fGAee;e3-$rH0KPQ`!Ud?dMjxPX6)WzoF3rDh-+^%cdD#_mulkBK6MNeasA~w#
z%1w{4SFwfE^Y3PM8<uSce=`OW6ET*c9n-*V!dr+sS8xo`$XzbCV;Z_mcneWit;Avb
z+cgjlyI_X9Pd*^)Uf1#$%yHMSi_dYW8oU~G(X#=n{%GvIf+-H+S8Vn|Jt>$yNxA~L
z)k4@6%wE%|U4a-#(Q~ptI0iocwGAjn?h{(I;BIjkNDSQPvuYWNl|G~PxyqQnP>wQY
zFO;K<*{d41Us5(-t<4eMte$#~&tBnFWZlMgJ;rxq`Qk6yX2s}>Z#_xCjJYfN?q<wg
zLCNNA5`Y;SF-JFi+Cl_oOj3xzY$Yy6;(Hz9FJaoU`jIegNvn~3l9Cp~Png?)x}M{c
zl(Y{MW+}9|gjq^j5dWJ!C_3abm9#w)rfQ!$<WsdzJ;JUE-7aBz_Nhm{t3oU$Ojw9T
zZ^RzNJ+fnpLId1=it433;yp1$5Ar#xmwM!V8%WcGY>w)s9t};@%6g2whacqAoehx9
zP`#%9*nHG;>d)9d^_;q6yQjLm+yGhQ=hPjWjv69!_mV%P`*;U}x#<^9DD`A#pati8
zurosqwzd!U28wZ(d(1%WO&(CwgPN6#9^+GSO#QK)QIDxV1&!|z4E@5$`_v!X8MROS
z@u}$1A1kpdCtjS|)teK0KpG{K@`127Ck8H!($)0wpvKKSAZxp+H>V9;2g811;BD%U
z54=gk?I%XwrvCWAC3|5VH^g7|j)QHj`sno2iuew697?O?E=~c4?EKA;4;5;s9||@D
zik{+Qq~3{B!T^#U;)ARx`5rIQym4q4(7|W;_#}pLiWmrg;iID*-ae2QF-17XROz8O
zX$*u*=0^}%jvT-mW~~?w6E$m=>|ju{RtyJ&D$(4b_17%zsCR#BC7nAo_$uk#p`BNj
ze1J*oMeVy%TkX)StCZCa?Ycr)#qnj7IWJIwYm(II4Fix|#+hbZD{*F^($;<Ijt^j$
z^`S#Kt-JOQl+%h+c!x6jDRcio*{nM?H=Kh8!j*$+S$CG;`oy>1^ur<n-7B>Ca%s_^
z4$3{M_(5p^Ts5eJ<(m37#<L9wo4eZIxnj`k%Egj3AyM63fh!c%+dxb@7U{M)T@8dC
zGkvX`>X&cvfv{h;%Qu6#oeDaCPMx#GC~U?SqJ-%7U2h09?+&%9gzR=Ds)Xc*##E#Z
z<Cr#((Y?(fuY^g1hExvq4GK{?Q1YIJ(9SO72gC(T=&o!59okIk>WXVKrE8-6#n=Xf
zzCckaA<11)83=bj^pp~U99l_f(%E{#goiA*?|W(Zw?87J?T!st`SR{&q!|Dw+c*3`
zINSJY7dkqXc3~PMfE&Nlg%a2ga-)nPHhhyy<q+G2X^<rVN4tS=hz;N1Lb2Q~e`V;c
zIRNi5q%ux=ql|B9<L9+VGB<o)OX24IAcsE}`vXV64}y|+HtUN4Cpv@lRPU_hw4VhH
z&{Ms)?zgxNV8?^mT^MtV%$ztb4urk+Z(@<)ZU?>^g+=eKj0`wC8ltCqZ>427w<{J?
ztv4XvUC8ow*uU9ReBX*BJC2eAVNW|g*Cna1_?#718Es0+<6t=uY}*FolsTe!x4M<M
zAMpt)66iP}<}3q4bK6Ijd~VIZJp<zK{Rdnrm?SbxsyHl;GKY^(LcUxS0@}S{j^Dlu
zS@OD7b&c<Ve*`k^5nI6lazN}p&inb~Yk&iOmJn|^yJrdU2AjM=1gv*b!0kk7<(*Y*
z^0S1xA1Mvso+#`cO5QWsa~p(umXV`Drsspb&+M6`JdT+IVfRgfk1|T$Gb!xN&#?K3
z*~gJJ%MQ}AdPg~w)H}|9!o-DT1P9LnaR^CH%iKW8x~Gpr!#OhJ<FFZ&{WlH2@b2kj
z(Y#siTATzkKNNld-3;M?cJ+)K$`7C)1SNaTbJL3tp`YWs(QsPJw7xW))pFBv>|XLV
z>V*Y_-ML=&CXO-|1IJK98tXJGXIAm`)AbWhp@v{<RmgHx@x_zjrk+?lebR6Q9f%L5
zp4?hGQdAs)vW^rLqC4YE0T0Ddu4>7rs7igVCniY-AM0x6(o{(4tV2h2DV_DntCZ4N
z-@IyfPg&+597qk>St<KZFhU$Va*=fkhfjl8-u)+BAKXyL1-9V$IS?ql6^Dqdk0MT=
zIqR!fab(Ckz~J<mbC&$V>2p9F70v`%-%6Z62ZCYYP>?hCAdjC0p?M1S{KZNMPvOEr
z|Iac@!EN0T2nrlP2gH$9b%)!NqFk2y3X^Z<V{K>TEK62}_MUZK!U5C}jGKa6U)>6A
z#~`%LhzOaxDn&Ow#1#hAEb~`|xiqKPu|@qUYMuSzz_a?pfm2$?%>fRcABZJ;h`!l4
zb`FFChXFFnhUUl4%^<8ebnYypTBUH-;SER6fp8{h9n4YyYEp-|-IF@RU69lvNEay2
zIWA*y_%sL|+SMVx05HYn9VMHXq|4g6!_t&=G^~)xNy<lsMJ@5Vqe3DlDI?X@?#&?Y
z3=W$E!Cc_DX$Z>pmM0x3an>A2f!<mmiIc2=ezY7w=3^2bgI!X*Z<rN7UHTaDZWPGa
zq+69@W~QWrD2|SX_>vS?j?+oC4hP49U=|8=;UqPuK+2|*Tcp65Af1wj<xp=p4^V%T
zRG$KaPtuXLz~Ylm35o()n@&y*ByEy{gcGA7=ptloI%W1R-6sQo_W75_<R`-caISEX
znxsPU)HfjCGR1EwlP-=5>?}z-Re@0@=_;u}ex@Vl3L-S=G+kgYNm8{6L})rRSI~x2
zXkR!)4hVCFOSB|)tW*u1b5%L?1f>Z_#+;;}6&N*A*MvbnCK+9E9yFxkK@gEiDjUv!
z1Hl|ZKqhH%1?p^~sdg&`S3gOoew_FQ!WR)Hi3C-zK>Q^cbW8T5c9Ob>!<!-KAH?4c
z;m|RslzvGnVSzaz$((=_njz?M(#ScfF7L;KylCNYoL^|7Nm`@_0T_VZ<8Fb-W{^*~
zOwBlv4FnTTIVX!nfq5Y{O?bZ4Iwm|*&dEfbDd}c}ZB^(Y8FEcpDvn`>_%LwlGQ|6w
zPqh_@tCWe#EY4V25zqxkDnon`^2x@r1{p{H6#8zaFl#9Ju9m)w!_Xb^IhN}N&p!rX
zP&l<G-EZdOR-zE2(wyB0ovO^JIK==0!j>UkGPJ`ay&C6~fl$04s1uMOO|3VS(KzH!
zZfaXAX)Y2;m#>*}OeUz@)N~+hnG0F@-J+Q)Q;bbO$JB9UE1Hfno2Ky^X8?mR5zzZ4
z1bSc6VE`Kb2SLe?1}ZiS;^4aDV17fg|AZR>x?PG(4d~<sVNxi%biBwET{Ggl&Q2Vg
zBWxWTCbMzwj;zLsB(<#<JE?JQAsn=m%y~Jf@j%$P?;v{+n&+NMYTo;|t8te7MUzuv
z-uY6`5S!*U+tqX+XqmfgXUS$fU1|uM4l3OpVLQI*(xqmyJ3pq2&0yE1>sC6|3ZxBG
zraJ;fREM{8>Zt+})*hQO9eQ#g_~H~4(N~nRM`2@ErsGz^byw0s&_9{m56GV=XVA|l
zX)d*R2qv&a4JaQjng`+=6vFTZ_yox|oA{0r**=gLF@uHA3_vw7fmuHh;J!LZcXMf1
zZv)8@yIywJl%rJ8bIQ=23Z<T~_pe*Cd($rhx%GXoZnC){s^c@V!^$`zxLwjT?&XWq
zyrEp~i?e4{2?U|~SkXO4C0y6+a6gG{v8Q;BkmI)5_Vo3$>_>9noI8$lC{d@;&fclQ
z%*gb9Yz8F0R+v}nD}2%Nb?L!@9P`_|4P*vJx!^T35ikHYB!KO>*vOYoT{Cpd(r5rb
z%WTI5*g)724uk_@Q!WYfb!bQv0@2-2=2wH|woMXw0Bkvsbd&W1*>AEwU$DW(Ct^VN
zkH$dQcE@z~ulA$N#(kd-gpD7K0Kb-)%oZO@A^KSQK4m;!e0B%Yew5kvg}G}Ky8%E*
zR4ejy#S&GL9TPX{B$%cuy%4J8fC{uK?m`@`sy5xElmH2(#6LU(IicNP9~LR4+;l~a
zbC(sh?Z`HuJZo$NpiasyRc@uMh8xQGK38p^tcC-TPKueyp_5`7GA??g%6_0*DXC>_
zjYNf%`yfdn#rI}F(!((cNiB0HB&mg5_#~ASR}J~nQ41xWs<_lHlIAjxIb3HLu;Mf_
zARelG70>I(F=rt6W6nVQqFSe;0nO*9QRXQJ%XY?z3Ttx4i3;DZ0pXa#Wjd*@@YFXD
z9;vV{XB??q4K)OP#>$*=rou9u_mU1+T$J;`caVqOfxvWt60HV!{mw&Yd91;C$ZUWk
zz<_8sz#5!gW&^B2m(_qX-eoly$mURcg^^&Cd6efGbeRqOu}ww;u7GSsUGv>!FyVYR
zSq(VfO(Q?}Wb0N~PzIFHW6p5Xz&XQJ1Lq9;>$!zZXF!wL$I3KJVOyV7b}7y%<=27G
zl0ly&yA(QD!Y+jlQh*(rK?<;g?rj62VTzMTThXC8EHX@S4$CX-ZzG}%-{*r9m}QaU
zY~`=n&^O8)Hs=Z&CAL+TMU)fAW7VmNqWn5FQ9M<dzP~xrV8`S{r7(!1Zz&9-7oVJ9
z$TUA%hiDMxL{Wg9ny6hCQBKq@i>RF?9HQ+PzbJSLr)sBlm~*wOH<+t~ZYQ!s59n}H
zHfHCzum-ec4`ecSkD@PuZt(|1YdmJ+pqQg!Js%WvZh9Z(6OXZp*$m?40OsMKkfWJ@
zAiNtm_#9phz+r1Z><*@a0fV}B$czBAYl+M-JzZPmgI<%m+hBYlE<k|z-Q&)=fsI_(
zC>c>>Timr|#((KPCNq9Zmo}M!Si0EB2$|aA_J{F|x**C7Z_*`FW}K2PnlfXK{KUTj
z@(y_wn45CaT<|h7X)2)A=~^rw_<F_NS!U2pPMQojB<d25!IiwG%M6ThtA_Wksy`fe
zRe!iEs`|r$L*w(SMLvlA;U=i)Pe#f6lJ#=XizI8{uocBkXl4vZ&Kfuz26d%65Z={t
z;EdnE%`AgG<L)*eyp7Bncu{|_;Jl2~!9FvnLU+lTAr!iB&Ww-Hr8I*^adFKD=`Q<X
zHQr@sHt!dbIzJt}kSvUL$qZn?U3)(0E24wWk-nz;dd8K;js8IFE<m^bnXv=%3-}<D
z;{d}>!?yror*J>mfOL2yaN+10B2Asn{c?23bnbUo2#;`0cuZGQ^uxgZL~N?OE*P5{
zju~5~TfV$E3~?_Ll<28~A<^GnE+QVj>V77wL`M~jsQV)zi~5Oqaz~X>KHLih9&L<d
z4ObUNvdSBVfvoVDAp%#G6Wf69@8))s>F6%E9LBeX>ki{v<=&G!R8e^VWjeCUL&)M?
zU-TeitgC#C49Rjs+JMl@2-}T*>hfk9F{tbu*M<UGkqwN24c{roz=nTSc0cqi^^0ET
z^wQc4%HhYwfY|W!VnA&8f*~OGC4aH(F6Hho#vwHIjzehlZbM0KYbblqPQ5U_(Y1}e
zr}UNvMBj0E&}I6L%gJtI$ZUAxWx9&fSufLDT>g9>LmMuC7DIc%8xgNOe8c5AXhF2q
z9TGYFl;@X5P!L}vFU3rkaQHE1IE2g5(IRc(v&h%Ge92dG15n@#$pOI1C!fnqH*IMF
zh?I4=P2UR8cIDbRkUV>TTI8%doT9YDjg^zY7&Cd8X8B<2OHCi_q&Z0RIK>>8gbqK~
zEO%>tg5_?lPq4hL=~Ii?TKL?4O55a-YeBWwIXUez%r+c*8D<;KzlNA;2oAy-9^Lwi
z%Bwr8r;y<CL$<(MJQg=W23c2&mnKhV3&Xw6$r;)Zd!#Il?V=m6EQtusrQ`J|&yLv^
zmy5?9{6WD}sly;pH+;Yi+4JNl{y`=`atqRhSG!A5M(u_>x<&0?*W|Kp2%ZY5)67yT
z$9Kl@x^MhOq~*zfKGU1q+og-O3>I>+)_22QthdRHpAoy^>d&a%2nR3(!3Y@R!H5Fy
z8U3#HnULSLJ`4@gThR*)>P3hHALKngQ1SumRPGVIilSgZFXJqL_<lX2FH^9F#r$69
z6whIZ^_B5@8D!@O4A}@-ORT~G74{6q3PqnVC^$k?viW>_gbKUX6rmE`Lxf6n?-kK9
znO@*@c>-h&T__zM!o!|HcW1l~qKID+(_@H72C-jI<rNvksN#qo%1yCC(KSDcDF}&y
z#vY`U=_9TnCPp1A&?(bt++(3OKnQgD;!ix7Qb)H2?Z58o8(eJ|nH9mw5x!-JwUxB<
zaU!T`>Y#_%L6&<kv5x|>yWz{DfHOnz;DbNucrIVWte`p+eFT!$?rg5mxJ-BRsxwc+
z`N4f1H$Zs~!^?C)SD+pPpCgzrw>(ArS=6(A_!SXoko`#aNzK1!HKZ}l95sY-f{CqC
z8pGnF@I^*SE5b3;W4-Dag3#$)>xQDQk4_zQVXu<DNfDl$r=(cT>>lmg6wPUnHLAlz
z+Zo@<#llxneA5|(eOrW<GVVIUPcvQL6{5;WY{an=F_Wf(T?drscvyyJN5pKVdwgwE
zhkV#w>T<=INb$Lh-;Nkw#&1WQZ?0~yf;0B!h`(<#)mD6H6;R9&?+7{`2&0$xc#x0&
zm^#Gp<>*kJqo6Gi{PO3}j8z%Ed`unk(My8UF<(*H3>H`9wg++h(#v#N{dlGj@LU<v
zEDanH<q<}{@t^#Y|7Z?J&-CwC#CoQOzoOdFD8{G9<T*T^J&geR%pd>-*>iwXB>tEM
zpAE_C$~b3<YDNnv?4PqaaRb<tkLeJB02d)h1`OHrL`1-~o7f5l<a`_Z)FUTCkbJJV
z=MXgl_sPVcV4KN$l%^gz5rT|h73zz~8ni2e(cuG4ln>m<!3trB^+qC^K@BbI1m}#7
zK|x_Jjdf3ksfshJXe{`yk?F$2?)@pJp5n7rP$IcT^n~mhE(L3MO+$<vnQ;=J?4VQ#
zQV&CRf5^d~I9r7Lw?2@*>E9AR!7pMW%DN_#Pi?_Ua`882WoS};8G0eI6GN&$=hSn2
z+9ZQ3EuvypG3XWKE0nXr&tkIJIw%Ru2#yve83=5V!3+SbE~g&jv)8AQ`|LqQHi_=j
z7qYdzg1ClXli;?oFV1zog8v5JpzQ^g975JPU0qes4#^0@*pU`uwZgb9#vXnFgVx7B
zlFgso^&o#RhaHSUyl1RIDTJ*DMX`m%1jo=hjokO*NxrxlilO@ypVP>Fimz$pKE<#=
z*n?gmV6q>Oc1W6SCGC*R4VA1zyz!_72RP9|0RmqX6qcZq$_$U`Ar_&e`ssKhG`inI
zE<$e=xz&uEdQc0BEZ57Na!n=(C|#o3%8a}b8`q5J7dAvudJV|PxKhl5GjGYd0R1nh
z!)8Ph5H4vVA)_K0L}edjA~ItMt!A>Rh49N{Q@fWm`B~&@na}XW3Xh`dwji;#O#o*e
zD!NGD45_C~Sl`<ON&jT%5gF#Fdj|>KjOZ8JD|qb4kr7;XH{{}PNUXPO1b&q7A?~t>
z^`dPjU2AIF7Fm7|0l>(B69-M6Gt#G~ecAi82EOWDca{^xWry)h%!N0ELwE)I;iqH_
zi}ueXQbx8J2zOc%O(R855+@_CyC#Tj!V9>EoC}1q$4@+<jofYs79K~Seol=O;jRN~
zl-Mh`89Frz-%{t)xFb5#R~)8DrwL$tk#N&br()!s%F&8%v1@9@Nk;cLLL@PWCe0NQ
zHe*}v*r$ew9F0S?O(?3;K+^Qwu@8@sSOTiL=UzpkP0fs$JJR%E+nGm*s6b+uxP|D*
z^RveU9}+`2MIL$D5{{I34moAFsmMJAe{b>91`?_f46;Y4Mm(OP7dV=VA$LZiA=|1)
zn;LSY$Da2S?a`-N2FNPLxWOaNR6tJHeXEll(1#=*a>^%@EuUrji6gf`57)&3P1VMr
z&Nk1=c^fnk&5KRtsR;6b`n)`6$R01n8*htw_WSZ~?p!tR6Gviq0f`6M?mB1D;og1c
zIlZj5P0vYG5D39AcKdlw4+cQfDBqcL77LC{Lcm_V^O|~0B;G}v%ULiG`5_3deHwuf
zI1sx$x%TOOZEy~p<kK~a1tRgT`pv?XrkB+O-8IVv6OY#{7>L~D?iH6O6QtL9?9^+P
z69&v;!Zzxa=MfT`zAs}ouUT*q37KS@^_oP9Yc$s^OKh`Vg`d1@(q`O!Rf>RZ)T`V-
zqMN*4r!Va_D>FnwiL#A))%lZtg}d$q<ylp@LO2PCc5VM%HNIxhK(1MpA#!O1w&AWe
zDN(+?TD0wf_E-C<MO|%Dn}|#rn+<!`UEIui&B}}KpFXKgzFqp%m~D?)bpg<0zI^5T
z)RwROaW73elCOG5n6i11`n9{Qx0~909n;~!SM`{VCBCYMe2oO1)A7L8E%XxDy|44@
zc3ik7tt6m0hxn?U({aF8?V64QO_2jA`(B+7WWH$gfy@_eK9KneO$RcM__=-_$SfX0
z=NBSz@EE@~L|ry_35%;xpU0|L>;(_K9-E<K=osBV?#Iv(&7qga&#DIL<UIa`2#_BL
z&&i)<8ATuV#-lU?P5d{b=SAo9YF(ALl%3BldPSYJ2_Mk?m_Lv>eRu0@o{stb@(0I3
zf4Ddg<ZgBt@ij@^@#!topik>=nFejw{~o3@fM$Q@N;gcU4E`{zl)bWK9ixG1gDGYp
zVPGoOvDv`n^Eexrd>&^5lS!BXg@wr<e6ufE;8Id|eJ*DMlh0+-brp<R0}2b%(L5wd
z&+(a?>`Ojzie08{t?cH`Q@e#&g}KkCt<ToIdLj%9W$OgE8y&KV>tWsVSqcHxF-u`t
z>ez7*Vl+(-fYaYGOUKj~pQR9G9a9pbteY}9kjdb>`*ZFF*Aagf-SKJC9cw)ppXOsc
z@UrTH6{g>TaPkjKRp?p=ChH7!^1!AFW$VCn#To3tbcMV-FkRQ&BcC1~%MMJ=HTB20
zkfhy#*`l!9Xo)Xr#}8~`(mr*?CMNM36$XC`^~0NZy52CL2Eb+}=^7Q63j;a$ld)xz
zykl@LQW8{Bzr!dgOi@1Z1Ic_uvto3^<|8Hb!Zzptq8m2;l%gAlKP0;06QGg}K8HL$
zG5pMK_%~_*?8t@T^LXQ{SQN0h;V!BqX>u1vA7auK?UD*gKKKxkVEHYIqQli$iHJDd
z(i8@+`2}2w5Hwucl!zU}rA<j?>WB~6#3rtAO2lX3!mvc7mEY-X2JxbF_wk04%8mig
zm!&@7`Lfhp@k^SoOB<TMUzd)cSl%h`SmgP()W+RpLBh>!N%L)~4?HeQla=B|c?ZIq
z(!^m(C&b-RiGUj19hDRgF9|za4ljwrl+49#QeoT+ZoEr`wBT~7D1gQ9%@Kvn8*Lxs
z!IF(H9A2`QZkP8Zf=OED_`=;K`!dR|4@ZF#ks)v<u;6Ms0epF#D_jYDbdtXAvY;4k
zAT~Z-m%{U*c*q7H<YPMJF5z1>99#-kjqZtXx+sdh*yx!t!p^^StyLn10uCQV971#o
zDG?#j3S~`rwIF$KL`1*=rKE6cDHuR_wG^MG;=v8L5GxVMfD5srxCQr>DG|1S3$o%d
z3UuSKK}AS{Q8j`XfMqlkE;k(wop5h;|DQoXz;%P37SRRpAp&c`0K7uDDVZQG3>v_N
znvo;O+bK7(C4B3KtwewTZrDJ(F#AxIaQBC!73doru;~xie)ww@`0;PUovVZse}gWR
z!@~u-P!10lSAD``zrl5_go8fr<%)doaV=NE_Z}W>1G#&-SrW;n=XiH@7;lHDHNIbT
zr7PiTk9)h4tJ#%tX;;Ft9=xa}hwz4?5uWvM{wwgK$Af$T;bM6B)(9U%XcBUp2i0qt
z+~&atTf%J~l(FP9`R3(c2|szbDjF@y&Yze>DB&9qe@vro5z?&84&!T?L!@3<gU*j(
z-;G~}PRjVuO+Ml~rk6g0=D=DecW-#OmdW26U#IZ*PDYo*MiLs4B!nxjbL`N8w~3eM
zTOPk<^2+v)K{#b+Osm{Kx>Gcj$-x>@S-#Vd$&>SR_NRvLH01Bid-_FAqi?@S8$ByK
zOJgKO%B2%)iz?|mF4l}r2_C*fdnuFiwW}{>^1il9(*bZsa6B)&&M3HQ1G&>Tuhj-O
zR5+pAo|zo5O-N4O*NBNO@~y6TsH7Jz(F~D;zs-H2&griBpu3`TzHR9uj}W_58?0IE
z8;*xX;teqYg)Y~d?$yfVVcpRiI#@$~O)l0hzl!3NI^|cPZfbE4#sk(^g?)*D3hzrn
z$>eN_cqGJNl<>MnoJI++YuvsWf`$(7Tanzs?c0F3(#Mzogx$v>s7OY7N(CcUQ$weZ
zP;wHNaV1={5#&<BH5)-NCET++ysC=)vvEOZ+;2N;H9RN6cI>?>bq?DBfgHnjPCSL9
z@^%$}<S&)X3w~8+0NS{?h;#T6$?hESX_~{2d<~^F<3i7P^!Rq;EKnq95idphy>G=-
z4TLdb(Dh5x+lbh#5)S2v-!k&Qoz*%X#P~<o<KbYwee2$@gopW&oKn!YH)72UK|9Ik
zirV*)I8`#yT1*?M3%_+M=){KKih?WQfQ~phupw@Me5$CRBjAo4ir<RKBhTWuZW0Hg
z5oWBNzC(xrEaAG2C_$1sek+o&z?*$jxM2x*c0?o^g61ipk6T=02@m%};#nUw#7B~v
z@>?;KC7j+7XGucK?+C^u>*cp1HjBH#Bcii}8$50|4XON%@1lrvLhPt9aH4JKvEeI^
z7}OHJ@`zJ)9#5MsigDR?j;8)_;7$GEz?=GW!lN4*@C<5v5c|V{LoqEX*+U}E8;-Z+
zDs{+v6OrB>z0oNJ5yd5Z@p)}aT2zNR9>g$Y^koib#$z}Yl--vC@s30NIp%2U5-$A5
zq3&?EL$NGZ>~<Ka>Kxilepp9r7l)fa!o$fb>xk`!BF}%snU@-&-7qHAi0p=-t`XUd
z0RF=00EE4lhz>wtydmfggmc6TAi%y<GWs(LztjlqHs!SH{t|)wq~vvEh`yRo@Gn@E
zs&ejL@?L;GfV{uoWEd!w$1-pb6u;=*0QoP-hyeLp<tG8MgTn9x&>@s6=hqW=-J~i0
z7O?`kjK4*`P!z)eeuh$Y!UKoHMo#2!5j~WuD-4i9kV*Mlgb~FfA3!Jp?qzaJ*fdCu
z0x3m_Xb5vkD3zy1_#~97n~>89!ASf3O*RZi(6u6>=x?!U45Xp#6Cm0%l5&u5`diE$
z<fHx;yGN<i%s>EA;FY$0izS4_*56_hDOE>Qu#J!o`&*18r52QId^*5_(}axLj@Wk8
z-7<(!NW=XtvXre<9(&<-Q6jbjtSjX6{uVJyiD(ayw}1tF1LPA?L<{2^L24n0Vn`+a
zEh?G97?DkUGetonMo3etG(~XMfVCXRi4ISQeaIrR1pGLpKX=4uyrSf@E!`4CJfKh~
z$&Syt)Xmcs*{Y*DJVS~CRL;|>+R=M>(%vDTZy9DmJXEUm)02Www%QY%u!W&6=c$J8
zL`Wo(|9+7y>5gRYKXoKHlaP@98_p!9Qq_ekNvTqGLFGhN`(Z_ZcS%5`geo=Ysdg@a
z=&5!rLPN>6ycA@RQ{54p{+XT1w|uZuC2sj(r^4y|hWHxLBjKX-lR*O<T*v@G4lcA#
z9x@6)sp6NHf@92Iwi)r`N^PPYW5ajWu~K!PctN$iA#9lIc$F7(9DK{+<c?(TJV?hV
z?4;{oxX!;rY?;ei)H0Wq(k>9ZLCnkWO}CRf;LUfGe9SsR!0Dt+0Z(u`DOD#6IGvOT
zfr8V?9kG`E@BvCa-*q~V7^PmRJdVHz<p!{2?hfRoD^(|!tE=e=xx9Pa9$ifb;!RVo
zUR{lI&vdokQ0Az;Oi?Ghnlm46KOnXoWQgrYnGKW4?oh+pWw?o~^0m88wH^qEjjeX7
zZ3MuWYYMZ5_%Dv10NdflyVOn~8YOq$rIrHm2Xo(DY$*V5>2Q8gimd}BABwo)cUREn
zvWp4jdE0k>i~>r0D9Li+H*!b(!M-QU4q<cfSVg}P<Yx&E(;L92`aT5}Y5*JQQcD%J
zKHNF(2r6CYD_B`)q*BKei~r6yc1F;+_pW{2OZ<5Y+Sx|n6*RP^DxJW7s;hx`9gxf>
z&oFmK%5{56qE0#^`PMY<c(*&0r~aop|632l&~bq(WD`U1G>NJ4i2;=R+N2hh{8Kx~
zil+rmJ*o(4*lb{X?s^7*<F>DyQ+e8YV6K}sXF4>TK=@F2%=6-K+V{=}H@z+CRNn%@
zlV9SQ-c-D%Hx(S!cc4&6U;;0FN5GpyI_!`eq|Ba>yic+Rw|aNL4K9>uWbVEJY{jJ@
z8Nlxd<#s2Ld(t-pyVdXPLM)Sw{EoCq-f!Q!s0(?|i#mQJ$c`T6td_|}j@yVE!lto7
zb5_%V@T-9>OD?TD#Ky5n!5yzpEbirQWwy<In#)&w$iK;8KYi<Y4R=SRA?)UP#f!Jl
zHF)uMNAMj%Y1UnE!M6Q?PAHVvin&TNB?5bvlquv8m^CgY8n`2q-o|7Fq1hpy0e}q%
z+vc|FYMZ;LODPV7N^y&13erwdX5-u=os9>;wtb6iBN;>}&Aht1BW#%4<50WU4oB#w
zT>eA4X&}^1x%@a9V1TDu-Z{XNdMQ_)XR(G7&tY6>%B#qSadN*$K8*9nX^4qH;t+*g
zAv$I;oe0ih8z7z4Q07UDOBN@w3Bhp=@$}4i!jmH}`r>fOd%ZY-@?I|vsmQ-FpJZ{3
zcL&(GFI(|uu|9=XsK{hdk`BXIq>^+V#gY`tyNVL+4p<Ui;>GEomv~_!VDg(gl4nZ;
zbLeccMes&W_KFuX@q|r-*?Pk6!IVCRYyc9v%n2`Hb3u<w*j&)RB7;w1#-pOKV}6T_
zE}Y}~3X2f$$--#l*JQI{iML{IcVZ5uuuJg<ENoZ2^n!hhxtL_~!faC7k;xyIT476L
zawyu{wr^cwmB=(+nrwf3%;B~{&LveOCA2MlwhS`4Rag&k@g(~qubILC>DNp!QEmV@
z3!F(F%T$6Hmh;AAnNs2w9m|xjuN*SNa^4QvVKHwsLMeeCZh5va@bXe8tiZg}p`Dm_
zIAKXfIy4xYnGdbtDV(YEYqD7LDkf~&196+Uw%p0%kMi#p>xTaeOQB4D1!8d5BvGkD
zAlbL>LEL(e-*h~NQ$j(g)P9A65Eli07r|=^drYMujKqF>TvB*<Dg|LA_S^X>Qf5CY
zf4u%+(!RJN;fUiJg~|Umzh~i;@*>6&_ehAuey~zS*7wS5(F+$F+$JT`z*k<3D%Ei1
zy{HoVRbGr<e)+~%A#SPoLd8`U-@&-<;+w21u}!ag+?&xX9+ztrHh%d=VHKBi5O3Rb
zgGV{3Yd%TWxC*3@j_X3?x!k5ZMSc))?WpfcTuk!Y6qlF$q~U^-89vz`?t!ZQaNt$_
z!JEOzjKaUeDMFe0DxF)Dn2#|Py4a-x6qmoUS;h@96|}fUrp1vL%~UAkDw;YduB$gd
z><{)ny<2p8WNd=2#;NvGB5n><+{|;NIJW8{o`<5itml!8_xWM^p?Ds@;l-%VON<DB
z>j2Kd;ah+M`0Re*Cwn<4(3%h~3`n&bUJlI03oi(tEO(sX03m?oO2M4J;cmgaz~PdC
z%)#3WjvIjJH^QYn<u_8*nEXaA*1Gs0zO9%1MmVZVek0tom;6TfvR<66hT`n@!o<ws
z8B^f#UX(Ez=kKCRh>`udh$@lUq3NB&^wHtJ!yMD$<AXfZlOGWCREMt+b6JN!5fWa%
z!sm!NvA1wcDsYj)XuwDo&P~X=9sW<u%nc8z4N!PdeJj0pI9f3UcsOG*Pq-YmHYF1;
z;?gWgIPPv=1$=Pf7FOUbF3+*zzTuN^S#jTRd7qU=A+Fp`bOeVBTWOTwS*in_yv07s
zwC&+8ht%%jQOE4>RM)p}B#37k%5SBRm*-xgOShc+n20_c0E-;B;UkEY_u)l20DAjz
zBI#$yzR^L2E(3*b)kQi+n;jlYqj!qb3Aj<qZL%~8=3T2y!7SyWQ7|h9FdeJSg|j$q
z5l(s=5cl(yUSLkt(g5T{Ee)VSNW;-|ly9D>1L&y2)jPtOwKT|7xw{S|%OiFJ;?Ath
zWh;;6GoDEwS<X7Wk>Q!U6?r4;Q$}xOeaXN)Bp2WU;-T;o9*Fr1$dkB$We5fg2fQJD
zN}B7Y@>eb(9)d@+4YKdy3GLzngt_4xUEq-{nc8t@KnLs1q3fEwunQ=H!d1I~;8)(<
zrKeXodzYT*)-ORSw`HC5!7?14<poT{;e9?37p0L{z9+h$qeRzvh)DW6OG<(x8E*0$
zAoo4jK^a6t;c!0?de7sH>Ci*nKDaqj;DNvEIkWqJ0ryZu2o(8IN9sK~QcK8zk%)l^
zqwM|FL9#=}F`A+D!YP-Gqc?RVX$O~egiaK9rjCT{pe;iD#RkYb3;_o3Y6Wo=dRH^X
z!vHkHu2hfl;4DFn%{ppzsIieVy(^A|U8}H(M27SZy*ARJcgC@>Z_sm<`Wyu1h@ja3
z`S#vf8l#CE=Je{09Om@uj{M}Efh>`r9Arrm6*Lf!j?y88p5Bpdyf?=2vFMRrI&IL=
zn;}f4Hw8jPXM6}JtUkRd5Q>taD-eoZfnbhY-W`HDol+y=9v<ntL3$tIT?Hge5dv1+
zVO&9CTcO8zq}}e&uOrEJcVlkk&jwXf1gsfyc|e*K58W?W2?L}|r9Zi1<_xj%xiY>L
z&^txoU7>@ya!_}eL?YpIKNOqC-F?7387ZW}02R@K1#ajHC@h_!wo;}00sT)=iKU+m
zTlA7*5IISVtCfmOH}y!nRysp#L!2|ZRvC{wqibc&?H*oRb&1%a`$yJcy0S;Y;LZTs
z5Z^crc&gvdOSZ_;+Zj+x%V+ljyTM>uWVh}3R8DzlJL79<n(U0Gm8yz#8y-zt=no%R
zItR7Y_EJ2qm2IZ;)DItPRzG~CA)*;fn-QpEh_#xhejuQDl#b8QL!rlouJjB}9sp#F
zv`esMF~)h6v&SzNJp^IYm<xK^Cs9fa2$9q%wO0gUkFqcG9^LSf?^7?_l!1Wn0U(Hc
z>IVbK)epvzCp`s$<lZYdDkwI+(0QNX>jsRTD8jvf<%==!+W<VeUX~*8enl+3A=f#@
z+ZRxQMNGau$fN7esXHEDFC)(ZWkd`Bg`ojr39ttlMZ-CDh~xv&A(9W^EoSt9C=1Gw
zXHJ6x7P8<y7>G}fbW_F`h(BQ<*|;}!W6y|#UFzxqTbrmF46*LXJaU-UvolbxFeG7@
ztUaIyfi=R)^_+MmiW8y*^~6>fv|zjx1^j3tu5iTq!TZRgOw<>J@eF&TL(_nK2kE}=
zz{yZN8-+m+;^G(xctChEWFUkXJq)qlNrE0lL?E1hSOq~Jf(NyUVWcp4LM$W$@rkP}
zS$C!G9tHFkWg0i>QyR<GwK5Hw<S8*|-(Mx9LVX1%OJOjEcv}YIbE!KNhG>ZY#Sjw=
zB8eH0O{OkD7{(#08AGhYY{%y@>5O?e7fnb(Tomn;f>AE&tk0rO-3KqucOAPAa?|Y7
zsBKS5DP^dLD0~bttyDZeh0!A-0~!dKe`3@`IBNJu2lLQ?oP|jO4_v@k2s~tU5XsSu
z@Pl|br|=aL53IxDQ!=FGiF2ti<r{dJwma0-X(wia#riN-Wbr?ZvNJBp%zQLbv4toD
z1GC7c3OEOYkZK^tiWS040FS>+ZFhw*10nQvOp^?RrR$uCwaU>qQg3;2V&*E$ttaxX
zf%pQ+7CRx-nVF?eRAGi(*F+~aBb-@e`@32!V?g+Zf{XhKQ3bwkQJ~F;mJt-+B2yd4
zOt%*0q7FNiR*jZHw^gU6eW@!;HfZT}6Vf$TzRF>noS>L=TW6Uf14!z;uX~Bo%z<Z6
zbLPB*y(e*=7FtNOYtlYA`3MDZUpbCf5c_#aH>^wz31-0UhOk+%#a|R$QRWT<!~7M3
z>j3McxC{-tu2&Eq&Ip&-lcim|TFN3-+<^G*+NYL;sK2)1MBq3hG@vt+CWs*Ca#8PW
z1CmWLfJxu7<Zq|0)Ku>3oNY-FTh54{>Z0a6rvca|JwwzWsla(mPbL!mHT^aiI{{6!
zo&zz8(mp*0K-FA1L#ddH18UP_Y_pzHY63`FN|2OBX?q3BX<<UtvrgT0B(#KcqEq!!
zmdS@XRzb)bW$umt^!kt6(CGJ1KR#RN$nEo-&v|7(&N_~E|NKv{e|@Fb{`p`3|Nr^D
z#bEur_>Ofyu6d+KOg!2>`m`sF8ukbU2-z);{CBm|v=sJaaTMbP*(QEu?bF_4=Itfw
zZ4wi<>LSbLCu9o}aeXCw`k^BP`8pJ%iKu=c7S(R-6??k<NEed_`QzK9uiKn9NoJ5>
zHl-0Qo|98KDtPoFiIgKIcWS(DL=L$ubfyuRO&>=S7vHyREIGW3`tc&O=r^rJgW8Q}
zT97Q{@K=CMFY^){Is25hiU#0ZCd)TiPUB9rA(PB><Aw|@MPICjG?tMnt|+^hu6U3I
zEN*Mslr69@%~aNj&n}j>DKBJUVxcS-?*<;+Fz;7p(=5z5!<?k_rdCc>-cCnKT3+u*
zBHQ6W6}ftgh+Jg_C7E!(yPxDF-LsriYH3D^BmcKM=(tj;{NB70jm+zI=@?1idHa^b
zc2@RnN*hmy#+>A88A<QyMd|AirmM`X>{Yt~7W)CwlM;-xVMfB_41{j-o(>3xD0A2L
zZ)B1&AMWfq>_iC}GQ_cFmMZIymz;o~Mxw-A;8I@p6A#dtX~!pOLa-@Q?9-hY>~(_M
znW0^Gr#rKy%du~d<{{}lCM7CSd5#`Z8;+(dM9CVLUndkpEW!)nW>zc0<D6zXDL(B)
zCZ(i6tdrkaZHWP)7JmZ`UPNbzXT2w*_iZ%gxHl1)tlb0Yq9XhIfjmnoBI6?)I0LyU
zx`LUCC#@-)HE46Q#m!C`of)+ap64H#i}!p>1spkf$*{td=5w-KZ`vfVQK3ZMShC<S
z6{|*t3!z*TKR@RWy^!1&q9Jm3He~k-9+`$5T*0cMB$G|lSuVB}Ag4r!3U`XkhE}S~
zG-xFg9pwu4IuJKU*!YyDF6j3B3l;e@A=kpqnklbx4eC*56gxx|d9>G@V#_z-lt8Mx
zF`X=d->=BEq$ue*?U7G`^8ZAx4fJbF7ppN@&djQ8+p~#$9qZVGEfYCLq{1oNhM38e
z8->BNk&nZROjZ#jt;uz*9t6tZ@=y4)bySL1WElu{aAsea<{#M><|G2Pjz^>-vb?WH
z<R;^DCz{fo8tVLmGdP6FpI@hk_%S5NxS5^d6bFj9{ez4Z83S$%^?m=z9B<zqJIP{d
z{iGLU!z3_|qyd(7@rq<iqz0EGpK|?NL9$<NmM^kQ7ws>%a?LyLBKI(%VDz0f>h2ca
zpt8MS|0b_4gU7)O%UhTrN+sK9kevFBNr(tiUpBFWiPtic3yP#N2pUNR8QhAzMIC=J
z{yDJ>PLk&H)wfcx<YAHVW`#S0lgc?^9FZUX7UNx`HwdLE{TIadf<!@Enet7;9mq;;
za@d)<w@A4Z99Ruy(6da$PhV|viJN(of~*K$k@z5yK&S^Jj#p8-!ikfH-?777Vo7|$
zc-`PVY1`z6{F7`X!B3lC?D91`$&WI)BH)4fc_m*nLB*l)h#(w5a7R!FFocLP+KB=C
z5qr-797fkh7#9PP>8>BKzNFTf0<sVN=<nioJ$jUZa|(TB(}!Xbb_O=M9;RSRs%rGl
zKPJ7<{mgY6zh8{)k;a|q5H3?{Vo=;1{mI@<ahwbx<b(P>G?&-;b8zJKQjF;oDyZNk
z1_VcFAY(=%(5`6#7zH(jf-%tO5V3)RlNchzV+H-!Wl2O<aR&Psm)q+eH^R6K#tK9z
z2hSo0qfM-&=ucVMDoJ!?#Gm}+ajbIp#c+u);*p|hg^cmD*K&c|Fx^&B!r|?bA1>W{
z#pb4)_eO5C@amLLq?g?9RenE>j^s&hFpb{a;p>O4O|E$KiPLEu`S1`XM?W;WvrW!l
z=0XHtF?nCn_W|pdb>B{2F*zO4Z6{53g2P>X!a;-%Ea8aZh)9qNI0Tcdbe-JfJahJm
zHXCjh!Pm{eO<iY)xtAC1=0r5z>GGz!<1%)-XtfdIc9S1++4gxYR(=?N?3PP+Ab#OC
zS#cY0tm3}q#GQ?d-)>RXDO^_sIGSyfJ-mc1%x?g~%mv%smBK{p24&qDz%F^lGh73U
zn`E3eC)*}c(VwzsA?fT{W=pjjad~s+*2vn<GuPMWALaTS4?q7n_H_01V2r$E(i~lQ
zPv*zC0)vtFI3~-gsp3b(@Zvt=sMF1XP1Pa00oUM2(}jzT>frU?rYoR+PM1P<T<EcB
z`YW>K>2j^doin`9l%SAi#Yn9vt74C<0i;D~@~_1?R*by9U;Pjg#z?5NO#uS#+TdK$
zUi9NmQQWjMHd4#`mIDmA-M{6m6RC*{55&wi?60w%h--Lvy)q+%-AOG+uxH0DWds_M
zxizw&mmcZhY0bomDZ-cF0h%NBr;ooM;VX$lMv;60^Kh1i7G_877!Wn*BD>5G#yoR}
zgLj^M(UFd{=xQ1V&pbI^gXb(~Z7F6T&y0`oQiR#y7@y}Dma$@)SsTOrs4GUMz6~E;
zCQA+9S*AkDamm1JVBw64FYIKwL|j%5M^S_k4Md@+xX(<w700)7n0QzXmh&Vh8-x_(
zL=%dI`@+acMgdGv_#7f8JI4nk(_+@;)seAy;s2MbESsbhNOwyoa(PXLO>h+ti1Z;y
zP@eFDr9+0eAl%?Dz^}oEE1l3_4m3k2%$l^-1wuoi-R15y)XAQ@AMBgHPH^NIKT6Va
zWtsKf;aoZ+h-%Hs1Tj8chno_~;X`|!)PFGl#LUo0xyAhPYc?4iFQoZRK}3aJ8TlD-
z^STX)rw=5qPdWgc=Z}p-LO0mQ4FM@_j;sct&C8LF;PiZ131&;%!ojV`O?~=Dnaq(i
z+LQb;UYCq-k?sL9KM`4{E4t+9K7lN+<MqX8Kuw#2WF5|UIqNjlFK;UHOUP~+bmx3m
zgPI&xvWaG#M!;PrQQZLPNC~F!$tDT!{2?;=8+5Tm3UTnU=TfI*y{%mE1A7EV4)R=Z
z<mVFkR~tUWLBWa(xLlc)!M`uE1|lOwu3<zikx=>j#kB3rhXq@ReZ$D!kEED9Rw9iG
zQ{m8-Y13IRSuXuHFfxeYV*?`%7NkW=7<v;lrVOSXGtz$2ju{y&-S<W}l}w(Mo4f#&
z7`#WuMP%!q(=q#d+?58Nxv!h%UOA|H7(Z?0`ypGKKP0jxnPu&WENh_E%!hLHKy?X2
z<?e6d!M>&5VCuwrB&7WSxASHYWS$<A5Jp0i$_If9WIlM?kPtA4*V!fu%w6N9$GRnd
zy-r=a6jzhI{|FAn?Z~(7%;u_g*lt~47k#a=1kNelXr-iikvZV6hGlgVW#-oK-yhm4
z?s)U}>8*ULZn5RY0L4H$zo{j2kGlUK&4ga#?{W}DwzRg>i?HKGp{pwf(!$G@CO(9N
zE7O(oyzFtKK+B>mRUUVzgI{J8oxWGf8A6ZzEmC#F2Ls_}Npg?|$0-jDo!se=uvrFp
zJ8UZ<0b{IaZS(_hf%x+<ogk=ZXit@Ol@T;?k7V>cj4~5(f25uOy+c<1#?G8snRgEz
z5wt<COw)t7hYtpeYGOq{o+Tf|?hRw-f%rtFA`xA+gtz#io9vKo5exEmbnd_x)C>Bg
zCR$_g?REPrukI~Run$FYp3JgAc6|o3HR)Z0I~ugBvefB&aFKyapX!SyE0P{xq`sq&
zx~fc6wB3ruu|N$Xa|>;ir$}N#n<DE9Z<7<*d{60Mq!FTeSAWpL+Pk*r8*-9*LSBM<
z5U<kINV35|^4H8+TN3H~#B|GdYogGBvOOc@e$*%uO~OUC9x<a8nJr;>CfO62zj#{C
zf5$k3bI(L3lWD7!`$gsk&>36IM<mZ4?}B;SPfR2}6G0L}{v5G#ls0WV5(0p{!Vf-7
zZgGlN<-D2p?L@V^wK1qZ+-BK>i-g=6!4JTDi-^5vz_C_R+zN#XDy`1sA^M(31Y~BF
zIa9nYO!QWEnV;aRG=~jS;E9NXNw>0``x<S8_$qD@j4Y4chSkdoscPpOl&Vl%IZbrr
zsGmYD84jy>M<(2n)s2Cn>6*+7_E89$jt+PEbj((X%cHjx+SlY{@;yc5DK_fZZXrk5
z5GhTz6R)9N#Q-eDwiLfq+QW(g=dU?913^H080r{%6ZT2Q!(<+)6}6(^BW7rpLwgPt
zLZ+tzFK!oD8-pT1bZbAN<`N#vP%bAwVJM*T&;2~8-F#%B!=Kk=K5L@D_Og3|hRv(d
z6SPe~^1EmHJ-fLwhZXNdhI_YE{)H{F|FlJ(`G!1J#K|0X)M3P=S+lGw)|;(!w7CDU
zem+#Bk+iX*{8Q7qV!hc?y~VqA^|3|&S!G4}-tOy)^=7L@i?j81(PBO2&GVkjzSp{9
znN7jI8aLbU<MQLE!D;}0nV533GkbG)%kyJ<_A}UC-;>F@tt;l69s6z8`MYKNp(5T9
zINQD_lXzWMEH^v3kMV9fe;gxEiL6MIds$a3H#0n1ycy=7TZFeTD+19O^0CF)%<nDU
z4gZfV`p>E=0y%yW8%5U$*4lKb@YK?a$=%+#h4@8G<lEJR@09yx#p6!#pCwf!a;z)D
zAmrcKcU&CtD&(;}|JBZF1p2aCx?QVGuI&9+F=#()61=*hsq2dAc5U;X+|&2<D?~5y
zLlt=gRMr*u+qIByulq&O<A(O1byWn?^SUCO&T;EBy|lWAT8oL+RFPJqw5*7L0N!f7
z<D0L0uICL7OByQ@xt0}qy#@Q)JM<7)+#Xx>pJi1faxN=+LOC~X`07uWbdQ@2*K}S5
z#bZ&0(E-Sw>kZAwqAmZ~u8KtZvLd1naF^(7e!E<J++^_XWVM|WvZ@BRNM2O>^xv;8
z9~a!CEu{G9&a<p5_S;41wBU99{^<r)@1Hi^`u(FVzQ+5PZpdQs{bzdrh_qkczdGOJ
z`eNKJb|07Ce^pRTz_qMaVbipRbYc9|1}w>M+%BK1AD8*c*=PKA2mQFj_N%070FHGv
z`a+j!y6-pKj|<F;3RWc2*A?Noj_dMy#`97o<^q>X6}jYXU6C7M=Z6w`MB|p_aVfmT
zLluj5%d+BryY7FBBqtmI9$WOEbyWl+e&N5a2;V8X6THP46b=TD8^C|oR1rvB3%_>K
zUBQ<^rRRmW>oZpH>0ec7$IS!cO<%6bC*pDX{bxlLiL9rew=nRqc+2_{J{OPE??20|
zDCAsM<SOZ)2X?dY>3Euc{7gqZA?vdq-1Xogg2|bY#d7%1c2*S9*A?^40mZv|cS(7i
z9KV&mRFS?cZCx?T!Nppe++Chpa@Q7AXwyaSLj_(D?>wTx92jmikJG>7YMT}5e^b^K
z_nTAB+k7hTZaNPY>CMwsky0ivD=L0a=U4c3h8NJ|g7ea!6?w<LKEJ{rdH580H^al|
zaZ>yz_HAXUEL!L{Kc%-=Kf`nBaWed8l@*E5*!)zHeiL1rIQ{U9dZ<VTs=|swu64y4
zepZ;4C@-cS{vKY5<#So7+#I-kQtmEYkIUdcORCuA^0BO#Zw_KUDR-B#$7QJSaA8Fv
z$GRf@RSHErJlVq~?Qt3CaK?&NZ{n&Vc;MmShOW-YVsaRK$cprpYs-q|y!p?)brlyL
zb&r$do>3AJa>c95isiWZ=e=J{?+`9X4=uuV1tFL3$<?o}XSHiNpv*C}DzCLbIu0gj
zfpR5WYk`Qhfqx;oIwOn8@pY6LPp*n<TReRBrwvf98?u-j|5;bXu0Zf*MLPV+2nA=S
zaF~3kNWV%M4~gWp*{kd~_sh2e9Ks><adP};O%?fpNz01h7lwQ1TM-|bk!6olLl;F<
z13<Toht}>Mfp1-uhL7Mwd-OTg7m7$;f1xtx@1SS|uXZ@AK2FSu7EzIit}h=d(xFnC
zeMvWDH97D&MMWWN%^u9abgg}ht2&FJ^Pyryv7@4pYh5wlJa^x^a1LMI$I0=Z$x1F{
z{Yrs)*FA&1qqC>*<HY!nV4qNVWuwUCcxW(n=RO0E)#$36S&hKCs)k|HA=f*3cX584
z5dWEu0z!^u#Y6#Ise0vdLlzU`Khw3AkYibK^0xMw$y52U5}mkVTvd5xT?N$wJ*VGt
zZV6xN$4T*@B~}!&zFbO0W6Ae^*5$HyjSkhihPSH5w?M5OGq9MJes7Jyy0!i00{<4{
zZ@9oePKy6b>WGlOtO#n+xy5!v9$Vz6I$9+1ON)9N(9Lk@f1DJ&1y(_Cz;g@z78c-L
zy9Ww9PR5QsiHdt@Ys-pN{3SSmOoS?{1BfPLXGJ0FYo49UTWLz)uOD#^kCRg%#aNNZ
zv93sx9KGrL`6G_vp(4XA^rj10zv*;7o?7fTWHCAZvuLqM$68c0B1()1X0Rz%WMu}^
z<j8&|WNAMe-b7PSiTCstW%4*R_A6aR6Ik9wlQNPKD{t|iMhwg2#Q4t=Dh9GN(;B<u
zb^G@1`;Qoz$BE(B)++|G{Pr1*Bld`Yrb$Zr%lAF_gpw+D?V4r9d<*D#i)S=Kd>$%N
zam}jObOK&hOt*lcx0pmDgy?ZOM8<@QRVUz8#q+uaB)!E58X-!LlS4tsieXn+Ra7if
z$17#DpA)i}oS8xE{R-q-Ry_MHp31v=kFa{29FlFJqLAgCyE*IKPG`~8<>@RYho>_k
z>(iOh&P?%OZ_#T0_F5^Bj4!f~yma#*^$o+#-r}%{0JO)+;Q@ygX~AFK-42JpIh@VA
zdJk}WoSY6T0xJT^OE<FN@P}}@w>f1hcJATlh_37Qb1&p)`Ep#^x;6>FZ{*u+b9$KF
zsseq45*_czz^N#|=YiAG!-~5sJ*$dzL9>uS>*Otj@M$8Z6UlpuJ1nb8^%jiyRxr~q
zwn0TP$~G8rjZ52LhPww2U2jHzMD*k1lpMactk!91Usj_XDD$&Lk2b|tK2)UL=~6{r
zF0^&Uq-j4I=4ApF3&ABuH3BP_ii}JWaa9s~r!GaE!bg)T5?Kq^e(A!=Rpd<HJH?$o
zE=9t`vtrg2*Qz4&r7(*1tth03Ykgb_|5;W=BImMV?^Bd4dO87%sj*)bRwHn&tF>DM
zu6OeullwR^yZ}N)B1$RuP?6U1Q!VZ{<gp@c<4r9BDQR7?+#-m5ZtgL~k4wP|JXQo!
z)&c{uc8E~^F*(bMu^g<(VCSVvT<+->0PT}=4~c$U4*x2gs>oRC<#9D4rSmj7_mJzy
z<?wesmV>d{YkAtPTLAZ4LBA2w{kR<TXkf)GkA_u6_>dw%9FsF6i{+4$04fq$+F&A-
zTxTRr&iag`<<J>P$oh<=NOhebdj1jd{<s|eGo2rVtj`agSCaAbJ~y|3`p3n{O=Qe(
z#o^cG9mH_boP+b{i8<F5kJy!H@Q}yUvSPVS!@pr-{%$FVh!6XrBE39!%u6s0JT8IL
zx*k@6)CA?ZLb~x4_+;D}3?8T7rOBa+q&`@`LP&s1J_MhPJ43?b^f$QRv0{<0>9XQ3
z?f`3TB42oF$%fAg#e5=H6%fftrUOj<jnv_Jf$e8W6^X3vO6Gz}iikISxPvm{aj~06
z|D%$Zm(D=!2*@XV)^BVSkIU@8s;mZ}?W<~)wDCFuAY7lwqCNjvQ$-+cedr*|g%M}?
z0?b4jj|=WU>RyTEmRFV9jgrF`;7-!<xY+Ksda$C{J(kAqAmhkrEeJp!TXIRrR=mPu
zO!Y=1f_0vd)wZhcGLMQvmfkhyM{Pf=U+uQci<>rWD}*sbd2!QboVy4m!ON*-UfcXc
zoFbc_khRT^J~T~-1X5JD^(kQ@m}W&H>vICwqVZ|*HNO$MJZ>!eRZ}$w`ZBte5+39*
zw=K4GiHnWgRS`&Ex}Z|9QcZhHu>KMbB+?oMAO(%h@=8lQ*PY&9nQ0sP(iKOfIPFqJ
z(&Q|?zeIW6X&tEjPNws?+5A_u4hUFU2kL$!=6MJCOJBP22cu6`MIvj34WDAf;l1@W
zUI*p{T~J{)0@t$IK9LIHMN)b7;v%GxO))g}xe|CoX#Ma_eJ3z_e2utJtjKWOWeA3G
z1BnjlO;#V#BR#g(6m$6&r&3u~DiME-$!{~TY76nmsFoFuyr@>L8;O%Qcc*oFY|nqT
zPor~W>Bux_nkJH{Prbe0S)(4Rx#_v<6(`x$@(oX(6`aw-?^i+~-#VO_#8rx47L(P|
zw=*G%4fIx{Uh6mHu_9lvQx(aSwLIjGpUv!9qvG|0PwSx~X}5M&B(hw;)JT^=qf<g6
z@8IitT#6n0m=%dE&0J|OH}<bj#r^uh2lh~rv|&vZft*XtHi74xMtfh58Ch%q|5;Z>
zAm{RkmM+rqO2efaz`53N>3DER!xazOTElg^a+0IH=>Q*WX%E%FsU|xffn}WOh-3is
z+Itu*f`;uuEG3&U{5(ZIx`&^anab^LC*2#j+e0-n!11I-;98!vN@rF*Kfb$IKbJ0w
z_<)>riA4EYdi*k97YXQGvAI*yJ*rZk#_v!?a@nm9@cgn~x)$J<^;(9#>N|Q~sz|Q9
z^+g1u3@*BvGO0{Z>OE?GJEnpai7Xvkm89k3frh0;Oa2q;mR?#;hB*J;h<X(T;G>@I
z2|44VZ{8qlH7%$F{lqg<3qGEA$ofMi&4~b4`WDqqkQBZ}Fc`FjkFEL7+H{_C=A^W)
zSZ^eVZ-ur;vft<P>Nsm$hxQ@)6xSwkoX5el6vuH9FRf4G*U6P5SL4d*(%07s9BED>
zo#V=Eb-~mE{>O!Tb0)Re&S*yqT)$?T$VUqeCz_`zBFkvUSlTKxS-v5Q7P%)-QONO|
zg$*5}y$hw4t;?t2wxyN^q?sqv?S*&d%two%|E#Jako3z2K5smn-r}8^^RY$$S=jM_
zq+jfK*Ua<jCfFPC=c5JIf7MwHK+4N%`%EGVEB1^mtk_PLcBmrxNXxq7e&Z;8%NP=@
zrH?K8t9+^==}wnHet4h3f%=BAEI3gg?**Do0xNmBuPfynyQ<%H-1$}??>iEvfE9_X
z{Z9E#gJIHJyz#j{x9C61sz~Jg<x=5B4(qo^ce>ce+av$kbcF$A?Udw+VCm)mCbLnn
z(LUafWv3cMH2`^i|IeH;;RDvw53bvXijj5&6_u51?E{8jax&+7i+3*F#}@r(eQMG3
z(5$VAN+3p)8JMujG9*lVz6?MMg5RZqt{r0i_50%B0RHO=qzQJfIFSY~S~$fd{1zXV
z^9nz-K<eQg)9t0jr|P<~6Tjv75PZcCEs^C@M@b=T*HBPJfc@Ai_8an8k+jMBehXQD
zzx|q<<jQZemEG8uAF6?qSzcrWmV_TR4P<V9y8}uPIX_f!vS*ryQCxl&;adYj=(kK(
zVu*gIMjq+PY5>ae1?lz1HvN7v7i#cNKU5@5wH(2Tl(eqs!Ukm4Z_yTt-TI*#Sd}vm
zMFh&ytmzi@5^h6BzEfvERC5mN$!Q3r*1z}+9XA^8w_DLB<f$V0yR%#>#OS>Y&ZmWu
zG~aKT7=!rxp+)e6=X3I=^NMTTq+c_QxK(U7<grD3_{B*QjO0sB61w?0OZnSORWob(
zLnTt1!|7J#zN(aG{`0pP2ycYw57j`M9;*&u?S6BV8@c-1tb=#D^@oaNWtV4?khN#h
zQ77{Dw^`w4GWUl{WPHz>erBp%RN|iC>w2acc&x_lOgn~vrEoYpDd*p2_Y?p8!_V<D
zSIoH)l0Uol9LLOI|5ozMHC>RX@2jfqXld=APX2H@<p*8<Lpx;D*F0awdcNw|OuGMe
z<LiVxRwP@0Q$-*(tt+M*r~lid6ei@cB9j5ge~ZX3{#!^tPU`lz*;nsb1Rg3f*+5rC
zAa#Agge1qzN$~b)lL>jO$Ycf)R{*50;|fl4^n*5aSc7j#5FV<5DZkLzt=tJKl2%3x
zmGD<X#8COgU+v@vL;h++e(_g3ne<iB3|F}!PZgQyp~wWH)DP=uhVz>9LA*UiEr7@N
zkVc}MtQM(ISJn18*~HuJ&H+4DE6PEDYD`+Oyb`(6oXNuK9XI5$B2+|C@<mdNUjp!o
z5@o#2^cZO~9x5=i#*W$W((@VTVvY>)o$mXObQ}*AnYBZDp^)`G6e0nOyc*3AJt2=3
znH5A=F+zR`@uM&(unN!+9qB~=vSMT%*;SE9U)mEcJJ`Tx|27k3lpkA5$fUtaUhd2D
z+jZTto_GxMJrBx5YfP6C(d$HhiC#~)tSWD1gZ)J`L^>AHE(tl-6*HDOT0C#aV?}PY
zXpzV-Ei&7*T1@+o%rOrYnP4VOljF!QEyA);MWB<?4SB4{4BL!b3S>>$v-ew?8|OW^
zC%$>8$ox1lMk2qA@w}zcah{8NVx7OPsQf!>QOGYXUQ?PLXRDag_B^zfk@%gJyu9YJ
z1+fJZ0KJ@xV@4h;GINl);e@OSkYL263h<T@_ZOug5)%a%2az=w2Z)d67OxxfSdod3
zqD3OVv{-NXk(@8)o-yg6A`>e~nhIIU(~_9VozAGk#x*046`8n+mnwlQ-Ct?Z_ViB9
z_A{q@`s+%{3ALjV%Zs!5*dJ5ks5dQLkxA;It;9nYs{vRu31&)6W-`eAo~G)d8k1Qu
zlYxL`CWB0A$<W4<j~nt>kq7!q6`4J28BB>J??n*_C7(0!Sj{t=7cr><ScgB1PR;4M
zoI~uM!0VwRO+A;EkD0&Lw8EJ}LAfDHx*?Ahc{&m;pE8TBb3^1VQAnP&d_x{9UOeK9
zC+(8(T~>7CRLI^^XW*%tXF)59-XidesL$7wD(wxMQKU|LXv@AnMOiP9Z*86PqVTXL
zf^_f{Mq0LqiZ~u3(OU2nmR~5@OP(wR!`AYPmB6#Y1><A;%{ov@9NIudRIVHHSdkg$
zlt-Y%DREhm$F|djEGWa5X1hpc2O>O{hxgZFGO&R~^I6jkd8|lNSDh#@_2pYtJZ>5F
zz=1j;PZgDlPX`Vnzilm~aEnE!htV$--b(c+(r_WaY_aQ>5b*sX?QWz9d}xuG1obfy
zvW%0by1|5lZ>bxRg7BeY(FFi25?OKq#6FQuU5^{`SdnJYAi=HLa?6TE%fY>R-H^wM
z%(NIJxLq4yS+U;oF}{se`ktZjq2i(Zi)``G23S^Xw|tLp<ITQjfPAQkM3GrSN~t4%
z*#Hz$A|XRCWn`Fqs0bmL83h%oDc7`TI36-z<=Z&VZy78fDl*aKL}Sj>mrHk1vSl+J
z=G*A!?+G#=T4WwgQMM8(>&z6DH~74w8!Yno1e^~o^1fc8gUI?)upmM>t|1E|gd@S{
zL&c&NS+S_aWkotNz!*J}0o?M3K2)Q_1gR<sl$Gh5jP*=K`nG%u_vEAx6`8|Srw<|5
zx?;VhI(;*h>6HBRp(1mn(%UJJrMJ^a!N63iZ%Y;uiB%sexaWm(Vc6U+E8vuwMeK_}
zj7Zq}P?33E<E16CrV^ee!<QSmU6c;?ud8vY)5U5r_p4oU%&BGH%3Y&evyZLO8%?cw
zwIzLOJ8yYw-<F)`p2_y1Js9+Zd|D}R%le(WZh3LvmhtAEDfgj8Ce&3jPa^r31VsCk
zch~Cm8F;LQbiGa09LVdBN>8_(zHiHubkFkpP_fGOkrjdDwRVVngUA`|4NkzKJ^vL`
zM+jKvj&MJuL@%r2j!0>pHUL?Sm8JmYrGHfcQwmZYzb&KI1Uyz_hUA^q2&@x|Ri#mW
zTW+vOs{Byla4Oh_WLUmcRu$?kHS;@iDyJo<k8(Qi<n)Ow&ua==<dS0Q=l6>_BqJI0
zLq!}o_SnRy=Kh!TVsmO~Z}FaN`msg-nY0EXYd7byx=LMb?d7TbSjqEUM^>u~-pk8M
z$1NxJTPY?ZOZHz^R5ERSvV^R;=(X@V6CsUeWZ`~nk%_o}Y_)xTChF%cr}x`ag-*z0
zi%bT-PYdtJnqRq}>gvJlloPOM&*B8Hi`9~5X7!ezb3Sr!?UtbYu{Gl(WSmUoHD7*R
zI|BKllWhhbTVsxNr9{MeW<4c+ifXD#u{<G*_7vw-nPyUPPU~$pXKH_Y`r!$AtjHAa
zRTUkvNUl}I{gw#+9f_;2wOv9P<Yku-vKCCF`Mbocd>l9Au_EL7B2_k#bxwgJ-4fY*
zi}%#_k1hJol(<I7G7iJu9Sb|l`c51-WYMDMVZT%n$ko;rJx&#-h2vD|u|hM?Bv$Zf
z!({~o^q)F0ALk8uZV5lriJ8c?J~1DRq@|EQr}CmTkE~^-hRE7wB@jEGk+b-`A&b`h
zXCdB+taBD084KN}(ap%JMf+KvM(D^d6T^_)iq=?KwB$cY6n$2D&R)O-(WkDVm|6Z@
z-$N;nye^`Moa>vYk#+r)m1?jJpX<ZK$g_Uv+%ih%Y?=CeYxj1Z`SnpJ`hI*S=OZ3#
zN}nJ8^FO`*;&F(vJwrf{4}qSL<IT4K;e!$3Gh)~Hn?t*EA57H@p=^@~Ie4Bg_*;fJ
z!-E{69ovxINeHHDd(aYm-)h;xZ<~I^&%lfn4dg~D5&%7(ZEZo7!PW_&;A1M9oIp4L
zi!Ry>if4F#i$>5zixLkaax?-?EHa)p1AfRT2iZCD^i=V6=&4SN0mhK+263hEuKXp^
zShg*Y)VLv=L1`DXJE;nnAP|2o268mT7u<kPr#MV<=%jl7K)Blw2i~t~phQ0FfCpJo
zYhb15{sm4T&RrmE#3o^LUK6$A>{F)(1ir0)YD9swx%d72yCL?I8<D*~HJL;XO=h>!
z$;ID9&NKI(dY3J8bN-^Dt~#yMF-`0Tu?L}OEH!-^E&y#wAAX-UJCV;kZ@2OHsbL>(
zpEfEHt*8Ykso~9vN4pKKsaX;xwb-91-}a}IQ(fp-K+_7_jMQnz8g)+nv0=e-Z0`@a
zyL+7`pGeb#ozJLB_Skp5SIx<%ycv-6BG_x$i<USL&4Vv#ndV_U&*HYKM&MIhxVJ!X
z)64XtI+A199@E(H=77n)XAKeAMG%a4M>s@KOZ4o!3eXPjugV{JV<<RrP{=Ffuk49q
zuKw2Ko-}A=r|1+;q)Q9oRDItj?KhCdI{DjngF;$?VX%j^LeAwL;woxMEJwBWqf&Io
z=X>Xp1mH_DG-(SDWmjB33l_hEFAjr;fsAQDs3j14om)sfav5G)fZ-dJ+c`bh)}Wo7
zagZ{(X?P>loW?MoOQh&IPGfg!(w*Z9OnRFmPUm+_1GUL&p-6xiWd4nnxF)t~H-oq+
zP!(GUKO{nIhc;&*SOeGboEKQnF?PcP1t$UwX_!S+$)15T)L9xgK=$Uhu643wLF-fB
ze8NM)L0X&ELob2}poPf9d8UQP%s#(u>L7SKF<Eg65_9ELi?37EivIYbgfz|m-sIMz
zKUQL2U?6EBNs+Rzg(wAcO{?+lkO(y-XYw_uc$siAZB<=KScS@kH21a55DGXWxD`q2
zDEpL$Y(?J6Rx~fj2h&PydmO}D2v<_67Rm9bmf}IEC0XNy*e#Sjq!ns;njD|=tX&Pm
z18z_4{qZ8VG_q@eE!q*E;SjfAZERU9HO%6hbI@Wg$j~d9ODfk8xnSjL6uB_N_|^Uf
z$mck5U65k0g@On+u@)lN>GY5Q+%`VQyc@|03v|5P7`bK$o`ZoSIYOh#XvQ$o4rAaQ
zv};v5V+UDbWg>RB0~_6I<u6RF$yGv@HoZ#Its%QVCb~l;=|P`?Ze%(7)@6oK`sz8h
z1w_nTpo<!-3ZLWjIoMdxOpPQN4{^b62p-~`fmL$3<K$jLFf*M&l^E_$G%X?Ak!Y(*
z5cl&3W3^dVv)5{RiVsp}KxnvG-sgoWIpih&K{hY?w!wAQVCZ3IaM-L=OgqV{rI;cZ
zddqO@EzpcdnNxMx5aAm;iUrMZ(Lkg(Vt_U)<|axp|GST_MK^qKP3v`l4eQ(Pq5R7w
z@6iGIYVkzcK{-{MMvnt#<==f1S3jFL<O8ehg`E>?RUdHRt5y9VM>%I=%)$1`^6uxI
zS(aO70qN*q)8Z=Nh$8Rqar=W2Qf2MXxvNxG+z@5>Xpgdwuc$XLNtv_r2Be`SE=?2Z
zJU1+~WrZyovL_Os^Fi6E&?#Jyb+AgWB_CwX+Ol4QONN;b+WLaif+0J9Wba&l{Iica
z`Fwrr+MV=nj`*M{mYK*y;jRNAjePSL5UQ}8e(eq!O;H{|KdniV33arR8hNABL1Y6c
zehMKCumiqKQjT#5$u%T(f%aZQR2OD5(DXqoRN@Ci{Lv_Rs*Oup)&y}Ok^HQLpoUgh
zqzvOYlRb8E1G0M}2R6-AFRbAi96}_!`cy(9XFp)tZyKNB*+{5T_k61XT?xLhc7KmX
zXdv+8k0EFl1c=IUVTh$+;M)j|MnU+)F~Ex4ETD@n2bzUyP^2R}BXllQk^Q_f7$Xn7
zhu~Z<eR`<3Ds@-cIJ%l)YL<d;e6z1?q0}VjYmr!N_<k0O#pVf9Fw}P96%<oJ0gKZ>
z&<}9j<idQL^mQ3XL)r6>aMp2j$wkJ$hKrZNV8?+lMGYStX>vL&4PYqB;-naeO|67V
zgODo{ERC6gT%Fq-s&&r5Q<UgKvIH9W2Vu#&rxSG>g1wM1csOV=r_8rGuKAvzjDfa3
z0QMZRsw8P04YCSB4c~G`%wk_DuAW=AqKiNAz2oZO=8(U|={1)mVW7ZglE@V3?*m}(
zifgk<QdK~5HV}5sPP|3Oak386TdzQyM?Rqqkk6{r$5xnh2qo)mmg)%azJYLKU_%Uu
zons0)$t24hk>$r%px$Tl(G=!_aktnFkWFQl)Pj2dLHKuT<&4f*iLXY2?KYq4s|%bA
zk<^k>c(I>MBc=m?gTS#skd4TmrW|aAsVB1ZN}L7;rS7+Rzxt%HWQ&;(ZC<7llh(;J
zGUOwo1ML8~CtLz;S)POjS*wzD^+JY0nMW&56<K;HknLX0=1JNs&I*|xqvkj352>ud
z{w16%aZva`DEVs2&_F6wrHC8uzusFaynaU548gD~lM&8HMJ?>V%G{;0J=D_=Ch~zC
zNWybCGu}Il588N^np_ViwBvb~w4z23R&X4!WQW(S2EPFHP&!0x(NSk}z&9vdu9+>)
zk?arQP>|ds>pOyQ?9CvI1vwIw>ycpwk#cY#%uI(}i<tFoq{qWYh{*`DzCjiCb@7eS
zNq-<+jhXZ_2(2;Ks%#(?N^{1C3QPx)hS88cGe71As2Px1huwpWz^UVdpyXYXI`2o0
zO*sd@Ev&)2Rx~2mc(d##e(W#+<MFS<ma{&ZcJg5IP)00g`Rg*?KIfv9D{2|Sg)F{V
zhL(ziL~=MKC&56ta79T{scBb8d*w}KSVpArWW*L&#lIB^Ie^jT=8*4_tUU_dG3PH<
z@;$4sKC=vDe)Ts7QW=Cf&T1TM2~%2@S*OBoCeK&nz_DA$EK3hbvvblCQ)EjWsBW3c
z{Ql!mfHb^5U;YS=5n5zUT3pu}vy_2Kp)F-#gxYSeNCRsDv3LrGxU(Nz++7`sIy;8L
z>jm<C>oEuoot{%Jbp|uV6cxyAyg7vK;0L})I{OrgXmY%M5HIbl;pWk)3M?~I6{x6F
zH8^dMMY4b~eTz)bjLS4+=X2OStN`Min9_HI5F$IZ&(fi;U@FU@hOy`DP%z4zwnNP(
z+<O(sTb<I%p=Pn;$}vjzFBmqI)wmQT-Q^*!FzLH=DCee67pJ2uH8RHz5u2_r{=yGm
zqC_QG(?GEM5U^wj#t$1rlEuzR;QT?@N>Im>Ziow0#>=Yb=aa~<UXWXGWHP3C2FDhI
z&^lyjl6r<yOQz@b0KD;2;s%G3$gIsErGaoGM2dMnX2)ZEb~Xl@Mc#WxsSbn#E$R*j
zifg3A<EK3c{lO2sFFKEctS~1jb4V;{2xcPVASX|7gYY0s1(Vq8uDd{qo`2H#gAIUv
zVU%gT-~?sJ&bAYt!r8;Q+>&0~j!)_fH&;?;IC~JXNg5%}Kskk%OZk~=9#PNtTI>$D
z<gV^uNAA%1k~Gu;(|wY<iGxs1GM^$OEi3#0VM^NvLCH6b%&W*TJUs(JX45lprWw!J
zyy%V05Ahu#wHASWH^fUm1x|pvIplNTya1V=`vnJ<oMdkBF!Vc+_!E4=GV_beY?0y8
zl%yGFSdbIU7N9_w%WlaMYcqnx27pC{(r-v(JDi03Z?^eIU7hiTMy%c)z?iV`nWC}l
zRG7Qk;;MD^Cy*VZ;yOb6OidCiQ#wjthhA<7`b_EAv{aOiP1e>-X(+Yc<||4Rgff@s
zs)o2y6^G~qD|)VKnPs-ib#c=}lHV6}U?ASL>P3vEs3U=}BX}L5%?<>MQuytekR3na
zGG)y!-p`yhxq<jiMUu@wyFi=E1^wf)WsWfbjM2wOS=LZ;p|7)wD|}gDI|Ulv9r3%b
z#ES()KHUJ9syg35shW{pZR>s9**KSdSL0lE=#aPHG(H*jqfE&*SIhonyw(ZF{2Ov&
z5DjH)umIQ)HdMOQP9PjO>u}gU|LN4IS>;r_fpCo2s0qjO6gEkGl@0QxONWLO2z!jp
ziVqEtjS$-R-TIN-Q-Lx_H$V`LcLX9(PD?JK?f|>12XkfsG|dbhv+Px#8)}*cKDI_B
zA$@Mh2#;#LHC;7gKDek-AQ~keTw>b?<g+QS&je%N4e>|o@SHNv(?6kGH5lP<2zJFN
zA;9cY+EC<d;=SJwzDogkeI4v~*Q!}I`Z7Eee=hgA-P_Me*<1X^CvK;;;0{%7Izy`7
z>p<##^X`=;A7Rl(#7n_cV$(y)-#w(<N>VH1Avqo*gb%^{h+wH3GQHA!(yTO;IVTV;
zd(s1h%+hJ!so=~IMIk0}5`{w8QJ1=4nRH+S!iHUVj{qY{d?A$hHcLi-NQvJ}pbm&l
z`EHyM@9{wH!!mBoNmko~&ROWc9JvkDVv=qH9ms8<#szu%;0)mBK##v`>G;{w;T}DA
z=++boIBx(2S+vA=4+_o*tGRzy5wdj$G|QOM{`d3VW8PJb{fTPokPvogyxI033RfS4
zUplGK_gRM+Nc&NymH|t(K~Sy=8f{cO{2j3bX?QM?Dy0X@Sf%qc{D8_;L(`$uaZ`m_
z7l=72NLw7pUB5J>o_EAbSk%z-{LLANPmxx+Xqvbblr}R`CIxwOhz(zu1uBExO1O+x
zsY5a6+z*X!3r*cfd~qm97%h*mJOmhWI~I(%A=?T%I#`ZAo<K0dq{a)zV^_(yG7oc5
zLkvQ9xXMZ0VM9Dxa8arG;n=k~gx+vfclCy=x~nOy+Rk$p*J$UrN6>lc!I=N^;!z!?
zHvRi{Al?kZaU9csUOJ9r`p;9xaZL7k>X__v?IhoRK*waCXP5_s+-(5^p=|<ld!Dc-
zx+y}DZ?`fm6PWDt2r~(WaL_8^YWDy*ZoC}lp;2-kkFb+q+=r|-Fs~RHHy-3G1a|KE
zIbGesOLKN~$EBB1db2xRvM%cxUW>EIc*cbZ1imU3bVUP}esnir4TJ_Yu3nQp4Xf7>
z3?W{K0nwg@SL1B5sB!hG3~F3G`-W_^!Wn5ihQ&Fx`;c^M9dIK;`=8OdV*vctoHa~~
z=t~L9BKm?ml5}cHsqtRCoEwk~n>!zLH*5~X4Vx(VEL>Wavfb)a8;<&!#$L`g^{<Pw
zP4(-d>SrN>cns&3BJa}NW?6UfnA=}@v8_KR4WI8xQb)KLDXh#FA44lMJ`-nBN4UY0
zI>P0kz3$TF@3i=%goDMU_1ZP!sNz>qtm0R(w6KpjJ->&Ns{*4C!+1XszZipq!vOrs
zgZBP`R6M8P6L!S42c{G0f_bmNAi=nK81aAXj!PXS(J%<zIn^EC-N=|6Hz5OIcQ7>`
z_2^eBn45#w9IV3YAkGaA#=0`f3`+Eys11;JCTWzso=zGSv_su`F=BDL78_8)gD|Q?
z9pb2X*GzvKL-x3m+Z?j%v#izQ?Q_;*ndsD=A@i*mg4u!tCvF}yW3Y18n7ZFo`krUJ
zRL)wY#%^HCGcZ_}qD)qPM;h-|QO3<KO5UlW6@spq>BpIIb<Cm1?J|e1+hs}#&_fJ}
z3pn2{XGZ8S#~O3*#3gq2=o;K~V*-m>=2&>UT-E!cOLqvqgSLWPHH5-jcD{SOT&`L^
zcoOM4pTF6DK==`d$t&opHKoguj$#N}*}~(1ndx)p$;RVR<hH<oQbW*ohG&IuP<j(J
z4SPbcj3}W=-d8s*V}fT-(<IQtNXLeQ*VQ;BFhoN>AeoUBZjRmn(dXk}t)0#$YKaJ!
zmUq~lH^7Wg4X+lamN(>LwFb8w4r`Z#jil)Q!^0*sqCs9b`Jh;r&U@@$@`n0_+2Yj*
zv#@35z{?$OM)>#SVgw|^3keg|d4(-Sl)(k^Wn!Fb_)Rg+HT!MI2FT|{iY9{xvXs$I
zaV{;g^U~T>#?6t0=is&M=1gY)I_MUr0Uh*D!}9cl{tndN=-@98H6}zeuQqhdueqg&
z(dXapnKmNuVLSB{`mk~CDe1ig0e)#>833N8$RJ?WJoYZu`dNv7f9yS-hpw3WF0Vrl
zfX+j>GtYFm&(ceJWB=^+_P|=WNaF7eewXYU-A<)0Ag(r?C>2*5ewGHghoq*vO}?7B
z)7g}I03GAYPM-h<)#jqFJ{{wWzVkhtO_QGN-Ai!nMoz_CqzcgMT|TQHgiftiD)NNo
zwl3zhQdppqFDHrqp!!Vr;w3CO-Osb%CK~|PUA91fbbW>8kDm2Xn6wsIE5dC@zY2?R
zP)>R%9h5mcNp8)YL5M_m2Jnf8_F5`R?r5t|9eu;~q3e)+@TNw%>oz%DXZnxpTO|K+
z8P()1uFp~5&F`D16{Jkf;(#?|b`EDqZ1|5GQoT}znuRFYTx4@XkZe}|zk&ER;>Scl
zm!+Ux^oft|(BEC%xjDQK#7fwAjaGs}1BV>bc`=^hnttHl*}d|y6v&Zm2&6m0XU&)2
zCl=we;oZ-)vh@FFNUb6S5K?=2C9GJ3XQrYGJR5Yx9WcapL?&Q&wId=T*yUpiW?)Dy
z0v?E1UvOk@o$(J;w~_Q(F%=A`jj#&_)MgP)TR^R?-=z<I^BXJio-==UW{y7w*ybWh
zEO&mKD%<~0+Z*)ivfEl>^ZFHg=r^!a5+zZZ21qxM41(@<MnNXs=ocV39`p+uN&bC4
zk!vm0x3BL$$NRo#1NIU3R}!UCi4?g=GBJdbXfvF)s@hs5oL{NEE3x|#)xx^Th=aL6
zy735C3Z_&=)I>OK&&Rlr8D4as#bSIBPg)}O70#0ZwzaVb#_gQH=Etm%AjI3AsG$hA
zjX??*?gSR`wYH2+N~U10Q1}wVaTVcIJ7SD<UqW~;0;O_~!hE6dtD5-!rgND1{-(2-
z0Dnb!ZAwPG=}OcYb5svAIUSw7h~KSEhb=(=S7l+2*HiI#zAfnNDwf43YBPOeRRM9d
z_4KNkxHELVK%L<T3yuiA#^2;?l+%~N!Y9;^!NLp%tVop|;ez6azd*{Eh$mjz^U}l^
z>3I0b&8urb2L_>a0-+-4IQWr2p%(=_a)lC_(9W@ptAfgWphW#4RK_Bx?g%22BbxJ8
zzcu4M4}W=1H7WFrPH5+}hNx84GDa`gChfi73<;Dyy5EXW<r~C(qS0F1;puDVguVg)
zY&@bNW1ByQVi>OTC;7JgF;L7i?;{9?i11%^!7yVn!YJdzNPY{GF<Z|c;i339zGOyI
zG@i~3rf52yGsrqZsnPTdwJz#{;n|g4<of6wZYN$lkCewx_(&Hu+qr)0u$9ZV9&DwZ
zso!WKApNk#cyzIqq5JoPtqjz^#g^Xgj}L}(pQv}N61P?o7;ulh*^qpL`#4FAxo_$x
zyE!8<;(n-`jJPk-un`!}uk!~t0zc^_<eb$C=7>J886lGA0v2T|R{^#VBFE#HLOY}Q
zb>KEvvI3ra2rfT~60pyaO96z8>z8`VV3VGfmkXr5FS=>)?Bop1d=SnbFdf7hI3-|j
zYzAlTF>K956*xN(zaA9zkt^49gL{(L4o;;sH&2m{E(Vsdqm>6umo|(FSyV2P;+f#X
z)JHCvj#wOBSM54v5jlSnh492X*+epwp4!k4os!U)E|8eYq^KKaGT}xZ%4E{iQOz7F
zfOheeh9U?;%Z{hI$)$6&m^OyHn8D~u0>jY#)M3#M-gLe~q?~*+2=0gWe1VedDUFxE
zk%s&D38#oVcc0AWQ5nS3<p+WgJlT1kl%<aLP&_v;%F^1`W16|-OViB7T#sqyYOcpL
z@l8vEZA=q&pLy!W_CwmhNpys)1iTwwpGe%`OcO=rv@uE4tyx2V9SYHSlFsn4qN6;9
z&pce^FYGw8aPfq^QteT8sng_?nUIS8WiqOB@-g+4Qd~jX($)Q)qER9pRecPTS)`1u
zuon$`jFUN~WC(A}DrI`hOd=)SGAY>+cU1d08O5kiDx(-vH+=d@FyC_7)f8*SglOap
zI{G;0-l23{n^AP@Bu!&Rh%f?aXi~V>IeKTFM-4A6^APNG6GNS|?NH|7Id;2J&YjVv
zFfy8KjK^3#O?4V7x6443+LLk?BR3In5~vsmE8!;!6>i3;jqz9tCGWdAc<d^Fa0kL+
zFBRP38ap@9Z`(ti=BDzqLrBp1XJNh7D#@0+Te$Fya}*v5k3z!p#?c>fvl>So#64+9
z9XtfCEHiiwo^!ZKjdQA{A9~2Y3WDE{aWa4BxrRSTT*xrOxjdT44O0D_SfmujOY!<i
zuf>ly3cpy~zPvoTCIu;xc(dJ37Vy#woiy)+(`%P6i0z9Gq$jubSO!wg>L#=HWH#2@
z?a6Jh*3jA;(9c;R!s#LoK5z2ih!m5#a}T=?(?h^_dczXyc3RiR$-i1rpn6l(Ckgqs
z3QXcmih2l@ZpOm2G@knFX;Tv|$O@)6^`PL@T!p3xr(S$0T>8?7D7mVKk|Q(snp1xR
zN$%tq<z|LiIzJADsEwfHTG0yuQX&Rg@(2Ib`OSkemwpo;@VvDcxR*{Dst9DAy7q_y
z@q7dNHIGwWB;7@BT$`uNJsBPtsFcqHr066}gLs%94@!GH73ay6U-m%>{%kM$q?Or<
za791ljUe{uor3u?q$^=f*C!G_GdM8<9+lq+?8X~-g^{rxrt5<9AVG*QR&q*leNf2I
zKtggNr$oRC7*zg=OMVzU1Lp>2vn?kULTRsn)S(O9(dSYZ`O<YMe^6XMi6vMPF(fUi
zp2+kQ*gu>-@E0#_xd%n}EtZKmXZNA-?1p`5mG_p;#)9u=(bCzNFJG3<G+_pkvX^(l
zIVwZMtt#ZsgQTN8%S_bADNIT~@^;mS7L|v?st?^JHsY!e-63|}vWM<KN|h!MH^OBP
zZ94n;jmEj28YlZ1Z<=d#G>_^UD=KUS_1`7;(vu?fejofxp#jpXSCe|r_8C0B;H7&-
zEN_3P)v0+be$~9gtaDrLiHz3GE~nfdcQjIDwty*r^~WVGr#v3FQBlriFWM<9bk$qq
zagWQbIv(tha&B@1{n9wf%jX&oc49L=@5UsEnK&QUQ68D#dr?`$4g1l~S^L9=kaP5h
z#UNknLwh9YXpnjPU-M})2xjKfWDqZQ%ArR~!#Yajp~z-1(a*7IO!OmF8_uXTA7+i*
z6Gs{KXkp7_gPb`MdaU)ZF6A<;V_nKAuZMMMQy93BlwDjbV>@Un+N;3$4^Vo2)JUP-
z%I<T#p-Sg{eClESVqu=sKIa>%ecw9XSazs9W*H*-{WohV3g(@1xbyxfB18M$raVo4
zJ;yri&6rbt*!)(^NjgBwzaPtJ9D<DLNm7qC&67F9`Y@H|6m>^W6Kuo|9ZPAjZ)haz
z_OOB`=XQ*s$@n=iXPTfkiEFYlq6vMVqS-C&6}f>T4r=i?`PLh4-ucRpmW^7y_qmd@
zyp^eood4rOzOVr8!Aq`yob$+w`iYXf2uy->syq6NuWR9T9Z%4mA!PE6lshXm(a8cd
zD<jW-$ZxSJ^h;$Kzgrp?TpuhMb{^UhZqFx<ubxlHSASz|b>^}jYXr@~fs%b34@|D*
z)7O(r`R411rF5xUaQ|!)nMsB5ostXVPk$6TO8zeT2sY_B%xYKQ-w*i=Hs#$vwkgLy
z)^ckezkR{XbP#ve)S3^5avD0C(_MFMN=G}lh|Xm={Wit<liVQ3b&nFB_oCY}7vgy7
zD;7dt`kIrLH2`kQP2mqPK_0_BE5ohFpfS60v$aPkG7a=N8#V!;B6w;y#neSiw%i&t
zW~NGV+aHWdgg-u%5<0>@<>4+E_CZ<M2j3NHV-+3Q9eCIv$qOE*K+&Nc-jCgG>L%y=
zbin7Fi>~AFxJRu<bu;g09lqyd4@x{$b=67VN>IdLuGP~~9~-0S*zQ?`@gN(pT+(+t
zi)2dO1q@+R$V|g>$!QecmI&jeU!0{FkEgz2PWBkx^C^B-4GWPAa{Z8_#>#Qjqn=zj
zj`}<pPpw8mKMaw|C#|}b<EQVKs1EfWI_vvSa-KA=Ty*-_iH1Z9NmF1Wt2m!HLO6k}
z@b9q~tn>%JIdLJbP=2@^#MSu;7c_r!*@^Ol=g3ZUULP3{E?iKq%Q?_b=}rN{P`vdV
z>L~wxBHZ9uvT{!KC=$s~wLUn-<K{=L`4gB1kdi602=o5ii8{;5z}eA(L*;vOy?^L>
zCzK3XMXfy1T47PK@`P*UBo17wcE$SRnVuDR$LV+F*g&&}qsz(@yp{W&zt6Asfz!%8
ze<XmXI&_NV5?N*^;HhWPSn@UT7KO3}U@Z&F60cUfvLqxSCqsx_&RrUK&nmOBJg_*0
zm4niP`gJ0E;52(uQ1Q7)CZvS9>;&a>R)s%;04mpsunEtaop72CZK@u}7f^|If@R=r
zV{Qvj&@m9Pw-RRj_&|A(YiHG9GkTO5KxJcPJ0mF5lzJ_ylJu+|EfjH#W(r(EVqmM;
zXL%G<4tHBj?BHI3nz0j~GExCK;V5v)8N*Qqi_pvYk9@{<;!Q^066{2mq?gW4c*$V7
zc0((d(;m#mEz>Gh@^PxB{}43RPUuJ`Z&q@b9|F``<}<uViuIvEIZGfbO(I=?c7jKc
zMfy;#_)*O7pm0;asFDkV1>&37&kcNHM+P;B6Bh!np`Ex87OIvI7>4&jA%INX$iQ>)
zH!Hg#HaGN#6BdH9Lsr>Ez6^zh3;@{dM1lZSZ6^|Bmszedwg8oFjQK#ea?6+xBEs{9
zNN6Os+fIZB;NNy4JOB~5M}&v!noDrN7immwy5Z_}qBP)iv=gO4%)2oSYu2B7Yvy!y
z)DKpxr!jX7ye*eq3+2ckQ5TSC6-WPoJbQ#(3`~Y@x<Qdvb=Je3$n0031bb5Xch%~*
zAdBQ}p0JUWI#s7Xyo*7>JA|M@?qJ4Yn34-$^e?_Y<o)fLg+BO_Cl-#EhOA6{eb^&1
zV`6KZ$c%|itWeb~PhNGAV7cLp#85;_%ZDn5%9T5@80*87#hG48dxT-EZ~!w;T2f*a
z5Mu#hpmfq1<CDqP^gw+4b}T?}TiS`bKm|NIK^KTFvJ-THqP%7Y4~$YQOc$4w&Wv(s
z#~RoPz)UG&k3U~ZQ}_J)BRnc6Ab+P9rM~;|!9sy%MKY4r$WIss%IVk%!+^7t$@qRK
zbj<94+E`@VbR$6w+D`Mw@IBlyl{y`MIy(v1>8CSgWl#T~DQ`RKF(T(+w!JGS;SUDo
zT}fJeCb>KDmpIrTzriVfB0U_}l}$P^iOJrHs5GpOgkZWonUFCFk)<L?m{h}3yvIzM
z(%e_nRExxqU>QehCWmAwCI{!M!7a)p8&LsnQ#c9SnXE~tM?pF};U<pj&xtq5qMh$Q
z$*qz<xssGWLFi>#%Og={=QEzaV3;LtGK^yJu@~w@SmH)v5~V13XeX!zg%<4uwIDwC
zvJ=%3A-vIE>}FtoT$Yin$&7~RVdNA=%yBj`Fpg^l!gwCmCl1DOAutJCkG$HE+?35&
z_|wjFN_RGdP}_-;L6~(=xDjwzo33)G6&n=rg2UQ`xIxgj*+454R3>muQgU;GGI261
z*alT<nHctm{N0zG_#0nXs1uV3D=UgrL>t|3-aNm@IYnV0Rjmt#-kTzM;3H@H+oZ&6
zb^bZe2Hg(l9W7>3fN9iDl95#LO*uwjvCK%H3#9x7b5y_{X(yiuG<-YhLU4NXCs+Ii
z9p^wL{>@|}FhttP3sT6~BWprv-=?%61&lF60uOFs)n_3a%zwaRdom?NZmg3L1cty9
zTQs4u+e!9Ov9XRGGog^5Af#EbxlV2m9@8hc2ao9~ku?o(h{-)n{BWsK`?izqgQqr?
zn~OO(OwmjLFEB~;4`CO~KIi*jYUv+=RLI-F33-}4%1^QmXvcQ)b?}sa{w7uTw;$!3
zI7vNtN}sGAU4xyBDaMXY%9MN?C#?t1<&(Ih<7F^!2an|w`}+6^7yA5Yh{J`UxG8yn
zFUB3u)VA&9?HF1gE-Mb_4Ah!=FrPTC2^6-eU{R#a!HTjE=P-ORIE&FK4&LmQ>3L#;
zZ@tDAXz~&Q%V8>>6v>131e>hXNGD_`iVOgcpkU58dK;q}Ce&g+bbTP3(Wj>-`@t-6
zvNqViGmny;;Iz!OlxxM;wlwua!FuaOF3o&uq;#b<nZ*GPu?%7ZFyypy%8IdAaZ0u#
zB<aF2c_P}7u*wwChMZOp0uIS0t#<9rej?t08rhVSC#&Yb?9wm>+Z{u2rz1g^oj^Gx
z@j{Y+P;w(2O4Y~|%L^x?;_DU;#wJ}FxDq=dcfgjg=)jdE&YG#`ELtbkSq@#%iU~{c
zUdBD}B;~Nu#eqAqMl8$<>%+5|i*k_HK$w_nvjt_%HwrY}6AK80iM6UTeKn1JQrP9-
z9j)9c@=QD^C-Yohz~4v{-D3IsTLYhtJQ)l2{B~T>3ukAOQ4G)&J5h;%ro2-)@ZuDq
zwl+g6C#-wK3jOr0ofFi(Vr3PucS^3dT;fQP$buR_gfMxhq=Zn&B$6?{5pp4(5B=sR
z<PXT}O#8^{9zTdVd843(m4sFLjUv{#Tc!p+6pqZz0;Tkgg2M_IthKZ-Y;#$-qn2LD
zq2zpM30q6!oXne?Vx9s7l$>rhrFIc6<PYUj(GTGx@01C4*mHSr!5X7DRw6;(DLFDS
zO5Z%#lo0pkF=pKI0rJ55A|viy)$yTZ$INhBwK5134yZ>==_JOr_ZAjP^>Ki~_(aKX
z`Xs__?=5W9M>bpV`lRFsdvZG8U1J+2)YTDF&vrd_D5I%sc9hF^MuWcd=z5&rfa2#j
z?8tw^wm;ea_#wynJLNHargDa~JGrSTLJtKt_cw~M=QPBG6F65ow^A`ZbSQl2q-ma5
z#H3vG%Rb&|Y3BgjKqS90QTlUdz%lxyARWbvgeG`FizftjCsLNaQ*bsR<15{lk52*a
z%g5(Z&KZ0t=qD58(mDAYYUsly#ovZGXX}Hq@F{Z~Ki!JLZZipSna{>KYA4f;Pn~#t
zKnI)%TsWK;nf~w)E;<Mw2TwUC>7kVO!|U;zoa6QU5odG`+(YS4{+5<s1WG_KT<^n-
zC}JkrtGC8El(cj}8qgv5Y`+T>LlV3vrRbRCu~G|9dVHVtoXGgnDo^Co=Ex}{FRMj^
zCkc+i_owEke(T!<^$3SU;<iJrg!(Sg4P~^B&`;kW)r$)h?m~R?)gBrNU4f5IjZ31o
z_Bux~EXiqeNi>F5<c!1D0n;37OdJ);YI~?$bm5&AwK#~d`p_Q_iE11^WmKO#>L9&u
z?-Xg<xo^X{_SU2(%}v{-NOOzgz&e$aQM~Wb&5&lzZiY14L$OE4SCXjF;%lwrlXeY%
z+B<<Okz;$#kKckHB_E66Qu4V0{r!HC&b4f^NDP;SJHg2YH-c*oxDlpChMy76Gm(DC
zd6w5BtMlB!@K)!iI~d$xd9lRdRHyD>SbyC9!0S4<KQOy^?;QMkmad*$`t`hgg2KBe
zM$whn67WeM*0}@IiDjq8G%|<j;!KBCT()tx+voc?-Ba%r&KfI@c$vKBXBnmI)89GC
zL*XRxLacBcv}kL<ZHaEAV}791C@7e8m6-*v$f(BLur;NVD9jr9mQK5|S6W^0M&SOT
zLB-5=i9nUIHIuysXFU8o$4V0vbiua)-CyP&R`@!0BzkO)nagaex>?Mv$%sbvI(;n1
z-bI(nv8$y^g%$aJ$cF+`+z&cTu7|mf4w7Tiqd(-B{a%#!mMm|upTHkNTOyqw$J$8m
z#<57!yKxMe7kwFKkAiSCE^^JrF^GcOA%iG)-vCnc?MF0-o*&U5%EceDPD2``OW}H$
zf45WNn1|^_I3{E`4P<1divWh`3#9%qUen@F^EPbx$0SZ`{xO@w?w*Wcr6$MaLQPq~
zIpc|OIp0b9_l0II{wXI%N6#rI2Q5$j1uij|W?@J4!yN{&yc`*<2YH+$+>dmHT-?OR
zUBXX+brOH*!!e~`qapV=doF%&=?>yIyI(D4i7);5k9af$Mct-wFckx)>*iGcg}!(S
zwKsa-Pc7gAu)LjO!1TvIA0vw$Z8CVCA%j#zA(oC)j-pL|I~os<YmY)TD0gLrRkDL^
z0twG=@rSg4cM5%)ylpl5dQ`2f(buCA#B}wj78x|Tprpx|S|Z)0)NjpB4Pp~J_&l14
z9WDlOQp#z_+ZyXfZVFxW9WA=UIZHa|8zZZDF+Yyzth>A0&R*zr<{TUS;X}iwZ^Kx7
z_;~9%Avn-6#AiqSrqEH(3bI{{@jb#(kADj@fKRCt!oZK9^X%hYtc{O@O<<knXBR{G
z1+E28T?68fMV;UK8E-fU7KbKMg5{$rWMfmfz!Y2|dV_fFKya5*avGzwg!Vv@>_mG^
zbwj9$vzvDu35#(b_=yplk~5qFm2iJfL0&KjuH~j;!xMlPzRpPjcB&8SCma(;fLZ|c
zaBfq`AX@oQ(0r3HH=gEFU>i^KQ+t@FdBM5NSSUM{hL`X|+@L)0PibKu_*4-uR&h5a
znKi~fDG{wP(8;6%?yx37s8C}*6=Vn-1R$BzJH{Is)VqFwS(rd4FbiG|>j#-t)GMK5
zjn5D|2JVq-Y^(3cGj9woQet3ZBoT85Z-N2$#t9VR>39ZqVtJoGBBYMfBv2PB7$bm`
z?l^Z80e8me9>Mes;XT6f8Il_w^q+NNY^U^g<V}44(YzlpLPKgXQx0g`5jw&uS~p^@
zp#d=*N7zN{MAJ^q#>5=ok%>842pBa}*@<^uDU(3#C^uC5U|G^=kujC9W#|iVqLyJU
zRn=iT0j{hd+Y_v+EpZU8TrQY4iD=z~u1kBiiJ~<<l4tW9X|)Hi))2EHe6BHOLl|CT
z%tmEtCd<@crUdcUanQa|fS?AqI3R_5zN{ytnGe8QE<klqRwALnD<Py3RvqY%gXT75
z@j4jrP06=Q3Dwh>StVSM)C*YioFWdrDwAEN7q(O6UeO4$D<N+&aq(A@h^8ky3`n5t
zP&k5Qhr$smgF;R52$C1b{bi~}j}*>!YSA+YLH3S;!;3{olk|u<FeC#r71#($um`(?
zViHcV_W`S@ioHL613{!{1>M^R%mpy1UP-DMyn!!E(F!W4u6PAqycMs2YxWf+#(aRE
zLpb~(1_Z5)G13V<3ZrXy1dsA5WW|u{g=I;TlHoMEz9Nhv%-lGV7?Yq78)E>1ii{)v
z;1m>R{6U%8p~zWgr(F23M=+2L1}o}jhv0*^pBO`ku&EhqpdwC|u?DAlIAaY?t?<F1
z!&ByaAjD7y;$Vm&4n&3@oHE-x{6Gb@2UOG(tYr*9I5nyne{hOYBhlH346_V3$T+aB
zjxx+nM<)XiPT^+;Ae^$!gC>zvvKjf&EGoy@V89{oEjwo6R7)O=HALyXO~}2XV#tG`
zhOAmV7)Geu$Y2y9|BlHut;r*X5NiUtaO(ADXvE+D1>YY758H!(&!@O(j4RZE%@~U!
z*sl%770Rc_u!~a!buhM2C-z`$VV>AmP#8GMNien$>OUhfiVo~CPG~9G2uzc*k4$eT
z9@VmBL<F&_mz-wRat(%0>cHN?8byjb62WZ>-XkLqrI!yz9^$}a*rDvq4CW|0m>G0<
z4rWIXG5?O)l?NXT2Ck3a1c3{npRg5N-MYCBS75dHU|h8(kJk>(dE~$O7MKB|=rCp!
zqO@crsmpNhM@uhdGNPR7B;!kN*)SPja!dI|TDu54S3lWJgROKh`@}h%nQTI)L{wE_
zf#0M=_6ZsQFJoAWNI}`lbk7HajI}3&D_Uf3F;&LYCkEHSeNJrLyzZ&BOSR-a=XK8I
ziW~!rzj@C(U?bB|oa32kDEu*YCKymOlrdE1mKuvtncKCmnU_L#GX~GxLpGnmyc9a6
z{m!%wIRl2$+&Z8cN^{F><#)OlltIE=86?<>VToxsM%vswpHU(R=#2}co&XQDatUNH
zVl2+h6Z-L!!$#TwZ~h=ws6E(V<_@vJ#2rIj<od9_vE$Bo>!|hY0ZcGmg$`K;^xQgR
zov5I9QY@+rF^+T<@|hz+;z^QXhyuD;={ZTcjyh>QeA&v!Vhj|zb<8@`S5%!ej2&X$
zm*;N|0lyfUXYNRNA5qNeB%m>dA1OhNIkRBY$7<zzm&ei|JB+-1UK1sSPM8&=JQgP3
z5f58DK#S>l0?+3QlEuQAM&o{rA<C`a<ld6@i$JMc9wle84H+d+MQl^J`boKz2gwj!
zby6igDf~s`tW$m^%W7q7(M^jimnS)svA~%UI2mHJl;tTYYcUhl^@-HQu+l||J*JC#
z{AOj>w05&D+oJo!P2fVc@?T1z#n-_!Y)7X>92fzPpsXbfWKuFemOK^@ir7L{+2vvj
zYprwCk*{+3TWdVn+ch%QIYCV+$_{f(NOqVbg_{Kz-jg5g{HQ<1%6HZugXIhAk69uS
zpS0PGb|Z8)3HcJwSt$xzu`G&wHU!9R680(c+?~VnP{<22-{ocCdM8!(lkf5znM!l_
z){;)@sByi{;m9O+_86HI&KX&$*EtJWzhxPlYYNEyPSKq6?Vn@sPym#+thBi5W8iF`
zVRL`T7T`$R{YHu6c1z}A)OcLwu#zvVJXpz>1~v52rrO|4_9rv1DEDKa{8DAJjd9Q4
zJCi9=4|OK{JEtRa{hh<{P&jgD4#aa9BK_Z7kHO;Q&vnKk;fxh;daiRk98y=$@$#pv
z0S^k_3sS_-by}C=Ig*sQLZvo7C}*BX7OG*g&6Bw+d1w*;N%6DZ$o=V$aY)Jd6=UJi
z>5qPr0w<&+!J)FKJ}ETmqoC<LXO0Muq2r<cn{N7J=-92ZeeR|`9%5?Q+CLFaFR>M8
zyWX1T3r2;hX^&Ty6n&sbw}>dU>q$EL12QnqqeC1DH_Z58h2v;t9^V}HKYjd%t9<PL
z{>%UQQ4%=N8OsUpa7kPFzx>yaf4;VUe7~mh`Tt)}|BrvYUhUU^|2#iRh`x`$V{q!L
zzw+_dzg_>sKmYmu^Zgp?um61g?|=I1Kb7Wx`j`LyU;pX<`0M|C{ZD_rwh^t*SzmpQ
zvc|nTZ{zhJ|M-vp{^P&Bp4*-0|NfW1T?Jsz9%aw}_EC^hAlo^!U*tBE(R{(}pZ?eX
z{D1$`U;nS<a-yr39?)Ooy}tO{XS34&E}IoD4zihrsJ_Ex07}2)@_+kZ{++mNdnwyq
zLR+<r*FXGzt!nwZOw#^BCIhYU+B{D#fBR4XDfLLWetz=6h@Uh(5Uq9pqwCPN|L5zy
z_3!?v_dosjA3r|!ifDT+Zm%--8+-kuw^CkT$KPF&RAM>3R-e1=YkvQ3cWLqJNJzM+
zAKiCq*#E!+Y*VqncEf8^ZO_!--wS_k+6w<Tm%yIvjS$C57Z~O5zgRqmD$eIIm398|
zvCP+Zo?`yKuO4cdMpq9trq%uOp*&l;_>D*Hx7NPBWQP0SUwixh+PAd4oQbg>!j}_6
z5ufvvs``BS81OddF=1i9d<;oj&ST2r^5tU)qtNn~{ut~ZU;md_s=u@M>mOKu+{Vx3
zbUpuSayIk+r^iV6$z#Z$aUOGCLB4zpUas@lD8Diq0496`Y=83&1XAI5zJT)mH$e31
znVeF9d^x$AD*Jh?QiuQYF<2STV=_B_^;lfko{y36lgCg%fp6dxRQN~KmDe-H%S?sx
z{`+s><Np2|h|)FvagdYnlgXiI+j&e?+`fDac+B&dtzQ`p@d)R!I(}ue2sG3Bm--JY
zi)Zz>)9vq{Kp%f#|G%BcKR=Dj?0<R4i){Yn5r1sl;y>H81=$(TBdT)t<zq;-&$VXz
zo2y-RQt;o|>wn<9FQ^ZGCZ~eoUrr95>+_gg*<U_(w@;(p?H5La#X?WXg7MWu$OXjZ
zcLJBcwfeiv%kOOUKcMWuU9Wi!`-OP{Lif-Y9~1k1i5cqqLtw%Z^7Y9Sc9qA$1S9pA
z?}`J(s;|c||M-@F-TZ%N$Nv%S{@g)Gs1N1gS8t>Hmi}V%wf-9n@jGh3ci03#^{^>I
z`ARuOuFvzB2wy%1+s%1QgfAb1Iqp0r!k3Q~c(cxPhw_b=u)QWfe+l3DKnoBu4@O1#
zdWLpCFSf7eNcj4(K(0TYLi_87GOO_8DH6VZ%%9sNTi;mxvM~rhU;XdMrY*$Z7m<Xo
zC$<uU@OVy?FCVOkwm%OZ%GVD9T>5xWl&>E|jNIcvQNHmmb|EYO`MdazR>tza4^Bn-
zdWxCA^!cDDUq6VPXpaX)`TD_?cJs%BqI~%vt13K1gDBsU4KE#ZT3_v}xADCj3L?Ir
zhBW(?bDj}aj|WBh`ax9tcswY|*AF5~@#8^JzJ3td6(0|Z@}0M_eT??gxACnT3-VMw
zI2Gl~DK=y~c?fw?zJ3sZ*T;jReEp!=^Py;c{Xmx0emq0MH{QWEtgWBFgYU?S7EtR4
zn`nPMx$rwbpCaMw$L8~l$kvw+bQsUhLx=M9gUGV-cu<sYtbgD5#-FeMcQmD*iKU;M
zit_ao5rO!4P?WD9?Bmlhe<)u+2(a4YK~cVbaJEmP>`=b*Hg-<apTCViaL3Ul?ET8~
z<Ky#8es;_M<gXFon<mpz{%t%qrF?eTi1M=;X2z7qbF8KC^<$r$HYEJa{PD?cL&DD<
zdw1Nh{oR*v|J%53%01S*KSh+E&F{1SMwFkLlj`RYf60aOQkdrF5r4^vQ*J~JoOhux
zf^WWz9VPOwcy|(`NIv(Nq3RNTX}|gG$yvYT$yuL0IqR1^ISUa?=dn?K!TqpMu~BBG
zM)csfUc%ZM?eCmQf54KxK6`RV_{roxdvew<d2$wt?>(%f{tFI)380-Gn?l}w`Pe5<
z&irGZocV9#$(f%$IrEo1IkVg2k#0Zxd1PKW4<HfCmygu(c%Y7-{rt^qGyjO!X8zlF
zZ5(K1P09sN{?bT~WZCDj*?++y;J}5S$GrT?XrDbf{!5-5M@|U25?XuM>Hpz3;M<e)
zJ8$3*ocNBU0B3T_67c2ZkjwBqR{U4ID@go#9#i$zuO1snD1BTWDog(5WA1cC#2aAy
zn{Qxj1^i#}4n!^yj(H|G>{lj-BnjuSe*c1_Wqek7$1iET<1<QW{1QrOASO(2Krv$9
zdjs3I^E=<bAG!y8cJ90=Upq4L0{D3FP`+`s+htGE@>j~gvgxnXjNg2)`XK$(;{SXs
zo8PkezdrJj&bcq=_m}S+WVIx2`oZdh^b=#Veck{M(swNCJEy}h&GcK__0D*o=YBn;
zpV(vbzVUqYkiKId-I;jGugr9O$2^BJ><@Myq+hW>KA#ljJ2uFjE$x@)IlnVc6c%`L
zdq`hfmylZS@#ur}9sAPGWo17<g}$Ti(SY=1_K?2bxxbMlpAPLGAHV7SSLPja{_~#w
zj=;{j&Rr5GU-su||9^Yd4`0pr%bIl-+aBKeKzaP>|JCw*1<c>p=Ktq+<;p~OTZomt
z8D50fq-Og1rZYYX#fYZEu(PL-aeh~{qLb-NQ-W}Y>5NR83EG*??J_f#Xa>4zW&r1O
zh9JS8HXR{IGqD2G8G$q-0CGC9Kqx0P8SomEoB}gQO#=&jbJM^A<Ai3!u1&ws6A`95
z2ZMyNzE2R6uXGsgHu%_X@i`bRiNZc}sJLMk_6Z6G*}rE_keLVN97qY0)qA3ic_a73
z9GMLXm3wv*BZeb-4yN{)0~}Lno+*-NhWKAe*~i_cfTcuO?z?E-Suz%A4(e|xoihjX
z8%`uki|cE)Js$v9Ir<z-tT89pVtf#a<jhPRaU~_!mN^3FjJ0Jxz&WwD38<SB3(K(W
zi8NH35+=;KFf9fXWpSK2h<nSht{~v|vFC>h1t7+34#rNe8$2*U1tQrtA+Pc4#^N$T
zMHZyFf)Z?HJ(}H2u27I>4(6RkMVd{(s0DmhhM}zjR+*uBWdlQ2>?&lYK)m1_jD==I
z;T*iBBI<Asrl!ca#5oAIUWWIDz~`(f6K&+zf|=$;*^T!42h;hi27ZVPTMZ2H(_9S;
zee-i(G??7k*vxdIw^rVFXJ;0Om0^Oj6REmTDRy>#sVn!%CSc6Hk7j3#9z63eLN?;H
zB4yN%>jR;)n}Q*8C(q7L74f!HS9p|XnVsRr3)RYJM}f8-KO8M^<Y0l-YnOu!&qi{<
z%sAJYU;)X(G5~rv!BK_^&d%6igi&t-MnpLFreMgN@h0TqfXXSeGsOZ*r))xwy0EY+
z863gnv(s>bX!A|Ls0-6#z(Khoj5^Vm<-W-ovmul_e~@gI8#1U9qqr&g0+0c06Jl3&
zm2lZ47}Wm4pTy3xGYD4M#2aLhz|+?z#X?sNU9r;qWDCllY)VHv*R^USyQ0Zq4D+d)
zp<zD!NH;h&-$l_=jr*Kt>P_0b-QuKy6Q*+6l;q_GZ~1#f@)l&dn3+5=3CYN<G4kEc
zw!|6)6Vf(bN!n}Mmd4F3v?<vyWL0D2?54!tYKuc7d-JAn>@9L;n;JQ#)TVG82)M?q
z0R`n%Hl=VUI2d+yltQezRt{3EF<7=B|H{l{p*c$kvgVou1X*)VA_Q4;%>a_D4Gle0
zIB(MI{83I~XmH50HZ-jiXl-cdT*+&bFm|4Zn@}2m6Z@eJv|=wbCITqsj#dnM?Pl(V
z#w-AvVt53@Moyq;-~7eEGZ?hooM3R3xr%0M>Jvgx)pj-|8E@(pVz4Q(Z9yib8I@p4
z+5a-l15!}6K{h4!u?m%JN(w^N_1L7`7p8Gj6sjIYLE5Mpr6dZnO3hO>Y?ESoP@YR^
zyOI9_Q`CGnC7CMvaSo@%dj)yFrqc440(qyD`USyTQyKF&C0`S>;g?8CHkIpsxAQgK
znmpv5QrExkYth1SlgZSsa4CS>A(sPt4QVu$?Y$tC+f+r$66xV)L^oe(2O}!kSzu<F
zNP}KViZ<mdFUW^Cm5%%>1=7v*0hb8}h^yZTUL5^Gx~X_;DNx;~O28IWs+r0oUZPUX
zRNC;}j*k^tx(hN8P9~pEQq5=3YsHPss1lb7k*3_$r9z~k!tfQ8IC+(*x}b#2RBGyi
z3Nll9s0$K7P9~n-9YL%i&veNIlT($MHzD~$SbagB$|<MerlgQoap{5#m{WP5OSNd>
z1yqPRWq96{oDnO@ZA$Jb(?EGsQz7n6$oD9Li*%tA6}_({<$J4|Q^OQ0=LF%XT*?JS
zU#4YiUsH`raj6iEMzwfT@(mTu2eMJ#j!g;uV_M;`DH=^5G^)Ey%Pt@omFbv<)oC}c
z00rq@rwY%Ph~S<|WxU(DGxRkB4E&-*%W*YPO5#n5=_tAIro?pW(lC&mRbO}(YPqJ;
z3m2r-ok}QNP^slbK`WRS$e~2K-<f%UFA#$JIyDTge9HS<DuiU68U{kLvK4Qzx+a(s
za#pC|1@oH9>RT}PSzQC?`dqV8RWGj<+%1fX+|VxyS~)pt>IIpuCo1$@N!s6=g5(PJ
z%dGwJRI&z5yI73|SwNMiO~RRCkZ`rD*NWHI)GGuWllB%kack4k<2&1={Dpyi>EfAL
zeb%Ot={lzJZKx<Xm4LU%*DSp`GvfyVbAqT-mfV8+BiAN%5b_bu5K>IZZVL(z%v#j#
zh}PiR=WCcqc3V&<VYfNIfn}4Xjgkyg$!@Qb^&e)vHLznFK(U5YnM_(6lzbx30n6kq
zvp^$8osOx@vIUhvHbsww%U${~3Ukb&G~5N1IW~z4fJ>Wl%@#=GS)?QfOkgt6>=lGq
z*)lmcE^bOTTTq5$D%!4~=*BFR!dJ<vH?v5MMrgrgBG`fg8k>NQ+aAXAU-@z}+v^2V
z4+1zx(WOnnvY~F%reFj}z(PIv#TF!BBz7%XmujOCa8jUR?WT}z2*4s$xKRKqy=y@s
zu%P7HztqGjP*#B&IZH<?C#P&!1*+)GJguPQ9+0}6CGn=xv=&sWn9wh;B*lap{+_H$
z8E%k#MappN(IVF!r;GBa7AW}JHl3~Hvuee<z#(}CWF3iFWH{cG+^kicL)Mk5ks<3!
z)xZ#SrJ@zzj8y0bImaxj1w|vKvZxkZwKj$0=HY#95(kFxQ{vQuG7+;#&u+Nx70FbD
z!(E$%vm)v<Ol3ALxSGy;iDif~qBINcvzwr`f+)LjIOL^x-cqA+Z=T9xT2NVGDvRm0
zN%5ZVsj-ubP06u)GCFS^4juCBhWbtGz`SX9E@3>FH|@>^28XG9qy;q)rt*;%lqHxq
z3}H!%&qb+33tD^xx43(VH^{gfx^~CznzvMIm|^BE)w)BX-Ce^#rrljbg-pBV-8B@9
zoJbW~P*h+lRp_SVj9_!#gq%;8rJ=uWf47u#n7HN*+1eo#1y?B@7q?r2vv-)=m7%i$
zkGd)6v5CjP%7_M605b1ZP3i(O;Joz(!%{eJRuC*OCT<ExPN@fz*OipqP}HhXC}1l2
z=BDI^Vk>7T#rj3r-?VajY(l;;s?4YyFmHXF8C=MhH^KR>gER{O%v<_#horovAtV3)
zRAS9dNk(rSq^JP!BH;)9!<RJXo<ed{$a+f2P2s>uY3xfX^GGqdDHu7^_-_K{2XnbE
zKCpZ9G|*lk5!p8Mqs^8t8l}s~M>uM#Grpuj50oc#CB-aAlkbZva{3W`N%@7RVN=L!
z1$Ta-nVd-jMrwOsgPmG5$Yu%|R~pMr3HygDkL4!qKW++#HGuu3MQ2KSUs9qG!+vcN
zMs8U8uF+dguxs#!3F<>f9(P|yOGe&yU-*(Uce*c`sF5k%mrT@1i@qt~Wu&!XQ}D6F
ziMA>HNskse8Q5^LP$O0OrtnxD{%T6iMrQJ$U@09-38fl2!*`p*cvxpPg~K?eBh@>z
ze!nPEy^$i@l?8HBu=i!5&J;?nERdU!%PkW%GF3a$k(G47?k4Ri@X>Bk9uRQjZUV-E
zqt~ab)W{dTDYQ~YGU!df$VmRYDeN|8r1Xvjd76DvC3pD1d`c<L9LqjsrS`nt`IJhI
zbjhxij|JZI%cr#I$iBPV_%@MQ*OkAqAZe~o=AtdghwD?hXbbY(`lQ0`mi$TIMsnI0
z1+C;w=4hsV-6W2jqHa?-a*Gz%DRt3J!JujC+yokMk>m75LW>|=4jUIlSI)?SgrKgR
zk;UQa^C^uR={9{z>qaKb7bRNb^)D&Y$k4bc$g{dh$*GLbKEP;Gmjlc;w1QEYpM4~l
zV3WwZgLkRi?%1I+KLbeWN=>;b*|FBlu?GyTeE$;S?s)%H!+m0cRpX}V^+iD|KBXy*
z+7~#bM(rW>l(llVlZQf}!zLvo(v^LI5!s|Cq~1h+*G-6h2%Gd3lzewGN&~5~DL9(|
zSJ@PtGQg`iQUAN6<ilM`_k{FwD%~^h`<sA;*;zWHoqx~b#O~CTCj_5MQw9)aQ}P!U
z|HcX+ov6Dr0eZoUb(dC*m+vksH8zO5v(sE!qKvN~Ej+{}fLL=`sWTy}yHxAh08WSM
zJaOyX1TJkpz&;`MT#EFBOmj&_AWk*~_S;Ak>n`gvjto}>PQkh24$=8Kb=;)@PtU#X
zPSf*rESgNu69UX-d7cnqF3WSGQk+NErcCSr>c{|{xJyqC)QP(+&48V_pix)JgWsL%
z?p)wS>Ml|UyR#L1NZZXM#8;4THXu{6yX?qFXY4LJ@`Cho>ck-({a~O91n7%|R&E=a
zk%3Nezcp^bu923!3O2p8WFS;rNU8!v%8P<lyv-q{cx8*r4nT?zX~fVoTtKQ4nurgn
z!wZrQwJ`Rchx+m&#Sb9UhUDi;p(gND0Z7G%6ySwa=su(YBh|ML*^rSA{6&e@OQ;PA
zU|?B%u*7Wvn8k+-$Uw9BkO3KJ79Ucf6Vl?)%wl$F`gFmv%IcV*v}hz}_aU7a3EZ7X
ztKHFvCOd(28`6lOQ2U@l3^m+`^xx3Zub|*7hbHesw&n$CHe_pFkY+=+=7q8%n}o4K
znvJHlf-nOHtKb^qL#F1He=Tt8;4<TbDm3moE=*PdBE^Rk;6S9f097R+DOZrrL%F$9
zBd&K!ra@)5;@0TGOjX=0JugfbNby=3*|-T4Pi41|N`t26P03YLW%f<V2~cI;l-=#E
zp_2(8H@dCZD!00Y>>ALID{lGTmw2;ib<7X4s#DRe0HAnh@rR0XAe%zQa@BX>5?O<=
z>eO^AijjC%@rQ~cCf=upPhr)kM#mkjPfj2;HisqPwbd)IE#6(DH_Vb>Y`uH5@{FiJ
zu51c=g>!CGIH$bG1?sB8s^oo$(*eeYSRLSOXrUnTgsZBkjPs&I>m~4d7mK)`Dad$J
z^7h-ihK0oIUBg1+30PGV!s5MaRLAYN=VWnV>rF#LBKD@CArgDj$RQHD)Z+?l%8L}O
z1@29qE^HiArx1~ys&5U;=M@w(j~iX5!MVbM>Jjl+VPAE@t}2iyo03R^8b}oHRCFtl
zDBfvrt_4D|)84!(Ih)F}xE4r7fw5{LR=gLD4WZbfB3A%bycZ2#aA)d8qeE2oqR}hn
z$j`r`2ATI;Pr+vA3dE`jG4XzjLCCtc#33$mZIMGrx+WWQMKv}DB&(Jd|K=bNc5R6_
z2)nj4F1CfYseu`$I5}{tf-Z>Gro@`JiE$z7SnN1SdxmXlY~10RYaob2LAENY{W)qv
zUr9=Cs0P<WsCXNXr()-|A^srT+5mqPWNnC@kYtUTafN%!Th};{Wvy$V87&l|ss$Ib
z)-lS&>gp3Okai9B<%;D0n*cXt&3clqbe<KU7H>_{$rtDXTvZ@eyir@O73Gs%fT@~(
zN^i6}SJdO&6flTT@J&euYf8Xow0~C=1NBCox>g9mMxDCC&+4seY{<ZLx?LdkAaLxI
zvfe7khUKzR5wCCxd&^ek6pIE<+h!{o7pBWr*eT?u&{q{07H_gOSEQo!cB>x?W^XMW
z1ZBI$J_IGfR#%Xc-CJWpP_`Sb&8;o54<Ttw<2Gox%Gz52a&bYjDnKrqf@28Xa#Y;=
zEYEvj4&0{3g&4J|aXX@ZseRXkEo{R6>6Mh&2{tusem<MRp+`=Ujhvo7`8qf~Sf^|C
zXs|<wQgd~PyQ9!s6~GR+!CQF+`onFg*JOTZHn4u$&>}*Z0zDA#57Ja9uL_{crf~F-
zrq(qhTrjP3Xn;XCg@dnXabO5s;lws2nWJ7^QHp$1QZh!x^W6j+2FYkNPFGY?-;`to
zrPp2Pt*ZjavPt=q6pKddbOnlKQ?LR+v1|&5rd%{ha@4AK;kl|+EG6`D!;R6ZhKd`b
zRa&4nA*Up%jqY~jIgTEKm^A6%K%#k0Wp7h^2|<;WuLdD#G)`|y?kFhVhWnn7S2b~V
zSCA@yGw}?LCgAnFF7XB-SeM358CaJ@hQYKcIM$}b*Ue(?74R3YQqt{pBdk);4dz#`
z($KMmU2v?5uf?l0Yk*r^SgK741GB40`X+TeM)n{Ut7~x}7FiX&+KdL}1<nEwFjd7_
z;i{2daiDApM}<(V($Rq}^(q}5Fd1h}^a_xSSE=X#$#|r{r~t@#?K<THA+re_7k9=g
zc?~>_3#C<ohjARK`;@?e@5x8vbG=G51H$X7nqC3(-4yl;yXz)_`v!qo8(O<lspNpj
zIPqB(2pO*mj;O%Mcr^`-Yo$W+Ysy-$($OJ~Ulg?RcoxR1LZmw@p;t)#O~7H*4D*wg
z-ts`XTxHHTsmD+7Z8r$iDwQ0%jI+#nO$dyi8s?jl+)CSqO60YuV~9%?G2fKrm{984
zdbG$t#HGrWS3qT4$gc{x%%*T;-aM<6_yo*&kq!@K(pjIpLf_m34xR#YL&$Q9FL}rk
z;}s|u7w)S9<gzLJMGQH`18mhN??!Eqbi#C1Xysm9{X)>8^mh%--izwWZUWPJZ~;=C
zaG}0xOjUY%!=<r63Fp1VRl&RF-Np&?s)0&zRNt-$d2yk$Do`q3XsoV1C79}DZ$fMl
zRno4w(Yf$fH7|Xe0IXca#c-3r3GQ{OiCq!v<En{W5e&2`z{=H#7jnV0Du63qs9yuO
zvI*=ruYyJDb;4GzAmQ`x5MruLT@hF1g{|F1dHg<CuE=E5A;C(~DnNpjqUD7IV=d}U
zsM#?OKbSAP6#PBDzH)11h_fP18g`OR;lSgHCP#&dQ<$s@9E(S(=?V;s-%^_s!{YZk
zv%?ioWuz-WEPhLCPMeXdjPxcL9s*colX^adA7m~XDbBD<Il))8&uHLd?h~?E<)Nb(
z+Fo~+hpxc7xXMFU1R=gCXvOU0bgDqU_)Vo5z!z6-=nCMAt2T56?#0s<m9q;0cuTh?
z_(hq$D#0%|ZPs<%(aLeh4QqjFJa1C+E}eO#M7*Uk4@g9nd9EW*>&sc^xx%38x76e?
zxw^1g6-L=j;XsgqcPDV7!n*4!<y;Xp>n!D50f)JzYZDFwNLL*cf~w?P35dCy#;%x?
zH1c710~FDNLQqJsO6<xl@e1t9EybDGmAgJ3$~{>jA_nA{$|cv4UEpjW*hQt1E3q!B
zlw3#Wo0P2^q1t}K){RJRzolyrh%=(PD&oQYRv7Un#e`(*9<Zg}P`3$p5sa(C^)gh~
z_^Roj8Ny&ypjS49Po-2Fi;6RX>W4Cg)vO$U1&Q;X$P*=18AafSiWJw8f9E)PI*i3i
zofTfLv8Gl$51Fx~Zlf~$5H71G24-Zf;`kf^a2YHyT!C*HDluFG-ZG-Va7DfFv7{6`
zG^4?^pA{JvhA>tYIT&6Pw1NrQu93rGq-!dsha%WRg@bFBv<?bBP86peDjZw`>N3_*
zlYw;^tK-iz)=Z{r_-Ho;ZvtN2vGi$r1{IAZUD}!FtD%+ePKvU(Xyq4(0>J~tq^>0O
zAdu|_E~OE}@jasSZ$-`9Av9KXKtl&>|JHDwN1JS?kQ_@2F#s$>wSOyWrH)nU{@tXU
zjg({`ua*>KAYBG4{Z`;yhARD5M}*%dap-{!Ae(i9U4}qj6%d0>;lPNH9jep2NzAZ@
z<G^RM_(+Pgp%T5D670=I`@W~>8>-Q}DZw4^S~am6yQx8PgH9T;uL^j}CUNZi<CrpH
zdv>rXSgSq2m{O!2m+~>8NqednV-h1>=N&C95{kTzDOG#kn4c4qTY*~HBtBNan!f1(
zsf;P}^~@7^QxM(9inIe2dv`lt(3Iwk6f1-1tePoShAQ~h1iS1B%AySf(WY?h%)T~>
znU3<fvE0zXr(r^!XtXG@8#AI&dm7fdYix@t%A^eh%$Q9lJP<HLK&}dS%b2ohC%`2r
zI3i|`7N0<n!zSTK1d41^z+C@JK10?zR$KZuR%1*>0JG}xn6hVMUB|2%eB^@5o(<^S
z$TtzMF%24HN;CsYGbUR(KPm3hqs2ktM%*M0;`oB}HDf=HDUCa7N(X_grZBsPP+6PQ
z@zm)jS(EV^^{ro&XubZ1Z{+%+>e!paVIdX;$ErZqYzl{kSo9^OG~qRy!eR3Oc~N!?
z2h4Ek;6T<4!n!J9rNgC&2ef9mv~VD2UX*AR@UAN|4#!QwQI&^mWQNT3!8yDsU=-){
z5M-+YZ95V@7}En(W;k`|K*|i4Wg1AC;j&BvC^KA2_JRj-2-{VGpV<@+9$S96v~1vK
zhEvH#j+f!e^-%$z87|QdxbqN1tS-n%mt0<ukqH31qA*H~Ep2!~1iI|gP$xD8+&}`l
z)Z+zP-6rKvM*N$6K>oRm)4;+EmvI^h^x=w=sKCbzmyW##*q4sIAORibYG_~sdQMEy
zbBa>Bmt%_hx)(&COJfF7e-QJv344PLmw|dgz_|?6$k{R+8Z%P13_-doATpZ*ofMk#
zrjVJ1q@glUBkEyOQ1AS{qm|>@jr2W3K(9@T<z(61O~~A&v`$-MX2zh_ZNSWoF^Q`&
zz-ETPUWS{<7_P@4;{?_++-S<Z<Rq{RQVG%x7E{T3k*Fwb(#Qv)DQ!w*S6_vuc*7km
zX!)DmL_sickUK3%1&rr*3=(dgn--nlVj#D4lCab%?}C)WHO@|`cuN#bkT_gk2a|*a
zkCgojy>xIWjp;JnnS)mOD?Fq=z~DTuEyZAvW;(<S@m4|OCK+HGdebHZ&yzPM1HvXq
zDG3b_n;?;e6ooI+*#apKgT!U?Y(g_K7%zgxJ?hv1gvT4qB0=G3o*N*ur(GcB29PRd
z_vGY;HtNLmhQ^zm-k?sjX_((250i80n%>GLxA)>yI<JHV<5bW%+~V}Q7I<-foue&G
zPjPDoJkF-=CcrqaCU0N{L{5+}TR?Jx1i!rnC?_Zw9;lokRdzo4SPDl&sOF1gr>8=`
z>7uX<`V30SIzwP+kl0rx?-r|6D!Hs;y#581EK)>m0+_5Ct8#}|dK3(1*PwAU<0hzR
z<_0KQH{%A#<K+qx-hUAThM5(O-?-idP0WJl#$^D~1dZ%;jL(~v!5&_2VdD+pnjoc*
z!^+4emvvybIWJP1l$*_$x*oBNJ`YC&>qvELQ*s%lZW)aJLE>Z`GjU;pECa@aL>3%}
zfIEA4Y$bQ~KC_vBPXYQO3_dZjVVw9M1B50>9fVwZLFFxj^wAU9SzN}U6<Op^-*H)F
zk@qO8_myohP;ahw-lH}FYfZJv;BE>M#!sIVy28noUaJ>{w<&}7D@YxL+)3Wl`4(zd
zP%3|eS7c(kl1UTam24WiMvA4N;QOx>uf*Y7g?JSX-zuf6p!mD8TnNmdkp&7^sbW?s
zV4YVjt0`Z-iUUhA9yG9E+?7>4P~<9`zf}rdFJhsE4izLECP3T-3B5PI@}k~5_t>r8
z5z7=b92PZ2uK@a+fDh`{bSQfL=6J}f86*x!$s4eJtB|{b?OUbX9ZNGwsdWX73{dcn
zB?c&XrRP=877n3Gu{%<B0+sV>PmNA7e3ZOOIXtEYM*{9ULH*eoh39ZRImx3=fr=*1
zvr6eXoCY+jl%B)U1V=+mQgRNS9u<;v48|~7rQ{sEl9^F@3c7Db={aa?HKX(#BRaB_
zoWkx~=Ko1j4sVp4gJ>bMl1&Z`BX7_+5QVGI`v$<xi`2v+#pIydVv}O8kM?*jx1*{>
zn^8^@q;E!%I3&1{?<q()bIiz<X*}b4n+Akj6ujRIiF<>F0UOs_0^KM*0rB4iOs|TA
zmZ#pRVxZv+7`zG?MXXT%1`JM+$R)0#FPc7Y8`;FcVU(!jR!4&@LCLq2r{k#jMtM4<
z;~NF)(6??BsC{X43e@z`U7*Dopr8OtP*0LN2>EgKrB$NPRb+q}rLIB)EUHN<F2DfW
z2~r0kUu{>)88eFFE;Zj4*_N7b3tUUfw?(d9_cNm`?$Y#)vbYnCWJX!chyZJMwn|$3
ztx*(rA``4p7<Xy@jl#G~^GBw=AW?&D5XK4~Fu;9+1O^KBZl^8Q8YOmDzGQ0@+6pAF
zK>a+5l^IYzLE?CLB*wa|QHFOZ42?3pcQlh_8d^66EK8+tlFePmN26@+QtBIJbA%39
zOS!Db0c*VXb_MNOqhRhP1}K=jj*~{gtbhV*xD0p2&RXMbI6?{x;Gb8sii3vP>SloI
zI!WT5pbYL(>KkP+BLb{JzzXbdjRLlp!xC?{oj<`Al`)`Exb~Ypd$w@0HAt|aaXlzt
zmAT#;1#H*dpgHHE%RzH$4h$Ty##?P$8WOkKwlpAbwM|!s2KQ;ua8@;n*d|TCQOq`a
zPOL$wwkft2&v@bgty8ErD*v4_RR!2K34GxK&~I_YtdCJbn9qUHPQlt}owXcmX!ycq
zS15sX3RXl8Sm%|s>Eh6FWmPPJC3*-waWLLl6;NQEa<xg}@4S90Aiz4H_b-|>etZ-`
zBBvC#3KOtSVcT#oh*ZkxiOd_mhQ^CQr>JdBEKt-o69+9NSkTBqi_gF5_5j#Xkk~h7
ztjj~9j?fV}phRxEK6G4q6?9;oH{7P1LWj>fXgFGMm<EX>4o;AFg`QHm=?;(uU$3O$
z+~}0bt*CQK<yO==r7{B!ECdm{;%q3Cn{<gzvD|c1=oHI}La>AzT}dMo=!gtV2!O`B
z0}w|+!8rlQ(Y0x4=T1>5f+gxGC>(rZwhBeCPGN3KrmqfZu3!Y~l;(;^uufra(e>Ce
z+H@&k-uR&5R2h`fiZ-x88Le;w8<f$;riTJ(G9nMkXVc|kP(YhbnLz<<E(QvByuuS~
zq<~g*f+4~FCZU<T&vfG$Xr^1q2BfhKw7{IM2!mE=1{7>c&o;Tx?bmc87?iT68^NHI
zwWiJ~Wv#Ju-hLH(V1q)|n%06<Kuy}gfS@(qErxEt3_-9#OSGAK&-<`R@(;>lMIqQ2
zWQzBJLCI_S`UeFsLJVwpHaLA=S*;LAw`t%<pZ@UVN0)&?nQDdoa%qdSc(^Ts#_3ba
znl2FoQr7g@58i9{)$jrZTjtjE@dI|uo34TnZ19F!msoO2Q$`Y4S`&hR=bXY+;RFW5
zM38u`aEj9^v%gcER;d4uXK)N<7K0=~HBEF<k~luatKt&ODPXH^0}cUO&t<@A6jo${
zIWN2nL@?)lx617AX%?=>>hHYoRtbHlTvkYexn+}M8E1D){!W?9kc3UaR3!2pm)$BI
z-zk8r5Lf0D!Btj&rwCSXf;sQIl~#XG0bIMZQKtmf4=^(s{hb%$Dx<$s{?=pkcL?CB
zD}vMNtS|<1-kT$6!Qgp*HH|O<gKafvoEk653REypfvh+MbKa8cQU09*Ibs#eDS4|@
zeaCfJp$VG;rYpnP%qe<n)o>KOidWbqZ20UbI?-*xCnXl670fAit6TuiJ9Cu}0I6q!
z#K9*uqMB_ASw%3I^OjpB(&wE`95s`-+_H4qO^Q&4AK1k8wMbS^ipL@qe^NZA75xG&
zUt^(Xz$Wjnj8@o`T-YMVz@&WK@e1r|@-duu6HSg!hi>7uVA9}>c!m8IC$FMK3jIt$
zS@dB~UPp^O1Cw$xJRQ*yWnz&&kGxSq;`%l+rEhyaYIyVHoREq|o`A{gC!!i`(r#Sj
z37B-^mM%y4r06WV8O#)&Mc0B!_iTZ}KWQQ^O>$x48q3fIo4k(}DelwB6BKvg*Mh(U
zZ&G+Nm|;_Tw#gx7r=l5bQhKKMjXi;HN%KkRS)|HONY5foe)5i5Dh*eYwqu1x*rbdt
zGW$;o*&?|=@e7{8lebs~KiH(LxJZ$oxYrhR!D&E;zdme1<|^7@Q^2%z_C=XnsIxCh
z+@canwkUEV48qoaKrs-uC~$8n?27_dQ4p3e&?{*iof21(5Vjz3Zz=4H0{70YQ>}Vw
z){2F&MFD)v;J+w=Z|U|cC9nb_Eb&fP(l~y_R236pi{kZ`-oAL{RoH_q-f(Z}=!*hY
zaSpa9UvEbfj7v*jy52I@!Bz^_duS}m)?03YMfs|Dh)u$2e#<YgC}8h_X6zBgL)fBh
zWjur-yJb*-)v`>186=L+tL?3ez@ostbrDz;oVRj-*y2@IK@PScJr&Ymi_-I!Z(vb)
z-o`7<qVT+><Sz=(8|Mjo;ZVG^0$>wg4&~=9SHXtlZ-P7pi_-Jv#Q@0upind{UR-b7
z3>GEoEl<J1tyM7;ws=Lo&wXLh;H<!jcJmT?Q_XKTFQE#0Xg37yee=+3Hzn;&cR{-;
zX%QRIGO!}r$>*jRpMq%Ew9d!!U~0&`yVep1DQDMO;yhab;I=zeowXLmPHkwdrLj{G
zFGg52;HuVI8aGq7EX7<jywSBLy3Loq6j0HCgj&nRSpzFl_%|uJp}ya8^9F?-HL&C4
zFQo5c_{0^Iz36KV@t2>)rc6w;gJWv{4FIZ5iNUWR^&oKU6!43Y7Y*>KwT9NFW1b^g
zBh7kCu@^0oQ)_jNJMb1eI~`!3pLav3){AnXxqE0@BnMkfj5_$D*1jppS7WS31MX=>
zR7Fe3(^61H1LA2d6Q_B;uVoq;*`d~=R^K2hmZB}%y`sgrEWCC@E8n<a*bUI9P2#u<
zubdiwL;2UGSc?WZyE3oc1yZsLWxbVbfGxx~uEiW74O!)16tv>pTtfIYK$$j$J?7q{
zRlfnpv=l+n0Atz|z>hX5_uj3MEA}2$`v#3@DX?NwVxLTceHubVmjWwVv1oDVT=XTB
z;HCt7bLxqf>iz<<uZ32*6z|XwQoE*$k(7UHI#(fe(>2eR4E=RYN3UteTGPc!%Cn`Q
ziA@=J2KhiYX|L}b8oOfxRQDSc_=Tv6hB)J;sEJM4r_~%9Xkbc1lN^{5_54;G>)-X1
zW3MaXp_Sc96DJd#&^F(2+gY=Lw;5|IHN7Fkdl6IDQ2k@gcE-Tsnpj&{TVq1xmX$`<
zG>x2!-<pPz7p6m#d;`R3F=nDA!08GK#;*6PMWw#s8oDW%G4M@Gh`ff|>zb92#D?N4
zYZi4>l3QM^HzBz#>ZgF;{QoOS$uQ0E4L9>m$tl!qkbB6wS<s5_Z_Qi7LewdUqQQo+
z6h+Yz<h16kK~pce*1S1tsxC|Dy#|2OiWrIpY}4|kf%jWku1MyFL_?dzaq}GB6b{_7
zg{6n|R0Ks!3(d7jXl}-Rsz*pgq4gTTOv|Twg;b=aBT32qL~D2Inh7MLyOt0lQAoZ<
zSkoqP<dm07ffg<8X-jby4Y;Nk1+927K6Jd-krRaK-fBoiANY5&MP<9e(6|^D(P~C^
zZUR|=z!NgB0i(2>T6F_NX?at}$nC$pvFH3dXAgPjO_PVr6K-!)dbFwRA-~LG*hGUB
zcsaH0mRV{RAbZVrhn2sElXD4R*9@`^u@1W(t4GUuLpGnK`rZvz_2o*H*|G-Prm)+J
zH7n>AVoSjg4Yl1i1)+SKlzUssw7uk(5Ooc1f`w3s20y}bDae-hkfpNV4Jnb9kaG=n
z^Og#IH{|nK#Je@%gs!E)h6d-#Qe;De3uX<56E|da+7vEBimq!3^VZUnvkCZq;q6&t
za`Y5GYfKFeSvC|~*Z?kCLwa+di<VGx4XB|_LBFX9Z$kEawS){U6$@`b3@w4=8a!od
z49&p7u=L+7<#+`NV?pMrM);;A!vn27uC!lNi`*2ReFl*?x(0^G8(jlK<grY6OEl3U
zIPMBc&WL}HeK?v%hP)e13zz5d8d9X&eMJ+a!j-xNu4@1cy(nnKz8un-+l{#h3De;H
zU8*+T;38gv)wOgZuOXEguI7aj8&{HYMus0G?~=R?t$YhW2yF_-p!^$Eqd@)*+P^m?
zXT(lo3rkJ|L$m@`m$QTH8$}~S_Kl*EA^(O{ZzLz&6p9%nFkAxTHI$WIDmcC=$(_FX
z1paISGDkK5e^!^?+#uyT?BSab{HV-$i(HONSh>b@kE<_@1hLka_`^-FPmKhr)+a|w
zq1II(aZ?%|;x7gs;n*qG`qap&ATJgmZw>i*R%arg2C&ako$;1fpCznY1Jq~r@pve7
ztJR@82V>HS0smQDIx&)rZVEdM!PPshFb##HHwj&0*}CQj(WXM;4JE3Vz-(8`GS;ip
z=-q(zSsj`*fIdr=##_8%s?h-Oyrw3NH~~CMc(jJ>KdVb6?iGwsCGIKi2+m1LuA;Q!
z4vD8S;teRYB{W(CQf+nR#cbW8$&qnW>y;ztQLs7<+zrs5rOM)sCDNDhY%R;EuP!|r
zpq|yKB4fdpYLB;A(nYo)G`o~!q#a&eN^<Yf;xa;Dc4^3&+V~0*28F;BhOKqn_4<w0
zX1hs2M&bI^j*5(pxtdhu4r!@U<eL(c6Pm5X*4}N332c8ZA?|%`YGg>$HZ@&{Q&lE!
z0Q)SV;TnKFo5BftPAMA`yh~`~^Ii#gyFlteAnOp7O)4?6bH6BPC8zr46R2|qDUXVT
z>8wU`b^}UhwIS9aDcjJ%kd#d&Up6T=fsk%(ysm~#+Vy~>Y}BrCXs<?q`=-R2(Tv>y
zpk69L-hi@RLdvxPp{Ek#ZNPc6gl=o2MvII=@--84uyHmj(-4ZQDUDu(<Xph8wM6W!
zW@ixWNE2@meT|mus{sPPTGiNw^`>eLHDC$Q)&?YBgJwQZgmn`*c#9SXhLu$H$TuY?
zB!e|l{;#HZ)dpD35*)1sDrdF(@ld`I*{YEZXj3}cd6jEY#SsXxRB*f@T4FV+;s~i&
zCPQ@wUR*)q=qdPYX>iy<4Yq0&Sy-m;eLyrCA?*!VpJh_$1M0I(>O2(brMl$}u%1O|
z+Ut}6VrQu=c>`i+2~gI?0y{ER4@gWX*U=F~rcpT`Au-Lx9t5W9k~aiuFQLiWKq<OS
z!r-{(YzhWX+|MRpaRB?-lpGqMpJhYh449u4z_bRq&oZg&UZTZ83tl6&@PzSPLBSb?
z5UUp@S}8zH8aAT2mP(d41bi)PvX43hs5SKp0cxRl`%8A3bZ)?OmdQ@-C_}eYuzZt}
zb?Mx=NpA{{pS)~u0!Kv|x)&*$4KKWEXh>I+q{p3pnKbc$>ny8u!fnF9LmW7MkpIG5
z^l8I9v5ZFSFkoCk(Bt?{WXMJ!;}R&X0g<yzwroe4`%Oa6AuCO`Y`}3gg=+?Jsp8}f
zNraXiM-?DC%Vf(=gwCo`$zcdul`1)mMGKKy`^(AL(4~Uq4S73Om6{G%&8o6yJ0v9V
zYR&UtSXJh1*wa>(IU6>&#p>b>$xT+3dd&<dtHPW;@AxzLfZ=aba0H_4)uv$FZBcx+
zl_F#ll6h(96F0>QbsUz=Rb|OeL+7fpWT!3k3K9o`$P^r{A;@`E>EII*k(jcU8G%-9
zvh*M&&?aFKU>05|Fy7K|yo42Nur04jEu2B%tIC><q&}<4nvLpftD4rKMT^72&{-8x
z-T=$lBn*U$VU^`NAvvo`O$Q=pv26KkhXIqb1SM-o3ba&~yv-3UeD4#ou1de214m6I
zUVM|1JK3oxE_szo_)Jl!vg8d8ju#~-2uW9^g~I@UK!CqXvMC%HlCDY<4`0h}Q}_Uw
zvsk*k0hY4_C~E-ayeQGaHL^$%pRkgarEy^sRk`z)*|wJ8Weo|rHig5ath`<%H1`8i
zs8Pvr6)Dsx_PB~n)4<)Va!k|6j`1R)wfAF@Z5kMyMMPNx0%sF&UL*qN3KB*J0B2J$
z^2$dr6}Ssm6gqEkC$6Hj^bJYaR-qD}=|_UVVR6w^Ve?H1=7(Hg3zD)($zG6@g-Z6a
zXpl|F!6NN>Q4SW_ui>X%MfPi?$=ek6ny*t9Y+!3v5s;(-TeFIkaKLL;X&Sv@0#eP9
z^lxR7gexhz*fMLc9<AgguZ1j4-cTTR2|(5o3UdXigOE>fNXRf19&f<KEP=urU;>*$
z_a(pto7B-ZJjD4zgq5QCLWZ&K_!Xp>fHdxfYhQsry<jXYQl|q!u?P`s3jz%F#2YeU
zE&;n55G<RbM`BHHs=WP9NxUgI-g^Q|f|N_yfj(IRarMBbteXbx4hYM-3HI(cE^Id~
z*d1V)b-M<K6jMd<o_Lofh*!UPr@Nsgcj8!XSI4_G)G0)ouv|T{LF;BUr=B&lgTgK#
zzygoev*h-=yLy25y1V$I{JOi=1oG?dS{2AIRuk`ci$=k+LVVq^;X4s7chj&CW_Q!D
zkY;z&s42}@Zu|;Ld<r*B)182pyP=hD(=<+8_HNTCor}(IufG;%-KGv9>~7OsaIw1$
ztz=x#jSkq{B2cR*u5R7+3<17rm+r*20ErZngRr}+MuxCMCn4x=e$t)zm%DIS&yBt*
zL(k-PC>j{T?k<{f+DuigykqZQOR%qww9o6lH9Bs6sz<&l$t|zMJwD%+-{A$qW_hml
z=w^Q(o05|#Dcz>(kM}$kCb3#qP&R{e(N5g~dYOxM>W-w`bJ0%Sfn1#ncIvB_5-qG1
zkTDZzu8vc0E*hzOoQrc!jhYJ6HCcbW1DQJ)mFNz%%2a*vUMyR=YCx;ZHFykflEs<~
zFp^t!uAzZLluY5TIuI^%QT=^QE(Opgaj2FH*~MGKI(7`yu!>zXZuz-P!n8Ie=hHRz
z?vp0#4uH!<sqqeY%S^eL^BY)L6C)!QmiN{UsLEV4Qg=XA<}#kbFHK}F6BCYQtYXBm
zidFM>utv?d7uX@^sv6pJX{$zdEN$fqOe}2G;JG7a78k!j$~jVt?ty}tt7z;LRC5*f
zyRdhtA74EIE^`(9J$LjiUKd!S5xOHtVzShDuehO3p{_a#J-jGry+)W+eRn&Sep2<_
zlvw(?coo^C;9a1r4yArhs>40i{yCS%&6~lCf>!i4=hV=-HdAHBJMJJ;z^z`h#ZmJ-
zeNiqnlXq8_6}<BU&CAoAE;bEZsk~`N_|A+1<GYny=>rBxWzNA)TQtaG%D!vPAwE-H
z%{eq|1Ls4_lk#s0p4Ah}GP92H1xmc|**S8mxSPPyQy^{%2hXp0B3<m2q>jgMqSOHn
zn;skBkjidP=*cEP)9bj{&uLm42SY{<9sEe%!h$dX(%S8QMU&$=UZaUS$7?jLjbjH^
zjXcx7H(5-4Q*usJoHwQ6DgGkYylU*3b5s__P02Y{jlD2O-j_SdAkA6C@dAI!7T*)P
zGA9ks9YvVtq~Uo}^1Y;@+>t|Ps-F1Okwj+_ht(~AkD~}Nn$u}>?kFEMeQDeh3+_w9
z=2dN?n0QCT=oAX8qbk+(#Ze*Xe4Y8l0Xba?I8ZTDCCEE0hEwpY4$I_3jqxi<@lph?
z>KS7@-5*aaJVgc@_;JbyOKIoQrD1%XDl*<-pq(y#+8P)f8XJYjH;JS7XmR9JdN&12
zli%4?CGrmB%!`r}gh+HL;fb1=E*%_@nCTR|0K`nEihXrt*O@M*8n*N4QmW0PMaCf{
z1<LA%tjn8(lL=Abn}U-Gq2n(KTEVMSYyf8FDPG<UB2u`m4#doKTB85c$A7r?R=!`4
zzIM0Q{vyAm*X^@eX&?Xb-+%nKkMeQ9{+s{%U;cIhjyRD5_irDwVCcNCPHrZCF7w5x
zl7R(Ob`F*K0oZpc{ZtCL7lBuINa8u5bO4Dxm2xRz<*(%%)Qh29O(hdTrRk{zK&Zwr
zyQ*Ag{pQ&Pge$4i&#sE`xSve9xXYcWuBn_U<;E6)S9e#SzEcoRd0-1}&{GLL3a;r>
zl{`y<RBZ}vEw2|c8}AS$!uzIjJ`|K7ohqnUVC0%c3v^-4&Z#<u1;L}!RHz%Zx~8${
zJ?ya4RIeUZ;A@%+!=t9#l!?4#Soo}}YM$2qDeG{78)8=FdM}oy*r}M`f~tj6rqE&#
zcq*1vEH6v5$jVUQ@0+SYRj_ok@SrK}bqSCWt3(o$Sy(5$!M-yKZ;++s**9q-DGk~p
zOe6&<cBX>Q3W@~Jd(huofD4(rhZo>c=1twZASu+;HMC?|>zQ#ryKFlv=jgUo0CMuB
zjW$p^jd3L}3d%SkkZgB^Y;mrjjxtcEXwlnL07-PIy~R=5m1PoM9r>$YCDJW{4s{{l
z3xKRXRU;mUxeK&j9O{Eh$0$hd?vpp;f`7R($rtDr?z9(`iO<-P#j~Wc=1PWHGIy^7
z!&;Do*ok8;3q|+5(DGPtjc}nl%R(8~k+;>dQZ@83^b1rZB}nm#lJ&8cZw2UMEt!q3
z?tvf0+oQ(Uqf|TMCcG=%Jgh{!C^;!9a$TUR3iAP~aA(|Sl&nTZ?~F}-t2K=ZLyyYR
zp$$K4H)r)7W=6WQit(LAiE}bA&U>S`roy)nWr1^~ippjUrGP3j^m)_J$V=dIp4UvW
z5S3a<L8U9pii~&GGYz&PxyG~1C~62QF-Jv0l2fJ=wT7zd^caFno>eYUTlG|hL^7Rc
zIYtz6JGB(!A0C&pSo(&#ol*Ay$)TbKU-H^e(o2!&6>ue2aCnrVi;B~QRWeZb+>2^e
zApM%dv|Kx@1*!rA_74h>1#dlzd|~g6JOKPwG0lO(buvrtI#jWcVGfMqQ1MOcEQ<<F
zd(mX1+BK2(-^S9*MM}}Eg0u+$abH8`m6{*xSQ<H#&kor%DiY?7r6l@*{f~81XRgk&
z6Q{BS>LMvqc!iR43Z$Ua0h3!_Q9NY-cqp@Ul;g;P9l3aOzE#a&27SF}W_TY`sVlUd
zXK991vWKf$64ad$s$o<TXjvtIl_gMU!+C@n7JjG4&#2bab%s#ob|VS(D$2EZGxk_<
zVRkd2vtqXFW+d)Z%0$>CGcov;$-5U4ZX+DJFa^U@cx+)dp{aCO1*vTpH>Z`Ig2y#@
zVQ{|g309e<M)4R{8ISHK*Fa^$(MQf-hF_ngyh^~SK=#U5<dLDkm3g0sl0q0la|4xb
zhI#@z{mqymLg?trjL8^=Y7CgN`YHb2n4Umb;Yd%pkl2#BG#ZoONETRQ8n~{cEUhuO
zB6I!i?4!LXH-A%NPh|>fOnco<;w{D|3p;3?Wfj^<X49D|<B?#lGqISGD|RL~Jju=`
zGsWFX9W$7QKtQI*b4AigDTP!_Cp#5$x0w+DWP>5-Z&{U)G)oy2ok7`ESq_}}uB$FL
z=JuCQ$#{_BhS_?UQi`I%u$LoU3yjF-$_t^iDuu}_lw)-=&Cnw~Nn?tZllf;dgN}-m
z+H|G8z*d-(Stk^|uFNivbP>!IDsP`H=15UhNLx%~eexVIwbqSV;}N~T5S`D|3(St8
zc=-nZUPPfY5WYq<@;Z^~?Ja`4BMSF~NGqB-T5zbW6Y+@Y?Z{koQs6>g0z?#s*a>4$
z;9b_4*HSOKmg+jRv}rGupK8#Hmh5&7M&30Q;{?5EO=SXmM&~gUvLg^mKz^76mkI?n
zXhzF*)p`bcF*2w8CF8OfPm`fhjLB+<oH#*E3^7*;l?F4#8Uh?ZLwXB!K_E^>vQ!0a
zoWKsoV=x+~Cm3E~6bMuhAQBqV4k5r1df@+p8>EW#33X3!{6VBA$esqm>j?-aP#X^T
zrfCZhEv!Z)WL}MKo|bCT^#&I{cw9b&(B-BLfOTBTY}f`sD1jms95m5#feV46w1JU$
zuTM~;u!1$Afr8E@;6Zil8x*A{bdCr&Ayb7l8_aau5LvsF0PKm)B6JKv+g0DTfJ?mI
zwwWLv4E-6kgTjGNq|8C6;8o^VeI>#Jm<>Sxb<{OzOHW7!kbTO0)0qilDSu37`ip}a
zfJ<NA!Q(e41b`mw%1^m7Rl<F1s0Fu>EXPomrZnS@^hEG?Uf~@}FC6|ZAJ<K165UZS
zK>{!~Rco+UqupNiUb#YOAn8zl=4=l~Lplj$?O!kq9V0x==c*kd8@1fT$FxjC<+0x4
z^8GZc=7Of}^7ZA-+CE<Yu=To(zW(7ap*YIdrptW&57TAXDUabY-YM*s_q*LPcBibC
zFgHJpmaz^Gn`IuA52Gclnh&F8K0=!%PgmJ2!=g!hr3^W=S9XS<J?xcf!H~I<_m8K!
zl2%WeE9pbLj=7S+ny0xkdwy6eX^f<`vdJ9TUXyG5&W^PbtjJo)UGcP5_NTS-MRD0=
zAJ$4(rev+;b^DkrWkZ6wa+*+9GFJ*tEOX_QnGxp7W51-iQb@U{xpICoSMt>#b0t-I
znJa5r8eps3rbdPi9Al-^9BE;>M4zx#J`9y%xkRd+W2lt*ke15A^ZnQ=slgswWwwy?
zHB6VVLDEhM6T>l6QiYM3lCFH3Dd(x!eC(9;eH}X`57=X;q&9oZl%0zIu~SmA96M!|
z84`9%)mTe2CC}F|Q*MK!tmd*)Qj{M%Wml*9ZMaHQ!A$vPxs;t!?gH8=={AI!G7OiP
zCGC{1NzzbB1Jf~8w$G+Y>NT=dvJTC4OqI?%%rRE-@_3Au)N78da?lKLjFrbyNe2@x
zl>lkLP#LC6*sWxzTqrFrGo@<N%S_4om9kW-^s_9L@{Jr*rOKtkRM~0tkg1Y-^RZOY
zjCvhgWfZ`cosy3IW2Xep9EQplfp^wQXNJpFBSWR~V;@5$ONxfAQdS=rD@X7oOQot|
z%2LUivouvcjF~B!T>%uZRBq#?su;^uNuhsCl`=QcR;l{-v{f2KvkaD1bt!4E6lDAu
zELCS2+PIfAJXRQdg;YM)N_tz5y;22xX|Ghu#xPeFMV=jd<&t5M_DUKSWv-NU6>7NO
z3CX&S!II*Q2Fq>Kq#ZQPGLP!@P{jQXvo7p$Ls&OiD^=fB*2+^Yoz_a(&S9*)wviLB
zk=Dw^TZ62XL?9h=rRvhlTIqU^Fjt;}&S~HLWUdrM1m?=DCj7KkURetG<7up<U^~W2
z?Kv4NRcl%X%Pt!hEtW0|0Zf*zoVqv4(JB)p)SZ2p!Z|^M<r1{u*ehLm#i4``7S5Et
z^2Wh-9ed>|Un6_vsfh-Ar4m7;xpJIRZ>o23ej<D2IAzmluN=>sWoZD?9U10I6cEBp
zWUy4CfMc*cRc>Un>`F)*x(}+ez_vrfWk-fZnJv3g7|UvTYLOU{=7fn5<H>B<@ChEP
zWmAGo87-SqRJY1Zmrd^qR?A~D467yFNXKM(Dig?LX(#=-Y?db(zigJKnmRIB+HXyk
zrql4)EafggMoZnUts}9kV$6;evrg@LnK3JkXR=~e<>ZtVv#M;4jF|Q0z?BuVVsVZQ
zQ~O0W%yQDTBggS0H9B%0Gn+JRnC0Dod6NAe`{hZj3vDoLjQAR4!MtVWqyh6JbCvz_
zBwL-Ve{riiA`O@~(iF>lc{7vnF<z#9Q-;f1^JIXC@>9}sxl>D?gr!XPh@lr#2ue+*
z;ZpezWw%tQc9<>8Z_Jhob-ev#%41r|sf=~ZyT%-83d5!8@{u*pV9Fpg@R%;^yXkVt
z;ZDn?)A~lkrK_TzESCa$$#SWZmB(-?L!b<oGQS_oWp+ZV<;ju;qvgX08Ai*YC`+?U
z5`=VAG+H7l2tMaEWb&28Qb{yqv6Soom@E}nPP1iKY9^X3<%5^ma-2*$FkH6Z7%mm<
zFT14ziDb6~MDaR?%SW~e7%m%Kmd9>+GBD6?$!cE5ZYdiu?3VT2ZW$&?rb>X>Qdjpz
z7w;1G=-4e4mkN#P5#cSf<q6R)*q)EbXxc6n7fIWtf)8Q3tV)<8)1@n8n{1a#J|Wws
z0@P%>R799emm&MEr|I&9N5XXZ3`)#ULG+QP%SS{W!p5*8Ww_Mo0Hx_^rKH_bFF|%o
zxv`JoaxxT!fmZ$-vn5T#vRh(9UdM1LB(MyZ&!89DEg8^q?3RMf({QQaD;X{Y;)KpL
zm2UP#E>QbHjKK*Fpmmd$OISA_;Q3?SBq0A`-7La~)4EAB>9KBphCm;9GdxXGi6Ecm
z&4aiF1ebtYnKw;HQ-M<vZt_HpKFpi1H}x9+<MkrP#$>+!(O;*!k6$!z0?Dkxwv){A
zut!45DJ^=Ik88K`bwCEdK3c#vfp{o1JypjRwWtFLnnuYiSUsIr;dg^8;mhg}D~DLB
zY5U)M51=yllrst#i%sxPpwo(Wa>DaE<=r*M|KHl#?Ci4J*m+)8v4{4+C#7GC(*WrJ
z$sp*&83man=nfFL2kD@Z+s`ZU;i~%1&-Tf7Y{1^)_g0lyQjrq1xR}F4=;a_&qj@H<
zO4P!wx<tnJB^-P$0LL>I)`ZDdLMoV8Yv$4=B0IaCu-Mq~Zb{5#k`9)98Q{4ccIF|3
zYbQ~`S5$hxY$NKN8`%gQEkO}Do?J5{depSvf)UNV>R*DdLA<*Kbn)kb@AEaz^zkd^
z{F)<IQEWID{+IR3620CcE}86lE26M7S1gOVUput!KL-dKSDZOL6Gez6*n$&Szt2B`
z?vsJDRH2qd)(dYOMs2A)t&@zS4VmABYiDeQei`kLtQ%FO1w^w{la{sKJ`NyP$%!pL
zsAeMSGj|ccJVK~3q0%gS%?ZW#Lxf<d?yNWFQ|tgp>{>G;77%a)q(0s1(Yl{Ai`S6_
z2{kiAicUVwOuyir)GiU}d8E^5i|T}w^Jtf>x83HR=infU%Wht;m_MSz<7oc{^(Kc#
z>oO;WW~4oKptuVnJdcbT(clqsUZTNs&MH)6_RG=C<)qS#jGAr$!fDRDJo?O8p)b0e
zI~XUVvsC02Oz+APujE)R6?kP&@)1NMPJ(#66S!AdS19?{$gMQTi%V5r3(Wp23%!0l
zU%HT->7oPmEjiP8==9^p!3;rqIon(VAZEGaf;^JK!wiM+$%$PfKgdGf>>G(+atNEA
z{PWW<l4V9N=E{w`A%IaLnzLf%eIW@An>s`G%urOHfZrNbZ-L~}Q8|zO?DJ16-vG{Q
z)SrIqTn_J*6ny1wsh=SCcPt`A!M6|dVonrpiw7G;V|osWMxsm$i@YWNy#fUNeISTm
zQ?b}BX&f3dfZ@ng0k%+9WObe8-FULB2wON8UtLE&Hyl9E(c>14)6UmIZjFk;ZpoR*
zU6^<B@>d{|LrvUZU-|HGgIz~FH-4}K+ortBQa#x%Ii9dDJsMZ|Iu^wjqR;V!J%efm
zc7rX++=d%p*e!<{Zz$BrK5C7=8?DoEB`n<O4RsVt<(;KXUZFhC63t!#$*@GTSIQm9
zCme<nIas3DE097g(d-ot4&P_KUrvGJMtDN;>Xj&Nv;}Bb@P&QQitfv%WQC;F^LVR}
zf7)|tTuQW_v*$BGd)G6*oJL=WVu)o!g4!eVYeEnsoFV2?aG-F;ULmS+Rp#m7M6<Z;
z77Q-R?vT9N8?DG?Q_M0Fd!D0myl7UBEzqGX;e-m6yjCxoT)#MA2Tzd5$r44wzGMu|
zPwUqE0Bf-z+$)^KER}vOKns`H^?vObAK%y<IM<e(&NkQh9R~@w-ah!>uQZRscKf_h
z0sTwH$zRw2!11do<%2?TOXXV&73Nl3w4xgd3T)9hf_(EZBZyXSOU_GEV0cT;tj`*)
z*UxbZ`$xfgv;|M%Rp^um)dF|Ymax$+oR+Po19zeftHt`f)VLrMtni&pIW|$_FY>!G
zRSV}SG}ysVoXZ{z1*xW@+bfkM`qgrOTp|XtR26m$LMMIO6>r%Ftx%`SG*?_@R)a0I
zokl+5msk#brOLpTJa=3IvlZesTavFkoMjU%fn(a0g<>~IBqpwSI1Bi+C7!-5i76v2
zM<rQRc_f86{Ax90m|GP6sjnZM{#11kmnpKn0;ps`ws-v;wZd<rKe+tE*0x(s_lS|r
zZ$1d#t|NI;_hSC)!>4%Z(&5CG#9P1hWXrd%1h9(JY%&kQV)usB;4|B;84^BoCl1m)
zDhgw`B>|twmBXRaTUEA$3b88=PA)_N!f`zq$68$v#<A+~`)7EcD<lESS^5m{uJyqr
z;aydTc1zBjrVi}}1>L8`lc}rwk<beL1hF{jMoUNVg_pkS0|8-VzNS)!f*IN?jPMc>
zV2N3<AOpBU5()}b)9}A}zO)6QjaCmWS_x*V;MPP0_zPInk(_U$YV`mo<*Fl}Q!^Jd
z5m~LG(f}0IP)I3z0e4tcnW_!ns}Sy0pxs=;*cZ4t-w-Xfxi3jSEhc+QY#wxj1?#h_
zwk=qwB}{9<imfUm6h>|Z-C(H5X1B5f`4z0#@#0n1rQyY^_8(!jcjvSLX){{rLL9Sd
z1Jc+MS2iFmHoUcJYxgS<H5_{_x-X8s${aOQW-b%|`1Pta2q2U#Nqyjus73m)JFc=v
zEjc8r3{s0FLX|!G1%eI^i7zR^7MCP;uq~wxV+-N?T>_;PD1le;%<v6QPHm*EB+H>y
zv^?p!^1^lkSj|$w*)2IUuB^Q6Ni5b@qT|U+9^Mp=TfU|*k2fAL+;OpsR&+{VcE=az
z!9!uWxr)B*pFs*Ke7wrcPU3uv789L~s?rWi$M+Ut;{q_W%JXGIhrKxQC?McZ>NTAW
znuttYEToDqfw>RhF|x7q2cb+Jq?JCR#n0Ks7Of=Ml59!(X|^&;Coct{*GEFjA|pKW
z#qrv|k|VBMUUK>uM1s40K9ZtuyifAX`6hr*tx~m4>Nx45ubM6568~U<t$jg1xZ9m;
zK)aNVi+;gC@yJEV^qpO7DXG(OxH@Ut?Fc6oWngz4Zpj}+XB9;FCD^owvn}^CDR8#X
z5f<PfOLT;#<7&&THwD#Fxdp%_3b9eF%*Yd`_>z%-Fs%>D6=#~Hg@pjgx-()}2%#+1
zncb4pJ24a%NFbIt3d^AU-%4az89@cW6#f~!7O#0{Y=2A60N$n)f4rv3&lV~@Eag{~
zftwT_qC^Rab(@?b2`@_sw?Zk3l}T9#?R(UDz`l6No4v>AfdyuCMi;RGqciZ5x7Gmz
zFR8k-TM~gSVKugBe`WX3gW*>KeOG|EuUiX&FF522$@$7|84O~bAIWLW!?*CTD@5M~
z-yLx2ZjqqP(RUe#!G8FpHJ5;=zLC%PP}Qj|10O1u!z~ff1MTRxjKerC^p<fLlw(@S
zYgmXvuUnSjmzZl9mhLM3@Q-)Z8w>w<E5HauY~6}55@cVuj0Jh7i*w{FM4>{_)6cH@
z)~;mWW$)aTe1(J~K})RyKw7L@He}w(fRU(iJTb*=3s}z;f$9rUOzT8kPdu?I*_Ihd
z^n5IsO;xeolCy_05gl$(pv(o=56H8*OvtQ2)3r*NF+7(+ZCI$EWTH0wH5hz5EoLAk
zne4pRt5CDaTzd)1I=vY{0JkbBa!WR#*JVLwaxJ(v6QE;E(9|tC3L1@2?g8h=w`J!n
zCEolvt-Rr&=du=a(0N%4D1gjmEheR?&2!r@10L^+N_@=<IFiW-=3;`=Obd{~h3MdU
zT@)-7BQw{6V%pCrQ3_WuttYHarb4${6dFAF2*&Hzt{{$X&1E+@+`UYYhr)^QmJHgV
zfy~4q95I)fAaUQ~$nQcF{4iB>+ZiOqC8kGb6qlIJ>x5MEFDHTG;H6zV0V>~_@WutM
zr!5(@$Cs1~{Jsgdu|?56?F1;oXD%CHg=r`o5UKc=xr~4n<|0M_?7?p5!^swKts?*&
z*uw$w^Q4eU>PCV}3IGWcM?^W*3~eQ<wHRgQZE2}t;jL}uQo~{_Y{_s~Ba<YPQTA81
z#J*9;=`hhTo`jXH;45P#e7A{`vA_$qCArwOewvxm(ory5p_~i}<YbnVjm3KAw`eUA
z`6sqyNGM)uhqAF4d@W0-7cf>><V0VHqU$=ouz6a1QDnWC7#a&i7#|6(69qcCIXq=T
z81!W8%;>0A7#4PGOF}t&Qxjc?LKg)afbW>Vl;v;>*;1szNS2}GZplif?=&G2BeLjj
zp(3g+Ei;V#m(^*VzPD#aEIO}a3KA)8i9X7l-s_mcoZh!*M)*&0=X|h}o%H5j3Waj*
z0mb1K#Bg0Da+wS=#{!_ploPPiprUuV!5}sCofnndHKO|1qH)?ycZtsBB4QQ3EiEEo
zg0yuj-~z(PRCl)o#K^?LQm7yN%E`hBC!OPG9lqLbo<HJFMao#HgltL5SSXfks*YPI
zsC=0@&6Cje<b2^yEl)t;2r$zpP8!CR#1S*RGp3yXvf`f1R+vZ4@&g8sv;}+xE2_De
z7#+*PnTmd<07)_x%PnA%Ox1GB;w0Bjx!iIvNhUVO0t136<)UB_Oe8JkV=>H#OI#=A
zEjmBrkMvxhcvvM9Q)2<AbR@hmcC992#$V>m0Y=(_d?jI*&G>@DaGR-Wc7bfylr2)I
zfNmxiA63%L<l-UBIg&d<u{a~~kKwMq=I}*dw9XG$kqOOLoZ~+ep09u`GRwn5k2F9`
zq2t&D+1rwMa8bC~k7qM|d!F=aMfc=Q>f2+HVJf716=<Q&^z8+0v<b{z03dzMNj&|V
za=cEw#%7)f1cb=M!Sid0j3jUguUBF<Xo2Rtkeqob?zREDo4zQYr}ZR9M%T2V_nBQ&
z*bcDKJA*Qu&(uf8qS>ZCGVn#0O?_n`jBM&F17-A)&>ANz^U2dZLo^@P%C5jvRJZtg
z5;=DZeKOp~u0vFHM-txkP!|<4*GwgKOR%`x)Q89($r8?204mwk;=9IP%x0!gf-BmB
zOaUcn?+}F4pgc5Hx~(_xG@I!HD<t{vR8+hS7`;kbo(ZJ4C2?B<#Fd@zi-r&Pp}ecg
zj(SV-E|tDkj(;i$Aro@1f)KJ9t&cZRUE2ye$Yzl)EvHp_!wNvil<l=8lgoIE_@SwM
z*E<~1XIjNQ*wej|aq%HjX{mSc3?^Y9n>Om%ULiVjB;k5naC#=Z-j+oEuK$$3IC;2A
z{Ja6anpmqUAtMv4uM$==C9ZABdG%T0b_-%dEo5JXmCiu+RcdsYuzmHm$TjA<?CQpP
zW~ZUyq7}+0TQQ<@M}WTgo)`7vN`A)tp0_B}QLg9Bo^BYeaZ;XhR<NHNxu32?Cv7M{
z7W9yfsRu(wC>ES8iQ$>FVi7Oe+e(Pml#x<__1I9labS3C<UY58;kj(+lLg3=<dR<#
zv_ldjksOHB$+4jW_$?}2m2{Ihry)wc6YVyUlvU#4mH@r$h(dw<j0>J<RB05R=#?yv
zCsJA5S}4F`3CgRbpKS6>9>-IO47e6{QA3|Crw=v+)2SR$SQf?Ig2h#-Qm6lM4_uk5
z;?@#TPg7Og%0Y?=v{$L_Wa2EUB<#J@-*fLIP+kS{W1Vj|4v$P#ZY$?Y);+t=)~Snv
zyn+C-o{-!M0?4|uj}HRKx<1?z-<M^fTX;mdC}+but(*z?FV(%R6znp!P|q~kabVqY
zW`zIh`j`O`S=Yy0*j#nXjZ+0zWP<Hg4iKRYIItoUYOew-vMxpgC!{FUUIkWULhV(K
zDNU%o8mJ=cq8hD%v%WqenxUS)ZjM<^puNgbto010*K>MnT{z#$0j~*@S2+Z>gydDo
z=}eHkO76e)PRe}1g-oS#D{!F~bpoDKoG}%|kO`z$D+PYGh^bTCX(i(;?z89Kw{n<n
zg6LJs`&k#-zET75P1}Hb6b`ROEkWzD8k8F}YS&*O3LUBjiJh9jdKD(DkL0w*VTO3f
zA|gc4OTJn>Y%h8&F80MIfr}N|uLiDS3vw|7_QHC`*ES19Xs881#ie%HjSAIC2kg5A
z(Rop|R{KI^fd}n3t<(7?vy;G~Ez0+bPi?Lt3!mCt3gRwXw$6yQhm`i9f*$q^5I|dy
zcL;Kgd_6eECeI&Oq3ek9{opH`>;<SJYiTb6m1Ir!0^rh?gqx=F=$p%fonDsVtw4ZG
zg?Q_M0GY6XR|W86LIPF*Kc=F)6)=wp>Q@2tB>OQyS`*H%f;KbZ{3?jFEy>&Bgquu8
zgRsm5{oA5(+RTE67jA=A^uFuCxa8Jzds2b-yje}cDGU5p!Sa}D@m8=r2GVbTf&AQ*
zF?!fhPG`i9f{Rsk-7Sg!w9`t4VpZ3zQD)dwT(|Oqwj{@u{iAB>*3WzYw4zt|-xnbZ
z{<mqp0K~?G#H&DTjPfE^h+>rQ*JXpta>#I=FRmASCs4d|qqs@F0G#K6;nkLOE&6Qv
zkgV#f4TMe5$K-&8_Y{S}rkFVz33hi#XWZYMGazg(tLt^y8I7v%6@al-eXkvkBURI_
zJ)NJ*=~nERWjWm~I6Zv$ZE$}zKSoTb1qkv&bgnu7#;w)dHrK%2ya{sfYcB@y%F<DY
zxQbUXA>t~Y#}W}&spW1}WJA<@zf4>Ym7?%g^(mgJ@g_`M#dlgwUyXaU+O^OQ7yM=@
z$Fm9GRzbp8)i)Dp7^}}hyF<q#B-&;Iif850y9eh|l@IN>oLcqlnQu!UQfC_{e#pvV
z>P<0Zhd`Y#hxOW)z^IOs5g4t;qR+ArZY8zDgfgq7e~7i{I-<kNo}XG@^z7DrSoAEZ
zc6$6d-<nvLZklHrtIBO9{l!$}c1upzi~M7x(O7Y9BS6Bu>6CCYMPJ&ulVC|4@yE|R
zShfl}#)M_7pkoXyTP0V>ioV3yxtPFfHFr13<W%T>hQPMubYEW~)COCUtW9{G@~pCf
zx*S3%T^96D4@FeC43UvkkS<n4xln<+d_?@<44_KeR`#ftrETkH3u{Fm;Q$P3MIRyA
zYo^j6^(42wiK=ixg&U%YfbbPs9m~qMo7yVgv)o~1;+YU^6-0|AT<tod(57q9iDH%}
z{pJ_KEF6;nYc-)S24bxSvc-z{r9ie=shUW*F5%N^BsW^A3GmvI##Mv%;F=tC{8q^w
zHW`#AyxLWPvRKik8Ys(_<ckSEB*<DNXk<dH)d(zINezZ5rks|;gs8TJK{*?_qSY}-
zmMt07Mqp%Bn`7QlP9bJ2iLjQ8HkDM_Hys&E_AR1k<l~xnwd+aPH38Hr8NH?wx^=Qe
z+kvDD!I@#VoGS6i7x7uRvRfPI1g+fJ3d4NsOHRm&>gR6BdDVBuw<}4`cI)HL5UYuZ
zqMoSir_H}ZnTLOk4O^nqD(I7Y$~q(j<(Ah?2#VlmTN1t1w+_vgMND#AhYeG?^|2>R
z1?X8#kjksJ1)H&?z^s|-Zi1dw0_dA9E=MQapb%)4FuVzYR%b>t6M<F}l5%S|ydf#7
zs#_D1BGUBA`GIBe;1ETBwHr=IN>U+J5Gi+4|A}axTDx^-H1pQ#IPobj@;h9oFlbv6
z!y!jMbIWyW2|RIrs+D_K^iJ=}>$1~5IdU*6m)!{_sfkfht=yUz71heEiBS=ttOiQu
zVSK8FI|NWx6QgqL^G=M)Q@JEDDz`AHTNJ}^^MkF)bh&&BZD*F-twDIP+sO=A!c$BY
z;NA3rhiuRD*lSA;C7x@wZ586WykZ=>!E`#DB+jh8TfwKiDG9^GPuJocfXd`_=n7Gd
zJLhv@7xZi$qCnTW9DvHq3cb~UGfdY`+WKkbQ#-oJV!*2RW=rfp1$$x!t~ke?f~9Rq
zD42#MO8HFz(<&&HnZUH`h@$^8BpftPA=4^n(Ql^4d0P4Iu~hHcG?RItRYTxXrVkqN
z=Cx^#DvHy)K4#A4-)xXZU(;wnt2o6qwk6Tk6PdR&t7Jng>+Z;gfKZvL16+ZqOw|Fd
z#$ND<?);HO<(+)&f`U@Z2tX;*b8}$Hvskq=Ihd5`EEzzgOxI~!lzw^F^I7+4Jye)y
zwYIr187j(zZAm<K-RSesW!`*{)J0l%D5IhaTN2vH<N#}#!mm|uEt@tnA6-Nw2@796
zxRxpSS_RjVT$2@8%M^UA0&973dDhsfQo;z)o+<*cRoL9NB>6rmB(${h2vpA&#EJo$
zqbdAa1qn10zgADR*f)u2xbC@f9dcFhFk8g@0T46A$5a8tYzg-bCe)=p#iCI4y8=^(
zf7JB!@b6Qc^%YdiTw0B+@s;8<KE5e(=Xx+;^FY=r2(c;1S_MQlv&!)1NZp4oQxLTZ
z-QE;L?eM6M@`Xut(o>bLTJT~{!PM%f4^tSmN)IO(wMwz%sq%Rhl+2b;Mhv9P6hy5C
zQf3OHRzb?l)%DoLAos*{*BF<nQYDq4n<`9P8Qv{vx=-l%Y)@7e);gwVMQyBnvyOhU
zJXEcoDpFh*Ii7RrL=d#ii-k7OHdA$qD`=Z399#A9&DSo)#e3ijd==*cWI9*wM!=!Y
zrI>>k`ds8wz0hd|`W%0+A}*Cu40B;#!V=AuE1Ii%Ru_|b!KBS4^Mc8nOW{Jy;#4u?
zs~*caRm->n-Ff(U@%XA`TtV*4#J^RCEN!Zuadnt=WnOR>lUl_UH1iZJt^#<T2NriB
z33lFmPk3wbq*ZECJ`BE<iuN-LJ6?xB_}C6h+Y!i~X|f%-+-Wi$fWxQBbT}1}-ZaFx
zbiv`O&o7nO;`^Ri+_<ucn1O`55S_6<NVpnALx<RyNe@lv6c+A~AM=}hPSBaY>5y^z
zS=_h+=ASBVTmk%V#^lsF-2OF1z*)~dWMEjnojP)~LmjPHSOiX!fnlMzCHdg+`!+O9
z@%yIJL&%IKxV!5}&Quogt^yO90Pl8ta814h>H!LPSDi9&Q^>paS#eLn?ha@4(NIjv
zH*0|}EYi_Aoeeg&6<ZX;)(%o=3U{~LF?Gdfd*il~NAEhKn7gWI2b^eHRe!^8n~J=#
zTbfCMw*|4(vfLuI$OM|=)Z2o1<to=j{?L}>lfqtJZ+h&;2bs5N`LTTq^6coW=`Dnl
zjxXjyl3!Z(4VNsuXiJch*bmzs^$qf+41xoqj%{c6eGsJFVt_x))38SN*g=re4*22B
z729U|4)`G-%@$PZDDW8Ad|zDP;kZ44sX-Wi7&A?E<iHfUDl)d)POH#2m^lx4wcP|X
zUFg+D?w$+2+CUk(;H&M1a#tkJpp33BJmm|H>emNwtm3I`m@_KLwk=D{-C`YAW$;F(
z;}PYLc6XyjBK_v?`Sfttr(z=BumLv`bNY?9_6(P|l9e@c8QM+)=u{p>%N)^X9eN1Z
zxhTf6louO&Bg_}I;<#y&Y2Va|Jm1r&`P7n(Z|;clF%|0SJ0pn=NYW8u<Qt%*Eu%TU
z62T{rwK(ZoNgnS(b(!nPf@^zZYDX){>OS<57V2=0rCv4$^rZb=h{oXd*@+ekkGv+7
z6-QkoWGuS+D`cVVGsjBujX!g&1m(KQ#x(#-OrCS2kuy`XCvv;r6A08&i0=GRC=!9X
z3t3FfsZy0C8P8Qyu9X>0K9`b(NoRk?ZT=K&{4`=jgdyFcP(vWnRt!C+O8#uwQDmx~
zXi2v9$q~YqpvQRK3N=PRD_Y6Q19RvlahH5UVVjQ@+&CQYt6;#@3S{T6_mfobv+MDy
zOWHNJJ-hvSN3H>&NvCB`IJr8a=u^GFytB#{{7VIcq?!kf+iEiI3y#}rmPyqFso;D=
z#@$N{V&y)CZ|zkYA(`D@zhPWed9Bro$;etYjnl^?$!BGehneS$jf2dn%L=i69CjX2
zcA@6`hiacg(=X*3S`LW7fvqMB{geT!LBB6l?-rnO{vB;^S(ciWC}x5N8tA4Y;)@A*
z(~<De0A`8;5=;o-OkavhWJOOQg&PDc#|kn}IFUZ0fUvfz@(?oqV3NKRsF<>Nk3<$P
zZ#5r_m-8;`E~qMct16kh^gazU$r1)ionsl9&c+Z6;@c>A_@!osrS-OF_|hK>_uDG|
zSh(L-RkPP<qR33lN2}?KhgK#v-SKz|8}p0Q)tS+Ne<?;BbNVUlQM0b9s6<<(6va^a
zgsLLKBJpS~>ynJvFEnsXN5CfxvgwFw{)k(j45*Nx+*4WPPURj^i6$Lt>ESt8y+Vd^
z6nSV_CPiGLt>N}ZLJV6=w?9P7(^~p{v5B^pet$e=n$zv801A#@{GqMM^JkffCdV%e
z*5voAw3Xj~%5}7K{4#9tk{uCqprw~jE7s)bt3KhDo}NKUCqEK}xJ9Uz+m1#t=-hN%
ztz|Xrp?ycog5X2us^wBZaOT!>EpWPgN?V6wPmP#d2z(LoS=`y98LfQKOfU0PqlOvp
zh%ihoe7=}T8;H6i${WW!KO#Q(mP>(G(VAQe2n^jCD*+W@XbofVE{NS!gC;sj;hVhe
zVrC2G+(2U;QOntoD}kqEPObz*NZJ|;0hNGgEf)gao{8nDh-qdyipadRTpM&%ac{Xa
z=$7lwmTQ5o!rT4+_N9u?o$ASy^{mB`z@LzzUWP$hR~_-(z;zY~U6!k7VWy3LzD~`c
znCV@cEdXCflpQEclUHS-SXK1#^e7h=eW*vdu*mWmt#g;`PA)1se~sab8s{T_f}&5|
z^;}YPEoM6_ir)3?noFUCPq&_HidQkDTt9Rz*LtiU1fOo5vW`c_`1f2ybWB@kZO}7>
z+UUxuw3I{Lb07JtzSQZtYKiw;2PB<o>$waNM7jl%?A%Hlw4O@?6?0-?Ak=f~xiC<9
z_?%Nml*6JT^0&I43xlqLOx>cHuf)>6K!@7kTRMUqm0UdZJD+bkZJvTtCi`-qHcJA*
zpSL8`5CFRMToyFh7NBR>k>$N}S<vFDQ)6mrFmg%Imb6Uw-@u8qp2eAjmTsK|fzZ;e
z=YpWg*o<`l?J+ImPDNx|#+`~-yvC9K|5a-%{eKhstK~IxU}QD0mW8lJdi$1Wur~1a
zO_{`7M8`9l+D3YN(WbVM-u_kWE1Y{9k8<hU+mLeU-36a+BfWc*-5BZJTgFiv`AkQY
z4@~dgv<QN_{7b<x9DYdhUZ~jBuk`q;tkXt%{U)0-((AXbeudj_S}u+B`c1q2kzT*a
zri}FZfzOUxrQ2^!eZcdJV6~0h+aDly8@aD<H8T!(IW=^tIr8Dtg}Xi#*P@d$C?mJ`
zttPH_%jl)Hb0eL)aN2F))Wy2mMsDw$Ql#6+-F#B5wvoGeQLVOdE|Sq1>FPoEUm;^6
zJeA?n)r)<#jr8>mTQu<WvEaTCd0v*&Iz4^6)g?TAb@eK@_?2_uEeTCtwdw9?^1^3&
zbpgHGOs`%&@fdBYz?`;nGrf8RgVH8my=o&j)2mn27u&`0Vir{G<YszyfyCQP&n}dB
zo8j53X|+$H?UC`yXYTz)p1MW!U18~oS58vh5YbiD=S#0#WtL{{^u?*#W;*IBL|dET
zsl}_h1u>!t5pOeh@xq9=iKnjPc~|MGUnK&2zV@Nlho`PXL)cT92;$A$)T{Puo9WCG
zUEXFo^QutOjH;J`F29h(*Z8VXI8wPsln%dknxUDB{I;3?zGm!cW*k5@yV^{5Uu9-y
zy8GIm*KN_xhg(kRMiaHFbhl8eYSvh;q(rs4WoSz9Y2xjx&U|Kid!g6cR775Mt6PQ|
zGDI`IeO7Rs{-u$VSV>@Qrn|2)N;3;j%HYg&?xI(1mYe+w(zQilr6a(PS~~kgzHiCM
ztC+)<oAe^O=4R>31zvB4=N5RqSvu|_+hOUri%1-rg_{Pg-Yk7|QMlaFM<@4cvlcC0
zh_zhliG8(M`e)IvZV|oK+Q!m9zeF&FoC2BI?{KO`=UJ9cwanLb^pX=T>$xHpLu<2i
zsjuRjxYVNKC(F(B!MiuWY}YQ&sSc&rP00I}@U~@GEH~3awVz6#S4eV{((_XLGrexn
zhR4$BimA03sWwN((!lV#MXM7_uUizbwsg9Op0#l@d7V<D`M7h1Li(02_f?EEJ#Nvu
zgd@<nQ9gd9W*N!>xo{*ob<*bw8Q;vMoD7BGbXCu9OX5p;DxzBY;V+^!@?O!2bw`U1
ztaQXhwq&IvE;1zm-mW9#HLP^R0@k;MCoYOnuk^$vS2>I7g-4W~NJsoC<(iII;Q9u&
z(-B$T>ns+JD7#fKanQoHMT1XZ<rZ5Q`z=D@TPu&1-uqVIXXQ5gcD)xI`crQ<-TCc`
zd#-foFv_+Sep+z-wlX4r%T%r0P~T6H;g#-Op#8SepWoOo&{SUv-lprm#Zj?k(Qz$v
zR{Czy$?i(IbUY*5D;)Fv?6QEHMKxVsXZq?_f!*}g2e02&`ssV>kZ$3u6S3b`x?BPD
zcb#53G--0Qieb8rjHA`3lyA7*Tj86Pk@tk)x0P}C`w25I{O+yY)Jng5%Q&s{u>$6|
zl|FWhLN$JnGcY&Rx56$fJ@2hE(v^<)e!|QvciOi$P77yz%RB+$Jffo<AkQPnwZ7ww
zMHAaRo$*uPIGwR@{ab{(57@<X?=5tHa}L*e-=6MT=k1<bZvZV<$U+ltk<&4nuY>h`
z$m?J|A5_zKKBx2^{{1<lcNK|FljJouP{`R^M&53nfO-0F@yBivdSGmv-Sw>qkGG7w
zC4+49++2%7w!!!5qLJN_JzrcjvhBd%E_WS$fq!#X90>f|DLC!<n|;G~3F;^*?9VO>
zxZ5sDoe!s4tk`H<@Ta=SXd6g&hl}=VfZbhWv<*c3mZ11VCoP?JA=fX}uxFS}cdevA
zyt%5tZb|5*MH3h}cS1x50e703@P>|-eThi5yLM+F;M^681_76~xz8;9TB@6h#I9u+
z7&v!UVdwR@D=6(N70jSC@7P_DBgVmfs3VSkGHULj;d8vkn7epv8}s6;Bve#riJTIT
zS#h0O<EIsU=^)_T(+YMFaIQ3iP7z-h^X--#%$bY+wg(57EAgO{SL2y@&;ioDi=3BG
zvR|}9!3<4zzH;|0MSk9q3O@tpaitV&NnojzQ_#W7y-TTACjVO!UCkuqe#4UMBpUQ%
zY+Y#t9eeD`BIwv`&n$utTFxVjAXM!1_^IUHdD}(rt<zyuat;98srEjyVEo`q%cJ>I
z68=j;_(2EXlIYKUS~HfRE(Y6vQ`X%z%;4Vyz3Pd7TdwEEX8Q7_LgS?A`Erd*ICfu7
z>*(_;RUcm6A6nZj8b^?Q34`I85zxW5xhQKp)cY>9|J6aQ9g%)?K8R%uZ2YzH3MlNp
zRFwQCC(V~>>_d59Q)3^F`$+Em&6y2r>cKFW`wG+1qcHbr^Yn7Z0Hih9f*1gd$rgl)
zGlP~}6e^}Q>44!}i37cq)1oJ!;kJZfE!461HS$3PjbteTAoo=e!z|MQJkFP5&mDN&
z7Uk0`W8HZTR5up|Zf6(dNr8K9$>N%Pc>A<elD;%FYSK8Ygs(ImrKO6h-Ci0xwx9AR
zN5iJ^XlR(Ls17F1msqqrkT_Qj@D3u*lN7ffJlt;PE5NZsiQ5bB%U9Jqz^`YnK?gAB
zD<jyQ<noV%*6F+=(4FnPiz2rdT=<e{DY)=ebXR=%5}dIUgm7`>b|MwN?$j_G@{+Lu
z@#gG5KTG!x<joIHZU^n==6Y>-WAnV}I*lBy2;yE_gzcex&X(k3k2^Nkc;RZ3IJXx(
zZ6>INX!qULPx*@g{VqKQKPx8P4(iRtrh9czZ(D?!s2@jbx!LLvK6ujYZowHoL8E(M
z;I1Rep9Jbx_9-B6E^u_Ocv)eiJAu59<f3`B%LDf<_zG&?k}sg<BS}nii&K^@N>Fo5
z$XZ{R<_=sgFwGsP+yiOufs_N~9AgDi&XsV`11IMuyF_f&m2uF)$z5(~ser_}$qXGt
zoQu}C1Bly_)VQIHGADcO*^CzI$S74DwdHaq0^F|DfnFhRaODnkP;YKcH^!HX#kYfb
zb8C6y<H=2d=w5N<rgct@m-vy;ib*aD1ZZwcm~4@hwgoxa65F2H*PZhS&kThlIVx7o
zw(xkDD?y=CJnkc*70ML7g5$@Po3PuVOv!L>=a|J!W(n-vmZZjbdn>fgq?SPn%-nTE
zXv|_jT*95Bs4dA)#TnC^*5{tnwFIfL6WgNa7N@6E3nGrmwuJHIDD6nNQ47B=_Tdi1
z&1ae=0B$~W|J7S;s(r4+6?fok5*^7NpeZW@c+F>88IWr}Wo23vc=4I1>m9}_pE5J;
z<6Y;>Ti{&Zg7ezulnv#;c8l^S(bf6fGP*kT4)B`^iSCWaxK9~`12Xf#L!VZR$J36{
z7<vd^bB;XV=unXP9C~T^&Dr(V2EETy^xp84vp+Y&RZguzKn(cQI^=-KTs*`bESV>S
z{5qoOv`hj}vMtFe#CCV4NeCR73*_7rM)ncWJd=G^JsI~pt5h<kM#gPA#CD!E9w91R
zmVLp;CJcHD#%X3(7CL5t`RbraTpY$*5<1E*05Wq?827-KZ9&dUkAAtZ%^i+FpBYH*
z0K<H0=>aaxg-7n4>}sF-^g;Ug$bd`-4&);PGCeRuKJ@u_iW>PK&7{NA=*sQreYdo+
z0l?&$)o~<e_6@~-JCH9IOK}JB<**d@fP1+}ihIW~j%NV^5^Ia{)x@&Zhp9XG%3;zm
zrs0;5pWUf$?SoYa^{-v@#l82_%D&($hZZFrMs^?CGf|A&hxSY`gZfCb638$YeQ}3g
zbW29ODBS6gRRKHZf-iTlV?MMrfrQM5uzMZk*cPQqvG*NAvuM)cq5I$;$Dp;5=03E{
z=xlpMl-xVMQAEjG68-IZFfl9_dGZ#G)6NIuG7ocd?|4fwCwI`CKC-S@2l44cd!4|P
zxrmcHkTM_I?EoKhh?1`m#n4yHAU~~~J&ros+H~jjv$g35GqRic6r5@Tk~?(6Tacd+
zK6Pl30VM46;c1BgBy39<`SYe_7l0SL5W}5o{Q!n9B%x3Sd^?yi9}(~E0T}a<$4ec!
zm<v;Ubvo|C6!*~0yKKu~M+<B6ZlBI~*L~X+O|--3b}bnIgl$Pa1)tlOG=wR8i{hIK
zG}vx455R)Cz{DLWn0FZ$kYL`G1kpi)d6#iHKrk1OxPt@pF4Mx7u_fvJMqGly=hJc_
zh&!L3ccQpkaK=OM;Vn7eoe;zws&W^AxPu6DktcWTgLl>^SP<_@2ki$m=3RyafS8Lb
zxdRV75>#ZDn_S7)5gmh?5a1qZBQ6l|7DRuwVZmf?N#2-O??M50jK2#6+>du~L4Z5{
z!xI492YxsR9xp_p!?7i}Ef<|~56|X818+g7*z}F0TLuf<frEKhm}K733WWiKxq!hP
zXT2rq1b5oe5%83Gqs&{fxM<K0Rb*RcA*Pu~;vU5hyvw$bUgf>0FYJDMo`!c8Dc+yJ
zEh`xZY20W0n-@Rv@?F*myqI^bTxM>7MYr66eR<c?g(aYiOS!X5+>+<2b13djkrNi2
zTN0oB?5Dxxr)-7`Jlsj~+mf9AWJY?E#Q_rLO%^8*VcukLSVB8A%b)4bGTWOh4v4U?
zlDJE1&HlD2k~;y_y117+a4;A5a-S2ma<4NdT4}E{!--!mC~=>7@n(8_>~aMq-h$9d
zF_no2ZjZSD$F)UFHGFPU95#?$E_US(u*;KO`8uLAzQPB0U|lYH<qoRL#jf0`TI0#D
zd>v7|=D`n+u@J%XmW<QJoJ{<%*p;`0mo5u4@x)?W?rfgDX|)o#FBb)K2ln-O>78b1
zsPzh4a&H-%WgqWN%N2_Y0BLvP04@sWPORXoBqp$;Bm^D&K!>}PR8N~EE2yU}k>Sgm
z;v`Wf$(zC?R#}U*{Co6W2F2QGVN3|xxX{8K=-8G-bQ_e|7BB-N6W;|C?qut`u)>{e
zYZolI8+%n3EVy-D1y~ea_a~)W2@zRh35kWJrKF`(8tIOOrF&6OQaVKG5>SxtkdTz_
zTtGtUZuY<E>-)W5{AZpW_MCg}J@=k-W*(m3Z)P^WZrkj|4wl{8a?nmkM`O<&Dlx&(
zG?4WAc=(jJq6Ze{**3hrn$f)#M{3J2WTRg_%U_rhtoj)u?nlt@_WtLWC0oJxHlHGJ
z>(K$OS$@J_)F`@ZuzdQ9lh~|uU)iM+IJ1Z1)ysXHDBi+ZGAso%2m3bRf=6+1efgB7
z4NpxYcbJE^o^4XVEYh);oY>sQE-;aoK)@WqBuDCxhX61|pWAEub!eHACznM!Y>Ch)
z6%RBw>8~&H>Z}Qi{Y-MKHu%)P_GROvHnfHqJn}g@z=1TTF-;sj#iLry0*K<B?HpA!
z`^Q*R2604dmF5u#(}KH2nij<7=`rx;?AYi|@5y`^BaFKg%-P!6XcvaA-(Refx>DO!
z3?_RlCz)<B>CdN?;H}4zkl>vKSV?NV9xI&L;M3vbGV>nSBmSs|yq(N{F7VkFW<5u#
z3@tAUxD>a!b+!sPO)?iap3U^c(g4L3iluczlGd_vS=?4W_VuU;!2aEWvu%rGdeeK~
z(v$E}Q!k@S%n$l+JN7%;S8Vm?YR0FTX2PT;U0D<~PhC@xw`b0@82==#bp*`-zp$>$
z6qBo2J+HJwwOo@VJQe)dY*@QQ__e>&e||~cHP#r?^P`1d!G1W<*UbV`4O&pShmeU#
z>b##x`N>~ZFKxBZJe4K|#VBQkaI8P*foF^rXR8a*`?p=(%OQ+o!__!y)3F`JhiATX
zWRo{`a$6r*itw5p6wl58R&Gm?!d0)Ey1z>YEwf3BB<HNrqc1!3M`(j!omYU+hCn}W
zb<1(Wk&Y1BolNz{?sOD}!)!G?7BFZqRt2EnX!8keW0gUO<Gt^&1`yRk65I1N%CI7n
zuP4gmbQ3t?t1g-3d9rgLHU#VZS?{QjUtM>ZuUU&i);)i98(@%e*xdY!YxM}qhL@Q$
zaei!Dr4eF>9sc+H*9eK{BC5srntaq*C{%P??l}eVOkjTB{=(*4r&}dFS3zh~^HP0w
z`@P56zVOQ?z+yF^W)u}cO5lklzD~cqgM+Ad4M8v8OrmpPPmZu^U@lkOn@{iN%<}Z5
zZy;?HhEp_O4IKBvf~R&3OYuX)jihH+o=_X<E}&lQGt}A0B1WMOJyiM92XCmm{8dE-
z3{OAt_MwK35|w+x4vvIR6;|F%WUHQ8nEJeqG4gaukfm>sZW1M(POM!dk+$Jn-X^J?
zh|Xnhc83MH2L;FhEUtHa1jWuH81JxDE9ituwwHKDX*M@3xQl=C8x>q@7?o_#e*;hG
zTx<ennT{3{7WfH>R=LXhT3dKx@Nbm}J%5>QWn-zBT|lBwm7zX^V9MuvVgpgnqIIa+
z#UCd8I<t$>L6F~`)R7A5h;(uBj+PD&>+@yQP{J@^7&cozc<A}6UuI1djf3gY?))2h
zzk-3Y-OGuJ{l(L?&F0vc^2>>KbG*RC`#e{kao)5&%`4FH)(4(v%Rr``pl5nJ8fLR;
zt0ix#l5BBueF^#}NfkUzmXl2C(Rpfte&ne1vuMrXD6vLzcQY_q%7O29P^7Cd`e<O?
zNhWnU2@XcXBD)qic@4lQ<hkpjuOtOkOtQ|kynFJ!?=aIQrl34{god$#{R>p?tOlsH
z17KLwZ-rus?N`b@C%doGlpOww$5>IAz~Qo02=v7bE3+J!veViF+V>$MN9%K+;YHJ_
z#^|Mi_a+sjp=noR_E(HZbzbo>q!hoCFdKvNYvn|anl#78RW)utBf3~1tK<KmQ;tzf
z!{|v9=HzyP{Fm0u0dr-un(*VDWPxw_-glaRHYwi`OXfjGnLa4GoN-STGJJ&wkw2<l
zQ{;JUaBLVc01ntZ%Kkn`krqRf)&K1vo0^>|BV3CJ#k>#FL>iq{$9HL#(FEsx0Pjqq
zte2xpDv!(dRV1I>+d@7I7nbcC!&nzQG#}?OBUJUY+pukgu$(^`UTXkNAbsG8LSoQo
z>-eNwUokqYbBXlA<FmR*oN%CPGqa0F^pwljD9IjuRfc=`1<le^qOdRy5)Y!2FZN-Q
zZZVG=I;NU{1JPb8QnaHL16v93$8kgQ9(nw3aYls%X%@OD;T&8IIVYRElsYD6Z2NWS
z2~(tHr<uVMq#~Zg`?X1XbqsCv23+prZy!4Q5}C0n&Mmy$=+l2uj~`=Uzgl9WD2e>x
z%ExNl+p;t^EDIkcFl-|ZOv$Pi;?xxHyfPU_%jt`Hqpw^<o#ynx@~GC9lq!eAT*F03
z5oK0_5&~@XfDsxL|HS0<=?`Z@i)?s15e@jRum732aE{a|f|f%4G)elkA{ql$%4guj
zHY$??4oDacr5aOd$%BV_H}})S4jY{j2cjot_O|<|3JzgbzLijYr5xGkr{!~N4(cm$
zen<Pg%S*`DFC}}62~>~tReqzws7dA!r7U2t-WhIVedloJbGeM)A@1-n$;WM*?W=dw
z3f}|5l6;Bhjk8xDMzPG3=Y@M2s#P$&xtH{$0^KUECU?|#v}?3&30F=yQ$mmF<(Il{
z(%n6{pe0FOv*ca#;7*&BD`DD5W0kwxa3$+7H?PXr`zlewPUkRt&&>@1-UhRlW@!o$
zSSg1uIbG{yQf4Lk*-W{J_I<48>e+L{D-S<{D2oB0#kP%yzMm^WhT{yXOLsN!9J{eL
zOx?}d@RVfu@l4e^m5tn)hci=chqA~_uXjd6CgNy&xAedfahieXszKY<qXUC_OP#F{
zS44|9`!lrj*WUeu2!!i-%gy1jZQ#vi!SSal!qWh!Dt~{P>fRc0#OQJ9&A#es#?D~-
z%~kYd;CXunLbv{UDFd-edvj)txY{iVJY2VLINRqI&3HGke7NAbdw58Dc|wcWu0b5v
zIW3CboVFlFpP?8gLYLzZN1v2P_3`A{3>p@vmwZgn7dQ84Z`uPdk#Ej8L`1&f+!_D)
zW{^x=F>Y2Hl83NUt*|TcQK)O8{jrfna~U9qIBY=(yI1Z~%$!CzJny@@YTp@b;Aoi{
zlnoO(b{$<vo13KF*pMZ^G=7T~c-qB%vj+-1@2i=&{DwBDr?wVQoDmp#^ETmd^727d
z#@K4dM??u{pp$O%b;f400PtDkllU`lve>2P9q-N%drT)q6JjgX%&o7OuP;7a7upX6
zR8+LgtHaBEyXpCafWxDU&0N~B(#=OEGrPv*Z*NNbz{iM&<oUAKew+=in&;PjW~e#p
zwXPC}<}aNC$pfrf#IUy^l)=;vUlc_prdvvBw~R{h<Sst!8c%HwW=w7F`q1~+mf~$*
z7^zxxT}6iIDhD`oov;o;@MW(J?z|i!1rh8TrU$6D_s5U9t1f@{1icJjt5X6BHT&v4
zDSMv$ZO$U_6dZoA#$s`ag|&nt9N7LSk(L(S`uvQA`Eld!Be}<uu6j+zGuLaD!O|Ih
zJNQZdyX7+8{6^JUrP~e3pM*2C&AZ%M9-jD8&}7($C*HfPy_{@$0XdD1ZhbMnsqQqe
zm@{WnswjJDFTRL_U5b~AIGR+tC^~ePNDJIvFW?Pc;0tjM+)~~}A2ZI_T)cTz=hTst
zm%#euTC~$a#$mtCA!>5uN&ti&du(X6dMZL7+p!MjZbZ(S6#wAb`Vvd7m7nrLKo$=9
zd^SNpvBxrbuyxYVdrxt-JhQ5)^732Xhp9uue6-5N28TA%oIZ^`9Zqw_bOx>}8AKL|
zpiEyt`^*&qUM5cSiMk5a^TlUxJ_fCW^GN(o%QHaU>%02<Dy<5GmXaX<Q!wFMUbM$N
zh%%C?*N<BE39ghcVb<;R^5+XLVp?Z5+vGG5ixeKhsTDJOH+2CFc?j|PO0<mi;$qOS
zXCnK_>iEzV>T$J-V>-!IbAb4DC|$8LV{`olslQIU!g$JQUi1bQ@23ocPz0xPpiMn=
z;4-~5dZQtgzua^oSuC4&$Za${`oNbrO+3>U3-jRTj^dG#GK2e0Ut-)9ES)+2$n!^C
zfV3(hV6n+xdU4z}=J93y5%2<4Srw)J+MVr)p|1&5;b?wZ?&$jMC7$X5PtJ8Rq@~t(
z?&oeP0?(`Z0VA%ZlZC4r)Y8=P_8Y{^4wnzW1-ShS008)fxcRvL=z0Fqi-_Ddfn>bg
z<TTw(-7EpW6}LK5E~EeeNl5^>0U&cz<WWrQ*7)}kBnxqJ`-im^2NwqyfFC)m#$QHA
zyT2v@{@WP<q~+~w2>_{?T3Z5u0PbJT)l8w5$g#Np^aUwfTG*OOLc9P5NEH`=Pe=&B
z4d&tk82vJrLOMp;y8?Ls?jQ$+xI6!2GQXYt(%yDKZXivhYpAJ{tMjchbMHTDd4L<#
z-SUqlg|w2k^sqIz)R2?BRsOYB4NF&uJJj6L6>u9j4cvb%O#mt1#`iW-N|sL6ZZ-hH
zzo#W@>)>Vy1%PB7kdc+PG>2IH^7NM>H$VXS8>Y8o{gpDW_uIO@es{;4#H|C?`?vbH
z%&jV@52hHY<A6jDad2=jw6uv=pGA_!n3%up2xUn&i7B`n97p^F9ZkL6J`qOA9z{Zj
zYF7mar5jIzbLi+7!OW;*ebgP4R4(2T=+0c0Ar=O&{dW4(dDi^{26uPg0~3g|V=Xa4
z11~<>TGD=+zYvy;B*Ko(SIH2VRDBrM$H16POQ)5PBr0M*km=2Xvu~ER<$YEbk|)#K
zN}OceDb&OBFjaebZ_b_cGBDb)j_322G9x|tr@2AL->E9rI8&<HZg3~COq<Tirbi1%
zpmVQ}qjW)U`5Yyv3|I%hT-4~ECX3#vO>?c5>TcbW!OoCi)Ocj4%UUXBcaM~;vSK&%
zil%BmkCcH*ZgvKXH0M*(CsCd@C0_I}D>GJxv{m9+Z}l;j0Z5CFp$bDn!jS8ThAn1^
z=?=32qbv^3Ksvtax5%eQOi546j41N%xwD{YNMaYS6qJ1jsA8^sK!1SI%KZXX5-b=}
zpk+51s#?w6Fe)fqA_1bDgtOEJD)5wfw(#YC-cHKd*0Wl866cb&opi$P`FyQ5O!Mx`
zG&THy?9T!O`J0SskxU`qNx&H&nG_he6)%RGV-%T(8n!)!nMO4(FpMzR3Ufm57V?sm
ze{+Duy|rLkgRwI{f_D5EWv+h+4;nZent9t~5Nxwga+eBdP(N4!4G77ND~F>jM-4q1
z3&stU?%u>Mq_!~bZlSYnYMf|b;25EhXeHa;ToLet%d4&O=C~S4F_tgmRAlRad?2&`
z+)==Hl}<qRGNhPdCQ21Vy)-G^Y@@~zmXXBu%{Z?6DM?hpb0Wp9d1fGUx|Q|n8vf7G
z<h7%_aXx(t1CCR@jSs0_l`hhW5hp(s6sv&G>p>nu7V10^`HsTr8E0!NtIW9Kc_-F@
z7-zS6+GbpgH~9TUg*VgrMu&a96wIg7>!*n7{T@;B489LJW!(kQ4tV*}T^*7MgWn@l
z-dB)(jaZYF>#j(TjgiJz&Q2{&Muoob%&ciOJGh}XluYTXKB-xd3{W%Q*3*eydKj_~
zx_g7^xJT99l2`pv-T@hAcC(1H#;IPL5EAllX1eUB$lK1oGn@6AuU{m^hi|NM_n9YO
zdc@C{F%^MeUlZdM?<~q9p5ccp*(4r$te-(I+)gTKn+*5kHSx%+l<TBLb9SQ1bv8FQ
z*GG?~tVIQ^0=|XDGGkd8T^vVyCUu6j1Rq~<ABf*`)MEIO>4_1Xa(7vkl`(gQ)Pgn!
zqlnsZ<-Q?iHv{ksUC6ea@NDVfB>5VV(9Aj-MSS=j=2Q{p7)Sc77jN!?hF&k^m<w<I
z)H~nEAEqhT3|l2jw9y%7futSL%YVTZ`p!gm>2o^6GQJ*;l_9|2yCL0^_13U<#>sFX
zw+T4vY;9eqETzyxpDz*TV^CLV)i?3!Y_|SbxG3Cy(Vw|QJ#jrk+l5q<?b}yR;%|gu
zP<6UTnBlKDb0aoJ$p>q~dmLEVm^ka11U1U!i{uSc3+;nz-{(ivKFFV!_!vE!^&@qD
z%-u0qN{1l(P~j|3Q`|w2#zQ$VXv(lZk2)!sw-U=>>aLrjQj(GG>cbVeP6Pa`{(cdj
z-B%1bMwHc?KYZQ>4zu-vW7)t<{Cb#jxf6Y+f^iRo-f+*%&tP<Exfk(k7Q3;#Iyl$z
zy^!9RD-m|r0sTzGx7vH2Dt9_%{+_$!Zk$p)Q2g+a*P!VBP~5SFZ#cvJ+ns}VFXaip
z#e(&iXtP&;)}7G35wT8Z8*NO(uvNpAjKTC)BYY$=i|wA^k!&968p&ou9^<<qI>Oj(
zeePE-BLCK*LA6QsU9M_5#bZ39b1PPkL@S$UL0Xr4?;;%W-s2fQv#6@qFt#m)Y6%q^
zf<C-EQa;hQ{#2||TCwZ0<HDD+`)<A8>5z`sc_&xYN$mZIL!y-;HIsuMwB39Kubiy&
zGs6+;MQbe8E@u&qk$NkWn^SPt)2V>hS=XG>MnByw_Eem*dAP_@%=`s&NHI0zJ~%Bu
z{ield=kKOm##&@s!OFlJqHe{|vOIDeXA!?GF!rN-ZuT>n=cDd9Q)jQ}%|gyJzV!NY
z@yxNn5`%jG=jKWgrq4e`d$3V|P&PYd)vVNTd}!3M#_C#CFb&<ttWFax5GnpN>M^V{
z1)5T^d`&*$cb{wEnQ}BL=(LF2=l;<WDxcA*@T(CK%6=@?I=l4rAC%~x2kJj{MK@R&
z<88CFuurp^an+6E$0bD<xo68@obC?!)QO^%Dz?szyMpT*9u~UXk_sBEH)=N@r9~7r
z2SZ;j!>KOny{_<;b8J7>ZW>O`R?0^veN~7xBm5*w<K~%3C?<!m-aVD6nZzGkKuPc-
z8l&!;O~a5kD$uP;lr3K0EbTzij6p){b<~vFt2H=X$QSHvCgPX(HC~u~kf>6cFDa6N
zahb_Hdh0*!UYEBC7B^aSNj<G{3y2}6>?0?Ox40u(UP7$-TERNrM|ar5@I<9%I4pKF
z{GHBhbah%KeSh;+=r#!{M>aZ(Spfybz={4D)imB$rpO;PtE+2kSy(!<_<LW(YNijY
zbQstc3?8Q)a#?N5^rybKlp!XfB0maJXq8`8D5%rUc`d5!@!IZigN%{7Zqz<V=lS5m
z#*W;qvcUbX&C?4tjkVsvZykN;KRtOBlKX%;Zshfjqt8K)vN*)<{`m|Uq(yPD04vYP
zXtWv<SfQeSg}kG3<cE$)jZFK4TvOH&I9(ZKY<yU9(Y@+tbC<ZQ-#mO+il*l+j5i~W
z75Gb|BID;u)SJ0t9ujmh;3<KESGLEUTM6<BqS+$wI{k?~fp3VI+kZIQ)_Que?-p20
zfyV-79Ki1elB|5KyNYC7)$A5JoEaZ($)sMBUs+j`0NE8nIJO-sYaXU}Uw!#OEApr$
ze1-SZAz2Zxys*wVzi=K_ezUjVP-fGQ>kZ<fVeH2mS4$hNmnTjYUXOOg1_$Tv;_=t@
z<frQrZ}+~kDK+hUG4Rg(%kd{}Rh;-($^p97j~m&}C+vCIm+UkO6rs<Sk*|Z)8VT`h
zv>~PFEXWRflh4hY^rnRDG{VuWp*CY;7;Ar?YGPj^0g|>Qq3>t$l<R)#HfNPkZ^Oj+
z-AhAWmxkT&^1kX6VeXR}YfB@7*R6OTj8~>s`>#9q`<A8lVNhH-D~N8_7#NhRA_**j
zXR%RpHeYR3fD8&Z-)5C^h{@MCsB#84+PGFE3?EEebEM?@D&~i^FB|v~sj^K+jj4ef
zE=3;5H5J4RzNiu0iqp(UA%<uIW!|O45Q|HWu8^f9YYjbGE8NqT;d}Q{Xvm^OIcoAK
zST|&j+TQgMzv`}fVUlWPmGP79^;M%9Y$-qg>9dRS%R3%IEl&hB+q_M8W#c4m)t!@6
z4}XYVqVR?X_=sO}xu@_e(OOMjcSH{ZpDB)yGJr*>7LK~d&c=dy1NF_I3L)BAI#X;9
zoba-M@)H&`TW}QS+E$oNXprt+nIIpK!O?3*btEaDL(w3aT%jS3JcO9{wU4jg7};B5
zF`Qm`feZ|up_i_AR<qaJQgIpzw4aIAx||KCO$LY`cbn&R<#QNc4yD7>*AYkWM*JPl
z7RJV2ynv@jTVLQkGdN)eHocA4^ct+ag0Xpz9ypeMJ?)5=t^C5<!AUkK9?Rb|hO_wH
zusE(@jz5Dx_@aB;X|vW^H&c~;sKqH}N%xH^(|iW8dK4T@hD5;IGuoEFdQ0?Rvx#H*
z!OWtJ%bScHzvbRSO&t^E_2^E$eLCfW9&!Tay#O$e-<?ZviXBf~|2@qlp_E7-RzK1z
z7aZ7?WTKE|IYFUWy=5q6;0^HV^Sd^}cIQzWbj654AI4tBadOtY1FcyT)?}jcdEk7H
z+zgXEk>X+QxnD?SxXvuU!aK(d`R7zxCB0?DpPUJJfw&sp#zICtmUSXJ1M1-IniU*V
ztwEeGH-NhpR9B{!VxWrBAigWAI{m`x$u@28;&R#rwS^$h1Vk`VqT-%VLkEK0_$B0g
z@p}OBB%5Rbr-o9H*)gSgsm{pi>9BW%Lh8#GR|*=6a?g!&ga;LOJqfmk@AZZOv)*gP
zk-PQ1(-j=Kn)_P#;>#;rQPMIIo=Ea2P8z+M9SbYLg!iyQBTJ0{9rO|-knE%<LG^?m
zbw$XA?Gqnbz@YqHiT6~Za&!He?Qn_o!3b}vmNrW}TfraO`ApM?H6Hdmaw*%uwtBpW
z05-<^%Gu2s!jvF=+O)?&3^PSOGeu>}^|+n{6KJr~gL@vN;R#aB-D$Gj&&Pe6AdamI
z2FEg8a%TW;I(}FmfP$heAe`igRwpmBAf$3gyYQaA9v&n%vHt9<S0Q%U`klSZ_@mkw
z3{&g_pQl7t%vLfA?#0y*<B+hT6@lo$(*%3nl^j}4&JsWR`VPxfRr4;$D^o0EpZ%dM
z3ggEt91aRQ49%p*3p$L=SA7M`gG*Ap^j1@zu#XbW6T#;S^i&oWT*M)UdEHrOH*}{L
zXH~4i;GC_VA7YU5!Mx?3hta1c9aBnpq3qu)DeGNm@h91>>%+oes~bHV8x!}K{eVh8
z(;`b~UCdEl1Xo(k52S5QY|pTIa2l)DBfL~T2L7C;S)Qq~U)G=BIA%+NOnvt2^!brC
z)7v}q?OtM4{B=~{a|Hb5WHR4{FKw}y>yMGQKh51{=2rXG&FDq7?{r+~w5z1>qPFZ~
ztl+uC<>kIp$sOH5yU@J&=%(~|b9ZI%i0HT_b*iCZ_M#;yc%!M3@-o?QH@fwvarZLt
zEUUIlPhYWS$noq|NlVwBe{yrg^+C(qADxDD@40f-+n~9}o?R`|Y|EE%mlu=g{t>Sz
z&!nQ+-V5Ipesk5-W1a})J#p6S%$Y}sBUZA6a>Fur>6gdiIov2F6w15_tAlf8%i~0X
zIOJ^bp08e-&vHUT-nYdj=3@S&$}*SduO@}QQvCji190gaCGs=N+iR500d2Nx$5MHV
zXF}ml1$3e}Tu<oRtK>6_W<1S@jSO`p;$%<BMCE#WB+ed`FL5=z6zUPO3GsoFc$(G*
z;1x2tTX2soXI1oQ*p|70svoR>$|YZ%o>~mo_Q5R_eyS5Q`rX@P#HKtdUA9@jTfhSI
z?o&mQ2jzJhxd_3M@$f@?c_D@?-to|w3o~ksXkSsvft5^gahibA%w!HG%v=@O&}VVZ
z6pCgI8zeKF5C9z%Hvr!i&QKo*ESq=WE!>Gkxf^e1*f5dGkgU;2@M^Jh;^&B;w$f(L
z`bS-F;>m!nW$e>A=J|*RiE-^IYkhYPcq2=KALWkyjAHoItD6*b=z?j916A&J=%(W-
zt4!GfM&*i+#n>6L_LqvJ1is{{`5Ya)Zg+uvm%43;@YDOOmdWZ9NjYQ0&?m7%=wWdI
z0XY)5k*v1Z3p||&CsQ*-07B!KI=m(5yMQ41#k=~3!-CJc&!<}b35Y-QeSR|1B|diU
zf(TeSC^)08mz{U<A6M`6G@0#S)vdIfirmiG!9LY{$G?Yi^YyO4S;635DZe%|fsvyK
zZ>2a6L*~(wQR>4@NpY9?13vi;mmiweOok2nO(&-7Ue;MY<i*;|+uYEENp_OgpXp2d
zr(B{d_IxhI(^)EqG=7M%E;Y5;;^p60qE)otyE_)4Ro?zxTd95Oe20)ykq{~{-8a+o
zz*~fM{UJ2w7+7&GmrGL0!K}+6M7J7S<FX?sSaW|gb@OsAs1P6L=j+H!v{nW2O?j_x
z%#8%BX)ka{CXf$An_`r>W4{nnx+Ly(ZoKvmZmfx+U>82*=6C|=uem8EbiId(nG1Rw
z^nsb~qRB))$UE=pRXLNb-sekURGNop1}M$nUfA>PMUgd=J3ng;#DcRiUsc^H!GQOT
z*BpW{4NHPRc9~7+HzTNl<a_68wY+FzWP7&chK*dY#vg<51ozsc1rhRh#1~OBELywJ
zZW!T)<X6M!fgge@(8QqafgC|Rui>X?VjWAgoI#_Gp8KPUncJL##|^px3az_lOEqX>
z#Cy%KMQoc-LGc{>SGlkxFE0?D3btVN$oDS4Jr%|W_nf6$OEDWc;2fweq<i@=V_ZRY
zcns_%6R!@2R|PB|{k2y-4E-|VEJ(`PglZNc3)=<ZdbHmFd>K$KF&dwvN1;6@8v?*7
z&`y$C2h;X`rlSN_VVsOLoTsCVH7wm@yhtRR;(%MCHehVINu|MPKtktl*u8piKuJ%q
zUkBTnG{77Uw*B70K6y-)3#CF>gT7VWS$sfHb*C}&%OP5NvCG~%#+aZ9naYe7I<<h{
z`B$wec(Apw$#uPyUlYuIT*hynPPZoVnK&7ITt<z?Vh{svi)ufK54XqsNQF`y`)#~N
zYWz`}j<-o7Vd9jU9@;&Y!f=$2yi3+-+Ux@7xTt-~UJ9*XR7FgThQN9Y97G`us0i;N
z)is2#MxcLw+A4{P_nvE!@Q~L_vUQG-Wf#^ZY@&jdfRn-j7sn7u!j8sGv3&#QVQynU
zvtkc=U8eB}PKOFa%g6IlYpu*un?og<%6i&*jh2tg@;-aNjW8wqi+}9!RWo}Ey9w!z
zh%LrlFH?HHvksQpN%YgmDEKLM_vDfjDp`QV9u8W7MXML;%4h5MurhOeF@ChK9YSZ6
z=(56aPE^l{)(`h<rCOgBiqlS`G7x^*UIDO})WT+++z)3(oHsc*1B$7gsMg>$7!5{T
z{isry-*G6xQ|+(aTH%H-iB6t4y%}&N=pHsz6R{8m*k=w@VBn9@@kp(|CF~wDeG-^R
z#Fg2CdtIIh@qwLk1Re1Ts1iL%rPk0y6FK&Hit{7`HgH)B$doFFF`_mZ#f17X)qgQY
z!=WLLX75OT@*drfMIr+>MHotjI;<N;PW%k5Nll{(LwY&4+hz}U4?C0?{uR{;mFd9l
z4T?EVtwJknt7-IiLR60jj?oxKFe})j)>rKgXm^Rafvun8voO6-4I}_RsSSS;jiJ!P
z_=n>XRY#i<6b}ztlv`W;mv0DX{L~=-4JO|rn}31Hd|-Z_Kk%;5e`BEBx47*uAQ<$&
zK+u0;o<?zfPQhIGGN<Rbpn?dJQq+7>$)bE}<P#*7v?yU&Pl3`wdV8l;E5lkp(fs1(
z?2S6ZIKR1?7Z7B7wrr3KP%_zzl=O|;2S4oUDPqLr`LSJ%8z}0Dd=A6u)V;l~tUbF3
zH=F3Op+HOfQV+YR7z;}1LZgKEGzp<`vUc@Mv8%XX&OAWdo!}0Z-RVf(q?2sui}NYU
z#~IbvPpic{*LR3VKC3XsJ;yI88Ql;T&MsQ6ePu^!7cy}rtjJS#^zvq>u}DK|L@+<Q
zXzOkYt_#z9?t(T}SNiwF1!Z353lsw>eO;|up@VJK%Z3;0b1ez!z*BbDrT4YOoGGeO
zCXXsX7xWuIgPv*V@VdleM6)$#Fy4vXzTH4%9F<Uo4S2#LE*{r-X4~WJ!fW8PZlm~=
zH*Sxzjok}3zVp)8CBj_iEC3a=E2s6p)AcI}f8~pZ=Wpnr`xa>bgIWJZ%5SlJX-ijg
zsI9Xb1bPd6|AO~bOdXL}y_~+1qO=N|w56S?w!0=0LjSv6*3{9~!5hHxy9sdH#`?R_
z!PFXwm4pAbl>Ck6b8vHkxd0rz{9pjLfDjK7)#m~Kh3d<@nL5~-OE_6OSOU0y^^<Tl
zzoi9)z=FTT+xgwf9AF;4UkWKx=ckso);37y06EMrm8P4eqc%YBcmG@A=^x>Cg~&>@
z1Osjn`+p+%x0J<yN8|T!?q+Vk=n5?)M{padUs_31SIb}I$Nv`@Td1p>l#MC$PXLrm
z|B|`EzX^|j4>#afLVlktGEPX6z}Cqc0MfB_l5ldh{iFEhS;yAG&BhhUitupXuHt|1
zJp5dLwe$1v1OD@aq-c=ZKga()0+MkNxaEz0@BDm!z6%Kc%PT*!xCD4^E9rml{5-ep
z4AKwxpWeUizykjogA2fmTsj}JB5vn%%dFgTJxC4m^NZ?1QZ|rhPPVta3E=i3^Ut*X
zcM;!mO22DU(bnQNO1HF=#^0oo`z^)v59WsZpRAM`6k_3Sj^t`s%uQ{f5CAtPHy<Z*
zi7Ym5ZqAQENcsz@wT7BH+t`}BazdcitiKCg3dyy(*+QJ8Z>cjD>BnF$FqlgaEXc*p
z!_C9R#sy~P;$r=$(|_@9f2c4iQ)J~stbZl=*Ao6B!v4iEc|k3$aJc~7ytrI{ZvbRk
zc=!NTfZsX+e(u{q-);b>zjXXUJhy554;`2vnf`y%A%*|Z7tD){&%fCT@bL@$XJ39H
zJ|SeH|J{yPh!2^a|I`WmmmMFE;D7tz<@(P#BiAN~ERBC3j~^_AETlg=H>fG{+=l*Q
z;WTZ1EN^3VdlA!sK#)oQ&Dq_`@=jLB-2SSI-@KbC)a_Sv1^9W8+$azzqbiI0f281R
Ay8r+H

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..81dc12e0c98617dbbcdc0a51400d4e2ceef72d6c
GIT binary patch
literal 67290
zcmV)#K##vAP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_MozZ5~YZk
zHefVhz=Q6tnc;!aMmNydIVgKz`|Z6&uC=J0_vXpEU!hP{DSk&gB#M$K{w&(p`Tn1O
zviJY7cAj7V_2=;~$N8g;^SQr%{r~^@KYsoD|Kt4n@BjB<U;oehfB%>F|Nf8TfBWCx
ze{g>NpNE}a|LfPkd|CWt{@?e{x&OFN`x@i?(cl07=a=^%_xs04czyksum5!Xwp;H%
z`unfn-P(`G9}%+K??(E6{r9i`@XyDcle@oK`_cTIZM?hBAKu1w+t)w;JpTQE`=|4t
z)<^&Oza9VXpX|r@pZ@uO9RKq_f5(8|4%Ft4vCS@;-_OmT=g0KBI+5^)Zg=}}ZJ$E>
z51r=tagVn30^twc{0^>*{UrQj?0<gTSNHz@>aZWr^&9s8b>@3-KkVFR2f`m_XXA%G
z&(;lu@4LOl?^BdX_(QkbD9Y#t!XLU#Pr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>Z7+
z{rnJRwExh_`ll$9@O`)TOp0=LBjFF-?)Tv~tQLTTe`pEb^J;e4{r>9Rf1H1R2Yj7>
zeF56+pQ22{A7<zCQ<O>gL$~*i{t#sn{?N_Zenw{V`!4nj3Rbe8gnx7gjNAKLwCufA
z=kM76Z`lEM-5;Wi_8(?9?NgLV_(Qk%|NjtW68_Mw-4tbX1K|(d%qUt|0ucV<4lwf{
z?e8B#U;l<X;PFpMM*I7@UDu}^qy2rSdG1mitv}o|{g->b|0~YMHX%<qc4mpwKP>g{
z-Ff{+=>JVh&+{q0&%Z);H$9L9`|hB6Z-~XK>L$YbhW|&;f$<)vkN17?HQv{#|4tG4
zODuWs_puEV&2Q)SKFa!=Vbw{5Z@bz1++6>;`W5B-j&C_w`+e&u%J&_8r1D)IMfnTM
zVE)zu=le8xzF&vGunIQYFJe}d@27Y@zX)1UzVG<VkA-LZ+fMDRvV1OmQNHi^K1V;-
zz9@fTCEELp=+7T_#9zA^+gk_x6t|*$Kgs#|MEv<xl<zy<p+9c@Ncg_n^Hx^RkJS+6
z+m7A*W9`}g3oFs>{4wu79{+A7{*sE=yZs_;MfrYu@5kP!uodO|j_=3i=gJr5`;PA?
z(dWt+<@=7${kifY{FSwM-rq`P<=eIRYggy{jrl2TMfrA$>rLw)hj3B8@90l-*soqv
zzVA3^FmLN9%J&`bzITe&Uswl!pTPF#J@J>6#^?D((2DZy)RtlAL(oL{zFY6Vta?$t
z@A&TUx#~svzT^9?|GDZ#`75f^c;ANek9*>;=}vDo^%p@a${$4gQxE;rF<)Q5{_wwM
z$}!!4S`%OIoSbL7-#aa5|Lc_hzct_O7;it$yWQ(TeXD?FYW#QqulQo;xbOD<>U`@8
z=lcA6TfKSv_XYL6dD_xM@&y*H36?C&U%U-2+VYCxc*rcuTda>D<zo+|HzidLP~QJ~
zQ$AXTS7lJvo8(P-%k1$BsSOa;Q{y`0$3F-)+%=6hpXmDfI(CxlQ%mbwl(gU#1uyC#
zy#Lc8)FfkEi&T?*3(uQ!#TPy)HSMw5+rQ`f7ANTO@S;VeC}ZPG4`WN7;Gitty(w?D
z96QA~#`JjMc?>8iZ3LlM6$Dzgf>Rcp>OaT?bJ%(G>7=yclLepJ#-}%Xjv$Fo@0Jyh
zqDB4~Y)K~`tU-y%#C|$RTC;f{5adcx$d&v+8@G6n&$vYyLq8PDI&N{na>d3a`L<kw
zH^nrfSb{OvNBKj+@i)meqTu+OVj5Afa}4pul6_+&k3fnMx%gwjw?!e3&fIaMi$}Qw
z7DYTdlWn7kM<;mH#G?~DYTQsKSd^=9fD{8VNzMrtnV7Z=67K^|EIYxV^9O(SJ@g|8
zrV$5woEvjdmi&2b%lzX-F^zZq>#gSBTd&~Gn}Tjv3dN$J+x5WEctJ|9JiQm8Ke_eZ
zq;+!OwUC71jZZEF9%o^%9Q@(ngip5Kb97n@7a`d2reHfSN_?2cvqgznJJ)0>An)%T
zi_|#U5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?JaxoFZ+4i;`2cSjr;^(ZoVt
zHzs*<Nv<19i`9R(V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P
z(E3%KVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wpp
zEeZu?=C130pqT^jTbCSo-@4?uwc+2C#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi
z9YG0J>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgp-<yzaWUFwm1
zU6kq->}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8
z%*)I804ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1
zw;a*AbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5
zoo`CR5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2l*3?}X+)5$P#3z_R;
zpQ+-!NoXY(`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpE-h}+3bhdfptEmYcNy^XK
z)-68^59^x{4II7m!emb#@~Jn!Id(qmkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT4i
zJIws>DHU(x{5>TU69?{jX(LaZucxG9=DDya)h(p!q*SbshsE79rQ%4^V(%%bfF{2v
zkcu}YC&}N)36@k0T%f0P!kI#}C}cmJI%n6a;b1(w)?gVASKIK!nvO|Qp`ZDhT?DRx
zM~lqtV5ZKF*|~}a?)UhJw8h!+4c#7a94`ua(xZj<%*^xb{Wsbvd1RTwR~BVNn+!>L
z<~Lh%ES#|<MT?v;d_r0yygv3^k}Hc(gajTS^zaz#X)seSS{8Y-<Af8rgye*ud1`(+
z@8xLb{L<i3uIEK*BM20d+&6E^YK<rLJbUzT7_o~M0dpLAzAg&pI36&mbB+V*=OW>U
z<3EFs>opY}8rN>zV3S@I<Hp#V&a82RQT&4(xz3Z3=kua)tQQv8G}bGhZT3jh92bTU
zO%qSF)#i9J;KFWcA^B(v3hfFbPxVCtZ{L(PjyEM+?|(^BM&A94!jX-9!P_lS$rs(5
zqQhc1y6FlTxg8gUpY;^2Hwn$P<oCc{9F89y+=~NV^?OhNNA7mJ<8uc{!Tg&KijnX4
zHz8ULzoBztU~}C%Cr0DI^z_d+qroPVgdClo7Xy3h=JRr3OWmOZ93X|T;BlUm_~8--
z!w;7zocQ6Cgd<70h7^SpD|qtTr`&6=utsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+
zwD%JLJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bo06^fzw`ug
z$oVB<as1RGL0a&XwM&K~pBS4Sq&^T`qPxaNPR`1{=L2KYLE>SJT7;3!_;;>_0$7^l
zz*8GG=%Pu<vB{L=j<M<XQRIv1m5WFRyYzf{Q*vxFGI<Bzq^o#;w{)&}i#Nrh475kI
z8k@PICt4w%P}LR%au40?NK%OBltSw{8k<sR@uprBO6iFZom*;_rzW~clpS0ZQ|e65
zYtqW<*z+ow^~&w*ze|w%jo_dVq<*0_(8{6fV!=DuX4g&FC&sRuqC;$^Zi=2e+J=tO
zjv1%<Eq@489@<cNQreJJwLPHBjS?do5dwPz!SE-!W(_kO6RlXm_c6`?8f!RoyS6KB
zdxn!dNpBtwr<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7
zw*gLyw{3uv+CF%2+K}Sb9BgaUI~uka27~M6ectAM(>i#jS0Emri$Xs2c;qY!<gvZC
zQkeo9?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>zL(2h0thYz_1P0JsxVLsce
z42UiDD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNjZF(91T+Fx&;h7
z(I<}t3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn+q2`ANm(>P1r>g?*
z)<qd;$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%E
zh7DcTPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+lUD0|VtFL&=Y!Reu%DC+>8R%o_0dl>
zLoUiVdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)
zval#vs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe
z=^93+S9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV
z7&|qkMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixl!Jf
zXtkUlE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5
zA^ZJ-U7*w6cq~%N`Kd1%mh2R#pp3~h{iZ~VJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}
zt1Lns7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@g_kSTK+@`LgPMN?O;>mZPf7!
zHCe<LCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSR
zo0NpRgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SA
zo9o-Bdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{
z5~9Nd4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk
z=r3jv<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4
zg@UHpPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8dQF<C^KXn|Tfd
zCC4`NEn_s0^oa}G<do^KiJR$EgaLd}IJlv2VQ?uChZzm_i-ca$f;7mn(-ET*6pRki
zU^lHQ9d>6k>NAVNZUb$0!qU==Y{;EEf;57F?LV73VGGhQY&Tl#?=Owju>I`PVDacM
z9lw#U5pDcrdcw_8ZR+Du5BRbdDb5DFD1`%8htY@G$E|J{D=n{fNib<^HJ#Zbbw}eP
zV-e!WGvs?LLL8HLIxIeo$xfI9Eu=^~U2XOOw?~?yf`Tbfb)eJiO^F5s12Hd)f-?uN
z={F@??|%)le(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p
z@w-SVk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZ
zA*IB*kNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vk;xALClOLo-lz
zW%rJ?khV<wo^^7dbN!@0D{HKa30!vFiH>vLbSt{?sOn;aVa0S&I!w<7TV{7|=1wv0
z+|F{V_0H|A+q82#_h{YVuI^Suu>>Vq(P2^!QVyoW|6%af^^V8BHL{{Zzc*?89j?el
z0x$4NGGs@tc1Sl(N4@iq-YEm)<C)cYO4F0vI}d5y>%D_pe1!Mjz^$g8gBbH5VHSAc
z8FQ?AzBNov>Q3t-C`XdO!}x;}(#c4dMM?H;lxSfM+CvGYb90fBokh8op@>y!u=RXU
zmc?yRa-E>8n>^}0jf)@cWR#SbHkBKRc+pOSqS0irD28v7GLli!cxXHX<w#O8Dm}Kn
zxmd+E8HMF<+=V+OtUhK^rCJjsiqdj0kPs+hpOkb!niMc7HXFqrPAWGcZD|{UIitZS
z+IEyi8o4j$-h-B!BHUUdY6~#C)Hu#dyu|R&Db^K*W25GO4sj2Rf$x9g=jj??QNX+$
zU#Esv1o9F~eRj=>lvaY5@^Ll_9?mNG_BY9+G3A3I!ApLgR)PnnpS9sq>d)G5*cj)z
zwHl2n+FXkwp(1J9Z^64oA*XU1FA6wCLMm)W9tEq(!z)jZM&rpwnL4}j$Z3&fhePQA
z;qx$S&)5$$P<WPwSS<pNvYx)n26Ktd%?6h}4p&fk9XO^0M=vQyka!*Br&`?xm_n=D
z!1ITx?9g%09*BZ&mG+!E{kaII7|2C9#X#`<PW|S{D{eJ)Pv&4~`q0hUX#6mGk=jl5
zwZlx*ZtOwc$cxZ%k%L(`^;cf)?dGmbZ{)EEeeC+co3iN(?H<xHz$ltJsCT>xR7-MP
zt{!00y=gNT7_}KkYo5Duv?$?Bkpk6_H&IGfgL|EdSP%?a7dc|&yo)6!wJ<xKQVKca
zQ(7Tsd`c@!^I@YAL;7f=4MR$6yB_s|AY_zrYQ613yl$z*?V_qfBTTyx{6Y1)T~u_a
zfWIkUP|$N^RD4p0Z`V`@tnW3y>KU-oSNQk2ni-tBzb01p3f}=(zl&$`M62cd1<QAF
zd8dwui)%bNlg>_9ELth_aB3G<cw#QljOz8(Xr$l^Ehy}S2~l;OTA7n#F|{;&nQ{j8
zGR5LdzEb$?T$JnsCr_J?I$;L0UZw+WzDqHId8<zxJ4fWmuoD(wUh0Mgn0%;Y3y+jr
zgPjOd(Sv@G(1Q%0gS|LfDnvI%JJbbt;>wai9~_d?)rW)S34Lp@Jv%*UblOvJ+D(`+
zX)8e%O<7ZzMN<|RCegqulVdY%7TRtin}!A-49?VzgTv(<CZfo#NlWP|Uedq~GgGA2
zWDgE+(7;V&)uM#*O_SCuQft@^yo3M0EMtqpZ$U8O>_1>*1F6F>2L{qkAyZvLL_nGI
z8tfEDnfw|}6|xI9nkr;FWR6am7m=g0ekiAv5<&Z9rsvSAiQj-k$j-UabI^&42RFYA
zra?)=ano2DdvPduAHg<zBq@98<{YqW>z-t!mCV3xm^zIN3yB;a7@WCUr@G-BK@v|H
zrJ2Md!}SrQQKs$YW!eTWXvu(qyrm&S2K45L2`MXkW0X|W)#6a(WUX%uiIPQsrR&`E
z0zhzms@p)jjm>k=81p3WLS*%v@<1FQ(T~B8m+ylgFW(2hUEYt8obt_C(rDhmYcDD3
z`_QTF^nK`*_C}A@MTX<(kbkE!PDxInmBe$6%}=xlxz-nh2P4tvq^pTZKJrB&$)~(k
z%<`c>D^h&I<|mieA|>~Ac6PkI<U3nQJh=dLueFZTST4BMVdU1~*e|f3p1cNE^`hjh
zNQ+5(=#PGrHs4_6_=L}t{=-E{PbHm<E3xMq<%VqOR6aIW<szj&UdLBQJPwj*f-p9Z
zXruWgy{0)dde4ntqVHVCQm5}+4;T1<>BBuT0SHc9ehb0T@&h;YPhW8mQaI#IUIffi
z8hnRv$SEBeK`|U1GW~>`nyZh8LNC=Be%SPnH%52Kf8J<xk(2#RkqdsM0;TNBOWztp
zDCo#<4DjkYC>oRtMFg}oxg1;2K%@taJ+Oe;K^b_kS`i;GHB^LeW$?lQQgWZs4GjlT
zML;wfVEWX6;X=<Xek3JD3Q83Y<O;`NYEXr2tQ?;l4#GNG<3XXYkA~~1B10lG=-i`6
znDtWuCz14%5g6KRjo}kgJ6a}rW?;)|Wq1=KUmDCfeoBv5Y?br}#a2mMFx(u@RtE8y
ze)WbbuehCN_ZHXFpr~ft&uZld^k#?3jNqXIB!mj-M{?;Eg!CpLKq(S_BIpM;;>L%H
zxwZwKKNa=V@Pw+!s6}DO6@)e)eFs9UlA-{th8J*!Xf-^oD~zk*4UbT-1El<n-b%1d
zC}!+UKsZ@TV@^ezHRG}1dcYVSn~GXnIX)Tmq{j&DZ;F14%%Hd_{L<toF%bC^dWPcc
z8se=OiMQH_=Hm<OguO^1eT$OIBY{7mkt!;X*+PgM%pZdG!SKRGm}kWwu69SXAx8%V
zRZ)z`$_$FAP$t7h^3WCxiPWKrmt^Wt#Z*S>P;6oaUAB`Ep;CoUMubZ5Jz>OWd}o7+
z@i6?XqCq)9#ONr5bY%)<M5wGqG&&CD88?P=4cT>8IF|xiky}(TuPsfGii(ZwqMV=X
zAScXJ3a?$13@mlc588_&bR*{|PILwFGU=!yeIx0}Z^Z(yb~0|s`${Of2Lp)@P#AqY
z&}Qs$@+7i~#vZY}C>dG{K|PdKWP%<rS|t@9z4C4{w4ADc<lRJQHuU^Mi8qMGjz3~(
zx$FB3Ezc2Sh7s+(vR*=?t#I%~isPQ~;*khb;p8jzWo!ZGksK4Fy6N#+q#U{?b2F-(
zir}K;$oXVml#a-GnC=%TgivrD%&Dn>`^c$@nEw;4jQ7XObrDjY5YNBTWgh&+jTxs(
zr-Xn-7+cDK(fn6%B#RVNyiCK#5v~M<MTsdYiD6M<r(R0IG$6(x9U>^OBr#)x$vI4?
zSnaW8TNo{e%E&MVNGWZ@fU#1k9R^gBO8+p0Oesgifbmg@BuL-cl1&U@RM$jfFiYhC
zA$dm)h^ai4?_z+fsGJxB76tNV4v=zXwXtq!lghs_+9;Kx6Inm;F~#B8#mpW)FO0EQ
zN(eGQDpb-Ce-b%GM^fT<kae`$nOP;l0&qbkFLCgd;B;8VXDJ1WOi<#K0YIQ~s|=6<
zm46l7-7~Z-)Bh`r%NVZ}d0$2oDAU3gA^u*OV~fIsGYA7?x0Hew(i8)MuCNFL8EkeT
z`JuAjjA2~Lj9ZkP?X8hRZB^2pWv=<L<>+yfA(1aBTcRHmfS4Q@dwG30(+3ZbBB!#}
z26i&#AsURPm8)pT1<zc@I8qMgI)Z>yM-7XKnmWZNqKK7OxhU7DtV=_ZcO_;nN)DfQ
zB6Eo<!E;e^_^z{MGGTL|m06X%{T5|xX{K>r=ihTfO-2|#uwlO`TRN-JZmX2nMPcSF
z#D<pK%AGZ&ZC84&(YUJ=+;t-*pCktpPVnch86u_`jKtxuMBqhfW6KmanuL{2Y!gNu
zq#P$DlC-IXnUb_mEh3Y&O^X;CDDs{Uv?JYLxzVO9ZCwz`(x#3TxAv(N>?0}pC2j5L
zND0^8R-QHucNTftx(+6u+m$lDNSO}q;!I|05Bxi`v`bW&r9E^7!h}s7^(9qB8Ss`y
z?aGl~gq$A^fFnqOop4@aWr9&DA%78)mr^<=fFzXIe*~2EnNR=&f08r2C1Vyde8hg>
zHVI&0Q3ADr7zB%upbe+E5Bw!z8Q3IZ#K}$sj8KTEMHFC@%YU`w)AFG&N}^RXts2mc
z=o((CEZ~jgur-7aCcMLH<(CQnuqa~#h_FohK7b&xnv2zP9~vSJ3x#57r1?!6UJZHR
zK(aVMN~j82Piz1?NRSv*ZH1a)gQyXcA+Vtk`@NxW7~BIw=rE*<7l?;tP-EeI9HD&2
z&)n5%$Xt-^9E-HiaV001qqzuieHAjvn<VIxSLpn~2Em(H21*tJiXpiiC@BX>LpGIc
z$4KO&K-yvfvMfR{MW8LmdY?1}Rj=1eBF{8+$s<f20n0S?4M8TJJb}$7<Gu~T_W0H<
zfoFW{mM|~A^-7R8ncdebERko1x;dCN)Xj5<bL$jhP#`?<zT0qm41Siv@(Idm8{SX6
z8)JYMAEgFoOaTY2_ht^TBm!6#tt0~AJr7K&HVEGHY@HG+=h-?XG!rkAfumI5NJqSl
zpJzi*GWdN6va|>r1`|^~3#Tb4aiR;%iO=#Tv#ufBwLqa3Wo)ofs~!C8ond7`it##H
zfg<Hwj|7pb^PvGmDhH12{sO=<AORFY7K{)Hpk=@XD1a?P#4SL$4v<Cxb)~7}xi>H`
z8b5^hWk9GaNU$SFeiJtgf0Tp2*$c<J(8mnXy@gI@<0SKG><o*|`j~Leg5tM;&<qj5
z1(jxSt^rQ%04b&gz%?5L%B!;g*Mtm~v?dAJ?Fdpr#7XHKXTifQi&V@=2y*7c#ACF|
zq6D%Qf#_)1DzG|pU=az=E{tLEU8xNK^g9X|Z;^72ldaP>Ts@fB3VLr5a>@#9Hzz8d
zmfv^Kzp&-SH)!ZKcpM8n5ca-fgBT2>V0`J>y5%Z9TepNn)Ji)bC5d=w_-bJy(*9Ve
zi9s1VvZ4Vh0`Q9mNQ)J;$uSMNKpYKIE}+LnNyNy`$i?g;4Zv}K%9>_ytrqO0A#A+K
zbY=mccx?EU29S!vxD3j<<6s(Gv;fN_g>ae&2+11hb`A`_GLFG04De1+f-^U9#1<td
zsu$r#c{H5h);uMjd7=<;G=6BJ0EWyz8-@G<rk`L<Y20Si27V}*NPN^HNR`h>dt$5_
zWWHcnK{+<4RvOj|%{3_Jj`&)XLCMK0^(f@nAZ^&PY|9SlQ+TwL98xaMFIKKhgBzt7
zm0+~@#wb!YMkPM&U5rY?voR|0X=`JOaBH|>=PUeQ`Y8$`I4FyE1QFf|#g=fo6&f)~
ziB@b#eJC{JqIgYGkjMv{QhZR#qHvW(xqE$5A%tuV1mfv)_uRNc%EpZ~<Xf+BQ3SW4
z$=~-TNu+EXTRgm<jbk7H)QoHKoEt+x*u-Eh=wrJWfI>qUCF8M841&<MiH3kZZIc61
z?p<y(BGx_y_o;n0qE)+WM3`*}P8?g0(;KfH_595qd$v6m8}r$>SnTI#?7T|SzR#j$
z&c4m!n0T)JZ~>*`)y(texwgY47;$gR3aNVTjaj55v))X<BGB4&H-wNp&vqEE|F*)n
z>o6vz4&xB1UiJ~3*ef!;PUE$h{j}{gUb9&-=XDy#(k)WmR_iM(n!RqT^^?7f9k_{l
z89W^6GK*B#)g2=m+jVuvh{kqZ-7%uET~|+zXl~d286%q8?QSumYrEZ(N7r_{FSGHY
zkVQ8ba&MP;GUVPa^EI@UpU|a##6iADQv(Wy*tuye-D)?cRufqd8eZ^XGf+T3>SkNF
zU`ClJ)=0`c0bG@?ICW@cN02TmjTWD-8!yh0uIOwkfL%#mR1jBj6DbLK?sr5mQ_<{-
zJf<?*6-P{kwKEF%_)4WVD5d4*tmmg{+^wFVXSAe8C&zl3BT^6S3U8%~z9@WlotWdT
zXH+Ws$0G3^bz+X}k~5Sk6Ay~6P)|NOdOOp0k}r#{7)?H1y23B{yy=Rp<O`@bp?UI|
zv`8OMsor!D<F(Zl-pCi(qC}@7-)t*2sQSbbDF%^GzuvU=`7-Ry^^CH#oGeoH$~m}t
zHOxV-3OrLgg8cA~?P-13-?@=Ar9L@>sXik!ug3nI?wj!eZoIx(9~u_n+PdW;Y{rLZ
zl?@?Ik2E|SBn7{pPa{JAusnpcd{`brVqkeFdqtP&0Va+9VR(oQuo)hbxtsC9A@ZB`
zA#ch~q!3zR`eu8`gST(ChqZTC4j^3VF!%J{w?0??Np;E5mHELjJTH@BzEKv5-3ErI
zXDG~Ay_b1%V0?8or$J0vlP?*~BC}H6Vu*A5R;+Hn^xPUV^EJ=ic-MQK265O#+UH4w
zUykM8I*lU;)hC(tY@K2x&(<fIrRUDLB14t@&bz&PNkg1ri=YlU5SKKp*IIYmdW4;b
z3A9OC<M38pf+1d_fD3c8M&Nq%5{6{PqENtb8J0-`ufLTj%#DPb%}Y;%ZF-To|B{I-
z9hu!8aDs<J-bqdk{eYD`(wuoXJi&>n9w8Vmg&TJG?$_2MRR^S8zhu#8R`yF)|6ZmG
zcm{fzF2Z-v18b7Lg#7rk^~sORe+@51_g@?t9j2k<1!qT4*eUP+K6G7#$D|K>PvWyf
z8o~ssRv&U+!!N@>X!xi!ymamKGGO4njAZ=-q>%MNdsRN5yJCjuXX-<;0bf+d$rOGi
z9HNR5qF1XA$woZ97c>DqLO3xI4kX9fB5=h#@D9os7m{2i4|wMQn(&eX55NisNI659
zuiy#n6*UBJVITB2CMR`h#MAx=3VA>9A)Oj{?DxTYBt4sb=o-QEzYm2((?i;)H2!p=
zc2pjvmz7u-FL_}Bh!HyozS>11WAe;g6fgz{QW;U;7Vfi2#P}kZ@_50)+-FBCzayLW
zjQ=K4!BI1NO%RHAnN-3L&PvzxlLt7-;E%+iGD}bp8rY{E5AewM$yf+D?faaXAC%N7
zV`sYldzArVctD@JVh}<An3fkJnR-QFAt<5Ga)u&up--J6Y4YfkXow7nSQHEfMvz5e
zEXvZn6iS7l3!>Y+7@3g>ID^p}aY$bj1;%q6i-aH%Xgrq|9`z0SrG<}Jr`6_2P<#8*
zm4R{$1OrM+{)!&<5snggLW*FCrDeIQLqRS5lJOIPFa2U*Oi24B)d8_Hfq=Bf)*K0w
zgfHcuxp)c$pwhx#;*2LoBI6mtd=`Zsc7y`;OOM6~7D^nbm!gR}Yd<sKs9&|ph|23%
zEi>f*Z(^JJRq->pG!@&FCV~XN+M}rYt(OEst@^DC0^wNwmI85~s<8NC0M`-NT&9?=
zVD~Kx4?@BE%||7o#fSp-Qhe1BP+=!YAq%%of{098Z3dm?Q{$F!AhK;y7^i~pw?Hw&
z_;6p{1Ff7gZ9oXKTLebCb(|Epu8@e=3(Pe}yM?gdIu#J`*KgT`U>O9M+a5Sb#J88C
z3m1jF!$ot`N`xTAe&??aj*WhDL^}2|2}Ud=k?LLy^&*(vOYxL}c!#%D##{!8<Hwy*
z5n7mAf8<9&P}rh~|JVR!Nkow7qA*+%_MnGKD`HI-As?a$N9{5!B4l;p1yX|I2B<);
z`$>SoJtX!>5JJov$8;GHF_8c_%n2dzc0nW-C3w^yT^k4$3v|YZlpMcq0E7ZBl*gPR
zqJ@tIY<ZEgI(eDb5O(aR_7*~uy~2$UD78R1$#O(E2T~^nokkMEc~+EkKz=$Y6O_r=
z`+Q^uPN<@`vzrnU5VakEqaTsoUU5bY|8`mB5F;Kari|=fZ}rvg`ipA__%vegdo&UJ
zp67(0*H?wHFC5jz|D4R^Mq)JlqQE81SSpuAk0JH0pd?1!`&s!113akwVubHIFh>;Q
z9{{qP-vAFD%`h&Qz?@BeK9dQYp-V_M@URLp86f~`m7WkRFy-%_xOfPCTWJq&%5B5k
z7JM$(Fz4p793sc!5XNpLVz?>&AXHLMNRCM4@WRbNs)t*nSTY;L3%mjbPA^~zq?LG~
zOkmt@Dvihd6bBjvQdpvWkq~@Sf~&PeF2-k3*uo260XZ~YcnTPk7ghq2aTby?Q(ll1
z?gBb6&)U5BkSB+Rrsw#~)bt#mnKixKTTc7{;FtvxG;($zTrz5|<R!OD6U=0XMZtO^
zC2CQ?q6?Ez>J7507K$~021(q6x>jyh{1JZV#*CEuiS#b7M0xznP1g%^$rcISkZZQ^
zywMH$XkH2H4YH8YS@}a5GU%064htvY#b3&h^GYEHs(FBt<19d`oma+qK%*zRd9D?r
ztQIAc@lv8($=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2klreb
zGS>PCBzepT_es;~jZDi$X<IgC5IEe281_u|%yp`iN?bQ>qLpi;oJwSjdgV~}2)cGy
zX_<7o+88<#Q(cx@WUmHjKl5aBlQ&g(Vh*fV&NT95y>h0JOY4mrp>y3Y#vw4cYE>0r
zqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0JoRt(k
zv1USt=vUNTAgA&e@J>S_^QwKzlFoC$w=C(Ht9Ri(z_!T}564Ss-oB+t=My?gL!et;
zZ{D>ZJG7Aw?T#T=i@-Gc^=MgbCecGgdi(&A+E+1i$e1IG(G^UG?06PDe<^|9D`^@@
z_O7I9$GOle8xG0(-uYBvLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+845`O^
zR}!5=q4F*?ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$Dv2`0%o|;t5Q(|
z1Y!{eTI|Aa<0j}#OpV-2)*5*+Nb87#B*YD&a42OJZZ?;dpRgB;@_~(!KSU%GQ#WE`
zKty!P0EWZm93WQ5;ljiRp2s2pSf!(rZd>F^I#a#VXM;*Ci5udODjq{{ws_@!rz^#K
z@C6={Rp<p0Kai8`$_)n!$|7(aQ@sY-`4MH#BI(gPP16KriIOt-6(|P%K`VRc%z|^k
z`=bTAIW|Gzz|QXq!6ep<cUm%uN3$qgAXM-0%1MU-J}4<O34RlWbRaSS$8m*n0zl^o
z62N*)y@=Lh>Xm<i^P+OuVd)ME?wmAidu6x7jLq6VFG2^c`aoz!2k9%*IW!_m0Gx;=
zhF-)ka;GJh7)S0>X@G(hm5Ojx!wl>SJq5s0P$1ul!Nej+FF`adie)$*ah#kEB0@by
zAtn4U-W0CW7G_JYm{!6{EfSHA9(BuY5a3j+$pPc4aKTtyC^F-&138STQ4}hd38qYz
ziFyf4%UwVhz}pH6G00N$Tcj8Zs-e0ZT158pO8N)-*P^7$8~|ZnC;)&Eb9uptGv*%p
zUc!*EIM$0OWk-_m8D|f|kl}K0o%=9p1_hr<ed}<=`x0i&UAMt?MGKf?P!zoI;jr5i
zk|5cH?e053T#B9^MrqAl1Ww?ARORh)yaYYxiZmuXovVxuA?$*ZlY(*4;rKg<gy)5R
z0IWP$yfOjxTzCjKmsT&c8<<Wkm-Z5NpF86#6W=dttYMxv*H-U2Sosc@-;qIp?!=G-
z)S$cWuY0JL+e=V|o`G=(NbHh7F|ks*-2jp31=;`@MQ0fHA*@ArT2a!f=!NTmBu;ld
zEpKjQ-HA8Cu2;pnmyjX7pdjwt#kw(X?qa=A0XOMh+B+~Q-FdG9w$ckvBJG3jx@b`e
z#9dK!1jKZ?Yzdm_M4<qzrn?>mPtSsVIogEbJXFK)C9qB};0geGeo{Jy3)sy(qYqXG
zd<jj|T?Qv0j(S000G0HUa_2^72rltXT~23WqJC16f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E+#jOpG@-G682@PI7?K9>0)oe0zKqw(Z`|`Fz6TI^+2Z
zL)V2CLY&=C3OPl9TqmaxQ%*czcVY+<^Y@cN#sD#QiV=A|5MS7p#6S$<Ps)`azrnp*
z(;@}tY<HDipy}*`!lg_}TCmC=EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NZ^K$UI_bJ2&D^BKxpXfL{8fkfB)L#Lzx=%G9(7t4-Btr+f$>Z7!>Qd=c||lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3jawNJm!wCf|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR8ObU8NE*qN~&fmRdk@*`Rc3A9-Zax*>olR&^+qg_R#lrRiQu
zPIAVV$xm7lOG}jM#PSoRUa>?)X<(fyQK@Mtby2Dut6@mnWAqm4-hx7<5sxJn-Y7jX
zOLI`sWaW-hMLUfdQdgq@NREw6c+?47a-7mU!H7Y<M-{6Eu-Qt*M!gajG8jvml&a3M
zC(`B_vgIy^9)q^(MS!5Kpk$|B4-0&$*TZ78tR~}nCvXz3cLG*(#BlRp_-oY(834el
zR}$;b=pn@dHTBj)I95H!Sm!1v2MFxL!C&ly6&ciTyH<qyZ6{P8EA!M7lhu3b9m)zn
z^;TsWAU<Xf6$+{cZw6rLO{@T{dN(rwtKQbAV03)(N&Zrqqk6VyA*6cOvsO~Q{aH`R
z!!F7iOeuM)3oyHSae%H~9H6Tg%zmr^B?|^iM3t3;b)?b=!ZK53Bta>vG|)hxQLhTt
z7Ess?;+p|gG}*8)7K}OvNbG~L-R#1l-ReYU(yaXu;sRy7$_~X!UuCRfIj}NlA?&Jb
zUI@F|4P&f4R@O6ACo2OR3z($=js?zOpv&rIdCoHfy3<Y}J0EMQ(GrMaYh@}#2-ap!
zWWBaBIkKo*nj~5Dtt^%-43|dD92n$4vDB<EN7E>4(3SC&b?RhaJ+hKr8DLrLuB@~y
zh*y@}ESXoPUKG{a?ZGI$w;7EyD67oMEZ<kAXO{SbdHMh;&C0rwXvd(Ho5cjn5YB>w
zG?gDHN$5(sXW7ECx3jci+2m3Eu*~)-ka*Cz4^oG@pWmjF14sT%4~Og9^l&&IiYV&1
zc_UWQ$MRONC}epwST?e}9w;q&$TPz7ljS#IiOTY=u#9E-Ur^|B^U<IhX8CbgFtc1e
z46!PAP?p^+f6>9JoaI$w>CW^zv9xD-r5I9Gek;UO9rA6lh-i7gP-nCpWGqEmPBd04
zg{SQRDHlzL;bULrty_Un$;!QMD&2Ltp&ujrb<jO|aBPKCacykHRB>&{CCNgsN4YIo
z4YpjHtQafrCu+*dJ*uj+aG@R`^|85GS-!SBv8%c*U9~S&zm+!^1#*wg<I5_#<rQY7
zT~`)R*5WPSGOP8%|D0okEXYaSk(5a{cF)4V<>qGH;BtklxN!Q)S$(*C>8wxef-*-5
z<MPL&%JES?dzL~jx4r|@s$BnBKDmMeSYR0e1jkoZVXi0xlxf}~5m?GOLls!~xgr@*
z9QxS89T;<#mFB;)%JkSGBv^&I!YCMB7J(MWm#SF@A$O}YzDm&<tNe8ZZ=gCh0zAG{
zK>OIDKv-qFB1Kq+yP`>0&AWn7RPMVXRag_eqFG$wPrT<@XS~8<P>lT8VrLk(rSKZh
zYE~71!+5NU(m`Q#M)Cx^Q1eL9J}j{A0$gGd_6iYVk#>d=9V+BrVMeU=&d?-QgLjof
zVMtX)IH9ckv4ugg@_a=~u{ym1saU|ig01+AM@3{gYOYk&mZP9bMRqxgrBwKrqZG<f
z@nON2iXU^7Fkyh%Vs=I=bxjjuQ8fY`l}sy`&5dFq!B!*`Zy^U@wpaPQMard#A8BWW
z+<6xBsGvMVLT!<I-hgaV;e8>^=N<w`iLWq0M=_0xCB$AjwtzzidQ}D_u9hR95u<C0
zdF1fA;vJ6{kARAa^v1AF+7i7nZc}yc8!YV%z&vz9Rg`8NZ08=y=>WGvxMxrpw+YWc
z9-$ex30;%tZbp@QW60*@45y-2IYU4dRN(3&A#jzmytc?!&k_%ajs;;be)a$%d7$&0
zfm;g1ja&0HM(cudgMyrEUeFcx8@Kq_LxXwKBYt>MkZXz<;{&7&f@OSXs4u}NzBrwx
zMaDBzA!f*P>fRYmJ=JL<7M!;#p9&RT9S@8MriRHRA1O)FrtW(n_j)_62zSMLduOaS
z1H#v9FVm6~F&@v#7#?5Me4i@poDW(Crqe~Ak?RL2^W3A``2?>Bcs|<^CJ#!6v!7Z#
zkKAQN+rz9-0r~Eo5&PLvz&_^ehzPI9e;QLNH-JVNr4P`8lj#LC`egRO0ZJsAC_{lJ
zsLEn+A5y`i#asyvd~je>qaR9_;OHSe%DJGWuo5$1e>^IAgJ#Uk?QrCFR_@2LuOc}l
zTi}`N%7d-2l1yk=t~3<duq#!C)^k3kjwFpO2L^tQN|T`<rgCZAnW1C)(!&YreD_Mx
zp^!2~2jG>y@D7mm<46rfUeEzj{DP8)94J?nVB~3UR92EBc8Y0BJ`iORkLa8aFyboH
z$(hrC@%8V>;aA3#GrX$OsvIDA%DZxA-(P&EJM-<8tL1~)XQQT>>1R4-2h-2;M;&96
zXbjJ>Npl!TBC6!GMasM}NeA=WmBQwO*=D-+#~`zs<~`6&N6kt(XL_A8om?q+&g}6^
zFq95NuFB<Gln^PV`}qLS%amd|kbHv#!6QkrXJ)NFlG2oE=u8Qp5(r2<vlEXXW$LGH
zWtdhg&(V?UN<&>zGR=|Z9v^$^qz~p~>iA%0w^A?{B~ma42M1xV)J~twz@*)MQQFv2
zL>D1Pn|6`a&Rj}aL7Z9IQx__;w3V*vFyK}?>!KuMI$C4ThIM9TD`nPEv%b=5eIkoZ
zxwt-os9hPm9yZ|0>2-X9S-%dOaHR$Ndqi8_uq)qM3Y_w-k$&t*x7LegBF{}Z%!k8>
zT#3%E6l>{X6ZeYJr#-k%lYX{y(=ZF$m0+!NKnd2mHL$#u?7b+Velj84m1A9!z#Qum
z1teL!_<-AJY_c$suU@i%oVii50QH7>@D7_c-7ZIxl7nsQl?;?-GOsU+26nXa^?jm}
zV`cR_0`@w_4vk8f01j}s!VPfj&`xliMY;=nz?p+Bc!EVqxCiMQI0`yF`il_8fC57B
zJU<F6!C`7IJO!W6hPU8|5Cka00aAW>Ru_C3&r&97%iHLvH6ehABS;A|0lB!&4Pe5V
zu`Lh^&qEbJ6(Gd>z0fQiM{yxuI1{_&wepKd50nXb0FFY}aNyV%0*51lQ6L?QkX*2>
zQ*uEiE*zc%p@A$y@<H0^g|kLJ6$ffwccRev1rP|~k~m@`3%kUbM=p4iMTzkc0wsSa
z@mcPzTMS50DvJ{Q5!#9){alDF>xYm|Nz9g@<cM^0Fe6<S|DZf~!NcSa<%q`CEfHhJ
z)-7;a#`dj5jG^KE@XLj0v;F`|v`}ySBHoT{4k+wV;5mzu3P+b{K-m@q&!Xh$+SV&Z
z*Q!qr&SVdY|1PES0uV))P!McK_JNCFJLlFZg`MW)MHw4-kweoefTKmZMnNDsd_5aX
z(jp}glpZ7(j#XhTIkddOV{&BX!^V3gC73Cbu0vZa@Fz$45`sgmb`DtPS!YVWAg&iB
z!JvjZ1$Tv0<=3_0SosCW@dCSYIHw8`Yf%z<t8d+M{C(?{!XWgmMal`l&9MjxzC{SH
zMG2O-txt}hUSB7`fNHGzb#G{5j`-d}9CJ9z3YBb80=Xor&#qQtqv=6`h~R=g^LRKU
zFq#vqfWT=-kP;cKj)A->tWE(U-sv@Q5#Em0n}j?#Hncat2yrKi4MLFx7#D=+*)Zi6
zr47Q)9iYVeSX~eWaYs=Jd?Dc5MQa!#@IXn8#%kFKa97I?e7jn7;@fG_iEpRsc8e6d
zNXUME1ExsGe-0mHp#uiR?;S$WvocP>3@$=0?YZ?zPMmD5!3fH5QI=#V%Q*;ZD1t;>
zl-PJ><0C-CNh`#iBiO(e9f95j$mm3o5NKmiVmR9Lw-NX;Cy0x+%yICu7KEfDe!O5N
z7iF>K6dbG*n?iV%ju(1iS~~o-g?s6VUm;}7BM31ZX?l437sjTetWe=_I$$pZ)wu|X
zaU?)bkT%dyM-Y4ggE}k^i!#toY|*Fq)i$V6w#X--#tW`=Q4)KUeuo6#I12WZqzxL?
zVG=3$RL{Ce1+XfDiuW!`g3s!fzJYpAFxMi;2?k#{Kw)zs8*pW%!-=9d{@s8zJ3d;b
z!Nw_3__ZKy7`G0Tk;1_(iWRToMP7KiBo*ea!*^e}ygQ|9xC@Pzb>TiJ;!J?i3L|)@
z41FoY<-Q5WRita1dq|K_i+4&*G^C0JrjDXWJG%RZoSZG1M*qv#e>&DaKi|Llp5oQU
zoBTfA&g=H~;rjKT|Kr!ceA(Ce{-6B6|Mlnl3sDFMC&o`5Cyl!P%t<vlR?^;;05h+&
zu1C45v7YQ5QSw%C3MeSAJF>GPZvhuPs1uexmQ2V(g+r@cUX=Q)V!7DnM27@K&>7Xl
zRx1q-M*tKMl@sL+6dY=ZE^IgbJ4VP`I@k;#>qmDY5#gnEDU+WL;Zq41dxmvV7%`S=
zf94c0{#M}uOvA2FUuBTNG;yBFUPpv3{pg$XLiWU`-o<!J&Fx0zJYkng0rGL*&EJCa
z9_d0$IDcHHJ=1<8KUebZJ^Yj&`;Z=>+Y9Z&0U2tyY%wfQUF#U${wE7NGe~a9kTF#I
z4*5}T+=H51M61YT!}URHrxpZ-A$uXTpc?FO0!rn9Z8+@#8yH8NHDDoz^f$!`3m9AT
zG2snYr7^fFb^(eTP?h^w@Tz=Wts~$>nNKhTMYJ1s$;0?v#8q@fF(X=IUKzQjkckm~
zLpng|=s)=)qJjL<V-bObT_Md>oK;0>NzLDp3*Y79Io0}YhbwdFAV`-|#(viUkA;-A
z)un&P-fzBA6-CB}z~0|<0_Q2kKhvP`A=kg@2=UJxl+{riVtm^X>%d*|GtJ;1`{wU=
z<o3ct<ma~G{M(KwJH$=+lTl;aw){;;lr%@G`OmMS%<nqVk(rzPrvhfU>3`D+C&PL=
zzdO}Q@y(+5%sgJl$4}bj^DOzzpX0Qd@#ooSzm>yyqi^TY&rHVnIHCT2M;>H&5&Yba
zw((uZhKMnocdH{V1yX+75eFrn96z_Cb9~zot_2>aKQpcR<ADA99eEDhrH(wA`?nq2
z{c&9XOxTc*1N`rI)H!eJNXqqH$A$d0T?an{hU(*f`1{|}En@6O!u3rzA}#W+`5FJ(
zDZlNAOA1f=pWC(N-*$wHDX+4hRcq0{*>Af4&Ig@%AAYmn43&IvN&XBDe%zYB86fV~
zu5KVa-*!V`r>3(~wVJ*^D|L12tgOrY+p}`%jQb6rBmKPdf6JKsGaeO1xxZ%(d>L^~
z{Y<!DwST*Iuv*}PRD0MrooF6}YVtEdAU~9q-*lu-GuUwh&HScg;OlLw&(8pJ`&5R0
z(~&w;Q%6$nZ#$-$m8#Xxz!Lh<wSIH5KqKqwrkLPwk3ie?wm1T>56W*lQsJBG$ZVqa
zZAZo!hgz7o!>%U&_HJOh&%n))?dO}D6`X{^`LmJ^=XdIj^wh3yAUxl8n=Wnk=W^X|
zy6tZ|T$v}39ahWj+YZm%H00Dtc8&SBI>}Jj>rbiK^Se$J&lfXKt!X2Cqo#!!?0MJ?
z0sZIrt{cO9E?&b_3ro}gRuSz$8~*tbL-Son`2G2A_?ceBkC()6I`YBM)sd9v+m7(=
zm`0jWK7V?s@Hu1bM#9dR^T%_pXYu<n{60pndp(bb+bRS9uXz<;3F`q%5b6?LWh^8`
zp?yTYB{GRf0dPV~6sjU!^0SIk2DzE`&UVozhw4gK+rGX`URPP*K#;i&Rh$w-`}l=)
z>eFF>yUuM6ps=;B)+smWjRb@?Wo$zws(EiyB&DV}5=2K|840t4Sf9JfvK7OVGPfzm
zD{Rhf&ZIC(`9{&TAseFzHRpIdPT%Gn)}*Nn(2c}D2sS9H^hP<e3WB+3XvsA3Ws81l
zB>Ajcg*-|RT$`}SAq=opw2LT+cR7Nz)_5wc^3JfrHcwe2QABqzvH=-K1fNPu8gz%k
zp8`Rd7*^R1g>fh@|3=;2!Ji1mv)INbi5x*;-XV{5hB3AwhxLt0y;*MrQw&y*v2iL`
zJrovsk7!YrP{_BUTW)~)v;kigAf;EE%tcxAAy?I%wSM((b_7)d{_G&>Y(z*)LP+|M
zgYu4Yz@r>h(AS4mm!5;OtxqxldO(H0%C=s?sM?mO7(B`fj+o9j3C-Y=m!ry~B@1+N
z$;(THYQg}GIFht@;N_D-IbkoK6!dm4pH$eQy*yGtoN5)Ff<V&d<(2xy<OuIwQ`$H^
ze9Z;pM>k;eazUnDcy~d@vik0Uyz+VCjATFoa^GE$v5LOAAcxQsU-E@Er6a>%dISn1
zy~rpEYg?~4L)^ArIm>cAXF*;@#$PN7OTTl>rtf~|HJdF41;t-gh6m2)BjGI7D`c?m
z&gYm=-@VVVM1A)@M<`h9oBKJ2-^=@)MUmM9Wm~&E&#2nkD{3|G=|!Qt8Z}ybd7e>`
zwd>BzSb+o_Wk3W>a^1IXEh|UUUyb6b$i{Sp;5Ox6u3(4sHFV{)AosSxp5+;(+mtiu
zfEa7al4RV)q96hRwH&)`opQA2)+t7-qx`}h(@(`}Uo+umPez*rciW>bxFM9M7%?hO
z)(o#+d0)4C>lVXP(qRO@tl_n5>$Zm1uB}rZH|^Sb1wR`D7@_2}rVIMQG27%VLp*Y8
ztQE=_pjH`x7tYMe_d_hvf*;nW;`~4q%JEW6QlJ*IS6~{W2aBgyC<2P7*E!J1t5%&x
zG^<OFqiubHQC2;26sF{ot4EU^;ACti3hBLUB?@qzwsY&WDjVCg^+}8Lvvpbnsq{Mp
zwFO=^J4H+5g2TL0?GQcJtmFW7&h7fa_`0+tUCLEKpdKN(^N-T|IMpcx#ilkMJbINf
zcV*R%W_2*2I=SsJiz5-m6?>RW*h3cc%g%Ha#5pb~b4Ib^7O{$A#jRnAV#O6<TNG<t
z3D&kg^d*$9?ia7wyyS(=S%z;RS)mL!M1lwCJGw#HuXHxVh7&zLeke3(W3U<mahJu9
zfy+>HPpR$*=xr6cGI1`yNoX!XJaus(aJZdP0})*Orl1u|e+s|I0o>WnJ@7duc<!Ok
zF~M_-e2)2@Q^EETE=`-#O99ob0$YIG5e8qhb9xo`-1B|WDy<CR+>25X;Bow%x=4U$
z+R8DTapOmj$jpwfNoEijaOw?^4veO7n22AGK1~-s5LX+1H23f+odN;!i$ZQ9rsdRu
zGBfgRS>(V?!)J7$01K8yF_N<40V-A|0c5{mPggR)@(4YTIFowIs?t&E0bw?O6zYWH
za8b$Q)DKy9%T|;EVOC0xU{NaBVe!i<fMx{jkUdJ6NdaC2Cd}liXHO-}q(WqmP8fjR
z9E()B84-D)kQ!Lq?P1{Sq6DK9`U*7QMdAFAJn|-?HKHC0(`+s<ME4Br!d3w_1B%EZ
zF+nE$e^0sKC&sELB$8<CQQ*{=V6@fPCWg!0o#eI@P}GlH6pj}@jz_o8$U1JTpbW>G
zyWDO>R*gK9QH2JS5S0qSiO1M#^TmjYoKfm#Fxe=7_SVvO{4gV~M#t}7y7*C5)GBNT
zwMgyOl{C`yZnwfDk)g0COy5PlRl8+8K#f+rrHKHA%5Fu(=F86RitIq5f>p#1%GKH}
z0|H`N?3Q02kG(}PM1hYJ{HUZlcxi8i&;4y^1`;h;gercBGds8G=ZI(!<UFoNqOnX9
zc1gn+kSZ&ySfY@pTT8Qu0bV)~P!!lMy*>s~Q{N;s*A~09#QE~Gt1>X*Sii1~4>89}
z#iksFM!WPLLB64tIS#L1yOg^O=tWCi`T%JJVW1UKdMO1H2f(E>0{N15ZE2XPNm^yw
z0eH_U*$xnTR(3x?(Arh0m~rMEtUmXGJHW243C!dkRaRiiMU}f~BLv~91pLI=k79b9
zK|TQN(#?a1I7{%ozKG3cnX|`S*<{|S8RRW$m+Tbo(c)-B=eDVn#DU9XQ(^T0Gc#Ej
z0aNxSL@O0&Q>q@4NNkpB>#6&$(u-S?@*4fr%>z`hsOX3p=3H%7E)H-BZC18#W|mmx
z>)|zTm9OWx@TO`xze%cf`C|U|BA~~@)QUFvlu%c!)R_eENfEg{-^na2nv~=mg`wvk
zXKC1%(2Hy+n$3ZBX_d_uPhXbAjdoVqMJtbqq5Hb8JGD%D0Pu;5!Gn~zP=+q&mRc%{
z7bhixLs|6rB|si4OP@ki^n^n<R-=9i0N}78Jq*udlhqCwJ*c?-64-#1*$yw^C=d>H
zC}0e%lF$<8z(&DPTnbfu2}g%D(O(6nV3n4J)C|^Re<f7TnxjjR2V{dOR}B?+4ug}A
zxHwkUKICgG3MZ7;lX)RggpJW$RlXMJjS0%t^W|(_7!=8N6AJ30gq(X}Pyn>bfICXi
z8*?F0;3^V0=%R#>mI)C>kKoxqKpH{d=u&|#8)L)16qcqVc-4rL8P2{O9L{zi+?W6@
z7dA;8F0KpT5MWY?at8IYa3=#BB|hbZcYz`q2$2M{u`){<t_;^nZ@e-D?&xr4nXnw+
zly^&lZ8KMha&3?%ulI#foMgW;9R7k*bVL!E(}rOq8u@RJ*M-RiyC^v|2|iLlOlXJ1
z(Xldg8qaw~!~$z(wfVz6TKrK4mMH-XAV1b00>Bao$U1fcu!5`%q<CnX&;|iHWSxrX
zL6jH+c%UO0#L8ZZ(r$}FG^RYk%Yb@5*xf97;)ox#uCo(3N+vKs#yl(v*5?H1xK*Ox
zxw^;=hR3#*-4$<b>)IXX1-?vO`X^o#eWEoY{*D+`cscaK<$~n&0_K7#(JE085aA}s
zzBeUfy)X_a2%UC2q?lOWV7Z|5_k!iZEmgK%fSjAq_Z&#*mgsxL_sXR%Xs(t^E#(PW
zCyP=@V!8G*_54j7^Mi}13$gUUjZ#Q@iH&9nr1#tu1tIA@42%<!9w69^KzhKpUu_2d
z<^|KGZxQOvI<s4W2Nx86X<|uEeQ8FEQQE+!T_k=8+F$49BX*s&M;}5$fbc;P&Un}c
zrH7T2g_=-$reK>MSthGZ#$jdK&1?>0^qGv<ixRwP!az@8zePyqVO<+{>_K=yYl8QD
z)-MRm^TDQXLfS@#iEYq&$QEBDEd9+;R$=P_0nrLw4-hrh1aE!csm9Y(POQa6Ab{ho
zPGBC2#F_$}64KF{(!DyKyq0i#c<!3AI|&@QD3~O?-;07t-Y^1M6Y?_<Xp9Jaz@IT0
z<U67ktraw<gWvMk5i@g<2p`$8POh(aEQ9cv;ViV&PmZ8Oi=T!@(F&UrDuvQb-;`)^
z&ZvTDP0-57W{Y@Md=>^U!uWOM)GPu72+4r&W$b8X4<RI{v(e~2=odvpFr61gL)cTm
zps}XY1<pBZeD(M1RxgNHK9;Q+Q_nkI%hq(}pftA$Bd{ac*8~wr%o$^{EDD698^jKN
zCKGC4XB@1uYCHTxh7y*qgq6u|I-B6wiL@g8kgFR<)YVHP$}>af)z#IB3~K7c@x&uW
zfQ9`+rk=@%5<tVNlL_JYGIZi<!E9qYz%l!Df)k(U1X$ryeIT%S>>?2+90_Iu5}gkR
zrsEEEq)g$ZM4>TL@df}^n5h;+<_hHxF^g-@z(GjN{%M@@L}O&um&r!gQL1bIu&Wb4
z+}Vqt?dp_K9UV_pldFmFFlH*k08_XrBbx9q24(q`U@#Mr=@>FLvZ*}6%pM%>sSX@2
z-0dc4$WD{9D$I78m`#WJSU(~_X28Li6@V%p&}Ka2M^3~{<p~Bd-At!GqGilji~zwh
zW-3NN!>=$Xdq&Hc+-V)bGG?kiFc9OjNSr{P;ig&xG}_7uM?4ra;k70n%=^eQ-5{e^
zx&tN=`%|8~PGc)`)B@>+eYkB#LnltEsS{_#{aK|1m|qAxNrJ+}X=PPP;7oC>QUWIg
zt4ax+>Xb_rZ|frnSSnf*1-;qvmNq27cUlgOKnNWbP8Nl;1h|?R9){hy;3_RZqo3)9
zbFR3fm1bALd3L;UO-{{Dlb%xVJI!^bYtWrC(KRQS>r5A;b9Dh>?YXu}@^h|juQ}rI
z6?$j~+P~4E+G&q7!CvQM(@=AItt72)$}sH+oOx5C#ht7Y1t@K}C}hKVWHaTtb6?ZZ
zLi83R+5o{@%m`OS?3SYvfqG)bo4mgZmL-|1LI*U)AunUK4Ws2n5Ab#~#uY6}{w&TR
z#Ee%$(2C5yF<yYh<2`0_Gj}|`f`akl9A}h5;Iv@8EO~>fj6125!DuCORdS*CXo1xz
zG;C%%0f9Ac@^=HHB`KH?)N*Df|C$(jB<YjeCbp1riY?@S<x&l_BWh0sniGrrjT^cs
zw?qsp(r$?u45n|=zCi7gh^45vOA-dcl!Rfy8q8XsBuE&RkaoZi3MCAy+6E8jB2^L_
zRu!l$JEfC(Xn_kXY?Um~vbPT*0FLe^2sFHXP%u9Ug25KDQJ8=y(Lnw8PYSMTN{co1
z5@CFFIVHBDd<ZEmE;W)9yIbQwxtDi}ZCr_ZX%im?V@~beXla+C#T|+@I2|_JowTnl
z0Bk=g6f8&tLJdGUK$<)YQnFwJ*$5`dN&!7hf`u~%@amhGpJ$z2qI{fP=UHc0FfD*M
zP8=~s;x5hmq|uauZQ5W+*_yo$T9)+VwnfslkO+24-wu_aY-c<YD35JE%$%tiwTw5|
zM?Zf#LKY?PQ1=N94Q8Otp&)Dg86QJ+Ei_>i9@k29^!=AxDk?T&xL1CsX<64w9ZBNC
z-WYGw!U6-~;qlwi;_Xh9hm(uQXK;H?-R_3LoVwmaf*Nfirh?)3Lr(F<y^uF1ln?Ok
z=4q>nwD-NKD+`!|J;<y3QWtOr84RTgHMsaoU0PTjRG?sWYWLWbt_FjL(b?8$@Q~it
zZYs+vR(=CKQQBU+sZFVj?Vb9RirC)Nr(8^+IwccnyQxp9(Cyu%!9qlCQ@0cdW~M^z
zJy1Coy~qeD%aDhg%Cc(R(#&ClaS07E0;Q`rWDOeOH{OIVX!~DTFLy$@$Gk5hkRT`Z
zP57!OM7u6^!2B-Wt9*#Gix;b0_wAzQtRlD9{CxGatKLeO;5GEXLga0`#^(!*`8)Lp
zWByJ()Y?U5T2X9F=`o>mWkydu2^(Pj^lEHZQx}MD27j6`zuLv8Qk18a8AIi0FRuKh
z;d5VK!rG7}L&avVQ{5nn7x%R)$<DNJ;kA7vg}rhD^HC>2b})Hg1z+ba13|9A5xGIp
zOT}E_moK|QL-1so9@?C;A`Je}R5!2~agQ={tXv@W;s|+23mYbFBWW*!oFHMy6k^MS
zAv2n{SH4iRa-n8dk1RevyE<Sa|1IPRz;R^&%N(JR)~%6+#!a0#$5Wj!#}hU)&hS(h
z%rGPGjx_7#U?NPw8Y58)K!B#e1~g-9s?<Ji^x<JOZgs-o#-&aW>5P$6HIvoOK8+9i
zl@gSlsO~JvfW0-(7>2tE9<VXKt>N;O8AP>Lm^dUOZKD~a>6WA!B+R@GCJ@+xbBc&c
zqpi3x1Wo4TmWa4vagJtF500a8Xu79HV;>I0WMzj84wIFgYn1NHrf|fSBSa%R*XUF)
zh}}5LG@rkNfCI}H!~s%T+6P+Mg-(FxPq_#h>eH4Np*fFu`5GGj04zY*fT=uCLoHHk
zI<65WU`;804fVdQvEDeM0>V*(PfzvAzW^SHj$H@br!^h3aQRzP9dM@sTPLg2fXy1-
zNIg1C)t8uiRBoh}HWWFU8f_?YMm3kq>p+wKF37&~m{5^w1~e(Jqj`C}CRt^4lclUP
zcu94vn$r!YW6miW4}sBEI+CeAR_hy@OLjrEzi<WS6#F9wBBmG-P2qM#tHYCt8N#)0
zosnY=bukuYpdHNb1vmz`dAUCujVzrlI#u}@I=XeFF*#|Gz)3*kmbbQbI=Xd)0UOsk
zUx2M69;DpD4L)sC6}HBREY)dS=}751*0(y`Ougx29n6Uni6L8EDtU%%3BE0olY+ga
zD0c=zbgc*iAwuDWOSydRturb@x@)K9yt`KZZ}7P~ZlW#)5=Goh8D1?hc8>@oNSR_p
znDW9JL%UdHupzR`gk=1tWP}5Roz@%GH*AekMxQEko~-L6V5C=<CBJ2)SEuQ}!PjeD
z`V?`Ox^{h|BVHKJt<e)t%?MstQ^m=K!_rizk~vS-OQT^hS7&<eqU;eY4WV3$acQ__
z7#Gu8=gMh^((co>LvhoZpW>EP7!L+)j8c+j0X@Z3WtDkLrrNAcVO6wtG=sn2R6Djo
zV>4BpU6lOkzIDr==FN*#r2v${s3TV?BC8&@TN1!7xN%Iyd>iy}^SVW$*Bg>e8_IK;
z>&Aqa#8k96@pVi&tj!QOuL{Zy?={7wHM|7PCtCRtJv<aiHJQfW@H!^$&5Mak6+qV_
zluGi;P%6gYH5#QErPqv0uRF@P^p_@w>qP;94d@HTi#|yw!VEdKlVOB7%PcfgEETj;
zhxZiuOGi+!oB-Mie4vMvju=Ud?PQ3ju9FkhV@(;;i<A&g%%W;1<34qLtWYbZVXu^>
zYXH&c03q80tr-0<jSP}CbSa#Wtf4#M#7dfy#v5&iDv=OrP9sB9iF-JNn`!!+4iHZs
zcqcr%Lk1KSA2cPpGxf=aqZLuCt|@x7a)Nm^4T=02n#_>3fN@!h(M9^x@l}Dme}mZA
zV3HhY#NT515nMd9_>og<Lyvx%CWmf;vjUD?6b2jv%ke?Tps5~*F{*1^`XfZ=4GMT<
zHF;7}h9c`H7H@K?3^lrJ^8K(feKNAV>thI=6@Y|2+=A0LQbvuFy>CjygePn5$@_W^
z{by{pIk9+=#j{p>UT852KIOwuPHTnAr-(<!PK;GkWQNWn-6G}i`SLZO<}M1RxGZ&(
ziR#GLu_=sR%h;uhAsefmc@?SMt#;-u;04R%9lH!IWK@_YgA@8<G>ZYX!!FavVd%RA
zCVMmfO~r~V&@W8&j10!VOA87J3cI>Sk8O2zy7!C$P*>*!p!{8qR*uaze!L=u1QY2&
zIX2e>I+9U1{5<NfA->}tzXV(g7-PFeF~2EYCed+$6m8f1!FJ|t@HxZ`BU9n3!){~<
zU1A(`%1e6)xZ$QES$0>75P65HzlLI4#z-qx<1&CF+x19Hkt6iz(@YY2_}DQZ$=k(i
z!2tDOx1^2{S%P0SpyOLwLXW=%lub%}>;|4JiVoOK1-&qgySR11ex(dArY}_%7};$%
z48}}eifl5p^Sn{MnW27o<)ke<qsmz`nltZ-R*qsKn$99wO-RZN(o*tVWHCkmODuwp
z!X&&!$b>*0BNv`E%H?BL6OI#5ay4%8wdXqkX@rL4`ARh89;{?ULqU~FSd5LlrtsK-
zW@cCFpg^8eB}!VNBvmdY&k&x$$4i+{Ovzm5P~~tk<*D*K4f*PE`a{^5=N5^fkrNf;
zbnyrW^rJff$?27V%DgCKtsWrd$QZa22Xiom0YHY*W|bq$;~Z(UM^ciNv~MiR$Xwi<
z6K;jd*EPnS@xQNpTG}KGaMhI!9O+j1=b8^*@efo!-cDQQF%q!0^kid}yfT=LS@I|D
z59Y|9f=e<0MOChJq-dRcKJ}smNQiQ-dA}|#1-8h@<2seNjX%n->C#YUd`Bxk)Ww^T
z=EKS%f0MQ(b5mA4&jMw|>wZ8|yexFKWyRxw`z0&hwybz;DIl6t>5Ta?E53w<S@Cd7
zn3Cd4RucK*EMWmqQaejpfP{bQpqK#S7o<RFQZdbY>y_X-LMkwr$(!nMm{Q{(NfuJ$
z?NqPW=11WsEK1^8oLjF%v@o)rcotGCfXUU&m~8qcZ9orygEx+##HP3-n}o#B0WwjQ
zq{;nhlc*TfAZFZ2O_5=XkU$VFrV|q*(Nt^_6Jv<u#Kag|pTxwVR=x586NF;2RLUYH
z3I&a-Hi(Kbw{9UNijp*-jJ5PC@rMGK<l1^AJMpXe&QD<&06>!W#s;jJO|^C`Tn<gu
zc&MJYsMcedvESrSF_dy_O?JaKX_+$OUw|l*ivtM2P3{Xr)MjI_b!I~@!%W-y5ErI8
zwS<nTJ~3+{D8DH*)Z~}|6{xs&%gTVQNn^x=rYWG_;1g+x!#|P~OVGyFEhJi&cZ27o
z$<A)T382v`eh3GltmX#yN|T9vQLe-Z;<o@9g1D$xKHk=!@E3A$_tqf?cW+<G!SM^Z
zdQV9d5Jg%^007?liPkk}t^^@5n@-7~6D7;gBw|x_NyH}Gy0oDZ5lKjVskV<SA*Pyo
z0e7u;b;J4Fr8$fQB0~J#k(3;;Z@mbLRlNv`m8S(z4_cR_-qH)zWM?&m<~CYY7a>PX
zq!lL4HW^KAAgQw{3C(~y(3H1kC~HeA{Y%yi+VPVz($Y_vZ$c&;Xy+94^h}@F@+aV|
zg&}28U?2@reCVlO;m2SXBdQutbc7Z+Wh^ET_(6|J5@HElN+W!4&FdU6;>4Z&S>nX;
zQG$Ho=56Z)!0hUkSa^CCAgH-T_9*O8M>v}(ou`oSC}$_o{B-Was0CLSC~+OS7XR0}
z7{IA$etir>4?dX2;JG_KhH~#84ldl=hjS==;N?gfE2yNIE-TnP5}y<7)?;9tKwFd&
zIO6sj=hi1Q?k0;K?SF09)+xXhWh6lM_42=(xVZ*)z)K5K!cfX80FP-?IaC@X+t3k?
z!5?kt5YIgBHgtx=&AL3(U^Ai6W%i0x?~z!Vyr3idyA55>h*%F_x`vZe*Or72H$3uC
zlGF6s%IF2u47&P3Ih(=(Udk(Pqc&l1LN9N}JwBy*Z4~n676d9;b7v$^o4R}vW#3dh
z*x+bxDll9Wov}=6Z)JiDRF4(0VH!`i2U>9usai4<;ZZW-_=Pm|o#5~s+r)#zla`i^
z0GLe!(!Odyi*Rj>2#K86#)nvyxwVdrq|ta|k><UzB`MFwmRPp3+9l;+U{6pK_fsv3
zPe$-Cc4()V-p%kBv@*+y(#R7iU6+igqTp0a-$Wc5myShIbPjszY64ynfhQafs&?sq
zgO8(K*EYV8pE6pJa+{`3+~cieP}LpaaG;;vH6Bvx^AjVw=l<JkME3<@Oug^EB#R*E
zSq)_HMWKmLBq>F32es$?Y;B{BWf2$@D92ZoXftG|sEk_?S}}C11jiOa4(WxedU893
zOB7<NdUQqcl9v>B!EhPyXImLcM3LT`{;r6~)u)3n542)uK64YN*v`+~<S8k7;Q+@6
z7614{ad@ySU=i+3=*CuC&;Y1gwFeJ#JTsnW;}j_pX1})zhm_^2f|wg%uawALQ{@!7
z*;bhM$A0W8!N@Heq2SNQ=C4|gYm`;&k;hGygXEcol94<@Ee7n{nbfNGWSyy1o|5M-
zgX)huudB{wp686h*A=jp%H%as<uni8E>&~WQbnn<oV=w}x|0`KRrfS!Syq(*wHVv8
zUHNOaRYjDSY*raHXN6WF0pnV(N~OHIQO$I_@B;*2D!_=8h-BPBwV_+vG=N}2nI^ny
zw3Y^NWsTNB9cGQHTi-N-;DKVF-|A78hW${Mx&n=<QFXY)U(&j|f_|ZxRh?Qojkls~
zWWLQ0#@pOfr~LBV7?)qZHpb<buU&VF0;6T6a8|^<w{9VGcK^a}YPC??dZzv!AIyEW
z1qkLo8~;PV+PU#Rb{Y_253slGI&Dm;?K*8tso9UQv9j$tZirTIyOJC8X}gXa;-ZXp
zD&f8LtygU3u4H<u_g#UDd;;|5dQC;6UQ#)J*Y$-*P;aB&UonHRb&3VqY!)a8Pk@Bu
z3wTYLVx=cd2>fQV$nvtA%>pIjX|wn`=)mudZ`%;6R(7g<h4#&Afr2~j+5X0}!u6w9
z8tcQKXvNSrLq!Co_RUU_uZ@)gC&OHiCVQkov2S(?7K(41?I4bh-ZnEp&uZtpp(2O2
z8!B>mzZfc*DEN{s<LH~A!j*3LN*l@9n2`uVjBadZlpNjAg$i>_FDnJ>#Lul)4sLFr
z3MuSqvOba$%q#O`ezhxZE6hute}hkj0IrnJ>H}WgTc`XJb;+?jTc2Rmv-QZKJoRv%
zk-^FyC<5<tYh{*q_mYL2Y8Re-SpSeY3u#EP?`~VCH4<-IpBRbjK{b*+$0D&8D_3>2
zVuieKU2-U8vOw*2_dKtlm~18s=os!>m)K*TOoaO2W3$^v5q2-LB~$~iBOq>lpIe_~
zz|^sUJH%(5H8(zd@vOn6;g@>hict7dShnNa1T{!dy(s1-+jo9j{!P{Lf_ZDA+PH$D
zY{FpCU0NTW%)Klj=?3U!2!W%3dF(HG6Bd4e9&2zpARqoEuS8dTlST27KFS$}vvQcE
zbfQL@pz#(ZxHrlfmI_B7<qV6LULPHe+(4t8VK@iNbb{A>FVo4)OQ;X|!+JDmS(`ZL
zhI9;MSM*WdupSenFAN9TD8Fe>gF_$XIQ3|eiD~2QLzYiKGWIgFpd?=(^&*&g)pb@A
zq;s#2a)de9SdOp(Hr`CGp&N05PrT$}Bsj%Oh?0Fg;v=ful__Q-45Uvz60%-SQ0U^y
z9n|M3)+7(Q3ev#Cnjjox4=Pkmz7FRVupQ(Kj*+R02PO`{f6&=G7D5RA9V;|TQgCd{
zl9c@Kl#(05HOotyJF=H8CliqR9GVK$$T>8V)Dl@oG$~7lr>-1iI(6ZEGTx~R3zWd7
zeb#Anoq^4Q_zvi4Qzs3OQUkt4fdnBLQ>VmbsZjRG2w#Rl^)lrEyR}E<CWb&QI2wF8
zw`9gGFi;}qb7_SU0@W`q@Wp~-TwsJibwp1cNs7y$0;qsryC@GsND{_J(IWXHT{A>n
zUB6_YLmWyMgf3%Q`X!wZ{|bbnK}zoEOFR0)y{SkhM%h#uH3s7JtJdX;79GBb-RTv^
zg!rC*=~0g`sIEAsUn)i)NebZ<VzMP@RKF^=?i6y=D*>9<XYLcNIRE<1bp^_E7qqhh
z$*SMl%XjM1x8fjR*9sUcOz?*I+%ml){;3OV+K_d+0JkcPY$PEv$0I^2zOCowohq#Y
zqwMa9@um2-;A_Q1v3^j$^_;+e?6;nqNUZHQbDRtXkorwc6X;_{zu6oCWX9;bEIfDX
z^@%!C{gy1DI#s`wW56)0eoO5{!L5Gl48RZcTQ3e+{{pTJryg>Wdqr6RtF0@_Dl5A6
zJAd>Fh&T=&KeR|3{)Hvgsex>1!qFuqSG2<DU`P&JyOX3`Q{5mpOdu6<g>3F#ro$W2
zI}3NuL|Ws2@FabfuLi(<FG0`~+wT?8STTdAGYCH-wia_Ao&FDwsImkCE^tw>Ziv!a
zD28-2KDb*S`72>2>=o?vz)<#R;;`TOdDaglpNJdzQjpT3FjSkhQF#$A%KC^`<%bAL
z@;jj|@kfR~s&MZ7$f7WuJNF_WGV_P>LGLoDEsA?m8UwB;{)BPeIY1tyQI@rjBr#6B
z<Ks${My%4JaDa|UAkXgfRA-%WLk$R^eqLzh@Rdn}$fZSL^!C!$fO2|(a3zJ&{yCxr
zmAb{$pGm2Z`hmZJ+oi!0=%><t5zMrZS}Wo|*FYJ)=LI&T5%y>p2M}O0iy)`KNTfxH
z1+Y`oj4L6KWih_RB~xAvzPBhG8!C&MvU5)enkjY70CMAsRciQx6CkDG8y-j`jC*p$
zF0t+m&~=%_F%p0`2baI)R(U!37+4s-m12_Pr|cfAmE$lYHlR>=AvM6_=mNH4ER+|@
zg28s|1)*RbE#{XvzRUnwmIGQa#@R})$&c3nDCWW^V{DWc+yG*uT;OQUW*{tc!Wnb#
z#w1jv_`4|$0R@p<rbt#z@=E203G(pD-nSbQs$85KKV7*vH-7q7uT&onH)V*z=C~*W
z?VM8Ok)6?E7TJjpKT32?Bp*RuCnZ;rnPn88N-Q&c_8}4^s$;q8Sv7!NdP8a_;-(1M
z{ZinR6HhYYqJra<uHI4!a2P#V`O5`(*?=nQvV%6*6M;*9fD}_|O1DH(uva=aQh;4X
z&xV9wz@#5Z3H~a8YsEadfJ+--=L3oz?fkAVJTm3>Nc?t;7so(TIwewSz3u6gAy$=o
z-C<VnO1(}CVo;c`iW1i<&Zg4XI^TQl;jCZ`LXKJalc=V*D9iv|8-AhT=f9Ja7yZLg
zu`k#l;EA3}Tq5kh7}4aFFb!j&SHg5h?$d(qXPW7N4Bg_(fD9?S5~-n!LbkxK>rJ}?
z<qa2wU%N0z-4lR&b0$e=lv9rA(bsOQOC?I<V%QR;Z!oA5rQtnrWJ>2tU{z7zm#~j3
zQyOMOXQniO@qEjaMhd4_rnFnsZg^$M$}?I@H%~{PSC(`JJsm+}zIjSZr_+#W>nIVC
zgy3Ws&;y|CJ&n@`NFxZC9uNp!)@ml%M`4QOV<cs|jMpj>>MG>Obbim2Y0snHD`h%^
zpj_DCQLZ#Q=pqELz#{R(6TH_Y26whsUbVAOyrY#DSl68vb8&t5=AVnPH`Yp*Tnyc%
z5y2Pem30lbo_9hugy45&q5|*11>Fuzh$Bf4|A^f%-E_h%0%kiX7`he_Tz7coWe*63
z&XqyI;AJ@|7&N7{LBW`SN`XJZD^q(=FsNI?m*A>LngxHoU-)-!NW~};`-62-k}|UW
z@GtTk0&jq2a8bCI#zZILc1(5J@JynUPNxVN_R9Po7bRBrHA1jleul(WaixMc*s@)v
zT^nMl9q0-#V7PeYh9i#Kdn^qs(q5_J5kS7$jkqxwmyR)502hU@JBB_4u`zywax$Cx
z@SU=3zCj?uPF}YzAIJ*UicYR9-mu@UHU@`Rk9%R`xcUsVb2sfEJ-KByMcgJ`5yiy+
z*{3+vi_k|?-8e}e58EWCx`F=yE%GSoOHd<Mor^`ehDrv#B7iH7MptDF;wA0V&h?Ah
zL--wNd-4|{r0ZA|B1xU<MJTBgz4+gANu*-IHi$Y%2T15bs4r75B1tv%B9c@rzVn%K
z5a!AYHQ?&%1SG7EJ{)~l7mgl)YwiurI5J%CZoqcA%AWw)%bgfP*H9k{0}#U81<{dd
zlZ!CWj6=|st_>(Mmj~@2UYWBx3n9(C;0>-zy*MH0{^556YT6M6usES7TbNAlQ5PBl
zfZ1HZ#YAs&uUickMK8pJ%zZ>Ht{|9t5pd4b2|?;D(?L<v>m^J&cin`*t@DCjxVh;Q
zWe<=_t85t2=5o=cG~ZnGUr_df0+2l}dx1CHT=&A+!@3vD-cYZBHoMR!a!>Ywh~8Xy
zCB)xcc%klb+4UT~FRo&t?%~S!fmSYBLGC?Zzo3=?sED#`2S~ww=FUId+`8f)Zf?O(
zJlx>8^AABjy6Z6vNXSJYVkJyWPJ0odC7r(6LjaUPO6I_7#}afe;aCO*Bf|6DhhB@w
zhIDy(7h<L-KnBn>tCgJ7vmAh&?ga}2)J|8aC_;Urbl!__pr3@~lOjtRD!2p*Lyy~8
zC8_qG{q<MLM_&2`-Ld^_QSxUYbPwM8E;9lOvN}UalQb}Iz=1wk4LUAY{9hZt5GKYO
zi;+=-4~CrUv*Q0cI6*927$r9fUh|PP&`-Gb*z8ylA?YWo#7@AA&}jqdCtid}IY7!K
z5k`L+3P0L8WtC<*v4Iuvw<r^z0{AUYWf8K`!J|i`FG?JwuB?a^fM@uPqU3i|G<rbN
ze6~4M+&Ud5mi<Q_4GrIhd1R-U#)o1lt%;eypKis=WJ_zsN>I9HV7Z+;jVs09#)DVO
zgov(B%7c#~dA1`DZCh{Tp+P{}+@%L)^H>Tq0kxqIN#JOE`Jh~5ms<cmeNrNtZrcH<
zFtk%1ZO6oyZVz`OIQ8tiF=5Zo+K$O7AYRp`4#4u~{-Bt4UxbqoE1kzjhcQM_Kpn=I
zPYSzWjXHcMH~>N7eg*&E57Up<cBJ<1x{My;)(_oA;5MF&b&Pks^_;0i9ob{N4UQ!7
z@*$rt-8}`YKYnR{-bKd>yW(Y(U%GV_<ptL9_|YvFVOMQzS7YyhjnMVk@i2)SHn|J^
zo25{b!kY=q1)$zhmv^T%B`){wJS|n9!rP__Fbs?O!jYu;Y&u1E9-&k_I%))#YSJBt
zs<fBxJXKk*f@f;gtKgBU+Dn+KD{N~~M(Qr8<S>5G$2!E(eXnRi)rvfsFcNr{w77CP
zs-OkTX;K{-c;zaYh`=i-pa&=u3MaX6V-c&K1&>wMv*4lH3DVog8BI(W`C_F)_i;+8
z#*{~?$B=^zPEA!Ea|SAuEAx*rRHg5CKtQ>xKt)D?9(p!(1bDh|(mE19-BtVm;7)v?
z^x^6QrN0kXCr-=NDVKI|@dYrS))B=H9*msw|DUz@>Afw-wZrE7Q`}*{L3bqT52>jE
z+dwi1Y<EUMCN}&61h)r%fsy3f=ZIWuom1t$zpA?ZP(b$;e@B~?wzf!7i=;vz$Ku;p
zuKe<j=-4*s9T6sREa$O}uEVjo092W3aRKlQITjW`*Q)}oLPycDLY+8-!%loHxWJvN
zp||+u3mS7_P*#U>3}QF+!XS22FN|UH!!K9FGd90{9^1$6>V&tjO`Wi~kPqSQB6u!1
zs{988M!o$D1E4lIA(Ar7Nl_E<;SfQ3je*1xZ*Rxg>%-wQKD;3{tsl-1OzYm|BEqBs
z67_aFjqM+<tpV8A9HCLd?ixWy@Yv;L!&})n3J+E6+jNVn_EWj?IQ_uzr|%8~{vOls
zEn77xr;}U;jyH9nOx{1-i^J(Cm%ZS4#X|;ymxmIo*o{J|tRG-fQ)w!Pk8+mc0YgkM
zyUthq*2zBPs-+}T9$rc^)s50j^_qOp`jumt=&Gr7ox_*9QKBsev?PLMJyd0hPLUxc
z<+blCeJJ5p6M*sOJ26)u4)P0?LNC52X#8}rCz1+IdMp&@HQIn{VgPlOZu`dHuovD7
zl0;2qQ6;46nL|52FjZ41`4RMvYEzGn%ZcJ0bdKuA@uH)2p@DYYPN<p&{Uo{;xoD`m
zo={qvOR8?#d!wuXUce+^3imj81%Vq;mK}}B>j`bELH}qMZ*B<MMT0v+6YI^Dt_=~8
zC>8+!E=bgT*B+(6M2UbeWxwyg1~5zS3$lxF%3Dfpalj|NZ{8B}gbO>kEl1{<df(s;
z<d~XDg?zzG9T$i-d-R`J$f!EyDKon06Yi9^nFtRX2%Vh9tNE-%dg^);d)vu-LT+P+
zm*LvV4zI&iwC?aaTqnOXY8KunWV%}v>5}DFaa)UT@=V><l2=}tm}(XfNA<o129E0E
zqWDs3W>ie>)ODItc|U`$7)9_5dSXnLIsz@H3XL9DIrHy@&B`@pvX_tR5*@S0^`TAW
z;DGQhDSBuqC~f+nS4FAS$EgLPum5m?(A_$T>$35nIevi~xRjg(`h_nhtmc5O<V&fS
zZ3rVEl585i)~r%Il^-94jNiZp);gZ5<oU27@+H*>5?VG3{lF1m$FLH2Lb@h-C$H62
zqP|T*Gx8N(gxHm(^LxC6f~W9<oXB1}`=Oqh2+VvVNhXp_O%=)nXzYzhxuCH(S|uT2
zg?3V1Zep>7gP8<l_0PiG`PNkEV#<Z1dXE#4nNt-WFA|G*9&`gXi)Gfo6PxuUN{HRM
zkVLsYFYaop5XuxzYUvqxlNBoYfK-fl-kU;7)md(S;G{4UKvhlVib}*(6=JWs6i#aB
zp~Ok4Ube7OxKDtX&j-?L3M$2Gj47xTPbf2?QoOzgL<*3z2NWXN@Z|vh^aip`Afs|Z
z!3X%7u7cQn%lT@+tdxV|W()n4ZxgKm&JH6y@GkYH5#m;*X@z%!K6&Fwa1)l&rBpH6
zr`Fpfsc@JK3!YV;V>W1*`yJi}{+*Ju{`+@*+*8@pCMsy;x-Ze_?rT&Ylh`Ui8K3V2
zI~D8_qM4wa6b%>fjh5`Cl=!GkI#E%1Hn_=Oo972SbXKtE8$rq~nHxk=$^qW=MF7||
z74DrdrW}CE$fKb3RFL>&4eYEQ4{^7^vRjk@pti&XjHhvV6S36{x95p-N@<KgA!yVz
zOc&ml6!`E_BrRtgvDrr}29O_Clm9LQn_Bw2pcn%Qgr6c20gVa6abzd~L!Mv~+)R{P
z9(h(#5O~0I)Ho6w;Dm8_%H@G=9DFSRCymS?aS;U12%uhZIJ|9a9+_*Nme+UPlaJ8q
zhl_30g;&luj=c$OuQ`~EcOX<^!s|v$uqcINcSeKp%6f!$dH4wubl*rRggwn6dMQvR
zy&i;E-{2xI|H#O6s^ww1*01w#HAY%A@b)}O!bIS{mNnChQe))Fh!?FxxkTU!dt}3Z
zmp?57BOpJ5(SrW2^7gTY`gb}JUxWv(dIP+trgM`=kni%E@{saf?${B^e@M@7MvFkW
z4dJw3*KHaLtAB@QJC9IhBGP|9l%JQk4flA4MT7g0;j%8^EPThvJd-&tT(-olI2_JX
zD0+wU6pG%#YsO{!a9Iva{ot<ILfnJ9mTP?m{$6DDK|EP(eUVggL0jCBKf$%gj^dB-
z;uz8Ix@edvWXz)NMX5k0nIw$GS47lgWPKqYo}yIX*TUaRI$0Zxhgam)WB|OPvu0wv
zo{tc&xfo8SwaEB(=YET9_V2i`d4t(q2jjVZ8C_Ns2A5$KEe4n2kUMY0xnkJn0wyFQ
z-403h4B5Ghv1LuuUEfIt&rJq}??eCTL~^co1m3LLQXgS@6Y09fhDK-5_lDQ&rLGnu
zFSVB~MqWyRFGgOz*8;-2Gp+kvs8lkxR5e1l$KHBlh*#TN@*-YsOFu7cpO>^iV4S3$
zTcL>Bx)`Rtr^JQQ*n(foipo}y=44d1(%(-c7aLn@Z5@?~&lcX|Hoj%V(rs;2NIo{U
zHmU`cv!w_T2AjUve9T5>l1=BvEMM=~S}q%(nR1s+hGbX#_5)H*RYRj<d9_DvsG~)f
z#HD0NG#wDLqG+FVTGtSfoc0nh#EPpOOUD}pUlV*d6@2XloSclkb`208=F*0Q;ss-A
zL#k;;W%;|KqM89q%io_Ms%kAw3%<>@(5jejDYZQ+7txYZ+XGLXng!^zC94e?jK?DQ
zer}vfc^6Wo#mkavR%EvphXSs(I23T*iPoD42p)@zgW=ZNO%!t7G<OWSM!e;dq?|ly
zF{FbVDo`>39vt&%#y2tyz{x&0iXHP3t4K@NT-C1B06G9~q<8R-F2!1K)d>XR5NhC3
zklo-HU9@?qhc=JRfJ0vJUJ7$DaLN&ZsN2zrJ#7dKH4E*CyGTk`+^6Qe5=*d0Fck&f
zQ79ROe$N~V_R*=bQJ6YaItu&fROu+RRcvO3==_k7IB34Nio=u~?8BrGO|P|*LU1WO
zmymOy<fOB3nPZ%fK1>b*MmJ_$cPY~memH~#o)y+Tbf0nw`7H{AJhQOI5RiG|c4OoP
z$OB3WvOl_%Aleta5~|b+b!=)wdxBSGoS`d*OUW4->)mN3tl-_H=3{<z$(J*x1cL!G
z#z(JwIYQ!37zCFBMy9+sfpae^0}KTYBqc{^?_R5l(1Q_k^7M}`xr@miK7m~wa(+)3
zGz5NJ3iI-4Q>e)KN(aPlNX(-Ek;zzkJ0IOvAysPiFt)xzSRRtjDa?yHF{9DDTO~BA
z%dv@q4FhN5yNx+=T_}=gBGKY7nU{`S7xME?fNrxqJ=$eQ+xqB~376(apAwHygo&G}
zp=ha@Jrw0SQ2}L`oK=qFvyFEbOefU>69%9_=u@O6kW{s6I{Uj%O(wIV%t|Ins8tcl
z08_Zy#1+}4K-D>R{7gzdk$!S0Om3o#$LK<#Pu!}#NNio<l?r{r?jLXeCr%XO?d^0X
z>FBa2>jY8h&eW~)s_l<%`9}Kw=%w6h_*9@3`up>DC3WNabtQG<QuIpdrlJKC^<xH|
znM|ahpwCNLAL-^MQgt#T-E`+5$43`0HXI}T9SSa;xLF*kCqBJe+;!j&QE~K3sqxvn
z2gaxUqtX}lPWb9{#LvH7nI1~i$4No@LWTRztc5e^rgY@5y#x-B*$a=pA|@}C3kC<?
z(R4_0ltCMEIr=+&A=ft)-`maTl@gIF6?(Awd!-_MVMcXNl+YP%Yo(T=RG|1J<kD_(
zlsne_P!RgWfqpdU4rE+;djdVxYkTVsoB`UDbJ?MA+k5%o{7pX~Q1YX_S5K+rW^zq9
z4&+T1CCUqp_TD?7x1073IJi_^WJY_kiHQXoe>80zfmD7?8%H2%RBLRVlXza*a~~wk
zZY2XT6<N82`zKQ&mZU683htc{24F`P!v|$aUS>A!k~cG`a&GI6{7KS!6S9rT4J7hD
z(iwp=7Du+@2L;!evw{-r%=cW9@Se>~d8>*$pA_J>CvNQR*vI6M@}8W?f%B`5rmVLC
z7t;rclhX@557s^5_0=6|(vQAgQbM6Z6WLho?LqyZV1)r(a6<%q{ff}w*bStQ4}Gwr
zXnU^&FpOXLAP81DQMt?BeoIkgi^I2PF+M~t3ei;cpgWn-KA0s%g}MIIxBu|;Z}-1{
z`9HsPfc_TuR@mFU*6zRj*Khy)-1XgFU4Q-mukQcmug|Of`tQ$CMaI^*b>D-%p4Y$q
z^>5Gr^v{28e{L^cfBom@fB(~8|EW*^)4%-p|N2k=$6x>F=imPIx!>Q4u-7wpKfB$B
zzm7zE`?vr2@4x-GSHJu4`rrTZw+A^#zpYHx{I|??bl=26^5#3V-zn`4XPaM1`=|f)
zKmXtV^w<BZqzpW2xUCoe*GAGj=1bxIT`?_<X-R3wGWHWvj>?Gpg_Qr>|MKr7<-Ail
z?-Y)6GbX$~+4h>%{&$7Ew$IYs{Y~ivKc)O1I{}TMPKc8Ix)adWE3*LoP3Y@|FZK`2
z$IMihU#_u#_fKp6>A!#f{_W0;mf7Jl>-)aB*FV<mw|3j#o0?fgo;1pP$MjxyUkm(q
zpI5f`LLBhxfpxSZ;Ro}^Zb$)o<tQ<f6ZDU)_t)+^+rG>4qT&AjV*2xId(~?C<Kw$o
zI6g+#_m9^E(a)t>-<?SKjc%3K>fI}F==ieJF0cH%*QT5P%Wl|nH2qU9qCYbIuie*Q
zpID@W|M(B4|K}$^!D{Vubc3eSm!rd3;oVJ#hp)N~l$}$zp*nP5c7rl{cZ>e9lz-T5
zPke`Ri2u>uUaS8)_J6RI{<-}ls~=9kkFibv9ZUK8C_a}m+P~2Wr?Yo29oN3<cFjU8
z<pG;(e=Ox6c7x%p7eK-vQ)MrD_gks<S}^VJe*xdx&%XdePSW@2_V^u3*$`&<?xuvc
zUv>k?;N8v6?^w!JrS9DcMeDxm(osS|)8AE7;g5X*Fa3LO9kW2>kEZ`0`2tWvR)bSX
z*)K<j>!Nor-5-6~4VUTfZi?~wvKuniyt^rd&6nNaJb1qXc@uu>3+Vl2ApZSL=-WS_
z0}#%u!JYX#7BU<_>ZIHCuR3Mk3U%4-w-x>Pm7X8JV{f#L^@MF_zn9Y=UiGi9(|@q&
z{~@F2{Brf4-?4T->_8IwR~r=~S>D}5;DyQ`n2{T;G}lXCd|Nkl@{bIWpPG_%qrJsM
z^UJXzr2O4UgfF{wq|kf!dsDvd2n_m1M^V1+h=BNyj-vd;Yv?zKYrl4b^Ywf9iMPNi
zuOE_%^7Rnms{80D%GVv!{q)fd?Jqms<buC^^>5189dWDk(NUD2coUfp@BHQ$@pGDy
z393G173J$e?q41e|Mu-o`MP5{>OT6B@O3vp`#<`L@@2=mNO*T+`zPK+*4v4(&iv|4
z{FI5vnjIf<it_dF0ABm(D9YCzk?827qbOf@MCRv@j-q_s@x(9Rya+$@F0OC2jFm6n
z#m}kEzJ9gX-jpwgc+a%+7n|^#@^wc<B7dr0Qoinp66GHqMftj8jL%Nl`ib|D*E_%c
zP5hM6h%6-^Qi}5B(5_?W7Yj{<ue%}s@1vh6Uw1@VjgO9^eBBWszK@Qg{EX>z5oY^0
zzloo-ovw5AmkaGp`HiLhOFQ(JHs<$lzkcu!H@bWky}!4Q^r?yP$IP48OqIK<XSt&v
zI9%q>Y~>Ubalm&g&$|~<ertr8%l5OM0mbrlw@Nwv(TzE%zwFk|{v|gMeybZjoOlcE
z)5H14UqZW}`5#y|;~#hlZ66$rHN1Vk)~DzQxb8<s)!Y5L<FsFMoc6moBFF4UM`fM;
zx+B8H-tR*3V?X&aZou3RUWWZ6F9X4hA0t$v{I5oM5bdFUN8uk|c0-8!yPMD7!wu-%
zcemZYa#XV$%0uxju>F%S;au?kk1j!e{v90TSAGv}%-=IO1cAQ0DJt~KZq4D%Vz=gB
zd9%<hPT}~}jfCImCO2@sf%q9O@M~PH%*yyz_5xGNy?-^hy?@W(*7)d>rL(^LdB$74
zJB;(i^(VU6{^(%)w|)*sG3NTiPyEMc`Xa>s6}^p+&<`)hFepFql?#^L5U%y^rueNd
zy8(py?&kgXa08tG-A(xZFS{W}6z8AqpL_#;A>u!H1OLE|?}OKA9NhTwI*r|s0Po#R
zwGF=Ph5*oaH${Yg)oq^!(-hrE_>FD=D)J4m{gZECUwG9IcAI~|0NQ)}YH<6@i#T>e
zo~w7a)jme|!*0JedH3(Kc()BXJ*u0H-*FV!06Xdp2>keSZ{WtP|KJ<=ht2^Xo*7cU
zJTL)h_tEi9`H55EMFH0Vz4w1*uT{5#DSwFiLHZ3}?k}bW&7W~p-}s-6TdOZUK|iyR
z-4ZNy!S>+=7U?%Vq`z7KAEcjg1iua-=XZ_tr<QB0XqC_P`X+tt*h56*XV*9BXPkRC
zh`0Zqk?x=ID<O~Vhqxc4-|%JZU-%sU_U%pi8RyxJ>G@sbjGywKRbb1fv~SXHxWeMs
zi{XRxQ@48aFKhhvF7z|z9vw)Z!oEqr;XVJgCi&H-{r%hj@bup^?i}-<@96J6e2q13
z5PiMuUl05LyQBWNhTnfVVbRB{_l*URQu@>XtLga)mU?fy|DPY~l|U-}R4aEeya=yB
zMS;%4nYjf(=x{i8?hxFVQUOroa3bJ=2M%WnNmP*x=W;<dfES?}H*PAN7;4-h1OvB`
zFFu?(1gflLsQM_1Nro%o3-T6RN}c<FL=FXV$AAcoyQ-9Ex2+zT#2_}&$fz6{8_qQ3
zV2Dj%c7jG@Gn5xu8)7TDSd_=}Qo!W?p7DE88)a-@QBZ^OwlQv`;|m0i$HF<1b&D$B
zL@<v0^)E<Fqd7_?C!yfwz<$T(aU5wdViRu_8JH8B_FEL{B2>&ayrBJge66-u2S`=i
zV>5LjK<S~F^9YEg#D&Ow9|}Uh1uU}(o`JcoXfhPDjLmd0l}zMGO1dzCm5<G!(>OIO
zVsYZ&3|@%6C@=MGBD5b_-eMExei~#TKm-X=V$(-)8YY)0*n>n+my%+gUQ#eN4O!u0
zGYSD=1hE-%f-G_Iu8fRyF0mQCc&Y)GhE;`_g=1J%#9SWZs^TdX0S_T~)2WmFW?Hc`
z@V<~w^$bYe8I=Jy&5Lpy^Ysr#Je~=8m^lp4pV<5~&%{Kln&zRyq*dbzvxr|gb>5A|
zkhxQrm$4Wvc~H{tQtC?ubR$$D``mRDiz%4^TZ@Gs=W9hSg743z<a=H8%AQ)uNvKIJ
zU|#45e>S9Kq~$^K&|vNF8%>ifNaPTKxtLIE;6<oLNx+!g2Q^49r5=|7JhusnDvm2u
zvmD9pVi7}lkZvbb<Q&QGE}=Gub1=0G?L&!yODL`f6T7G$GF{$ngX_Vtm`4=p^Wt5M
zy+Ii*)$FY>s3%D%NZaZMC00j~)L1G7jCur@QdM#rlu)Gwc|d|g?JxXEuB`E9f>|Dt
z4Z3JC1I5!T1yn2(Yr{;dwlV6eUdlqd=GDY$JlQ0hf$^9|I4~X+Sw>dAkX_Rm+?J$f
zAYIv-B$<$e6-7G&2ri{$tKTDnuQw>A)#_8fgc78QN4?vaN1{P7AzRH;q&v6sh;J>S
zOR48VS4~y4ZctXtd~gXV)}@g5RXHJ;`)%iHnjt<=a8nhKk?`zNI#+^2VAq36iA~qc
zL5od>Pj$pW2J#F&MJkb1EVx0DvCKlxG;X0v2)CUdgbEp4N-F12O@fZhaG?OfKt8|v
z0v(~7p`sy|a@V1<Gj!yfdxGUkI%>s+>Hu6yu7^zO-;v2Kl&`<{maSy^+-9u?rP;rf
zfi7U1v8kaH`W=O3L+SA^1p`c}dg;J9^-L&1WuWhfk&QX^RH(s92l0SZ($8$&e+`WT
zT5vK1up`4_sC3b#lp<8YqmF>yP?Gmc$#pR_7{j_4*&0|A#xUkyNfLvJ+Iye3QU8Ka
zw0t|ll7qFaE+N@<CY0$N>Q1T4U&j&fq_Nu(7!j)9)sb29QmP8+rL1go^iX-TY4Ff{
zN<#iRuVo9{O;xac@=5{HZe2O>si}=Z8N@qE+J>@-_pEsmDol6VDTs>Kb+}nBrP!2e
zQ_;Lj$OWUM7Eebl+)(wsjs&4GT+a>2;&?8!+i=MS(>;c3)X;Fl#XU9L(D&PGAH0-&
zEXvu&*xFSqNopvWcSj!8P%XrcWUMi0(q2j~4y4R@l9D^`SRcJ=@@Up}q=F3P+rE^N
zZ?Yy+N1lUADv?X44SLNxG9$!5eTPe^`JG}7gEYnvZ|J!(#Cv25F90cXL)khy(l*3k
zwEd;jni^tMC$(W>Gw>dzaFMMyQ2FyIQoT3Rm?nn6Qu7AosBol?`noSlw(c=?&?xRm
zTyZJbQ&7StloX^Rg>mS%qZ=%vO9I<cjjF2JQD`_uJpzhxG%<!^9F0eSj^a3>#3DT_
z@!mH1ZmbM_&B*^8nLoQTL3AjAc1IHFP!-yaMAM-}Bpu19F9lzC<*R-!g^Zv&?P!Eh
zop#Vl;RSNIlvQmgXoHrt5E~r%EW`#%(n4&YB#o_ngGzSN5eE}YvE4DQP>Su2v4>J@
zcg)Wd%CX&FGk9Cz3W#rHW#f+OyJ57{`{<CWwD41;`@I?M?2h#kwmy25Xt1>VuxwBS
zD?J!0_k2n9`j(z*czsh(g@R+6?2b#^s@U{^a?q)MF(AHd@k*@|N}Anubxh-XAW7w=
z;M><-v+U+7=Nw9t-H{9^%+#rd@?6pap}KH{&|)St85L;5x*of;wK@0o8Uoe9JL)Zj
z@?&?@WC)X`J)r1RWBln=Z8oflv11v)u!dF%rGDwDcY+DC`-obfD4E_--}Scf4UfQu
z`+0ZCD|gw$NCp)>=t=3Qz7ah%0XVcNV@!uOjxHlPVFCfgdQ}7}g+veX#=%WFwL9{*
zhO*3b)Fz2eE&TK<(i*B--%%>%QtH7-n-wZ`-{)oH^{;w4UD+-#X(a)Yqmt64VA_zq
zHJG8MqbyA*L-$K8XuzI^aOHBnXawvO6Z)?&i46s)oHl(@0e0EKsNtEEn){cT7y@N=
zn2|3ES~WQ3!09kWLn*#H?A7Qpm#d`HC18g_{?~wg`4lM!H1YQmUB)mfMuk$|^trM{
zsgd71lt`z;z`wrfYL%R(8CwE})E-b7;iAiN+)*ejx=C{Ax^ChOUDr*Fq3XJ!mEVj^
zXjE6b6!687uy>6Oim!L^t<C$nBr=Bb>r%@T%CF1L2EIPJbSjE;KbM5PVx}%r+VGB}
zX|yAep~{HTWbTM)=RH?YWeuA{9g3sLjK;b7Qpgy}tR49(CbU@#@h&NXd4KNRM!tfk
z%>nre0}04Gy#vwcckbyth(^D2hr=Nn4f2kf;Yq2fLfxxqs-n}8P&Slpyrab~IK?S}
z(52*CLhkX~F6*kvw1yidDfRvrG@6nObtH@o<s`q9n+5k$$O=x*w!jK5PNgXC$W0l{
zOVm+`JesoA^z}OZH5un{aYch}MZVb(T%{wQY&0p($|w6I2|EDrsF(8Y7U%|1b~ZQz
z(0R?ICg28)rY{(t!e~qa-Qi4(X5w60uPJd_hetA)8NDOtY$zX6N6OJqt41ipx>A&0
z0{Oz**=RB&(P=b&oK^ITFE1duDs}Zro*GT|F-m|%lZA|wt4YCgpeS3@Mv6qOky)2|
z7E$*jiy4VsFNLC)mh>Zwxypz=Ny7HCOHH~mHT6n1dkGjH+~t1Q;XchzXn?y3*|zng
zE0!y{Q{UBvT+5ts<wNKdt$9V0iHwr%ms0yf-6Qys@r#>=OQEa=>HI;nB$EZa4U%m>
zbYz2KmXf&?ii&cTezw?_W_0C`>VQ=EkrkbZWnTmt(Fja?{LqTt6H~v$ebxY%m`@B)
zA3E~E`gvQ)ND1o)UvlMobtR$d$o1;V;@^?$^->_qE^mV$eeAeIyA=LpWs8z*EI4_n
z_r}}~ZL8Z~O_|x-A-wEtBxJpmg?3G(+|!wk^+^iZIEEwByXw)uC^Ef~@!FOAs_)?1
zmxsD?rMij>^h&0k6i&jydV(cg7qGWUe+uqsFR3;NT;uwYml_wn9`aJ7u$#x*OP#q;
zF9Dp93)KT!7lrRVWRiR7H4mEPjyo_{cCMb;PhSLisl85j9x}<jPIn&qdU1RHc*vU0
z9Hh66ZxcC4T^YSDrQ~B~wvLRWUbnV6Sx7nRL4&*UuDc2#bYvHOQP3*c<c@aK*1RNg
zE>-6tJKSfsI8SAZI?E+=)S<fsI&hIR)U$-bZ4rb^ws}DGkPYs29J~~=!BwA!EN&$C
z^pMr<3j-=a_Um6Vrja54QjmGLBi-gD@sS&XPCar%*ojsOD)+PR0ux*kWp~IflN&iP
zU0KsQfTXT64Lvhn-nQn<u?7ZO_5P*AQKi5cl#{8?vV)0lxn5rswDMC5S=4?YDJ|+u
zuIM3C8KKu+`Q#puN)Xw~$a&}?pEOb$dLWHVuk?h@gm6z%>fOmH4Wx>PPSJp?xQat`
z;8mQc|NEel!<AaDBl(>>jc%l<bC>fv3-r0;+mEVb;7k>A2`QY*QU(yk9hUOzrMSyW
z9Z+kPU-SVfmzK*a#>;n?ml_Mi-T6=?!+@9iNzy?lP65=K%S#=l)?B7_RrE{BLOX4V
zOW@R22R;*8&t*slbec;u0&(J5MB)MEK1JSVY#FWyoQ{3vQc4idf8&b|ueE+jhQDLd
z<a!P$Fqh{!pu$vkq8BQ~xpiGiU<J@d2I$0Hc5<RlTxBRaU?(nU)YEI@zZ5*=Ko*(1
zaUcs@DTl1xIM^Fp_U?i9a`}-Dw3o||e4xFYHgRf4e`BCJ6zGeDRxKO3k%3OR6!Ps@
zHL{XV$D)^&41|gcN!5W!@vMo_fkyEyqxe*d(+)t2Z&}2!Gh9Hbo|cGjnZqb_cqtuM
z7BF94r2GMN+Lr#Tx`!_CR0l}Kw+!F{sXR#{Bg6}A`H&A3+pgA2sck7>U|GDf)jvha
zwW%r{9cUKcav%fE;;P%x3)14S%yM+)`gFmvdSyI)QDjA*1zBYip9NVrlXdsAv&n}*
zyKPy-FsOagAch(4TlQ~S=}%JdmBW&E6#(f6+HA|$j8w3$k|39o_Sz+ZS86kr2<gDQ
zI51cp#}MCgHJ|!x$E6MqGrnm;<E-PtWOX1?e9Hh%M2ZVg)tNHaw|#V~#Z?xuwbD$R
z#;)Pi=)z1HPL{q^Ho~gRqi;qwUP7Q(Jr-JN)75+_HET4PA44TbSM1@X+{ZStE+HJr
zjSMI4+va1TyEg1&!ztfYiNxB-*24Ips}>Di0|3R>!Om_d5_u^UtY-ZNE>Scnt3^xq
zQc~EZ;$GIEtX7D9DXSIYjx*Q_4xlVHXUUT%NfkEb;yy7-ezDe8wrY<sAXhF0PsQcj
zrEpAjkW18+!K>sdh;k_<*p{dpl5I^CRGx5Emr{c5Y`qlTS`rcGGX)u6N}Yb!5?g4z
zwZs-0PrxcG2#c>Ju8!01s=?yGwx(D^Bd#gdP>E}bbE?E8^Von*d6BYpApOuo4;IeQ
zL!lxUO<zmT=aUo)j}zUZ!`a|L^^ABl_*Y%9D+3b67mM^+B2j$N&@~`YT-9H!Ln$u$
zn=hqCW890aLn{i5WrbMr)x{f1alu4309G!6%sb9ZtBX5S<?7;Y7$ZObODPGPdckMs
z3dFL4nD}ZE5V}r<WiBNJnuiiX(@pu94Vf7okSyyn|4k-PcJoL!D7$&Y7t6wDh%v(y
zgN%{PO%Sb1$vK|^zEE}LOn*SSBb*`LIKxdBBd9|`wyfirhCD`3kxCkx!Bz+rpZlX%
zuDrP=AC%kNkdKONZi$ncOm%P!*IPc9_&}G<B}S1gq-(d1gV|i*5|~|m;vL#<!oO@t
zeeJ5G^IQ^wK*<-Uw>dSOdVwy$l>xEhs-|OwS$UF#ueR<fF9E$!w$vxR&W2F%ODO@X
zj_GZ~|9vSnyR@kd^)h_YrZ(KO`ZV!|4y;SJ2c(q*@-8jw)5sg1%Sl7ra4GDwTE-!E
zF)rWc?BWa8<?MVY^rp~P1`LZ&`I-&2p?x+zXQZ%AQwK#ko5Y8rB-rXnQi<Ed3yN|!
zw63%&7-T49?c<2=goUdjLI#kF3zB63xm*giAv~5`aqb(n-ve{tBg7YKbcFaWME%nG
zwt_8OLRLL2O0I+vVq2fjrI7WmA+k}!(<g76!-IF)%(KA<LX{5J195f~ddmRp@UeL+
zH=sX!Y(2Gv-x>|PpJQthp-h1u$oB_rDwLN2=yECKp4wD}k_<SPO95+uK`({OPqxSy
z3RgHWL){=Bw5xB@xe{(x$*N0O*@PGano)(6E+yCFfMtCNxf+GudJI68ORArgS{(FF
z8&E8lf*Amc<x<F+dT~gTqso#C&t=0fm9WPLPK?9EDo>0<wWBYgh9s?x$KA+tY(2<M
z?nCxBkZ4{*xyy9Cl;CI*1WItwIejU$qF{UvocDyhvVlrRmt_1+pbxet;Pu>&WP=j4
zBi^M0O%*;2b%0%PtV_wS+YVXbNN6(B$LmCBGSCOyuWqu?v4mZ4EW_90Cd(S&78jQ4
zQqsZf<{#Y_x=}o+MRQFK)S}S@ACV2}3+x4+U@F62;VM04*ibHoT%i<AHaf7SZnDt<
zlX2VR3N5J$RtAuaXZi~RK*nupmrsPuC6F)9j3#{zJd6vaWx&HYYhFD`sv#}>;O;ag
z)eH!)s|1z-=6fl8D*UdO1nE)K_(ehMK2#<-ATmyTmH{E-rr-zzM#fc0%b-YIA^BFi
z)=f4#)bWdgR&CG1co|f>v-Flh>t6ykt2r<}S?RMjl;@JjC>5%3Uxp;TZZgSX%Qy>m
zSwUdj1f{-|l2+C>Od?keF9R~ht?9u~mqsYH&6O?64|Qp>*a4MsA-@c88Mh|RJb9Xo
z_yWv$mkkeN@=`D)D9nDuycFhzkkt@h`modT2Fk^S`!axBE``5HmLVD7tA6L*unA2k
zOqanb_wITw6kT^bH`QEMVW>-BIuA}jnG-J5m*r4pr=wo7qf~?O+;Rz=)pD&8=4FXW
z@eX?$Auld;mI0;Woz7}orNKJA)t8V<q|187iOz+;vO4r#0<dz1gW)AX5}fNgUDk$J
zA6MBiLom>#04rx1FXV!08GtL^X<q}katVBH9R*dJ%nG*hBnhAYf)eYpj1gDmovr(b
z{_*>oxh|K@f(BFZvP&u1x~3NztkZa2rND@&dXiGp+wu4O`c&=A-~+i7P66~;mo2^a
zlTC7ki&K~^1CHfIL90^4$ZReQi?{P09gcuadKDlRR}D2QpOH5i&8VB~@PIr;TGb0b
zs9ZEMoZ**pg0E~vHt;d8fNpLfu26tYMl-N3mx8?!L5MF3S~)shIvJ2J-e@!f_~OmQ
z8OpD@7()S;FRDhD3b4txCiq2}y^P?OMxV9qmaXEu8@vUo|7NJ5?1FDu6;SpjlNkk=
zy~$|awOc>lXf?y3>P=>Hx?EjYErV0`QpgB8uq^^74BlN=T{%P4?4^KHslX;%n{XIF
zx@=Pkwkh7Gq(tOx7?Uh=6ol|b6}_nhg#<HVSDMr-uq&!hXT+{F`{-0_(x4(X^jR}W
zQ;)#jK(I@b*-WfU>teI`Cgtl!sJ1uwx)I6kO}6%iIwPvf5D$I{H2-$#vnF3RYMEaO
z`;_$B0C4rPRi5Xux}Vv?U>VRWm%?79)h-3XlnUF*6lNQhR4<9+4&;fFsf>ET`^cBQ
z>+j@KyTd*~or7DheL^!{o6J5kw^1B;3zubufw=?(xEKH~msBGFzU30|;Dool+WGG~
zyzL{S*kKuMru{TzSlGf?8FDbZC}^b+@?9f`!>+5T93JZLUJ@n*1$eg*R+mze%1}<I
z%WYFr0PFH1;m=vy;mCE3JK9UZo4_sZKKeAhf{ON$E$z(nHPNbfCqvn1w(1M?3AxK{
z{S;{>fnrZcDT^2v-!BSUC8fSt2Q+jaTEuyEo^6U<N^&0=!~n4DBeylG(e7is{<W$;
zn<VThzF#dF$UwSW3K(xJMER^85q_6M)*A~zKI;OzY=OKC5Q9r0V?@aABb(S=8P>2J
zcw~!RN}cVH_3Nebb{zWmQ5|)M%-^bqnv{k1l`YPjNiEQz6Z<j1TP}&b>yJC+#I7Qw
zNx@uQ20LU(I}YVLU`eA2=ni6}En2oPNvPhrL#8%raqhx<<p6<Nxg>V$5KZ57f>d_M
zeI2y}Ukal8E-BYwz;uq<$#0vo)o#Cu&az6ea@%BMWk&9hM;i#DOCj&dz81txUqVec
zZ15Nu&>|Y`l4?YBYRAA_FYz8ZM7gwqfY~v%!vg`c1>`coTehlFS^->=f-NFew%7wf
z4wr;25h$`tfpF_D)rX=j%(m=p%*GBy02`)khy2-?*BvJ2yCz)zY(VFBy@`B{<<Qt6
z)eJ1n4z_B1GTg(nMW(n$+^S?|0M2Y-xmYlChb-=hl1v77lrnp^P+6C>(Chu25>3wQ
zfM$#|!{hZgd?U~IDrI`-(dD`hs71lCSO9gqY;b(|8&!kxpiIFi?=?1%7v;9F!EBce
z4rI+Htjh>1-7Z5sp*7oOg#$VBqGYQ>b{&ziIc|4uRkg`xX2_Z!?8BD=L9tJ7LADHN
z+g<3v93G%D+i625Qf9k6(?H5>muDJ4ne8&N4{i{*uw4fH%yyaCg`e3jD;xNk?KHBH
z<7K;YeXzprC6PPoE(s!b>++U_(#r=rvH)ODR`*TbvW5>-pvylEbK+7U4K$$3JU;N%
zT~hsI=f5cj^q<Q)4J^!dIj4a@->x_b13qTEZ0xfkzHDsNs@o2CH7u|VJ12+eHAETR
z$1y~G-3KbrWibP(zlr&>Q=ZN3a!?;AIG2MOIa{{FVn)iAEl8IEB6BIQNnt5p3WYgH
z8Y%}hq8=`#c;8CYw^e*cL;9XApw}hkbZ!{gS>L+VGm6hB%*@`jx(6^bdk1kf1F)Gb
zu-CvzWN%kD=s1D3SdY86qf3HOK`KdV5V4G`7m0?_CGF}6OX*TFyZY&L#Sfgpl2*T|
zMU;dA32LP!sYCEuj!D9)v&xUZC`|&?k}eXay7XO=irwVsgo+=9qDd0j)p4*$nD9*5
zfAEwA31u-o183%>8GnUNdIkiH_iHOPn53u+F&1@C8W+ii*sz-}A!QDpm<A9wNh(b^
z0I^9DMJQGHBE6SD>BA&(+Ps>uj0T(+N#h!IEC9me2izh_AvdoDP}$QSkZJ+Q6dNr#
zxUGd67~U4Y;P5tWqD#a0Hf0EoWodY)nq1z8Ls>i$4mhWhMs|n8Tbkg*@hx&Y7@p$R
z2JkqScAEg>yqY|L4IpxogwX<$lO){Rj|Al;1?+*!Ns{s5!EU7-2SPPpr15@Ir`)`v
z7!~xHl+twrfuTv_vy8HjoTYA*(j>V31(hsHMO^}fH1RU7aN~`_fZH``<Tkhn49!{q
zUGp}$0BU=Al7#o)CBVSQy7*7dcSjSW;J)z;0BMp&aTfUVq&46V?@ieF0dP%{>W*Xd
zT}@8w#%gmOq%Nrzn;$)T=QMh}CEA!rnp>Ar(<pOm!0DeP4%RUe7ba*_z<81<f@2eK
z=hGca$z4y6YS!ONfxZZvJpv2HiT@dZ&?ISrP*X3c{HP#(Jc;5QPUF^$97?F~xF3qh
zbJVc*R2u?V<80SC>Jl*5G^+-#o00_nbti>KVdtt_s~3f*se#+CBrOnXCHd6DuTp!G
zV*CwW(U8zaA&2BPiaGFTq*zJ{zJH^7B@TZW)T?m#!>C;a#UF<Fwxm%6Dp;9f!>C}L
zN3CI{U)?0ZC^eomh%mS+O)^mBDx3c>DqZgqVWth0By1)?+$0H4pM2$APhVVPO;1NG
zQ_`?mSgBqC^e+J)RMT*%dcBb!@@giD45@h&wm%GdSFrtI)Vup=B&D^Uq)`AW-hCth
z6|d|(^J-xeGOFEOx)Z3JS3AU=YWQvB8TIfEF-HRKR-pcR7?tOC^$g0WUBJ-9erD93
z+vz|XM(w#BO-QsQBsJ&e?qSfJdozY<7&YhSk!%cVPeJ#`p!VGKwT?mUxpzKjl;#w6
ze^maTA{F~V&AEvd8lzW}tl{KM8W~Z!3cWu7xOtJLB&3?$ytcTcT<d#&^sD8#hoq#Q
zBuIY@s>ChDjeJi@!k#k*r5fTlINw7Ip%(@39|MVdlLm&9^DTuws67GkzXS}=B*Cm*
zZ<_>|*aJ3?0)r}6DE|QrPLe1kj-oG`KJT%siH&1Wqwb~$ZHfdVf0RDmZxeq|pKjUs
zg9>%)TOU-Y>xerQYTeO2pyeK*pny@Jo+2#}>f>5RvqYt<$bd1Zbrl*gvYM3Q0tR3^
zNm?M(t6fStGX_=hl9@ja#g>^r4y2ZqKMtjKozDh!@sg!KsEZfTNMleJGa_KjR;^wh
z|1qhG7m*2LQW-B<{*%gh$?`|0y(H0solwRK9vFc8Bnbj^tldRl?3mQpOZk$=q|#O(
z!AR84N3pU2luwe#4_%ViGbVNTlEE;k!`DKyM5d$lQXsNS`YGMKw0%tK<|U(kQa5Ml
zz?h|%6*({_&%H}Qdt*{DuOR`bn3uMbNyV&yf-!LzUW%O^lc(VfDHs6%yqYEnCPu51
z0jld1iEDy7c*&@r)WM7h7!wLsVE-|xU{`;O#FOpfPq0Mg4471|tMSQRE$nO)8Z2p?
z4=Pw?t{;;McIj*|o#W8qU^*=a1`dqLQ|&xriBs)7V#rhN)RAH0`ZQ_St0q<Kl%+qZ
zW+!h>#)MLxA+Zkkc;WxYqEekS{ugzs3b0)g<iY`9HA%&+kC(RD4}vZ#)=BT|C|+Ca
zJEvWt1Y=RLB646X9$BXj4hu(C#S)A{58+8<#xtt|3dW*doig|rkDm$%7z@z*7flvF
zK8hq!QYu@835-Q$J8>?^RLXb~g&+7DCJzRSs&-C^Kvg@3B$%bal133`e*ROZ2f&V!
z#Ajo~Iy@BW2oHh;)W}oEhlNA0f)2*w33uwGuyALcG;A%{Op`>8n*-!oVU<>%Is>fD
z^MoP^#-di9T@R;Lo?Q>8R%XD#NJWH4aWquQQ?|sSTAn&7EUINiA&i0>Jw>Ascn}2$
zD1gbc0}w|^!9D@V(Q|2N*Gf?+!YI^HQph|oT7@EvMP)vYTwe>?T)_xqQJX6wVJs^1
zk&oV2M-Lqem^VIY*i|-lw4x2hrjAy)!PwN%gH2BZaL9?gsh@`q7n=%tXqVYk(8DD_
z=ZaT&!q}yt6`e4UVE>ZPtkpMk;@D``wbIzo#$%%e;dDgU^g=VB;8Iq#DTPkILnnew
zEjx4~*wnIP>fzL~WAfoV{VMigY%19?H5aS`I%FMeDB7X3#n$PUAqZpB6Fr8WUgzN<
z&A+LO6@@VNrcgW&Y---2uYXhVBE(>9uLg(DBkSk{(p?(l(Wk$?<k4YZQ>Tv3=W=Sh
ztaw~oB#pzTmK{1oY-rh`&wle<dyj?>C|EL0!^aQ!V4idpd@wdosCFchQ=2l9V3ao@
z3FzlkrV1w*a7-kL#|o!9HM#wr>eOKVJNjT7sw@UYf@xalq#}_&)vMwXhEu_sP6G}F
zYwyE=(<!XTgyB5!G7w=n&$}kKzn5Fs-d=y_dDo=$oqAaz3ByM<$!l<QZ<oJQCo?4B
zQZN*$e8*weWaB#(unBQBoGRGl^>?aZ1t$#WdDrOm_fo*NWQ{sCuzrA%$?5Mr5SyI-
zPW@|dr@uo1n~n%hud~7!hV$H<K??&n&#&enOklvbnluiLhhzmR3@?SOIECRnCEMHh
zcPiwJRTxgqYclm6$6<vgTndCXhOrH&>NOKPs$Rt_ToM+1Jt!Zd(}D*z7NZr0Q|+3r
z0GwxL(;Wa(&m@V=gBFohn@Uy@48wWKHL3Jy)x=g4JmvPI-7cs?8GbMV$JZ`h9aN89
zCVo&omKXg2tzKj2&A<qrUm2}%DK)WO7Xv~4c;glLq+mDfcY!AP^Fp`tSP*nLBVOUY
z#o$r2%b<@^lwBWo@HpCaGZ561dDD>(qE76x=aDxmNu1wFq4aIXM-6Z8oB^%abrTRg
zej=)21pUTcHvz#*+`e?t9aNoNCxa-}*>x-kUe9(I{6QCSpVA9~V=O}(M({k^Ww?h^
zCK&F(uO)#SUQl^5nBh`ZwJ9NWr=l4~P<z(x8=nNZrOkudv&)nZXwNQ7K6pm$M#ojq
zcdXEe5!A6=ZvUW??b7>!UvLi&o?;pNFoM3~E<-+WuI+dPhXEV@`8E!8uA&_-1wzYa
zKh(LMHv6H*?JA)(4pnZ3L5y=dC<bC2D%>W6{ZQd53Stxt^eGy-Q{yTUVjO7PCWHM@
z;kJ5onN=^#TCou0PyshN{0}v7lWl)W11lh66yE768u=TBs+fpzs9u}w_QNBu!XC!q
z3Af2cKUA=aa~OyEwK<v)Tvqzg@s_a;<CJo3TfC@So2~^8^{e6`E(yDN)4jl<f^8ek
zTqBBy7>Bx*@el*qEt3MQ)~FPiNg{t9ZJQ1PhYGjpAaJNSn{t4R!=tQ%9L9n6R7k@(
z)SgXu1Bc494IXI@m1mQYf2ceg_7gsZtaxYzz$U*O>d&UDf(yyN1l<%IYR|@l0g(Mk
zp=vlhxHg;&4mE1iO~JvbRWTIf@QB*p=Y>OuvjQh(;~})s%%6>iPz62A21VN%H@(@Y
zX&bK#W}~J>Y{aa<ifoshmonH3s^QWWyVb@tk$Lx=BMC~+o^vF5wE)1KtxTPB4tSR}
zbj}g)QpAT578AItbB_2{>XxIJi-|XSPT;Zi(vJcvCXi6)xFnkpMF#&Rl{B>XXD!~O
z@Ie#eIOR+2dl)|PB;`)}Ia~78XK^WkVJ=8a>wf}3bt%dGNzzIJd6$AejJ%kDPo1+h
zHw)w3+1lmSJBq!Sg`7HPiSNc+Tzu$;`24&lLbYC$2hID0sY!B(H6^G+E?VuEQgThk
zYE0msPDWMCf;=4sRZJkB&KZ)l_V;s!I3qjMIkf60RK-!W#cU^A9LvFLA86GZ7Yus>
z`gBR;d+^F>;ZKx*J&LuM(6guV+C3nZxG>gduLi_IeB(LH5i*fg{zXA6_st`O-vpHD
zQuxGLd-Up0;FyjgC?;S`mjd|FCDqz%;%r!ZH0>uWqNBiyOUZQ-1p7>ciXH`4%s#S3
z)-~xzD8Wlf@gme?mbrg`?3-y-9>qIMgw&pJ2~zs+gmV_kHa+qFl3~A|a6GmASSMVf
zls-EOnz)pWKF9}pNq2r@i}%6+XzouK@CQ*76LH2zQ4^PPcdOW9v@xWuL2e9*cK+;+
z`CsbgSnG;-nEgIvN|Jyi^vzG4c1}#l7CE;v(<ef_4>5HU)jv+mHxEqikZ1>UJD3o8
zR;7^>L!8U-J2AldU^sNiPe7awV<u(+oSvkBx3yP`M*YMw^inWl;G2#Rc@wAC6Glkl
zMDdjqT@UIdEf3b0P||iir$gTQ|EEYLFx~JIC-Y0GAy_piJ#<}kwDS8q(Zm+2PC*nC
zK7^wvidi716HQFZE_qHgaxK&42)#D}a5@=7F@bG5e#H2`mE($Jo=7xwN#tAm@THLP
ztQMvo+EWn}vph7<C82o*_s|oe6@}KD05csAJr!D!o{l1w^nuoWsB0w9i0+y~s6-+8
zCSgsNM9!rzj{+@b`O}W#EGBSGFA7@uVti|Rw_O8-={_yBqHp}W#G<i1;b=Szi<nlC
zotHonpzwsuo4_a?r&T=xQ93^LVC42cKKbPOJ4X+F=Tn1+&J%9$QdYKU>><C*Vc5ik
z7x*}>?O9oB4j_AT+y@$ejZ4lWfZZI>ZHRTa?VLS&&L^_@9M$)p@TwnIs?1q6*e->S
zHOyJZW1+Sb3^7sL?NSiRcS*IjWlWEk-V&m2;+o(f6k_5Y;kXRsQRk4OvfvXbk&cja
z6Ls^B3Vl!H^Et%3P2hx{qrirV%ax<ZhKVbfvl&i2k=5x^I1Qz`o+HfLtec!m!1s&W
zp0k78OZ}W3Vh&xl6<as~E;?IwbE1omP;(Qgp-aJY%M!kXdhRm|GIUfdd;&3a1d^M$
zDLZ>>1P*~^|5ho-CrRK1ou?Y%mr??6v@Ty+zo-^@Dct)8RNh`<43)Q+7(?Z;O!zD`
z(IGhQNlJ}~f6sNer#M63?Wu{Y{rGGd(z89;1Xo<89)as707EYdTDdN_Z06Z879n9K
zZhw!ejZa(=AHnKoT_c|@lNndd2PHP1BGrfneo(SY^G>wtEdU{ODda)@w@qB2|2F;K
zmr^6*LvjgAPXj}A5>{8EgYMg1oT2-67iZ|dEz=vx2``0e1_=z0z<3j7WseGuUrI@*
zufBjkmw?QX6TqLdWH(P}xdngtC8RtmGd?qy;}KSFGTq}@N1UM6){%TT>8%haXtfpO
zR7!2BK;orLbmA{Ix{!CNwH4xA2J&G6@;Q;8=PV}jnE?A7)fu0K^*O@2O+bCl+8>?L
zwmJ)@a|$M#81SF7WD_IF=%w(Xskqjn7iOYx^d;eun6{<yLA9xn_(X~7BQV=DtBmzo
zbb3!<ea?a<4WQ3arSX}sm}WEpJg=e2A}#>W5gu(K`_EZ2iI+hTn#8Nr9l<$8sacd&
zyrA(^MtlN=c7#ToK&qXkyqI&1Y?3ohYRkyEwt}<h;GTf~990&dERlYMXPZ?<{Vdth
z0QH<j6B!eBRC|2plpcx&rMYAzBkk~6GLqNI7N-#kbIC%k)W%Pez!VBo7`C}^)>{p&
zEB2IujKcM2zD;B-%rj*oFKA1ZBEOUzoX~7Dm-cN_O<?(R3UTh6A<odIGc;VNQ&lFP
z0Q(%F;U<7Rm%;&h4XGLd*`>7cd7py3Js_<lP;{uuDU%r4xnC5tN>Y9E1=M+xR9i*C
zbk3wZdjh3%=9cKtlyi$QH04yumrKe;Af(&eucP6Vb-ke}C#`F2+Gi5reknO;bYo8d
zsE<mJPoS)ikaBZF>8Zr{+_=0sLbuIr*`i?3d~--R_&6txX(+`rl}2wua~@#WW+8UY
z9B(FAkwdaU^-X%Np9u*3nI_%?^G(wnX221kZEk433Cnz=2<s(~`OFp>!%M1q<d;$d
zlEWG)|Ibvs>I5w32#z)rm2+nM=u~e+zG`Fxx|D@>9p$D>aRfpf6&#<4mN-+UI6^AU
zkfXW+FP<ckdnvwg#2kLm0bezWES#b5eM2=4LfR*=K4-|FPpHosGUs7PAJr|Nfb|?g
z(_Xs-5IaX@$tMsyM}V@q55$qPdP8HvxXuSbWeytWJ2mETi3f$Ly5tjq+DB-zxlxMl
zlE56toJ#@o!u?zVCI_&eODWa>{hYC-&Vczj2~3-S`<x+j-FvpkwBt3>3NIMXlN9Vx
z2(fxmvQ-Ln$ihZ6*HOvxiGZ&&ru?H01v;jl3I#gS?)I1N9J09q(>X(aYDXEmqk`p^
zRHDn~#!328u>I6w`x3|%W$0d{Y)-sz6KiPKAx)1n{TZ^v6RvZH@e=M5Had}U{-FMa
zvFOu=d*Tc_vD1O^BthNroyd`mK*l3b+5{r!4EeGhW$rHtPflGq<jV#e=TbOlP?suB
zK9NM|jQ2$qAUbErmt6>*V=~F%2s%cS9L}PHNUi(jRBY%`!Sac`9miy*16FfP-fV}4
z1YT`=Z4Afc&W1njnB3X$xgAy)pGa<UOy)H+pd5ocJ6ir3a=`I-DcAy0_Ucl=_j(jx
zZKVjggc4pBdf=pJFvsD^JSI<eIXaKYlU=^hCrM-kl_@ydM3D0_+28?<NKDzRj6lbx
zJUvJWbV-;5xP=c2jL&i$A7RBNe9OmZg)<2Jn7r9Y>T^uqY*b%6HZ%`2TVxAIrzxU*
z0+w@0V1$FA$#Y$hoMST6fyg;5TmD*Mz~mf3$tIEl9hD`Yv9pEmJ)rAM_H}G*HAcMn
zC6#pYQwI)tMk72*)u}A`#0AHTQUiphGg;xdCAk!GhNd%F;(6C{+f+UP<{XwTpMd2Y
z0m>#oIWJ1KaE$CS!~<T^e#93(QI$KNm2K+?UN(`C>r%+3bmj9Rp?N#VphhLf(`8Vj
z*yHJPO#^px`r9>)>=-W+T6aBm`KE!vIYg9AAaE`L`$Zveo+N=Y063Qd&ZoLyD7Y>>
zS?GM?I`MR+rJqQ`b~=slN<WeWvc*ADh0QM|h2OgRI?$9|M)rZG>@>2^$OgrP9_+H7
z5A|S|{~GtSr^|nhG<lc8r`GF~2OHR$(*-1%z}B2DBOLIW)2Fyk3_zwilK!1alJFFz
zCR=Xpv$9o^)UlAI$tMcL9s$T^L1CUGEfA^)Swe@Y@c0BS<_Huv0TZ|sUS9%Ca7hd8
zfleGRR9NpCFLW5|jz3At0m$M$IQDhe(+AGdE^|5&6o(M8d7!{hPkbU1<`J-K0>N@A
z>XLKXX!5RBn)p(%y{`h6B&nuy0ex}=;#!GMIgJkN1qjP&1beTB16!j9djSk{nu|HK
zm@0~|!n+(nyjJ6xuE9!P#IZEjgKul=p-^eUa;?G!oyKZTt7>K^g^z#&OFY)9lG~>(
zJpt;gEy+dw)t2T2`l~I?3iKDNiLW-Z(J`%1Uo98>BEqFjv4t{gQ*5El+7#E)W-K@U
zBqcwEM%VNrpruW;>TM43$-`b7;<7mD{PxysVon=+Ae3Dj8Ve3~ZJ<?x3%aoYn>z$*
zt-{rvW^Wddn||p<YzvS`IXEc0X5tKGhlix1Yy6}a@h`2Dt=B@ol&wCs9J&}o*|n|_
zm(Nty$`{uDa|HWZNc((R6L*~YRFC{pN?IO?SAM>yzQYHED{`Fk@tFI4TuKe1mv#%)
zA78aA1hHCAQm%k;=%-!)y~LrPdLb!y9QvsjkgIXvr+!xN*}_}_852NrE$n)6=%ik`
zFUARREraO^)*oL$=Ek8By?|B;)fZoVRI6qUXq7md+wdigoRbYfYN^KAVw|cZguhxq
zxWu9P`x;y+pi3gFSrfS=+r&IBFq)Xfr4i5iT!JvIOR4cJ@xITb%X$Ie5-2sk0B?!X
zi#5KDi5(JT=fv{dx&T#)LnrkDR3*;fF8s1Y;tUDlm`0Nzj#)H~-ys?;-__xVjALT$
zHMJ(rj;S@yKwx4`%xgtN6&HU%sxi`vUWtN<)5W_KRh-V}9;_YO$ImK&OPr3s*NSeE
z^*}T_p%;QAf~Cfn;e;AOT`d%Pcu~-LaR{2ex1CcTG<`26r#=pkBA1l13v{($)JM=9
zUS;-29PzD_!Ha@cJ}n}|y5=TSW_;lc5&~{5s}{M|e)^(3XqN1*M;c`32U>@x2$z@x
zQmMS@LikQ(f$`fasq_H@q!O|D(3uU2Si0|t*pjpKRm2wC3CXvnr}SS4p0x_g5>?0e
z0VQ8}EOIUr_Y%mx6yl|jd40`+bg@s77P?_au?-2Qx@|~EV|Nww<Pu=%EgbA4hUUg0
z(4d44d8BXQK?s1fZhJl1Bp=6X9ForQ8i(e_u>wt;qx^fpV&a!lW1``FDHFZ;i<)y2
z@2D{<3*)8K7)`tn#>n&XLK&opE{PB1Q?~e3(3J=}o)?NRMbPnlDfM2;P+rKP6RIcv
zEF{qh;;`1J-(xF6jAl4}&I{$E!jJg&oNzy4TSv7(G4X|n(GUu2p(<7QAy+6mKkxD7
z1{p2`9H^L33GxMxVF;eJ;F%267=MbCFGb+0RWY{V{?Y587X_S<$EhDiX*-uK4d-j9
z$oPVTHeB}fm=JJ_Hwuqm61lHzk#iZnmx8IO?<`b_d;vN0qSOGP5?w}kp=QEmg98#1
zPPGd_OgK&KXCb>zxQuG}&ckI?56>0_hmsU1YYk*wz9j5Shzh?H>`Vw9e^Jm%S!H4a
zFca_M<!eAi3b(a@m<gvR`aga956@l7?bY?Qy4}``{L)^{V~#$*{l|a*?Z18N-`eZH
z`rrTZw+C><Kzg>neS;|zD&X63=#0q&d57CD21}7w)|=Ou8>^zbeRC#H@0D58H6fOf
z6<KSz+9)mLQ~Rl*V4TZ4oi&D9)geN*-d%IyO(m<GIj0YC95>nUT{GK1l3gNk;yaff
zV{=?tRR&|E*E>NNZm2)=Q8?o{OtDYFu-5)Y(Km*aD3jByszrwyZ)Uvsh0zf~Blrd{
zHBHxqyzy}Q4C(&<@a*uw08d?e@1p~D1;71TH*>xA<M~=Ia~$jY^$&0T?Edw#DckU4
z*{Fp3$Fc!M%SM&tCy?>M5>8l2xsd9WawYwGA?1t1LSmKc=e>}W`&#ShT}q7W=v{w<
z>xku>98k<H6Ysr@6z2I}M@o?JxsI4cO_^&{4f<mpDeCaOj(E)ZSVy`$u66We2o0h6
zSVls)aoy-LU+YE)E`Vi^DMI(XaCGX>!f9_ikL#wysdaPOT{y4h()ZnHUjJCL_t(Ds
zyVecx(V?7<fKZ13r$AW;@TO5e#=$3Wz+@gr<h2iFaYXvmP!30ASPf-xjDnzrps3NY
z`O*;|RLu0l2X!v(j=+i38~5uN*}?;GAXUmnq^k`kY=k8jO153L-V@5s2y-x$n-L~s
zC^2Ky_8dyf2rDx-@3b>`AcRmwbis>IjkHgckTF&^zzo`Uvxp6h<4dSDjhKko+*A-X
zaS65RGOQw$fiZA6kL~YAlnD2XfYi&eX*JZRAI!6O+qsf}2zZi`OG!Bv>x2?Yu!z8u
zNI)s#QbLGQl<Ihb$rVw_Ba~V(ccD;fMdZGY#EBv|c5Lnifgp%WDfX|!VJLATHkMG@
z#ER-kLUKpkPiz&RIXFfN?TPH*A+#sT6oe8e;@lfbpO`1(D-><~gA*iEC!UT;q@xX|
z>k$4E$M2}LiFYxaYJnxrk4%_|P^%EGv+CZ&E{FITST}-~z(En4elhqkLa7rGM;1z)
zh)}aY+Qc*OTcmxDIJFSg6QOLed994{K%r!bs2~*YREej~jY^bwaB4)F#Dg=VfS(6P
zM!`PI|ML{3;U_E2Eb#ob0)^k{MYxSJeA6l`j~!|k1R<iQPLeVg;2ev^FZAFTxzH&2
zR3+}<2uX10jhxID-Wm>&i=Q*XFE0TM0X4rAj5#1Q4YsU-^=eZ!A*eGJY#`LoinR%+
zLY=KxJolfPfLOfBhI=v=^)g~qWAU>+c#8oj>B|Z$F?g5NQA;cqKi*3zNpP2S2_?v+
zPw|pUl!?dI?@O!>-)}5g&2SILn&M0IXALoidRn~1?&XUP;ZHj%9b8KBg?d_pA7n2x
z{8Gr<Fv20;I7teB+TpMdRH}T6R9^<wX|M8hvAV>AVp?7DK{Krm`4EkA37j0LCW1+O
z7S9VoNjvT^US}Ce2Pf%LNc791$|l+3&?rD@N1%HUJ=z<z)@tHY7?_wxeCld2=Ftet
zdlZwZ_fm50&rmO92nyjpdtE_=z@C?o?_lyCtRoRY%%Fg!v1ZT%&{1U|Fh(e?>EePz
zpa7wll5;y<j5B%4C6I4<4=x3K0|TNi?zr=dM2PkV?KTxO)$5ip<`&;FL}G5Sfp=BL
zc<<19b1}nD$A#r3;X!$&dD{>l^#VeG&r2zBd1d|lozn)=ZhRbDD>X+5;n`8TG=%W%
zoi0>DJUgnQUIMvS3ro2hhNN$;*Zos4DQb~&B?``YDfQ}&d`c|}&3Os+=F9Hw9ghp4
zIeTSN2?07g>Ij4YogKAgLx9d+m+vnPIlJZo`c8n(UU&E*L}$k}e+bdp0R^~}^?*=s
zvPqm&aYAo)q_qj5H+$v2NeaL;{dM#VK{q>q4FTw8N6~>8N0R`j>VO}ucW93gbh8(N
zB81)SC_@|r2g?raH}q}dbQnXS$d`1dTQJQ_$n`V)qgTEFqBJid=YJ@vKt~Rw5KyzD
z-arVb*^y2ugwwo~l2AznE@>r!%%S;+)4YV5-K~j$4>e($-5UJ6!fEzG_=KRE9XO#N
zRI>w06hdltq^F9Z{9l(;qR<6$DJ9F>9RNKhaAr4XvIJ+|R@$lpXkJRq_mFhZV!~&3
zV6Z~?%u6XtTma2(BU@yP<5_|;JF<v{z?mJ1#-d!U4@mjN2%Xuhw0aErEez+eVQAIs
z>v}3?D+tK!Iq_XGLZ1nY*-=*hMM0~iYD5BFQc2bH#1g7WN@zDBF+1>nZ>P-jcl<P!
z0Pl6oJ(^~m&xES%$mt(;-VcJ`Q@*i|l>RRYT30-i&IFb+EcAjAC>VlfUQ&u@A=XfN
z77{p*Y8K)Pjc4^G8}yw?k0PUC5WCrt^)SrEw=^CGbw5CZf-}e8^TRNjw|%s1)dP`{
zF^nhJp85U5HsQ*bP*T#Cy_6D^H&`9XAj6ipK+)C9eu|QkE^&gQGpW#lbDp4_mr{dS
z%&F6{Si@u~kK2-!44+yUtz;mP!=^X`t{eb+c6>2mvXm=JXPET#Fbq+OdX%CwCJnlT
z8j!4F>;Pe~ieGz3n5<pwF=0}`M2QD+oJp$XDjkfhrk8?;mZ;Le$c=g_xZLW<pn6GU
zj>Dk9pqEk$R$6(as>HULa}Ql<u%fX=hslV3?crfvlLkd8DCni+*)FW93(kPVabCiU
zZI`V(aLnsczzAHp6ihv?2?g8i1FEu91CLUaUHTVlHE=<n<HJ2+*FD3id%~`7e?SR#
zn#WN3A<yllTout>GYcIk@McG@<LJD#>PUth3B2sHr~8?jYvSD2rB)}-ZSqlPp8a1m
zH+o>VnTT_Lk+NB*u`Y`i$)%&~b3_K}5D4>9@^kFU&Us0>1bVT3>99UEO6ai8d#Xz*
zvGpyM3Hv08e4)p>v~n4~m%zc`fY(zg!+4H9bP}jk;L&L@&urAcAe6p3SnNS0X0JG}
z=qjnz5epXGBmq>Ez?dDm(?ej)j{NFTd32tltZZ}ixZCSpgU2zhOXp7LIbkuMjw4ZY
zS<6VIADvnj+2${Syh^ckY1s)sO9-FYCsa~9>IJO?h-ROqaM}^)`sAVoy*3>|jM4NN
z;g}i%WcCS6OM|hC#QA}f;{6(tIX@bKSeKF$+8FR~DOVbOYB-xmb37LJ^3ixf(Cd63
z&Gl3$BEd2Hf(~h0ol1#3(R3*Uoza$f1BB9u#Om;4L?aZdFWgsLyy62wO2ey?j)2`D
z;<6*A_Yx=`&QEP>=R&=TOCs-?E%Jq~5$f_%a>ej|=@ROQ(xw=dYH345glcK>1i@hy
zf?jq6LqE}m#snNn8|1Yxf+1E=C5gW5Yv*lSa3w&GG!qjXxteJ_IC3=;*Nr!Xdzhz}
zPw(R%4{pJL3^;H#*~2SUQR`xhgI5T8*;nZm%m#obt?3C+DZH`j<r|IG=uYeiv5%%N
z6Jhuv&}E0uHX85#I^4Q13R<uA<N{oFc!iyS%U*utBvA4?ce(EEI*Ro?mjuRjjd=;+
zyGwPsAefhOr^gAnyo5V?KgtZych4sI)K=z4wsB>qPYS-u^u^ycxd6ZJhp|nUR70YD
zyz8vy$HmD?e0}}fAim2u+O>xKxOf>xB&&HFhD6JGk8EHnH&Qw~u$&#&AGb}$bzpO$
zJ3DW9kL>8WXYnH>SjSb2pGCeCL)4anBp`ld0`FBVOzom<+70%Cbg+MMo8(94ZrwNe
z(N=(hUw#I$kA0Wimqb<@?^PD?-gvLDfN%blY;jgL-zv8T<ZN+aKKu4pOCDj|-T8s}
zi)w0qbpP6SfT`TSH*rn2u~{IujUV2gcI3Zt!Ze>=d30RmZaXe9{V+<Y<DSz6)w~q1
zPJAw|+MQ6%j->Xk>bD(vemvxYLM|W|UbAPmAP;2>=twB!EQs4t#?Ms|w^yk@kAp_e
zt7_VIe|?%lF#zN7i$B*Q30k^&+3l)!+i@H2p?p3aH|DNlw;h-2&U&{m%7C15SyjzN
z$L;A;l$>gozrBQ<X;r`N1w(pK<go%&$(cRxr8s<M6R!(+C}%<2jyzT#@<mmes}~^~
z3-4vg5=X{(7qsD0N;2wept~*sTP6Tt9`*Nqr(H&}Z%n+5WYkFakgi4@byvOG?(ipi
z$VjeKVXktu9TnRz{^7Q2ck__v${oWS??vTUcXC~2jZ#-}+uN@9nR>c1sl8hAOI5bD
zCrKPnKzjM5s_v?XN%nxKvaeCU_3<z?OIE37KM<9kszf!qiq&@D9z8k(yE?Fu9x|?h
zpY)JJ3m8k!yn4Ohm#%WQy}%+*k^m%YSOBuL0T;Ox%o^|_9#ZJYNdLI<>UE$>T~%>A
zkf*N1cpb10SH;^)N%)aqGnbNUR26S8B}H_B-=N@B?zZC%UP^6$uNUmjkcbYnh^x$P
z2VCS*C@nOcOF;)xP&iBBc4T$D1Z)S${OBl#+mRd6T`IfMN4mc?HogpZ>1TXB?hLr-
zfQPus-ge+a+*Poy7r@$8^tK1ooXXyI;Iti8Z#ys~t~`2APZWu(yluyh<0^04k)PgO
zS~)yhWCA>&qx@|LaQ%%cyObJ_baX)Txm;2OE^&YBXaGnYiS#<~Be%`xrfPKE6rn7-
ztL|-&!s<A{P94zz?(#SxMXM9>)GLdt3-Q#E=+#}J6CK%LU7)9q67eq7Q$NsyNWj;#
z(7X%t)C+#{B+2-TT3~WH0f6Glz}JC5aY3beX?=e~r8*!cPBc^p#Ke_?ub)>-;HZ9}
zK!uL#2VfKzKB}LB2Fhc7phAU@>Ih?TX7TH=e0&Rm-C-K}K4@Lp1(NCjtGJL-9cUF-
z{=R;&=esiabpTeJ8T|U0*}(1u$jXa?R<6(Ox-<o1#g)6S1G3`6U-g2lTmqSv(dvX?
zy>vDrj$9b5j%?Dd<b53pr(M--``OvTHhGZT$Az=%z@~TttvXD1-?~#O%iaa7>M;Jj
zuvInj(4ku%F<@3)b!<D18on1=_o34EOb70p?rG$e_br!LGL<(BrzX#&d>vtIj&niI
zI~3v8-BG4Lcj2o#&?hc{RYwMOC&J1aZrxmvDl0^as}ijNk>Y|?84xMH=>)Sn=K5B?
zc|$0n6MJQdHgtin3@~5^{OY!AM06`ZmsF1>XK2RV_*5uH;javi02k=W8WNNVn`><(
z;yZu<hmu?TUJdXQU;JVX=o4S67I#S--T2g+UBRjh9uya{%HU*ifTx}!-3ebI?oetg
z_+T9MREpMGcBp?9CeKw!)~fP?3k_w!k@(`LWx$cVC}`!2Sb|hsQqH1k$X-gm^tCl7
z(02kv86uZ`=^n|NXOny#Q@zouY37yhrPMSpu|*7@3qxgvO!2kE7TRttv~n4(si&r{
zORv_0cD<H&5Ws<4Q<5IYHqk1%h|aKbl|D(rQY_`ShUA3uQ)yW1(0!^5dnqNlibEOP
zvMzj-B?`qCKVt(5<x+|@Kq$UwYCi@L$|aFG)Za2OFZH+dVRvXh7LK)!#Ph!N)xz`b
ztLwprG4Q*!UNIG21AxA(O0o|~B{IKc)Y);Ns0_t;d=-?^3S#0*A2uuc_-YyfRGzBH
z8c-)bkERbAPp~TMGh3T)06K3TFoxEfN1UPbR87`!wQ(s3pEIPCcR{lZ*DjaBZqRX4
zpLTy~wCR$J8g06!1sV-iWDTGbR}EQ1P7Wug$_jIG+pr}JrKWst$p$5-3bF=Ziq9?9
zP;ymL_DRC32#3QTY;*x<sJV9#L@%x!f0UMWCfPGo+;Sz^v#QGF!dw|pD?XP-3{^KL
zU5|!~L`MZ#t9wQl;_4D=-t<jd18aWL)^f{m)rB>rf_J3UGlNzWbbSMOCCk=!Y-8d~
zY#S5Xwr$(S#7-u*ZF^$d6Wh)N^Y5H<&;9O)zx&y>yWUz|SgX4C?)6qxLyg<RpMn@*
zRZG0X_t$qyxCqq3rB+FlS@eTffjXM>7PKO%K}biy0uBpX1v%mDQF4B>#J6l}>@VIX
ztd)RZ!9T6gfu#^e#={1hj5zNH>SNUtdXO%9CB)syq^1#;Bs8>FV8u9rm|(%YwDD`0
zhEF>cEi}9;2h_vOpsAUtf!6jy_cQ4udS^aiN{PS(oA@(4L)B3p%@pyYtFXEGnJq9E
zI=Kln!G(PBk$1yU-nFm0wH9E<iuE7sGvlvm?bU(E41?V;@ekza(^1t&{(2>c3-o2$
zvpUq+fKEFVxMR291*?|2`pqlVF*VIz2jV&cb=kzf<~c5=#oP29R*=r~xiWu18(km%
zWnLSJPAGzP+Sn^pGoSaEyrG=^wEWi6zq~b~6FZlR&Oa5nd>6!hwKw8P*j-~sSsRER
zRQ9I^@Dh-c1G+zJud+8BJ~|xdrS>x&&P>er<Mt}-7+xQs5$_o(8zcKksh{1(Z{fUy
z1loY9K>R+}S54aK=bZb|PqQr1GqNDYSSZ6CKpJfJWH?lJh9O-YX!W61&Mb|N3Fqec
zc{`XG<{|hV34&AHTKg~|rq%~U^)pcd^ctN-<%k0^5$IoIsU@;^K%GcOnY}}Ff60n^
ziZ)Yx*~kpmASFH0u(*XY$=0#Bwch?co=iRsBfBeTq$5a&N>p#1w7M;5jD<v=s;Ekh
zL|#4Nk;1QxAvj)Z)2@(eXy#I&b=FphE%4H0%Pm4&d5R**vPF&6+h%)js3ZA%U;Fz#
z9QIH^RXtd7Yn%#%aRjWUi9c|MOxaK9q7q?G2$e(0LbDKkhrB8{s4tLfr;I@A8-<C$
z`VNV*5WYW?wWs55mXdX@>XdI0dXxL0?Du3E@_ajS-t<(jQ8AKEQN{#G)2So?i=sb4
zSCwpdrYg=UNKAWDwYd6gY!v1Ln>r*$gtqNVR-4t9b|#$N2)sNN6~_PB{65B1=;xN0
zK({{i>M@PFkjr$A6-Pz4l1vER_!P8sP+{yLDj(riHU}LoGLqb9`6zp&96G(_;TbkP
z_3hL}M+Qq#*DF;bx)$n6v9;ktR>A(uxngs&$EyU2aDeF<Q;r#BGu=bP-B6J~{1nND
zs5=${9bIthj`LoyvqrYBEh_Qg%LwYU37o)9H8V>s!<I{^C`}~ng9&(O8(4i+(~~yJ
zvn$}y$wR=6GUW|06wAsIW6HzD-;;mLj)YK4wHD(_D6rRJ)kPHI@@EIjasGTg;`cye
zZNrXp7ttqMY`#V#_Gmvr`}q?B(4x*W`>4V<0P&Rj<hd*)b>V^^wcH);iDrAtMIQ-A
zflf{}4&(2*j*Akb$MK=3g%WSE<>IJ=Zm{KS9}+o?qe98l*kKPCyX~}CD2vgkJ%8e|
z$XtsK(z#3ften}a*;!J7hAFR=k{7y_iD&=YlB)p41>{@GMamyh=`_NIcGxHr@v6&<
zEP3GJ2C||yhi?^e<h&FIbI|DV>8XlQfC=0uOo8&)i-$(Sd5yG(WnIBH?HAhk@S2I?
ziN&bLLl%{^@X($TKy<|2!sfI=R!bo(_0dB4>=cS%GwtOWx{}|=(SW%hlCHIW2<b!k
zUi&Lv?cK4n5|wERN`u|DCu#ee<nfA>A;Z;&7Ng{k)4>$|z=x4py!V)^x$L*cQf%yC
z&<;hrkcCUNIW8(LppCfuR&6>~PX7hmSDS)vfG3dMLRZ+?>+JRvC2X$LlO9fF^bW2C
zH3m9R5%qE$rudfRyS0O|m5jC2EA+DoPCBiC4g~Hvuh=2Ct^H$sBzDU;tya4A#eRea
zsYn~bRyxuq%&+n|gS>>RX9^kqbkxe@st7#P%2JB%+rX73u=6JVP3Od{@ap5d)|+8t
zFmBq1HoI+b7|yRFD8r;%U;4-GXIo-BH*}8*0Q2lxjiT06HV87`6k4Y?K+H9C-EB<`
zX#1zyv=ded2x)D!Gju_~C*+KoSGN+A98MYcS*|rrd_cGALrwvcWghz`XN`CpewO{f
zM1F+T#=9zbC!$Yn;nxj)Jy{mMF^}Xvrv*v{o^+&4vKBz_S?_N6*@YRN;v<b%Cb89P
zt&yizFQedE#o)UbOXxGtt7DDZKU!W*Bd^6lFO**@rD0wY;sTusHthebQ?T(%m6!K!
zgoN4{N1Z#IlEt5_nO|46H9{sl71-k@z6{(xWfG-SF5%Xv45A!(u0F_;hmckaTpm6y
zrOMm;a0R;=<yNE7+Q2YCV0FUF*uTvBV68#0{@mSf+`r?T;A0>^sG)nXw53)7bP*=3
zUSsS20U|(Xb*$8kAIRnq@DF9DS;!K{V~g!HOOqeg7X2G*VdQ$byQMf~OS0lL)6oWk
zPca2vJ2m)kP{ryRe=^8RV`|_;bU^5l4eZ-w)HSRg)`}PGiK(xr^>Pmf{lYe$t69H6
z73jI%bW;XXPN?>ZaH5Z9w^<%&$zNqdveFRPbb&c%P)Eqn<ZK;IO$%Q+rb?&`s%lbz
zbh`Msvr3{j3{}(;AhRk!8*NfAq{)>>=@$MwGycUmjMuD?Z<Q*^GK6P?Pz2t6w?Tz`
zF|OXHLAD(H&gKL)CXu$3y|8?PurX}sY_%LffebcF7GU!ZOh$RD=A4)+c9T=G76O(e
zTWX;yzy_jQFX{reU!{t+Y?`z_*k>+OU!52=^KZ3A7h|<nT|fI_QfN&UMWr})$)&8e
zdR(<zni^N%(fGhPGOapRw8z-|RMlPraXzNHsT35mLgj4<xj5vi%G(4|V{LNC?61ZK
zn}c0Ty?%fsRGzF;Is#e9Pw$wGq<d+8+~rnJ6J)yav2<Pbtp%n6n_*rHictt=1O8hY
zaJA$5^A>a1Wg;4rCT5Z>5G2=a7AsunNYOUyvVYFS8hV`Uvmyn2W1*EAzvC19V5$n~
z%f*!r@Zw>MlN!IkZ`zUNq6IW7H6Uq|S1+~aKUy8>x>}Cwtyg+CDa?@$nnVwMHvSy^
z^-!78sse1#=Rg5n;h@BRd}78b52NmfQ+HV_{ysn5NEA+Olf{!qtc5B-Ts@pDRDhgJ
z6400G{4(=H9yScJ%jU}cIi{2<YhxlI#QI|)I4JSe5eF-?_5)l7zvmeGtXj$OU|;|b
zh(xrt@~~?+r%CBD4h(ryiKcAw%gyyyLeVQ#GJyU%ARR>!gp!%<hqF$lR80%GV)_Z&
zP}m_|*DuSdCloTtmEetDEch0H!fe*0;q*-ewt*?HSlz&N5BnUAb^>Y4I|AJl{rnp^
zyI;Z{D)YqU8n&)ez51Tk=_*o^>}wY>HqyqMj7XVRAT<u$Op?vLEtF;{PflNw%&dQI
zEY)5z`(TQk#!>84nvx(oZr#PMhuK)U3^E&nYb;g6>+dn8K@D7a$FTcs`CEf)Ege!R
zWNO*cwj6T4JaUf@2-``i`kWt{Du==JgSYF`1J$gYBIh=Qoq7RO*kc$3CdYKqb!hh4
zU-IQI=j@%#BQcsQ4JS*&-|eL7DBr~b9ca2F1W1pVr37fvXOVQPQ4D-RHQTdcjZCru
z(*(i7G$oOYP;Fb#b|%5j$V8gP8wxi&!SWZe!`Uf=AfUK&h)VsrGbs(vq6-w3WT^Fa
zr4|-d3odnRT&VQek^-y~L0acy;M$Ewn@F~eu@DjAGE>8)ssjQNiMsa*b_%1gF>{!^
z8}fIIvFNRC>?MO;VDPul6u<}EAAS&q`b4Z`IJr+dMsdVls74uCfl69PnH;prLhCxa
zw<rx_;L%+t8I)tLIfk&{xffSxW*^D<m=x|8MrFx;a}42ahV#q;nVK`^m-RJ*kC{N*
z(dzx)k8I-LkgKVBhD1bq-sS%$iRGn*`^C*9R9KjP7V!GEoCTt=X-xyCi0p_5T}w3+
zC{!n5iX|hZ86&H-`y_?g?eoM9BPg#NB1@!9-+HjhU*=Go#LM%@dEqDIN7GzEX-q*~
z0h>-mP+jDGCBDH^0>3zk(9Y&HjiIs9I4S#I8XjbQq^Vp_g)t%sv)=*AQa=Jc)+fhT
zI9Vt%IeK#|v&i(j4S);FpzM!^J`3JnED{#Dwp0v2>clpS0Gdz^CmkrQgLB@!vYZ2g
z>Ks{al5N#7{LmoZ;tjCizH!|w=j7<sN=J3{Xsb46?Zr~|-G4SUe}ouf-&1=Nfk*V9
zsYzJ8HWddoe1fw8I?mQg6axg)u`@g#XYb*bBTho#fiD~Bohl-kkQ(HU(?wI^8;M~*
zmY_G3>O7HU_(W!)YQLpI)R(a#GQ>hz%CX8`AG%B?2;6<o+lIsy-Ihv&k==m4vR^$q
zhPrYR2kw8xRRp@`4TBJKpJu5!8pYc2p$cwB-Xh<##+mh*Lu00P&Y^RLWG6F`@6|-F
zh#$(k0a}QX=QHTmG4+42kRx8u&;lc_l*<lIM_wtBW@83<WkD$P_el>G(9daHje(-~
zPr&?vyh1J~G6{9wAO*?)dXAlY!|5W({VYeBkK+HRK}wI;cEl!{pZ!gg(TV6+Weo6^
zQicVwyBwB*=y|rB@L6CAwTX4cG0!|&L(rCxDW<z6<*u;w#H~C`5-|>GU!c|Cfr7~H
z?M!#C|2WaD9)zaiD1%DIJM4@Am83$I!A}gyfaFCRQMfPPe<3MdhRaueoVc;>qsh+p
zuS<a8D`6uC{M?)7-(e+Q1ATr!ptXKBkp;uQ@5Wc?q6RG?5>u>+7<oP9*RFl4K`}7z
z_mYoM3|0Yi&Px?nzvzn49?YVs<S!93t`uSY-cNM*75Uy+ncOM2_W12k*Z_>1l^g;Q
zC3@m}ANu8eAY4r<8;C9@jc5-iV_K50lcBu>)e6d%04As`9R3<OVCj=W0C+ufkx5)J
zJKFDhbliC7CdiOqf)7kpw4;Y|TqV<msxw^G3|+nZn1QMd8KX84P?i6bfvSbY@*vKD
z_M($HbD9^j@x9vcIirTE-b-^V_c;UA26_2VKMB<~s~JT6nbP17OOTHFmH#?Si>H9H
zkV3DD(=IJ>wdMn<xf>DXZkaA=Q2PBaetZL223f)_h(D+QeH*a8EXg7|5KgdSiQW=K
zo^qc`?1*~&9!{_<%AZ)UY5xgQq4@{$dqV!ZO=;w%7J<0?07KQC2X~xcUJQIh!5r$F
zW_ZDz4o$NAwt{dC*657Zqjplepxz@*R0w}LWDT1ce;1)TUSA}HnuO?tg%V!#3D4BP
z-T`vT0RsF$Vvl6F8u`SnM$@hn4`jqHi$gNA$D3qAbC<De>F`K89A7jV&nA#w;=ErG
zInK%9#2O2Xv+kLM;T3j4=H|EF@cDT^@1QK&(l@e$QYyeBUI?V^qqyBDcaNCE)5w^8
zfLLwLpivNQ3e@M#VsosvREFT>4D)W%7RVT7yuC68Sx~XbCn>;tyH;0PXf9S){Cqi?
z|LhBdOv;)CBRi85PJ^{4#+fnIlM~7*duQOK^t3*+efJn@kjn_>C@|oGw$I=Hs?bDI
znJvtbh+#X&O)c8B!)6@;0X8$bRc@mSIw(Vw3~fjrEy8$VLv-mgmg`BFKKhFd+8iQ0
zE0`H|u-~{%Q4~Jhj7-Q2WG3lxiwt-YtOFH)ItgC<y3<5$T1Dhh<hs7N`^(opTC{J6
zdJ-!bv*Ta`iOu<&$65BKEo=;^?xrA{5*%kF!0RNLE(Vu{FDouhQ)H9F2-{iDz+sXz
zXM-COBY<F>jIqY<L2lwq>mBsIJ<bE=j*0B-B>{u51~%<1ik!5lk7(QFr9WP_h)`q-
z94nOCTG#p2b#>uDkrFv27M$T6F`F(u%14qm-++9OPBTo0?Vc*?TqyJxk+`eJ&KH4t
zL`q8)W4)o0I1cCJ5q0Ru0U}XByndrpR9j&Do!e39lIa%MMhwD+L~-j#x?gm!?#QGa
zw(Bb((ymG({l=-pwt#qE`0zae6N0bOkOYyiYunBj<oa>=7N~d~0peKeq+pntoAp(=
zV!hHXbL~e_b9EL5FQq@d>st#vS)E;Z;jxj*##;JMg;7q8WwG*}Hm4+Z>qNfI@<y%v
zsr8!t7~2h_o6Y9VY^zg|qGqrsNZL>7xVDkv>-+ZWkmebkHW~cu{8miDOKpl^@N5?|
z5O(XuSZn(>>kL9T^l+;~St+Serq9K9Ej-_AvBT<T*gmpg=D}=~hL*?(*sDM?{5Og<
z$p~6TQ}T8f1g6Pw**TZlqG!msy;1WrmO^C0Z4Cui>4+OgTbiL~ZTLaga%HNUWKbLH
z+f{@b1v4_OpyZN0j!HocIxIkIq1U5@P1eCjWTqNq_-!4tZ3OER;#Z49R`EN$P!lrP
zz;WU#32K|6M`cRvGrpLdG03nJwpkzob!$aDlYA-B(ejs3x1BzDq*J$D1F`OROg!j<
z9*55e1fUmKU-jE8+yLW+WtN`FXxME)*$mn?`>O#-E0ET2KvMSr@bZBj00th&sCPHf
zt^^-wtp~!Zcbh~L1L;PD`wOtBu&feOk=kW-h*S_U5FO`r<rG}xMm~~dLlUar7|{at
zwPZR9fOV(B^%8*n5`4~GeoT453qHtLazmr~6?=mxeBhNA9zUuHRY3$PS!qJBM*O1*
z^H)83;8OAKm}XL)hgIs=`=PD9D(ucWH^5V$%7Qv<|7jJx58PC~e8<WRW#7YBSfaD6
z6jvk_JB>8~<*q)_W`feKF?Lgh-177EFToR0xK;wKoevg}v)7lmnkiJjd4mp*s(3tS
z-a0+7Q=s=6;Jm-<{E`_fMF76HO@{|5ozu~r`RHtNip_sC=8`Sv2Q#@=hXpyV%FGp@
zR%wBXdIC>dyOT1ts5GS9es*B^R$0(D!wOO(8%uz}7p9Ax$0qgCG8pTkLFD|}dnPC%
zIR&Oiimd|6$8j2F`<27i7R>JJvkrJUxDY#<>|?mBTV4fZ3{(#wL@-qXlj3AE!FKAT
z>+66-P*pm<3<z35YxmkFU=tbPxstGsP)|SZAJyMhudyQnw_eWsQ0~ypXp(<kA(o7W
zz7&&(nFrr~@*fJ)fv5Q9?s?W)f~GKX=@Com&Q3T!U!j7K%g^S_+GjU74ZA60Ka&yY
zhT5rGB0r)5*+gm2-PdOop;<;3eyU>sz{4o2_6ydC#iffud@ppUE;H<shJ!;gj~iB(
z07;<nNiZTwy1NXA%k{YP#?+M(Q>8x$?%P_i?shv2;|i{KF;c*!fEmp7GA<NWd&9Q>
zEYzGOu0D=ojR&w}c!w)k5l{3RaT#>AAEyx5SIR+UC$N&(Nh3yjU&Zj^!(8&8DUlm>
zi_rB8xZH&+TE7W0D$FfoB7YF3tR1v=VHuWrG|-?&aN7DpoLI!H=Mj3Qv!{jBX%q}K
zEL1JJr$DIFYsaM@uKa))V8U0hu`rS=W13;ka*bJl77J7<fp_Kw%!jE=#7HfNo7j(|
zLq+9e0Y+V$H92Ad+d?@nu0o0uIIATSWHiSk6FdL?gll0<D(0x|h!B$I68BvY*%VJX
zUp`zzOgU!+sbOoXzVf*qA(5)t!XD?&5_?0oOGc<-`GAzN3Z!9c5ip}%#|8qe#N)Eo
z6tvE;24%4UB*p8-M=(GiFU64psgl@2!dmeDzy+QU4SvZ%i4PNQ$>9ed8r-9}<s8)X
z7P1sI0QZ_kQAKY>H$=|d@#Fw$)&yz}q(g#ar%2hx^3IlzTP7YI4k4)7;`wuURi_0D
z?%~2=C@7#CTj;En4jSetJT=ydDuvG|2KAjkN)57v9Bpq=;N&~$Hdr1xQp+<9)95iY
zxQ`2xr=Wly9zv};DjslZiakq~shZ>pa-2kfAzmH3;jHx|%rtU4_;&cVLkP%Eu6%DW
zItUKIpx|m?TnW~|WEhJkqwk)(+vmX`Kk+5tCFEhQj0jXKQ~j8nleZn88G_uPaWk`t
z^?x-ThSFhhK=I^_gKte!m1lq>h{|o71_Vu^O11r(PsQm}+qQ=pp4;RPJ9`ele%IVd
zsfNcDpp?5DjZb>~Y1yTy*bZY+WddCRhRK!34T=ybOA*kFvnv=@jf|_n<4y~5y&F~y
zjVp2LRgpD!7g0pN0pvo|+y;EQ^uFW>zcV!ldtfiJJ!W`P!wnL{AxOxT5fqQA)M1C4
z1NQB}{J68Vozx!eg>tG~0jFYyHh_2((ZTV_W+fL7+KZQdi?ZR@?ZsdvK7{i!Oh95$
z8f+m<4Rg8tuFbH3D#dXHj=#Ki6EWo?nNbcGCbt-v4Ju@E+-uSus#5L>@hH8tG%NeQ
z1U%y+Ze@0wCThe2pkNz$&%hsTcmbh?yd5@~a6^L$`mhBHzT8ec5J7#}hGiA8UAu8Q
zl;t^SKvWhjdxI=VP3sPo*oN7hr928@b{N7hA2QyPzDK`iV2_&fDmP=?1@da^by;!>
z(p?v~UvQy4MN3<W`@)fAFU8A^08dXH>u39%Xy!|J9Mr`>_QJoR5ij*!L(fcBC+%yw
zN@3|21`cwSatF|CB5cWqTOZnb|Jk|WN(kUmE_UU}Gu}i15uj+T>@fR2kBA^hQGXu4
z|1`l+e+i@-68~U$HYh*D1gS+n$m_)5AjoKlC!C4Nnq5CJq}bCciUEV`CA`SYKB)Ul
zKDLUi+yi0+`9}KlJkZz}>lcSOGvRGo&>l*D44y<cF6ggSETZigV<!4+>2S%z?YUr(
zJ}wScLZTmP&pFg0-eo}UV{JO~^aWoSd4gV=@eKHkC|V22Z72qXofskoIa}~(ejxcx
z#KUp%f4yq}MRe%*2I>%o;ZE>w7=?BU){f4Lg%R+q1|pt_R7c$ndhwqn<4q$DaE+?2
zhF!<^T><p9dOgTEIPF@cYK?_34jQR*a9|rD1${i03?#LQzFt^|Zd{fwf`joy8dUr>
zN#&(GGzXN^PR8DYTLtuMMZ|3s32j~a;batVD)%74cuhPzjprpWG}rHk2kvS$@|re~
zVPxVbj`HS$J32gAEIU$oz-6ZytpsD!LLQBHdN$$Z2O{Y3$W1W>B`Dvjf)WZ`uXdDv
z_pvDTE)i3Lle5Yiqgb3JIbB4M*k&1?kZFCXP^7SEHrjzHntaq;kLi651nv?Ca-s<*
z{GA#UhC1a}6E-nmlJk@-au1_u9}aie)*4oC&z<rI32_1#nO=fQ1qp?Y*#*Q;_=*d#
z*wz9S9FH+ir=)Vb=EwFMsgNs3Z)b%BP#RIk??L!Ud2=;Log?vURu#A>!2c^qwIgxM
zHX!4#z{|ATo*dn~yXj^>e0l)$P?uzLllwdIp?UEM%q|RM<2`}X(FPX#rl3RYUE-Yj
z@%0C{DB`r&ovzR%t1bu*gF}kJo{JaOcu(?_wbjIk09TXRa0)}5?RuTXHxpNt(o{li
zsTN_DAaq!484ApbAQ4o!q0^sf(1`(D4*2M7tckr;;94%%CW5o7c&~T*jVi+`Nz_TA
z>kbB_(yG+eO}Nk<a;=I)He$acYWoOxiJa0Z7xMdpZ-ABsf;dq+$7@q#3Kuz}iJ|0-
z<y9b8Ns~y{9eTI{p}}~_XlA9?u3CiUiV1M&oH2LQ;7D#c0x?q(*}8$*P$JoDxFwy5
z1Kl_ZuTZT<KbK@toAtQL!ZpKcN-N5jp+rKt`EQjwSBg8Tu)UNWZ7O5S(sabycCbJ7
zT(tdRO?q565&*{!;2p$FKxdTMs@xJd2)0rTALRo($S^&p_7TE<8<N+V!A#~}zf}cK
z8t^Jpi2G6zzeqW+#H9ueqDZD){4{_*7<Ubhceg8+)fL>J(=*`@E!9C_R}No0uvZZo
zHiQ48N<mav@<crr=_nvijD#5kf$CF6oU5gG3U!>Ko7JE|3nNWIQW*s7MB?rfVB>SL
z2h!{U%tib=xYV%wiY8CbUN6QtR~vM}G9a>P_UDcLMmKzXPiKEoaH(F5RVU$ND&PVZ
z`QQ=?mSS!H5~M@gxvJkKjDa0=hqAedC?GRPA9lsY^{yh~@tw{M9g3b_A_cBMp<k~C
ziCwHe#vsw98qZ!j49cL}K%X)0EII!?tqd90IvFW)TtM~vmI7B#s@nHDZ^3;UNSOoi
zmE#E%955D_HypBa-yw)XMX+UJ%E=~EW$~h8O{QK!4+(iHYSlaqo)>ZfkksYxl8yX?
zzrY!*aUq!$f-5RWO2lTXV)OxQOsU<AIESOZ^8EV{@z_(#=x`@$QTm%0jwt$zddz$|
z;5V!F-a+^n_XWM+#H;dIdv@OlqJ;!|Q%pZaIAe`cWZdwb`J7In61T*Cb|0f(LXRcA
z0?r(nNS!kV4)m>DN%rUd7nokn#5!#MW;V=<!*EG2pQzke;l!uU+X{y5&*E4{clD*`
z6L6rKll6*Y``LZUp&ct0yoc=(w$tW6;PE?R&tn6OV7~Fd#@5Bv{!v&{i+hz15l5%M
z>dM~$zy5Yb&|}E1SK=$w26Zm3S|g>}TQS6dRTkj&6&UsKCXz}kDKLZ|=1vFX496%N
z^m_AAJh;=S0NUpVi755~HV2!%&kC|clG!qyK^C;=?81aqqbRK;F5Hc`4+i?_T97pM
z>z0nZi8O7j7_6)-f0!$r*1-z!2q3kw2IIeUn~<9%M%&`8M9>IEJi+x$<6wmhoCPot
z<HoL-GEZzrR1|SpHe?ztJ+ve%KOLc%VmsZO(=fca^7$(8V}#%|LcJQAr)ylN<8p*U
z5sBVv2L7RgS{d&F@SFn0#5sYEh=M63@y#I50y4qP5EB!>M%&2)c6b#wln6JH2kWH(
z-)ZS_WuAN^D6;mRYcq_z^2VwID4JaXq^-YKzI$!ZM&i0MY_2;_l7xDv3^A^K4<*q#
zvdXf~<P=SvMDOnAEQ$Zk<@7U9l-n{8a1;z8_o>9s%>{b@8@l-?Y;pLnZu87i=EnQW
zN|kDVe60!&KMubcvU`v$e8r?fSnAcn&o_wvjkMd%Di@NstV(v}K#b)cd<Z?-OT2)Q
z5Fn;sJ@x0x&{78}GY22Jqx!J<)*Z1{+SR^?r<ZB9t}Px{gn6~^{Sk=WS?r<(GNl}k
zr2sOep=x7mxi>vE-&6WRS>v>oO-wA1u_Y9l&Lt{%TWhonvbB-Bb_c)d@G8x+SZKY>
zl<Qu^GX&V3Gf;C3lHgc;rqU#!9484+@hh-EOgLVuN?US^mw%cgNmFwyQSmwE>B=)3
z+~c`BR;cF_c7BD^Fp`cBcj)n8O@RKT7IZh{F%7_2Wf2lBnm=6Al7tpICl@wBrIYbC
z3}Ow-aiJwkWI%ocNtuZG-KV<;>fqJT)Xjr;wF!J(x$YvNAPv4SKQ&pDH?KytrfHcA
zK(yv@v!C`Q!8)|1UVQ>$B_&O(FD>gSlF~o5li}Aty@LJe-IBEIwXOKmbYeLm5<^Qt
zFSalb#dhqg!c;|mH~#1d6W3)E!iDq)PaM3V-Q|(k@O$lKZ!M^IYE^G-!7-f|Y6Rp&
zCb0oKJm}g+3c`x47rhGgud%J)@?K%C{aagkJDzqF<k~kzkO|J#L$P=!8(r+$H6_^H
ziprAn$M_5=Es9}?NJfuKf;UVoE&X!{ibia^a|lRA&BywngK3ldyP%zERr|XI;f!9?
zf3AU$P3@{+2>PvWdLY6Xw2W(jGkolH$FP06C4X;u5gw^Z-Vjr|=v2v;o>`)^O`B$}
zDO9Fb@i&12LXIZT!c^L&W&V$hcVqOg*WuQ)-J-vxAD1*iYQ{`+*MNt|Rdd&@dbt~z
z@1B96O(U_`s9@zKIZkzcyRo&OX<JcGKKr*=T*b`2bS;G-EGP#z1V}}9gd1T97h%Bv
z22L2CLfb8XqSLxDgM^~<va(<t<XDg3<3<WHjbvln=G!oghPTo%tbs?>lY+O6wiU_2
z^Qd#CmS3YhIv%9L`DwFCEibP2po)J3oO)u4e`AmWehNyUjMM<UG^RU!3$!-&CBWLh
zxn6<*M?`bgN}|T|7n{&zceiD0dP{yfo<xnNx?&uqHFMIr|9~fT(s`|eNxTxAGMbLH
ze`-B?$!92Vhds){NeYit+N=$ld7Ro|tEJIPZr96l-6q@SifHJJry!GVWe=Muia!#+
zU-_e5XN4zxmbJ239|x`4@Aqv+g%9VS_dP#v3n;dE{y)rOV2%Ajd>@bFSJih^ziQb0
zp8wRG`n|tDQ1yJgZhp)$Ev#0Q4X|7qb@2vY{jq;vyz1`g>Cnsa`O|Tx*ZuObet4F_
z_i@tl>*MUn&+UEkY5B!`=mkm7&NtE{XUV7g1Mu>uy<fgBHELb+p6^#Ze|9W$)f-b{
zD*3!E8ooe5Svu>L*-!6H$D(~4e*L)U>3RR)lbVfgwtl!dy$M-)TC<(>Q=XraS6@I|
zwc{-SIQ?GKXZ=22^`sQ|P*2T>Xk`UwQ`;PS4x8UgvqO!G=jM^{c9<jZxeVSWsISlL
zhMy1Rdj7np7SwMAZfngP{#ac8I-o~?@aB+p1`?@E_Vb}a*_U;t`)&H+D4OV*AE#-d
z+cdvgU-24aa&YyoYT1dKzSn^F?OEw{>S4xLaWzL34KnH|e$ghkn0UD0L{6;|enE?;
zeVngabw~AAIV0+9*y1HqZnh;mZFy|PqJ@7p$XJdK)RWbE<5Dai*ef_<05a&W&=SnR
zud#@Anp;#<7Z1be0<i8C6#2cw=zSkP6)R6_4^SO99$&^_9!J9*5I}r)4es@B8ITxX
zZGze9H@sQ;{VfVS3AK&}Ecx$B(zo9SEE}w=OV;*%vJoph0{C)3#&f)(!i-q`3{@<1
z{2+`$zXdV>N$=Z{J}WC0sz$8nvwBrd#Ca;Pytgl1+q-?PUF%-eqQ}|uJv+Bz$E)G8
zY0`0>e&5sUOMShQ(<h!?WNzi`F|{AqDu;UoaCb^aWk9=AVJf<hr%HL#Ij<g~bxYbU
z9~gF5**|#2Z23N_{a(PYeg{q~2WdLy`?A!AaO=pi>fHXW#V%!%W8DmTuEowb<5?W~
zNZ;yZJbY_-8zr|-m>!n<7NA$VOJ8W=3t`5x#)pfW86d}s$L*&M4-KAe+2SW+hk7(#
zF4{M(JitTA8&Kw@l;a8VWB!m_HAAl!IDOuiq18f<nZw>U$C3!xPyHfHYwJaYd+R%t
zfE;TG9H4Yrse3TApSw<S+nE$^gY4Il=l;X`@r6E(gu<=`EfKMWe-3augy7fN0HZFC
z#?#*Xf*V86m+Z>Bzw_c6YyB~^lz$t%o=USmM16Dj?)g0-xD@~6S!R)aHjH>eIOoq3
zxI3zkVIldXjrXEB-$VOu>+QRbkMP%+h2CAin&08PjB}`CE{!!<CvSt|cw$3#r=J;9
zUT$<QC+(x|eS7L!Q;T-;GtK0v@mhXF_TiWU?tah$WKS;YxzRb`>x=$-!qsm3^tGct
z_IQu|X*zBnGV<}N=S|~malx+o5BP=Rk_?QAt+A7{qltmd=aHSEB@8P81HtDv0RaIk
zCo4PqKRENh@NeHfljud<oyC-#4V+B~{sulV0|r2ZfL=&|fRTXS$N&)X@_q{c9ny>1
z**gD+v?(nEEdv1?AX~+M2?6B(RSBkl7e+v@>|t+0Kre4#W<o$p!1!0;@&=A3fV>$0
zIhS6>#Mr_>(9WGe3ji?yD$Ys3$i%=vp!1iw5TIayyb}S-zfTZzv~#ilkIMXA$Y1E^
zDS(Y$2~f17fvuDMXJJMj|G*Li&W<i7|HOm<Qo<&#7DgtDVuGLGzuKy3;$-LIXk_9<
z@ToUNnEz@TJ0Sk4-%m|Ro7kE;n-g&SyIP_a*3Kr51oWcT0L==U7y(|K^O@<t1Q`j~
zSvc7~^ZJ*`+%qrKz1-16nrlv#7I`*#c;<P2K$H9+K}{fpt_cnX0!~5}&W<DiM%}0t
zFceOLg}O!3(3K+a4>g;)#wH~QtY@r8!aqB`MG;bUgWeiP$3T~NCa%{-V<$`Y@&uvl
zcyjvF_3OQRomEArrkbnfcb1Y61)(r;Bvf2)VHs+P-}BoNAF5#$p)fX|#bYIq2Mup(
zT&bvFDaDVE;{_}pQ#r!HFq`_PS@OeV?@Qf`*atOeMtV74W5c=~JnzuB<D<HoBja<1
zX6m99->>VGi6v9%uf|1;nCtAdI&XuG5~$Fev$1imkJyPNvYFgj$z#m5?_Zih=X1P`
zJ@pQ1)NP&^3B8%(#lM&8lXk+Csfb&TjQSGXA};h{NJbgs+L@orPJ|AH4oy%{kHU~?
zNRURcOb53fQs)ag`23knbmYn_Ow&#JA}Qqne+INl#3-5Ou_L`dKT%4er&x!!>?oqC
z8A6jN2W7DL!kHvbv5x~}Ko;_17!s@^mVXYJAnwv&;NHYd{|8AH;epQl+g6mYF^lPD
z?I<QMSx+wL<`o2cB8(TQ#y9dbn;nEe1XTJNv8|$k^oqyYA3~O4ELrP9=kL6OhF_7{
zY#>J!zYoPdPFQO(HK;YyzYH{(h4gx?Ytq*l7E)(RLy<P9|D<BwGa86sw@$%QOrv2_
zrB;EycvA-Do0aD5vo0Q}D7Xt%^SZ+q)SO&u@x<83UvE4SUHvg!lLtqq*F9_Q>pF=x
zJZY6e&Q64MW}BWR;;oyokY{8m3&Q4kcz>L>A)v||n3iIn`bH<iBEk}0LynvA?W1Z~
z&+BP(S+pl@c=`hQY{S;!V!S894m6<s@&{zIHD}x$@=MZ)V_{FG9yynVSb~s(<BCxK
zR8#iig-Q=M@LPB5<H!TNRt_7_GLr@5C=<`B2L5=GVnet|!ajm4Wz|}}3-w2{?R!A^
z?ja&yc!u&pfp8Z`P+PXC(WyYgfMGEO`uI=j-!xfbImOd!_1#iYMz9*l4)ZE`0TDuq
zw7W|*I>dt)^&5jW>asyA^r?9#>GN|gHvV}PWV0`h&s9=<mhEsQ#bf-qwuehH>nJQ}
zb;Lx5n_ntu?K*5DU!NT+bgCzj)<To54)X11dC?O6iqc}VUR1OE7U^K&$(?n`HV7;9
zg{>~&=Ed0@qw?0?*TjuFxpXt~Y1zMEox#V7#zAFqyQE&)iuojrN^i;Do$8uZQZHpm
zDw;>2=>un9iYo<aMr7|wvvRd@wSlVACkQzeN~er^S@Aq%Pi=`-Q!i&(Yzhgokc1En
z3VtIAONuk{=Mu-UhI4^;39J0Zlpd2Z)K9?{5t}$nwTFvXj%aE0P&Wml7T}enA}Ccj
zx@J^8ydkpWJ*>T~?S`dMMmL|zIUdEN_Tv@YrJ#FO<D}eK?L=j&tGesb@{H#!f6<ah
zQ5>c%(zTe=-0+=pQq`il(RV-8Y>AJNh@M;Go=22io~7O`yBb$9eOQ#u&YxU-f8+kA
z6BnXO*?d6WYbz-=Q-eR{V<a<`LM_Sn(=SsCG%5v;Qp;#z`I-n}O#DiiCJ49OberW8
z2&*1iS(lw*p=uef1|n$Gzw*>M^H)OICQa|HCM=&&CEtgetJaTLhZ@xn=eaE1>MqyR
zA9E9GlFb`V=B=BVq`XpSXLa@0SIJDWnnl+|^bC4Txs&lU)$go&In-ErzIbnx44t0L
z#6vF1diEX*Iptwo0migDJxCi-Yz#w|4cx~m@DI&`lmX!j`=IA`50!!crZ7rpOr>LC
zn};9M)htrRxx&JTRwV`n%xM{=`uTM%2R(B5B>Qf+mcu){n=t#E+`I)BwPoANEn5}3
zP@#chW17IY0%Vm;X%IaUV8|HFenL^SF=GMYU=EU78hmO7eL=7-i>ZmCR^>|%DFTY1
z3r9GpiTT5+4pIb>B@ts8B`H-gwqi-ex=It0^_xU<g7KrvcvE|dRXCN*k-M4JQ5bZ9
zfi-WPxakP>8BCqC`enIFELD2c_|_3)Ml8GOPBj$aFwWG9d9$DL!Xw4^FLSnNJL6%n
zX0O)vk+zTnC}FOvx3_shJ_z)Yr-xzh_!XCvDcGuwHO44M$P;T}Y00s#BFOY7IJZHP
zy&?w(bXHBGv7T00p{LiU#H5gI(`G?xw(DE&8?o$~_$*QH^WJtZ_IDK2>$jro1QE&m
zxEKj@@s|}ohd-ig7MBpb-^*Hl<z3AV%vGm+UvKHrAf5a}_+~j;cvib!YydG=i)3+~
zz`?|mB<QV7>r%PhtwzDOUnsWr^>%?v?RC#PVc>{hfHc-Cjt``8IR2H5q03r#z?m52
zGVlK5W`1wr=4x0k_UK*0Z%yy?>g?-q2L)CPTvH@lv~<CIp+&cagXIofQaU{)$VZpA
zxKnSao-?eZa1xBxiuPV5AIHJMK;o94_6Aakx#wMpa#^x#b?LYL1hOc<JLOpXS1y;l
zt}@YrWBwb!i&bBrY#Kb$S3SSy^bBBF-^WGUbQ26^!87vCKY~xX{SMU9GWvl{NKC0H
zcnUr%xYG|VDRKtB7B+=WJt*NINK<n645dI_9X>5gizjGgfs3a|ijT5B=z4=xm5*q&
zhBbR*kYty9E~5EX=tcp7z`1#v_t?F7xz;MfIJk$ku|>&kcoiuYQD1K>{B~=yP~&l{
zc^Hr%ECRg)#?L8|SwNp}gng5B+$29*#@oo=dVAaMLciX2(8gOc%_pR(H9g_iHJvA<
zD7tx+vuu!pPmxU#6LH0em!;l`Q<i6}c}B_+;weX(6ZRWRcC;u~LfXDGAwOC|S{gI=
z1p51gn4|^PUCQsVwXgLndHPjNT(ko7sC#I){Fwtq9G!T8*Fl=)=iM+_e$CM$LjR@9
z+|zZ~7OhiVgEW;St}&ArTBxXrnSQ$b*8Xc1J~}^g>*uQ4Ma9G7E7t=MbgrAk{M@~)
z0@fCsUdeG|aO2=Tzo(+4WtnPuDwh;|Z1hY5iB&y<EJH82EdwEhAtAyWjjqh3_*KqF
z<bB9V<lJ&$*nCY%ix^b8fRByY0#24VYUwmJ`7bPQ<8A1vlUY<bx=QReFK><20i54o
ze|g;T4Sn^>-`^i3t@yf%v-bKn>_@RW{rgHvYJ40PUdGYIGtYWFV1J+8$q_~r@hiG>
ziM4k9#bPkqAB7;cw3rnWgG`KzIGU{M=;}o(jdO?RrmY3JO97U;O`t&DI)Oha0;1lW
zyg%;w4V5_qVbMf49opBW8;Wgz)&07vK*gB-s1A>O)4o$$p3d$<s7UvtqYFngCr>w=
zx5qZxpo~|)JCjcz*kw|q(Kys+oFa*IV(aZA1-i9TIZPTwD2zC1Cd~iyLjE*xY0nL}
zDH9E9O<R2@nIut8tSPx?5u>Xpw>7}1-X4qS9F>fpY%1mStY`sF?`9px#?71R%~YzL
zyhk9qgKaM9CBBz+AS)@il=zh7lq7w`gGmTy8HtpMD1@9b@m1yU`eaI_HiC~lmHJ>x
za)ruH1)<k23DsWk#qF8D4MwlF;!Wy>%zOF|nHyzhK)Y!CEJ-q%0`<#%#~j<3<}QJ%
z_j1BJ9pADd*`x*5oVSE$O_5hdwY)41)<I#yeVo|V2vPPSD`W`_7fx}L#31hv<i=8m
zvk^~{sOZ*&d4_J2c9!y@-#Xm<c=aVksa=Qb>JtNr5QPH*^%D6|yL>~NgaiA8yb%~T
zCvRM-WmP--Eml@0SHG}rCMZNb%j59BV;Vb9WMk_i0T}@S>p(lfM5>%FgzLF7l#F*W
zbZQRg_J;?f$gU?~|ISN|ptyDfEx&eEACWEiExR5sNS@_PBqR>(5j8<b{T)SyJ29q_
z`M!|&<bCQj+MzL+S0pFYWTDoFT_(`l*=n?Tc>-8NTzNm-=}5Lkdb{sXO8!@7msYUF
zY+X1_3&GZ;@VShT-CXo@exo959SairBbI?n*Eu5O5_wIs+N*1!*lPilyU`mSXz|z1
z@8y}cIbl7&C>ENLT7W}hS`CO{LG}(tREQF+-GqcJ9r_0czX$A+h{6z;q`wa&=hI$y
zxU`Ja#V79cg?(7Lg+KjVgf1!G?_z$KR0?yw<gRsCk2xCdeA%Cv2hUMBazc{+)_quD
z7uaXC*+4bs*W|FAdBS{D;=J({>aFhZM;BWTdTD{dNJ)-0Y|+r*kboB-L@0@4`2<E4
zyy!|tN_?%bv`l__PZqRe=VUJZwCQc$y0)NJ=koKC7P239+tH@^8{__--mGO0R-X*^
z820$kjl<adxdkt`tw&TpRHQ*2P0XuV{OYYz9rK>)OKRL)8fl%>ZpyP;;-<rwa{6%5
z^!dd5_Kc4POtc>}OeYtI$nM`qv!5GMrTiRRFX!Q3)XLmugcx^+vU$7?XPSJ9ZLzsZ
z410T-Hyf%yK90Cch9i4~-!wT-+lY3Jl*D~0NF~Wc%MybN4r=*4OR!v1T-49>@SI)c
z-x;A5e8nZBVDn#y?NW((K?+)WDj4^xh+P_W%fmcXhtG^VEtW{cLyn(pxp_#s;JZm%
zeO#;~F%s(Yi^|d0TWWfx7m+i>I-Qm_TMlpJC@_}!&}nzE@kI7StwX!R^gM4y;xY8N
zXeKLUPAIyO_4w2&x<AIvcE?A+5xQK!S^_EsyH!P=CCRXi^(j{H+a!|*pmheao1iO{
z+>D#uik)v?72j;p?ULP_oXLNhtjW$iuCWQV*s#vk2fQJW1p*dm7a%u^<TI=u#Z#QQ
z5Z=u8he=SaT5WThOxNN5IYnwEah5|L(G<CSfy8dNg~nbHTB*}+{QjF%YFUz;DwV!w
zL%Y4xQ9IXk76;%?8_G}T4@*2as?p`q^G%S=Y%(6DnJ9$c@n88f#sQruy2}k*bIh-8
zOlVPLbS%u3`jJqbC@YBpf(QB|fHy!bk*l$J?N4ePgOC50o##NUJq3>J*S%*sKD4J+
ze(IAi?eI#^s$Abs@O~r2jQ`n{>P;vJ5kdVbS_EgrA-MJ@vg;e)Ql*yN-Y`Bo=X=>O
zI%U?M84MRO9b#LW2l34Sx41ukAHzaU;<SAYkz2NitAcI@6<{4^`f}>!gySPhD^5{M
zgcHs`yLI-tI3t-;6S-CfpzuWN>r&(Hw29cw@mFK5_7&+Te`>KA5U=_^0#%sgG<eQM
zP8vT{hEEo*UZZ>+b~Bg?K}~@4aU&`#!Wfly#O(IB<`}y)p>sq&H9%|&1kAzdiAhSN
zV)|-vGiPC($D-#6<RyFKsrcOjJ7&2cIa}luVZLY|*8@L|CD^*)D6WR<7Ec4lV@?n(
z%(@KhgfGNuaqlVFn2h)hcQHJU%jm0OtQQY1<z5~&ABM#8P0}Q}N1>$XQ#HvRUGt#p
ztWl$au3Y~<%^P4<$uMUuDbtQsBt^ieL<*vVR@b8UXl=nG!YkKwyBfMl0}*G$mq2t%
z#Jx3g>lpj#_c_oJ1!&F)j~HtrIiC|I3L(jhS$D-6I3uiQp6Xm0{%YtS5S+#^ONWU*
zg`v(NFp4qMBG1WQH&@r=wCAY%ZJE5(K4Pakx(Tw9E38SZ_|og3_{zpp{P~4ay_G3}
zLXj0h1$UrVXe2Hdw{nyIWnkr_rItpzxy?;3%DkRcftHswp}7U=;E8-MWqoq(u2{TO
zeDa%2$6Hzz2vqGDuS5Gri?#;rkBIH;Os004lR?ion#y=-ES$A-+CMhTieAKXs!0O<
z=YrQ{pfP^ZZ@hPtevb)<&*9;_J-m3DL`)ZJg;{_d<h`-c6P7e74;Sl2V&^l*zMyJd
z{PRQ(LE9+YE*#;(efzyJ!aMxRCN0${tF~aDZo+4^Xo(C{6u}8`br^dT&I9bnXxBc&
znRM|Dq6EBds$7GlqvjZ?-CoP1rWS*mKHYHV>5}e~VRp=m5eb|{<E%3FYzkIBiP*(h
zxWz3q35bRyXuV?aix*g<_rypB>U1#b*%UlfazR|pR&Xn0M)7-&S8xaB2yxb^v9K7N
z{s?R{OPXB75PL=Pmk>=qq?!GY9`K!4npO?qUv1l3!0cdeYDnD<eR|Z}o=Dxg9*BQ5
zdz)aM%R#U+w&`WAi~Q+-_bvioxA{-kZ;u@?zDa^>4}DJ^?k$pIel8+=W&!0zzOM6+
z)VMaI_f`hR0P{W$_@fPU6x-_u^$b+vR|_=73U_$)g?~Vw<F$mtSG6~1cRLnj3*$Q5
zpAV|E#-G^*`Yp=89n75_Ru-0{ZDN=F-JS?L29|?t`w3+0%XNzXFKBnAUORAHbbH}m
z16YJ)h!;ZOCdk-pO<+hwwA&!D?QJ60ZFT|QT!sZ0NWpV<fff4gXqZyu>vn%j;GQqF
zHJG|ieHC6oZ;OU29m4}p5C*Z3x&rxn7J-`}x?gIgdSwxnp;vAaBCkdQQ?;)R8G{`p
zTS1y(SDF_`TcB4?gK0C2o>L50v@LEY8379=!eW1;*H;SZV}~wf&?ok7tOH@Ibi0AK
zsNDiTOV__hC-$!LXFUk<o<vq}2v6q2*gpu7$2Xh?-_ZcBP;=R<08DL%ppKtRe&Sz+
z$x8Jw2tgRHGxA_e$}f}*s+|bbgH~@J+?4{Ssnf6X7XkSK1J(55*az|<1q}P8m-#0H
z-}LYi<c<aK9oU3RA1?XC(l#Y<L%O~x>bF%e=5+mbe+!TgnO;<h>sEijimJROaNo%E
zZ$aGAa7aP$k>zRh6a2%#rO!b{WElFOLqPCR7<Bmsx`$xX3G{*>3yhwFG#F%i)i*rO
zfky87FfDHxFLr?Gqwv4{6obVq8h8g0{g~J%27j9fMg|Gp8?gr-2u=4^M}v!If0joL
z#bi+L^+9JS1-V3LkUt%RWb5-Mwx70#f<C6-zU=t+W=p@ZI6ZlF%iq%tafM;&BBTfU
z8)^i7rXw}=$u>}zM`mjrmdD9?Yd#nk&y$3|8CYY}C7U$21K|f2*E9=(P?)Wb%GP9X
zHI?&d;8a#%rxT;I<kPjRfcO)?re$2oCTN+!G3J7Y7(1AYIC30KZV*mF+%yRySOj4m
zG)i1ZuwgiRZ!F3^Y`9h63NTVoG$!yxWFDSmd6vKV8wD4HH%KQ)KA5|GpqPJ1rzU8x
zHqfP^Jv2k+>;}^I;Odn547fR2DF`mdBq9Gzpf(&FB$lQ>Vl4((e$Qx8HNOl2h&e5-
z?jy~`o8J!MpLMXeaq^EI;H21ej{oh~{&ceb<JV?kVEV_?%=y3Fv5cQC<iC8<^#7MX
z_CMXPItk;pK@3PDPahE)#gXA*pc16P%0)O|d`cU?0zJkNp&Mb<Z(nimeOD}lO&fUL
zs)!HU-}uIEt4-*E*kIuhV&KfS&7>D3aD2nWm3*Kt*09yRyDpuj2K{5*M#I5!gQ224
za6bqkmDRe|tKKOV5e6usMV~S15~QQXiMs0X^c_+5SXEp_C+KIut}fS~H5n)gmMa{o
zqrLWv(Z`bKjc<bZJ<M366JIcXVZmi}<d)AhhFW4;hD?2Mk0TnMK;CVFs~n^hT1bkh
za79Xo{HE~P_a%G}<V2U%AkJj|`juFTkQX{9JW|M*YGJx4hgs?{o>^)q;e|oCSkPxS
zRiQ?thEwTYWZ^0Q>IVSt6738%OTl89&LtIdib?UFe9`Po@6tRh>Bn&IpzN01dhroE
z#0IG%|G;#h?~I?_dH;3OV5a8n3!F((jQGE8_Ln98Wi)1H)_-iq`04on$A|v6=l+vh
z5H@i#a<l-vv%~Q(pZO;wYhVN54rHV?RWwAXg-t9CR9%z+F8zO}iyGKiSbGpq{GCMb
znMV0{qP2k;z<1B|Z%M(w*#%lg1||jqS{61Y0!DUDW&q2;%=9moLBiR<+QLY{*325P
zgxX){2{;*j(iEIb9DhYW>-QO_Wdbzi)2lCJU@vZBVP+0sG63291t~e3*r*b4{C)ms
zMEsw~XLA7E(S(WMlR@}TM&Xk}`QO_3J3ALc=fCI^WdLXKsj0tEK?5g~zsQ*XpJpr^
zot%Zt4IKYbfV9EC;*3mx6EOc>-2{Ib<nJp+#1=qWSlF5o(5qS43fMYX`~&<|vYLgl
zv$+$1rD10LY{mb*GqW-LE1iv*jo|<H0Z>PP)c-q&Pn4DYlgavfXJh^6n4ROl%4Gv|
zFLvh7zVv_ZY|Nj05uhB#f6o3}j*0!h@?aof0W_W!&?i3Y^U3vmvQGd6@cD~;0+2{{
zDz+A%Ob)^4z2-j+_rJUGC(HGB@07AI{?yYa5vKTW8q4LA^!g7jiSa*qGI>WkV;3U;
zdqiPmVBu&-z(~i)N(X2ng}Jk{Jr_NIkOQD*jt2JT7Di5Vc8+G0e|L2u0Q=``VP`A+
zN#;=qb1^Y6F)?s3aWF74aj>vZGcb`eFi`$yq5s7M{zJ|Q836jeo!MU|{;LW9qUQdK
z^>TMKF@<3uU}S+|`1eKtFbgv)fhob?7#kZK2jC|Cxe?g@3uEQvU;wo7e_(8Y3-7;U
zfY_&z{-+!pK;!=nV`F1t0T}PUV+;&T089LLjFt7XgZ@v91z_I)fpN0_&$_U&a<T(D
z=6{!CWB=cBY#i+Wk)N}p0pRL({EHV<vhXzd)Ya!rLeb6+VDwL&|9yc;*qQ=t`&YmC
an+Y^<bpA`bY;2rN%rK;+B69z4Zd?FK!TBNp

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..662647f3cdbc8cee6e7eec0dbe4998665c6f9e87
GIT binary patch
literal 76444
zcmV)pK%2iMP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lz6ypkO@*RME3XK;_jPf1e)
zK?4CYaQn`J3<3u>V4OYZWMJptXR~UpRn+cRJniRpqx(IqXHz7LRH;}WtJ2s0{@=f)
z_y0?I-@pFzYx|dN|ITf{&acn^{_{V5{rmrG|N5{0@0Py)`}_a?xA*`3x9$J<Ki@yt
zzy9wn?O*@<*S~xvd!+yW_v1?a?tA`fZT~KN`g(np{CzaFf4=_H*MEE*@&Ea+U;p9n
z+v$@$ztZ*Hk5bF|?q0r2ZpWFv{{Gtj{eSt}{<ksa-~Y?@@BUW*m%snF?SK9IY8j8S
zEdBfRS(fj9T_X52AG_tk#i1JrzjWKL!HVeR?RBSm_4hiW6WYIYIx|MH|DySaysu~b
zK90ZUefe|V*M8j>=Ivh=)|&k|dV%mux0=7xts4lxbj#<*XdwL3Ej5nj>__`g`Jc}3
z{BZX3KfwPzeJl=y_2SBTey4gyHxhp7cD(<4>juIv-Fo^M4TN91)q|ti4zT@)J5b)j
zt3SK}>Cbndy#Jft|Bc0g@XO-zZvTyLApFv8KR!kSVcjiX<vtn-zjQm_ABh(7pY8vt
z9eA&6Pe(f6f1Txf|LYz2+W&k9a_`@*O@f?+Ul#ZN8tu1kApFv;Tpy!>@JqMcKSl%L
zmu@M4$0xvBf6D#00Be6OfxiBM^M8}bzf0rv{tivw3vd3?<(LlcX#Dc?c7E47PYQ%z
zy4Cu9)sXjW{~@>2TUcEWXZ;_L_o<|h#ewk4;?lvzp&JOlbldC4XdtY+UHkWWP2wKy
zb*JO_E>{S9H2;wMZ#h*Tj`}~K?DTS97uvt+i(D7=#c5&BU(D~b%~Iamze%R=GIv7z
zm%ZXZ#`S9&=70Xk=kN33#Q!7OecVAv$dmH$Z=7X$e_Y>ZKE3(h-$(dC4fvC3*3-Bg
z(-a}Cl+&K=vmM<;Sav&_-E5+p2+MA#f1;wB2+MA1_Zw043(6mC!gYO@-#6h;UeF=V
z_S*u3vR>i)U`!X=cRv!=-QFLETQ9WNo!;M}eCtKRy4x`y6L0+i^HV?HFY2${|C4Xi
z_=w+`NWywy@AEJ|CR0CAmK}2{_RrBVDC>@Io$I=d7?gF#y1Vd>j-vd*UgWntKYrhf
zKher^tM+}FW-7{hiQR92Q%6zO9nWN+!KtGt>yB5m``pw~lx4@VUmt4>${&3j-a6=6
z+ErJ(@n<)b_c!=1=7X|cBEI-jM^V-t+y4346lLA<z4ZHsEGX-a$N3?9gYqZ4an$cz
ze%*~fy0Kj8<Leoe<r3>SA-5$4W!*7dA0N=5tUH!6ce2*HL+y7NEW#h`!7!{{zwg1H
zd@E|-Z(mNf*NYox;?|3Vb+>bt5#CyMXfU2dr=YAmzVFuePgzj@fd4JMNBy1uf1)Y1
ze0_X7gR)-YI1~3Jin8w5`iGbg%DUsRe~9^@tUI3d<5L!tKiQ4<ZL<8n8~?x^N0+es
zmFMT{b0z<ldE1=-HfH}mMad_d&-`7x-O@hi{r`<=Pv63~K6Ji6;BSHRmf~@V{&)XF
z%S(GZ&-^uRR9D}}@U_4H=lJUt;#-i9ixvn`XwH38tmRfTZ*^F)%VCC!%}D%#+b;6B
z``C4LP=>-WDAA3Sgh7t+>+zr#&3CKfK5mpfIb}~bN|^>4cDTcC*xQ}rhLJ(A+xJnX
z$2cWVj~PoJlrfv_Mwy;7ZuM`<^c+xjaiSS3UE#umNOA+OQLG&g_IA-^s<D$V6)1yM
zwA>WfV+KY1BcY4I#W=cuw~uxTW))-TKCQqg{enGeP~M__5Kb){1RKcLn9R<5X(YC@
z2!oq%LJ||4a!%vC|7|l;jFilvd`@e!v-+mQ;Uh)o##*^;Q;Wm;^&<B}!v=+iq5Dzo
zhYqh%HY0IZ*Zu~D!@85xD0}*#@XVVI@Yd~*XbtOlj7)oZj4X;)U<dO}u`_We#mKb8
z$H;aJd)H2r(tL3s839L%%^2DaW^dp8cRO<LcF_WgGpgzAc0YA*N(}5rtm-gN6fGbd
zqpEhk<4jcz&UOs$N2>DFbsV4SCu=5^Y5)EFlo;Du+5u~E+Z&|co5X!@I4*_5HXMy2
z=8M9Xtv0&=bdsHfOwOxK);FAk5JwH0PI0su$rhKz{GjYwfbV(|^PBB*ilJTByeVDN
z_kB*^?W0ZBH*9hW9{7%?V10A3v5WH!JGhJULFrn6@9A#S-axW7?b8nU7VbL#J`mYo
z@rv)!dM~hDdhh%s4hoo1eZ$@aZh#-nLE#2e+oLz3a2G55R+sqi$9GW3e>%HD?p5EB
zW@2yqAayOFS-a^m_A0iJdj8$aZo{(U;BUsD1S7^4v}0PhF}#JSa|OpJTDi;Rc1%k*
zhPM!P)mmJ(zg>gEWfyR`JM%%Z>2+;?0gt<uU7W|EYS1<4qGtoC`lE673RoP%uNe12
zJt^RxBwc~rY9Z_jxYx95S0DzZ=sDRR919<RZG#jmcZODNxLX_sB^K`dtlEZRt@o;(
zR~hUJ<tT%Dp&Vs!uWH%uq-?%hn^WjnJ@p*tULh;8ys=%6@zYqo`HQw$Gv?w)PZBVL
zcSYab4Bi#AjBk?w%s7ZSrr~T05tzZG5P{iR+>FHcI>cWB+p^}7z_z5_NY13B&F~xM
zHb`C1aV905!vrpc7MH-Kqz&<Zvj@e5oKs21BY{=>G$CizKFtWHDs;O9_UzM){8WWl
zOkh}uMIXc-#51ykMWF%i&Z2thjQC89q6ayT>ZKX^+y<rTLB^wcX+}d6wYDB(@8O&B
zp3Vl6aj0I?e2gFUoaQr*Pd%sU*y*V*FE@~E@N=4uv7?5_+`Z)w>Av1U0dM++8%jMn
z8EC<|9-PcjgKg}Cvw>oq6&^Dv_9hQf(}S9|iyq^wIHvj7$*9LPpMt@62!?)P<$aou
zos8P2`8X?j%*R@s%83`JcFpF*8IVQ^rF>90n-dF{M(Jw$cu?bE9wZyPX*Q=VTo=QB
zV&QF?k1xDQ!|f+l-lqBZ!X<lQ9XE=<>>U@|TJ_QCr#0~%=(v<t$z9w6jI#4LLq1ff
zoqj3Uj8OCxUnBKS+!6*M=^?(zik6@8BF!6@hCw>`3}2tbFm4fp!e996D2KN<$(vvi
z?lDz*C~g{q!Y%VF2rNfVz#eAp7%mevi%WJfs98IPi$RrW?$G*cmUh&;zqOLi9U6R<
zbnej3D_g$6r2V4yU8${hXx3HAYKL}Rp{(NiGTP(|RN$H<b$Y`BB$sig8Ez$V1}bgc
zr|I|tc3B@fl+(KF{6IOaxP^BpqwhA)50uTiQ**;TXi&IwP%Z1u7DAu+)|-A<B%phR
z7GExH8q`6BM-{&)4FY!!>R`F1xsCN~gM`Cf?ccd$(Cf;@mJK0M-Ccnz6xG|Hm~<@C
zZE?FA6i&?awQ_1+e#8fb^RiRE8HvZKVDjfQIopiFVQeExh;BdiMuFztp;ncU-L6EH
zklfIiiqv6T(*|WsZ*!7&0@I)&l|yrbLR1d4e5N6^v&;BF;sz#6SGIr-ZKiZh#kHBz
z#VCI<wn4&Nps19P<gTa;3Qs@uloEm*T1jcr*?I!QLzdh3y)^voj|geI;{aB^yt^4`
z27%1>13xI_Hon@0flj4eV1op3<9E7H0{ca7w6Vm7Z*r+zV!OZwSpsmi8x$_F;Tv2i
zmfPj845Kv%!DkGqjGNwQ<6GMJc`cI64WHLiczEBG!=H=ufvew}f|gG<>x+RPIwR?+
zK3U0WzY7{cPxaY)+~PI}J08sG!kAlR=EQYzP&ixvCKd_qcHpZ~*!1bj$bh?}QS?-w
zt+edscEw_<^#+Ph7qYw^_BUsW?^}^%$5nDrIMa^LbxE2lK4*np#+Z`wxL6Jfj%|Z+
z$^ub*THRVakN5-?33OZ#bC!Xjx$PrMKDXxIo<ZXB{RiABm?Sbxs<<qUHkXf2LcUxS
zg0%a<T)%x6vgCEEni}5&{|IE-BesGI<REeSxbNqauK_OjSwg(w?w%#Y8*K7MBEe=S
z1>A0w*5290n4cxo{Yq&Bo{7TQq2)7^J-0!qXBjyfWO_b0`^=e1%Hx_jD4f1Y@X<!g
zXC{Tc`5iVN!F^m=v+N)(Yj%`FNwXvW6Brkk5nMb6iAzWdTIK;tHa&eD8t#!9ABW9I
z*?-gU3!k1o7R`s{sl`n&^F!em(9I}Z(5{*BK=}pqO+m|E^W5~}L+I!DZZzE1GOaHS
zceUKK9lN)DjCx@MVRx>Vy@{iZ&A>I(D2;uZwKKc;{>lA>Tc}ZRv?^q|y7=bFa8plg
zo<3=~f)0u=rJg)mx>8hJfwHa?6{0)iPJsx;(XJZFSyZJy*Aq;V!N;arxiuA1I_uI=
zT}o$t@+zft);F)3?<vb1gbS%rc6Q4C6RZ%|j$CA&!sXLQZ14UP?hiZ^3V|)Sehvzh
z-ik{^)<+Sy&z$vDthh2{U0`tg%sESb;r2O5TovvFS>H<BKL-WN!lfW*o<UwejfCMT
z*z-3#B|L>22mL?GEQPRjqd-vL0y;=sY1MRiJSoa$xvwz!W<J(VM$WQiRcP;7_a$6F
zje>PkaO<mEq3sw6V>2T{=B`T7jSq2!0X56~Rbej8DNbzBe2PZre7Nwe`EcQs*5Nt8
z#q&*K%O0X{Hm;q6!iB>CnPo%sYv*Pp>^OApETdYbaMtAwSI<EqCukkaQUGewgm~PO
zCd5;aG$BYAD9<^ZvABF12@~2iA-(`G#pN9>V@#5>w(hVrC0z|GWO9=7QDIR_bazxp
z<RoRJy4t-N$tQ!$=AeKVxNaH+ZF|d;E|j=y4oZRES|Ev&tbl&C9E8lrBs>PEr1;#x
z6~A5j8u4xv$k-&WN-;B2(nS<kN2B<b6jzSZNwp3a$3X!X3UuKlHK#zzrjtjcAebPX
zl85EcY{&<wze%c3fx#!~N?Ty@Nv8xwfvim@Sp!L%q#)tOXcSBlvNoME`<L#_z&|_x
zr7`)<a1h8VI8u{TDBk)8$&XBN4`q_$sKCyWq*E0bRgzpu1@bc;!7GT+q}z0X!6Zr5
zDiERR5U-#Or_jD|i5w*G3Qn{nb*xk^oxG}CdV<n~D`QSl&<czisf%Hdk4Z*X+y{-)
z@F0lDB$W;Kzd->HAs~~qxB_)H(Nw#Y0@qK{tsghOLE(!ClSG25S0Mh947w%zRXa)D
z!{yB=m><O7jl!jar<8t4Dq(>+A<3M88=6rt<D`|7sV?uwgS=_!aO5vE(IhR>lK_l>
z*~7O$%4Q^IxJ=EskqrtMPB|xwMS*!CH8DJ28XXMJlyfpsXG*%6!m%p!kPNvdEfv==
zqxdp#>oSVZIiDIUD6Uc_Dzms_Wo1AYT&axWn~+Zqjy=e@`lrx$Glf}0%TKlRU0jCl
z6z8!*H+cUs5*CG9dy;=MAGa2T7?tMiM(9*!M#U`#Bv3dq#7l;Dn50+Zo-!yDFG%VH
z$tX>uH?%Q0<WFuITRUkX5=qY2OgSbKRBjqNC>)s^S^3?fnJQC^O@t2Cac3)rjy8v;
z@fvpkBY_dn`z8wXzNE_lH2gOOEx#J5*(`~J`;LqGjgtK*JP6S3QaClBlN$+4q3F`}
zB2#qD6hC!#<Jg?S(Q#lh2j}U?8l04*vGrmn4bCHki*}MZFDDHi6b|ku$R32@d8U$v
z_xbG_oNa&66qJ~EzSJ{`L-UyJ8agN#nWt=L%Q&7c4TM7nmF`aAIDY8TrD3uMKc<Vr
z;MAq-);cu`qzzQ2I|YiUE^q17Q$<MFdmPGi=*dCB7pI_!xuTUl3md009k&+TT}c-~
z|730-B!8lULEoRGxz*w!U|@?LP(EBV4~id92*Vq}86?|m;yX&p_9l4~94vfh5Yz(<
z%=(E49;=h&n@hW98<ZTm>t%OMIa&oXrwrYxQ0fVL|Go{oH~k_gx4G}tO*S`*`Zz~+
zSQ#e@yh~!^UcSlZ4efH@oIR^cP>`yR9o=(ug1cr%_(>d#J;ifGIc|q-Pv4(yzmogm
z+;N>li#m-?_D&UMrcCe0W`xAo3Vfx$!WS)HmmVCHV}5(LL754oUGSQj2p9woBm&2A
zv5_y`x@OWbOQS*fY;znJV1vSea3LHd4&{<CUx$`7Q6Rb-+Wcy;-L^?04+2LHO1jDV
zLD_GzK3}lG#wTKs?jMao;n*GQ?BDI9&B6Vg4hjc98VUSbf|)HomZIom>F1RBc=6dC
zl=ji)*cW)$D0YJYAyKW#+Z9_>Np>)9(n-LkD!mY@<RBGjRXl~bT2&poNhtv(loJ2&
z49W@Z2IsIyDdnLn8l0!BXl$o!gOq2DZ4juF@<^3iD{J6}HonhQ2PkXcphzbLXL9JI
zU_*wZN2=_bbZaGzjH8jLkn$WPDWv$`43hM4Fd=DVo`fW|kQ<+*lET%HFI~0J;;o8X
z?ILMz^P0nbh5;*XBZI_CmG9zteOz+}<$lc>6n9kXb~H%y{b{s$%fYstaihYXoN=SV
z_iK=F&EYnkR9ATG8x&rturFs^say>;3g(QRIpa=+Z8+~OU9h+*=Yj7aFS~;R(*atv
z8sPOi58dUl2j?NP0j>apM7sg@;OsIRU=O;i2IP2`)nHIIC$+CI5{x#l^4x<ivw=Uh
z$!NeGkgceT-%SP+^1I1uKz=u^{NR&qT46yMq=Xrh!%Yh(hpQG&4*To5g-vIWCbN&V
zX_&&XKCA3f<S6CWfz*-#pCr2!CRoBQg$YuC9pWGb*un6&L84)bOr)*o5D$wCQ{-X!
z3j5p0D8u*pAOo{3a^zP2o(+AY&1I8U&?s@NvMi!x9IsWU7)AMYic!2(nZCa{rNNF#
zMx`)_Vs0r6q8Fc>V92yMS|`yUN=8wDonq83izpej%OYxb2`AC^i(eExg{<0X9VV}K
z%?7+W7<M8%^dKE>$_96i3wuCY_MlA0?$PuukQaZDXpILa4vIM%*7HFz=cf13KJgf1
z%w{Ay2f&AeLXKwsL7{Kp;B)92K)}`@aXMfH69(mW$jksVw?t-|p4=AsVAQ018_X|+
z0|XTJJ?`WUY~*sIWMqwP;cLmv|B^o@Gk;4?o6JNkId(Eqrnd0@FrQHlqRjLrIgv8+
zl;mj2%sKKK{|1sz$h*MYl#_TtXJis9pw-DOmJfWr!grRLbd!^qfq+Cg;h0=WH(h38
zj9WE)c2)D?x~t~HQ&BY^E*u)4yB7H%&WDGfVm=uypG(%u!6=ffg~L`9p3ux3kesz}
z1PschIw<tja^cM1fM=G;p5eRA2fdM53on`vHk{5#UF<WHD&$MfOrem&IWs>(PH85M
z!g0+9$(Mbx8-3ZC!@EOL_ossn$--=x%mfDb+VjC!5nXhS^ga3OnO7Pf{XsEbfV}>h
zxdVy|cvGgp0j8ZsYyr|v5q_|N(h-rsjbmttG<62|E6^b`xZgt|Ji|5NF<nD34g=>C
zxv7e}U~XyzW^9>Z`HJ2!ibt8C#Yhz_iShOd5%Kg@k26sx2C861-5&v2)KBoq164-*
z@F)~Sv@w%4LS2~2s%RJ{vLa%J6ojgrI0g)Vx3HVcKzD`ZFuyfIcbMO*@SfbEiYfvq
zGmu>oLYD9P#Rwwix+=!VC|O}h8z_u2!f|7qx}upz4k{<dy`g|sW&?9zBX){8un}LC
zJq|rf{bJNPqqH_7<%r{ALTto&F(Ec$!H^L9rFgOIA>|$~#w9e(j!S5aZbM69YiRq-
zPQ5U_F|>`dr}UNv#Mp5}&}GJsE68qR%4|g9Wrm6~ST8eLT=9IKLmMG~mP30X8WFEN
zV#5_VXi2oy0}{!7%JWMrD9A5TlwxK`IN}&H0>TyOXqmQ%S>)?oz7;FEflv?&$pyg5
zr<lvkFl}i8$dvW4O+O0Ib`{z=D0z<lw9Hu#I7Mqm7%Q2;95Y3jX2oFZOU)SUBpxJ2
zoPq}?p(D;UE8JS2V1--j6Rc=!#?&IW7BRQ));2}tT2k$GPC>g&vyH%BrrAdDuTji2
zgaF};h;DsF71f<JQ%G>dAzR`t9t%&9k!-5PTT`U7rQu%Z6bx+?d!#Il?P3_OEQv_X
zW#IK_&w<&Nmy5?9{6WD}sly;qH)6nzvgavI{7sqS$Sp}1QSB~8nYA0?=$5s6T~o-q
zQSekqoo1F&1->(n*JI;1Qd*wk=QE?ZeO!iE%V41pYkfC7#Cn^;_?fXAq5jO;jdTE`
zAQ=H`JeX17Gh^JfJ`;+&)`y`%dMkT@NxevM;Dda|2U@;h-O4?qS6LKH=w+S-D1Kg#
zn9G!`VL89oIpuR0#pcR<y$rB(B!+Ax*+}fd1QpH<#tLPhFex}vRI<f<dxi?9)|8<V
z(?f<zOz$hQWiq3{8S(^@4RoP(cnS|^2Hl<cI>;jaiku#!cxDji1yx>|LCh+S?4jJ0
zD-=`ntC*6Im}u-tN|`a@N@8Nxu@ap!gT_4<Y6A(0PT%~ACsXR`)}Z~@U2{XI4KuSM
zIXTj|jACOYoqXH~YMLhKDRz+Mo=ohkfb4Gg@+jfVD0uL}pL9HzFJe|w9h$xZNox-_
zS87~lxOvr`r{VtKv5p%^c}~O23_w?+9uuD<nJ>3IW&2syvwirL5ojd)k^D)`zh^b1
zG432SgmHq2tx_7p;-mCMW=bo=F*9Pl>KcO7>0IlErtgn#9SmWwlD<h9p5#+fu4eX#
z_HD}MG?ERf%S79m-^tCwS5bJ=8GwCTq?R)8I?_)wL*JF6%1mtJv65mYO(nYyQl9f+
znVKCLvzg)XwM`T9Wp}B|6?Y=#=Q4jga(J1)9eKXFy1fd)*qc-QeUquS;zO&1Vy1XU
z((#}$dwGus`Rb2pLQG$d3FSEp+7iJpe-6!9mD$V3G$CKTBsc@}m6gq8ab<3M61Q)?
zOqbQKXG#Ijl_|~Az>!fNY2+LK<Uje3=5+MT_<m)qXGZuds~v-4eR@ou)8jeQNTAP5
z0#K4Y7dU0&4=y-2B&#d)oF%H6Eugf2a&y84FqRK?2ta_F5Fi6a+4BTMz`dK$3I@sX
zHuh;o4ul~2T;b;sGy>1bgr8uC$!3(M895Mwj9?Y&i@+LmDg)8sO`0Gdc#s1X!YDQy
ziD)J@w5%JPBRU2Ig}pR3JsGAd?yQ2b;JZeo3s1ZEr<{6<bE}|5aE+J=(KTEO*6x~y
z5IHjQBmmh#sSuzZM%n!#2Y=#d5sKe>lk`phk@yLG5ff21HJN;B3sjPezcDLAlj_UV
z3xS;&rTTMDJ;&K58C+=*6|#zvz5;xOayIZ;OcvV&C4rg2(ZVDHfh{nYK>(`DsmD0?
z`m}QA9#mwL=+3^7t?es-Yxp$@Y#aOHT<2Hd-{2dxeE}thB%7RER~4{BGJ-I7q=i_m
zFm4O6hhM;e^|6m+^Cx#b$REsQ2ci)Dj5Q#IaP*)kwvd>>7&@nw`&m4R7dMk)>CWPF
zTDi0MnpW;Ch6TbN^aTJW`vGBxq}f)&4$0h5i8@4&M=iL(2@VP*;6*`U2{@_D^q3xE
z5lX7xjyICV^n1uf=&b^`nklCq)B+;Q^)iQClL-P!m!P&XGjD{(HB<BpTcRMn2Fbv<
zQgFeMw`5&_{uj_;Ger^*A!!03qaqnVWpBy^WX2Xo%|ufR;g^Y~c5jLKS>S4!&+yHP
zh@$GYAfdKR1aclKx<KEIQcsz%ezu7u{gbIjM3|%Q9UycwMZeg-0>_RR8G&_oqg?zA
zf%SH+z_0Q>#9bD!UX1OaYfWR@CM)hC2rx3>#zB+kOzG3mzU_V51K;&7pXEg2w!?TP
z<iZ<;OZW=(!*|ON7VXa@P)3d!6rQvsm_~}8BuqxSyCxFHL=<ojITsYl9>4JbHgdaB
zu<^J8^>Z4W6rMVuMhU%gn@Oiu;YaG626u|?^c9yW!fArAeGzceZ>K`!oZ2ypAF*p1
z#X&~*xI!c$h$iuh6b@rY?%1b+NI4ppXopZxr9ny4bH_P6LSl(fH9e0i5^QQ_#@vyn
z2iwU!LPP~6PKjHHjyykmF!+!d!Y%U1(~)pWiRTbgcAJ_!Q;7E#E^SakHG)C*2-S$!
zQ_KQaQz7Kelo-g4>d~fwoYLdW`;GSKQ!gXPD#pCQBkok7oUr>=2RmR4Nj&6KOeRM@
z%k&ec+!j4T7YAwTHWqcZnJedQ(V&Pg#>!I}<U#85_M9PmycKV}ZRXkU+q-#i)qGBz
z5~mB4c#xg0a~2&Q-FKeT%WB8;oJ0i)AsEJKKhNpGAkZ|*cjlbMf>S0TV6WbJO*1AX
z-bLf(EEq`n5Cqpgtw0n65W76N_UV0X2o9X&(>03)QsP~8&%%|am(>K_HOmDPkJl_1
zNV&<~E1V}2Nw4!bsn;wgj4+D{JE&KlS4h(IeHq-mX2C&9$Rs<g*Ca|@qq$~TVu$rA
z{N!DeHsj%|QUvUvUgiD~-4yjYeQB>*nIR>VC_AWEoj>VUgzHYEJgW*<2qzI@TswbP
zjjtIrkZV?DNV&8EJ8)N<lqf%5Eyngl`>TCwQCFMPCQ>Gi&6YjuE^cPMX641tPoLB#
zKQ4V5%#O#bx`5DwU%vBw8q0V7xVI)9$#*>@Oxe6i{o2FU+f8l0j_GpXyLwF565rKB
zu|^`D)AhjiE%XxDy|458c3rq8tt3cs5Aj_)r|W?4+BIDVnlcB__Om))$b8f03z=`)
zd?E84nl5CX@pFA%$Sfa1_ZL#);xT@06iwN}B`mK(a~`{5xfi_jdTxfUp<{J}a=(U-
zY!1CVepfY;ZqDN`WPp57cu#(B%V_$tH(sTgXyU&aGcUTISDUJ$rR;ug*(;i?F?^8j
z*Ze_=+jqCg=INT>FMn`c^hb#Epxn(4BflnTI?moQE&8<SmTA%E{`WMUL1^~R-022Z
z%HR*fO4%!0HZdBQHke`tB@9f(CN>+GoR71C$@w@Nm`uV9QdpS$!8iMoB`zgR*LgV`
zn4FhQ?kX6w1}Q8|NAr{@J;ymW*_WJg%3Y>yt?U-gQ@f>Dg}Kk!)@SQpJ&}fmwoL-q
zjZQMg^|0<amqLJba49TH9VZS#jHby!Ap1MGbWC$`E`=!TU`dFwZp!4KOa|B8pK~|3
zj{LKjj<ZQV)_O2M&DVI~WtD>!rr$v!^AE5pbgcu-Izyd2aHvArI>4^DgB@U3$h!mV
zy5<=<dw4B7z?^HEj~^jPy93;!u-j;fFKNdQj4^4Srecgqbfd!HZ>fHG6HnJ02C0Ey
zoJn${!nrUg2Y)h-Oj2|V{30bmC3PQ0Nnwg|#t%y7Bbqg18pe;5Gz&YRgAmiO^`{im
zIQ$_o4QGH_w)h<K_{8!vr{UkILEuC#ET7jK-^HSY#SOlwlBCI9Sbc~|SF}qiX!+tp
zL;~fvD2ooRvl1C`@X{0}uDJuQL<$<5HYIY$;It{JOcU`1o7jX4r$l}h9EK$_t=y-x
z8HtY4-PapIDmxZDJ4=1Rv$NDf@k^TBr47U1-K8TbmOkYjn>>3<ZQV^4BzR^^n!TmI
z@NkwUYlTO72Zf%}#AQk+gzu<CLJfRJB}KqX!pT;^OX4ymbKy-Y%zJ^yyF^M0oJ&Os
zEbcc)7BW5BzQ%(sTVDjcWN+P^_a%}^TITv9+$H-q%C3(<ffAV^2qv)PY6by(d!H*p
z34C>uz8<om9Boi+eR7u~@}YRj1|Q^WIu$PAM>PUm3U-a*i3qwV%DvbanK9DNf8^FG
zkwbxik0J~q28EQ!kZ6UnCZbwUyf-o;5P(urgtZhbAfj4|v#EG;0~}%{G8y0yE6Q8&
zSeX)O3viGX&rx6)k1Z-v5)7&lzyNGxpa{9?80bWJtH=Kg00QnC^t8w>KnxL33kJbE
zM3|BZ(!!(xIMfUrLD5dR2`%AA9<~w*0`RZ_c43a8DiQ9FKr6sEIKkK-q5X*0Dv0CX
zMmSfAApQnjC`W_~bfFv(F0T4S#C}8QT8RLC_~nXX@8Om!5qpmawn4c^xmgj(rsw!{
zbs2Ampf!HJ7)n<n)E<7jlB?O3;j}9eSr1&)l0$ey(TK=;1pgJp(c?kBfCw=>{Afgs
zAv6hv%>(MSOkwlDgDnv@56D>Jnf%cCS0YXxp^65Jvhyb<5lY0yBOcRWTSRHr=7jOJ
z%pp=Q>_O+pu<wR1!ysjR=%yI)9qeVyparm&Dcl<ou4Rh%#@8w0y_3P^aFB#SBnc6U
z>lix>;BCU?`BB7gnWD1&V-P{v8EjSfM|X&(G6h&eDl2vxGI<J~&i>Shore6qMNfYb
z)9A-NX=7$(XKSpaNV#-iZ9ygdgk#O%ln~)Nw3jjkU%UEJrs!*PnhpXvg6nzNbw`1#
z4d6~cbgK<)s0c#0GcyHXn~<EMuaOg76kA>KP)RR1(Tt)1f8%|j&gr4}fV*OFz8&eJ
zh!AtC4b&{o4cEgW@rIm$!jS7tezh`1Sa-~Z0oIUTQ;4<8ucADqPWe@+n_Aw3;ea)E
z;ano2!sk-ZGC5l!9|<`aC8Dm8r%@v68s0afV4%b2RwQ@eeH$e1^zrRK;q-9{Dw2_2
zQo(@LG|=fQl$?Y!u0&`yl3YrJW+MrvM0j>bR8>)YHXL+@{kF4L!*e2S$KI<_=d>LF
z$T4l_#8bE`A6NND{!+=j;I29&V2q2KIHw;G?9M69raAq{_fT3h9D0VM$G01Ifg(YR
zd?~{3{V1nuP?#eIUB5KFjmXU^5m1i&Ed&4C*{$P2%ztz}9s%atkNkcmBFvBEkb-`^
zk!xlYjFX&K)V_~IR>?$bIc<b4{E=7Cfen9@1y>>f9eHv<L)<`eR#8Dm!W}Ubf0UC)
zoW&n`5(h;q%-B19hmZkSB6J;Df&_K^Q6^zQH2bD>!xG`_$VfB_hNpl&Zh4I*BHRy&
zXMNC+A4zD+ALUS%2zp1JB>^peA{mpYmp{tbEFK1rjLs5a@bGRLrSdm^iXzVmxub@_
ziLs%_Myxz?P)o$hBTv<FJdIlv<Ff4>P4nTxo94rXH_hinL^mqn8L9C>oDUZc#k8np
z4~aZ)1l|&>)JZ;@$n@@*jczH(C@v9;Pq!^$QJvKBAf_Q>E^|6F9z#}8c3(=wI}Xj~
zn6s%%gzz7Sro+<?#j;#++F_uob80v7VVz>9IKupq9!^wQr`TyIiu^~Od8v`w4P#P`
z%x(zk8kyZl;4jP$K-znW>;NRj8wJyWaE^QdB-ocqM1N-Cml}!Prkqy!FOkSkNM5H5
z(N_~1{spU2RnFa8J`2DH5cl_o2m__^S_TY);*Q=8B>x2w5g>o7;v@ieP?(+oID}Fa
z{CdLIO_<^z0V@#8_($LiML7(>XDC%SJYYC%#6<oP&_k(mVE_z*NXkC~j3}P@06+;~
zFB4<J*dR3upcEytAuK4NRNfj9lTfNWA*Ta^5%&3qXc$hx)QW(je}twnC=G3AfMCxE
z%0ay8A0c-TkNQXG9;H$<0{}=tRND3<ln?@2{|HH>R9#VlHbOY;A0d*ITF|of=>iK(
z6C!Fm#g3zV%K$<l4EK+~Qnpfg?M2u{iQEpLt`N`rN5Cv4vONIa0u=BKBxghsEQ}un
zsf7TFA(Z%!pkxYjL^k2g6eWomAWf;#6oFX-)N)WxOn9Q$hb%HnfR97?bEi1RD_YKN
z>6QTE0fah1cAV!@H&0h&tFG#Z3@J)bIZuab$LtYFdnY-+Wtau<P^r>SPYOcWYENLo
z7N)wKrv|<QArVOa=Zj!TcS`p8Q%6ED2?6PU5KK}kRb7OVlqyvhP)<a(A65iJmjsEB
zP^AVu)y@qNJk^d(XlU7ymx2s%syoHlKciFmkq>mL#3LW*RJgt0D82`bNVq8dWY7Qx
z7b*Y{gA1b*hm68cs`%xtz!>wFZKn8jr8dEiao{`ZSgG<SUQjJ>6b{UNyvi4A9Q-KY
z<W9*xd4P^l*h$yF;Lg93I5M}jXk>0HrCm_)2C*)~55rFG1RuVm<!jaz0zoHbN_axh
zNvXP7An2q-3KW7)?i3r@FCT!^^HZn$h(YR=%IgSXP;LZ{%+rCobfxOXa&-+oQ7)ez
zk4M+gLGhs}SFf(Yd1kssZ)kJX-lnLNUCogXw+|9W4lu;_(dNKJvO6@eP8mFrRk3#0
zsnLVNW#g!w8XE~P7MjAUA^wZwlfZF!@GgxL6s?jc@6t#?@dxwVT^uP0KGNa%q7+*P
zTD}xv!|$%3&21MGs`Iw*{1^o(@u39EMcl}p;t%#SS#}7UgV!p?ji5eDV3^(re5#*Q
zK%oX<BV1~!g4Rbk$DM*s*ZCEwtTUxj#}tbH&Np_ZU~r#Z`@XmM^A@nPjfAg&p)FPA
z1ol%?4T|>x$ZYZob9YL)Zcj<nNoPvF4Gkafb|>X&{;AG?>w#E09H^pfLI|Fim>QoL
zgmT}T)S{DrY6n>Hw85!I7f~7x8_=G+o&myfJ6DdWJRLnC*G-2r9a>IM_)tX5({VVR
zd&h&D-j;M~Zb8A5zl1Zrsd-IrDln?=ghC+!244D(05^wl*daFvnLSbRKFJ<<_3i{W
zxKN@Ix%)=oC@uww0Dh-XZg&E?Cw((;THR+CVwq^<cS@V&{q`eAUC4Vn>iCf$I(oFT
zMkX3Lyb(7FhsFWTSwjbfUkw~tVrkt;92|!f*zx+r!Y_Agb8Mc|T)yK&{zC-&>03`X
z+?^r~VYkRDI^IIppyTaM!FL3$S$BbhZTlddP$+Q}bCqUF3hY@@rcgs**0@+`;7*zJ
zHWn)g%?|YpK-fUx*gRHUWAhYsDaApdQrx1Lg0xe#IXKTq=iou$*nUK|Q4AuKX1ea~
z6b{VeacEo|ha+@TZvP?OG$_<fx&62rV1cJb-nqb&dMS6Fcd>>R?_u0%%B!e{aq_%J
zJ&g0?HpD_8afw2$5M8raP6YR`4J6&w(B@5yTNXF5iGu4K^66Regf~Yz`r>j)zg}EG
z>DP-(D(bJyH(9vx?gS3*+g5y7>`$Q;Dk@o&q{}cisU+P;u_cA_uA)V|1Ga=tytw_-
zi5DgU7QeYu@@#2f4V_K42zumXulQmmp0H`KT2I(LSklKR8wd$gCc{hETrlGjHW$pV
z$lz00@u+C+;BS%9g*>ibVG*LAER06(CYudQ^oqINi8YkME=3Pm*skdGf_;m%m}K$-
zH!1Ci<PWD-*wR=WiuShcM=q=qmBvex?T?Q++%`yFQbkfh+tO#tAd6dt^$?CH*%#?%
z3In9OnP8&aKp+>$NnXp;f*F>4<F!mBaf_~Hs@GQznPJJdLv~p3jYcRH@Pn6U3j;5m
zI$;H-PltA5`f$RMjB;o&HnSdD!Bfbo^Lw&b(-jjo?Ll#yxQ^V(>yPU17Mq6ug{@E}
zzXCD1i%C@KkVy6;KZslJ@tcmvkR=p^D(zP&2;nGjUj*G0_LxdR7=``za8memDg|K_
z_S^X>Qe{6Xe{_GaXkWNUxZ-f5u=wBReipKnju@wSL_!qygOw_(zE`?MFE}=MOiGl2
zuXK#6)NrL=RE7O29ix{!-}owomx?b`xU%>ThP#VzvRq=DUia{u(JUU$H3}PdzEN0(
za}MHdn>=`wlXCM(x`r!|LOR@qsB^hZK1F^I;C9q^B^;CdHih$&pENi)S>coO;Tfo!
z4;NlFAG{gN%qaYK1VyM)UuAHM3iC0iLXKT3K;itA%`!a1RM5hWOp7BO%~UAE6-^x!
z?&=LB&If0o(Ji_?GB-i4ajN~4h?|otJo8*BuB~#!^HLPfdS1!s&kxfN#q;<L9izH0
zF(Uw>1GooAYymFdbNGSZ>=mFuYeIxDpww<eIj|Zpq9B}E9yq}TLI5k2f;E35+=6w1
zBP0WrgSRgPZh*wN5pLzFxRI*C6gP6Q*To0%ZM_sX!c|?08{wI~6gR?`^&+<#nse9-
z3o}P#OhLqZQN?83zl)p@qxy3ZR3fWGGdhRmqa%KYHKrrR2X&~YI3U)kj#weqvW|En
z6ukb5m?PH2-XbumAVdnQ0U}uhH=*iw#6PhzHzK4qkRpoeN9DaE(26C%BN&Ty!WFQ!
zshD^XmS#c0aS!_{z=Mmhu!3lDMUEAZ4WDAmipPd4`m8hxan*KWAUHzUN}~kNQXLrN
zE%Z^AZI5s{ly;AZI#z$Dy1xCOKs?J({-}h!BKHbIx)t2VLi7;;SQNmG7(tZ0k0`=H
zV6-0@$v8vKjR7hQ87K^^F48gD9Pn5gqf?|#AdFgJlch;8@7iSwW+@Mif>||y8CY#0
zoW)^_aMRmB@i<@U1r|gt4M0KE(f}HSGy+XW`xc2h2pwIxdq)JbmIj%saMwY}iiq7n
z@nBZgvQ@<L8P8;lEV<5TWJKm}MbXImlrb7vUos#MDFnCxcqpQT2gTwA6iHlwG6VyL
z6MP_jN}B7YidQZG9zsO3Ewb+s3GLznfVmMHT@aBhncCqqV1V`Jr0bfZunQo9B2>Eo
z;8)SyrKhh5_AWg!tY3muVavMd17$cO%L|Z*Bl>($T$Dy(`JNbljuu1bAtD*;EGY?$
zWQ56YAbIS$F3JEJih%n;Ve~xSm<~PE?Sq?B3L@}#J!cO8FTfs(41uCJ>L|U(Kxzp&
zAQCYVVYGd|x=41&IA$}HUdVFEI7U-Pk#=BNN9siJVCpEy4%i~(Uu+=xgdxBXU9BXJ
z!su$|co+f0a4OYvJjf-eu~}EG4mCDvrg!DBaB3Ack*JW~q1Q$^^v*mM&JB95N}mIu
z92qnlNPfI`w#I6rhB>3UqlP)7x}!dMXCg}!C<j<lWCab1XGiIh!btC^Hr^Za_}KJJ
zFWoj6=*<+S(wh>YVluvj6IP$zln6!1(3J?qsX#DCE$<G&oKC5c2oI0)-2lCh^sWLB
zrbq!R9x$#Xv8^y-Jj!l&=+{wXySp(r>SqJ0DH7I<a(P0UH4pihtc3+qrZS#fIdev_
z^|>;>6~H@1;$2~YxoS{%m_(xBbU&1v$J2elJQ*dVfdCcRf(2pdN+>LyskTz3`vLt=
zS&5~eOk4DpauCTR=G96?W|(@ET`QfbwIR-#U8{=6o!Par=5|l7t#TrE=>Ac4n4#=Z
zFt{_pHpDk>177O4)5#W9dOH(pY5DBl;53*_i|V!=pUSBYZD)QhO_QD3v{F@3Zo{)_
z3*+IVO6P#K+P;*JYi;9np620e&6<a=G(<F$X)_XajAEnaX&y)@9<Aej^-$_@VJJP5
zlLrAZM%pFNvY6vM+S&7$iyneBYVd-Q_DPTugM>_KwAxoBVvn|O^B&XimG9Fm+?0WY
z??FHk`7{qEl4~B!BTsq?63Km52vksRdSUQB)7OnKW}*!D0+cW2z;A=#+4Zs%0rx9%
z>5X!oQ@(ux6j<cs+k-s2{+y=c`SmjL98gAt08p43Ad~=mkU=z@(}V~<5ECN!0N!F|
z4+yfL9C^kxC_o_#+=D@J=14bXeu3~41|=KzhCKGnIM}7G9<a3us=+8WJ())i(|UF$
z$`z(0?2@$y^dO){Si7DRu0(M_w1A%23X>KLm!be4O~4gSv3bxRd6WtIqA;IfZwzP}
zBtJp&_Z_$y3TLA*=|NZ=g9027-VB)tAw&<O*z6=hk0Kxt@*h?~z=z;LZ9*6+Or8)5
z$)GsnDqA*Psk=u3yhWMTP56|?woR=}izawVEZWak38_%O0+XdM8AG@&gW|lD4}~cj
z!hbP}2?l}043aTZ4iKhs2x`VCHertAd`!Ay9*#v5QV@=!ol-E`MU!<d>ehYGalY%?
zeGr>wpH^*WQc5XPMFinv6w^wD^HZ2TA~2vqA@WbGniQ@Y@zH@iG)RuZB!LGk;41_k
zsyYbdXr}OkcsQo;6%r4q!@^TCO3M@GQenwA;4*D@QrDy%m<bl^!%&fh|1{c;xFj?4
z(FnyBq6`Sk0-Gwp91K9JK`~UU5N0Cq`peRGR|qozLSM(kWKh_;&Iwqn9DO77mNzG4
zuEN@S0`D3W-yqpyCkl0DR_PN|m{G24f)kr5<SeTFT`jgTNce^Vi~9;u1-x!Spv@F*
zBOty7rZy-u+*-7YChSmJHAV*9R-K0St*&g@qNUeOlrCQRE{AP$A_dcJpJj>+Lek`Y
z-%GS+3_K$>N6tGqdjjWaqeY2vP1*-0A4vh+SB~Q=fc?BB4=YPU0vT|-Q8+Bn;x7uW
zX!C>tVg3ribpZ8IScXQruCD+*oGIL5FP3)g8Yv4@aRbFq*FKFTisowvP5_QGg$8t1
z(gYCX+%B4(9YCT<24T{-toYk0mzvsLld~f!V9S}Jr@E*)&uIa6NY4;8C@OFs)00Vw
z`I>$kh@Bu!u%3fr5T$*34hU7ea)eSL7YC_LkFmpgN~sA#(pCbbG+NtNpqv&KL_O;?
zU8jVWa87Wl-pVrhu*NC?S)<Lf@t?l_<2E$<{XLKO5jt{vKj(d4*^jf1tKC2U)7QUz
zrLX<{zyAOK^J^2&4%_xu?AQ_C6R$#X^ywh`Pug@U?aIhR&goS<%ETf&|Hu4}G^Ho2
z-Dx4AjOd}|nhfl-h;9zYtuK<nS?B44>2R4nO`jW}x9?I7j0NqQR0BJ0jV*iKo8V>(
z>w>mAY4$eP=8_h;pe^JSU{+hqgO%0lHQ#Vs`ie3kMiEBXk8Z^|q8w3CvQDN1@HxVX
zSa31Id{~<>f-pL8`#r>gHaMHJYDv+0=~b}I&U?)zy^8AE@kQyo7aOD3fQ8V)t%X7@
z!b70zAQy$IG<>)7%~4_lWvN*0vl?MxQKj%N_;+AKbxM$IiCLap)SJoSg}tUSq6`YQ
z0<3iHdu2!I?JU0#Mqd;R2+JyQUGo$oa<X!C1gMx4PmH56`4UFS!cy|m*_`WEGo0aI
z#@jII!BrU5+Zj$5W$qac2nqrXt;q;Zy#5L9*NkB!m=Pr^!a$S@m!~tCSvOqD3W^=)
zu=pet&sL|zN-{|b3rf?^y*RusN(n_Dk_`R{9>ttwhflkH<Ov9uro$8r*1gtiv_or4
zst@d041*B45qu0OtbH!4)Xrk#cr7;MrPxR|wrArQv(WBj4KrfArQ|KsS;D|b1t+J-
zU_({Lq_nY<HN=(Rb+SNs6QCD9rsE7T_YfD3M2MZadcCy)@S9|DvAkg0q{z8Pd8j1J
z*{R5RWVQRNMd7^>)cjsNyWPrJ7rl?n8fP`;sQe6s2^Ll!q}|_pp9`$9tQG8P#8lFj
zVj;?1O{G~0fm6NeY4a{DBuy+I91Bz$^~>yrTAou$Ou$n`SxRq58OlJKa_Jp~ZQ!(>
z%Ox7G0zrWV`v^4vKR65cA)s?EnHN>)gp}vsuo-I5rWRR{KtbH@HN|W_b5SoLJ^l!P
zbFOp6qDV;@fGP$R=!&fF6J<SEWQQd&K8x~raU!1r&T$jMI;)QaBxY1M;gD9jua`hx
zjT#|@bVT)$8DHACcq>6+rw7<Hs5oJRA42(LZG$xRa>|S~?z&oKg2P-ypnP<j(f^IP
zN0de*l>E-X@c`~mF(Lm=fDPk0XCUtqwVq1B7I6GC_P$?F0)HBn1g=1CCSrMt2jwq;
zs`KJY@Xo*n$FU@ydEnm$E;f;}SOn*ax)}i~9Y+Qr#%MJY`a<?~_rQcR99X?%Khb&v
zF*h(^$q~fZnOz+_67Z`6C~cEFWQG<cbeo4FC0So*q)Q^T5yvuWo0bn3sUQziAl**z
zg@KOe4&{IiJmeq`@H=;hD-OWm<;)qZ&k~A4-C^F2ro<2@_)kuVQg=d5(w1RCfon$0
z8J^xwWSAL6OTk`&WrbihA}|RWic(%6P57`d?2jy`!MkYov?otsJpUS!=J<-3-Rzfh
zM~Rufme)1KRr6Jy5k{CI8UP|5H!)#pFf(z6d${Ld%%BW`EkLvZ?&HaXmB^}Rtn^2^
z``4VZ9r@!*t0yEyWcEfXHM=p*le!JOhs-f^n=+COp*ikMt&e0~rc}s)urrl`4(^T4
zkfN%Q=J9Fw9N+7n1)O$ex`II5)+wtpl0=z985yCW>@v}o4?3}b^6KC%o$?@a5(AkM
zmbFmkSOLIoPHQBBM`Yy@B7^B(OaPC}A!d;&B_&dR;>N*D7T$E2J{<WkOw-Q@H!lr&
z2E3#&t6W(S%*&EnU<&YO7;IvSlCE9(12<_3_x|#$or{DioEc%gw5$>In;2q+;L}Cs
z-Z`N4ViYMOK$+R1sLG-k%8u~Jh=wFOBBS)0DEI`9yE20R;yUdCX!4P^^CQm9!*yg5
z>$r;sz~{KvGZO0~qD!_}FTXa$8wCcgf|d}WlV!V9e9IiW!Z4JGcsUUOQX^Qxe-t5e
zLgJR^-~HBM`lZV}F>;Vj=M<KpG<|ZzyR7Ro;o)|@5$1;U&wF_K=(P*~)TbxR{e|JH
zM=i$LJp?uN3YRq9I`r1kZE|xf>?p|Mx}HqRIn1yAlQh|IT_3w98>uNhH@j~4qDIGL
zs-qeg4{{T2xIs_+Cf`ko8z88@XtS*CJahee|52{@z4HCXv8Su22a~0%1N`8<?6HlQ
zVi?Bwd4wU@#RKu+oZ=??qkh_OkML5!G<_)HiH7t3VQt^0I&bE5==vDY$<kZ6I{X=7
z3Wl4kXIb&+{Od_pNjMt+!g8rhn1kgw4;gRZdRAppI@}2Z?dQ5pcO)}k?p~30ijeTD
zRroyi?<VB=9|hk;)ni5t<@kQNX_r?wBYZ{0>;j%e0dR)0MS=1HEe&;`ZgxuMZ2^2X
z>e*X-r`a9#HtDtv$-Xh5HWx*a0c<!&Mg$^>^OQ3HXMrN_DT4DPxM8fk1(VxP_DQzW
zo=FQQ>pNxzuCN+<7A^$~iYrK&m9TT<ouFi4&Wf*K;o=DLWm(*;Z!!zAW-)%0C(1%;
z<F`0R$SLo7dCsw;0f*UpZo*_%r5*OL0WoDIM+9W4W=3N7Obh2^zBDsZmjNzcu!{x;
z0gYH<3KW?fk$zBiCPSCSK$}4-lDlcki<Ij`+b1oZyNsg_>IqniFx@c-Ge<<8M>1v)
zze`~~4fADl+bJ!aFdy@4mr$#3GL-u9PT`M1d|N6Z8Gw9}vbcbdsFWr8clWO+-EaIe
zcJN}gF=ilTA;w*Pnv%*X0<$PZDYXk5&ALDr>@K@s3yLhHaZvyhY3}s><Q3(T<@@XB
zOJ(!MIpWQSMr&`;Xsp}QNo$?%^=Hum2c|c^V}lathGSZRRu5-fyf!joBCOp2G~u}m
z`1bL^2!M5XsB+-$S{>#rI9yim4f`X)$g&X25z3dd%6=ixF-tXM&CzYhAtDSPAEL^U
zrE^i$^A0tn=ngM8QIXvQG3{oJ#8uipF#!{d9D%F^zk#tnq%rW55eYt<CgBeed}%x3
z3yX3HhrSJg^l#p=9OeZSEw2I4kHDKixNFeI9DED~ATsfBP_SZCxtpKK3>u{+=mL!L
z4e1LNKz_bZYz5UZRMn+rnOuLuCMr`U<XDTcmF}8tr_A9f1vJ;dhUK(Jp&yvcr_#>Q
z9Q#y29)8m>T0%nhscMz$HBsUYXQQ*S9KxRZ6~<7!XUAMm&2_9>88cxPM_Z=6isOHD
zG&5?MeuX)X$grT8Vk*0-_c&c2SK&2-2-OT+1+LSatWVP@Zr2R!A+W&>tr47u8~MDZ
z=X$hCl)P+I&}kd@Xsr_G0zp-Cm3udZ-VBI)79blowE2w!@JqC{k820mz}i>>eN_Rg
zDEkIHw|z1Ius~10A0rBV4|6`i*!C#wd?B6|N8N)7&&dplplJaDGnp}^`ITxOm<@v`
z%=%N^qgKZykoL!pRDz`U+T+8cG!7FZv_&k(;U8%$o8fm>8ai>ApQ@v<0)>t%3c62q
zK{_B4rrI0IN|IHR7iK~IF}Ws;ny@}hRV7%Z<eCLGk_u@XWomDlq<&;fW{(5+1W!y(
zMoPIGN7QbSy^q140bVZ@ZD9e?5jSJByXAzBydn+VDGp{FnBOPuGY+zS1`Yr}$pm7O
z5m!*OtQc_;fhfM(pU@WpY3im!T1oW^UWAa5{!$zfg}ztEdy=Q{Y6RM)azbbigOa@h
z5(qg5dm!$FPndW*RK>C^s;=7a#A>MmzSxNer<<H0@uaiv0yO$^m5(@7q-0@CeYvjb
z5AariRPpCTsML@`daF{w6HU>fCldxySB{)N0C<_y2OOVViJ+;=U=Fi$gd)&bO^hd6
zKOL=x@YtDA@Fji1!xUK(X*eXfR{)g6DH9M4w^*^lfJ+Hn4Z@NXM$}c5Mv$GL0)v53
zA#x0S`3<bVbHJ+{(|jXCpMVF!`+Cml>MV1oq8^bvuYhpGz?g`@HCH*{abr~#m@mJ-
zD*IQaNEeGT!k{>kpt*h`oma8E^6cma(k`X7B7g|yN!~6t%SdgWh)KIaW?CZ61}rJY
zAni_vRYX=*C8{ZXh*^ALp6HXm?CWRBU}MlNtCFO!+;rAFR4&x+Rz^MpAIEF5q~vzX
zHKB;!Wy4omjpB5aq7qglI5bqF)srt0!|9j~5#jBuy&L&6MbX(b*;Tqpai5j3Qt>_q
zwVH?`rma$TM@Ds1@!2en`;3@*1Z1DO`7@CEoC3k&6;?Lh0h{pnGDL`=2Z7FU#IA-h
zLSz^n|H7=;KFx}ZQ8~C%4;^Wb?2|q6gyD19u}x-6A8$5eK91HDdMVrInSL8-Hi-II
zcN6L3X#TUpj-p)aj_qb}^%3tT*vAnIjIih^%DL_c^C;}OKH^MSjL0wwbQI-ScdR#i
z@fdOcupmEl#3c>N*=sUAw{^#Qvq$@gcMJ97h#rG-imNnj*LBBwvv>Q5cMJIAi2k$A
zj-(uU-4VAjnA0)hL|Kh!KWpqr%8}L`tIYK_+GM<c8p(r>ckG=h)yocLb^(k&*WD-Z
z(2bsh%x)x{%Wmc7U-04X9*4*A{AW5|q8#gvdG=q-BC!9m*$}!-$4jn|w(gj3?h%NI
zo5SQ;FqxU<R7ZMR>bhgTxnCwRA&1ObFd_QoHF<K%x?{SzcV3a<AcxPhn6RHUb*wV^
zEIX#zeKfy9jXs?9ON)T`S9qfOzV5is-YGwEH+R+J5%*seb}Kqat8V+v_2t9eonepT
z`OlI%l5#9NdH_FMYrgfftL^cqHIJJ_CvW#<C*1q#wDT>vyYU`3{e<n39qIpT%Z`9C
zpij_8yn6{BNAwH@sXlTq)@4VlBuJm5Z^G<@eBAVA<}Y@#c3TT3fM3v?>6>u(Z$56g
z|E#eiDJ`u#(l8zGUi$E#K5m2mOz$2kZT;?90ZTe#eY|KdMr&WpEqQ&heXTn+8G~({
z$?5wviUK@e@Di`pVtkJ2I`(b8JCh%el>cmJM^XB^W4XDeUjncQXZ7RJq9cPH>E&L3
z^I$`S>l@6UDT|GEcg(4d^rF{w$257?UxHqtr~Pp&e6$0d=$<dDPW#Pg|57ASc<~>%
z!GES>OiEpgJ$d(CZ+PkcA5j92+n}%jbOfcQWk*F19QbJUdJjT)+yn+4pc_N%_f<DV
zCUjnFdijWOc-#twG@v6X*RmrDWHVl3VoX`z`Lq?f^Ua&H>ez1a7!z;G`p&1V(4BAE
zoMp#)i}#qBQ<hf%ZO6`z^9HRtmN}fnd2@>|dE5+hB46r;u#~p$mTwMVXUyFt{J0e!
z!E&l2!(QsTW13@OUbGTMaLnUI*!rYYGp1&(Q@8yVX!8=1VT9g1ZiD}<t0N^(UUsbb
zDj<&MMU=-WvgdItkaDDspa{wGVZ`$mC*-`jM-Dx1ML}Q?JA$H^(}xj{IS%P1<W2=9
zJ#GfWj?j&SYt;>y!VGeH3FS1xo*uWtf2NmLlxy7)pdVQx-(8qr5moiL75=l#j-sqT
zGH@m_M#QIjkJ@@<j{i(|cv04Oc=*2<1Ljk`M}<8y$A7k~W7F<0JEmK(%uCVm5kB+K
z5!Z|)4NBo^YYnRIjA3)esP()Jo^p#0#YR|l0J=EC;$Bla@LD-wJYAAHq6oXX?1+K@
zGyBU&Al?%*l(xx^jNn^uI6hbm>wA3>9zFv79y&4}u(Km6$_RSs*bp{oY*7f|(-znW
z_T%w406QOk%pB>HrdX)u5taDJ1m()2BPcnoJLX%A<4X>~h<bctLgeD2BPe-o{4Gf_
zlrQrxMnvU9hw7nr=uoHB^}p_r6@LetTBM?{Oll10tm>ATD8K5K&pGJRr+A}0GXg)8
zIYyLg*)jK9OzBHWVi9Hf$Qb`wVMkG}bw_TtzHuepC=2E^#D=1yDC=)rrciAZ2W7ue
z9y>CaHnXEB=elE_V{S3knX+I`zapppHHGh<>yAV_sQhr`<0HuTkvaaeq>iK<>yG4M
z6?6JW5b;At#v1FgFUqm(=oqvNNq!LzI%1R`S!2IS>X!HluezlGgYe5~E;C`l7XMXZ
zHxiatVFgO_)|T^3c<hD{Y+d$9Sl{)4yvjiBmw=BWbo-Gh9ean4q8#gvg@NGHB<rv2
zFj2<F@%(dQE)*VOAOuIO`6DCzXS+I*($^h#pjhA&X`kf?WPfBrv$5F8+iOSleoZ0q
zFM;hcME+qU#?iyPrFLI*+PRf7fdY&q!tWoM;Xm8ek(9N`bw6*x{LcP+c>m*u`_Cjp
zL|MxapspfW0Q{UO3y%8FWQ!)Hu5Ho4KV>e0bM>B`@W@sFnZ7=vtiL`EL8@Gbmts#N
z`{8jr{AZ0FNhxXFvD|VgUSB-5kzMi7kx3Xy9Z5M>9X%}?xf(BrJ&n|jhp{ZZqpQnk
z3eVwTlzPhmc?qpEazY+DGIeA}$Ds6e$2@14yo7G4l#_>UNKEkvtk;yOvU0;)T+@`k
z@^Y-tTSCi2N94VnmpU>NW@!**jdxFv@#W3wGLNhCAMM{<oVOR!3`mG0@5Z^0#$v1O
z7u|ji#o|#aGq#qAJkEf7YR@CfeeRb!7TtbU9ZzLjo#1%8XAV6w92x?<WoihkZs(~i
zB;&`Flk~*yFQPoXki@h!JC5i#Wj4JCm&rt@M;1Wevo2`nh0BInyv&z+DM2_gsGb;r
zpV7G|N?y8vN5CHQv0h(sP8J=gXxh<ZD=#=#ZaH2rAyWKu*^A_`u8yFnV8}zqbju<0
zY2LHS9+^R)Hg;q>T3L78ryMoRbRsNR!`l+N6`7hA-59i#83ZxT%{?RTVLZ6b5q<lb
zQt6gq7a7o#vYrmU+!F2{HzGH^TCd2{TN-QgaeUY#2VedT_DE&@$sQSbfJ=L1X7mZR
z*%>oa7F*#z(@_(puRFF|?xFMMo{jjp75ijsdQEAJOS^I&(RH~7W2Q{Ur){uN(7{^E
zJ9a+uoG<A!yCqOQvf}Ww#BLxg)xYdf5*hJIo_D6)%qJEAArf7@xr$WEs1d;w&zD8&
z&XmWFK(We29Z6Y>y-wuI1IiIW%b8R9$ovG+fo>p_ebo(hRG6RY)4XS_J~GCC*3=P{
zvJCtSh`vi5^G8PPBV+t$H2#Sq(9(yFEnL3UM@%=$W5-h-8+0T^8Cnk=>xcI?AN#+>
zd#k)(d2b^Vc<H^(R;!BX!OogFUHEY;ntX0A<rptLD<hJ0PCRy|+*6Ssx52#{mpU?s
zxve{<Ik6c`nJJ5H@SpAKNXq)<MQu3dO*?DunbeQlQ1A}0BPqwSW4orjY-i1!r~SAU
zzRB#Afg-sa>AYopzl6XRIpB}m;6E$sNXjzsZ=`Y}qx|LIn`J4<x`&P6=N@0P__=V3
z>DM1DpDBw?_MbI%1f?$h`b=L%2K-B)lS+wy++zO~obw{o<z*ScpG>cJw%-%(A2-_H
zu7e$wslR@08Uw|oU-EsZYyDDCr_wKl1hCdG5nEHG0wA_VHRvBV!a_|hbpy=6TH!#*
zDWL~misKG2g2%16z<72frT;eK3~k^e-oXwYNA#biX+)<i4S+<C9MB2A4FRO^xat0r
zVjb98j6gV9MA2DXbPyI>ed0u*8whO`MK}J{q0>(qB3i#u7UTKPnmU5g(y}8eDica#
zX8qD~7n|MH5tO#J-vMQp;ljQRckqhG&9<K@WI0eT)(0Bl&=5y8a50|7F?QqU$>z8C
zxgP{zYk>0;VX@WOLz&qP7#(XZfr#+H?Qpi=kvtwZ+JDASk)Rywj?7tTZsBS9h7<BQ
zn*S(!C$-O2r*=ae@eRIXkUSnK{~29BL0RSv5)T82CO+T|;^c8WY!$kJ(9^mb!JuU+
zpmb?#vz%a7Wc(wguT2wmN{iV!;vJvmaYQBJ>>SZMmUYK+LwoV9zvI6=9y2Bzu_J+F
z)?ZZuDR*9YDbffp^EjUWYG*eRmX~WGa91(rx=|M6`OlI%lCt!9Q#(*L-#BbHXq?BR
z?Z2YaLWET|pN%%b>|nSX@Xqsi)sz0%5tL(n{Y2or!}z@Pr6a7*<7oaP2qm_UwCa>+
zfFO)DQx>E7&$>E-a^!W#bi*I=*XWK&^!VaBAp4<?gfdz>&#BZ$LbH7?C(2?(&)Jpt
zNKi>@?@>(?ev*$j<0(Ck){F`4<n6UJ5hL-^gn`x{XMZj~{%9^QW`vACI>jDZD<Nw?
zDHy_A%RLf?)Qg%VA*CM2$PKo<SKvdfyet3|AvD!X5KIA9^*C0-zOy4J=hEXWVE<Dh
z^|)hUJ&%X{_srFKx3vIIfvXi<JeL9hTs-ewtZOdLXkF8X@LaoR_~||55EAfLTX#%1
zG%&DnqOAC6KTFda?3A_5oSbZTPA>I3urA*@xfI#y24eOS09asdJdWi*E9ywfG5}cB
zD9&?In`X*NYS_=3I)ZX7!>XAXM+`Pd-y161v-Gu}_35;DvBY1FS-N4oO<$PnS7p@e
z!AbWOTwGmu%rk~uD8JX*JPlR*ls%kSbj#pN)Hk_e>(8mZx=5%Nq7T)k+8d7}O~`jI
z-T?y&?{Tc7sRpDEW`tj^5cvkH_fn>B0PQ`F=RcEQUzA@i5#<KkH(koEb=ZOM{uJc^
zN>s&t*34VL0zx&PC@bCEe%93yKw$gY)L&T~d5^om4TkXf?qToR5qAL=S^nk2wFji3
z->&W;hmW@_=ji9BIf_RwMIj**eZ)J6;^T-8k#tRpD1jA!QAB4*#<;Tzq;Y*`ExVjU
zqAcM~sLB&=?j;jeU_d_J%E^k5Oio!l`D(i%O1=cV5EzrsrmX8!B@evB*IbYO@xTGG
z(hVwtuY9zo*e`gb4@3M~Uf%bBz;u(;9TfA?CgneC)A2G&S|WL5q?r+6(`|Y)Wnt6v
zbAPBKD5)$vLRvD45>~{0#`Ju)B7zm{NHEZ4SR`dvQQ|>HW@TW8K3hsncInzFu+e3(
zDQz`H5zPT9x{PTK=+a#sNm(1x3~bJ=e24w@Y)2o<hCQ{U#TwELC>2)vIzy*ETk7kn
zbMTrlSC;^3G(QuF)x8jRXx2wBL~C&lUV-VVDpS9(TY6@@Zj@hKY~vi1`v$Mm_u}nB
z9bNP31!3X2@?SBWgoK=z-I_pZ%`Z1W);{^<jM;_$xCu~k>2fN{V<dFYuZ#d<?!<ax
z=&sG-Ko20W?#m2icc|TmjzHv1vXcm-cWozW#|^mmWd_PSl<!}66yoo$j-)Ij`3X8j
zT;P`i0|F`dVMJhb=A@3K9BZf0b;BKgO{l_c?WHDQaaKoCesyn8xW+G<Zv*J~p&Q_k
zi@JgEOK?t_L6cu*pSz(bKXe1uvTpPsl=W*gu>f!RITIec1<TQm@X5<CO`XO|VL;ah
z{_{h}uG7elpp^V;{7?-v>6gb3O_axu_=E_KA%Llucnpk@8ab*j#YZ`I^+N|j#?En3
zBS&??j2Qv@rMR!a#D3@q=<Iwd&Ls+YEjywt8Zv!f9@{oio;n_^Vkp-yDW$E&!+8Vn
zewkhJ4(a_cB9XsuA!-e<!>f+F0K#8pi!HwdiW#DKgryaS248hZH_-8ynIrEo<PRMQ
zoGgczD9f~Gv&UZoHMfrEjq=zrDo3&-DND#omL?`<`pb-ycNF!9js#nm%|Vp4&A|Yu
z<w-izgwX!b;q<M=={P6I>&L0hIPWjP;0E&hLq`I{GtDhZS}uVM+)iJF<21~YGp_t!
zcLMml^gM5`5u7r>ZwEmA%S&aV^*9QOsTR*#K&viBpoozOINJvd{=-OF?`?#VJ23lN
z=m0vHp!zQ}PTyhnA39cTD?1XOe+h-ea^S#2f0@PehT{Lw4Q2?1^a=dGEW5F&r*b5&
znef;Rg#?OnBv@HsnImzsW~UUjYyYS}@X+yK;mIj^guwdCjzq=xl%hP<HhAa&l@N!R
z#Sj*2I&KvbUP{J_nhAg1k);)iOw1~_ur?f>ESaGEzB&^g$4iod=*CJ8>-@f5)g4Bk
zKGk}7=ujjDjTwfqv+R(jiV-g}Yt9uU9y)oMiCvw%y;h?=L5%Q0FSBUgic>svLkSDT
zdXlh?SB7I^lx%p-Wi6gNuxtXeJ-zjqvp(h##WTKMGUWd98mi_7UwRRiL4r}ZgTNAd
zxltZE#?l2xEXooBWz1_X{NYKu_fjAaBeG(Ma=S%Ye`c?1E-dmg+v2U#$isM9Vhr6#
zSo!YF*j%G($;%Ck6XmfZ%bg^3BxM=VPGd7Gl)PkYj+!M89a&997{8*d;c|A?OcAOG
z42w~Q<)I_1wFp&2lr^fz-c*yt^46ycEe{>M2nsq_Yv~Oe6Jf1xj*@Sb$BwML9ix%*
z%ZMx{9V3>HVl{u=Q8jHeqA0(NNcED45o|q<1Vy%HFvMF+Z~|7-arBF*t@F@<M~TQ6
z-daLD%oTco=`m3rJF>J-aE+8T*OJQg@HI)-jq=!$rGxZ-iL!pbR0o~zPOJ1XQ64)+
z=_hm)W$9q0C47>~Io~Lc9eJbzaf6g!P<xJBfg}ggxtC1(>yE0dB)mUS)_8yEx)or0
zsor;#WO^8pm79bHBgz^LChscn<TyxC?&+Zej~W?*)AHN_HtIluM(Sw!1qB)@sU=XL
zMOmXj!(Lee5IbKt%40{W?LvbQWsL@tsS48#V^yvu%40_s%c4s#C`-pr0T@TI6paFq
zUazqA(1As`b~40Tj{$o&k;*z<Hb|KXPu*DFi~4@l`&yRO$md)G%;Dp1MZq3M^U`5~
zP|aFmYn1#Fsv$w=`bWvJhmKG^iy-JrD5Jl@+_flRW|)5;CCwf>(oQA}U)4feWB8W1
z(E~lKoHxp2$GFq8V_fQ&9jk;;5_sjkBHKepsQ5C1MJc!CrEg4Zs_*vV-69IUJ#<4^
zxXx}MtW(Tr#zFBohuFMTlY8jKnsY3tK|)>m6Jb&b+XGB0znCvo&`t$+Kv<hPhT(yx
z*q3QTzZhnRHWX%HYt=O#Wo41O!#eb-uHHijmfovay|wE8+=13<;WO6bMtSVWcPuc7
zN%;kXINz%Oy-ZQN*8_a$$g+V#R~KasI9lnoklqChVp1MEvMixQo+xX*%g%!I5j)6h
zT?DQvq5z*lVO>mZE{OOt?C5)m#D|Woq^Pf_DC@5$1IgqZ7~t6V5{!S{k)dny21V`0
zr8|PS%@g~PSsNuDA4a54SzjF0hWus2FFilN-)G9>h~ZETC~uCq?6|8Q<;yVKqdMh7
z2LxQ@16$x7o|PD6vKGM<6r^62U%<ju95dj_=_pu(O*h6ns4Px9KdNdzbZm-uU`J5O
zx)2ZQ5HX10HPzo-h809{&#I1m!<SG;K<Q@*(3h1@xYY!G=!VLn4C@nN8Pzw~;L{YU
zU{5#7V@G<Kg(@h@8dY#+jE$G4_G2e9-7_a{o3LWZTp9Ic^*!#jQvbT6N~-SaNXim*
zZ?M2ap`tKPy-^-V#K$tJw5DpfuFC*<H7^!+eOZZ?Tcy{B@w^^vU|zF8>@TH&_PJ{8
z%SzDP%E&%+W3gElKOiA5FE2<<Eds@g;<D#@nyh8p)De_53|B$ECv6Qr;!IhL=sy#t
zFe!Ph-ZO$LMRA_<qsHz-N0#D^I#W$iUcZzBnkx3btSHm1gzrN)6#CVbkc4HDe{2Q4
z6UROi9=ma)iGD1?x)4yEYYk(#nX(wqezr%&DV8n%rQ%dmDdQLFgR!vjLkFvUyq^$$
zUI}?6`g*^WM}AqIwR^$jhmM!xlw+qEr~J!SPvw_=z*{}$$MNh}D)I|L`bG2|b8Y9B
zm8`oJd;aTgED0So)0~jj-*ZMD?NRKm+$f9j{AXo4T25IP*X!r4F7?Z608W(05n0eW
zt0O6E_+7?2?NQydepJGK9MOLk)lErRTT1(NtE>G|ee0;S{V*a6a;xT(DC<k&h_2fC
z)^+^-_~YULvA*3v`CV+ZhrY{ha`YSJc@$&-$!?;0;%mDJ5y&o8*f{z}+408_{b#DM
z0m@*<vg3X$V(uf}%bGuq=s%O$AC$qIWydrXNq<?@)M!6;LS=Q8FhzS^!8F~fufL*@
z^R@P;s%*RbsiLg?sjNbI6}_m(jj|Zgf3{De!6{4BBEBTR;C)%4-CH^Nhi*+dsOZKj
z^ljNK-%8W_aQ9;MkK@_Tl&=|8?w9$R_QE0vX>_{OdhE~@e&hmSaAMg3NMvV}`@U|J
z=aKL;8JS4Aekm{x@t|B{t2sSU79;x4qHrfE>taHza(za*@9Rccjc7lUK}M8c3XG$!
z(pk0P*Nw6m(SH_4jFjV-li~;=XO7cyqbx?WpB-_`KslFT|Eg4es#XS3e?eJ|XqW-#
z^kMOib8(Kh!n(Kf%wO-XP2Z2RzW-=7rT3x!=YRV8i^n1d_Xu^36xxi7p$FK&CREs_
ztcUp61n3}na!@HM2<*%Uv$1AMiD8-nPrSv+cBAmX6$A_iLdQ(m<2QywV0WnPgH$xU
zgI3gORiwm&9Hzk-yxm9?%|@|x(4R6>VvdG;<6>jGk+K*9fTO>pa4`Rr49c4!+XpFO
zJ5Y4w$hTIS9(y=MNIdmun?uQ9<wQ_PS^{tcjx-HJ%C26GaIxEsK+Yg1_u$oIrWDQ2
z_Y-N9TaY>t1ynV?U(*^$i8VO75fWUs8!0#Z#!#$ia0~((3HU+5x;JGr(&xbEzZ&?|
z$qveWTstY-jdC0KxDV`E9~w6Sq$tL<(?t|jkj6gtBlgj8jkw&=vcFJVt;Y*$l+7`K
zFeZ=yd)Jsj;gC=Td)JU=vhxS=?4V>~?`Vw!+1oU<BP+qpERD9CaNRyg{D~dM-gJ@-
z^|m*?;B4=jyNj(}C8qG%=v5~TpRQgd?eO{RRRi-EWl!4&DaK}}7@e41r#MH-d)1p$
z>`;_xY(EA?W3wHL_G3||q3w_v3EK|*gr2o<hj8dw>lT4S2f7x7GvTkYwjKp(d*(3@
zLX7OY<Vx=bl4GSc{>1kn<P++-_B4$oip|%wMdw}!C}LRc)1#d^JI_@Rx+Vy2g^U8E
zdk-1aJpWYF<3qT&C}-L(e}$%pv}@upDPpm;_-a9!Z<kh$4_a=LU&N8Tv}msx(n4fa
zq0DiwfwSTk_l>08!3w*c<8XrKG#`I(%*OVqL8#e<#EyMCr`b5Do?2sz+A&SeU<D8E
zhy8x@l<DjG=)^4wO4W++7>XQ!@jU-m&#_%<hjs}VPp#_>tk{ySO{&)F{A#0`W$SqV
zP(`+NZioZkwvcqtFk5HKM6@t3bqjBjbtuHrnigyr;H_y)=X-NrImsCxvJTgU*7W89
z45ig+WM6HSyeY~#A1%P?HVQgi<XY7c2q4a^pO~m`RpUCyOsi-(H;PUG>S4D~s0{zc
zJ!cyTzTh&=%-35qGhc0)W|kX)NxkhK?pCxj83&@UwP#_AI>p(OxiS9FW4gvHV9mFz
zW9YShT9%wZh1r(1FMvyeQ{0piB7P>lpoaR^LLvf3s)a-Za(WAmE%D7s({!>whi?UN
zwpyB|<2(o*&i^tf22IByQ1Fl)r()M+2<f?NGAP;ZP%Rrs#+zM}L1~p1a&!l8LXKK_
zyGjeGS)Lr|`kJQWSlib$ojaN@Y`cR%&g{^X0GtWZ?$3$oIKc45>2y@CtrDgEf<y*5
zhm&j-H;Qd=m2h<s|0>Z618DZZf(;~J7wrk96Sr8>)z#Rncw)2A*HgGN+mDR)Spm6&
z;_K4=trI0%LKhk@(Ze>7_9PS?rx+-=q;3apW|h$Gxa3s`-3>mAtVq_vA_K~V85Cc7
zpQbY-FFR%2SQN@RKL#(~^qBOo9s}XjPl$!urujGzrH%GeNYk2+x9|{L(+1|&MuLsp
zVlD#Eymv_P2<stDwBt^uERF)zKaj->OGwl@O~sEIM0UsZs#bj~dLXxF{)UL<F&jTK
zQcd4?gaDTx9v;6L2v)tY_(v_;Awael?GOwkRk~_-72bim^c-J+bkz=(yh>MP$%ZOX
z-F?%y`;T(__>Boa#Ra}8Uk<kRW8TjTqli%rOQJT*awAnYZTL)c&1@OllGxV#eI`mC
zNX>slMmZ{6mE7)4)e87x`9Tp<qLIF`qD|>8&Q(IYLo=*WepwB|lYKXk3c5A6cQ4F<
z?<j6CM!{U5M==a^Gk?4>Pvs&CE;WO~(V;0RnsZQ$c?Gsve~{NixiFt-S3TGZ18_D_
zhKj_tIjFZmL5n3LVj_093qXP21g|K8{ehB$$jt3WAtt$;ng!Gtr9c<llXBq=zoWun
zIfG3su)=}7YJ|*eer?JnBsDAjgj~+JofK)q-JijkB~1U&%%EPBgEKSjq8u_ssSL}(
zmaSG=afjMaLP7&*wS<HoN?+-k6iWs{PsSB2myph`4-_iS9V&yvB5WXajLYvEi|vH8
zMq#@W(t20z8ECb*x3M0`kH!C7_zg}C5N)zTJ&l5~>?+};xr|Q1&1@7k!E_pGJQbw+
z8DaM-KR94*2+qQkV}?EDBFiLhT)EJ!TU78v#siNO+PqNC#UI(}k(6%mA{8jfxOI&-
zUT(j383C#`kgBp`HLcf<!bn&(zC#w;$C$mS5rnv@%}JVy?|@`)b8}b8+7ecK$(pTw
zbiD+WPYx!klC?)&b)q<3R1V4F6h0rGOE6wTRe6y%-SBBBNwWa}WJ#D!pUPhqzr1Zu
z!c16-N&*_!w<ru%a68LInzO^{Z%)FGaO*D+$*dGnB$EBQmW8BK8q56buFTwiLpJC)
zXnA$VOPhu-fohl;#jbK$61(AJprF8lYu=z>wo|pQ!U`aspt6B<OtslYyW;^o{^k4Q
z2b>rg3jwbv(SkeOn}U{?%{#R?Tx7FUa#oP=Qgj<gUZPQ-0^Icmg)b{)wh)?1V|6ye
z0p1kt997oXft!_7g$)Z#EQ-gsJ;6qhrPs44gzEGa-0}tmau3%$qi87XpgtD3`DFw?
zmd4tIvKZsq7exmL#d&qmEz?|f=R;G5T+Xtsv>jFZIA0VR%KWNWgmG?DxxM)}5S~$^
zk0%g?oD|Jk{Ia-tUB*GcZ7~ZDtJJB!ob!qW8dz1(2)qA;U!Qtm1vq2`a?KqrXI%XI
z$#KzgLx>7g78Wtc`czfijxtR@ECis!iWX{anyt{p3c!c6d}4s29F)qTrdpiyzf-rx
z53qQA7;@u&ddj&GFebhW>d;taas$D4PL~xRYG-~2iHn|fdBK&?C{X`!1&m6Wg)p_O
zn_6%K90bl40zUKlVmSzYZYqA@XTE4BP=+GQ3We(*i#j^xv@dMd9f##4vg}Ym+4!LB
zX(}%|C~j-W_zu^m(Ro0jy=UEwkbs7gmQLW<l<@@U&a!9`Bs>!mjJd6E3R?GStAm2K
zNB1Nor$#Marm3)yr&Br}#B~>UNDdMg4%Iy4i_WSgS@yCT)nAJSciv=uF>0|U4<gj_
ztPeautTX@lUN6_uy2k4xV;Ue;1_ejc)$S~H0QWniV0GDAbh%c_aA*f8;+2Km$OJ7G
zb9IVyBhgyUstZ{T3*z8ssSK6!S@yX~`OKT%Mo^Kgpl#wg<*dtJg`S-0`9NCiAaId8
zKNnI)D#b075u^ZSp@WW`Drbe%lX7V`+`@8cI)0jwG&czNr~|>qD3#B#ZP{fxLjIPO
zm&RC-xk=Yd-1DLY^`O}1Fvi?620NaErQ>F2l%3D9%}FvMmQyu|8`}QrC}4UdUvWBx
z)0sNJ>T~<O6%xOs;^JC2Kfz>e(uEfnyDUi9;ukw3RR6L9Fv>_+PS?zEj!Gw^ZvU=p
za-q{UNom4uZ&3UU71o-UGrYhwlcYoym&KcrG#NWpNqQA-cv;cl1(ibwh3Cp0lIhe(
z3|U%6!VKX$OjNFLor@~#gTlebe>W#_bh4{*bhJ<t9#RvRxtw%$ANRS<35`$iZIU)t
z>a7D*<EaNU;pB!tr}(gBZqYNzTnJF57clFQmCo(8$x-~=egbobuz?2!3nZ_z=E7r`
zaj8qv3rp5?G9S#@klApdBx#BTeqSSD%1QI#*-YdwTFr{ZllzdHsmnuD;KoSOC5!(6
z=M>h6Bt6n=CuabLIKcu7jD&eXLM9oV3k(Sfs%BwXa#^8q;Tjaa(iz%kl0KR*4i4tx
zK6R&XY<qj0#KE22xDjQcN)HN02fJ|xG76L|T!ID(?8c4fPHB9QGXvKd{l*`JeZUW}
z1=fN}ndIiokabdiaVgo1<eQdZt-euw3~I<3aWKLWCnBm*5E_yx&7?Eqk})XQ%M8sj
z!K-T5hpa3Xpl56!r0l=pM#4&vq-sOkzf-z-qNi@K4BUQH|5Z0G9IqR+b9)dDfKLVu
ziY%G5awW%k7^=qQB_~%6%#DU2AjziXy7!&n%dYY=<*Me7r-3#60Ly{Gm=sq71^G^K
zV|n7G0eN;ef*&&7A~GeQ>}ybdv*%LzDxowcS=}-u-c0Ctazne_S~v_<haqd=pm1Pr
zG$Ol`Y<sSBZkQY>9n1_$MK4Yc6`5`nk8jWnlLq(pt|fDNJC_^;jx1TVW7S;1u1(5(
zEKi3BI2=56bgj-LZ~6YDONS#UJRCTL>C!NakAns@NDxvE{C<B9PlqVCr^48CCvky%
z>ZzfF;^TNje;w1)e4+U0&J#F3=Xk^%F$Gt|wmXRo;T-zEnpK}?MUASOWPZ!woOIhw
zxVGLXK2I5s@&4Z^n>YR7;x(NgLJeo8Bn-rdFx=%vYPSa$JqB_hW&T2K{sM|o${NV!
zLgK53D|X^56zzi9<M8hng^ftb?`-LiC`takzf;~^Plx1B@|)?F!bbyev^!<&UQ$l<
zn=-d{e<hNCD>jhEb5mG?P`xANbE1q@rA&Q%w{NW42Km<QDbnEq4meZ%i=K)E18SiJ
z#i09qO%N~p_-f8A<5PGw_Nqq&#k93Sf}pdct3wy8-EPLW_F%!GI~i&(Ibj23u<+1D
zZucF#5&WUfvyqEq6H^K|N<nQOq;5>2J;w1w?`_{v+Hfpw%UE3~O-B|E$8tVeJucg^
znZlu(wOva{2ZD|^B-e;A+BVQZ`wXj8-6{4|g_0Y#>Gnb3KqppEIZzNd(si5dmaZ&b
z4ZZ2!wzF_$@yaCConX(sa<B?VP8HQGDQzt3%3_tjFL#PRcw*glBbb=mgSRFXrnX6i
zowhpT?U18;p{?glvZfzF=78NPCS7-$0FAQe4~k!&_M&rGH8!@@wYB}aJ%ZPDJc5+%
z_6XkcZNqH(6UAGY2QHn;#2pliGPzMWbZ#JUWNtB4x7Y}O4Yr)fdM^l`vN+3oX;64A
z&0-~-GG1J01IfQ#S-i{|oUDXFFX;`*9GtIE=2w{SN7h$Zlu2D>4qvFW06N|#HP|qR
z@wE>Mv}v@c!gCXOO>I<b-lR$S_Ey(>vVYthndui7PT)QJy|sa$TPxbUEtB!PF3V*6
z{)MZs%?Wv7aa|r1UYG9#Hz_c^PF4q_$X<X^PHJ#8Ukr-O7kVxY2Be(uwI;*}4+_S{
z-koQdW1MqVl{2g@_K+|GZMRM^6|q2ORso|y$*?%-F@A_)rrIpOjD|CR%At|Si9=R1
zGUAZkii|k8ix-*&mcm^Rp*b??A-;=xyU*hbRzY82m$?xO>>swpL6P|pZQ2&`;h#z5
zcBi@V)Kl(e*^vTAYa`x_Q{I#vO*feDT3`!{FcwJP%B}^{x3b3~n+()gWR-cG{D;Vv
zRolu6Tw(g&oW$XI?&wR|dF-l2Cnu@~H&$%QQw&o)(=NkaKPcv~NNCV?fCb2rLf63{
z(RIL$qbnt8>*xY!6xpEce2_nxu9GCzz;%+unQ)(w4W^9SwRQXW1s9m*>fi$DVc|2)
zj-R#FnGUh6z0Tgkm~^jX@&tEe`H8&dv9+N<oQb2vFB1D;qO<R5l%w!tfiKp%`<F25
zb9C++m9Hs%Ci?cAum}=~W)S>hE{B?t@Eo#i|M0`bZ-$?4<YLkr$?wELA2ywREMx+Y
zASwP3@QvBC&|5br6+8!QLE>i)o%En@TYAxPae54j8^ykJmKJoJnjScFxRlP+Z<y{W
z53ALrcDE?l!X!;OY6r!=$Y}T^cuyY1Qs@ZY{0H<X<IQ0ry(*(+W<%zx)j~c4K+3C~
z;4xhOAr~`F0u%b=&dyBG%Ty`sL7Wec0+Z~r^oo&ym!&{3cP>k1u+%sYBjBRDf(CdJ
zOpMc=&xG2n;%pgdWVz{eVV0Oe21bRU2r0-+v{%$YMn0JCqxpcnRnZIC6S)-Lz#2V9
z!D<^qKG0w+2UXew5f@k&-Qry*+?8a(Xl14{DYV1t#d|aexWT}txeww__y$x>gv_8A
z@45#ZMUx>%=oXh&#N2KMuw<t4WY~C|R1uy+rcju7y&3e2&%a5CPeIyTW_FHZZkRZ1
zaXFYGW10?ekTFdM9Shm>ZSo-wGRWx=J0QZL?H!DHqDJPKG9GBeB_z#`OGug>PdnY_
zr&f@7rcNCKm-MF=kQ9PdG*tGV6piHjc{2MXGeu?k5uN5x+?af#(5^vgh$HJB!OOhm
zObZLsmUBLJ=qcMzEu6C5=f97SgVeZAxvmS?M8Q-Y2#GOvmh+5|IoLt6=aVQ<k15YN
z!{?ouJCdcfF;yfhxh69)#9{=Q^o*!NQY^+%8X2;n2gTnu&-d7-=)~;#9tvM%Rx|?~
zkrN#ekeLY>MRDqx85o7iSZ8eOuJs(69F7;WBM^YOIjK!CnoN|AI8IbI%tfkJXI!cj
zE5{P^=ue2t&d5|oj4+LwVW&!>&Z>!*mHkkpOLddvLa}64b;P$at2$y}GxHiEP&Ri)
zuR^zBa)Y96nQ9#Yxk$Cng^EmX&_j!qln(oeLVcNQ?V-RKi42Mq&P-$|f<0jN^&sKI
zRK_5amyA@E`NR^fNBdw8H{B}K8O0?d7&<da!O9jg={gJYG%I7F>MGIUv?|gbJP+Fl
zcq-&O?4GP2nPt+nl9CM7CS!|&#JTYqVdPj3oAJ+BUlZrEV)7v=l^US0C3374QJ=fw
z?R|aB4A55&P@TERG=P-ri0d~Bo(gBXk*YuF(u0^{u<Jq2hC|a!N_WW3U&h3A2fk{M
z+sbChfN&fX&Jf{GEOoajy*roxpSHK@wJpc7#OC`~++o$A!ds#wN>c;w2JC^+-RY6x
zNjJI-7%vB1M#J{M_Yt|)(mppL?t6K&sshM*;yse6k1bNvB1v&X*8-UXMtT2hjz}VA
z`w;BUP!eU}mCGb82COIsX^}Ztt4UalTYe^k8|p#Qk8(Iu(|bn=+qf_Jo?vFvTRgm3
zIJNRr(8XV#3cTsVPeJ#5`6(<3M5Jq$^UWK@*-DOCGDF@COIis18`^#NJHA2bW4`9Y
ze~6yx$H%D3nL$Cv;Zt5)QLFUIE0315XWpE9{+au|)5#9kUpg{0-FD&r&~(|Q_k;2V
zg#Wmq6|x2ZR%07*Gb?H|8P$>9DKDBXr`@B3T@G*a+H}!`7ekXlzXPq1@W<=@H{|~D
z8+3!Kg1q9=Z@o6+Lo*+Dj8C^nx<@oUhjh5o>B<Q2_T%hVJ7Y{VJ7b6v_7dIebU%ax
z{P8NRbfHME!wV$3JaQi(=tOJU2VE|Ym3{T}cub&qMW}2#MMn8954XupsaeN=_Y1KL
zM^PQ)oo;%%zV$9gQL+njlzczoexDwvoL{`HDrX-&^24E2?c}h#rnk{|vTFkIY7luq
zDt$bZId4<wB8!=7@{rY6Lk~chkLmK!bnWT%|Kla6L%KFbj@ilDA0EDyZXiwfk_QEx
znEZ|TiQr|T;nIQl0O6yoM(AzKMS?t50<#PdP&3)r1w!tH`QU|))<w<0t@`kiBTTz*
zoO||h{I?@$09qw0xQn%OxTmqLowL2-Nuiyy9o98Dp>IkKNv|)x{`T}`uZZUkclV2=
zyL=oE_)UQa{NXRxbv^i_1H2A*MnE`+dwn?USNgK_bGYM@*Ke^`7!g7i+0Lj4GPXXd
z9SXt)a3u?HREkSbJ7Xynt>p=&a9Hda0zu6%ltLOb@u%94SirkYr|RAnM?t(i|9Zn2
z`tf%LL{KT(J2HZy4`iF{41G|^7A~Lt$b`V=Fc<}Am|HI?wSOWo<^_v;ffWIR>stFc
z>hF&eM1xxa-_-?D4o&Agb`Sz~fD&sbZJh2lI4LgFifNZ+PVL~7W-B_RAFVilfnX{+
zlj+CP`2$8$DPoqfQ!0PL$SJ%%(a{I-Rw~j^Jj*v)C1-%4E2v9+_8F;XuozA1EXKK@
zz%e{JD3C#kJ#masbQtPGvkw4MADV)=Z+D%(^eO622q?l#d_Z~mp`(tv4Jg4Mj$b$(
zDF_duP-LW@Gw7VC`K%%14i4B*+}1j6d`JO&Yl8;}qFY30B6b}mYywyU6z~YaFCt13
zi!nCo%Ls*`C`t^MK^6F&LXG*+4*59kh!=!#I;>=fEcwb)e&Gg@zsZPL(udQ%YUsRd
zj4*dUdQMjj2C{-AJ)y2D9j+7(i{cmeu6Kg=K1|l5oX#JSxG2<lbxcZz1(SlDlq+te
zTzbZHlTzFmy-hkXJ-deV;+FB+s?1y>V9X5GCWW^#?wYX_^QHqY9m6sdT4fuEux8?3
z5!S>!DMQUL#u_ih2q{9tLQ--nWpsE_I16dc0Qa2%_jm-J3S4;T(L)ai4SMwG?<HAW
z5XU5JHCQr6f0Ob5LE)e~L-K{xO-e4b3>6QGvv-E=JKW_m3pV~Faa9--Zag?7<#5<#
zGRtyfa6)ySyJ0-|%iZ8_%=x3=<b;l`r(f50IFvIp{o}-8Jmu3XIFq4UtV!t<YeXMB
z2&d;zHq(Im-pbGbSZQkFL{T&O5gg#qgH$vIg~~j02MRk!piEl24n^~ypUHZ#m!HXc
zuqTSx%ZsB+$3#>d1pxived+`WeNxal!;D^!BKyE4%%wTf;ZmVXpA>f509kM;kGT6)
zmzkG-noey{g!*VXqODe08gcK8hnBm1qBL=s!Bu6leNZNaWf(@?p8tL{nSoW$$#y7R
ztVP(@H$pyaX~0>fy_X(M#&*kKf!8O}X{7V%?iBlDezMj6nECvIyq`MRXn(9}QpTg5
z4BtE6OY}m7f#Ad&7U6uAxa|6TutG{~;WPl`_S9XElzFqX_xO~6KZLXWQZb+9bJw#x
z)?#xvVZLIqsu<&&2P^j=P3?jB(Eos9&uQBeIqkVWNt*9lM`5@RzwNQ%g2ARcGAZv2
zA6@)VJ`K4)hI~cYKezGN20<B*Z!||Z9-mUW(9dz&$>EIO4bUGe--Ww+mUYJ9dz}8*
z*g;^6@k!757%%?*;5A>%=G2H;No{6`@A=>~DeJ*$h~c@OTb-mc3Hub9>v5d0owGMc
zS!V^KopnF<DJkbG+AXhJLqPHEh`bWcsGj1GTyF>RUbXf7ATpJ~^N3FMXq_{<C(M#U
zK@iM`h*;&JGmw&zfh1~Hd6!3l5PgWFJuRy~^afJ+h7MtP;LC?_)P~rpt3DKm*r}_^
zZuTG@)givcWuH}tWk+?0y}RsPb-0Aom6o#XA)C7Z!4ExWwa2(g(ZK+PX+2d|QqHu;
zE?Q5WHMdNAOgky3``9&7Vq>cMW5)B(59Y!;xcWm!V5P%b?x{C57nH+W-WAtFhs}NW
z)M1m7f@LItT{nT;QscQ5l9BOb1eE^9#&~BVC{He~^ceWWhM!y22eZXISvf}*?j+04
zCH9cc{Vg}MKQ1nDw6FQNxWs0jjD+=|oZDOO-1)d9<vyLCu4{{D*>y<kaZ}88)}!-m
zXPqk>E1k}<-<K{<JxYg{+{^3mlKXZ&Z>?>H!-(|cyxK<M9^G2Kr<cjO{i2qbV;ut~
zl&M+o`@zoM0GlFqHXGsLB6jw2Y$q5#)x2)v;S;0V{QiU8f-W!*>V1yDL*bc&sBfDz
zPqmdjEmf;M5=U_fa!Un8?SxF-q+>F%mHDP<U1%|a`mkE`p3QKS=Qrz^S$d>A;)Y-)
zd-Of-OpA27&Q&nsvhgTj$5A7VGbV?N##CPRG#tgUG?ap;?YVU3A(!b%$z^J?q-B~c
zS<!L<+R@UO&rAC7#Qe919j#_=vST^R`R~V!gcP**xz!^f_}w1{#B8RknVic0upWj2
zLjNw1RyK3k@h(5HB;?GEhaqp~b{G$Ka;}aZHZfP@!4Q8V8*h{VHio5jQ;sD$C)8Pr
zx%7v9Hz!k;O(;c?f=q2#&!lAJ1KD+Ne;BoMGX34C{TiW+-qFT6BNxUpPtQ5r^Ne&O
zbKegd<F8D{rdNR+4G&B_v~0q8ScsjmP{?sC*?O3?_dbtIH-@J36b}a{9bdjIghwP!
zEQIsgq^4%_3tJCvbDx|irIXNZo`xn^Jp9Bo6={@sy$OomY+@qHIYaXa=A<m-Bh98f
zo^5)zbKa0*q~(@^)icB5^9d<FiSm3xijkJ*6H<({JRgxlrKO+g4?X_Si8Lv({^h_6
z^6&5OZJVOU$%=tX`RquvdcXt~<Cg6JG3kP`Cg1IH;L<)HKjL%J`3-hk{VjXqUW47$
zim@2HNfBi><w8ZYBNcDa!HieXaQfv4b5e9HcgvEVUJVt_3vTk+Q0iBD8lOktm_@z*
z8~D^AoFNBIj_-V_vJ)YIZ&g;>gOlX+y!W46q})Ai`$^+(`8gk7F1(Xlc|QHu%#><s
zF&9%BD#9>crqC69wWk|*QgYM2z5Jsuv6hBgQ&5ldqw!!UW=4lLkO+1>&N?&Go=2#j
zRk)8jW<_v-j&bYIM%+t_a4x`BT<Hog_(dF2MR0(Q5ef+g+=m?xGhjn5JN{(MMtxkv
z@FHi&6%0reD@3v+_w$^g1N`$KM|4m-j$zD(u5d*J&G0u@l5*XiKkDd=YYX+U9NYl(
zM?_shL-T%SEoQ<BJN{vK?z7_!)|v4()#iMt%YhwS81zHAh#_0X`%hxe9!cQ&R%hji
z0;p)mM~sQwk4qSW#@g}t>hQa^<KTs-M3XmHpUR^B<AaDVt54)u3~76NT_Ds<U(GGS
zl-g9a@vvz1APb-t(L?LfTcgz{{w(=_;?H7Pj-M7XtT0^1k4)4Ot8m=10GPAmbcF{+
zJMK_`_!%9bE@q9f<KOi74ZDB*W)T>e^GO`=ePyJRgIPq!f+OboALk_iAMLm*Wi;hW
zfmVL#snX<l^dL0Vik*IZikO$)4$2$af_#Pm_GCPn9|DBhaS_7%<_=0jY(YM7nnFYp
zduog#NqDLqzaYfGHaY!V@dlbfbJR+%6E$}{i`wz;!Lz8TmoP5aao!ovl<b7{ZVHjW
z$%GF7zy{li3&8|UmM%2N-(-qHT9q1Ihdf?CPwx4O2<dh_V30n_5JMHuqhJ4^p=0?V
z7}oq?hYj;1#})*Ex8vA?K=D>XHjH*<h$jrDVS~yli>FglbXq{a-w7!~71OpNe162J
z5;8q%$<RL_f*6)J(~3omE8?difvV2)eD`FqtRH$Bwc|sAM^47!x_;=D)2i_N(eLpH
zft08^$_JzbV<P99=M{wG1du%+rxA}5y(Q447Q)pnACvIHX>tgOH_qL!qDa?~cj$)$
z2(HX<0ExtSij($3FP@C02FhN+hx<qH_U8W))*MruZ06RBKyEj^O32$(SFyK@e~*2Y
z&L41+$)a3jk~5+qkjMVv`GI@l!}DX2v*Y=J!&{-l>AzzSM-SWtkDrIb$YfSg%sG(+
zKn|OrG**cfGdjh_(<g%P(Z?yLMCU*9G~4m}VA65Z%>d7&@f)1Ocontd9Ky`uis%lf
zt03eck&%ee2CpA*-P#ce-@LmNqwoixP0fxAE3Q$dcg&<*`6EmPZdQ+KxJx~%RZQve
zb45tmO*(#U4GnQNDmL2jY{f0dj%O=!T$wyl5Hcl#I$|~~LO^nu2KFS8kfh!kkq6B6
ztuz4fDx2lSDg%wsw=fwyZmPzqI)19S#T<7OBt44|mzb)iuDLxMy5_|c>EReD6O`!v
z_@yFAymBg3B(U2QxO^ZlUWDbuC~-G1S*?)TFQR**+|UXoGaO3~i3wsig(JstZBK{Q
z-21#XU3^cr<9vhnWIMh$aFsP1DCLK#Yn3C^qa9Zqq@oPUVk0?S$4?a}_HoByzD+~Y
zjEdx)cKmbTWE_!L(UoJijuR?ust=DHWOHTAS5VN99Ff6K2x8v@mQ~GhJ2K`Ffn#<A
zqs1nIJ@R<-M3P`TzC6wo+o7wchqxWz9_N{@3mrVsO`)_Z(rhDiZun%v<o8x9*GT@U
zu;$ruPhD6cmuU$8^bF#gKgua#tGSy6XoS;#L<Y`pU;=T=V8K5WA;3&=M)KS~QAT)d
zpD-h-8QXDRojjx&Wu$!AaVwfUoliUwSjUc|(Jb7hv@QZ^V8{Jv7IDHr1w66YMsl$v
zQ)kU0I)VL4jz|*<uJZLTHiRALq={6<3<3Q^K_*OTe~4gU;Al{KeWO^EsE<w_x-w8s
zQ{NnMp0OvCiK*k5fh$1}==sF&h-qjU$^=%S;{Y|GqqY;u1lhOj_(cIG5fpHTGqycK
zne1(FJf{%JBq)&i6F<Pb!SvFkZOznkk>80iRTvFCDXG#l#X0HXgR_)Js40~c!nq^`
zT@QvPXYiSr{8muPZe?YiI3bTa*MyR*3|EL(a|KBeY+^=EWE32t?L<cLEP*SSJTmzD
z1yXEDx`iRuj<pjN#l_nR*pm}b<aCHQKX#nQri&LgG~XJToDzMd$o98M3T?!$-(wpE
zrL!IOe4-nL%C$+{qf4C~N{+LllpUR@EI9sJJs&p=3d(mzXowx>HXuWcNzyhUb{xzS
ziTj8Xu*p&pSP?t!Z~%)iH2)8VwfaPfJFp$UImE}Z#-L+afnlzSIAfTrLe_?&Z*fu-
zUaY8Nh8HWE7=#xqnihzlKl}+eJMqQrIOYLM@=i(Zw4LyKRm?HI7_`%7C}poKWtVmW
z#KAhCTzYj`mM~UW29EFFGJG5~<SgSBeNe!|BODy~(0ZD9A*E%B;r^h6wi5?2ukmk$
z&N?U$Fw59fh<g~hC-4)FH_I?hx3~CyV3m8K^JspOvS)6IuAUEt9dnbUDWDxdIPfEO
z{2SL0J6!ak1vnHgz&ueT8%Fhr!id>Bl<2;pkUeK<ABgSj37CcXN6ZIH*|{)43%cYR
z1&6Y3H_Orag8&A!(<Xa;P$Fy(bCM*9-5*NsEZXfB&%Os?fk9&57LPt56B9XNO;@YM
zv+zmjV33b!YpE}8!KKb}3j!?i_zkfl{LPi5_Pc5WEOwMJgDi6Xa^D8*BM-kPiL;ga
zmbedVidK6UwtEO+hGIIIABpK`+1a76WrUTjVpjyTi`^cO0L4H$zmER)6XV~rB-Rdv
zZRXauyIt=^@rB62Pl|p+PS0=h3j81?r-)H}cP;(zDXO8(fR8XB6IfPO8~V|q<Zn7l
zZGQTD+70jnKu1v8KjrP3ugLF|N8<%<;4GT9Aww~TV*6H3ZutA$U|GWH@ceoE%zSD3
z8Zb+Ujrlvu^~N?X^KX=PhFx%OvM?WObN$d;<&zP-v^}~#GkqvxHeciT*!b8y`Plf_
zk`c`Ez07tIW!fK`3%{9XPl|$OQE6(Qh`_A`qrM^Q%Hta>Z{IO;y}VOCef@>D$v2XY
z8BG4tK_h~Wnq98v`09)Z&yH|-)!!Xw^&Dq;;^MW9$MmIe^g6itvUU!8hO~dDNFc<p
zFTSH465r8|_(6>QcLF=dCajfPUct+2J+e4=QLRr|3<^atHc=%=;*CVXp9@~?t)OnO
z)b;3G+z*J?mtr}d%pU)yE<(Ody2yh<osEpQPpU^ej;-~HVo=(!l`B;+gk7&qdItt`
z6fSnurP#6APQ?xm6jpiQo{qXYLUDYWqt6N#5^X?l!%i6L8y`R&pVU3RXdNxm7~<`y
zntZ`J>Z{f9Nugzmk)sCV+3KMxTXhbd8`{<Tq2L!7gKOx8$tzskoJ!<|)l?-*+GE`B
zGhh7PC}0I8-g>x+rmi$x+No;~o{Tn$*Fml}&n08&?FJJsQs{`yu5+(Djp+6yiaN^K
zwsY^yO@jbq*SX8(6Vti>nVoB<>TpQdR)`*kMwnaZ=8X{T@}xQ~7hQ32uo@4lxSL*j
zAUfAqGn`Yr;_`jyT#O$-Id$-DpIY_3q?;w%;4!AGxppp=Na$%*%Yr>-^_T-1Tjr`@
zpIOyp;d;Txo@2n^vyE&Ve4{y*6F$h$GIIUUi_9^f@creOSNPgOOU_QP#VmV2`1+E@
z70wOrn99;;Jo1!p&ze}lhl1E%SDLbr3yfL#lJIT{Gt0kY>)Nr&@c=X#<uD`1D#sb2
z2CC$I)@3i`gmj9YTQhPDb!?ctaaMqSItkv5r>2aGmJ!5`;gPQvGEL?S#j$4cJ>r-=
z&72bU{Kz#E=SR5}Zj{nWuPpL-8h|-g3G&u@*lcOkKUQ5@@Q>w}7J4KiyhuVroKU=J
zJZsTj%vG3Ts3+KjMt8H57Le?4&iSmNyvW994VuL-8qsAs=iiQXoh_OIf02#1N_m*R
z{f2gO&ic~yV2?LGWGt4}BHtHCe8j-4V@sXa1MbZ8=D_`oDPlu-+UV-~`LeOUvhxx`
z^YD2sNn3C}V_<VOK0GVMUn_WF!4$Ofu7N3Ncz2%9be`wsXB$bGuJMP?!1GuHYo{KV
zaQ<E&=b<VOe&%!hA@OmZyC8-#!Q&5!#P}#U?e=jV)F|%t2uF#ZPj*l{Oi}rutmJ#*
zR1^6Vt{LByl^8FTu=Bu3O)e<VNM5Qa-zceNpJz;{_~)gQRu-N#NojoP<Q6<H%uDU?
zg_-McUYN;$<CCc}D4!Q*4&b~nb16DLEu?;H=Y_d3q49Y=<~GZls$RE|AXo?dri_pC
zLT(Kq(Y8FuB3}GCnsJ`pF;N50?#>!~@aM&V-bE*e4xNkioNx3cvPbIWJZ+l9D}sX@
z>;UpL6I{TA&If*wIiC+a0U4n$O4X!z{)F?vCuQBlT7o3F!aS8t8YNs`h^%1x>w~^v
zitK~XU>0qmIIa(-+CESZqtA++6w6a65-u^1WoX)0kjNsJod@;Fy1c|Am!2neC8E?C
zk7_BtjqlAT&+-yDXQ;CWI4ASV-vZ}g>F76N(h@t*^XG2>*Mafe=sjXm6zLd3gpnZz
z74v!~g*;<L)9HgqCZl_Y@!iRy0VQ9iYX`&PMvi(^0N&ZsN8|YmA*^!3J5FzDf^@zR
zQp<Yb!65Aq!OWOGG%2~1MdRapwG_gxlf9hcrymR;+@?ALNN%bhg5+?MrW=Gwze9+*
zxU*nTJnp5uAxszGbr(r1e}pyDZ=Qdy%9z}V(v<$x0l+l|i#9k+)b(JF=)%KX0#Bvo
z&^sd2lwKeuSd;1r{T&2tG(`70@JEB=Lc$}h)1Iqv+SYMeD*(9BTY%V2gKNNncN#nc
zt^)xzx(3v26^}EDS8f@Zi`VZYBnDP70E`%aL`FB_`GrO`g7>S$KEeA8ufD%&&nj3D
z7wQ$mae-brZ3J{GWp0PoK*L0mx=a^Y&bek<Tw(Gh>@y<j1J%1J^8x(bWg?FGT}>g5
zIcB2r2i+BoxO~Zbf$k}|JM`$26;A;BLs@A);+7+nURhHSpw^fR!7{{`DOZ9a#FydX
z+n0dgTy`AP%Hyyp$(gLPLfSW6?gg}$xEyzuvI*hpB?*PAmoyyV!yxdxJuvhb{_imK
zo6-P~KRqQDph~O=GcN<iC<6Yop(5ZvCU@j9c^#Jn6O3N+K&W}b2n?Wk9sdH&7s+_R
z=6S*kHD4YK=6vF6Kg#i}SZN7HaIxclu_?LjbexY$ZxAdlqK%ny_}D;RYg6W*O`<;t
zG>m~WzT#dzs+?IkHH78gG^va#UlwdVf%R`qmdQtl3?53xN-)CrPqKP|^G{~_fiwRk
zmPa@<J`?OMIzsh7S>p-UKRMzDJ?Ewt51w<n^$j9Sl>&ayDNg6}px@i$C-k4<2<Z1V
z=~QMw?VFNqZ3_LTxWG*el4S^sq5!X(Bp<NOAJGSl>)9W!Wk&CSlkA+))8vq5@E15q
z%Mnd2ecFuP14V~zx(}pN+=X(?lg?WD6EK-LLao_JCO+uS#;eq2^e{L%zX$!<bh{d3
zm-1g2nUZcJS-@pVs67Uq5;-|^Wy9@=9ttOa^{K+^5`7v@w(3VMGD?3q-H_<%P}*6&
zA$QKhaZZa)-;DTXCt)(3AIf=iAM}vZePz%ej@OkzcR1Zw2EE@JO7K(E>&9?-r#jon
zF`Y9ygl;(}G(F)2elfaLlyhjO*e&+pBo|eN^X*n4-&{+#iYrK*l_}q0PRpe4F!$3u
zzQbxK!#EV`{A0>3xTu+E1^>>`lm{n0->c8x(=nQxWy+sgJ<y$+qlKU^g{7F}Tjr;M
zt6HJObYy{Zj(c0-@w|@z_~I`xUs9$K{7z2hL4l7sckGgnIp<>GkwFgaHW(>D3U!3c
zJAUy|-t5VD-Vh=W{`D70YaK8Apm=|{=^Mi69anxEC*}Yj%*Tm30Cqg14uBaXqd8#*
zg3_`POpO!8tk4CU6oCh%Q2U8AQ0_nfNw56LMN%*<OPezqfggTj`uxFhP9Ki%D@Zwi
z{$M$$Pl~svrSbL$J2`#SnXf|{4|XzO!FaHv7!_)WaV!uE(Y!nYT^Rjm6b!@YKck2l
zhB$*Ks)ji%o3|`rUKI9YeriWqq1BGg@2r&#9foox`hy{c4>=4me8^#_e;||dMM8|L
zJ^0B$5dtP4G~%XoHG`-sglGk6<&RG9jHANdYk-6}70~u>y%~FD01chJ4h2y8e2rc}
zx88O$mDMKXX@nSz5ncv1YI+6TdQcUmKKSX0dJ;DbZ8KmxLgdDXha+xsZt8=Z+_rj~
z%QVkKWyRitYAIH7Hi`bV?P_%6{B=7)f%sR20D@xbP$+MiFb;*K;7Lzda8|mdA!n4y
zOF%Y|f-fDg2t0X$B|U$Glivw1y`>W~Kbj&lSvW!|bkivgwZTwMG(0d58$(7Je5FoQ
zsZH@N{NS^h$>=4gnR&V<;S4()o{wSsGcuOBG5*~-8IkQ^&Bv&d;*U{hNHEtPGsXn-
z$JklzK|!^CDt$0v`8$O>qJ1!Zd6XDO45bVhb`Hct;dW>U1-^#1I>JM)b0}tP$2GVl
zDxZG$K6z0t7JJ5OI~|j9I?m8w{n2mko}-&SNZf}J%2Cnf4Bl-_?hQ&q5IcU(41Cxg
zeUZYcMeM`&=qV$=9R$-M@dq&`dvr~TbE0xZW$<<dLX=h9``Zr~=uqbG2ZgLL(Bb3Y
z6N#mkQ4YB!4+X3t<nOAFo-?wklC+yMJRw!gOcS}JV4^IOfiv)65xn$4;y!2KK^cLa
zfd|jocPLUo7<ur1^p?}B7k^Ri$H4QGxt|=7M2^M>gJAOCJOLP)PnxA8<>d*ixk)kk
zQ<~+2!V_RTB6zZ-Ll3<uFzA!Qp|MHb)*lqU(K0tEf|5SVk7iazOMNs0ij=er5jc;I
zCc@z_zWC{nhT{`gU{<4drGmE_)0@sA_F{i21ni;oM=KduR?A0%77vY{ljJmFY9uM`
zNQi7kS5uYwk)0~{r)Evu_w+J5%=eEIvDe@^8a{E_DM=|0?j50mulMq4G`@tXJC`W?
zo!~!x{D-T2?En7d|NJQFA=nWFnGRV9TJtae_2Zwft?A#dN%{Q$U$y_ozg(~K>%V`R
zA0^b0kG{W(`f9Iy{N=CL|M1WMbpO-+>gq55eEskL@Rxrq&Hv$F{`-IZ$N%Fm|MT@f
z{pH%<L!Yz0+8kw#dpF+3>;L@YKmPlV|Msf48_)m!FMquXo~QeE+WPqGN5RcG%Q>=N
z<TgXae8KHM{ICD{|Nh6n{9noCL{l$?tiSqusV}$BwoM0r#Ad~d2iZi5p>J>*PxfDO
z`M>=y|4v-CJ(X=wp{-iR>mPo<X0`kwleC|ZNuo5KT>idNpi@;PB2N6I!ib+VREQGJ
z&A(wD+QuG!y|@0|Klc6)|NY00k3A#WUW?nSjJ;y7fAm($>n#1lDM_u9!)x`q+rH-a
z51UIxqa#e;9)2{h{7HYq1Z;b-zjniGQ|(v2Ki&)f)U*};b}j)E*&87aoG#qRA1^Gb
z;Vt4+)8oXK)$W+-Q|pGl|5c@y+N3HqYL{PD%B=UCd=$Sq_ie`}_dlL{`~KXwv_+kP
zjr9uy!?Wk9)u}0eSq-4iQ%xw)FRK9|e5%#?E4{%Wtm&75_<Qre-7WrP@7KR${t+?v
z3{D|*zZ#q&*t@EkqQ8Gx4cCoR&1p~hvKm5PoodSU^JO(e%jF8N{LK{zOvs;n0p<HE
zK+w<`oKQqx4i1lYr<z{zzN~ipr`~S=h2D7OQnhmj`?A_hYX?_=<-bi`dDSUiX69+Q
z|9AyH?(eSv15us94PNiR92}4=r&_ni=>D`Cu&k$=0y}(J4TyqMO%Q`GtL@0BXZ}n5
zo0Y{g`}>{jk58bFzhnQuoyb2wjZ5UrI2DjW<I5`k*tom!lb<7S;;Et(ZC_S{=N{*p
z<!{b**#WozWUv1n=Y0Wk><ms&vM&dh@6L~E#UG>l(`tA7)Z5*Dp*PqgR7>`WuPS-k
z{W$$jGvK#o|8-8aKiTSkhq8kZfEw4ZUl<qST0iu~$H4wvVut$u5SXyKeSI>;E&6dV
z;a2_STCt;;_4VlHZ{PCuxA`YK{_oN5&mDw>`cNKz^)|Y1=`S{4^S|L5f1(C_hfM%~
z51S&Cuawh~R>f0IgfFWhG}x&o!k5($Mdefz;mc~}&KuFGcPQUjg#GaG^F{d12fB~5
z`)z=S^7RM<>iVol!q?Tp4f#<E<*zFxw(wDlgs-dlbDL!88<Stge0``to&E2~rjmKD
z9!!$(^}tpl5+3zL`Lbdy`SN!v9?I7hfjNCt6y@uR@DO@b6y+OhQD5h||9maJqm?l*
z`-4+az8)fQIgg5>d|eUI)*cl_`MM(F)jTSS@@2)qp1k#VDBqF|FCBDRU+t^a_}&er
z+NWdwP`(}_B>tnKC|_4ZN{mNEQNFH-^sbMJqI_M^=clvxP`<Mo`@PkEx*FfQu^=GU
zgHuty9AZPDm4}cQ<?D*TwLU6}@^wYCXQe28T_H0*J?fC~jWyVYwe|Bg_>Qb-8!i51
z6XmZ5mv8WoS|og3Z9dP4EPYv_!+3To9m>}g5iI6WQIv1Yf8RlLem?)-(Uf{!pJeBu
zd_6?OMtD>d<?D*@HF;DN<?D(7;XNvf@^!`8K8dnJ`Oa$W$f!SGjlbiLqf6NPmFLID
z=aKyEmjCI!MucygOkef?O<rtD`TS%f%FjlanHwJUn9AYnYM&l$Ncfrg<I}SZ2|ug$
z{&2(ccNgLQw|TlLH;~1T;VIGf*W>&Aek00H%}MohkH7SU^HP}R=N^CQ5vSax^XUO=
zQTjLTPLIXdJ{|vxcPBA=m-nX?QGQ~-`TUZze(5D=eSXPVzx0x`;E;8yjq(f64-1(P
zWoByhaQW6EtgX@h$*J^rShCmWmmCs)GPut#IqR2Rau(p-4=btv!h^s>SW{J-N}c;<
zwNEcO^Y44fng2E~IrH;N&itj9oZ0PBrQ6Sb9uZJZ1q4L-vPvC~3X#(0%b&l!+RVS_
z)n@+NyxKVM#2S<fVEm<#KBI6ys?Gij4+0L<{Hf;US9<&WlH<ShlH-W4sHX(QTm04v
z_<qUxlNI<oPJD;M{~4Sj0DL((B#1lJlriqhYIpn8+ueSlw}Hsj=gDK;zwi<<knDjg
z!16a&U~C2aU-1q^F4IZ$F}PvBGB^aJIMw?73lA;hv&uVuN#h-#QA*>NP)g%o>@8Q|
zUXRZH_7&J~JAd*G{9X5e&yPDV%GVDWc>#P>Jd|%-?KXxrEq|r_E1UibVmdxpeUN@?
z@qbp!;<s%6uaA7><J_0y`|UdiSw;5B2dfX#PmIm>c>_F1-?6CgY?;3_(r;~7I6FS~
z>mmKb9-H@#XVpXcj(v2;H!8m}((xVh+@1ag4|X4<U$H<wYl`w68|01y_e<lP-x((|
z6g;^-q_3?@i1GHQ`XGJBzO-Xm+0Rd*@2Gn;AU&Bqq_21G?<C2mL;J_a?^^$ramSed
zX^(z8R_9pftiQEf?9apg|MsXKZ#Cn$HR~+4UwG#O<?#>yucqfKVE(o?|37~!S3G^-
zQmmw+n(hxX)gE_ZDqfwsGu9To72K850(p(x>4=FZu}we&`QGnN1IP@wBX_zRO$2m0
zx^gBU3PQ^AS*1<q-5t4x+|$i+TKqHgyz65cxP*iIH1NnP{7f$_clsPngZj=WBr`)S
zyVIEnDTdq`4GKAhJe{ngY(1MmC;O$`)BF3%@@~op6_lBNXFlkcKJ)izKhI7dj8Qp}
zrP+x*Mp_^rywK!hv=2I(!`sFOEl4wwcs>;6W2T_q6!ellJ3bJ(DSUc-(5D<ZfnJ0x
z<N%zJWM)1xZwh)$(54RtTbdES!v|4MNcOV{*`FtCJ{VeQdX8#4Kh6p680#oJqI}S;
z8@YLWF!9@k+&nMJ{`1Pt=~9FYJe!cWEuckw&@&M^c%1P^f)YD#Y;M>6`Uia!*NqiJ
zn7@@r#V)6nWThvrk49HW_^SD!e-galUW8pJm^{L-ki^CZ!&0m);9Eov8z1x!%oH|3
zNRINFIOy99N5W0WPjjIy9}FL~3>$>r&6$5D2-&7#$`}_IE|5Ny;R&vkKIr}Q5&%AU
zCa;EBK`4oZi`<}bX~leAKGG#6lEHX~SsM@O-sydeOfZ`ee@|~Z?=<*kK9?&f7-Bkr
z?K?MyICLw|FEx|7cxSjA<a61CaPLA27w>d2Mi!S%K(Bc(^iGex@CNoyaN<I^9PjDJ
zvL@K(eR9S3=pCO4e4@QGc+Fa1VPpWTwZH+tlyt@pLbkAi0XqA_d)qr>9b~eVD=3(S
z^n>(HAH8zl;F2HIrUaXG(c6UBE`5jVxj=~x)0wBTz>VEIfv5$Z?wgW*msnDI^_3fY
zYm;I$o04nR)N08^Gc{VkKQF(pA11fP<FFtQfOpdXAd9-OC&;31>IuRq407eR%~w?)
z5JtU<d5EK4HEWPZy{gv`NZAm&wHyxhu1&~InB6q2e^JK}P(2=YFOYH%6!jcJsu%U!
zFgV8WDu__w2sHWHS_NS&yz>j)lwj_D)Jo=Vu?yMLZ<N9-+1nDokUR}v_9pZwvJ=Rj
z#-Li|h5%}dfh-CFhino%h6qBHls}E%`X<DRx5;i1Owij@&nbf1RLA)lZwh<KFMU&P
zOf5pdY_l3?Wq}ns+-^#+<EjOb)P@*@OlkwMDhmSJYzp`(ca-v|C<TJ3F}6uTNS#eV
zKP6(@d80#aLGT`L2t&0AIk}8uvMD*Y31u$@@~L&YJeQ0q<gKgcgcUfGtrP?*a%D~_
zh>zsVS#bp^CY-TFN`a(OZi#{nJC4+1yIivhX91BcTxl8#f<U<vGi*w-NA-16lE13H
zTa@68T@anhk>hTc;{#EA{{pW~X9m7fXs@Npdu>vTu&CdT4OGx<$CByWERbx9bpN_U
zT~Q>X1DxHOqygTjwHCxObA_AV6zun#?54O=RQOGZ*;gERf=*o_-Zv%qXTb9$#Sr8-
zQX-*`E9`nfLLX<i^a8VrD>nK?0KeN*=MavHeO@xfk1No5K}sKIj@MEUI^7j=ycCE`
zn<(uTT&zMMnv2;5-WaB1Q<636s-;3AMgZ_qQyL1?z6tSlE4uflq`s?^!Ub^;Hw8Uc
zh(n{ETWX0Cd&RZPB2Y&`07h31<$@$VuGGr~ksVzzxJ!lTvqo*cAR47JaCNB`1u_BA
zrufnYCfgSUrIgY}1$LA2O~BM*>@~%XE)`-;fuaji<+zzndF0A*g?ui^mE#KeyeY|i
zRp$_HX(_&vk`r6ieUB2m#wE<E#td<&2+XA-a)ir4h2~FJ=K2y&)ow-1L6#{-@uuYN
zVo2fw#O|h$Ifyb#O}HSat=p}B91DFjV0OvixItp)Db5svxFE!?Gv08ikZ%e&TrzO)
z6(s&7CcG~79e1(1G%>i0)uoPc8Otm+IY>x11qLn^S1!c`F7}dcl|gq3hUS${l7-Qi
z9YKFf%#SO6Z$VIJXZ+rRNYGyW^pTTYhgd^IX|F?Fr*u<v-h!7bM=aig0NAcryw@h>
za0dH^0IWlO?-KRyg1zPnvRe!hQ8x)^1RnetRkt9nxmPLGmhw<Rb2lM*Rq*<P`0QSr
z+J!t+*xZ7gE}Md`S`^p~A`Q91<`x_fUZrOvhs&nm_~C1v0_PUPEw4)RMqqv?@Tnk@
zzgLNG#QuL#P|7W-d`Kk{3Ty)V#dT3}b_)(kuhPA3L<xNkj!%j=PT>~?rC156)JWj&
zRmXurSk|Hg%pfgmQL7M^wV<>cy)}anl!}R4GRex7q?<p=O>nDcNXjb3JO!dF25v!W
zkJrTCDCX;{^zsZo;)Q2Jpa?diKmQ$UDb{Q;UK<%~wxn9&3L0CWdU%oY4E1DFa8khO
z0B^n*NU>1G*>H&h29Lxft|+nvNvSu5Jx4eeFH*muet8*e6UNFi)NbAp6$7>)vy*2G
z*klcYP$63jl8`w<ww6rd;fl0cpzM0#lYO|_#5O7VWHWJx7pcm~YPu;M<&G*i>X^fD
zlQ>8Sxzg16ZdBhZl5Kc_CJlvumo>n=-xX=nxHkj^BZfp%DAR&O7>-D$S5R`gt7<uB
zPI@qIOPj)3fJ`gO^<4m~azr^Tndrh5<8%{}KbU|E?qyzzx~4=c(x>6k=0z%X3z??C
zrn{V@ltPW96`KOB5E&|5K}t7eucJbgZbGc19;*woQ8<E>UP(#-gVbjvpYU4>G;&Y)
zO$8cH^p4x-o~$0yP~k^+ImVz6q@_a~-b@0tDKV;hswaf(+9Y(9(ope63(N>F3Q9R5
zSH}>A8A<d4DfZ?qy&EO=3X`Uyh;B;khTBof%ZtK;Zc+|LIyQ1U_$?J1wi{Q3(30kz
z%M~HCzy!1@IHr)P;YC3yS(i@TTbAxfa9TPpii-MKkZr*g^>b5lG+mt#$I?-XcZj=b
zc#w)Wb@C3Wc+<?hDFw(EcAS#&@>|L~Y<7N2c?Y!hML{WtC*8fnEP4WSZqoklZYkYJ
zrQo-e?hfI1SMnR8P4P8%Ij+{5gwv(t7I;^+3(=+^o7<%@m$0zilx%4Tyg+HF#Cd>p
zyQP@-lx}xX-!PnJ2I%;HU^!K2%@VfdU5<`Ne&<8+F*oJK%2@ik$DOu_p&*$B$pprN
zK0Wf^7%!~jLtwQ6<N3&h+ZRYZ2y8MB$W1|$(f?57%Yvx=LxC^LK+x8)^ciQ2{;^zL
zS3shmUXL_xjwJ<qSd?%8W{~=^pcLczVwdq%kA@kePCQz6DU~>b&u_M*7mtPs>zdUD
zzN9JREoLbEWEnk5i1c0Z9VbZWIX}fsVAuJ%jwNgK=)j0IX2jW~7@{oF2;;sfXn0_~
zq$+QS=c_EaJ4SB&p-__ranpywNS5JI;%FS~OG(a{=t1G^JNTDqM#S?GQ6x)-HXlnC
z>fu-)X~|>em3Azt$zx)CQj-y>d@Oy*5qW$pDar^m{-Rtc=5~~c8ZVcd!k!m)hSceN
z?c4-Jk}r57-6VFja!66ZQzUKx9~#Z**-6P6@vwf5CAApuykki(##8W%f>Llgr558c
zc~fv-&*$c$aF7Kr(wl<w2l1LWg&pV6H)VHxB`G$+%qsg|Qm+wEc~kP#L$u^gV6WRQ
zxyyKcD+pISgqJUPtRIRWSr9dMOvzaUvK<*5G8<}9WR(V1WT{5H*ulV%1z}t_ffJDO
zY$!BjK`_-ZWvoVI)G=kOMpV<G@R6I6=fkAA8Uaa%B1jfQ79EJZvdcN5uD(Z<G`<1;
zo4QHH$COI$4pyX01M)eh$#UQxOJI*mvAd?M*X~#o=-lpD5t*-jrj*?zPRs;<`m%k3
zKbfz6V#;N{_Sh=drm*vgDTf8y7baY)yDyBA*I-{5WM$yiP1=K$;_eGWfKEOk7N?YQ
zU`sa26`ah1gJw#fo{)S~25JP&+>~S{dKgpcHNtKV7uI5vVt!pB7>sTTjs*ZyHidns
z<a6W{NJ@OdPW>9tlucmokd7`<4RFe)AS`K_7De`)w#`jJs|Gl+K2dC*7bQw5AKmp(
zIU5+0syrbdU7s+bpl%9Vg?#i-p6C7&U5YahC&Q&UPY6es;tUl0aDCAeNpFWsbIxya
zxD;o6w=YVR^1B``^EAHwkzecuQY^abN*zd);ZmmO!04n*Pe?~^XWk(mo!WAuNrtya
zrQ}U|Fiyo61*JG2hD#9!3S~Hr*nvVBE*myrD8psL1`K8Rv0+aLKbH-ALioAV=>)6{
zmo^PiGBPNAjBsJ=$b>yp8oI35b76>*)C)3Fn5?S+iZYxyj<O&Dfw3wp<(tchjkwOk
zWyDUgeFe!`DOX9~JjDNSsLw0^jgtr3!(hgXBpE8O;}CH}`u57BZ3tSmDKWVN+Vw*A
z_Dx_<apN2E1T0Xh#*h{c#cK#*RS-!08bca1@GC<Ysj>*W_eZtx$ve8zN*Qwn4eJjb
zbdyl5QAu~6RAiHc=}oB@6kdA}jXh}C0SMV1Br-6v$iDMq4HDo)1;CgWO{+QRFDg|k
zu`xkmXQ>bbiJKh=nV@mrQYe=DC``-2=FylIenCsrn&5MubxW}rBre<p=SOowhJYYJ
zVaqH6K_LSZtRvEP!Hp~k+&9^AkhDdCk-m>c75BOq!NtJhc=eP4L`{%_r3yq%P_n<8
zkeZ<6fGaRHLCW4LKs7It-Y;t2V1tzXZ3>3R7mRur4lr+P6<6aRV0bl>StRAIAYd%K
zo^8_1Rp{!jaCn`s=k=}}U`Kxy!|NJw<?wJxtH9s{1?ooy4Ch5_Vxe;TG_hb=<Y<k%
z2YCW3z&JrkL0W;v2@?7@4!3Cr8pmO0Yz;%<eXYXxC`fF*aV*Bx;W>?D^cA+Cpbe~e
zCzn-CcXC<PbU$v{75k~nF`JBc?t!9t8{7lDnN_643DV#$7#vIy6N8ITIGDjT;L%c%
zCg?@Fc@M9Ns7Vr5%E{NQij#cZDDEm!*RD;;b#a~-o0Qwoms+0KhQ8GD!W8?;h8E_R
zDqH*{=T~Z5MY^aY-TYOI!*$)N$X2y!DCYO%w1d{jiWP)7RcjilHvy%XrB|6Zt4+&I
z<KxuHd6p)&V`kp`5r$rBe#1e-*kPa#5>Ais+k6qa`m3DS&i-neoq~kHBNtkb$b;dt
zkXBX`m=hG7UkSR2wi=r^4yUR0mPNMQxMY0msDRbHWT<qripP^6q3K30dHdP{LcwKT
zzcyi8e}llrDQg9OkGP^8ZFA-*Yo(&qOzn4phB+8nWd9VlUeW*H{;TSr!q=<L;X?82
zRSZD<3Oir%x)r1j0v5bbjMf0+1chUB4ulURwFHN^#z4tSRqhHJ_`cB>1+O%^S}1sl
zl&=MHmr(g^D8K%(G!BYhX?3+w^p2&eq~zV2-UUj}GLFSU!AszL1(GMjKwz*G#Y5PH
zS}BYNfxxvw7!Mj<D;`^egi{gePG2Oat#;GEC!z7Rrc@O)zE(<Aq2o6RoYJ~lE2Zin
zc%fDb)d0!Y3XwW^wX2mP6}cO)q~&gw>v^q|slwOSN|`!ftF6_tRImpsWokg|D}r&p
zie0^14zz3J#!+?k1M5lBFxidlG;!F-jt+(#YEva3^@D~ZuTp#ltbP{}7sSL7<mBKT
zZd0J34^vlz^K9yFV6IJ_QA`d)5z{PG!lq$hcoeCXVslh6;8|qf&V7czroR6w^LkJL
z$q5pfNtro#XRDPWbKH+=INAxpuXSaKtWaEzTkKF`4oPri9>0QyW2I7Lj$0f+WcDQn
z7CwH0`fFm9t|Wm8qg(~DzZxZL=bf%vN>+jWYr=Y>p~<!j7Ey5i3XD#Wz@-)PL<PQD
z6;ssUD_~$jVq=uAfbwrb&my@5m^5f)wBnQK(&>%jwKExFHHz0Ro!-*$A0%>M*nu57
zJ#aojAP)*?GsJ>XaLFs6+7`m{38(<_1gV3N+o?-^H%eeZ{;T08D>(nAfJN!%M(Nrc
z+NNynO?sp8B1_<ZwUH$<OwlUbe>Do%ZhXJlGz>&afl;`2sqY5iDsO;lyxVru;CQu_
zLqIi(;9kXqbHGvxfHe&gb!?-M?NZo{GPbjrJV^;R%1*q$$M`5bI~8-I?Cd%mjItB$
zq~PoX9o0nlTuH-0X%wCPR{s>8iuha`C8s<BHp%jokx#&;VHIu^5j}~oESnUgZM52M
z3eM%mi$HC>#L6{blakLS^}SJW3fNy;#mCd8_@t;5wttgyp;SajCu#Jp^3!Ql>YI@#
zS8s+TXf8G>E#)MzNgXY*e_lVEqllsDe$b3V<NcuJ7jXrN{o{Trzk%9#8Ev{AGzwk$
z3e<+weJ`41bE6Cu)W0^!(AFOn!B!KeBX96Q1FI0BO{#yR2yHkD8ii<+^4|t85v_>>
zO3~KD!j_^<*8@yykkETh{1qe|1&y*6&IPsc3M==5+HixFcR_8F@}cQ6kRT(FFmoxA
z;XY8YKZC%gQG^|?Hi}<)3)DvO+lt!dg|!upgVMJl4_R#xzO9_jaC$V|1pq2aQm#m+
z@NKu$<4*Z24}{uN{>lNN0&5hc4gxmst;-0&MnTKNs#8YG2cdRclI4R?aoh!oYIZLe
zvFV1;OAZ;)k9K*o8jh>Zn{)UfTp&dyY5tv8Vw2j?DYH$gf2Yh&SY<Xvp-pE5<QfYC
zM@NxuuHjK=o7`(REjNql7SVZgmg_?8EsGo-Z_eSk5aOXXES>2N5mI*(q5y$yRQfyR
zwVV!W0*J1lMR^Ni>tcd}*relk3S!eS(kX{c4z{&Z5L-tv*N+gW+9`ysX%;AiEl;#7
zX%!W5+;v`Z!#`mcF?FV<XBOG)<Yht*3bj+*T2(DdTcbYTQ<lnapmxbptC~T|Qj1o`
zz5gj~e%zcu82c+!?V!NeUk62~ybtQ27&RLE>wp+F$^Jo8u*u$E2k))Md%)nWRXzxH
z<gL|o6BxX;+WDdfg=m%fJ}5-tKu`z8s5}TN9G8Pco5!FWl^ek(C7*R_vM5I@)%=l{
z&Z;b$5qBjRt@AhjB<H_QaX>*Te}p<{>8<n36eMZY<zUd#D@TPoC`sX#PzNus>6wr%
zp&52Y+i%r1VDR!<bqyG_{ibUI8sg}54;Y=}!#!Z|{#vE<4+!5nWLY1SzVb<6o}nOd
zbiBjLPoWNq-|eT6O?j3$yOh54Td0691qBDupzy6}xVw^;TUzc6bwK`BT_6T6$Q4?{
zp#8X>3&fy6rawa+yfw?Ip~95&D(Mn2D5k5ODW4p#4vc}H;1C>?-12JJB#hX28V`!;
zs_VjloUS@!2IaJz8LCrGrzz(G4dc_ZfKyJ>siAs`>8d-1Q%r|X!&RM9y6Q#1DWq#r
z|CG{leyEx1K1rN%<gpJL`lpnZ`$Ki!nyW4mo+7yF6|p*Hu-q4_QwE3oLUl;iqPu}p
zvX(^z*{0?C7CjO;C2P?mfm5=U9PO5>MehTdPy0$5Cxl|P=!W4bRtsH+tJ54^vJ;x3
z%aQU9=}S+C>LW_|Pwc27<=-h*>BUezU4?_f@eOvXPv4zgOVf9V%%Yco#Ft!2L+iY^
z%H3g;Fnf9la0=I=&)?(Pru2f<X)G?h3OH@WMRx(meHShd)l;$-!z=D4<fbUn-+i%f
z=<oB+0vMSTt#oL(f`(a?aeq>_7U}bovb9K`pOCFZF2b9X-zoxP*2xR1yd&zQur0)3
zFgtLNC~0PjTlq)S$y+RZAL^v>w@9a-FaVeA<4O`f1L^e0U;HB7YMilyrO{7{<n)0^
zo+y$Fl=?}5Tx9j16v%}-{Y-%juZSxtxpH!hsFNaDo)L9YB;Qi$Cq?p2qyL0JmS;qr
z6v%XqsFRo7TUP%`5q%%4|D=?@rTfpGMSSLy5?S66k)=8b(bt8{)|(`Se)2XfkBFTi
zJK2`*J}G=}*8w^yeQ)PbD14O^F%onq+i_0JEqUb>Q4<<<C5^+N?3G^xQ-cSIBctfO
zc^3!>6`I0PIVpO>HG+A`Uq!tE%!!fe5n!f}y@JNhC}rg#Q75mpw;ll|<)s`PDp0sV
zIu*f_-T@W`X1F*oAN;E*`MpvyGW^C5rIQaDI$M;Ex1IqOrQ@x40AOo2=|UOPEt$S3
z8R;BR7bWAZcYuZa>s|H4ym()|b(dH)M9XKQF5X3N-2)b{qUrB&ftD+yH-bfxdFzc}
zQDWY_8Z1TczRz44r(Cy#)yS%jhSkWbo(UEO=Y8wsTl>IYa;n(ny%1~hkpOV~P2g0e
zY+dlFs0(nBwRFWuP}N#`AplxxEnXaem0I$vs6aifC1=D<%D$!TuYtbx5U}#wTyUGH
z;UE#k<mK9wJ<)4P|6h3!tR?k-Irx+I50uned;@qjG^5Cl({j1sfKdUE+GWl{O5ROj
z$1_)P$p@q6j4XLzR7~1hF#cm!cbV-juus#!-S?|RrQPluoKb1tl;n+Hw_)#WN}dYF
z9k%FPVYv&Jd@Bq)b;-NJu$?!BofoigG`AbTPD>sZ7Eq@p{|W=rX)R;d1uIW$|7E~A
ztyR@|#nSUrw}d$@`B+$f&Ou?<HMiF$aae{yu(X>fs$k%)h+6}5Me}dqjheOrxwKY6
zDfqg@Xv3bo#c9ji#U`=mhD~{^=Y~y5gTLL`EPL&k{QE*NCSLv&k((;Y>@}~IYc6$~
zB6SfQctw!J*l%;HT8g(NOrO2v;VzM@yn>$O0hX?X*CwGD>muNu0l%~+)NxDj(wcs{
z$laIXGY6Qay(NbVOWj~iSI4P6ETQ-eD#n5X#TAs8);ZKy{=H$NEevO<o4nF2`BPZI
znYt9h+<;M90^M1ta=Q#x;PSfU3$ZE5N`vNYr9=sgl>$~$QQzfcq^XaBscm8nhO8xb
zicN~iHT7FCxv<z9a866!6b2P~Q@~lp_A>Qdf6G?cbH!$=>L<V6b&z<5ctM-QYL?tp
zv1{Ot3cA6~dQDp9FM}`knnfHpFjz2IA?#)myAXD>sOOe;halbjQF45%?~YwZ{oNAT
zwB&MOz%^Z))IrEW>RSe=Y0=@r3Phq@F071?b=)ls_sr!>-E7&jgw@;S7?3aZ0uf5r
ziq|xyfb=QmAs+?7+mv9|ry7QQ^r?n%lU{VMu##<%cZf%KO&bKHAbN)T`f|A{8}9VW
zU0tVulnaId#kAbnaoQ{wuG+DuAVdS~w@W!fYU)<+C}n-vIhN3ShDZ+A3SWv{3>Ij1
z--Kj=I<-{@LLu@D_@qsN&D{V`TKR<qGHKC`BFedVw6_~@Nt?osOYVjx$etl&#*(we
zrsT9XlyXK*9c9)OKN7lDjEDAj3pCNIjDII%`icQ9T5ynf5n71CCFci2Y?I|xliIMW
z^jQOXw7jU{#$8p|a>v9Lu?8XMMN<Gd=S97ToO9{l1}p2L%Y*@Cv<Yl?<cD#q*?}QI
zsebLN3c)s(YNhB|@PRM{0$TETFxaY>JRUYBS8+@Y9FlBI@|S{45V%bUZpQqLKZxl}
z%jyME%%|KYHYLuKG1d3}yQD5KM{7{Sw!{}*LFypnfT&ShVv9C`z2x;_Q_u^-Agv*w
zyaj4#jntNRDOshqyeY{lKTFH{I8X9XW%ET%+3@nR2F>M$=b1HVEw_Bc2?`ob-sP-p
zcnjJj^b5&1y84FX8%<q9^bI*HTL6$Yfjy@gbqQ8yfEukq1sg!4HKbt!XS9YiY((f<
zLmD<7$(C?+mT|r|fjy<Xyfz63ltEw)s@MkMIHXToh{qvq8nB}^gq$(Jj@FPqZ4i&6
zswarYQQ1>UN2H|QpAlXw*Qoe=?&PALAsa{05Fs3g^zt2sZ5P?=z)mjgbzpqb$?*)k
zhGcNQ)vh7qx8Xr|jr&n6xx1sZ^F>MC0!XweI5QGQbOi}#kwMD!r6wWdI;-r}>r<nL
zfa~<3F$C&cUHW#$@>|MaV;K=}Q&5WO60Xh~uXkOlal(F<uy6*{&+0?9Al5pJ-WGuq
zS09=%;2@R|ZU(T#rm)@3NmrW?SiQ5&$~mK{dy{g`q)a!6F+t!qCD`xkIQ7nJ^~RP{
zGhJQ!b6`ytz;BjVoz<!IBJ$7bayK!6cQ%PX@vK5N8YWFzFQ7S_k`r(l@H?wZgf_@5
zA=NAbey&dZ`Yz|pR`lGVoA#={A=SE6=LWGRWSb@MXLYI04d~=e>LBE1kz(9DO8FrH
zr?a}$-R9uzKGOst*P-t=2WR@$8YEn&zS~m5b*Z}zXpUD!@d_c=mimT_Yf^$6WSo#{
z*7EN>;eqT~ZLw$E-r7>v`2nvs)icCin>yhW*0Y3lGvIYrqY8}Ct|m1Y0KV0z24_m;
zs3koZKLGcD4sHsj4sn7v1^pm0^QN#P2)aP8S;BEv8>frhrEQ3Lh`B_4T_ELnhI)pa
zYZS_{8JB=;hVA;Ipp;v*b#)A(*Sb1})N4|wyJ37%r@L{0(x*EFSd)6(ap4oB&EmV>
z<x?lQYtq4ij(w3(O75f_BVhI-bj=c_v&-zHbDPpuZ3y$TnyF_<ux6SmNU#<<H4ews
zDy^M{6Ld8y)xZ(2R@HUf_gYoIxZO1>*_Q#vyqdIZ;Bi)yb___)5*W?;j1p@Akh2<1
z)0>n_MEx0}Xf>(JiTz%UCg@E_R^(-D9fGXg>MI4AE%k)Unl1JObEiS)zJe4(0@`es
zV?ag=w7sPDGO6Ie?<}KsJtz%@Gc%xYmPup=2xpm8V`wAG{84A3P73Og1u_9iXVR3B
z6krJvX7D{&M$5B}O5TQgPElt=9pl1gP^W?4StfNF@SPRlvI~?Ppmgd$?<|u-4Xtw-
zlx66pOW-nN#GqwTj>k!N$!1bSnheqdBGRNBj}(#DGHJ&HBGP1$9uSd6eL0l)lSb2^
z<}XuF5W`(ylh`?Ar0`~jOT{wj%X#Nmfb?HU$z4cw8Q`2{rru!$H7U@5<}6~?UORPo
z6xlPbk0$jQx2jFys3BZU5}XcB%d(hq)1(O_t;kZwKLfO88D%(tHH){XBqg)i#{Q$s
z(?HZLlX)6|noVJ^yeOJPJZ{B7x%s2m3eu(luz68-3D}xd7hxHe{%fnsM2#ffOCUFM
z2*@gp85jQrT-p_s-Eoyk8a9Sa0V}XWyeKHe_7m955-f8CDNl{S%B(7jG>|f@5@~J#
z%B(7bv|E%o>xe_Kggi5ZuUM5THjFTvz<%<6SBFgUaK+pt_5<-K(AlOWFVdlbidn>p
z?S@jiRhgt=(pps}X_&n>1q?#ARmt7-X}yA!KY@6wGD|z8Ta{VbA>OL2(jMY1V^d!s
z<OEX~I|N>pRT_|+RiU552)HU0^vlvvxGC%zm%M7~8J9d^!wg}7Hifm|eY}L|+N9*K
zJgOywv`ZTz)~qVCbVjwgg496>2Bm+)e!Ga}GMIQbfn7rcRzbxLfSgT2-}BD&!PzeW
zIh)c^&LQdpPAtw9q{`pqW|WqmNSsxqqXTxciZpWA(^uldE|6lei!9UdZ{HMjwf`)u
z^n~mb?rT%>npk9(o)DfzW@*4}R+(xw*_B3)w}@3-69=fxD$>aDgt3aNcSz47Jw2c{
z3)b`fE#awT6{_jL*=zzkhlCB7nE_$5iq!PkI7aE|Go@*v29CF)RiuOCJ?TY3Y5%;R
zsfUylYRmwe*%X`}K+P<rGdF~xcu`OayHt_28W5UIA)}CxLX{Z+G^@y1o%oq-h+R9l
zZ|d4H`3<F<c&X?+jz^SX9ZA&7i-1D%rJFV&Fso3no+}FMe?i$TvQ#5*+$z$c@fx~{
zEY*O=tWwl!u9HyXo3c;|!(TThRjT+(aaW{?<3)HCM#eO}8gB~bb(JWwQHVpq!VIx&
z)-92_fOXrX4nmI-28iH3>y||tuj)$xEn5~PUilY9*$spA!Y%He;sc`XmOXkwwjt<5
z3@?S75L^c2%BFObV*}jMs}r<xORG+x!<8fq7-H;}LcBV<=7+R;c03++a@x91h6Oox
z%ft*Y$GT-=2H<1e(3%4fvIMuXHOL(;%*3_aQlg1#xurxC*K$jX2D0UDX9Xa~1lls<
zSZ=D!gt6RGnxlfu%ZpdNTM9FQEW&G9ggV`2_5!hY%euTE_HH_C+QLommPB1C<pj*y
zgycs0F_A3@MRO%7M<fM#LCoE-FSm_;xhazy(Jw0HfqK)p+z5TSX<TlIIlC!2!UpKe
zO^vz%`f@G7yc)4DHx1025+mfFlkr=P;<k9-1TeHai);}x@4nR{?u+-0(&lrnCC+Oc
zf>Y?MhM2&clIKGMyk%3^PfE8<VLymMJ{PO>*T1KxEG63{e5+x%%r(_-ZmGHE8C;&|
zb4_)ef?#4!k=}k$<!%71Yzi3*Cx<DdR>OBU*LYM)UIv+qFMO_{Zc|pxrC>`9n3lPQ
z8cty~S69OWQ`y<DV<r`Ty5SJoBu=+u3^Y`?ILLOnEdC;=s<GXf3gKK$(>ZetsZTc`
zROT`<x3Yv0E=;uy*9{PrP3kD;Y@7I4m^jlMEO3U8_WEc*5^oavO04l*G*oXwPH!5j
z8^X5FMLYGT#0%0~)TSGNE>ke9R(2IC(hWj$Q##7YzQU`t6uomnNp8TS%yo;i3Qq3d
z_={X)YP_2=bK~D^#iBr_QpnA@#8`^CP2q&3nA;Rien~kug{x|bX_<4W=UmD;7dy^-
z&_sa3nEVulb58Z1!f?*1-uD)n!e%w#Rpy**7x>Ig;ix*s;A*#H3{-(zdLqo}8UbQ;
z%;_4#0L#w41{l@{oCzE@1*P5Q;B~(Nu`=fn|0x{j9O`&rL___iaGX=`P%V}2O<~8$
z<%@z+?1b4hz7&<4!kz(X*(7#7ql8bpOpK0tbHjaQ&Zb5tm~GSpTi$TyY^t@uS`)Ji
z>@}2<H50Rotl=iy>Kz3f7l5$LNt1K~gk?^eq#I)B%&Exo4OvZIB$Q&ssW~^mT;{Co
zv|!$=I!+AaoK+nc429}+gD=w*o~r?&GN*)Th0${gi`5dQGG}?zN_K8B2+=lgGHBRs
zN5qC<U=wf_!E~@G>?o&sQ`l4cn7-5tUJo`2-Q-eEA+a_kM&zkqH`qp|FZCOz{d759
zHW*!|PxX{CVhWtqfLqxV@|ODQblqQDB3GunYC+(+i@yPW9Q=*s#>L)9tIKrPyg=L$
zR~3}xkH+eT^iR`=`VML5LuVmUNKGH;I@z2))Heho5m^mrm`wouw<R8CdRNbR;%y4+
z#3~At)et>rdQ+Y7WSQQ?>;i9169u6t%+;nOcQi~lyK$mA)a*?O?x<xq7)7U3({8Yw
zPM6Szb#)#fR)Yz4I(6-4S%p2Pt~uS<alsf(J>zX~Dp_~~2xe1oo+J!r6L4$+^s*`J
zs^*Xw<*>m-J%#9MFk`<cQF;kZmj;cbanq$jGqc<jOsfIhGF>V(z%4HdO2OtWz9BUI
zK2rv<shr`PlDm{w<OZzErm*Lbntn6DR>RxGi-bSNE*MKaL#!%~cuQycq+se{2AxU{
z-V73wxULp2HoHhhAOOeI6hHuu{Cw~*GzHpfcs!cJ*=EYV;bH``4_>}8J_x|!>KOu1
zIlvp9zNT<o%^>jxbn9zVVk*Z_XER1LG}#j)lKzeO4s*~p-3+hub96NW5eTGKYj^w`
zj5G+iL9=vg5O9M?>4vAsDGXLateZ_in_z@y>4r3)n*txjhIkyC#Li33uas}33!MUG
zZAwliwCz?Pu!pIu8YRpCo^0ok@|`f47e(JKqT9@&;DikrmpP<11LHDBc~r}pEaJ|<
zUD2tG7w<WsU$++jCa<`<5lz+broIX67x~raxYaR)-ni9q3cVqX9B7$|G~*3enaSKO
zNy;HoBL`Gw4r%29m6=^SdBYV@`N^*aXv`E?t0jhEcIw**&@=l|vndpnk-Rku#V++4
zNrX3r?LsJa8lg8O817WTTgb#d>HXh;pqZV&PxhsJ11>VVt6zx3E`2;uCs$C|Z*nl1
zzq|oHGlltT0I$3#D8(k|M<I`1rHr?Qu}K+k3uBWqzHv8MzWIyTWV1^b2Yly6*`-7P
zP31FhfXz&yy&7OMn?eO2u$fIltB9fXqC{!`oaX5U5Y1FJ^VX3Ua0(38I_{Xgsb5IS
zE?qs5G_y-p2a@J`k)l|!F4EOAnfN5AtaaOk{1=##hTSO>d)2SAzbXbG@|2Uj0SPm^
z^l2brX7YA{l<QR3a7esfG<XQSUNrcI`J{ZlTF)vtv#>t1Q{4t&Zz@N5OHkhg46FrU
zWj1DSX$YS;h2Cm_u*?R<Irr`^a%_-gN+y0ad;_!TL+v37XPaskqO46coBH!?G)`|y
z9ICTTjSsR->BTo?H>+zhAT6^&jmFtAn_`W$JYS}=k2e5Xrm$KK;L@pN;tfG(CU90)
zP<oV4ot!x-z&K@Rqiwq3B%Y17={As0ZX%m_%L9E1Y1M$B-IU5-<m7gB4cXS3ZX5u<
zY!ds<68nX8Yto{DbD51QGhr^XNoh`)%WTq_0dtvxXEg}W*`y!?;(Toq#{>b`s3ij`
zJ(ZGtQ*r?DVUCyZYXWUF#5A2v>M<gp&Q{eeE__W2Gk`FY3CXXPK$t0XR)hBPqC^R@
zugNqG49sjYO%G&!-z4@N!cQ5?8&EJ)_^t-X%Zn1FfzjML<e{uhWh`${=ceFXEmgkR
zq%sefL!pXo>n9Y&7wIEQ@%flk<nSSwCIuPTmQ7(Vz_x4>`+@8;S*MZo;YC4dZ(-#n
zZ@|AyBVM`z|1wSHX#ilRP4x`fXHv!CpfPRAKmsq0X%nR!pj2@LSDwmE-V(nuO)9iQ
zvzay?wURwrtZ~7aCMDYQ&o~}%KiU*3g1AIYlK~t4Fw<nfhR@8Vpr6zTryT<}LRwE?
zzM4axnatOo^2}tv#;tKOVR>^JQ3dd70I^IZC2t90nF3}tU|2SVl~S->o76$bDjZ@%
z&r*@$J~d6|>F6YF(=k5W(hSCFIA~3iaT;;er;?2~1Ye(mU|lUkv`>?g4Lr-Hbd+;%
zNQVx4$0P)+dB&EWNGra}*{y8R?&$VDRiabry$-2X<rLUp7@Ae)XvdvR5UNcH-l}wA
z54lzsu?r1ImQ6z6xU*Gh#{ja-Dq}R#Gfe@pu9i@iS*0%nr!p&bVW3o|GLN@;?^6CN
z7pp2vPlMrZlh9(gRPHjy0<X(W!9>C_b21b8)!@82tG)nXK%T!-IC#D&C<WUDVl?E_
znpLXsMAn^Ir3+68MkOL|$n7wN%W5-A>=kmcjtj-uj8#@?*ikoy{o>J2X~|ofV<&K3
zS5k6c$S{rUWwT0KM!t+$r4dg^Mc68%p%z6p0y$Wv{KAI)qM($_N<7o*J&D+A318V|
zoW#JdYzodg;8!+<9YYS*W2%M|^^7FsEkG`_N{<G{Wmc-ufVj*mOZ6PDgQdz$jfa9w
zVW$IQ(>VZW%2bl^258DPh1F_-MwwMs>IoTFWu-<cnpvqf<Jo0a1@&lno0-67wS2wV
zMRo%rS7o*au4Pl;X3{cY;Vd#;BQwurUh#(PJyT$<h7>=uKmlhOpjl+Po^it~OFiQ{
zr-bAU&tp^gtp*&+EQ;sX0A!g(>hvm6ViicaBC9o`xy%A}d(pO8WVc=ktD8zUz9|!x
zaKPYIaTb}a7c%V4BD?iUF;|8<hrP4FZjBfcvq&r>&crOlST}%XHidn^Zhu8OI}kAw
z8Os~+FtbP>Ux;`%m7u&KM#mJ?sv(ZYrr=CKj?_&#4W&>n)VNoV0vUr~REqLV$=TND
zj92Yhj)fX;-?K;o&*$+?V9y<!j_Nla*(dXuUqQ-UXZS&U+(icJ0MX1M1snjGSqS<_
ze9RRT98Sx@e?=+SlHLrM!Bqb8wjeu8k(B{CduNeF8hL$R6qI(OGDrgoGs`Vb5$Jy^
zdwD~C;VH~k13G3?aQY-VW)s*i@*}=TD8`cCvPc63GH=OwAY-O*Up*uJ1O@M5n-m-?
zRr#jG2Xn(l-4n;M%gI~^4rWteFYmz0%t%At0d|=;HRBGj%e<Y9W`T_5s$KIYcDe)W
zGL?nABYMje(yJ2zb5p(U8PsXsgO-mD#L*_9XUM{PsCUZ&4)tvq;2<)(6TNbG)q?N?
z(5q*1@LeP?5N&tUEc876CKHKwglL&JRpn05%iVtCFM5;=%hNHpjmm#V#IH?a*W*<(
zbqnDpP*=xL=WXa@Kv3VNe)7V1n<g6<J|!OS1i%Q?wJG5qH<ees6W$_7RtK2nF5(8l
z>@J#wiG@WB?Vg))Du;LnGI8Ees5`)mo4|e`%I=%+l}*aYz14RJv-?)hcmfnos}lut
zLl5tT?|nBl@tz<UUo=5?fM8td$UDA&7h0?1P`P|9wUgs>r6BJSanOam+U3pPrkrMW
z7n=f%Z%5?9P0F*amz@1g!60gKJk@mt$NYUX=F8P{p1!_ZJ?HuCi^_L@o!`D(ou+})
zm8HA`E#pFTb)aQl6qH7=In--tj+?+vTYf{X)aE@!nhW98A@+O?b<;5WBTD<%ouI-F
zn6nGD)q#ld)zxGNpIuFM@Y+$@)&^fqoTuD#<ty*N$GC7^9RL|$O+Am)w|q5qJz@(q
zbv&>I8cMnRrj9*I`9jx=gH2O?&neY+TpXNIf$piM1trg^4YI$YOr|E7(1#9X&sSBu
z6Wg$;UHCdUlWF!u!}uzil7+P^nv#XJ)5i})%%<=Rgp%uvns<k4>`bKDp*_3uX!cOA
z9dNJ?@QTmH3MuD&QakQIv-n)7Qsdw3F{PNNntg#38%Y4Ijys3XsYcU0;mCiv%M*1d
zec*`Vlg8;@Q;NBgU-pb`>;iFhL`e4OXcxI=TzM}0>*D6haoKUP3koJE<dh>%Wrr7#
zC-f=@nBvYSz#1LiM6N8A9amLXlFE+jtmB?`C267>&XPK!gl`;|W@moNjytu_E@nq+
zHLmQG9XJ<Pa>|}a7Z*aS1H|G?JlTO^@pQ+yK-zUo%{o?0-yF;ruAGw{zGlvplh>x?
z%9}WzV9!tr*6O3tobD=S7Y;w=r0f~CJt*vXVE~mQTEAtxH~;{1c~LGDbH5dJys+J9
zc<wMdxzbSfG)wtZ{+kZdl?%qz0cm+rP|78yy4<ZqiGAQ}b|oh7FrWFPs@%iC=1O6?
z%Q+Tm%A1nIiKurSRy$V?@}5wZAmlOt%Hqms*#Tv7B(%Je6k}0B%MQOz_pI^~eS&Uv
z;9cCQL=*1f%4699cX6NU7UIvPYA58ym7~0;bL&fK5Cp6vBZDgmc}Lm?7kH~%j}mJ@
z;Q3LLksiXC?6Sis?8<f7({AhnYIT^F9mdanP{ID}%5&KbB2I}eI}F**JeNH{Fs>Yz
z-GCNzfVnndq6WM6C~<U-nWS265PB}}hz{(EJC)@B^zk3Ay%X;jSFi2lwZEEpU6AhA
zmv5zg{KtR)@!vkm$Nl;*|M$QA^+LQhN8<9oe$0X?;MX^~s8mDe9@@UM#Ubh^Jt0nR
zSKuU|gMIL@TG@sx8Q#kKjt_#Z7qEz~%yKJ_R9AjB#5r{#6rede5|x$IYrS_GS<4;5
z**j;dAm*-jr8kEkit|0W;Hu<|s<HEW=AtR5Q$e6;Z^~MaDA=yJ4y8amDr&=3UTfic
zdn;ipab?LVC3m$OIxg@BbiMYJ3WeR3uBFt}HyrOA1ql^h?-2z#4%|4`1-`Uyg3T0|
zp}j8sDD@fIw@aq=a60S02+#;BzmTh-Q&&oZg69@j-hqPWBA3f&$!s?-3Qd5ohH!2d
zWyEf&MLEOTm-afQ3S?-BR8L-bQ7lM5bvbP{1#w86er*LoQv8OJRPfmEH_ycaXoBAg
z-CL0H&2Jt81#x;@fuajwCVuDBOi8$m>ppiC<Zf}rFfJoS%~)J~gsU2hriB7<*H~JC
z0bJf#Stai)L!J-?sprR{_$$B;4tWX`e>M3?kse8H$H_A8sTK`sLB;c(U`(D`1<?@)
z{7qlSXMs!_62%26orm*kS!Qm?p|r^bu{{Uzy|0F5oUKDyiA!Sg2T#ZXg>)!EZb1~;
zp`)xUpw@;{sV*z+0|W8x%4&!{t(!qvjHbS{RTsd?nRg!DF~+zit=`Cqp4~?V@{dd`
z9^<Sx<62Kec-X16dq<Y;T;F;#$HFXXO8Ic(7lpY9o++f6k5clj7KYe&rcTME36YE#
zofSlr_me&VChVQoH;T&Isrc75HK0sZn;cf=;uwk!P%A@w4^2U3PAH)dYh{*+p(x~)
zNgl?@2x2=OgD`W|GRJ{Jh*e{Pfk)=chFL@Snw_%2n9imvemer7M3zJFWX!?RmAItc
znBR6XhcyOJ7Y?Uppq)&Phl<F|Ap}aKoQoN4XCE|XY!s-YHfE$~%z@IG?4c>)NoTGF
zn>1?I&NK#k$FH4v1Rlw@7`NY)H={?<cq;6KPq{fwLEQ(#$m@l+BLD4+l)qqhl6tZc
zjDacE+hHBdTB#Sj3NUhc<g{^Syr>HGQJo1Vl;6>j$>EVzg{c(uNK&1t3o=w~HpOf_
zd{wBE@%@Xw$I0YxkAxaZ5OV{hQ73b>oZJ!PH{@x+^v;=C3a|jsmm>Z@qW;#!q#uv;
z0!+DaE9J&gE(@jDg5I=))bl%rk!po$szPmAG6@;P&<Z<@rPB0_YL4KIOR*nr2G2hc
zx)H<o895tae-&rwhLl;l8b?^@HG`6Vy_oE!>!;xzC&C|R%O!)L5`1UH-(m&BEnb%h
z!$ab7K5!e9re{c6L+px2I9UYQdc<QzEJoxjHz-XJ%rsfU9d@0w&r)yNQ8&|{J}+%+
zC>#)!rX@tRL1{WcAuq$lVG%rRP@3LDCuYDthG~Gxw3N4ZhZc-u<{4bDA#k9=>P3h=
z%mK8fM{qmDBo_41pf)XKDm6eyBPLt!4ronF$vq8d*VRt2UZ_n=$TLeQV?@<rL^Z_S
zVQdYkO*`&XS_vb9)cqbY3V!yF&`t<hW(sr$)oBSma~WdTE&*Q*y3>-5YycUpsyH2?
zJ}m+?Y|qiEUBP1*aOT8W$#61?d<MN~DJhl#(6MN7{E@*x8e)iKLqIevJ^LEm|CSOc
zSt?EuZz3%Lme1;skP^_Go{=38^zso=!4$S&CdkHMDqgqZYeIEed>%49Qm$L!=AbsM
zo4sER=i1X>y@reN@d9t*b`AgdE??&?(~Vi#=o+72=qwC<>FM>0cXpX}TcH>EO>MT}
zg?dh*Y*Sl$x{T(t?8B)NURsKA-!gtpIy=H2tjevAo?O6h%7W9NC{2YRhfCYXH5K=}
zK~I_r_5J4El_L#BX)?4m-I}1mGz2UQub*rI3er@J<pyKK96|~~J(`Ktq_;}C$>^OQ
z%F$GI`ZvD~P<pzeq;9n#J9Ju*TSMwaQ<=~Y`d$b=s6|uhyRVH}Pw=<gx}g+J1s83I
z;X0L-x<MtHjp)tmK%_P4fHDiw1dZq&)ti7_jeO8)xe0sofT)5WXhhS5Hp8k+MciwQ
z0saI^{tmy`65%LB(n0$Ph?k&2DlZRs+%5^ECMfv>2nOH{UYM1qu}#3Kr-E5Eq?~x7
zi{=})h(H_y7zzLkQXHQsm3a^)z?cwPa4;N%m^i>7<p4bnvVrfSH=b9QDCgN9)=Ivt
zA3Hx^$@#hsl$8!RJ|XY-Vm|erM_WEV-FbtL$JE9L%X~JX-qfK1?MFbqPVx;;kL`FW
z1KcBCx$?QH^L;3v!ERap&jS!m@_dMKy)pwqx8FqO?_Mv?vjd+HWTdAZKTVkMX?&W~
zWw@T7t;5H#n^s({fJ~<?U((a+`T8t3Xz%q8d&$i4`iH-+1EYLx^vtv1Vf5sCy^NmF
zcec%Q@CjRXPk`HG_Z)v<_e_)Jv3u^;9#+q2{Y#@KY@EmFnN^O>6E>4$^~9t3!|Iu)
zq=(Uyb&k>V&F0x<kGg?W^(NztjGjcc9HZxu4f7a1VLu9+r_ne;qbD!;GI};Xo*b(u
z?Y^*jZae6Q44&Ht%9r$G^OW&bHctwIWAi*#P-N$D9)~h{5@slyCoRs$=E-yTm^?d0
z>9Kj{(QquD_B)FwZ&WgPBACIpe97XuWCOLZe}aG5JY^Vz&C?4X4Po=V!Z3;f(CVqY
zkurNKYvVC{!ZaqEr~C(w(Q~L0jh<A1WcH-Cd#s)nA;4($bj2e&W=~lOW%iU6Jk6eA
z8ij>kmQPt_W%<M!$nGiI=(c<6fK0RJwaud7UUpAHT8`b57HFA0dDS>pPk9u{>^Zdr
zG<)h9Q)W+wdyvsnICfb*We=CxbNtTiNuxMMH(X}%1&hu$je;B4J%>-VGjK|BoC`6}
zmEeXZ&npayFj9r}n){h1PXVfq$#XCVpbVa_XeY<wDYxrm@uXY$F?vc5JvPt5<k2#D
z>Y^>1r<|2#^OTSAF?o)Yu~c?X<vuue&;D-n>`J32ljm{uJT_11r^n{mxgy8rDF?+g
zc{T-;rOmVPTsk&Sx#u05r~K%S$+Ml5*0Onq$JnuVHj2cDy_3mUW$m>5%C3jG(`4kL
zxzmmTl;%#88CcfNaE-a1#?D8o`$r;q)RVPSz8}ZfStn3h$JlwYpUc>JGLLs;^u{)k
ztur9`uybB%c|?t4=u}=x89U3#G*4TnQZWylpka-~{+6v%dhD@vN|8OLP8lOTQxhpq
z@6*;PFzvB*-Y17NO`U?D!q$0xyyaY_u@f5ZF?HTXyQVCiSp#NH#jx0R&ZY2dG;^+{
zq_&G`7RM(W=UU3@x`19;!i^mh=gEai3#W34%gRZW23F2U)kpIdOr4Khd@;186J3_h
zliN;~&XY?+rcPO|py{vqX60m@9a%XAn1Ge@ibED1!OTg!VOTj8a8y=Kh3%G=Q&*j1
z<~*sNn3+d8TWICv=_(^9PT=cl=adCacFvQl2WC#?@SvTOm%K}c&aN2PG<0@_)});?
z{P>TN^W;5Rh{!BY_G9KeIY^M3p(`{otelD@x~-h4X350a6#ZT{P9=w+iBnN5W#Z&*
z?>aV4rU#OVQwjEH;WQZ#Y2lQ!W?DF}x48MVaVm?9Y@7-pPZOtNP{PD{E%@;r3#YyZ
z8aS&$qsqXE2&FP_$~}|zO@+(#{s>V``{pyWblNu+fju>(E2ApIc1Z)LBACm*$<X04
zZ$3l)hM{N`McJl(Q;BA1-jo4X=FJGwF4Lyq#!uTOSdnRypW(x@$yRCFtQ3aFw#f~6
zOq<W3m>G)_mcKA<D$>o3>)ce5-DBQVsF;U!lSap5-(&<fU_7=t^OJ!S*w3eR^8~l6
zif8xnX5FMc=3(BXSrYCRg8d!y<_U*(%$pwK{%PLiZvfACS$bsMq`&Xy&{dbLn{ugz
zc@wry7&l!ewuf<3v4+xdU@*wY!?t-s^U$=(I3hG{(xUsYY|az+g{IA%-DBCLA@i6v
z8TdtkMKnO!HnsdRZEE?yG;J~pz{9plYbQ;cGBGPk!-;#4rcIez)3kYowKHcB(jg)T
z!2C(eX7nPf=5d>+RdYVwztjC#{%f*o%Cb(grgk39nw6-LW7s@i%g65*bNn!F(v_0N
z&EsEttef-*M7*pj7d06-6@&rCO?f76_h<#9KgP}ALUv7k`m$>>YMjiPO?ygqO)b65
zngXrUtXT*fmsRs%L21^MZv?HH$AgG=&EpM3yC%)M*D-7os0)o}DhK>AYXWdCqox3%
zdAO%P1R(XEjtjubr%hANK(c8b1aT3*o@ja*H3fyINmE$W|G%}f>Di=5vhqHEMJ=Zn
z)1<%cEfRwS3j{PP#0E5jgk}~D8u9nJ?YPd#e5&5Ad8e9gsk<D{?ew?94xcz-lcrIn
zHfg?4-7;zlTx~?KT@5g55|mda%@>@vJ-}I+J!R9>Gg25eKicNAi+=m$>>I=R`A7Tg
z<D>shqbB}2BkZq$l*iDXFyn84IuiieB#Q-`^%%O#&txDdMp7V$BU(Dc+&Hw<CR^Vt
zgOJN)!1^nr&lGAIJKPjzIq4m53bL%D)D&V_Mypv)!dBd9luY~+1LR}Z6+T&`L!9Z+
z^#*YQQID?6%fz7Amuz4l@jsGp-`k0?T|34pkAkD?zD{`UH-;7qY?n{c+t?h*C|}0c
ziMNb-?<OHhhk5Vte)tF?u{*s>rSoz*#DE7M?hyao<}*CwYD)|;&4>B#ezbpsOm=kB
z8O}BiWQwcEa2!*tSOaoA_<%>(?GNkQI6+LW5S(V{CIav9a0t^MZ16mA3@h!49c6UA
z%&z++fF|DzR*ghdSWkNErow2wb*tBP6ZqcdpQ6ITvn*V3bYkGfy3<T{z?#E+dD!tr
z*Q53Nf}F-$>(HeuGui#j@cpwxj)B!4fVb4J6%2=}(fvG(*>rR*=~ZZkF5C+r9Wm?S
z#WhT<w`x3ePy`-2&&x+;(V(qxEgM~T*I*UjX+UY5gSRB6-@=2Zi#Pyk^8K3P=aqQp
zKpU)ME!;`Q?uX}>Fdz-RLI<?qq-hn-J8^`%LUQJh<DP~(d%@Ou4lu7CB=FB0&%k};
zC5US4e724okB^Hy6>b5eGpP2^)n@UkVoc-@4@r1t4wK{sfGh-2>QcS5B`h3tOp<rB
z`!GQsubSiV<KaO%6ft$1bf{(%_MVp>2Tc9?x`p6OJag)$aB#hjh^LSn<!ny9Es54e
zIq5u)>0t{U7@T@~LM!}86+sJ{Q*TSo47DZVyN9=9o1=k#1BnyTXh!D~|6v$~ng|lH
zC7{0&ktDW=cM_saY>6KEPC~_?0h{&^9s#c}uYf#uHe>U7ygm|t=rrl=FL9VchF=n6
z2KXiAm<wO-6!`R*pzl0Bl7(K1->YS~^e9g278D*U)jITPyWP6Rqo9Mirns?>rb9sj
zvOkRS*w3D^Kin$n%RA_WD86z#&zaKIkA%E|jVeciyYnn+*3QJc#()iQr}s3de&f7R
z$5qhk1X^^MF)$s<0iI+j8kPKdq(ue$X&@1{W=k}L=OA6D-X+qFT7EgWpqELZh3oJ{
z2{mlYACJS=`*j#N#g=G&po;5oISbbsoxM}K&wH}`Eih<|$}uGo4QLA}IvwBFYOjcd
z&bD*Tm3Z46#$x~0(=~eAM1)&%8Yz=_N=c0r`XNEXF&y+Y@f0;oMYtu=NIlG@NTBZ%
zOdlT+sWaWH_ov@@R7XMA>h=UicT3cfXlSzzCSHNJ<oQn2Rad!`<XT(f`0{$cj}%oY
zq+*JCONl48p-`_WLGw4v75F0p0G(R}z}u1-Ex(SZeo}H)B1G7zz!!J}-)WW;&nv@`
zV7Dadn(U(z=EY(AYyw*}syC6}fG2P_ta3oO5^sj%umz@w&^F5Qgy6BiEKi6ZAP#8?
zi{SMS3DK6Qr?`VE+G~QzXgJtwB6{7mMdbPpJrVk}_$e2=#1MjZ3!-wyxopvyCdF$T
zgYK3HaS>S<<cvx!gH-4qQw1idr-rBk6OU_eR0r;_MX$VxaD>+u(Urt39Hk4x5enA9
zV7DL|=yjb@u;p<S#64|`R5}XQZW1Y%K$uYQkC+o(GK(DX!ZFY5IJm<`sV<{1#MNa~
zd;qHvGlZJlB6Thl5T%lesy|Q{6zt0daBmF`6q{gJ8wvuu1yNTYAaZC=6A~sYV58)x
z(*T?}4(xA%Y|yCC6z+6<R@feS$eN{ai(=fpMeuq%%u=|qJ2C9uA|f*BC8tJ2m28c4
zCzDE#EA9gTLZ22}9#ZC#TN0`Ld!HaOn$u*5TN1U`nIdyD7!DSj;2s<&SnQ9eBj^ja
zWC)jZ20X84NiO?q>L+K+v$vGb$4B;V!n4oF-c5ERu7hogLJDd#dow9$%@_O$t!cb_
zik|u`Nk^nj(VN2oX%q2#M^-8t<1MJ5F$Ks9Q8dSXt|d~B@99~6jz{}j$SjC>NA|8$
zvV2&lb47!UqG1V)j8k!}k&(MSB#EXx9FaB=aQX3sO{}$%z3CM0!*85eJxTe+qFS>~
z2>>{@K(MjUuGs*uf<<`vK`udOI&7c*5sr2gup`*+bPT+Cm{Nhm!k!AL^n+hhxu{oO
z{&qU5TKv%-XVt7N<~Kla=+*<X*r|5hgjH+wY;4~bqL`0a-{hK`eYhyFS7gEL&e-{G
z67R{^7vLSt6$W=CRPZo7IiaUV_DSIcXdeRfhajqZzdjSSz3HRx5PshhM~Fd4ql5Vi
z^_;y`;NSO=kP0Ve;X4uslVKOQBs%2b7uHlGi;CrLo9yR&&QWiiA-Xu(sF65}4HF@5
ziCnY=NJJN>pnpm6626o8)FfPcMiQPpK|DPi$2Q?0Kg_0>I9?7jDqi0sA<@N-VVgLy
z4uz~uJk$@9C#D*4R)_rpx8zJwJJBRg)5B3~Q_y^Gfl7)ex9b2gmw}n&D*jHisk_V3
z(I>WTs_po)AFqy+q&>2Wz$!43?IINw?icYbi59kJHiZ&5uxJaSh0R0#BWM&IZl1;~
z!RJ0q)VL+>q?<nzGp4!|(Bkr^+=9@9rfN*w1Ba;^6L-a7s>Z~9awMN#DhJaysx|bu
zU&9jI_v6qoCY*AIX&BR?&mTbqb|Huc*z!@aMLVMIZ(wJGBVzF8c7-HnxNkE&vwk5S
zh{@m`2V25O98|*Ea2)~rDah<$uvY@ivL%e=2~IGQHz{l(BN@t=u$T-xKP3E`$1N;=
z!jv=2znDlVM+UWSd@!o__Spk-(U1ph!k{#6qiGx5Q1`RPge_|jcQ;||8n+J{Sj5IH
zP6~`><Mvsj>Hd00vWmSSQs#4j@&Ti>J#!Q0y#amW6{4uS&l)ZCu<>&n4t-XU9pHWd
zNMA>E2JH4(1FPn^IcwmZJ{;UPH59Re`=-{flTt5o6TW@Uz!W<i**9UW9gggq8YGDW
z#>Xu<4SKNKxE<V$RMgz3jCQm&w!JF^ff2XC6l3+97vl#&I6P7c+j|{Rbhhs<Ey$$&
z+Pnp4wLtl}Vdc^JK72G8s)bZcU@gY&(?>fR-1y`~h@CA_!Ed<wnV{i(J8tg?9qoMk
z00MY)fK*32-`)+nwDYa)pa=e4*!D!n%RMX+yy%UQPi7C%(&6c5+yYvqc<dQwf82to
ztFJ1&7!CL!Hy*zn<UJkGL#=ibJ#L9uO7ztNuHMFtcnG`RR3_)%+f5FcpnT9rV?K0K
zLvG0iyDt+NBtYC>odBY8zDD#$<+QrP<+?+kd)oJ%=RoSA{`&H<fXB?fd@ShQyem?O
z8+d*MOi7Tw-5y$rch+uh$HYTzUtX&5mV141TZoOQD>QEkSY}^V{19z)Q#>a8Gy5{o
ze2bzHrfBJtMp*Oj$LQl9@pw!`8}J^yw&b`NnC0;YuZq4HI$tLGilLL%?<*c>w&R7G
zy`o88;eF90FY$5HBx`t(TUTFx0vR_=(jq@@`EL)8o7&1636)h}+4tzc9Q5V)4NwW)
zL4LO+hSH1pJJ%8P;hSYAGuFxV&!=u)!=N>~g8Xj5B#TTB1UmePPO4COFYySL*q3dS
z#8cc76<gH(k7G;SsrVPJDYiV|EZl{bNx`yn_<>kL1Amd}+rw{o$~630gosE4uk2!v
zypE{zqsC88H`~X0175nK{U+Gk-poX3v6n+mkJ?(B10mcJwSG`pD|4vj`ZQ%jB6?^)
zv3=7CE!yn@nII?H5{iu~ZGp;#Ca6!pN<e(~b{3jA3wiYi$6hzRWP*n8>eIS=Eb}on
z(vgK_P3YEc>d1tbWe>p0h3L$zDgV(lZ+w|p+4Jaxon*oSGwK3BrOC5vHv%-lfY{A1
znE)Sc2~8sGZJ%E36SUUbMJk;}X<^Sqo5cLOCDEpHz7IfApV=;uK#IB%`3X=_pH|+0
zir#)$IG@dEO}W1CSD_6}C7B38+|5jqa3Af{+IvbH8Uvf?i$0UfEeuEe9erqa$rODa
z?qL^#sQT@XR;q3f&KWu6F4oMx#blePi!QH(Ejbg?+ymeHp&dbZi%GXn6zDKJMFQN^
zhgUyy{!R3C6zG`l%D7-}N#k|qv-ozBVg}XsL7xTu_K1r`-iOcolbd3<D_d+8eRzie
z)YOM}2vAMkA%qjKrap!ZWNcF1-Wus_W8IkL1k|aEhVn;;y(_Ulb|MHTcF;q1##cg}
zDuD1#S8{00g}*=_-Za?Gx8(5*j3)Ul1Fx9wpu)#{FkA!eK6upWu<-yaR3G|lG{<)W
ze9QZIU=(1Xx`Pg<(0AQ2hZ8EXo2Me7Mn4i#P`5o^jQBM2^UT!nhJxzugA2ksx_6k(
zY7079SS;{?bmPajBwFJe!a@OuroIrJ);!d6XyBKBWuY}PS^|vff?!_T2XiOSA4A^?
z3He*znT=Z5D8HIqLuDw%dFoj{P=t4Lh-^t`POEw7U$oi2)U6&%g+A)6xZ$zmX8CxE
zVh4WK*TN3`tS`Zzp7pi3I}Ynl4)sF|V@-LVM*Ai_Oi$h7^<hiYD-##1r?wMssB`$g
zLb4r190z<0!cpreegII*G%IQ0_B3n{T;jAcxl}qBsF!DK0tK~2Bw^L7ukVH<-LrNw
zSg0ezr!6jOM<P1F8=pKy?9R8m7e_Tu+I>UzS4o9qpQ*0$jZ%L3?<Q^#GE!ZckOk*Z
z%TGAc`XgVCw3)aF-Smn124&pMLy?K5(AVvvvyZiPBKUf&%|N8CFAl~9&sFnnWQY%r
zh$<DlKOMv&-}v!;Wa;%S94Vg;De`r+7w9eWwa2AdKAGKgY`45p4P@M+7@}_PQ7kFJ
zYq<2Q89tfDGv>R67cvxlK&6hzKGk+rRt1`TwcGlmeguc44AeQmQb(fV`$HMYw?iw1
z)3-j}HQSn7*F`_s+`17-wIY=H^~K9ueyaVclRS01sRFUnZ4t?E==MW?#@KgcxRl;g
zp65@sr<}u|YERKtKK|Or5_u#lf3lM8iw;ogNS=?!Ows**%j8yVxOTop8+zc`nb<a`
zwG3~%Rq^f*rCT+BeBbY=C1->T{^{Ls;GgKXD+jVEyyf{w(loW>Ezl<Q$hYs^><^13
z*rxbVjCRUTf6LE4KmE<JOF<COeJRN}?j0E`EM?UjALNwPx7EcJt->m|?;!pC;`%S&
z<*t2_$AcqLm5N&TuyOJb5j3TALX9NT3rN%v@o9P92d4XYwey<tg?s@2_@2dUU`o{N
z4iHDew$;Ul`nNYhDlbZh!a&oeYbiaf23@NncI)$@p<&W~eWH<_?M5vf&#t5j4fV&1
zA3+Qa&(4%)tjuO^P~c3lGx4n@qShtShQ&OwZ(IiB^d?_Op<vtc^p=8c59ei)N^Jlf
za+X4UsA4k;wb?nI*V!X7ZNshh>De-8G-}iBBWGz<7$HR8N$m40WVBA_mYl_G(7b(Q
z_-u!(l+==O7B7&eLpFi_2IKUFe<Cw;U`NjYnvNia)jsD!nxdsbn{1Ss7yTn*B+sLN
zQ0a0qfavSU8b68I-n^S+=})7ybB3(7HB#sN`bo<snX@!ys~W@>DSg5k(BuHbioA|Y
zgVQvs5AlYSpaY!ej1qhZfinc#M<#lX7jLlI291co*g1<ix)oQehjC)dPI~La7wN}P
zL$bdrmDqH8$x?sK-dZ`M0}a5=St{_MEY4Da&HM;iDzH7w%2_&4*z24_13pY7S^BP-
z2skg2VI0rdl*!&TvKdrvCdi`JKH30(Iy5Id2IV3JSj}fqr2ncpe~XBE?a-P_sKmM+
zniDBSGx}w~Oj~r4N#rQgg`p<v)H_!$(vvUl73s+@A}CYzcDY4U8BtS3iqd|!xtK@V
z92rI2GS&3rC3I&sUMd&q#mdV@E>epxMi|th!PdD*Ek20rT%;HUxz0s8&=~7nY9!gD
z!6usQ`U)95*4@QPRaTiiGm(|Qu+)fEq>9U@h+D;&>I_ixP}wM7Q#H*aU3w%j3myWT
zD9tB>B5kPv?l~Z-hkyIw&0*}y)8kT~j@X_dXFMW(eW-)AH4wQ$^xo#+AtOl|Vt$h{
zBdK<YB1mKtIbcjzh}d$9^sB?J=OP9B(EAiASkTm4aPBZhQ|BW6YX0$}JFLT3<RXP@
zJaw*wt2i?HlDO+f^bibH<!lI`E;74$#Ymj);v+>hEs*zu8p_k)>r6Y3==sz+avs@3
zXmkoJ({<0WSiVSNl*;_0a&bc|Z`Swd^D_1AP?yE4w@O=<;T|Zi(nFslg=y4vuDWm<
zcAYCa^dWe!)}se}ovU<c@o}N*wkh;=299(jrf-U*ZXQ*tw)lotb=!PVJfTAsnmyMS
z-@FctRVtLACAp$N9h`kjV&OPE`xeoV=2KqPWwZFq06*&&lBp3%O%mza^6U&%%C=PZ
zwv?uU)457%mf~)b&fNQ^2>jbOvF9V`%9Z?~sa&j|=%j4rS9L!GI=uz4DvX}aRZ8>4
zl_i~7GRd=;ixq#9CM<fS$W7P7qDP9{q#R4~my=d=Nu*=Y9#SqT$1fr(tyjt%u3<-_
z-fvQl#!+vAFWMp2v1ZmW$9`zijpaT%r-fq7J}xxfDIGLEH{B^;%wf`=c|BFqWiSiz
zn49#Vqrm4@Bl%E}#mve!#vWQS<)R@qYUwl=L1=e!(>>6U->=+s5fnE?Zc=wIZnOSf
zQnm5QZ()u-B0eMC_5@^TQf;}DjOv*htVyfoCxAkeUVHJXNv-84)PxjQw%TsGJ?6*u
z*|<I$#GIS1j}K2<lY09iiYbz93usbr#xmy?_eaB-bCWhRV{z_xBzcY6q;T}5b$gd4
z6UI4rDKdkcbC)VRDCaA8E{+cIp1UrNit(Pi?v4)fp1Y%8WZ}|sm-=(4_buY%3}u)4
z%eEMFT_+DiNd)DP`g<|lN!b|%y+u^i3cgF*JxJ)>MZ9Pzbnd!Df`!gKbmEIWPdYK%
zy*qbZA{`ehcj?6JEubsn#}kD_7S}KfT*zW}5)D3gsX#}A&s{n&=~&SDa1?drE*1FV
z_|wfY$;<$^LBt@Tj*dYxF`IQ1p5t3>3AJ`4oi2s<@CQoWh2#nmwf4!Ok4Q!q?uX*i
z%3aq(M}*IPisF!%@VQITy?6?x=o}|L!)I|s8lh!|Lt9(BZhu6FKa_`OzNPlc7uB?_
zwJ+Vh)5$cX*pgNK&}A^mJTM%z#i49Q+y#?8s`8M!OEww|sXNn&<)Qnaql#@24Jn@P
zL<c!Cx^qb9rFekM1C5t_Bp8k)Q}m{shcsUD?lGkD(h~<qDlZABm`7;6u%GHv%t6i$
zLrU+(AIWVnWl~H(*%7ZibQ2VGIgc7CwwqB^y@!HQ+U|=;JeBHNUHX!Z2t)Q!u@!9z
zL*jj8G@U>a8_7U*ChsIe$}@S_7}A}|)`o%N3aZSdufvP^uxIv2qV2&Ty(0VYWO*Ht
z<`VbETX}dlvRPrEP;Z|bh7{`kgz*|usJAZ{Lkjh_A#&)hczY)q=R*!zmxtmj3HF?a
zNLQbTL_>=CX5Sc6%lGh(JW$IIap;g*eu<=(9m{@;VxBzF?6)i?io)6F5o+1+=sa}o
z1RuQxQ+Z^@o_C~QOs3H^n;53F@{8LPEvyhs*AdYY+Zd)pFez%<lp4PMjxnW$4^;Zf
zGgPpl(s@b+-@br=UJ7c}=%OjD4BP7GLsH6S8qAYB>FpR*villSy+w>$5gp-{MRRS@
zn9}8jRp%*P4z79&Xl(Iec1n{!9I&Cv-)Wj_)93VS>M?IjJ(AwGeom?E+t$x1jcv4b
zp3>QdTj%LVQd-|$|J1bi%gEGyRp9G<P;~L88(54yrM`{8&eOEI-ub3(wYRTFQ<vI!
zOuvw2C~;K<srg&`+?1BTeM6eMpx(D_MAJmRH^~iMFc3QfWLgGdXMjv^0^Tq^Ziy-l
z!7AlKD!ZnuD;8ayZs5*cYYIY}XZ&5A6{Rinx@9m+Tf%-Y33Buh0fS;%4tkM6F>MLG
z0*Yx%X!BCsGToE1P)th*?|e{9%lPgLtY8`6ok1RK2}>4q0<^@Zkt;zk{4f<m%WBMb
zCeZsb<~tJ%eoF#!k{7|%{N@6x_#-)~OdGvb5te=}zh?)$={h2noKGVk&SVHwzeu8y
z+R8vPZB}JHB?OvjEpJ_*nYKh_7iNezF7QoTa?k-Gnq;G_N~^p}txBsNPG=}=PYk-9
zI@7^#GekOB>xqV^7<9J3MpKT2$+()hql?x+bifuoWYW>dLMj^gP)id?YuWKVf5vK=
zbucdolb81{kW$N`L^DXKWnR|2KreqpB%?Kc#$kdkqslXr_)T&hl(!+ckVI=7F_h)9
z49j6ft>vu?xYb(m(M_*xlzA4|$}saRu+@Xd5!lL6WwZ8&wQl!8psh^EorShqzRWGr
zX8Vnp4enZy)n=Sg*7Ut?#i?LT1%><Ukjr57L;Jn!KkaB%AmM!zfx~<}W!WhNRD1_C
z42ElnBd?$jKeKqwZ;^`14}W!^1(x9H1?141ZX8qeSJ4@EL)HsWrDe!^2{_Z5W+}e0
z3M_M2ZYJ}nTX!zVjbG&Ehs=5E@KkPvT5MPb3g?P7%{?7wj|Kd^aHx6nqr;eN$yM&1
zLASPYH)^KXa5pUAj+9o8U)oNq3$Pt;ky;Z<dCltD_o!LXXJKkK(!79H+7g-vA@_9X
z#T)){Vb9AwPC}Cjp82W!Sh?Yy*rG|*29wE5)SR;yA(2X)#NT}JXzyun_i|6VUVP%=
z^|)qsWl-KTxiTnl4w#$X{6>RMbD?t)*^<VP#otwzMH`a}UTR`;(dhI^ewt^R?+B{B
z=I!N#I-fTB7H(r}nw_4T-Ws}q9p?O9*I~-|l-@l0!~)t9mO|WB*KoW-F0^Zy<{W_1
z8dIN%JN0^kD3^0_e)IFAKMg=HT*;RK=mkj864v!PA`qrbTZ{>7=)P32IJ}Aft5K$0
z#kVMG==hH5FxneTzSGfnaaSq;j+TQ!mxQKY2Kns}180tn?y^HY4go+4prmDdc>$Aj
zy+RWZPtzd4lKM%hWW`N&)KM@>YxpUr9MjVp-X<_lEd}~6xaFUqt+&1#Lr`h+K;6IM
zB!q@Ey1XP5<ftA<6y!n27BEjM;N};iXr6YKG*3dc5E|LhM3d0S#icT{PP_(+6&%@{
zO9GDUy(I~5%(g**yfw0}<XaS#*DjIo69R&<f=Gg(5J;kK4yPNCr|V0gTa@3>g{K7I
zX$z=+R!ocdGl4wD?Op@zv_;WtV4b!=B_I9xicW!owB#xfb!?Gpf`T-4Z^7LCk&rqK
z?A}B&gs7`)-@vfGx`Pme@qG(am$(kUBW0jb9}3_CI%;)gX(t%4$|WL1_n{&y)UPZ*
zB`fYncL-S?DvpFEhtBQZdwB8qNJyPI(2bBUkV3tpdZ3jJQ!TmCKp!+toZ5BZs3l9|
z8je~r8dr?L1tiominqk8(pN!Ltv`K+&h6fFp!HeCnHGRf%LvjfiNZ~rw?$_nnEJP5
zRHnIqOT4iybN?2e?p7B^=axjzI4W;Ge~*7rGsnWtsJiaO9#E!hbuV_HOsjjX17!M0
zNX4uXo}(PR(&~0gExeX)5ykMN`VO#?PKplVopzbkw-k7|S9bsm5JyXp&jQ|PnWeYz
zxctOzDd+up^=D<n?zIdQEj(MVPGIb!Ff$Ig64;|<c>9S4Q^})(VoTleVHnWhP+vxo
zo)9v-YhNK`YG{yU&fYCLjcPK5Y{_YqXneOIzN=QFJs%q1EjlyKJiY~B(h0du;pk6u
z`)<i@C)~bQNX}Y)$GAB`x?>RmNm}OaEkv$fjVLUe|L!_T=clqhLl7-tHJ>2}AEP)r
z+#CZjdLcR$)nYFDgFXI5jbuSBM5kHJG0eFGy#w>0&VYcHASqnUhk(Lu?+HC#7PWc~
z0fETb!F@CXxb8JneBrX!9Db$VUxESMvC%98LJNqakA&2jc7}Zx&_-Jlt*fEyTJdtM
zC_6{mD9}i5iAqM_8S+`cC#?hc+^I8+Pn06GUCSyLUFT56rRI~0zoN66Ba4)v**p^J
zkg4Yr_y{%jMH2Ol<Np<+m@Hn<AdR+!sUAS1W%Aqtgzf}Y+6}rQ%2G>T;w;sup@R+)
zKxBz5cMDD@nJl*iV(2;|W;1{x=0u={mT{T|u+XYrm|%rgePa7mg_pOY1u3*DK#Wqy
zNoe@E>p2ydpz7;A)I`g)xP=%}?^sgkt;%AKvQ|JaFC<ZUD_U@*tNO4{!<GZG6dJz{
z5!31W__O+*JDfvU0ejs7H4oiZJE`-Kwaj)~Vu+TxZVS+&WfW#%TvxT`W;U!qi(QDK
zIgL~_<%y+*W;2qroL|ccq_o76uIvE~%WL%>(6GD;!&!hGt!kwnsH0Ww+EG9lEtB6C
z5Jpc_uL8hmnE|()<+#(Q=<5h#%mwZ$AdFU(Gid=}w5k_BRNYHVxhH;Dv?{xBG-PE5
zXy``=*eS7Py+V$K*%Tz_PDa&yw{Ivl0Xa{Qvh&R+NLgsGdOsb71r&H@0eQ5H&fI~`
zqAPEG_FU!+)hrE~&v)oEbk-Ni=_R8#3kaee9!($OjJq5gy|j5!%7XSPUgiz$^@_2E
zxw6b>lA^wfvh02>!^1VHn$$K&hh@BGIcJOONHkTrn;Dx~IJT@}J>Ae}uW)boNr5jY
z0FPGj(g%06C5?1c-Pig687*_*UImcRG6`<se77ZZEf}L!tkXF-K9T3Hau7z#v6yzc
zld1SKlT4~kq-b%6E@c_Axkb?;UG+P<&S1<EPExCQ$%96U7<kcBs5-}mDnOBzsc{QP
zq-AQ{a-c{%ecF5-!C5qgsCK}RRuS;4fI?cL&n;XXmcg6_U$kZZ+yW};9ip$&Na_C`
z%CdL^=#@5R+od|Uwvyf7XjDT$3$A#pWK#R1$(^m6T}djJi(Rovpf_5m;DP90Gv}57
zFl_<wmC_a5Q1^Y1NvqtRPiWNQ^Fbd}^_Jhj7PT*73c2Qq4R^;aJeA4bIJk1ZA{q95
zet0LNV3FMxAW6%yzX~`1m2L9tQi-OvEnz@drnW6m7p-g~ATXtsy>~>+p_PY>>H{5_
zy>}3(=n1@tk~9ExOQMMiO;$$yo(YFxW*Pliu-z<^-4^US%Vf7@$bOpjh*<)wv~qXJ
z*iVHRE#Q=v`ELv8qLrKH=_n`3Fk|)F5@kW#W$z1^&rWPfN-nD16K*mTUiN(+R*02t
z6a-wfvJd!Ri>{S*!UtQlvK2kv`cEv&(1IqkE#Qh)HejoOD_TZ-7C4P|1Wb)WqkeuJ
z!1}r+adN{#yRy~#vEeS!+!l<y@3@-iPNO=@fL(KCFLY=PmLk!Wz#XmZWe)6UWtKUR
zqZO9A3sJNvxooVV28Na~Bf=-eqJUp9KXIj8*|!M{>nqz92*brPJ#HaP+R8Tljj2Z3
z_BYVOhaa~DEzL4LZh^UGOXvf1ax#^6;cej^k@P+(N+p8ZGGA_)iX*y6g?TagLNZaw
z0)>_U94$ja3vi>Ayxo8{TFH*51-Q{WGAbH5DHV<Jl>~C4m3$?c@TV-3<Cd9EO63xZ
zI1N%!^X^ZgXj2!wumBZWphe5U0PPeLf)}@yY(W45w31I7Q-;sv;|9b>3z%r(vF~ft
z*C^QQf1>>Y?|C6=N1*W|TC~xg1whX`b}R}{SkKS01kbaQHjM!D?6k&^Yo}>v3s|0I
zpl6vtNLKRofT*e~`Fg;s?G9b5{u(q(XM-7v^7<OyHY(^9A7p7qK-0NfnrgNP;*%0j
zphEaOQE~<Gc}e2$sy~`iNX;@G)7Psx2;>$p&7E9i;gc(rq7j(|=)gyEkv#P@7PEjq
zScYR3Fbd1mv}HvOG}qF_QE<&7%#OjDMVOs?kvg;ASj_@n=Qb5(5g<n-v<14MWfIyV
z_>IGA7T_dXf+uNN<s?;eG~{iK4`gMTcD8_Pc}FLfhP(&KQ(3QFA#v{RKI66VmY-J<
z6z8_9R}mKHHg@0;KJK&%M#<it)LBmkSQep*UU8FAux6nx0^Zy{CctvJZXXkZ2Xozz
zg%GaH9e<fwzqowfwjU5Pc}r9lIyTUi*AcWYL7dUCx8Vdr<lNpQgvhyzi`IkVtxW<%
z&h1S?fE-YjMQ|Lm)fVA#?&oA7K+f$gVm$$-Pl~zW&0xoOJ88|Q$tmB6$}O5?V&aCj
zG{;Q=JGgGY76QK^koAQqs>`84@SEGAb~pa!#=uZP&D^mQ)SG97Wg6NF`OrHwc8ZEQ
zTC*b8F4XuI>_WGIZNJ`;jGedw5uM9Hmchu(C9C3=^pop}!5vh;bIIPYC3~#rlDVNW
zCUeQ;P=VTPiJAo0*cQ<Zd-!)UPKp)W?KA|k0?wT#w5`B#=CYr6g-rP!C_MDsT!Rjd
z0KRLum6aA4O;CyDI~8cRvf!o}Z7Yj%uKq{;qMej_lUw9FK6#@7-9<MV;ONOPS04!-
z9MH(Qnu`v#x+RTtJGE^tyfYmfjT++Zxx7)l!=<Z-2d#Vps1I6M)e++~Q<sTr3u2t=
zAN7N1WOZc*jjXQBq><Gf5y0E&;Kdc}&RmL~4RmLk1h<0Rc|~_eEnU-a#(KvORPthu
zXMJ@s#k1!Nk;Rv73R|?uMVr!13miv09ew?dD}U1fWoQwuUiif=it1}KsepN=@ryO3
zlVa7R#N<vo0dG+>h@aD%+l8c<?N4m`#6;k5QUmOB9SL0k8__f;ZUq1|4OZNe7>?Tw
zCRo5+I<wRiN_$R6G*2-w6SQLGXgKF`BSSOHxv*Q+IABgA7AuF)Y5LsCL3K{=OJIa1
zG?Q0|P9vr_rh^fh)7uglp(#?`3P@-R)JhchoRK7^yD^QG@Df|1VQsW=xLg93PZMC(
z2xT#iVXWK@ra_FA`@=k}yA_wRIlD_H1kYDdJ84xVH1wPboldxqIlDXeDCmzMs<ms-
z^y5j9%|D)WsrQiM!8d1h4bZc5R#$>Z^V1RHBaX_EXe1W(sw#U$wW{C^6|m1Vy>2DO
z%QTs8<)XVK6#lsfPxI*3%xmbJGG110(^CM)$`yPX(pUrQGp8(-mCHSnQ@fmKKz7L~
zT993Mq5;`u$HJdL8m}XXCV5{WSkIhM^8S~%6o5X{6udRSKGzYcSoFLJcPqZO)9}O!
zxMxo7636T_<6eIuh^6B7k3H!lIjQ<>3WiuST6xGKxg}Ar!A6inEgP0tF>_7B5-X;#
z>G1FsbJ-kIr>}}lZHpS|c2dPzPQ8s&tiX0Y5>m0g&5~Pz@l3IJ*0A(VlXzB)fzu?O
zThhtn9_!IUff6c_xTY9zw;<}?{o$i-fh^XHmK3hA5@u|g$+qHZ|K%rV0)6?(8K(hz
zOwI9UR2%F>(^$j`IngvhVLd_BrlE*6<48P5_0XU*fgV;k38twzD}bG8UfNpHN%0_E
zLF~-owF&*g99o-DG)!XzD>nKGQSB9?)A2GMRBZiQ5}gF>XA9`~l4FPkFWQ0wJf6dc
zfKooGq)(vg-h!xW@;A|SVP?J%MQyzn1JSbu^gdvnDVSj8iDwEXcpXtY0#z10HtyF~
zVv<`o1J;>cV4_-hlHMXlk$0>uX{1kmyKfD_V>0{Fh@hmpfkKscw=Ej_&1pfO?wX^g
z`g8-(Q$5CuTjcCslduF$gYzmJL0dvi;>TN{xe@y7n!US$D6no7dB|&~*&{2lLuc=v
zh3K#I#1kz<TlMC?40Y9gu!mk}b|36P?#!Ty{2Zl$?o2a9)_R{5V;In#BVi0d?o1>6
zYG8G)BVtuSEi{estMRx!MfF&D{@w!i#EK&7^|Y_<T3KmAptL3QNX^tk>ykJ6*{w4x
zH^*+J$y@(4%CCY4nB6K8%)snckySUxo>f+%t^)SeV4>O)Qqiq41J+uZ)z3M)Rx0du
z7s#AxnBNveeSMa$C?x1@uOo^2`Ya86XPO~$OWH}RjcBCq3x6d9;_SED7#hbozY5dX
zG|sOQ?|B;LSA(ByHj}(nAT-nLkrk@5Dd1l{IGow6VnOO`32cTH$j%li%UP_==V<ua
zX45%3P(8ExdSBsxna%fmP(53sve8|J{#8&t6X;)bf&H&5!NF(K9zgu?El|Nnb+ztN
zx$c=5@~RN*Z4vEhD6ghta|A@6W`?Z5dZvjXYtxOd$>>*s_RJ>4PzBmEn>-ck>4D~g
zQGo|@av?cOt@#WNwr83ZvI6dzB89Ah?U}$`_C$qHXaXCoEz?3@+k;eb3s?|vG0x^Y
zdee=s`M}*W4YE>i<)ql90r5<O04smn5?LlFb2h!<SE@Ce@7t&1U(+#9dGWiBDC&|t
zCheqD*GA_i*Oj|lOY}-(H#NUw4T$G#$=%OAt=%pK71(^77Nh7EF(RnI=8fVYf_A$4
zD=`btaheG{>k_!JLNYX~FV|2EP4hg~K+(?X+jT=JMqs|vOYt&4>+*<j&7&S@NTUhs
zS@+Xe!Wx^!bwnzL3tjcO8$8f7m1B)9XPU^dvX@;GEMNuuv(tPRXwR%(zXwr0jRdUh
zv$Og&t^&iJ)jGZ3RL?6MeD@R{um%Er0<7E})zOmGOT42cP0d(A`%Gg3D`=lBfk~nE
zNUCJCX|<jQ?K7+OJSg{By~G8DpH*u-06??KG*<xtO;CXq_|G&dumb<t5)A7Voj$8g
za}YVtDnndHpBe;Mdp#*8ZiiQY3IljVQ5B!BIm1k#dzDkpG<2_W3YrJIcOhvfo&1d$
zYOik&SF?JJb0V9fbKKqE>2MY~gzD2Ez>0gu6bNt&&W36-$J&D@>?1iTZgSO19o){W
zUe5=%Gph|~9mOg@c8H?-XUPNOnI>=Cl07Gj7d$>OTcT3H^KOv}LW`E=35FIezHImS
z*DStlcR~ctqEkC({#kr#KevKed}{A;y`N@#tOLba%(hYk?K4gHSV8+tvprVOKC`e7
zjQBTo9lTmjLjo(;r&+uW0OgrR1y=516I5Wu2W%DxuHK?WrWkiZkW2#wYq*h3!vrgV
zOr}7A*AYdBTd5DUqG5q`l#^nJfd5QG0&Bp3t|L;rQIv)SR$T0+V1YHzKeKob0R1zI
z$(`!JRBEJPg{5c~t9nR^rjdg6T;peP9LgGjIF3kN9zTeRb$ta`Tg%oqP-xK>mqH;F
zFBS-H!6~i<iU$wwR=l_rD-<mb1zOx)N^vRf1Sqb>oj<gv=bn4d_wW5=C$nbFteLge
z?BsdhOp>7$i3WdHe6EWld9E}RoBl*;dWTIcuKhqWiqe>G&kN-o6u$Y9u{(XU^^Cwj
zbF=o005*i&r19VkgtgG{A}Cc#t>e4`<prs{mglq9@6PD38u%Z&T3+~ZF$<hM1C4Vm
zl=vSe1)aV6tXnZBM1jL&VX8kba$yy!^=xLGxD|cGtbNNZa3caTu|(0b%xo~XzWy-T
z+O%tmyJ83lPbdc3+r?}VGeMUnowVI9{>*G27tc90{{;Kv*l2Cr(}juA(zY<M(|-0o
z$nqQ#vjk=)-kd?F8sCxKbWGSO-j&r;YE8Nl;Zgh;&Tjua96thtVGioj<tJbiw9gQ^
zj}Ym`Xz^YCf=~6kD4L(m5-4r6T;wTU(?x%TiW^|{`a%!8(TiFW=!udi$6^RVhB*iD
z>LkpPP5lD45U~cVFc32`qXN_-pk;`jr*UIB!kebrI56EQ+*5HwM4M3bU5m`!H#ll`
zPlYwx9$JTLg>VgWQT6i}d24OxBH9h(pO<_~8R9rEIb^D&DFkqjT~A@HMQl-@_2qOl
zDa*0szMe(uCj)^WHXf02VeJ+jys-+E40vOaAPqne9j$!Fi69Dx`nP=pOb-JQqKD<0
zaSqgZB(^j)jEBVoQB3kAwjz=<Jqdh=6F!Yinb(NtmV<3^0yADm&J`VW%26FvQ*T-D
z^V4TqiY{ns@cNiCzr~rs<x*VmGdtY$>sn6guT&?pP{WMoTu9BopkN#t!4uG5UGhlY
zEMs{$to{BZMU=d%bfmrF$0SP|T|i*_k1q%4%473g$f7d}j>75)A|Otc{Dp<bgi9oO
z=M;=nZ=si6=t2<MVl-i5)58mxFqx?b3mVKbFWQG-ISm@t#T-grQTN292+eSxFV<zm
zg1nyf;tNJ%kKDw$uyP(7{Nv%Pd}S|AJO0s(W^@}fTyV4hOp@fmD`9?6Zhkzy*eHAT
zRUTUX7B@BzsE5r?HtTB8qD6E>fsfBKKRZclR~vU=Y&B!v{A<o+RT2EjDV-vKi-XsQ
z>hh$~-Er1`^xK;{SU}yH9t(+=8|w$M0!{dqu#7ibMZ_+)qbXJV$4i1Y-=|XY-AS~g
z7v)uf)ug+02ry@H<;BdbE$L5s0+df@Cy{q}hnv&*FwFSAdQy#D;`<psxHK}?$2(r%
zE9ReJi}oVQ0)1OkvTDDbo8RS~`TjnP-zzU}*h}NVCHMYX`;~No0e()Kx4e03L;aId
zCxy2MS}=ReHcS5%V*g3xZXBc%w5aS_8|?sg<hPSZ^}JYZmZB?johXWY8p#(HY|?qk
zZjtWyn8&g9scX~%9<2Bo_JEE4=TTbBNU?^R07*R0Vl<HB8+n`lervO9+Tn<EWYTc&
z1-%$E?Zlc%D$*_v*q((I%V=~%0xD5UW3%tqh^kLsJ6=Zaytxh%v6z`9K|h_b-1>pd
z#fZ@)vZrSWt?*oASdZ9I7%74o1-1UFT!$t6=<dihl+6<4gMam@Qi_qiD$al_E3jI8
zfQo$%SX-Pq6x8O7wbO@PU5s*Q!c-y?&8j_;Ws$b!S_7O|zE=nfZgbwH-=;L5cSgQZ
zt1b9Z%lKGqTk9zufzLCw%KELPOb+#v4a`EVn?Pw@M*XCGLcI*X;ER{NAThe}VRV$o
zAWUb=R!DVDj8MlqO0wGzl5h2#kG<fZ2*i3K<L9#^Zk*9<lPuRX`4qV~I)h1Wp7yUA
z^$<?_FM7%<ypTANYnW`U$9y~eRPzJnOw+?L6AW`ir4P(Y%q^>FW04Jht|UkmoVC_L
zWmZ^~eVX=5HYB(kWlrlhB8p)A(WW*7uw40MZ55`H<*wuA^xeeBk~+tlQ>Wn&`L}HA
zo`SApzHd~Pay&!Y!Uo?epQ9|WuTeXj)@GVUmLiHFd+a(Uk&TALNq+T*piU=<H#G`_
zC@r2fHzDeh*pI^ZCcIc9NJdlU=fA;8Cp8_kG|&#JJJOPLkK82iuvzU`nkOYXTRPvv
zLQg?V(R<r!`t{~m6kpzg1v-+mHqD!js8{1A^mw@;U6N&{wS6F*P^|{ahVTmHa>LeK
zXz1I9+2v|WZ2XOhyiy|0iQ7ilC<p>&7WL5S_*5x57e%S26%GSP32!PbN8lYc`4y8u
zQhDHvyYx3Tw5~BK1EnZVE1v5&9eUL?PF8-A_Tj|srHx+Hd{H&AP<a(;-UJN?5%a;&
z@Bu<`Z6~tDSo82Rq&fd!hEpwu^!HWXzLv#Q7N~|#-=saNG{q?Q#&MpcY=G=vzhsGR
zSTmiS^;dPQ*sbz^N7iRV6!cvr`kYZbf3G8d2RHpynfXZB%QUoIgM%+HF1`p)O9P9b
zo|C5;$xFWDyPEY~#3ce|!d(Y#QPEP`_`2-R_c+9OKTRq{VHI)-po+cPW+7~XzGx=Q
zLFf?4Bo$80EZx1knDuEKskvG7xlUhHY2?YlUsJ{Ff{~s_`CRSp7YhcQ<;O1G-O*jO
z+>V||``lhl9%=K@mk#Bh?xoL~9eQ4kf_3h;_HQq5x35&E(r@=JOMFi9!8v@lTNHPj
zws!}Mx5xX%K1cbMCEu!-;?qywtGAp@THalod0r{rozC9f{+QK|y1Svcv!gknVX*ex
zukkrgu<Mq@{&JN@Ft}cIVn%RV1n=f<h~oCRB`Yh=Ha=!H|7+A%Gk8{6`h?qZtMzRm
z^qpHoi^_NT&`}@wKe8O|-+d$a(jd0I*In)sFcH<<4E9R#uJ|Z{WAthW=}l*enp4NK
zNiYcIcJ0ZRn{n_BeD<@iPMI{5Q403;ZmzS(hjMmWbk`3W?c)Q3ZggMWdIG(!S|+0?
zXcTNL>~SuR#j(d_4_LQCy)H@9?Pu`}I)L79#%}99hHtG*?mQ*jeP_i8)sA}<9UAg{
zgp5+#^e*s08|%~UGe3K2kGd2q=0&(~jl~XzOfXhAm1}e5e5|qe2A&IezrpU+2co(P
z%r~b@IzPB^ziOpvVt-n2d=$ayqi;CSQY5YysYi124ld9UN-rywKPGx)M4ENiZ}6kV
z7znHMt~y9~eQ3t4<Ce;^SdP)FSRt}^U`%>)_Wt4ZYL97iN4jZI<`yTq%-u48jJ*n6
z!I-O0@!;pYK;%)ysUm6DQGeWk4kmaYNP9kR0HWueVBJ2lZ#7zZ10LYAjVDx}a&JMu
zY6^a*_>p5IwQF<rcK6l6?(GQ<cJd`Ob!i-It;1Nt6ij`P4_>U)EWtFn`I$aDa<;u4
zw<OScd%PZeJmV$5^GSbu^XB+y*70UmA2?|u<CIN4yFB!?x}^6+wwj^iSg`^z(Y-wK
z_>Ih4y`7%5gG2DZ!%O)aa755mE)FrN+qsz}jCJbgBgE45Zv;t=-ZMN*p^99=byv{p
z25*fST^}iEnv}lT_9^iVv>He8%TvT$AA97>=H$Di`88G^1ZRXW#TAbW!N|Aok9tfK
z2GdQiZo6lF;2XvsIJlLQoE(f=xzW8r-aC1*qc4PX6}mk1*{@}T{6I&ONgB+LJqWaI
zVi$_NW(7}Kr%o|hk1O8Z*2&%as6o-xOEg~TXQgwoN3!aQ9TFwi%&J|Iw58YVN41p4
ztl|@9|EjJ&2w=G3L)6RCH{XQcqr5d_eW3M+fQyeMQ5*Tp%sfvTD}?UrXxptf&nheL
zL}eL=vP-s_#lhALHsbrK3D=_hQ6+Qx7VFpXE{BpQ#k*9OP=3-+s~Qs@Hi)!5tU6ZH
z7X!UlYbQ-_yf2%?!Rd8i^Vof^-Ilx4j>#3(yPuanW-mowpqtnjJ32X-K&<ay*&14)
za{_>X`)2?Ez{SJE&HYCX`b#b#a9_nL;pQZz>I88z0sI!+%OF5_0l+FI0$>BM8bRP!
zA)$Na-&a;iTN|f;Xqz$vnSlWK&&2{%{!)VL{WS>ozl{M{)!gk&0IW(7GZO#}fbExY
zC5VFwyf3ytZCT|_jG+)wTQ`6<Tm%Gg^6~=M*nvQR?k{yQxM8@yBY@-Y22u{T&UXJ8
z%x@#Vr1wqW2dgUFv;)M((eB=uk^3L9G{DKh+2l`246Y?^;sP}?QIQh87ydO@6%$8W
zX9pt_N5H+`RM7u3HEwwM-oN*rk~6U}b210;{5>p5sFjn61AtZ13hr5P6C+#WUzYw-
zWCL)s^K#wy^;gK;Qg=1qc;b&Yfz7<v`*-?xj7%#?52vU}V`-j{qoJW8tEpqJzKXz&
zHZXeoHH7|yL3BQTKrFWK10>}R%XnX6rbrx0M2jjw2<3PJj9Ejg(ASVO#zWakPT?{I
zOLOL`>~3M`#&fU#BWT^rduV?@mF7KmR*VU9h|lF`s0qcF`AdG$h$pBqc?#*=lZxb_
zeN@z06qIW369fe;2Q%D3Xg>|pcHGa)0&^vLTd@=LJ9&FR<jLyG2XoH2S3XhJb)eF=
zGTqnGFLV4(evnkGu_RWt-=a@Ef;63%O^@c|ILrl~L~61oaaxOzXfq78UDjxxeGt4=
zng*_xXzmb5pr(sZtGuw#WGE4{Ai%||tk@5^epdA}7nh1eYIf!kZuXa^FM^<UIgSUR
zriKhuX{*???#g5IgSIUmIto<p-w!*Es6bJQA$xS%)RJhR!H<}V0}(HeX%k+S=@R7<
zIMXAkh@uv)<d^*bD59)<dO(KU%I5D|9KaKpuVyhBqFBw=Fv`PUEW%1W38Sy|kpY#t
zws7W@?j~gKzBXMDj<wI+O*mz8)my6#RmFdsriAI8RmzQ(w@sZEK^yo3hduo>tqk?9
z?B#HCv@G3l!>%ho?WoEnvMw@XL3Rj!0S8X`fR$}*k}>U?FBA0(hp(HXboJygzrmy7
znWQG|0P~+X_#`yi^+Od7-hnx><uHWh$l(`b0q8#B-P@=Iq{jN)EtJrv#)$?h<`E*1
zR=nNq6>d+Mw9+a^wxf<1b@?({MV8iQGKrsh*4%GaDY+%D0*i=dA{ALlmnOxV&6Su#
z(-VLL`mx<FaU%2ep2+UZ)6vj<G&NgY!`vGEuy%|e>(M7OXg$^2NKO(|vPda}{ehfE
zr~)?s+LqjQq0aR#&zk>Z`uW<*DjhmF_tXp!ZRa#k(TtA#4zs_o;C4Ds_o%Ozi0*89
z{p_y#XOAFZI_IbCvhMsSD~vqxuCJo+hkisPrdHs53ty9z>aO@06D^J@pOswl0ns6~
zGoz-}@bH#YM>Mgo`m|<2)LY4D_q9gM5_#ZHR{UEO>jRSRmfY&k(pGRcGZ}`TH%|4M
z2jUP87-}+|4bU9@pfl_>TE9$)3)@&_>ofXr<q|hvMq9}0`z=0B_Ti%B-7Cy6IrI2q
zm-TapOQ+LHiYA?(ajF=ERq}P>g4ugfgc{r1+v}qzVrGKerrrY~F?5eibuUk%ToXD&
zTLMn5*$%-3)@oF38Lr3yiTKNk4AeO@xW*LG$c3cVD^GP$x~XW|C<Aw;_-9LwCJEP`
z@Xo9w5ygc)q)Qf{i?)8A>Hm&^bvSq-+lYUA>-EJ(-uGwu+o7v?@#Y%i^tNfo&!yW?
zd4JGSUU{6&(2uW&Jxb^1>fI3U$xPCzow3mw%xR(-wKFrTlNXced7dW{>!Dp&Y1%jO
z<$SjOgugJ%a?y*fSUG+@T-_d5m2u#kEB3(SPzPno7bsytEIHvDql7~>VLet1jI=EE
zv^*+h(uLAG$pw}HwW)dGwPbnoBA=s1GdGjx$DFML#5Az7j%3brRl!y~&s^l={ibyK
zb4e2dI4U1$PvJYs$|dM(u9B}vb!uZ~_V){b;CmCYb&0FDH$9SkzBBf*$1t)lalJ;7
z%9-ec@WhhwzGIu2pF!?Yb1vjkEplRVw6d$^^cUZlE9Q6BVBLzxG(FHumO7g<N@Xj?
zkCls~0UsT4Xcs;mjy*Ac6Gk<kw0D^DR{HTk4Et+ZimcVGx>L$`0%ji>M;p_Sp-SkY
z(J1apk6(z)qB_5K`Ct^`7{O>x82x5LaD=+s?838LKsw2)L9t0OB}cKGhz~>e!jyqI
z-qbvbhr*s9CEOY#6+`EhaaFyFKD5L^jkidL^;62R{Hd1Nmm-CdihcV%d(OoDl=Xg_
zBT5dty&ORsq0|wpcvD$YS}RY74x<%}a=gw`s$;~<))<m~mcnPc%B{3cHUV8Pr@VtR
zZ&<{2x15X*6l}6UK)gglFP>~%6xG;IHp?#u)Hp4?oaD<G3ZWGYR2+fIrc^D<BPX%O
zal71Oo8@z}rR<>3nisU4y@Iz3+0&Tf>w4gfF`r`XdM`aAxp0WymnauT(ogb+XAG*9
zD%Rw>U)LBMtMaEEc2TO+1oH)ozKptj*O+3RQZNZ79PxY#9DF4og~)nV$ma3%cnOhH
z_l!SiM1Z*e5ksBD$B&!D4_ptGw=@Me=&9qNnQEwKna$|R`f=l;f{SdkWxg!VR(YiH
zf|UwTyT*N<^$izeO*T;(6^2`-+t1<xGTTETZ<k>tm-TMfnDW`s&$Zh+le3l55eeU9
zVhkUDk$mRln(<gj3RAgzDnm7aD<+>9%RdUaZos@@*d39^sY;MBPRlUuP}Y!2L@hXS
zN+}5bZS}x5)GS);w@+344L^xg$;}rRO85c|C0-<XO*_}+ZnJ}R7wwbJs+_!|v5ET#
z@#2gh3YHgRs|L%M#d&CcH`X~-sQDfmGa8nnF&kB#R{6ZY`8s452bVeP0li^95z*kO
z);Y;E#y8rC&6?HKwYAJg8j_d?Z9+BEho%}-j0@U)X-7cQU5Wl=|0@aXCnSW&elo4n
zt1|g@>e<19@-D#^M;mz5q;;c~ej0j13mbb<v+~?ezco)U)HK$*2P9d0JpUpb6qrLs
z7dsNXXYFy=BM-K<czQ8|XWJsXnExnOS9i49)~7;2>sohXd}LF@phlvDEC<3c0;4P=
zj)@EXP)JbyYVHbsb-=}gzHoZpSbsbGM24#*G9qrSSh*P(O^($?g(1fpu(CUD*NT;g
z6~!2i(dmWlO7rdsUB{*!wAR&)X+Ph1ihay`#)>^<Fv0YVSy!QiqmsqKS37F*9f{-{
z!fR7A92zE>K;~Vm${O-S_v^Mz3V|2JVJjS8j_?XOr1>?*x%hJ*<u$u|4rerN-fUnO
zen;g~xnA0EygIe1aC@;YG&D4akHJ;fllM^*d$%{pyadweKbT_FcJhTy5iKr;c#v}S
z^G254DN}CN71J{rqL5e1iEdJABY~cc=D0+i`B|aw^4K^M-WB7Wg<Bgo)TU2-fAn*n
zWa6jDd)u@f5iL*Sm%yjVyDU|_y$uuN_*Xg{_6_@C<$cwO{A{N+W+u8=!L1md^jD@<
z`)@jb_AQJ3^mRa&GPTw08e?b8Q4pochh;L7vNT`sRIq9nY$s)wFbhf7Hz=}rTbnyp
zy#IbUZN{9K^F}r=v}0M@^NAwkbmW*4d&89gnN(AL^pJlI&rYmrdLp*1Dvd-+Vl*~b
zbaVwT@q^m%i?xCSbqUUt&%DFN#qyDp#{rswbEKAzFSr!<l?xISE35Q{ch^^SYf!~J
zy{6AE%dZ}~@U{r^sJ6R9_9bIQp~`j%ibtD5R|p(o-X7p9pmQRZ9EIuR&DW^!G_PdG
zN2%BaNEVK}$IizBIDE7W9b^L4Gc~3d$!st(X{0BNpY6a9=xSSi%|rY&56XBrX{fB-
zW)w#f@|b0{KM=|^#1aN#a|C<5@f^cT!WKg7mF7-I1`WS;e7Ksm-kyxskgxtqu-5+k
zd)lNo_@vt?w=0iX|7!Rn?Bn{~amt97)%n8Mn7=<PQQYhj<CXR)9ZgeGoT}SU?X@qX
z`{<!{$+xqwQIeHy9A8=RhQKjgJ!5E#KXi&>^XItIxdJY`cWt(7%``I<nTA_zqL(z^
zDbmiTV=G6(kR))p-Cd)gT-7^*hucle%VaZ)687)X_dJ(-3sf}><kzD*U;m_(&+j3`
zqC4<r2YEicVo$UH)%6poCh#UkfEYY+tL)KyuSMf|P0Fzf4C_roh<$Epu1izeA9vV|
znm>>YAM&8?r5-0_$URh>HDLJgq<o%czDH_?R{DwTQO<>DU}c!bESF4*b-J`3iCS@Q
z8TJ=DEDjoU6?c7J-5!%V0gXXr_T8ElG>F;|TH7rEzk=i%Vj{#^QR2sWO;V>-P(9hM
z?p{<*v7ofz=lcFG;7Ppf0dK?CJ0|_Nwik;(yy1&%lAb*|gb2@qHqA|OM)I`=)7KE&
z`trq<{D#7u3*Bt~A=!Obtex)!y`eOjscNx=PJJnwJR{e0-wOQOf}n!9WdfiG!bp~9
zuWR;<O?lp@`WEP#sCa8UDAr|_oOH#ip712C2;6`Qdr$y|r13>kNd%?l`ZGFUA|Hps
z-AP*7O)Q{1o4a|m(?>NfmU~i(yEN_f7~}v(>ZkHq&FTEatXdRld^E_0vYdvp^2F=0
zJ?{-10_4aDTyVqQi#2zrNp|avziG0yZe7qmk?4{-2e46c`St;bh}ylwaE>W7ax?M+
zD~Ht!2((^f*v7=ypMP^JKrLH;c#siyTpNuHK|S<%`NWjYR6@qNsM=OPFtl)mJId$m
zy`|<#HiarnvFG#puO`WgMqRc+kVpC+KZi4k^!ezStz`D7nsN0PG^m@e`|_8Emc%%o
zn@+j<eimt-2)K}WPGW2f#17QS?an;Er98VluVUb5&)(_T6tXQJ%3bauk2)*<Iwgk@
z!t|q(xZa)ubCSudJ~Y&Kb)#ovV}gLrlSXbUEuxsh-Uz`zpwe`HFl~EccZR`*MPIT0
z&Q0O7&(`#_<(VqWWv%&*6UGGFsZ!5QkIl51-rku3g7~Vqo5()BJJ{RF51f~8D2jv}
zH%F4TjGSiXR{Pcsp9`u#{CcU;p^(Ud*zyy31;aizHz!3QXLJMUQuXq)lN{gn{>sqt
zlarR@sfLEx%ND<YjiyTCs}DN+QLVR)`&T~anYCT7wPb6Ct<QssTe=RsJ~W5l9JVBF
zcIr^30&|qx9db@wyIQ6hm#<>4E+;R%!h?v<#iAHf`ELsb993V_P55w}+P&_~p1%X%
ztz`1%gl6nNUmlBNb|RXPDRX~Z9grhg9xLF-EM<<Nw|ZqX%i<82+8z_1gR(`EX(Y{6
zjq4C3`{M;O;L0viU@OzzZIsdqX|`+6M1BV}A@i`pVWKzeHSa*shjZg*3{~<*syZAn
z-b*||sooxubF%U!V8dJ99$xc64+k7qNUb+U0j;w!+sJZeMUM)!%!##{Z2e0P;o|hv
zVwk!IdIA4Sjp)%I?gk^~<&hsHo3*;RjZyGl%Hoif=c?q~@f44T9a&2AQeAV5heTf*
zlBz_#5hNa5$pC|&d6#5-V5UXMQIHII6>CQ%YuK=XGs9vFpmad@#&m>H)yLA5&0BF4
z?8PA9$64q!Oe9l%P-(;pTI`(I8u3(@+wNKatm%$D>D{%AdNxNlA5In@+mX1|_wbM-
zqB!71&e&EY)t6q)1ivGD6caQD`EILjN>Ev4;tow@4tOluLWiNhL?F@UEvTk6DrVi{
zvho-U8p!|hDTB!e<%xvsF>D9n7~Th=vEJU<BIpqeP}Bub=ba72@Xq^A<%Be>#qS3<
z58-7>eZx_Hsixjks}~k_DQBthNEdkQ!v4;C<uL!8v|e)F-fLXB)74=1D}!dG#Z<&@
z_8#il>lCg7gxhcU+~@g22PItUbXdC90vwfKG^&ha;Zf3~ZBelO{2{0GhW)0h8Ldvk
z&!$tzx|><12Vs#q-7cHM`$;C8;L_*CUQ_l_6$c(y;E(i`!z!Bs3`<SzP>j5%aul+b
z2l!**YULe2)a5#+F7_T1%RYACp6;9JA#)dCSSNRgKB1|&kjlX+VW!h$=A~SXsj=Ua
z;;DH$n!J5A=U0G<wiO(afz&Dk-j;S7plifpNb^U-nczYmg&-F@qxuWUU19gyHQu-f
zG}c5DG4UU<F$)9wYi^4kI})Iv<gh0BeWIhhY%-AcbI*NwT}}&qU3$fj_>BBq8=-l?
z-;(nn60e!i?p3SLBN!vyb=AXSWLV#L%@He#PO%@WMMl$u+Yv+`!h;K?S`H*3yaOnq
zP9rcz|Fa(k&q2F5&z<x`@FHTmacdXSEj3Js@cR1$pHF@jNJ0)BKFofgVAvUw(AOmj
z7Qazz*Po-Z8M`bzCk>k3GOhcDOEpMB*aywNi>T&b{Nk8@Ug!8GxVf=nD4_CGkNoKJ
zJW!w}Bd`;1EkS8yhA|_y;2z}p>Z9{8!J>WN(sF1ZyH)t+JqUJ-^L=m?e(on`XFxK0
zC+WM-itf^J3wT3?aE08c_aG8U4{sO%BSJb&XdOyB*!qazQ-ypw)^PC=VXR?^fci52
z@f0)61hD~m$4M;B_Zchi#XBaq9yHbjVbtIN3xft<Ywcan6yGl{Q{}wLwhVp)RSy@*
zu&N$5X0#n4eJrv+SVtb?F~C!pQF}nj&2#ZhZ3-4(#&2*_FXq|g>pU*uIZvrs6Y&a+
z2OF1AdS*NX-`9X>If)6gMEOjDP!uyTUL!XCB2B~HApUXul+tS?0{Vh5gwGsHW=QHx
z+!yGGee!NHt?Y=hD98;y^~Pv-1->-0upV4Z9oTC4gVL9+qKFu&z{ST$9B!hmbC2ow
zeY^M#6dt`tOJs(Dkp&V^qtFwf?_eOhb}A%OCcoe^l@~BdL>i<#3^%3L%1os>#3xgk
zFI#Vr^3ds1vwp&Vg*>axE9U!kGgBgy0q&jv6dB(Q@|^ShD}C+cgR_W8*coc~<dO{{
zp11J<8j`nhs~h4<sadLTnGvQC7t*({yywIZB>7=1h^`Z@pPtr=wZ1F>Q%oaLJ#O1w
z0ni)N`p()oAI%EbZ8NiY7m?bKtifuK8+3vFh+-%|(1_WmI)a^AVLET0oC@2#8+63#
z{ti(RFy;qXW(-y!V~$aR#MYA@cMn5^ed3=0Gg{DZ$}?;|e9xHujybp$p9m+Ds;D9f
zoVdJ16HfOXys8Cch?V<NBR1(qhj`M~x9KCHJ;RP-`uagQ^?@h7NV@OT;}8<W@0y{6
z*sqY9lvJ9K#g}us%@5EIP(!d`-w<sOX%8*lAsC_6%Cs`HLZW^=Msy*wjzZS;HT8Yb
z8q{Hhg#V<QrnNLK6U7ZtTLiF0s<ZWE4B@#i*Z0_X#nI+FBJ#r)`PLS%<=e+Io=Ud=
z29xiR&A-58PIfNPA9$Dd-xw&{J#PC82xk4iK+u0;p1QGpHUU6PiL(oI*8Fgs62v@Q
z(ZW1ZLa$Gi6bPZ2FKNX6ULTxQt$bJ8Lh_8Av()VjWf^cZ%E!ubZP_5?CZ@F%DDE4#
z3?T37DWpaLZSGd1`v|%!NEq9kId{~Rbz~KyXFcK5;cn?z>R}QTqDKf>XcU2OseG*e
zLA`pW$PvtwJr7WK#(Mb3;%uaD(nd1G|6+=mFTMKaWi_~SeGhx2RDn8H53{&<bc3Hi
zt8lqC$b#4+aN?R@7F2fp_I9taP(^HnCoijT2R{+ro;H;&zn#JHc`9~(nVZo9(O_a<
zSF2jcP`lZ(&gJ@C%lnTsXH1SuskPWFiHc$dFDh9tpKs7;_e?u{Ul&;nZ#H8Iz&N$|
zX)zcPOTt@W&OTur8;7nxv+Htx={9&)w^4M)5qm(~&g6z3*Ln5EKHNy-+#3<4E4%gI
z;rbPXzv2Y~0sn-H?H*|VgIWJZ%I~p!aT7-)2dJHst;0R={R`e#fLOz^dMPbAS#bqM
zaT5!Oy0a=ALjSv75@HRtatF}=t^(ZGG5oHyf|$Xva`wM9MSr9D%xpk*Ab^>Jiygqm
z%?pB~`XKhdP<?49h!xaG#Kz3Z1OWWiPQ=mZo)+L`=lNB<AK!hMnH|LWOCScZduakS
zGlw$=@NRyIRGmz$)d4)e+us*n{wdtg5T1!9?0|d3{+|f`J!SE4Z~X4g+0f}1U7-f&
z2<|=gODYO+H2Fn-{Qo=yb#QbNGlw|*aey4;uQD6^Z^Glh-3|B^kl%|%!Uj$fKyAzb
ztQt@o5gSM7AHgrn8c<^=b4NHU0%E(L#s7VRxPX7vbAh-3|NDSbG;ryk>;K&YoN?j4
z=Z$`!T%3PibMySiDi=JtxIy=s^nagRpnG-(Zinqp>)(3p-2dqV2;hKEofDoB_v5)|
zR_?hTxCH+AMfJcb8{1bl(0kqlaDS8eXW0Io#P^)i@7$Dy8sB^Ao_13Cn>2F1r<nf1
z+_3$Vl~QuBHFh?Fb2aov5U7JKfQ^NXlLbCSdUGcyJ3dx8{RNkrIY8{pp+=4@whm?t
zzY|>y&b2u~ZEeKwsWW<UK6W5GJCKK+2gnBE0dg?{+3A2lhJPCU5AXJe3KN6CGvC(i
zSAc&_;V&ZWKOB>rgNZ3R5WvQP4*dH7z{3LK1egMT%eXmtIN<ZSKL9p=$+&potL=Yf
zJiPE__uqQ((tVKbkN>pg;pKvR{J&(}oE*UaZOg?AVuwfKzx6n{xZ&><|0ClD{!5RO
z4ft;xZ16k6|Fq@g1;Uf&zx(3?vcnVXkIcyd0$<w>zgRd`sE5hDukLSRDz>)ppx^ua
l_wtgqF@?wWKJdR%$<Ybo;PlJ8++097H%dbzp(u&|{{RYy^H%@>

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..4588d6b1975fd9b8cff13350d14858343a4ce472
GIT binary patch
literal 79465
zcmV)SK(fCjP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz00oVOp+wF=Tn^JXi+(g2oGMi
z0|*TW&|-ReCukvzFar$Ew`gf0>FvdEH!}}rC3&j<Mxm-Q?9e~PjdAgddHGte|NO07
z|5NI^e*M?a@~_MKtM>IgzJCAzfBvVh|M-8bU;q98Udq@1bN%;!x&He<mjCU4zaCh>
z{?DbXU;pdZzkU_}$@t&v=gfW`Yx(MZ{nf7j|9n~dbzDD2;QQ;peEsL;QLMFJ?RxqW
ztG`Y=1%%jBP5-a|{`H^!WjUg8$5*Yts;yh?m-zO}YTu9Y^)H|0KmNDBt$!OY{g?l?
z{D;4lU;Tgjm;bT+&;Rn)0gn|e+pj*g&WrDDv-AA5*^xp7eh@qAuYGzI%0CEg{nyd!
zBn99HF+051)%^tiZQXzVI`(GmdTTGg&i$eL|9a<JtG~)Rw+_G$tt<UkInPN9z`NKr
z{q9qlzz<?a;Z%kgfFHy*i-{Ej5XHYZ``fnv>JPJj{rAlNX8V0A6ZoNRZM{uplz$K^
z?LL(Wyo=Ry<5UhY0zZfy*W%Vo4gi6F(-2(ks%0<7_12^PTL1h7e64?d0P5E6Q<=aI
zt+VYul?nVHc74&esZ8Jpu~O$XGK%ja<?NhT(ftJetzSSttX)&9T%YRp)cyaSFQDwl
zZ7QSuL+iG3pUMP&5WD{WHkAqdAXX1fWrzXzL97%`EervGzxV}|V!!I27oo3z#~yIn
zeI}#)-nM<e&tsI|g|>B`#a{YhpJ~7C^X(s48|#Mogk@*T>GW@&_1D+AKTP_6*P-XU
z&))MNn7h+CkU)7`sICuU^i_%pxOVt|>pIY{dRo8si?4odqxN(V`Ac1LeeZp$CW^0Z
zyOy$cbyx}scoi$xx;g%wa*4bPUh`ml?~|aAcR}lM_)b9~e_<GkU8lh9S`E(karg_P
zP`3KpG)v^YiTnB6L`&pd@Z4?#&+@BKy^bvRp-<#p@LEUjW1q-h7>RnV5$*i(i}-6h
zW4+FR_vx0%dn32|74h?x$h+X-=f_Eoz`NLa9ah)dXb5=~Y{hP4&+=awiB{HM+tK=I
zZzJ)Sj)<+5-zHlk@6Ed|d-utf$h+Wmxx9~jBJYCNmFPb5iM$J*$9?1l{FSjduXn{^
z<#jCn+SYm9G4GQtk=G`UJFVRo;Y8jA?R0^8>m~9oxNY8flc11y!K2MWUiu5;VAl#<
ze*Px@(xLG@f17BDyf$qpc5V|*z`Iy$zm0k#?}C@Webf_q7rgHJ_fb#euN<BFwHt0f
zeiMJ~>~tMdf17BD{4lle=g|8Z^ZV=fAO1(0?9Kh#X!yA2L_6zoeQDA9-<$mZjrLB<
zc>T2=^%xuKbp%XR<A3;n)h}i3$5F4hZr5319k0JWtE+GSJW;QYr;d|I+`zoFp-YD5
z&+i61b$N*xE;0kTruE`bT=oE6NE|tUT>rX|TdCky>BzW~T*x(Nm*1e;0gS80zWR^f
zfUNFlM%_*q{r*~J$n>gl>KaIB@Djm|+JWm&1IR{ty#|zxye7|u?EZ#3lFja;JpFqc
z?_vYZFJ9D$B+{pTX|8OE6&%Ruy9>FxWtkD1I;Qyz&%8o`)b2obl>^jlc~2GZsrHMV
zPz-t=y*iMZ{Zzc4>eNqH_bd*npRQ8LKJpU#r$Cpq;=<~PH^#rGh0titwLq{}5@D~z
z3u-^q2XT!XNbmX~AJ%@T7fOs+-!;EW48esI)yRjSZ{wx>A@A`EGS$d?{6dOq<lWi3
z`ldwp^&Wi$$ZKTkpW^*C5cbg;UtDkMqxb>_qCQ%q+j><Wt>~kwK3dU7l^@iKE{aiD
z0C|OqX3mN(D(bYMkhm5!b=iszT7U6puc|K&6xG<f$M|6mWXwOy&oUk!NKt*qzpi8c
zF-dvvTnNPWm=ptn*nUFMxMP;?v3d`no$={i&{#QeTL{4W#x@QFE@!T<?EGQx3ENn@
z+Gx}k4#2zNLhv~c#9vJ1*+9J2#xWTOkn4TRfGTV2QvxcFK%&u2QU@B{D0HCBSc?I9
zmsgHtC=3UHfxLidB6WfTi6#~w%EbXMVj%Yeja)e-`+=dw=wD@T;yQ_xvEtQsPBPx2
zrqSOIFL4O>XinpTJb>|%cH|KH@D7AS7zTmb_7w8QH0s<2;vaXzxGxU*7_}VuIK&Ku
z1HZ?o+%}fR0JWYHix>I$hT3<Q{O3#)C0;cUPLwUax@HTCQSmm3M8(@A67|*xe<7pe
zTYT?JApS|UI!Q&xYvbKxs~HF<SM2oz8Ix;q#JgG>@7_`0brNb&)8{h{n*5l5%YeKe
z>&a=`qbuu?QeNVWH7NhJU|+~SKD)Y0BKmb8DdpW)_esjTuWpl6tWkBF#G-cFBo@`v
z>1Q`DQG&J!Z`T6In_!Y?sGdzyQ9bR&dqd~NX1oCM-fNRsRIg29KA5%YWjLJG_~w^@
z!l060Jx)ZmOkz<ZE&4kSA~hC${E$z$x=vzIqjeIC4%3MYC%jrtZ81A`_;N}Nn|C=U
zF|Sd{iGh8&9N9GNx#i$=!j@b1Ny@vZ<mABKc_9@`95%|5lLPx=*)+Ye36_no!k$-j
zQrpLdwm6bP-Ww%1g!L+EGuW^%6|D>#cA;Y0*ta<1To6jp3vCjKPS8<%oNK-IElO?%
z+b}=3LzXc<9=k%(dF=w?jXJY!2i_Vdp(UVrZJEU4wXm>WfETdzZaW&ga*>a7^VMVP
zNr}*j4FKE1h6Q^)xtrjMSy!D2wm7LR1H#YvpDD1#i&q`-Hmtv^CdGyYcir_NZ&+Vf
z&5AA7g@L4)&#slTVz@kv-d$r>ECG$~T{SCkk{<|W#f3y8`5V!|oE04#=&Cc}7L#Zo
z?0y(^)}~Rz!nih#!B8HKa={gAGc=M1`Ymp=1K<dlm)MyNovF2BYaGRb-f#XAoffx-
zcWC#3;dmhIljbGdXSP_+u4nY6#FACyzA}*RWp+r+XTGyWkGV0HkeApK1+UPl5muja
z?wVJ{U*R)w0nprHtgFEm=c1vJXLqbHBIhJoVQ1ddzG(L_G_!r7a7okiKx%h@lO(>I
z3mK(;#yPK?x;S+IiUxo-_E=vBf;RROoz&RIj^pQm@WcLR^y9cqxj^OE^#k3cTSY%m
z_o_9kALuAP5H;6&(qnxd2<y6IfQ#z7$F;4TI%)PD)yGK_SF}-PeZ%3R96E)>rOgrQ
z6?&}d147?k$f(DKMCtmMW=fB}e;}+`j~jeBG*#k8cOhCVx<O1^NRQ8PAbhRG)Vd%P
z$B-W#-(olXXy>=sVO2jmCt#1Sy&V3!1(0|C!3#x?`}+lWsp2=ZPIP=+ht`Q+SutJx
z<IY&1lL;Vdr|U(>H+ArO+3`soeg;?o`DDT6JP`lkoC*a$oKs=N564Vc0*W!@R9G>B
zE8o4!y!P$d=y0K+6Ujh)K9pUT4#U^6YiF_8b;_;-srhDEt}6h(TpN4ND071~%zYX9
z4L8$*d&59tD=NE|4LCEEIQcJtysLK27mM@kg+%H4m#!d&dA@717=CI%m@T-<mR*V>
z+fX-MNUg)WM0<_(Xk1DCo^{ks3yHZlY5+Zo{_hwIIj~gC1B=se!C5qrsGC$tW~iHX
zA9=nM-E!gSP<CBkE+pzEC6hJuo6aiMu9DUjtA3{#NJqJQsj?U&x}xOM6GydyVBX_w
zwglwUbJKy=qBdpIffje_fpC_taM3w*%(6I%4v2FHTg9g1Op9%@q}H*;R<PwQw~fDR
zBDDj~K|Yb%j#5V{s;-R%_u#TM?SySZ-L+FROq)$RMT;-GbS<R~Ee`ct{1BSl^+DlE
zS-P~U^#rm_h}WpQ3+&=R!6Pwd6)o%=N<M<uGR?pG7<TQhbr0QM!Ac&`)rZ|UOR8TO
z2GIF{m(b_oJ~IFwu4>%bOQ(v}aI+i;CToo&z(CMRHI4uSDbN$wj-FKC){dUk=YtDp
z={mSoL$_6)J1RagR0iA2wcf^lQycnBw?JGz2f}`8e#sdK=3~7+rBnr0>?K`CyIRo;
zx(VPWT0%P*EiCXd(}}NQ?=XF46<^SWbd-I}?c_zS;-qD##xSmJB^8J@&Q*4(eyf*I
zw{l{wGu<CbeAdM@MGLkC(-g%ubs!yO?|a*ICc2=gzEq9{v(U5)6nu%caY-mX2`$bi
zW2P7E0VX9y!I>wtl4V1`@f1;TwlQff$`(^}K$yJO4K-feIjp6l=d@Me-a3$uvJbW8
zU9}kArH!Is4L5xQaHTDBQ5%R4Nu#={zzfj)0$VVpOh=DW@fw{$OT}xnd6a?=I<=jp
zph+QugSu(sC|GMvM-kj!2f_sl*VhXgrS<gT(PUpwjE*Mz%9)`v>U!Y#Xe)|7FH$+W
zVqP>EH&)kZ4uHRklW&XdW{nwCnx;AKr~~0|_|iB4tPktvrC2Z59(vW%w5_Z$7Y2fX
zTCtBe%<?r9Sfh+tvtom8n>Oe**1D4V)fETSrYq9gyoAZPV!*M<1cKUaC`Qe?np;pa
z-Lm~QI?8M<Hky{U7hFF}(-e;@=m4Us4L8t%bd-IHG%ou~!xeNuQQLvU_?egD#MpRJ
z8i21SQtl2UZmX@Ky6waXQTpD2#Lq-mk8*TA^}p@h(8M^-1QIRehcb}pdwwVv;-wnx
z!{*bd3~J#pIO<l=O9P7bVdH40MH9Ji3?Q0V^cJiGu2YV>VYg{TuWH`HRqw&EjV}A`
zgkGRg-?$7Y=J~2O6%5&`p2A^Fs_6^y68mJunqN<K{~CizMfCu@&6T%>cElO0GFoK-
zzF5T3V*%u?t~}zk<B+3tN7;L-9+*%A@lU&A16nQ!lcB~>_(Z7uPDk0hsd6`JxP=yJ
z#0L_0fy!ISfNK0swD9N>VhcO^ZBrBDyfhFs5xYX&)I{8K>xL$pgxEy$QbBDS*2B7S
zCL9gj-}UB({^uv(VAn6T>&09pYR8+ag!twXgVyzO98zo7yK$_j#>+|z7r%k<-8h3+
z)4Nwm`KxzaI4iX=%YZ0U`Am#7^)qef>}YJao8L<1?%8Nd8xTf&=j@=RU?3rc*}QXx
zXfeUXvxF^S0Te>$2l#-L%0p*^UC0sq3=Ro3{3pg-g^8!ss@fPPmX;jYXB=7i45c{f
zcSaCIyKxe&T7}|v=>UEMij7LuLJPCT;t(rSDaE=JNwF?Pufl>J4k!b_*3n=@D0S69
z;iOqt)h9NSx^kelQ$jG%4Tw@0tL>x|rYtUurQ$j|0LsL)Sq2nB{&y(Xik7=A)&WPN
zZd=@C3Kb-6!-idClxfh3m!ee>3h;rja$WC2<zhxGrBGo%AV_%$vq6TP1|JniP&>?q
za!{+%pm#2X=b3>}tfNdJ3@z2j1+jCBL)`&<{#%t0K0zvm%Yo8(epg)!KEJZ7vbb~<
zEx#VG;br_}Si(z*V^iy=Bw))PkgpA8=Pc~lItp!=tsfFYU8#93yCx=etwn2gkF#Up
zC1U`-<Q2qw48WI3TpdO~^^HPk12v=wIvr)optpOdq8vdJcyyrA>_WVNi2<LNfnd$S
zZTdo@bp5Nd>pQoJqAh@$&eGWuh7V~^fb&Z!y!{Mh2rUjdP$a~r6bWITLrGaW8-nk@
z$nZO$n2%k<vtn|&h@F^NH2*cf$c{1wCbW%9K+!@wBor+Sb)yW14cAmh;;n`|<Zu*U
z0K_aYe#f?Bl5lfshViCDLNkuH;Zin`7;##yn{mXof8jzo5R9n#ulm1?<43=iW;hur
zy0TfrSm?A&{a$J8fyVLE`B_n8O`X7D*Pdut=ZkhlD_p9Yx}jjiv{4#V&jq^7X8f2N
zr*Y%wEVEi`{G7F$Hh#{{O9y&adn>$H9Eq-IP$@eUm1(el6j<w8!)3ozc16SazUai?
zV2T_N`U1D4g6POm_SsF<QEObJXQZQkT(cTiX<Cw7<07qny*2a}FX63K^j6iE10QpT
z&<b4e3S+Drm5H)aH{2U8#7jKG7do~KD0*u`yo4^VxXTrqG6xc!S7=OWINq0{V@8E)
zXF_lQlfAr!>X7Bdfr58opz5a3$3zUT!q8PH=ZTCT>hYoKKttW&4T+8kdu*fDuM`eu
z)lxb`Y&yP$TGh@(YP=icUG)Vew5l&K1#nE6kaDsO@kvoLR&+Nk#}oqEsHwRjb^Zma
zT@pBA1gEz`hjIhhbEy2fVL_Xb@vmj-g|%ziB*MN!Z?2}kO9VBJ7E)2dL0X$yfMHx~
z&Z?LWYvrs`xo{XUho}d+A(~aud27j81!VeoVqsbH+lfhD&)>h6flObEBL|lneq;k;
zPsB$!5cC8Ao>wbMTxf8nsnm4n+pjRU=lW1RBraEwQNAra%LVm$<?)BQ79O8A1K_&T
z(CkocXpO63USGHp0^-_jXcDZlH-t-fys75O9h*iyYcAbr1WzW^@>i-dxC7L4)k+P|
zu>r9MIS8vd5Pg2|Fw#)co)+DCK!=grT&1R>(BxAOo;9&I)&rjych3PdY`WMr1{9se
zeYhU{>cVt5%B|0P_k~P*dp&v{B+yaROYo3z0n-_xQX`>rMm?sJ2P?*-hoQ8s^GRkP
zwNHngiWrAH5Y>bCO`Mt>DL5jrONvf(m_G0d_XC@kR~_IuHK=dUxvx^+z=L6>!a--p
zN__(km`gyE!bAv{;5eezoyQU$Ve8Ig2^A)F*Rcd=;kxrw!qf7FeC26+1d~MX$9cQ%
zo1TZM`+~mm%sygGD1f$go%7i?)0rJ}d`EA^-C-1KTsAO#JBOFokAZBsDxo2bGO%Y<
zsuXm~sqmEKJ*e&+VBVA}6$*Kqs?;d(##Q$sDNM+n`{t&R;VqI4So7+M(b@PF^Nu)>
z5W;NRPF+3GfGuy4z7y3gFOg`$c1Q@z&bCVk1F-Fq;s><xRuS*Pjp9&cdAvDPSsrf=
zRkw#BUU&F`G^h(Y%9LSkjW1$lO(IZI4rrx{0l(Wq>O`SIi-EbZLET8bMnt@XdIXak
zAup*OVZ=+SP#E=+dKQm-p`L|ZStQ2Ftx#>QC^aa6*p*a9uQ)Jy985^Cdi|6Xs@G3R
zq3ik~Dd<@$jP<F;8VJQOGwG{UskyIIDbzxXZlzK|dbJAked^vSl?qbNRjL(2hZjH8
zCB_<ciJ`;jepRDcF(axD1D$)e6pod?RZ>chSQ<#NE|?Wn`!O7;mehcbP#Q?FD!9x@
zkvfo24Qu1<&_XMEr_wD-I@{Wdq*$L-%3;j(zDf%B6-L~o2AL5zsb#LAcc2=&TB@O;
zs;*Q!K$~4d>mY4+MT~Z8#4A0Ts&*Em|DIIqmHtaozmM3O1L}9oTZ7gSI{Z<tomzfx
zA{~@u3h)q|bv73;1Sd@j48eijVF5%#1z(<~ig>wAhK)*91g>s@goaBdk^#lU(kg8<
zRP5|<tQ@k%RQMDvX|Wj*H+!FqIs=Hors2nfa#os!7?1<I(E_MXrX_~t(D>x>IDIxx
z4J3M>x>%3N3F8<IT_fTq27tD(3M;eBWwk*et+lc3=zh6jR@jvX6uTnT8?w_~$YjU!
zcpSHH($+VS@MMrha75wkJ#B^+7T`214kT>nTD}^5XJnkLZtqR=Wu>k|Ce9Iv6UNrU
z7tzkmRcT?cPFhnLtRsV~2kXG#%2&aWSvK3+a1{!}t|KuyWcnQdZOZH{Ob!{4J$lD$
zBR8%A^~n%TqK`CIGn^-E*_EDHvUS%`nJkk<{DNdJA8|Wj%BMxWR=PXT=w9iJm6rJt
zxD(Bx`My$tA_KpN^7PpWfRQ}mBrr<usU$CgN?$8^8dUmP$rGVsAxdwBT047xQ;lKo
z)+b&KwcF8bD8l4A!7v`US41N@7vO_Y={qGCjf&kVy*NCIXH8F!ai~X#PI`xUgpP}y
z5~HhwP8~G@GQ$aFl%kPxQ>oC>$djeY4@&0;`9bNhP-5d)!aatuI`E$X60g;#RgTFA
zr{bU*K02cmXI?q+R2-Sp(`O)X>(P(Io*{>!3vg$m(OU(_2}Vv<TvUo_>&5jaJ(Mc0
zQ1W709HM^|zU{d5!5u09IZIXOnA4rAmd3W}wuMW4`ejw<Y}0wGLNy`(t_yJ2FK=5c
z3vvys&_Bt4%#j!}?P>*+g<fcjL-bx_+g3TRv2i$q!sBfO=!6HEHmud-W7BPJ0C2s-
z2f0GID)+mA#OP?kukeLU7e0peq?;c@d*li@fNf1*!BKAT4CG07#Q{|=ha-x|Jvdj@
z&y`AYTtt{p`ZglWXPF!zJ<i9S8|fffS9)*iB)rmlQ@hD(Fu&3nv##>qL<ydoY#{t;
z<nB45dcu3NW)tbYsnaQ4ue#Ja!}Uter-%be|I`7vyQefKE1frWoLr%$k}K>$Hax@j
z6$BK>oz??{yc2Xhq>Glkay>u@&vcYSW*hAr(LYC@yna1AXq8{E!h_Ot*du`Y>|MMJ
zDEweKQ5gbML=#Y`m6R{@h>;05aQ5xuK{D<~-6RGb`o^`zBVPLKUF{Js?n)gs<}Ke{
zvqy+ZxOUU1IuP%F`gVKJO1gfJFqNLp;Y&oac&&I7A4pVPjXCH6&V%4UqUN|UN3=_W
zn>(6!;Kna%4aUEubG*mDxPShNQp^K7*AFCo^TYRkgtmB#<(-dsm~`GBK&N~E0w5gp
zxs43Oo4E5Zh5(r<m|!5@#9bz>0r{t@sDuJ`7lbZ20!0#|8yHB#(1&FJeF}{z&>Sjy
zqR^R1Ar=LEC>e%P$TyO)8U<7!8P8F`$B{uF2(_64LrS<jEfF*_N_`3`DWI)D+zF6~
zx}a{VfLa3aD+{0))m>8vchP;<i*cA#tW2Sfau*|qhv@j*xVo2}Q8>I^6#7Xic&C8=
z00BM=Apb%c05kyq9YhF?azsICVu55J1C18eKBJLJ_);lci9tLHaw-V+&p4<O;r+`L
zELFm}O3_p$LiID^s?fK}W3&o2pdP}t0C5323k-n4VVDf`vr@R2&n9n8oE2g+b%dK0
z1h;2|TA|C8qSyu!&uH;r3{OVL6$FN7JRLtW1l<KP1?BNW^+3J_fKTl+2PZr(6c5Pn
zKVt?9b*6|bTmnLLA|B|BOGFuAiK-TZD!Gb}l`Gn(AjkoEU}b#Y1p(O^L^+VCJ@-Ve
zk%iWxfTI3d`8Nhvc9bFllDpqP`V<oC>$Phe6gOI^sy(>_ZpRdQTBx^Gc<MkH<q9o9
zp(-~5U4bypl`X`qSGerhks{9Z$QHt+t(e<^L|3sCFQN{0Ahl0Xy=CKtUZKAQR7eO9
z4!{Gdc?v5Es9rUQ45*ghehIcD1}PWlku#3DD56>$gd(bW##(&aUZ;5J0mPg1X>W$`
zZGGE{scz~QTc*(MaXg3@X+PLN8lf2Qf~e|_e@8@hrvkAkq`IqDKn}6yWC1DHs>u@c
zS&V029EtX61%R3xk?}yhCwI*<kUl8Dei<aw(V2%j6O2uW(Ju(M&M^MszIGYtUp8#;
z$p$c>+LJF}l!IVlRqul<NxTDPBfG;2ulTZ&-9aY`_t>kl=#R2@uuS9w31*4Pkh%gb
zd@?B%@KaUUYYSZcf{J03;>B%}aLNeYGz%iMgY99IMtfyFEbt0U#)xqujd#jjxgcme
zX(tL4{YgzxI(U9WU%{g-F3$^)wM;A+ejv7EV#+A64v0;oAhcVA8;e6uFtJMrL_Or~
z7(kb{Aj(mfV-g8+4IMr^Sa@V@xe(EeeEXT-dqGqrC7c?;R<Z!`=`Ko>xH(Xz5@oN6
zOcc0mBzej*5bqT+tc<9`Dnr7!y#z~4)mvf-lSQB~q&(?f{La&hbV-3kU2GByk{Fw$
ze8o!w8eXufwC>{)7A!GcVusG@l5!o_l4LjoiO$+4sXlS)l(4f*ygQDph1@&~pdgLe
zC$XrYu3NpKf;l6=I}t=d3n1^rlaq)<JLe=6U6_-ifkp|N$>Mk4J~J8l-S|8wwxa^O
z4+)V5F!3efdc91fN)C;7i+G8VnpJAu0@u_ea2iM_#nS@7JGABc01}>NC^_SkO>YUp
zCz}L<kFQ0|u`r9Qsvv4V*{q<02(qh!7=DsrEr8aUG0PPhNvaj9j`Ns^x2XIOH&^M{
znv=iFAv?(N1ti$24oYEp7gJb)C+?C|Vg-h>q#JXM&FFk_k~w0BNXrVmcVR_Y0Qp=I
z_Zc-oBu6Wqq;@()z~xsIYm3xLNy9dfpmWoqv#&|zHWX66T!`(hgzNA!QNj&q4<0!Q
zMGI{b@=+4^oGZipy?JZ^`(BdR4J6vQv9y+n0}m>;q{$mV45YM$#mHc%;kTKf&sBN;
z4l23}42~fBTL`UXq62iLpttdy#9|aR(oh`Mj4d9JHyiAP1#eCMLh2ur;n0yju^>i3
za1cC7rC>pHN1YrMn@PA>(Bvd#97ueQopzZJ(FbnWKc!78Fs&v<WPywK#3NaP>oB<{
z3kW5WkJ6EK=Bz9RemrobEPy8N%Yq?HeoROD%%Mr8Fo-sNRkc03M*Fwz=o{S#C*)Lh
zytlShU9*!+bXEUsNLEqQKZ&q^z`rL7QYg2ViKw)IFhg9X3Fs&vUh(8ZEtvD5OkHk}
zwqz*QlX=yVb!KNxgbc0)R_|nab!6g!Wm$?F+r%B4J>$ByV4J1RKe=dUBs(gIV~?q$
zi11p6d_5w^P2ik5%DH6o!xRwT<wB!Ga`nzg_KQym68_FWc8gySlQ|d=n1u_%6q0#3
z5z9uBzIahl2Op%JNDgEnN6S~rg^;Dr+XY{DY*X(LIW%})<s-i{BBI7n<BwySNkpa|
z8+~}3Q;z`v0U5{QT&E5JFinFopl6w<0TB3vXl9&cng$Nksi8i>&N|HlBF8*$7x#!Q
z^Tc(8Kis`^^yyPL=TFQ(meX{o<QH}R-8Xjj>>2+s&-oMckN50zUj;OOXP(|>{>*%t
zIQMyR0n(r=hcRtHxwv>o98+ictU8aWvxw-c+1<}N7h|6!=Q%CL<8Q-XI~QXjoHgLI
zYpEZ>ialJxb2T1=+14_x#-laE%RE<OAG!hMZZ+OA+}Crr8b8@m*@2y?rM|=9Lpq?`
zt`4tJpSG*RYt*Oh>hKzMO{P6Ay~9tReH2SsTeoR<FJ7a4+TEj%q{4`;d>Ke??$IH~
zw3$bT9Mfh#sy4z8w3kOj#DF$c$UCI0(}|^({2Jp_<Jmb>J@1QBa(j>SQ7dH<^Ug>W
z#i&WC(;3YBq2z{l#?sk}cD%Suw~{-auOm&)**pL?IaBk1I1-WQgca+4g9kGYnoXf?
zJd8H^5%a*>7?`(w;Y{1)(~EQOg>3huaVvQRUA?4pbo5wDbwr%Lo4i|jL>~yRT`Ssn
z=o%FV{bfL#&i>IxibM;g%EX1D$<>pWj#k&WHN~x@$wiY_m!=3|UT>N_D|rKIRm_{b
zCJku5N_l(^FGX?NYVvO6jcg!0F23UuGva<y#)n8Qh`jo>s<DroVXLMa5hA4qlv2?K
zlT<|;WU9b5wZX{`_t+NN2i<(f(ARB}i56^<=@CZN=j(Kvln=0kH+j|ZUf$$HN85Ot
zl@DG@9fGeOcf~{W_oR7<%FdbxpDj1dgU=Xf9v0~<+D-E?y7#7d@DE^8JVfVC$_K-g
zpOg==Q#Lx8Q47;1-9s$AZPGoAZ+FD&!QcdKPit+G+2fHEiQ1+5!B9P8ggdoQ1EN?*
z^-?|AQNL7AcGNGoX6VBh;rLCZSwulf%&WLf@AA=YJ43*SZmzXl4Pt(^maBm;HXfq6
zQsEbMIVPdLIFK^YS?46=H904l=qz1#`tH%B?C;pyo8@fqHEaM9h>DnI!?>(9E0ct4
z5gF_n(5Q#i6!8wRoC?@5Cv60_N6X0&oiPwjaBPODk-+V51oiSm!p>%SPJ?QCK>Yrq
z6G!MU#ZL4D7l+uBj3@MkO7dp8IGo-Sn<RW<m=4^~!#CR}i8wk~n!Q%^M4G*@SET9!
zmVuV43%4CK=Y^cD3oZ2)us}4E{Tfz^X1^IS8dO8eH*FoQry(Qu{?@f!xW%M(T2K77
zT_=PM3|Otpcnz}*AE<b#PIzJ3X{o@#bs2&63m~8Co%*V{KsWge(azMm<_2t04J(sd
zPq2u}M~GIf)-^Z$;yq{tXc5AS33nja%@zkZV&>cgX^ZojoGK4k=Rk1qEdw4%5Eeku
zLaDD{32gEjqP4Jf+8d)MwP^U&esP3--|-@?8o2DY&V3{-o2_db!S%n9?f07&(jb+P
zS#=B=vV_vgN?wX@Sz$q5;a?C;wF6?u#F{w}bPN`xRHDEv+%_4!Hr@y}S-fCiZd*es
z-Xm?-=6};v!BVreY#<KasZwz}II~jIPVPh^oj>A>%9a!5#HP6E@&Jo`+dA8abL_UM
zeK@3UQg(*rzh%lExCb~yr<N7{#3QGB9W>E%(kG#9hq@o03vJUX5-N|j(WQ|d5d%SG
zpadBReNo2AOP*A4x*!wHw;VItE=?!G*9M~vy++~$unZ_V20kByDu;E6(QCT~-hG`$
znKeP4>|I+1yh}*j6G;4uF81z?;@m&-VDX`4YN_;oYP*!5aC~W~EWWB;M+f-MI9t)|
zTeAeE5#AKv%+6K7{c{FS5?j2XCQ_ck&1WD8V4y2d+jVJlXQAM1`j#tHW1eO@9JM`1
z`M{lQ&tb;=-*cF;v+n6XgH2PuO`#$PqAL1T`L7(hNx;*p9oit^j@6EIn_HC)@tY1@
zi}PsF;}5r>LmD1<g0+K}N_dNrvFls@Rg2Sl-Q3RFp_RZL(?*$2XK~dyG&$heHV}j_
z(EZIB$521)S4T%FnoJ!K-0TKGZ?}e(;?Ncn?s_ftcka*E4y_7s_-luBLeLC?c#W=v
zQ8!&j;9NKm_8m5wgIXfEceNvawX<%tlf%)mrAp9!A;~KDO;;}x&wb0E(%I?gE*Uz)
z0kQtrGtxr~ZEL42W^f7{i25HNKxz`<BRUYeOF|!X^3V!j(*eL;5(iKz7U8ivxcxYT
zd<RHJuHy_cz}Y2s3Bo|M8q0Jl5z!DQB8&#X@pjM|CgOe6PHh`-6>}y<`SeEpwFAHv
zcrY@;4LR<c%OIiLi3}l2^%}g6ZPm90*JP8s5gnxlVJ5pA9?s6HiAsl(gw&hqCGGT_
zMq~rRC^{$uozqiZ+aacS1aL<<Iq1!^+rrIg`AYY1lU9x{;)8LNp55cFKFUo`>|G?K
zBUEZ_UWD&^tP{5GU+Kj@I8Q789G%GziQe!7k?*^q?{;;Iq3bgKz|aR7f6&nfN477n
zq85}QU+LmM$X?mLjy^cmLf>GVA2!bO5lmooT|%&dxmJ*|2u?1G;E6bE4TNpP#zUIg
z412Jm*fz9nP~CD2qirV5Az~~R@!@75h80C0_>t6tlEX=EEon0l>S3iSkPOivmfRIk
zaGD5>7*%4)GJ$$q$v{}drx?i~5W!+%c8DsDGNLw04VGcN7D*^9`4tdDW1`4noQ)+{
z0%$G<>oFr<Kv`kpIVcu+bnzmK9_nhI;We9@XLwB#3Lvz|NFRXUBWG<!$POl#l$s-W
z$;z$<Mp)ZG7$dadH9Na#M`ILugQ%*(IL)7lv&lkQ>I}^q2!7{4ixl~Z@Gi?hdHl<Y
zwim>bIRr7pnhox4h#?-$GF}}qYnI+w6%pSiB1T5PkqZ1<5ptFx<cOkk0&%Pbh_tf|
z7<U@;U?PvPf|u1mA{H-ZlqvXosZep6+_)GlXc@JQfWm=fn4-VQQ1HfC%>YV_Ud{MP
z44<637!K)-?lDWMkM-iL?`RSBld9Dlk(L9gb1>!rSlyF+^U+Ty#wkN8vE9@Sr5GcH
zR3c#1GK9LhOSdtC8bPO{jH)9r)ug#)@aiDgXP9h!<W<?25CiMbJx<m#WE!!wR{0?`
zj(h9@V--d??8pGXK-q>SG7J-uy`D4xuQId}8o&hs!UMpY@Tn`09ixnG3X<;8D1~V<
zdf7xp%n)bGnCJ~-HpfJd90}~HSO%<#3IZ{wHbqItI$%?fw71pTszHgCF&)G5ttfAs
z!ldI0?P(k!7TcROeUAt!ABdms=yEjxhS85p%P2F59#f?G4<M+0Bp$~cGsKRWoaqo8
z&*bFa3ZS<Pnnrx6DP|gB_yZtg31aoFiK`(3`W+!dK|^=a!Z}C*MhOG~*lse08mt1A
zG1TzDvX-0-agMi^oD4WnSreNOcn&NhtHW?_46cS9+*<N7Y!V^$2{;$5{YK2-89VrL
zoFiKDG8~ZVTGpKdVgMZ_itydo2^s@aJ@%4$LB8pvwRrLnQe$v(C}I_6Hj|d0v=;-p
zQDejpk;$Y;jNBNQB3flY!(lQGkg8*`4CD?vj{(G50PBx6?Y4-OG=_SI%?4Rhf`Y>^
ztGEoo*kYpA2SbT9?-y7|Mp72c_zp6DQ)oCyPzJzyY?A6I$4eABi=anqR85nU#nZpw
zS8y<BCrTlqH4DZ8Yo`Y2VBN%o13kaV1CvxU*2IJZI+}rSfDnpn8IukLydyDZz<o24
z-eAgr8^`3z3I3eLA&~VHNs+9lNGhJddXcg0&~!V3Jtq{~meK7{V>3_Bx0r*>_;(l3
zd1W(Jt*~lF0aeW?L>eKS5lu%LkRW+hA#Bx91Djk=$*(jJ%<rIJV#1<tF*FTiRB-tg
zkCV|rM5-rGdW0Xwox-%*LTzbuX<bAsH6St_of3=Bz`3bLkrl>PVPdf$#g&;BWLKto
z0;d=zs4|(->04Y{W+J)(-IgO*=@ADyAg>E(yG#Zx5_?$&{e%2#AYn2GL6|9*2`R)(
zRxr|xnfZAySjd>j>N{D=9Kvgi5~Lx+=3rX)q0)2&uYotV$={bWYi8OF_T5XM9K%7u
zk{=FVyO}mb(7l<>{BSY#bTJBT<^b4$6SFFI5Ae*z1W_b6bd8qO24JvrBpL<fqQUUD
zkO|L{{Qz8fCVyq}>6!Qt4i2quW~Aj~YO`-~_nC<?=)l-&Z#p=(y3aw&x0vjXbOJOZ
zha9K|&9r|VU3u5O#Z+kF7`FhTNc_Zxk<#u4hD1x!2Cyg^-LMyNEt*k_5?V!5b|LaL
zn(1nJ@I%&~NaDwlUG7`Vkd{mkM|{QFF%N#lx}kz?(kxH!prkb8z6#n(OFoIv51MJC
z1=XdQyz0n@X)@W8Gt<aI0a{HnT?)<?$@QYPCkUIEZ|_@NotDHE;PbpA4b=thW~|W*
zGx>dsOw>#YClHQWGGKs}^o|_yA=3qybf+exGdWT3Nc5l13_+`Ec4VjHOm8CG13#-7
zj}@SBWzNEH(Yz8_oC`LJ-b^yX-jNOUjSra&vnC^XBmcu4I`HoPB{thzIofmQ!v#VT
zUG`LrZ=<g8hOno|h->VrEjB^Y^_nqom6X1BgdGEl+)W)3+XLx?O-v=E7``KWy!=4#
z9cmU4sI$$KB7v&28^WQCnKU?)Zza_Zi#uqSr{Acnh6%5(MID+5I}{-Tpn;y+1g7Zh
z8jwlf0CpZ3vW*|&46*yjh>er+4Pl33e1i~snUPJ+A|p1BMl*7oeAKy&^72In?`gKe
zVQfb9!C}_d{NCcrSjZkeeJu6&FOD?i6Vmb%iw}1Jz4-)@{ybLzQl#f9(V#||fQp-w
zRvVJ98-Anywq%jP{f=}lbIVuKzUNv<YIu_;4f*4>f|6pMi|isA`doJD50;BH{lRiY
zr#qNd{6(zz+!RQgubqV4`qOSh{{7sLz|p_trbQ0_-0H~lpW7jm0py0sgaJ$Js7xr3
zn=q3O<VMZR1lr2!&xP$ivN}|rSI{+9bzVW&;9!kJu#PmHK4QtDc0&YF%)pRG7G`P4
zBTchB<V4TdQ2FUp#553jbYiNAJYF%KM4rGJk3@M)Lt2VF$}w|=PJ8s;LXKJ>JT&66
z#3UJcj*K)KJZLh@Mjk~Ql^Hs&da{nF8$02Y5I)Ji>g0)z=sfo*yHxo6#svWF?uC~G
zw7T=;qckAB=#CK0?p1dLHnLYqVf=fQR0y@aSl~@9FBZK<<`>gFfsHWT6EK?Hs~i8q
z)5_`5kt{fGNz4_aixiW|<XsEySa}^|P8vrR0F+_ncgkQyI?uOFBf|47h+DsvMJKPA
z%(RpDP-f%FyDC%m@G`q7sZU;b!vRZoVmV;ty_pVJdACNkq2-HL@^7Ui%4>ThEy{a6
z^BU#dpSh3B^`gv|6f;kW0JbJ6R?sBH3Yw&#_G7*#X)u`1DYYET`4mbJri4l*3DQP|
zf(8>Bxuu|O0YWiM-*Bj+%7#g-pww9aQ3iE8D8i~85@Kgkt$mW%3Mscz55=rpsjOn^
zu2g8j?J9L%aJ!lnW6Tnk+B0MlO9dN~jfDb^$;hCfi%es&&NBkKQBNT~AM>736NtoU
zsVamE)}&5kZnac7G67qtB$=QsHI_``7D~;i80LX|shJIqs!`^POXVqZ%1OVvMAo@f
zz%nsiYH69gE;YH4-Y!+WNPsu%gOMh0QW}R-R;rbmYA;pKOveZH^a3c<%G!~r$Do#*
ziT_d&&g6hpl`lviXbQP!iow*kGYw(t<dLZ`)%HkcxKOzds6pM&chks$CI6s>!}M-i
zIE)uXBw(DZ5hFokS}T~qF)bQQ@t9T*q=8&y8DXl(w3{%UWZG7kax(2NNJ=@`Xpp%w
z?Kn(snWi4PSfx2AQe>vRXkiA;v??*pW>}q=hBK{Fbg4?a6@01|*|wPQGp%3937Q5n
zrVULa8Z(Q+(zXDKLDOP*manwd4acbH$~ng=&2{lXhh}8?O3UEzkE(q#95Q>VO^Hvj
zZOA0aq^wJtEt$DBO`FW_D(ffmzsfwS46!hwE`VB}%&bf`o0iy-iPppl!c4WY<|3Kx
zGFg0?@iwi(%!+G@0*bu3X<KGyUD%(aZkP))Qa1!;(v00AiEo;@nd3K2;YtJ?wsK|)
zPFp&22{XaF(ha9Q9vO+3wAnLlahmmQ#dSfZ|44P5&H+q@3<rYcD>EjimjO~LPo4-&
zyBw|xOwyd53`pd>OzsZ!Ig70DUy%{IPaYD?7@cku^e%Hpi{(q1ryYo|)#zU(?~IYE
zI-NI=$r=tGUrKhpOkN<&h@GAyOqreDB+R^>PAE#vot`Sp-<{qpCif@q^UMjJZZSw4
zzD&L|blZ}9jYYDmbikoMR(k0mi8(!ayt|O{NZvk7hHfNWQo{6f5n@7hx)Ci(x}I)E
z%*#&KBxY_m<#VJ<ReCrf1^hC(K`~2wdP*^qyd0^RY(AZ>_=`(=WHD`hdTlYYeR_5o
zlBJ~kmmw3%lKx@dFX=yKNMS+;v(ee%t<=;^OpDCtXUH~^&TLjVEi|#^3B_H=K$vZr
z>TW<WH2x!XO_w{1{I2Pg2T!QUbI&TsY0|yVXY)F{0CL8so1h^fZu%19TUsWELj!qL
zI3$je!J!egtMYkd^_u)0mv1fs=@V&{ZkyC4TBYBna?)35+UbC~XoX5IO<&m7*^|@2
zZ3TBvN9eZ+%Rnrl;kSviCfD8YDz!?N&5bSG<h9Bcf~p`LR|f>gRkm`UJYOwRJeWxM
zEYygryeNEs^FGjePRA`d;`*++7JBOfIe;MMnj3Vw{rWE6XV+lv^za`Z2x3j)W4r(g
zCs_J-`tij(iZ@Q9YLWiTJP_06InLhUO}$BIgD*IDRbCa+z1lAr?o17pNnBC_(nsB9
zNA7WV8XoTQ^|nS|Z#smJ+g^kv$z$BFm0msGs(C+^+c__^bWEp-K0MbKAlo{7xAO{~
z9`L-j!%ZGYxU-9r$dv?>w>{Jf>5y;M=&>IqIqaj&29NOc{HHP{V*{v^QTPBgI1yez
zrB6g3EI>TaL=g&9L1h$!S=SNVON^CZ#XBpusrFsr60ALDk76#UDa^nO=pUC1-k=&Y
zVml16of-Qv^s5LCi4ywEwB<opm_a5~EN2)Bb=VoILhU)PQcFO6ih+ThBg159hsjtP
zGe+nXz3F5FwZ2=1=x~xUL<i|iZ15c*>c<coinyQ!kpF^$hYT!N8DM0gZ&Xy0!FP&b
zOV;6K;+N=X4>;m7(#aUpzw`EQh~Zbnl+nE^!>SA<c#69+M&IweryJw#6{}^P(PurI
z8R2JIW;?^r;ztd2)70n|b<@eABZw%2&ju86W11a|Z&wJLbw-<M*C%mf#>NdO#I)3m
zkaLFD8N<mHf@h2#58svrkdM1!`3B-sis60+j;^-pVA>IUg8;!LApd5z9DM|(Dbmmw
z6256dV8$~#ad9X@Kea1EwVH8`hEP{3>H>){N2+_Q&!Lmn8I!5ygOS||!5oN(V0Kmx
zlRZN_ZDRx`_3i_yeF_mBK-4z$BBLC!l+uD2qqH||sEpE9xT-;co8hbjiH>O~^*I{W
z7?rJ%SwnvL46C&bQEZCEwRn1&B6iJnz!}qPcm<<=4Lacr3%099Q{1pA-dYDZ#ako%
z*br{58_R|`H^ne71|@O^I-5eQbr##OuPA)lyw|DHk8*r8jKVerSZf_nfVFlF3~vT|
z55$k33<x*HSm#V&jCD>01X-K<0lQJ3=E8<}^_&Zcnd><haJ*q0yg{c;v&#}t^kAK&
zq62j@+4e6^4Sdmx*SCncUZ$vigTr1!-EpE4CxC(6EqMbBUuYva&VY{O9x%pWi=JR0
zLHD5Z29|<Gi~ayy8IVK>7VAfHB^Xrg$){l3Iq@wRJOn|?umFlTZz+N|<66ofZCM))
zxh6yqu{abo6POqKIuT45Beq3CVX>%!r~-iB-;>S4uoNfbg)y*ORx8`d^uRd*3&4`>
z8U`NwWZ*D(Fp8vO0MQF&5{h0ZbTc+s4#WmBfanLEPIs&|vZ)wY^O})`#&(cEh?m6R
z8=2fC#yE1(n+(M3Lkg7mq2OmZCNZy&s8j~x{Uf#&L-@HES;h|`oRXX^jzo>Lb1))Z
z8h=O5Bk5t{hoVM(5(~zdK8ZO`OP}5qj4@QaFSeT)ZN>vQM2q#tcJl2==YYf>NuD#1
zIB+yg4IH*b!84GkU7e)7b~R<9az*+e|GN&AJBTQnCI!iMq#xKxwzEz`G1;k39!Q_a
ziwq~NBsdz#-jf2!VC$J^k_Hq+P`Z%pSXRZgWH{v|ACn<6A3EM85bsQ>bPcD)B!4ob
zFCjV9C`W~*o;8N_i{g49K?c<&<h?7ND%<yo$I6)hB+0G}#;Ih)8c0xYwMi`M-zKS;
z3}W9JP&5E$jsXPu7Ad?2;$2=RnW#UlzD9xprC7E7nApS&{=LaKW-yc`E7?Gtxx|yt
zj#6-==|TaI;G{k?zc>Ujnvtu3#A%B|!Hky6K<pGHR{=8K={B*G-j3RvpgdS6wl~{J
zaVL!pT#-c>=fHVRoN@!HowRcc5FekC8$?pvajH1K5cuu9)C(!_fW(QW<gk<AE{7fb
zb~)(ex6`1L-%crs2IOCnnEmVkO_7-Y3^vGQ2Xw@anL^MaF;3D94j_hhour~CR+dI(
zL}fUTF*6k9?7*msC=mzZA71MCND#473vomZCbC6?qjwTA8d)Sn+UST^M<4xBNc<QL
z#KxNHIM`W}Lek(ro-~sK8QlUV$|aB>$29dgG(qCDG}vpC_tJvDLd=+p1701S^l<l2
zj!i>aq2%E-&|ZkDa{$3{BtlO>6X~bH2|kHI4Vs66bd-Zz^vwRM6V)h7?5CJ*Nmn|M
z;2x#jA;>qDq&+1xQKK4EB1xZWkvAy`Rt0ozX-5V5taj-GtoI~yO+ZF4*up^y8v|Lv
zE2}e{5Z&>Q3a;6HD-~7NSBd1W1vGKo8dye>2RD(DedRau<kKaToVy0wee&|oNK<tO
z8|`t<odrZa<7Bkr2%eFyH~Dlq4$^TYv`=mK86?)?8OetFtU`jRG3$xwbab?dIXOyH
zjsBOf|GbRve7%14YT{n|1z)S%x*v8eu3!KBPhbD~Rle5iKk>i+^>e)ed2PUF^U2A&
z>t=Bv$HZQzarX9YQ<IT(XEQZt#Y5|~Uie7rjvQ-v?S1+_eJE;QryVkQ>W^vR^dF|%
zqCq8A<(|b2Z>jQyF=T10t>#feA=&<SkKm4@mVbEF`1?pR&(QmCzl!+CXm3P9z?%Ef
zwj%=%?}5m)bmqkvNl9`=MIys0(*W4t3fWMo(<x`3%!AsH$q>I?XEy$p3BxYLDQBc6
z>_P4$MX5KhOzKo5bK7@l?~x^Z*B*{ct(lmQ@quMKrFd(RY*AK@y?<q{M#D{lEP&tc
zP~tz@b#jS()yr2Voiuo)lYR7CvHfHh{SK4dsEgd{VU}LRd;CqKZ)S|OGH1dy=6_A|
zJF;%us%ztlev#i(xDR9+Wja-O=4d!oc*4adPsbCt(2|ZW2Q$XYmE=HzFr2Q3{@k0a
z({;lE1nJ<z;R^jCX8=0L6<Oqm2GmEb&}DIS{P=sgiIDcNloO7FNGn?8+6|i0qVrwD
zIFur{GjJG}BA)ohWc9M}Hs)k6@>^|@<2D~@kt>?Hr55g>r7!_8_KiZylW-y$5{%pO
z6ojg5Rcc7jDpkWaP;}0$Oaz!rByr0v$!@|NcIC)u*Nz4&8T^Kfdr9O0SJ|TbMeQ80
zOezkGgO6cU7@DObCW>&WFO{Kc%3aU+FoP=GbHT@tL^yS6VzyDvb0v>PaK)4by&@aD
zB|8Z^N93&)2J@0p#|6JL<-SH1d6SMXQ!}fV*F*f?-^!}yEXomnwPI!LVjWq7wV`ye
zC&NjIjI!U%)ED%hK7Bodpd+G+JrUPYl4tQmX2UHLfg%s_z9!pPjYOp}PJ_D5U%s2T
zFqI9I6lKWfSq>3{K{?>$WoIDh8iXV+0r{jj)e7W>D5u!xl!#C?ec{hLn6aSQ%fxue
zX^NCiYvxUi{6*^y!pInan%w9eL2`qk2mKD)i8I{9uk^Ti)QKS*c?T-;6!b_bShYQ7
zlBbDPTe+HIt-R$j@`@)}ufhGOYEFT?-#;p}4*Juobka&T&@+h-f^+Ida!6*P*_4Bf
zNo1yMAaMb%nFSaD6N@h?dYKQvo^1L|T_G+}<V-l`%mFRWlFR(ETNaA*b~yLM8fRv!
z0kPwn9QWiqmhVL7F*xSZjTS!?0?Itld7T!6FZtjn7Iu<^Cy6x~%xB7PvTpClpGPgA
zcmhRhoq6qCcjCbm$v>RgI^k2^Ocb%S$;{a$!%&jxBx$Rd^K7~iylt7>@|4jm*+N&?
z3i)N@%AM4pX<5a3n!K1vWeOG0L{3R#cq}`3&tbU^h5qrNtB_Lw(yt=wa;5`EM>*U#
zwCbD<-WiHJ9&2Z~{M2bR4R4oBfL>?jIr<R^@PI(~lZwZoKd~ad2D$AimK?rs6LlD(
zC+QOQ?FaMl1{JG9o!lN{!w`cLsR7_=?7mIlcY%MkyTD?j?DAaZPI=1nmy|S&B1l3&
z25mJZi%0GUI`Vuw*-4$f=$T#0u$zw9e}?6V@uG;Ag7gs^qcliVageBj%moeZ%oDvq
z2N48F5*TdBz_pCm=Z1Hko4(BC<vRtTe<5<b&jFqFWXLCuv@3(|GI-YzIgSSy-KhwO
z!eB~;fD{shNUFf5M_-Na2%tR?pXy~(%w-0fM$nDIO%!yw@!-`OqsucUa8>9Y!|oK@
z?j=U<bO!RB3{TT_pf?3fWo%abYDOgG7{ix)1Et>_q||?-fN8jr&har#&!ECPjDvGT
z$oXsH=t1bgEp`G?f>Xf4As2cEP@W8xP@K|<px~+)-^t560MI}$zix!`qwb7aO&4cr
zjaK(&{`wB@Q1{N1>brn#pfDKZy3^5VmaeAZzRB&K4$HP4x=$tnX8IY%Gx<X>ySRfO
z?y4TRyGpqMin7^d4@>vi85~8fpr+i`__Am3H5<1*{}-0+0~QshfVyse;fs>)O1$-h
zHdo2&%?<f&=Pot-!62sEIvKbb!aTW%NGIV_lHLX+pO>@2M)w10{I?GO19{)lB%CHD
zRA2lmG@W`BEzNV@p$LGI`7R9$u#z=7h``czNGmJ5Pns8DKdGrJ$}~9q8RpmVVL0gj
zSk~0JAJFAfvjq!5`j1L=PhT^sIy+BoGsNFPj@8uVNKLrkRDe99h0@RZaa8-d{&9VX
zSFNviuGhi8Jm~z8tsC)JAJ_1O&QDzcN58r^DO6)esC0E2IzRJ^Za&~Yl5RHCxOPo0
zs@8jInoBHgnJ&@}rv23LjFYt@dO3tudmt@wRq=E*S=Pyl+;N+bE62{ny}PD@N%KdC
zUfjMisj<P;tQHwlaK@`e77bj!YD}3WzKPK6QRA=7<~#+vu5XPD>HOHDPm}|G@z1kH
z9((!@LXUFlD?sNC^&ga9RLDply})mAaBXwlfzC-64~Ebe9Y%S8C_6Q;M&-$lj~0#(
zWtVRi7!=DU;|ItJ@-oekwGur*M{2+IZY!2w*CBKb6|yatbVaIE2+${>QXin9LwLfZ
z76d_T(Jt@t1*5(uvvhdr57l9lmT!ZYIt!%9MZu^HHY)PG&{=w@2dNB<88>t)8Pevx
zo(e*6e3uM+i!ay}I$sKAbcGKiHc!_F;U(~6D7tVpc)(1GCI<JG8pn%JwABo6j`>n~
z%xs;{uV3Hv2wPm?g|PHcpE4_XkOU01A+>$31}#aI5Q>FTl(q__5e|{31NuKvx1Om*
z#5o(rB}XEfq9U}g6j5HnpL(eI$i!6ddPEqUOX1aU@vN3>C^31AuG9qLjscIWA|rYY
zt$!(EKiUv2Qk0IJlz%1pd%<E@l4G}X#KibU>Yg#Iq2@#Vs;*8}eNv#&jfz7tZNuTG
zv{e@uIM9sg$9ofcB1t(hvr2Ma)=-Hysi=4(8{Y#jZ7!2^eu!i$$r^|7pCb0Lm6nO5
zR9fRhWxBWTATS?eDeXVG*GuN_J(0pBl01F8R?LMqrT2)iOD5zAHK6zSCT-0L75kRi
zZ9vFhb|n@H5Bsu9r2r#d*_D0vz_PxJG^vCmMJ~PtHm#z2J$5S+{C_KvNNNEWW;H3P
z^+EJ~NrHX&BRbVRlpe@Ey7D7h3Y>lGn)zI!K{XRLZm|DmQp63Gxk6j>!dy{KZ5^5^
z&{<w{=1bZ`>XyGTLSxcVmx$1Xsz_(9`Bl`Xo}|sU`xDAUs4-={ab=<(8n$21ONCxD
zRe?;8-t#@sDRySU^4+{<vY?Kf9(Bu9UPy(WiGurz;}*4tBR_ejX|dQbYxpcJGjx>u
zi{_-ctlKf=W<(m=*x?7Thy6W8LM6DPxp8DwW+UbrT$u*F!(cz9_GHSxlG;3Y0T!Ev
zCyvjV7p}*Nd``}|@nnuc-{85{F)QL|uUtF*lqX?hZliE(G|k2?`k(K}U8UQFpEcke
zi<WHQm~EN4d<#`zd~P`7r|Dp4_AX6L=HS^7eal2Ro3fw4h~743yQ6>9UbH^Augi{v
zOb26;cCOoFMR5(}j>&y67$<YfK>es|!B`U_C}@{%@ig5uv79latVoJCR&gt@aLvI!
zyL>ByL_1~kA$i*>Ll$}1*548jtXu<^VJ&F5cGFPAkW|m&P!N(=#J~!wv=Zd+Aj~N8
zbg8_f=U&?o>tB)*+!*Z)9U!$7l}3>oA#o<R#A;+hPx5836IQ*+$ObR({)#XkH(|$)
zCvM^bmSIx;R-G0|PQU~Wn~@-x)T7%j1r6T4Lywu9&O2WuYR4TM<siu{NnMNs5m*S4
zV_5u_s{RQAw7A)hsc?$n#{YiI>^CcUm!#KPNkB)7T~qQ5lZCpFi%B+LW_g&9Lq9|Y
zx{^OcrQd$z530vpYUDYkIkB~51@6J025nXF@JPi=>uoa<aGcT)CK(RNo)CKC)G+a$
zNUAw;v~<$rkp7E=L`{5OSiGDAg=h76lQ>48<gs)!*i!>d<sWJ3<@U~~yD>-6x2|lm
zDjg!HfqaS^*+%O|+8L2r@RLC#t5tbp!{5%BX4l9qIdKD!*eLaTD`UQO+l3w91I%%!
z1D8&QdKcz)S>^x2Nbyz5IVQhY<&aFq#8r+lb%Wx3m4`}Yc&wr@pndY7Tluv_ekIgd
zfx4^IiH(tnqAM`O2^>;o8q-&0Brf*MV^u6YlV(qWf-vpu^3!81p|0cz;Ny*aaV0|R
zQ_@8B9g0CUgLy!;{~42W_O7@E=rG1MnhL`W0Ws8bKyN2fyl|DuIFAi(@6FN+3<|a>
zXrU-hfNDF&OsJvcYHC%^Y=~NHRf=3Dy{qZMAKQ4LigQP_U}+gBfCGzkg0aB1HDAQk
z>FLAFB<L&o;pnRE4xIF;4ia7YG>7wMI+Vwpu19vn8PmNUeA7@0{z2_m|4!|9+>l2>
z>I*js0#VTJgJ8L-6^G#do1*bSkow3bK_ch7V7aL+<BfMk=HnaVu~mXZws*nxrWPH7
z+g(xmBuIVgCP5$yb$x21w65O1NeBDXHc|9{ptL=HYSXOAjW*qNyN_*(E7T!DDuwM;
z5W`AMaZIth?)Y(1$79(cKxDFbc;j)?M8|;Nb<>YiEFLQoB(lE>BKU)f?s(&jyu8sL
zgE93Zr~1kaz)x@7rAUvVNVWRoz{exq1yFkH#qFk?|D=Dkz4xND`szg?KlEb1DgQrm
z`%iPgWB2=G?VzCS2=*@6C*uNMH~}y3i>C}?1Z;g3Yd6EiCs%x#G9HH_9$O_yWP2B+
zn^mZ=KIw8TQ_1sCoMAtqAZ;w|U9j8?FCX7d@1~dsL0W7~f<W5(E?8#64&FE;FK>*;
zG~I;kuY%CK(QXu-bGIZt4u?Nhb_vo1)m{Y=c}%<1R8?83-a7{xoKKp#>iQ}OM=098
zqN;aG*kk9!V=D!PydMmZUmSL|kDm)C;86_bxL_~(O!m3<DpqHk-6!I-XCvN&7)^cr
z@(GmJFCTY*8U#NKSf5OUkDU^a6$ujAUj?a~U3EBs<|<8)j~#PBg-k)(F5izL(Du@x
z8CAWRIG;Nw9_tc>2k2T}1^YJJOQWVY1L|Yf_*0c)1deyHb~DC)$gnY)XCJFcn=J)t
z*X{3u<!0>th=C-{zYl`65^oYTRrOVHy&03Es(179W9JmOHd7FY@*@9PFfwe=R{h}x
zHjUShUE@!!5(BWkih=onwwR9yd(t}dSk2j9{+Vp*@0$$By=TGmH`DurAT9J=g4;h<
z)iN9MKk~YhW&c5p_Ww#T0>_&exDUcf;1f=TDnGuf%CZ(hEN?GDIO@>-AjIwt36E8b
zSfrhT@??0wRX2tY#9jI$a<p`Kco3vtM5iE;y}S#SoBKov-W@6)s~V4KaT4;r_<{x(
z?int)-H=B?_;qwGPV)5VuYw>f7~UTtl)fO3RSb8K-3918(w^VYZyqI|pyj*ym^=v5
z6-8%IBHQ~JwAP!)%12Ix>BI6^RmQ$hkjVZjSkBoa<|7M+Tx1?A8c*?%C186K3vvN^
z+k8l3neI0aZ}Ybl({UF-e?RRa`iibRA6G5koqHYx=>ya$NTio{!FqEQ3c<Vc&|_8O
zu_i$x=d0j)-dvGF@a~-SSk-t;TbPjdTMNUi;OP{CGxAc^cx<JhknLTt-8`v6@a|jn
zSk-V#(WWV<toP1AJ}r7`eS*yR=DYPENEfe7f<R=^`lDb&m;^n+KH?co->`=_(uK?<
z2*lPm!G<7xI+}&xjJ#Ae9;*;c<aie>H%B%I-dx+BtLl#x2@=^~1;Ij3N4bw^P1AMm
z;f)NbJS9k<yZ$P8*v%0Sf;ZQ^=c>AA7S)^S)A!yv(Af_^zmIHj;q~_*Kv%!b1yE|w
za}%^L^c@VLyEoxu)#5ReAP{jOJ-l&~Z=wrLo{CRZbVo%9c<Fo>V6X8e?c|#`56A~W
z_Fj=7k=L6v$sOTO>4J7c9^Xi}zEy%mwpT$07}pA+bl!ZdVnihSTjcHexSzKO{G<!$
z$B8FzKA{g{M!!#r!Ijir#riS(mxkEQ;q<YRHQXyH20ztTWvNpf!g)1h(v|hGdeM91
ze3`zlkLSzAJ7f66emu@+0v^Q-Pj!j`pyB+_V!<Q`XWNjPoo^qj2=7%0X~18E;I_MS
zy7qE&>wT<Vc<n+c%5{Ags*{7Tgv$F`f$C|sK>2;WXvge&>|%C99^Xcv<tjlU$EzTA
zVR{aS;N92xv8r@shM<t+U9ila(;xSoySY+7h>384Vs`gu{-c;j9ZzoApCD7ZIch%$
zLhH4j5~PRstHQ2A+eNqUj}pcbd3+;und>P*dXT@~QQe1p@+uF(yPx@ERU6s}K{=@R
zcfoe^T8H4xkNvr-{@5x(BCpo%x}TF*{D;&;<yCDiSNfGgD8Jnv=@F2hZiOK?J@6l^
z7?06>mB{N-QFjhA4=@$p80p~uAjpYTBuM1-$TU0xrf`9fyTuPYR&?*vCokajiyw{!
zb1Xv0-J=s8s~L|q3JN*j1?#*vd>D%S(_+C836od=au)uxSU<2Z99$|kyCIM7E4LNp
z^Cd*#77uUiw>XUuyhm<4RyAhiPC<oyw0A)svS}u#Kg2&!)nJ=Z=P0D))i7U;Cs}T3
zwc8DOd?VR=P6_fP`?`r%<5|pH(OY|&$}iRI=mr;3d4ChCw*Z+CyNAp?Rxuu{670Is
zy$KEitjb&eaI460oTn;!!zmE4Id1}Oy9M>Q&~ITrPgTQX^gj~PUX6bhG`t8Jg5Zq2
zRCU8$ih_(kYOjKDx@1h!$5|QfQA!VQgz_Kmte+{o>3zwqR4z4Dwf+_b^;p$-Or0a-
zRY_QJ!DUQU2;QTt9;?bxqacx214IpuFUD+z+yuN-lq66P3&38TMJjG+5f2tpb9~ri
z72}}|LMX$_`{7Of7HRegPO1rc6g;xuLQp|#uik5Q(vf1r#O*g@+a9Y*ttkb&w5D%@
zV39?n+(#rS3Y~kbXgpOZM&RvI>hT@tp(wnMLcTIC@3ETkSf?Nn@hv?Fwp)~62;SrV
z9;>=R&rLxF489tR2YJ{WMHqtjxWdP(#$&4liEM9z1$hz~rTB3_k9*wW!y6giSS3j0
zRYyAlen_wAqrcXv{3rwkVUO)uW#r0u5NfyZ$`HE;Ts~GY`fisXBQ;+?r4qp@4Bz}X
zH_<Jg^Fb`Gv;CA9!a)10*m2%sLqG1OagP>#cprmGiv)@6uY%xzK<udtwj1*JMh2~#
z1cB`9tKeZWz{fOm)~H*s>tj{@v5h-RM#;Wj<w}qj^Qn)=y53@GAH)!Gt9lZ6z5kI(
zi*dOjcaPM4tY$n`B}nA;G+2-VigCZ6aD|zW$2T%yxJwYoQC<Zjk|AAL*v0SeA&f?r
zKZ?SWUoC4SG(*ht$6ar3LCg<g40SFL6Y%C{SKvj;fauS}rugbJo{`jDf<Vq!Gmg)&
zDd74OQ|uOk{UC@>^*AKR*ll|iMBFIX)2Qk_!uzpvHh5N1kjVBbh`c+D7yl&x<oW7G
zoPp+aTu$VC7worq^r-4RLjAFG;<1f_Kr)d1L9pH8-J`1a2>8d&3G!uCRiX2*+R1`E
zRSc*9#BzTNuzwI_9Db7^k=N^;lPaGXu8*poa{&Ky=lEk<7Ktbl_s@ce3**`F<D2N6
zAmHJR;1R&t@G~(BydH$;{zAHesOp`7;IVV!F`X8K9It|4&?1|`M;=hgZ}8YT@z_Q|
zBK7qOJKjjPgm_zWCp^9>9$E30C~eOIeP&?z_}Sz}$?zaX;s)F$5_r2y#4(ce4j&vN
zlkVYhpu68sAr$5I8htj-?fz-DHg)-oymWaywn~u5t1k;3w8%^Gk%Lw;RXldefr?R(
z$op5`%fx#T@0)or9^Y0F7t--AFTdTYlV6v5!Gf64<k)x|27j!b5+pgtt6q@KQO?-m
zVtpz<zKt{=4MHrxbx7QPNd*!;a^nVh?ELYR?Ggi}NP88t<Hj=*ue&pkJiad;%XvxU
zeO`*>m_6BUye97h-r18ZzxL!lGo*azX_%BLkM9~!^<83MT6ymf(m8L`yO1`x{%~0&
zol0I$g}mxrz>zF=myhUAlJDj5jq#XC5Xk;&I`B3od(21b2+_$rx6q?YcZ!jP=FN0>
zy-n0K{;G+n=IK4oKS6;tsH|TE$V<KJf{zT3L|&GIc+4m$nw)o)0^fKP&8~VwetaY2
zF7u7AahIBxhmOLWm&dDHO49tS5+w3|_~sXW>^Vzr^g!?5cyQNGANlz@xon@PhT>&2
z_0Z$Hy4Qz7E3yN<3E4h#7{#k@q(+bL+M`C<jeF!t`k@y|kQA><x}?YV#3P261b@<_
z8<7*oPozuOd~Y;N&l|l(GN?nFjVMRocbkdSDPDMEd3t<bJXI)0;B`VF&j$&kV%MIL
zmwh`PvuRmyr2O!8pEp9Pc;lU->hX<{_e<&naa+CmWOCtd3YQd@Re4_)#FSO0-7%2Y
z08LMNF%fFTIqy!f^?1^Y$4r7i>Z^}t67n-Zv-IPJyj>>HA_@YjuOXr8ifTBiCp*~V
zDIG+<^AOaRkJToQv5&$v+MCHZiOEa{Y%jMr?Kg9lHz{A3r@FnyLWuUP?m8=z2<=_n
zgJ8iXt6TwZ3z4^b=@~gtAt>b440u&c<ZGWGTWhaAfWg*g5-85@@_K(eCqlQ-Cd>qH
zkGh2JK5=<H?^E94=c*aQdCEv3E#kN*txS0OLBO0>?p2`P=;uOJbtj~IRF1`CS{I4*
z_jM7OoLWx>;Ce$I1+la!AV<i1L{8Z@u;;nXP)vGH+QMi-DBqlB@8#kB#>E%v(>pug
zqrx^GYZ4@KzAK2%8`s~*RquE9zlS%HBv85vBHO#Rf?2A4!iFw8%P*R2f2ia7FG9lp
zCe&t<LMiv#dq|$R4Xea9vPiv(*^L1)i~@H~#7C<DDXBPiK=$%3xZM~QKT36%oQscE
z4}WYsC@8YV_eC^P_U_ms4x9KKAMH6koc3YM>CWKwBCsaSSM>g|-H=DYhQ~~TK#q6i
z26BxC>13GVW)jLrOI$nzMFY#n+a$(iigcEr2nRoBg3AX%@L=xraZ6^*S0A^6l$)f>
z{4nL$M4<T~NS;kbVkYt$iCK_86m*>aM!O+Tg5vR%-hjyYt~WR{uLSJO`<?#tK@23J
zo5TWm=LB$DbWbYLkDEyD<f0FP_*jvw=rggBz7NIOZ&an>1aT)XeGnwasV;{?-fxHJ
zaic;Fe~lS=5KIo$CP5;v2CfRyL^7>@lm;)kS04mP(JDtr(k-s9Hk^tK%w%$f!%m;M
zT^|HFYKH_#3j4Zty5X#oDfZ(=rkOeRL5TFSD;!x^emO;qhh`4ij}q1;EA5{JMP4iK
zPa*HafUGm5xcxX2&z<!4L6F?ICP5(O-TkRFQRsf$CY6M`4+7xaU3V8C1Mj1GsUi&~
zX?Z_kz*=Xb-UmVO`N|-f48N~IdE+tA{(jshB@W;}KTek5g1UL(@m5Il8}p5Q+<rA9
zkAfs1)~pcnJ}VHsZ|NrA$_;rGB)_p7<%#^@DG!1I(jb4Fl<ZE7{AWS&CvOr2QeWMw
z#$!pd{Bf$ZnRfX>D7cv!#3ruhH$_!NRw_$>b#SZN5B}<8eolXNaY4WPtG8|DhYpA9
z8)5W=7-*&GiX-6l+FU^|OzMVkJ-^dY|5;G1)e6B9@*W-mo@J6-hnM`F?)pKHtk{~L
zMB4lOH0J7~UsOe!*QC>a5G3n1{i1}lSHGwVVjgmHN0h^zt^3b{B=xSl1WEJV-UaK#
z{he_f<N|*X0%P|0&c8B-WAL`T3eBwI8Ksgu;}3%D&69#6DDOWBPORk-h;ySc|Ff9L
z&R2>N*nSc_4>F>E!t|EFqnP2TGF8%nH!rigWj;JiYUSB`W!p)f_NuTZBCl*aBWP--
zbN{%>>rU|gXF>76HwhAXRa%g6)}+s?`*A}a1#>=9kR0!?y1nsO(9sW>qp<M!IN0ku
z>gEYAU!oRSdve26&<7{s{htNJi{B+!$O8Y9;7p(YaYNUPJPML`UqO0A?EPas$cnEO
z>@2?#_CE-M(7kB|6Vw0u3U(Yb{r|_=|0m!{3|Rx(E-|DLXg`TDwZJE`iT3h3=*&eB
zb4r;Bo)3y=SGt1F7gKP)O<G?p=n@;*4&Jx?lWA2&C$ZXZNfG`isN4zdkRY=uyc1Z!
zqn{}jJ~D6F4-_@b%^*^o%+~N4el#A7Y^#idZip4noDL6y+*=q0EyP}<pc}%bnGfRQ
z86xgEBmOMN)DrEKAd^k>p9JR&6d%t(anDKdAc&82dLuvEAKsX$GQgry%ME!HJT#6F
zRI-fMJ-n4eqvm7~%!csh6o#}L@itVFBls#brRMm!wd<Cv<3TJ|n`{_Ue7v`--d@#y
z?!kK8UUK~WhU1n?Bsdc8*+u>=$Rs4~kRa2N{6NZ3r(7jT0TJa#AtnqyAjE_xFK5XH
zzr|RE2P4P&z6vXAim$?%L*;Q5ZjI?rPA+v!qugHI#xo<!CP5%pe-fM%w*<4uJ(bIY
zATz#f5(HxJgj3dUiD7~@<(?|$L6CV~HVP84`Ys5qoeZIa@n%Mz1UnLWHxZK%c{jX{
z$ELhC!I5)Ibn_sFbT}rl&O^nk*fuB4`GlD)fk!b;wnoaEoPF<Nb4H#|*vcm4Nl>YL
zngofwQq48kizAgx&^2ZGQHW`Ru!O68ybH~#gn~=zo?PfbkaM%BZA9LO98}*-RRof)
z33(D!j-yqAM1CL;<D@3fb=!{{@+gRpM#1%&Rq2)I+H-KPO0_fuk8(pE1+f%WnoBcl
z(<>=SLk<^aata=|8F>;sQr$yACWU&ZE_0)vDYSl=aOTWW4?>Y%YLk$c-^2JxV`p-U
zX}s&ySF>9tucDz($h#wsoAXZPxcbO;qoh}V7E@|0t}g;!*B7-$1X<_)TSl!1K_=eP
zHAcugA=hbhey*U0yd~^<5DPVK(O%6wU$3h2#@kzk>LrtZy^)$JXBa8eGKtumq9>o?
z&6upFnQQDput^P1LDuv2W;`CF;-55~=M8xj++=E?AdvbRP&gj*PgE2(!wfMakAlpo
zCSrRb@67fzu_5u=Claqs$djNlwyhE*vi&G{W@5LG56nH)+k+r7!mWn{nIrC%gV5k6
z$-HsFMLZ*qf;%3gokU1^wUZdqT`(_Qa4p|6)jbF@p`Fsi2zfm=o6K;GTpu6rJrmxa
z1(h(bNRY^D<ht=vh`f3q*%30+-h-eav)(B|rs(VMg3&2V+xJo0zD(rzAc#b7=Ptnw
zg71@j5+u=iy&;c+%qN(`kyZUca85h;kv=*T5&l_F`3kE9iM(D7;#k=-BZeO<GtJ?H
zkUMQ2r-ULm;`<_nqfWYLP{&B*Q4pSr2kAgF_u_l<B$)n~k1_HF+%q&j2r`jlry!BD
z{3JN%dyK3I_Y9DK7F43hI#o50_o`aC<&%u05BCg{4}wTUxr@bLsVU!C{6Tn*e3f63
z*J4H<1>w!T?-FF{%U3cMs@0edGjey#$fF?hXqtNUNI$tZ!TpwQGm@Iz6L9`nP<c9)
z4o=8>x+Xj4be==5-}8Guyf3nVW`YZ*1%1zN5jj&@rnl((EqUmZn9-+{VgdY++X7)r
z%tIRab7tgGkO@qy1c|(-P+>UCrgd#wZ^)w{5~OymZAzK?Lu#SzmPa*G65TVaJ_s@a
z>o#?cBk#V&#-N2x9~UKM?XL&-Oz^6Ef{<4q7iN}X8raM%m5E^=-pKs1%EKw-Jr5@<
zW~ZvU{g!z4L6G@rx4-M0*UOMWmBTc)ksj=x*!Dq?`EPZU7IMA|TBga3+-FnP+y{}!
ztjkOuD8A<L!1QJE-AD&FBaecIB1a%d#9pKPMy=-Lz8_EAdr$ZKXF+8J&SZ&1ei-!Q
zmOS_qx$-9D@r}$ntju*ne#l&h$hf9u8~Fe;UGc*k5eHYba4XO8`^vqq62x+`Z#U#o
z5Z<Fxvc#sUz6zFGZsm_>S-fXkeh_3*=1i7I<dv;vbcHYSl}2d;XVDJ<Zc6&Bkh)9*
z{c4vsL{CI+=#OXToO4A#2qB?#qY%pH51BxHJ1KJ}&>4AoTRb*r0uAJc&&lSb)*sIR
zd&_eDAcpNl*%g%>`*mpw9}s5D{&-&1TMF$5F(lf~$r(WTVQz-Pmf^A=rE&csfHw1Z
z=Z8yVdl&4tbl>sDTLSRsH#*x$-a?f*{QVXR8fs<}k2l`)i$A_G9-~S=kyqyYYho!|
z`FLBMa+f~{L~uF3xznrmDzM!$p!-{X%ZdK<rg-egUSu-$A9``SWmu0l-gB-$zA+yA
zyVSkM`);H+=G?3|<i|JW+|2awDR`{|Yd@~hxi-gb-4DC|(XEtg^#1vuzW)AamGC_?
z#b*lmXo!J4t?nGY8S$@vO5@J0F%i0Wcslak^sD9!6|v+SI&!H<6qq^Ld5CmmjhyNE
z3Lv)^y4hv9L3E{$w=$fPrGlRW3&3_xwep|J1n&bH!c}?nW~51MFq$0GzkQip066c$
zwyR%2y0vYpWg=a#^@U<{rSWoux~gkag7|EXO*K8vWF`?Z8fYx~Px26Fn3V&m{RY&j
zvV(9T%(ARm<Yli@*D_OkcI`dQ{DnA6%Yjbu6ZzthVa9;VW1~jFGmwu4b?mMVj0SYB
zWlU1O)Sg3FgS#h3keTIk1i>ZLkKg{jvWa|PpMPYH)bRNu-I;gTmsMOmKJrT}aNdBf
z&mwd^?%JzHI%AHh!<mGhi06&p;~CDEf-0Ma0J+n9escvi<|kKT1f877_^R=<RijeS
zgsMR)XhGGWFk}6w)AAdVm5F@w>r@&4-upT=!N2a{Md1%cUiJJ!LCXQsCqo9<QDzfB
z_r_d-OF*MOcBmC`#vce<0X7!>h}TZB-xg}EMVwF$Ib#(D5+}HUU?BGsHNmQB(6ZHV
z8d(52(G>lVe3kb%Q`M_=-xxKQzY`N;!9!ks`@0{q>4$vbGSVeG5`<bV6Fch}99t>m
z^HWq{I2MyqY!sv8=(gfWbQL{o4J4>lZkPj!%1~?M$W=xnZ9f=!ReU{I2zk5LNoLfg
zohjtw*0dhrL?^bjWk6R^i@_e2r-9%*mdMUu1$m5IrXjRA#Hz$4uF}KZkIJKC<iX&`
zI#b5k9&C56-d_L&rCOhaf}pNXLf&Yt^E_nWuDk@)zsTnwW$(?#b$uuAUDX8M;%Dn5
zQ_LG#Qz&|-Xa;q3P0_sTptma&a<`vBxu;2wr0H!{BRg8Ks*xS!fox-Rh*Rf}VOqX$
z%cx3*U~o1WK~X6c9Emx&aUi)6l&;ENO;r5LfJSxe{&x~u3wAL0DdB@(ug-Ctagq`P
zldI<%kVw!Rra&}D8^LbTny!-r__=EBlT<WErz+ee2a<0JDa-H1yvWZJr-It_bz+ZK
zLc4+Z_bTf+^aP8?-KAKxp-y7{fz~>SMQzF?wZ;z>EFhuts8xFdcohc1Nrj6+)!_~P
zK{aB$7C_!RN@YXsRx)@xGJZ%&yawV;4PO5Rkk?3Ac&PrUW!J>V{w02&3-KsR{_KjG
zrHniS8Z)bGl8D<<m0^D%{`r?a35|K^2?bKjSKMNgShQTL|8}C~h_ExbW_cJX)|&0~
zB0fQAIIHqa8IHVzN;OtA&^jdPtAz%BaR}=miF!*(sd%&2{w+!rAl0ky(hH#IhLyG7
z!T!srYAP11%=Z`KB?xTje#P;+(s(pyJtPrBGZ1`WNu-O?_$1dn%x~coI3TPJNX$JD
zG`HhNcXbk$F65$J0`gzxRnA~dsq3ar!m_h&{FcB!?{U>Q*=+II52)jj?j=kWL~D(3
zcFfBOIrXAg=2xvD*X_U~;30xr!fGf*gQ-m&NcXb0cX1$?lbgmEBzdc*60QTQ)(+_0
z2NLa-#em5SzGY4sQTF&95)7B=ccOv1Xl#`Y)NNxc=-d_khGk*Z`m)8ckVMr38Lt=!
z7m6*}tSf)Vx!X_eKpRq5pNFOc(ovj8PKP*-7I_qybLWmSTeX6odRMFBh?=C|!%*Ty
zECDdo3?wQClTtag=k(xym(6|vesmiUJ`(2QI<*Ti!PVJO3Mz0NM{uoj0(9*7AP_Dm
z9Z!ehDr$$z2n<=Hj1d6w)gbWjA6^_985~ZnKb@53T7EitytU!<4IPF3rf-WE_!^{p
zI;AtfRg5_i0`b%)=c+#N4|t?t@Dj3<iGgDvq=o0NBBAu5<p*g?KpnpT8VwZ7y@Bbt
z9GVHZtT`b{%mmPe5*ZV!Bdz<P{iq{B+>wKiRJupkz#&)K5zSo!^07X;Iv8{QFmz{R
zWj%DM0CR0QbolJp3kSsh3-$AbpyZ#{AyrSX#Fj(LLubALe9YhOao``)Ati$$Th*b{
zs39rML8m)Id@%APEP$diS~3jTfeuXy!wfz&DJ=fZpWS2kVq%1VA~gnYCl<R#*=Y<O
zh!5tj0}3vb&OF3dBTdS#>nmI)m~|o$@4<baq&(5XF723Y!99h(!o1&i)fe-A*REt8
z6%O(Z_hT8IKLEZMQ(uWSJi^6)rnA{`)-5|WDWqH)WnT0RDWg(dXz?ZN+LN62xrnZ5
zlq1y%mlStO@i~%eM%-G<-ZUX<<||o$M>@*BYz=^otf;XrONjCt2<wOKVb|H$N~{rk
z&d;J`4d3qh6eCbHCUM{$2*#u_lSv+q8nTY1TGL~+n8M<lArF}Z#zwBXjk7QUWtT|e
z0Knh6aTjaIzOd=+gnVNqwV(|-k9h(N$Y-VeM;K$A32+Ri)XZ$-;jx~<fM=SB^YCmH
z{&!FFyKyo#%(qRe7HAL$QiQ}b-E>06)wpb$Pt5wZ=>!alcJlszhbwt>RrWQ8X!C_1
z@${viD2<wTu;gE5FF>*mUBwc_@hcJU=dPP2EWu9pE+pO{MN`~5mmtPG0g1Ey+Z`J{
z@sYmK>RsHo_;(Pu`oDXeWJpOL5K}^7PFAE*()}?=JILzk07;2`8h{Oy#K?j8G?3SY
zdtIM_psTQ91*!O$2B0AsOx5vsUx`vR2^Uq8$$q<Ib#xx1Q>_*@Q0If-DIuS~172cV
za1!g}L^7nZE}_g^0Qqm|!dllL{f<|_U3Vb(je?v~onGqhtLsx#E-duY9!T^F5>^!I
zIt$KKcCvj4038Sw)de%ibivg_43M9nVU>p-s$ka}y<c3%L{j5#_vrQy2t>+(cr%SR
zpTb;n`!AN`FqtY-B;6+Uc_2Q&O(&ItRIDcDN$D}U2E-l>RnI^$$>6hoAt*)Pbu}6%
zGV40N7mNILcrTJ2b~PC%Ei*Q-3c#lp{_cxIv34SJ@BpyDfhuYw3}g$V#MWWTS$;w=
zco#YV4ItjE%lV4KPwHh?tVM`eTxLk0;(91eAclTrB19dkS1k5$KJ_08EyqZ+NHLtw
zO&`k2`Jk&9F0&;z!ZEFInH>n*!5N{CY0b=uSl)0kE!6uiK|MCanyzOnGE}v567zN_
zAkW|rFw#ICnCJ-bD2SvpqzNji4qmYkHGK<S;;dgwC{#+@)i+2=DV|;T_$Ct5aYe$l
zR3NV_)^&MCU67ajMZ;HK*+yN0-t$Eo=Ee+uO=iR4`t3<QsdFBHk4mE*u`yktXiq#y
z>5OM^6Ce}bfNIo-8D6`787Z?Gx7`cz5`VR`tEi_MP;?ddn}I|VXt!v{+t*C*iSKVI
zqE7bUC_8QsAx~jzs!SXLi~PU_GFG|PxFigpcVFgOQ++u6P4&T5sx`f<dXiSwMKhx6
zMFk^O)o^G58V`^IiR$sr(}Jph8A!~Uc1-DVL+W6H-ilIGjoaIWcnK@Qa3uFn3EV_<
zEFWdG7kAHrpuGpSi^h-EgXp?v!bR5}oG-B6G+aDAS#C_$16Or9nhm5xKdowC$0S?T
zK3q!LiqaUcda8Ly?-quF1<&|rUr#*X3CE8~!l%EC1P!hSrShoO!sxv?gfGkO`o+(1
zC{m`NeYk2=Zjcd0S?bP{djs)mktJau-r03mH!<z_u5Q9=!gF6h6k|6<#$Pu-xL^Aj
z`JXvHEBb_siQh>V2k>HCN=xNAvV|Sb5e&~Be@B<>Omx1fV(?}f5GuAasrlxm9U{~?
zHMkKLW~6FyA6*<_)#5-~<Jj8vO(K}HuuGN7D}cuxuaR*3j7_!em<f!9YCC6w7AV{$
zJwJKO1eit&94425D8_DS665Qu#IQubov~Ee=osQ$WQZ9q^n8e8Q1H`DFT+S<Ia(Z{
z6ko>S=7D=eW=DmzN^Kl(sn<Mw8)E4B?T}bUnL_CLjoH~*@;i=F*f$V-7a4#C5)!1)
zXpzaLRBCM+JY$wpd6sBQURbqIg=>r>@lC?Jc>wq(H|C#@*|}i`<a=;+oL+-d#Ppg*
zp>Ta_xG?%_Vva+ZeIZ`L#j<L3+?cj~RUcGN@>QKsB*xB<t4duph&V;aQr2)UT}tJ`
zi*!u>Gf_K4F%((TNR3dcmg0U&s)aSJAw5B<u)z!<YJ)jWoo=NyzEKri*Zlj{#=<jN
z>zE9MdeVkuz@_li){rTxh`(}#2gD&;hP~jFFXdGIajq=%vTsP#P|C^bcZl#{giCKJ
zxUM(PUpI>EIAm}w+85wU;|R)QwioRZRL&|mxZ%QD3U>~;(hLC82ba^O6smolL?on8
z+WY(y<?nt1%S4bDMe|k&q2M#HXmg@IwJ^+nL@4+KEI8RBWMOdxgJbb`3=H+Ag^3OZ
z(!Gpv!ToU{Fa<QjX`)aQ*^uF=6y%?2xE&VRR!3L^g<vyj)OZ$Zk_G}XFZF1@_CUi?
zQ#M+sqgfnidL*i=9nTCe-dHzm8nWVg28tLyGKP5gN4yH9=xVA+ou|gTTHByOzfrnQ
z3!oS(Mdx%Y^Fxk6jb3zeHzcwx@*`ltL{a9<f%u_HX66Q!VPPm%!xgENya7;8ShVkg
zov6q*JrK4PQ?u=A28XWgY6pg{?G*D8ZjxdT9!N;&X3>Tfr%-P-D378ew7WOto}G|b
z{)@JIXbu;LP+P43#ne|#m0@2sRVJ$2{NK2|H=O7J0bx}z(HhjpMb{pXhm=rL#1CP)
zrwzYR_o!q<4S6gl1V>{>aOSVB9xl|Ak8(i;iC~*odZdBGG&ht&lY=78YzkHwxp_tj
zV*|GrN1}B&LIUyD!SltT7#|$??#Tbo+Pn1Xwj*0Y{rM|S^WMfy{0Q6OE)s<V4Fn`D
zM5j;{656*xp%U=#`5ZCE@Lc=mS?A==Qc8KYV|{*3KZe5*BVty9YqSHGN$}A7q*mSO
zS^)J*^-6EtlCOkYG9RdV>JpzXBJ8<*I3P>gTY@*)nhyuPZnieeAUhR$RcJ2NY_IfG
zOE58N`6_wj{qV|$_`q)opg5aSmWGn)z-71bV54|T#vRHWgEBajO239O`dCbj!{}1$
za=%FF9Lg);{8^zFI^>3Ie}3uGG`5%vUuQ<CKTokzp+0$uiar2lW+|FLn7O5B98z-p
zA^<lGNv@V$8;ARmt0mV@+gdFzNiAB2Ply(`pIoZp1cLQ_CER^t#fJw4);COu+rC?2
zo>7gOnMxDw1|xu4n>wY>9jU=Cc6Ey1`lk7<*(KA|%&ooc`|$y)+P+^OJ<!KzYq|QU
z$v=`T26vMuL|M%3QstaMiYtKaEt)}WZy|h9gMDk(Wa}Ky!<8DABPkfV+?fwKYS{Kw
znLRaXO)6D2A4#OLP@Z^H_RvwKCS}NzqD<z8ckY;Y4>^MVb(DN+MWD+*pLc(KsB@T3
zKD6tiyQV#t-OZElsiJy0BIaV}y0Q(VwY#7xom(F^hL%S6ud18YJgaW{hOD{j8%E7f
zh?s5QC(Ja_?fc;;zVh9dIlSe0Z60mypEi%SwhF-~hTXF&UfL_8d&^Y>YK3v~t5%o|
zzbn4mGLFHP#=NiXXHA{@_|7ozeeEvr1|v#&Qp7EY)emh!tX=?!-8St&8w0*f0FKr7
zF90qjUtu4;b}HD8qM(a$Ii#2pH&;_Rm=mkraw1buU$dP25LKBl`BqgXev6_!xtx~v
zf}y^b-!39Q4nGsfAKji%rOJNuBZ(Ae_;h8-N~S9Z>X@7XQ}u8L<WB$mkYiA-ROTJ0
zpZ&fN9RYJ;sibM*y=gsd;=aSXTAM?6K79W<bg#m$N(D%z8ndMWBrmo2OwfSnPTQyf
zsWeDw)PU%!e0+hHZqqqlur3lCRgl+5dp1%HH*_?mNLzqmD0t4*HUEg(TNBWz?U1gZ
zQQILELxb5{Y9XR+G;))wg5E;Vh(OYz5Mf>ZQrEyW=&jSCZ_riP97%!d1v3J#__a~H
z-qM6EwP^SRg9=WXF)<XtRb4THz}3ASXCSnwscgKP$wIpgYP@s=4lMYl^KNvQ#55gg
zqbnO0-Dt{&`8KHc5)2vAd+8LTGDDilMrFn;8&Gl6VK?9vB0XsO4N+B^1=&`%fixAR
z_-1e$I+FBVqT5g?WwZ0C(~u@N(j#@d1L@R*nM#FsNF|$Hv!y&N6*^CCvxa?NI&69p
z)wKVAAVMyDbi*x5%JN1lE-KU;4ZY}U@F;jksOgm}2LgJIM#YEJ{oz^^Y0Q9hEW#TC
zT8!J6T>I%;ln)bhE4uF%;a2qZapNOmGEzUkhcs$I^kxE|p?GOQQw!&-Yj`<3w5@f{
z4!-oZ&iRq*z1FuLdGNSI$D%5ylh&y;=PuRr!L`u^sdXyNu_Zkr%96Dwb*RPkv~?u;
z#>R^78ykBtG0(a-seWJC2GV#w<1+1hq@^<YBZ(B=N#Ko?4}i!r?js?x@R3%#50oqS
zsj(q)M7%{J7awU!k<So6_dS#TNVUuOpi!aH1<CQR`<&Xq_IjUOkN;72qtQvOb-v4M
z^8v$crCU_Ps8sRQwiwAOPpZ}nUoCN0rIS+pCOd&|Uq$0VC#BlsPT8C<+PoZ6-=cT$
zh*gCbZS)b0sP{p=(Ksw0+#iVINn2nI{B?S_Z&=Y^e^T+1PxRKXX>{#0@%mP~Fc$Wy
zYevwpxz#?Ain|VM5g^K`r#<DEj>(>((Q=F?53MEg=+Yk3Md=z_&_$_s!5o|<wL4Nd
zMq2n0IqZ3vcpO)xoMFz2`Cd;8$VT;#XuTVb@Tc~)&uVybxfUpm8X{S#97%z33kILI
zVaN9Kfgo*d1S4b_#uud~)3B;y06wj1BdxUT(L%<9K{dW^HK_luVNavw7ZQ)`fPQ2U
zxoDb@fo#5-@=sY0;d@kS8>}Nqqa;l1nrc4lH^(ucihlv1nyE$_cbd*y+~cY|WE*a#
z$CwK%9rw;7$z@P`B%rlD4oqod#A6c*fV3y0f77)$i)e<WzHHK3rM00f*N!N9rt>gN
zzm^(B(=Q!&wOkvz2ZH=$c$JB$jqwY?@q%N@1ir!OdL*e}qtjE($y_*DXm;MpwIoDu
z(xIsuiSv(Oq`@NklB6(oXexu)Gz=fnH0U*kW-ek!K6Pm7Qt>!62WbK}baWJ`GKP?B
z8Ifu^Oa)e|P{EYIDno}sG1;49Jr~TGAxK$3{!oViWWl5vnyLlbt06d8!pdV%V;3f=
zMl_jzN_Cj31=<}#dGJ%JL-%B=EyvJVTClYYZMGnq2`k@df8EghD{%IaqzP@RnV%nu
z-C76dV5P~};2f;fZw@}|y?+yG_X?x3fk_#0RwJ3+JU&P9ckYDrQo4rJ;V%@!EpzJ%
zL$BG?f!zORe+kn1n&|v^{-i`lV5L5BnhI`dQa;q_{4R5-H5FFoIlLKT_X#U>4lfRX
zNd~y^7%C}Y^JpAC)jS&YO+sEe5nU7bBgvw9y$?sC7%m=jHSN5zAlHvNOz=^(V<(t=
zkf#3;W74N&rg1#awj;^`<95K1&~@@&eVmKZOQNXgg+~*yt%SSLsclsiL{F8fg6OFN
z7rvTiV8>4)do{y{qUGOGsj-OjjvzfGG-+TGwz}FiaK~I-ea2;Gb#<9eDyEj=W{l|G
zl~!Ski@8z_x-^YIb5g~5Q`1ar4Slv$j4n>Bh`!BI*p^h4$fxEAvXc`{!TX^cbHWQM
z$6k{N5w)*}PXz-AT!0|?>Lpa2J}R!t>&w%qg1DouJAd-;Y<ph47A`*#&OF<`(e@&r
zC$=3YnuucKZ`<|Tl%(dud2gwpctVSRuuk?V1d+;F1(vJoji&Jx;TAZYDM>dk?Kq2W
zUVM0{;C09^`{U7YR`09|?>NpgfnTM%@h8~+TvKO3kyynEd_?I5H`M3(lha;IlBish
zWr0lOhz10Ms}t!ggx1LPvbt`D6`J9E*LWbwUh2bBS?v1wSUj=qpfO#pldwanG?&}j
zIFe_tZsJ?|Vx29P9|jh6yHdeT-zx@5Pf5CZYA;wYu-sjpZ;@in6?UDwt8V)F8dD{+
zV3Vb~d26Fs^zpTXX!O>qTj$N9i|<f7=;1rmmh|u)w7#p0F1{0grh6~OWWtO?tZEg+
zlU32pk0cczd%dz{bJr_dwpY6VeE+Lx!r|!k;ABt15H!eiwwCvyI_cx9Gh=$BJ~Qh<
zj`+&^Rc-q4ms_oTvgtH-y|yb^wXSb>4c61^{ar;Az<oeG0R)aUcmf)4l=M7ng<z2<
zd@I@m=0qV~4V@WyJ^nq&HK17|Rsd5&Nef_V>OeJ`HWLn!;lN*5Q2NPh-oU5rNYF#D
zk(8+(l8vMYt4u@nQ@u1)zmQ4?{X1{KHFDVxh`Nr5^DVi+M4&*Zc1aeFBt7(<dKkLg
zU2cY&bYrdTS2@XtuvHG&z!(JKB1h3gRMG>~^2#-mS^}d7x~(dNlB8u1uWuBUrhxS+
zNkWRI&j6Z%dZ!I(2J}K(CmBh)z5^Lav;obe@(N>viWiZVc0mtBSv75xjwJgqkV-ZX
zVGs}uG}(I{$-yv}Xyiz;qRF8n^T^aF6jU=`nF6U@(vu^~9_p?zz=I{j!U`gSOQ%x7
zMDR2iQr@5J_fMi*`&DqVvg}vE(dH(`up=T-3=59Y(F;rkFI>~(N(JFH329C`PKh9`
zK_*b4wDxLW7Sow!Ctpri4sz;n`3#U?HA5<CZ|s#NyQ43S=*z9KT{%-__+Ale8mvJf
z0asPn+apW-eW{F+%tVAm!=)3<{K;)JnPZU;36mP$s;#Y89&iJ#n<*K5_^!z7Ws^rm
zg`qE$p(rLarO?UTQuh5tODd^bYVv*YO^z2^Dsq23a-F5J_eWlcM{-m#+f0%wDjX_k
z{F*e=PX*aTlY>qjB+=5jFhHW!HEVHn$PK9u41JS_QypZ{GG!x+mMPmngS4s#JQ<JZ
z{wV3gxU6C1d@09LIq_m8JAy2D@|B~4SFrW<$~7W=GbNvxzBqVgI=}c+VL#3HkNi>0
zKE-OL9;L}g@BRiCh+!PAyY4}HWx@?G%s!IAbV;VTn<rMV)w@^VtTJu<(DMXw9r}sW
z%XlM&a;QP!`F#D&tt>{z`m2FSUDscAwQ<S#Qty<cgLdnRp^&EYI75^5?}xNmjXKTn
zjt(SZcaq?YG+iME4oSm(VSva|N=mv^pEpX46%IhV`#eaxY`vP3eZ2d8QdvSV`J^P~
zg!wC1c5>fN#FQ`{{R3>5R4az^Fuvx{^>C2xvLY2d7*#uEGF#H;qz=%3G-(v+^UY^#
zNKTLFre2fmq)BNAukes)*8*wfxF0`L95_%|j=Lj(#B%7vlRRwPFAok&sS;}%_@8Hg
zocjZ$mg61<1?TLTOrD`0f`uSnX@hg2U<mG9016ndxlk}F>(!+gmi6jUvU~cg{mJg>
z^nbdd{pvvu-G24plsxZB2l*KliO;QUmUs21<XP{4M!~bb+Cxc>=VwxtFk3-e;F#Yg
z4ID!AeFkUtuc_ByCOn$&Z=J2}Kab3Oed}zi{XA4tzH7I&ua6xm4bw3R`qFHDV>R@(
zzvsMYSK-L1F_#tyB~lWAs<owdkp%_wF_%Xs?_Q4Sb=8QJEIN2%$~{Tb{O<lLKYhGa
zUb7-4cX^lJU@7(}sb$PDSzN{v^xLj5eXI7$kk)WtGiYDss9rUmB<nTunQPH*@QVE3
z6y!e_<mIR4LK*kGMfTI|qp{{&!cjac>8hJT@T6g>=4LExpZ9yFVEz0>ecg{U(&QET
z9tixkreoGzMUo`@=h^35+7OC%c}>5Vv{#XoRqgk*IO$ilPZ|!ZmZ*2vpXc~)?@A!K
zm88;Pw>v7?kp3E#*m?JBK1t#lhqGO0v@(uVZ0Y;`4Jo-T3}CaztA#N;Qj_%jBvK1w
zcI<i2sYtPPnPST-5SGa0ZUIX_U$2w2KyuI0Sh3shrQ(Y2SsEMP_IsAb^t>7*9=CYO
zdLSB2X8O0Be$_%Ks9&uR3ObU1Q&4*qM9KI90Qyz@1ZwDo?@tebMK5=i<pFa19*AEe
zaq(A)4EDlbp&RYxZsrYrx*K{%@VW{dfUABLIDje7aqi&UK+KeKaXJFZls9f;NRNxa
z)<_=`u3-dbx(XT)%Jr+E0r)%;wmJ14y~>G{koJgf$D-(3UyVK==}7t)T-%dEG$HmU
z)ijw|(Y=VV9;t$XzPgP60l}XTy`g-U88~r!ulB<28SmtaBnmcd>bPxm8CLT?(q-$+
zJ4=_@^5<d`DSiaQtf;T6TlPu%UIbc`H8EM5j$cvNed_!e!Ebn(%Py=}w)4TOzj9@B
z?;f3(j9zg+eZswob1~JET^6-`&hG8*))@ju=Cc)1>Ypz2*vMrW8|de9>Z_cX_wCLO
zcqDd)7*0MbIB_8zgV65$$c5G0ogcAR_OvK{Ac;X}{go@eS?fP(1v*qXxfZ*a0PxcO
zgoq=V>a&iIy27iCW0L1;c)o3_FLD4TQaNSYd}WC#+U6_E2%o&K`k5nnDR6pPk5R9Z
zJ-rt-j}&L7qgnTohM-#Q>gSwI+plcdwEfC9<fNGC_%OY^@<da5xvk4hr}wL%OF-HC
zy{IF^X1^Ep+?aZAUvz<|J-xlM#ctT!D_acKOM?^2rVb6xlaly?FBJ|YCUtO$6m_}<
z4c4hW6KwT<_4v6mx=44zHX>YIZ=M{j`N|U$?xm`MvbSGV4TBtBWzDRS;=2P5P#MhC
zS<yIY>n2XZtGbzS64F4ff*!YDy-n(|d%x;C=(;=E`Kb=?GJb>3JiV5sS0CZ&oS);N
zPXCBl$jV<_-F#FdGqw7;pml^Nh=&BrzjA`j)WsaXY(CCl-?y$zF;8TXR>6AQ!Ce`z
z4;D!(<x_2SBz)7z-P*2R9)ZuUa%SQT=~p|0w;KiWqZLcH`N|a^*sfw8zSZ3b%adTb
zUv&-cieDvJuoU$Z`<=Pg5bR&lu|LyM?tKTG=+u1&L?}ArrSGYr-tM+v*<#v`I~7)>
z?mJ%0eR1p^$$7)*<G$P^g6V@Z1Hrq-of_D-MpNSuZYz<}1JMvq!w;Ft^sD3n3rZh)
zNQUi9A9O^nGgH}+9E(2g^x3G^ROXIa?`t5QMEao3z+|A!yNMu3+;~4CXHD8fzyjJ2
z%W)<H5e_{g!&;|bGcj<?^r88*GF)4#+v9B-`@vQD;HA6|&7L&q3EB_SYx{N(hy2Lb
z`G7b>vnLIG`p_=IsDBFRQ*n*I5mbY7HD)`*0M)$M_gP-W#7NDz(Lr=_{%m#7XMNi#
z^!YYIh>38OMqmT#QX17|LFNLB6!`A<iOna}2mKnjF$&+j_6a~<^V%qkNO6Bh+>1Vi
zF&JF(DvXk8w~OtRwnaU6fgefO+cIb`n}T(F4cy>n*r$#g*c<gptnpNa8=P@5T!`+e
z*jBVY>ep~Bl^-GkN=fvtPvH+3Bn6ug()ls`RZI?@zlzDB6QxUK_&zY((g1=$eZQKA
z>_<Oj@k55BAF>MSG;Di*BOCJ}Ut+hgewR=vg6Z@nWkS+C9|0ALuypD#^EDj$OHT!`
zm+DK0QL26V)lE5kGy2k_F_^0RGNeY3R}G|Mvt8UsU>Vk7w{{?n<J?_>qKHFvBsBEG
z)$wOTwN68|B=pX5u4Ni7RZA)(1V9U>Fa0LIC8h=na%AJc<jYWB*SZmLrmt~hEU)Dn
z75KXyp0Z44zxlENX1KltS)mQ<OK(e#8_4<1!=Ip(YjGGe<{GdeSo#epevGlA^<MP+
z>$wE|Z7mrC<6o>LcS>j)89k6yTT;9~B94Oyc~~y42rfY6SUjRrKazk$-Ko`bfc{`)
z2Pb{--0`F3^`N_y+a6%ByPTP;?_|@H$!fMtDA@tzT^D5#7IyK=A4y^&AFpgtk*4M@
zq6++x#%58EY~nUfy&T~OqKO~DWEtn6$4<7fprqG?nOS$~y>{c+Yj4|FG_JjELz&^4
zq#Mc#*EHRoJ=AR~4V{l5E4TPJ8k*Byu?1iz-5HGF2}$hAideuH4}I(G+W8ROul*b%
zhxXlsX+bU#KN`#ypIs3aDo83wjQK;xW=F!e%#GQyrBjzgnll)a^=n!OJM$wMNauBW
z(`%y?{6c<7&;#}@&kWG7lCkuMVv0P6*OcB2fEAk?4h_KimM=6yoE%owD~Vg-`4KJp
zu}{hDjgeD=uoac%He;o{Bmwt=85Z^Dgg)%C*PkM@@ze?Pt&)<d--KC}m8ydBR6fMD
zEGTz`BcWqP4unbhNu#dEiX3-J9-me^Qm2E5F&Ez=*1y3Fj!q{`KjD{BQb0G1jSh+J
z0NO(<;y^)&pJ4cnPCwxT6Ybz_tAP{8%Julk^=&epJFYe+6>ECpJYpCAp?E|`g2tr2
z(aQDlX_2CTPmZ3I%K-q2k6=SaI~qn|sU01|aGiWQKF3Ov;szE8V-TSRItY`cT?5^V
zNo~tuPo!&(fihGs-yraC9m#dJ%F5~M2JSGEvbQBI!V~<_*Ym555M0Nvtevm)4P-`S
zriQy%O!8Wgj84&9k7i`1_|9QQmW<f=&Z(m~5)x*BB+u#>*SFK_D)&_AF^^;*oi$g!
zFVWI07`)LVOxG&!)SA5|?{`YFV7Q`YL0Ps|QZgpmrEUT9q9u0?SRn24v?O8W6CyfB
zR#Yv&Q_yAFWfKWM#$Yl3AvZ^>CN3T*J597>4gT|FM^8!CBa#p(Gp*`<39g*U%#LiB
zXkwzHJE&bsjc^zZ68Jn^=u;Xz@i{@@cxsnp1BPfOQjNBPjGjK1P>7l|-VJWxNnxMq
z*gq~21{9lLCE5IS{buvdZkGuo4beg(-{72i)RH&&T^pjwJt@i=5*1|-M61^qykc~<
zY(V^G;>1LB#V17clTIjiA`e_Y=@IGc5*>rv==hz;903g;h@wN6jUru`?NU#G{?0D*
zL=W^~qCcgLnzgs<cZ_D!q13VKwCnmkP`7SJM--J`*YAnSbxJ|=X;S3FNG+p7AlJ%Z
z5prh7IEYT7<2byO6VQd)<&H=*w#P1a1c(fegf8aTW}1#O1QE3+9-+P?J_cSvgDoH$
zqtgw{izcg2#4fc)P0+Df%bG8_k71r&J_($53Iy4#M(_^OIbfPK;wGzkW*rIn9P(2j
z3P?zDL%GZm*i*#T+z?v;63{iE7%}H$)Pf^Gr>&#YTKKSf%g7{WG9XH=DPkrg*&Yc#
zt#O`-O~*LTmX1J+U8j*b$2jk__6^fcxDT|U)*PvLU9!e|XYg=D+jOeJgV&k}a1h$*
zNG=IT7~vc3TU)f$RV}B}Mv8T?|66sykhR%XB^-c_Y(l7`WGXv5IB`UnLvw}*T@!*D
z|0anGCysU_7}l9ybsF@mmL%=TpOcIDh;rP+5!V#pl_8}~FFy=AeI!sW!HAAwckm--
zBNa?uFHOe04LVfQd(qQUhiW3VCpV6P_P#-bYQ3uCKtUZ>?M5?Q>z7Xl+fi>wWsXaw
zgK5Edx#a&j0-mJ^AZ{I=%CO+JetC5K{sKd_?{5HKpdYn<$#%A~kzNTK$)&r%o0H*i
z_>tk(Gn;tX5V6oM1qK`rj$|OsJZSR->wt+A0}n)|5DjfMg<<+3L%WF8RPcA?xCmzU
z4DW=7b!B10y0VaV$|A*P!HvQ?H%`34d=bP{(M4i%s%UGSoGe2ddy;J(2^JdEsMdAi
zm{Ymf+NIxcV@IG<(<2}$!`>1{w}rK!6*bs>KPk#=!Bzn7vJ*;+gA3q#$vE(sV4W`m
zZ54h*U3p+~mqEHtIt#@Xw>U3oSVXcmOB$LaxN8_s?d<T|Gtqp2D((nK&eoL))}kbx
zGd*-3Nqhv|w7^|wo$e_lxHHCGdBR|iKVqYYendvO!IIfie%__c3f`J_c}JiGWoWb?
zVfe>vWcT9-r&Z<C;9zQceQi*A+NCVXIOmp(CX1i{ogpu5uN<5LM6Zi8K&&TTGL@ei
zp$sD$+yenKkmWJ|OqxZ0eJZv{&S*042Yq8U47*agE=NqdOyzj!0CS!cB3kjz9Ata&
zu3RLO?8<d%EOQX0mvK`rPEI(6M@&6bHk6IM3Piz2?32vXkJsF%LGfsp<^{n{7``th
zfp{#g!l`C76S)%&D36HU&d>W*5*?7=!;wV$jpr^H03I`OaD-CPOg9B^3mgds1`1Sz
z_e2AY0m2bJ5TW^861%bs7`fzBc>kiQ0~4nWs2S{X+rW9(492cuRcWs1h$$IAr9&BD
z^6qF*A=+ig*`_{_0@u)m`sMHS`T9qG5yZQ-OR=+4XJ?mBXV0%GoHnvvAb&4HLH-cK
zubFfeU;(zv$&*CE5M=9I@g;wxO=WyQfEffEHu<qM=uy8)av@%#pY+T%BLoT?%hG<5
z<mXbT4rp7SBLY)%#rJv%CW^_CKax0Vf>WqN37M%UsGlQ0Uo?8@UsLEUwV56I#J2=j
zE(YpMQ4Z@{68+_?$g#G}QM%>8wCt;hxlj!D{V$T7!nfp5W0_2m!q^g>NGf-#R^I}4
zDklb6z9o6m`VyVWxk7UAuM)N<clHhymn2WvN#YxbihQ8SH=UE=N~Zci34B7{b-4<@
z5_Ti!Vh1mk!9=G+^AYK!hA)^>s;ObKc?&pPQ3e<;?=PMX`pS2v_VduRj$Yq1`-tIe
zFwyxc(s<^lYMNT;V!NX^kmhF^WWV>X9{?efzDm9}?tTD%$F?+$*tms#?JfDax&EcC
z&TWg0y;G4b**{MPD#u=}yI&F8R`2&aqAh9W_nP*&w0#jcHaFaLI+b5{7sA!(wNv5N
zbGNq+#y;+nz1#CnXbVM$V7zCFXGr6{yD`&vFG|S{PVJb?G__+g6L$yh_?-$V#0O3Z
zJI$yWu0CTU0t~w+)Um5W1ChcGuXsUFE$L9C;oUtryA>VCdAfGf4$qK6R&^p{{9_pJ
zNl#-u#xMRMV>~0PU8gQdh^T}5^P;8>#gULzr{W0U>j}vQhGScxuNH*saF?{M2tqK*
zGx(IkChvKH!!XJN?!%{qnclnLp%$~?coum8DIsAlmONECOI~U+ri3lLlyrtGLR)a4
zP+26H+^I0?BqHr_sRVG&LEjuu=Gtr>QX7{Me1UN<0r&*z5R(W#rvrRLF7EGC8g(ka
zI+aHKhEB?x0-ocKxgAC5;@~Cl1~uxsPN0k9-T^lY0vPB^eYm$kOzClNfo!qqf@c{d
z1vc&X64>EOeJ_fAjIS5YK6EWa3YQ(l97?xx>r+kPjc}?dyb<z#+z}x9!7VyOyb&rm
zAIJi%Q>RL+I-~D5!+fRSfy8n1#u&q~(r$QAI949z0v0O#Dy<Jb!gY{NSZCC}S(OXD
zfc0<0??%a~UM8hz+R0IoflkbJTbN@!sVAIB4Jke{op%9gM>?oXt_I~uhSV;Z&Pota
z5Rt>tj0d93azo1@2M3P(#Vvz+8?5p<xyeu`6oz!j#A2qhar~FGTpWKeuv{fopQ*xP
z|6EzvL%)hKq#bH6xI6TTy}^(e(D`v-@eEIeUQc(-tMls%w?nE0`zp$UAxJyYt6Mw*
z)`J09Rhgh%V_d{{IjK#)#c-C~V!HB_G$}ixlZon3hH^X-^oSY)g<xHVEd0CY2NcLz
zLs@cSz<|!W?kkHEL)V`*Bjt>dIq|gwUe;6=ES1G+Az-nVasf1ehs?y&+!u9+Sq5}Q
zI_sr35=L5%mqrm`z*x>i^-N>AcQu?E@ptDAQurj)om+^a!4|z3pk}Yig^I)G%@hju
z=~4~dpS0XfZ@5^V5DH4@JRzuA=?+`k`+(7%ubi9hGd+{AeWr&MRzC6>g&|mn9!fAQ
zsVCCgONUXQi7Gq{)bgc?c2clV`%RBTuur@1NFBbn_6kJ{jlm5@yV%7Wjh4@sHySP9
zn{+Hv!KA0K?l_?B6`^*kAZ*dTRS<j1S15(z+a(|Fu$#hE&E&My;k0X_lRpx^Bch+w
zIVC53#GtNvB}6}W)e|N93DY&bV$!_LNRj`9$nf-uuS+#lQ*>)69rdQ#K_hqHT%Qga
zIlaqvgg?5kxktiWjXz-?7L0cVQ_O(~i;cHt6pUR(&(R$ge%7>0?zGWqipJDoymz0z
zJ9t>{^Y}4<YxxY%0bKeCJfJ!PgqtElbVR%|5hC^U>otX%U@USYi_)Wj<<_+I!A8!&
zy>!wWb^^J^4I#UX-hQx{dos_+-&ENf<RmpP!d*iKLqsuCzz$2z(-WfnTCi<1xiK0H
z{;uJLf#mHPXBbG{o@>HkV0pV{9tQ1`EJ2LgCsAI}SnVTukW9l6SE;yvR9C6cJSzg}
z7fEhaM>JlBEk=En!obj2?OMo$vD&y+HAWV=Yj{K3G^;m)eV#ZX3^SSp)`?PRQX}($
zBZ_e$SUa|2hFCwx?2EQYjRIOC;RDq|V;O=Y1Gk%rG0kY|r;v=tIIF;1iUn0nE0ML)
z?#tvuZ16ZX#U(TFznOU8tajQcQQ=~sBR9D)TjeaOYBkVEt!lO5K2fWh4b_vl>Wl_{
zRZ|}^JYyJ8&`9f+O3lFMgXCDE#XuyrVA!#3)S?bx+o**oji3FR`&p%xsU|%_#eS8f
zh2rLmxPg@3%2s<_CW>sY%SMrH#)D_^w4t<&5`;PUBhs1V_l16{@ciQ{x3bha(9T+!
zsu>$n!DFSty02hLhrLx8iK<YCktjzB=2fwL@grQA3$G-!owCB45VuXspo>`$=3}9w
zkHP2J#35;j%zY%7AuyE+gIeqet;xm~^AS-LOca&|H)s?20S%w5bbY%<J5{ZaJm*Xl
z3Kn5<u-77;rBEsO7;Oh-!pwu&iWWm2=hqY(sK825Me{FV;Hzn!6n0j$y91w?$Rub=
zWTj}>6V-%aHoLT7ORv2<kyjUUg=O#;o|7raJd3#BpvF80H@-}##W~FgtkdG$UXt)b
zxV#~TFe+UnwzP=oV!Ac(#>pff7uA=Ee!l5ncL1s+uFC*59|6P$CE-Z2i~4|vOX9Z_
zg%5;?S@=@jMcoqb&SAB$QBGA+dPT4{I0(45kG_RJBSp^$tntwAb@w~w8(tr-_QI>u
z`3%lS*e*6?yrza%M+pFwFQZ2=^ouMPc4kz%rZ)*60J{_KLPLB3{|_mz<5rME05$4$
zZQ+wr7i$j`?$66(#$c4!U7LW>3q_lN(F?`c;Ji$Ku33iU;9Uu6`1Y{1;IDA4bhtvF
zTN!Y^!9uTlQ%eTw%{#RvRozK8rbpcUFn4Ugh0C?_p>^%9rEhR$@v0$!-->Id+T?W7
zR7DW+BSGb0bC4sKfdlXQgBfCxKi6r@puUw~*%1slof*vju2<TT#K<ktW*NewU*9%^
zg7^Br8A$WwBo`7n(s96Do^(Y&${tL8f{ko<R)O?jDMq*<s>gK*G;nNnvE3V#!*VP%
z5FvH&fIlh9a(I<7&;@m|@mrGU9RaJtN+3ViV=yu7iw{ml9-YN!R|Az`Xpm42e0mml
zu*blov-rGWq`z4@1IRx!1?b5yGq;-DlObVh?-_I#*5(5`$xb#jI|MI^&0rvJnNAIy
z!EmupAri8;OrY*DLPN-rglnSWP1u0K61ql+Ryz7(`VB0fNyVfM_#Mun!G)tnXhMxY
zO5b0>YEqMsxy}ZCeY*yZzP_F8GX{IdKD$~-U*8@n91T<W84R|4>gXC6v#!V>24>tY
zzCMFO{3Ah1zT3t^=)29;Gt%9g-w$5<v+(=D>30f1j5uGW&a7k)d0x)xHt4m#Uq4E(
zeZHyKq}RSqr3ur!KKLGDlb-v!rA;iiA-p=_`=;0}Ht8!o;vkyWwI9QvLZ~pgg$(^B
zQ$&j-3>gEdBp9Ij*}zcEXO@&CIe>0g6Z%gvCK!C^`_K^s+U-lcVDOyhOHfL}Ah45?
z)8I=FMh8e*GCHsr(0eGHkdfeH;3e0{?=f^~0%hZ6pfE6^_kn8?9vV7$_70|kK`LL?
zP)w<Mc}q#MY;1ira))fBVy`jR_aJeIFbnA1yZ)Z^8oIt?)pol_#Y{R7jw8s9Y^un4
zQu!}Xrf3hr_7d-=EDoE9B5WD9rFec-Hj<`rV&Hr=`AFE|{V+`m5DJ)pY;1*i8O~%5
zaMJ(-VRwZfGuY5}8Wk9sL1dC-WCoGFfPoq0>3XO?qU>XNWy?Ma+Ge1HWUx`Lu*!Y^
z2tU9`Z<5|1mBdB+{u<;vx&J&VO5&o8A0+vXFb26oy1yz(@|`Ghl`t}ZCy<dgr0beX
z+7KD{8u$>p?1OD3Kas+S8mxo69{rAF<!^2tG9|I5n#LB$0N1xJGj9X=h)l%|0XKRV
zIt4Mqk)XREW_Y@c-3@O|T_GWDk+i72vPFB_D^t=b)jL?3WR4~-DrNx=kt2hF@1e_&
z;YjkJ&|`*yvqW6xN03Bec$Ki#WoHv9kaBGShy{*2J{}k;P4re^u$u0A8L)U3>tt$=
zWZ+~4ST*vV$g9TE(z=rq{-l#YY`*d&Roc9*!*)qUyy3mA%LVC3f+S9R$b#!M73$BC
z#2Re&%9LG_ssgcUdehxxVMml-SQNC9C60~BF0@yk?1D}SK;JG`H(OA~^roxFy3}{*
z=0J<3XeMJz<HZASggwJeKNOu}6z{+g<h@@7F%W#OLJ}l;snmik@J>|W&V}7v@fZyJ
z9i6&eaKlu6-ASUvsWAstfWo6&#HQ+3ZM(n|P<4U8tL8`YFu9XA@n#`y;?0sggoadh
zPB({?B!we42e1*yQPyB|e<T=f94c37yH@tN(Z1R6yc#5vn+0c=b-h?|6kW9{9$;y4
z8N-j`sg_%J^t$X<-NCkbzw-jw=6+Qj)1sIAp*?LzQ8Ui7tINbq@<=#Ual(~#S7fTK
zzWgRBQ140yKaSL$2nE*Z2LFU8sYy8%a8oUJGT@lJ+Dya``$(9ITYk9*L6V7-dknCT
z{oThXwZHoq_m<LM9f&?QO<mj+N_(|8dtG1c&0gQT0XkV;?aNH%)uqf-Ua2P12aMd4
zw%6*x2z%|V_9r8;9&|8rN7BY?;M!hytGJ?}9-W?C0$)S;v$p4J9L`)i5<;)#;tjq7
zA#!2#awi=zip><ev$LqS?{Z92vm;@Tt^_^WKmEDH5a`wNikfCW%i!jH)9i0zs^f&9
zwRlB#8yCZLH*ZR`d52Eta!lL8lYfZRnjT|Ym>S@&R$EfyuThD~;iA~RB3<tmqS;(6
z<4eMwVS^}pN*gTEc#T%f4<8z>O!wQ#%+l}actv-xnClK!N=}yl`M3Y^slT27{ipvU
zL-&3vAM3*E^Itqv{-^)&+kbq{j#xfD{rSJ2?Em#&pHKSpzkl)M>>9s~qhW5J^6GDY
z{nzKe`j7uo{-u2C`s;su{?~u{>pxdp|MZ{!^MCl~|Lw2;-Sgl4^*In~xVKN4v+h|=
z;h(F<{9G;mr~mf1|Lc?Q6rTV8zyIs=nHBM2#u@3~{xxXb&V<W!cI{8L_IM!Lcdh-W
z|KZ>N-~asA|1(?ZD5|eEKJ}Nsl(O8;Y4^993D<kJ^7w_GY4r=O>=_66n^yiW|NXyH
zEA0%WogwVI)%p3yDxXoUf3uOqD{N($?0zQ6yOsYo6Rca535ILmXM)+%2-dHE{Y~jz
z{@(GhpgH(<j{UoT9^;?>^N%0DosrQr+ni=~o-g<L$FN%0{F_5VavJuMZrgw61OCnO
zQoTQ*hW!+n8VU-2XWW<#)^w*G*$kQ2{XO&jbECF0&$K+IsDFDh{mbX#rP=iN_b-eE
zZtq|_@Lk^whpsZ2PT_B}r9IirMJ}{&GeL85b17)>x7o1gX!t4k`-cC6B3D0dphrW#
z*Y6DfuMd7aQkHk`I<;uu_6|JfH=Bshzsq*sOTSEI3jQD)UV?5mJq>-EZ5q}g^vm{l
z@AjJgp`rhs*<b#V*-uY^+c#T(Vk-AEwY<4#diiZ87@^!;V#5C}TSK@}WowE*`fWDP
z2PJ&~3jV&M>?5zMdIFR3w^zV#<<~#JInlpNWeWbFcQ(IHWeWZvTiai!G6jE-?c7{n
znQHsPJ+i`rP{U8b-@5`n=Wkyb3U>b9@c$z#pyo|bokRK$dN=FWsZ7BiWP@YS%_jQp
zZ?iS$R7SSuuc`dI*<hG<KY^l<{?ZDl^#c(9_9pb(KX3-%ey7gqzV}_<pe<3Rwf@93
z4#In7ndOfU`u@{7-~Ytkm|Dxb?aVu!{_a_SbhE!R>Hi_nv%k*X{U_$`3kOnAzuTzr
z5_+>qz)SSsF(QYT$HwQp_-%ZSQTsh0@=HS!N|M`5B){z&)D<_A1m9+>(DvPYSMq&E
z*z~_LO7eY15dFV0O7aVzp`Hh=`PmKj_ut_cz5;_QzgjBE_g#dV;FVF5?=v22^>;R;
zzs<zZ$~W7Ue4i0MBd?5-{KA)LVH*F3E8^EqM)Hll+A7KSot$5<i2wTAm3*HuNyuOM
zDEK}bg3Q12N%C#Rh^F+)#`G_IiHJ4jeQf*gOZ*Z<<TK!_osxXtJ%mJkWt8Omj9{aB
zWt8OmjGzO5Wt8OmjOoYm%16Pke2b%LO|bIqxA?WA6Lh4ngHV!hyJ!gD{MMvU@_j~_
zY`l+NO1{qslZsbHNxskM{hcXNzwjMG&;7@1;+H_<-ak#WEBUr-Bi|cuJ_)|h2406(
zK1sgMh~P4>jFNnx5gxg(jFS8cbUH?3^AFd=uVJSF)~i=rCHaG?{S}9P#h5>S`?=uX
z-RR;|)Oxp%(5XrA_raUbNTs@~Mrgj@QMlNzY~^eyT=UOX9*<y>{80~Eyl1`gH9T;A
zpDq2JUfIh2=6cI)C4KvDHVFPG8#SEx3gxZg{QEyb@$q}tpMUB9z(*(<!sXq)xxYV8
zkrAw&uZ)U>^nFGc*1s}}z3KamAjf%SZ2qTegrnB|7Ipjr;D3FLW8(2UAEW&v9|Jx&
zuO7+^=er(mcXlxIQSb-Z5EJQUTlQyagJtW@HtTnaYG$*9qx=d?|Kdm3#{&NM9zlNn
z8*GrG-p+|7_1n(D;^=0R3DURO5I^>2Q$X48vU!Fvx!EZAgKSa*=NIr_(E=aOy@Zwi
zUswywRw9Vq?cAJyrgNjevW)&mKM#MUn*sDh-)3p^l_8>pe*1GMiZRwNJ@MZ^(#I+H
zzo51eEnJ%qW9Zb{{+$Yz**vZ6ZZ@Yk!?)QGo$F>(xUO%r!MWgO8~$f%v-HB__%r>B
zUtk?iqTl%f|G<vFI-k?nx&G~Q8neND{AQCs`M23X%y_dY(93t(CVUW;ZOSR}+iZwO
z$1lM2FMfe}NOFH?xA_ME(476J&dqNh;+PHW?l;>guipJ`wx1#I{8NZ`wl1YdW^4UV
zTm@#?tS!Gl*{{m}{x5KhIDcmi{6qJEmu7~NZ!b)q7GkfASMm$D!ec(07xY^H3u~<^
z0x`Ur`V#$tF89mOAo(kb>f^#P@oM$0Cg@i-GKL9yHT5O>Lk;Oq6W}HK6-DrItol<u
z{iW%O2wLy?dPUzW_7H9To%M=-MY(s}UhALf>HHPFQYm;Ny^5tP`U73Y{GxOC*Wa$>
zSCnUmKJicW(|<{Smd+yY)?U#csKWf`$?y{W(yN~RW%NJZg?<I@QGxVs>=pfi_Wb9Q
z<fl#h$8Z0p^gq+@=<~mv-k*2)?5iKvvHaLScl-Z4y?#Bz&%bPMUi&BaG4<A=^iTh<
zhUYu8)brZ?|NQQ`vcOgs$4Ua#WZ8p<`;zyx*GS~}AujA%V$<_<m0F7qa~Vr?t-K1r
z^L{P5M1h`vEviGpRsTsr!7s9fM9v5ldjxs1dlR<Kn|x9Pgdm(jyvM&2_JL7gEpVhG
z<mg(w(8DHqExO@3+>4joy3@3IEt=~)tq|z^56ZX2D8IiY5yA>q!za_xW`znyjM5`W
z^^T87puF5U*QB|Q!(VnyumT`T?3%pJc=$n`bV56@JgiCm5n{$30o+m$Sl~!dOS)?w
zK~{2}NY|uu7x*SVf=pxw7Wo-`MGCd07swH0Q48&*4*?i5mf}Gl5{*ozW3Z<m!kY8u
z2wRYOuBCp;rfDR?5-ho;Bkt=Fu&*2K;XMwlA4iZYIwPVk`KbHG0G{S=FcU2~tRt$y
zn(!rq0sm6m>@XZY$*d0qCLh5k@xVu5O%fSoyn~a@(khxuPlgPCu;k|sVwGo2dZq1#
z?@JfO-OxfhCLx~e5o9GTTG;3{up364zRsYnTXKWn4V~cf1&`ekpwgr=Sd+vrAdNYK
ztTfd)OJUD5IPIGBqu5wn*OML&B5P9Lv|$wlo1P5cx+YaUJ3Ro`pjXt!G*}Gj4wsZQ
zXvn*BDy@+^l0D;}xo08t>k(w9AH=a;gX|1pOK@)Os4sofmLk!^gmEEO{Z5CdHC$bc
zWwPX-kFX7E(DDo3IBSq`5oADX@XEPC$#x{M<aR8mLFcQD^)%)!Ax3fVeg@UZ8j3)Q
z(6mP~G8wJpk_Bba5j6Zg8%YAi4aTb_K7hS3&<Yh_N~H2TRPZ7lNp6J|1WQMfd+Cv+
z+C)*EOPCL=LG!u_EO#WV1}hH40#Axs=3-S9{ZUBiQqd!@QdE#gtwEopCrjmxx*{0x
z8j7Zlh!jV{dK$XaRSy>78l4rTPDgA76`WTq^nSJEDqlmP-b=?cZS*a!1#538LVTfu
zsj-@l{t(dBLZuXZo>LTUQNVgoge~zIRPYThR5P$ZiUwhvvw01LkS<(;bXh(UM<!M?
zBgHBvMz%ai#;}@#t0Q*Ck*onhD$2HMovA6?B#Eviy`L7^kgI7KmvRLU;gPUaSb3(<
z@r6szxLhm386Tw@3vx7Ov2~tpQM~Vxl^zL*%qyaFEK_uQ_;DUd#n5iFd8zWVi!GZZ
z<En^*yo}+=0d|*7Rld<rI$hVAzT-<I4o^+T(<4FM2oQ24s5==GKN6D99W&JILpqF|
z^qC5xcBtSay!y){$>!m3t%#a?1lTA*cK968fS{!kG+TQFG5bvcz!5}unW<`E$+V1o
zAj%HVeXSyt?y`=WItIL}svZO0RZ-6!G(;E$Lu;Bc8Ct`&SWg*MwGPx;xf@q_KQF|Y
zs6k}86dvNFb0Diq#5h(p1HqS<SSM<o_|8RD&m794!JcS50q>E-Ho6!as)EFESy5dd
zK&XHW6=8N)SEPB6eXhQ>V^zRLMLal?iEQj;>RuLu8B}nOuI>!yRx_&ZQlNnf(#IuI
zizA8QR}g^;8py?{WlxBrQ;c&~YyO=*1n}&RRQ6}7*4$^FrPu%!oUKcd0FLDB1AVE3
zSc)A7d2LvU8QSB4C>zGJxVD<99NUJgnz;BYSRq$1-PdG<{LBOK*w>`MT_UnSf>;Tp
z)c;6;F~z`9!O;6Gk<M4p_<kfv<uDUCA4v`~7dO~~S6;lcdp(k@7FV=jlRv2(L1O2M
zaJNf@?MHI<7}0ecK~AIg%9OP>He*DBoyQd{ZMPnXas-=tKhQAZ;R+h)CC-nU1QiQ$
zKA)82xK`GTtC^_NsX<+0POpe=yT}#tgeVJU-9VZ2&Z&({PN#0;l1t=VgQ(+)G@F|T
z))JpNy$=?dLyjOCr?{@Qf!$^y?CTMX_yP7h1fE^uFRutZyTo5!;lQ|>)BCt0GSFg_
z+K`;@q(HV69xbamYR39%u2U-;zM89UT<t_#QV~~siHE#`U1c%WZw+ev&rm61aK%H`
zQdHpziv5Ma!!>zcB8^pwX|NijW>n0SCD!qZ*|fwuUO_3dnox5@5jbhYzN-i`uoQ3k
zNOC*}dw|QDNXL&PMpL-CgM9UfSQ9R6jm#Pq453RL;}rpqR_iLrqJ5ppfeKQdrTErI
zk|Qi!3>u#$((&2{nj8&%Qqr<y){Wa<>qup5g^RJlt=3dAB8{vjT>RM-m*~eUHq9f!
z$N_7L&ZQz$%14r|!i|q?<RQtvRMml7pZH#CZt#n2<WESlGXmB)Cq5FSV$*5@*4;CO
z!SFmGmPp4dxKNJ-yH*D_73+9KXq}G)sk2_{z8??Bv~mkT%%3F&@|vgds$2DLyxTIB
zV_t=<5#VWwOr~Z`s8xlc5nJlM{Z_=MdX6ZY0y2PAg`)w8RwWZjMWn(ddhv>AUyDKJ
zQWRrbg`@4HrmDuxj!ZTcA<vG0HRG^2B39kdOQPr_iCzjs12?WZSTF!)8XP|mjS%n$
zG2KLmLyCkY&)8}fDR#v$F{(f|LR*ET@JBH*L~UM;ukirc3CLG9DlRHO`w_8XTm?mb
zek9pJZ4U+{TRX{gYg`YO*mx>JW~~a;ZNRc3P^WLps>0m{ey9-PlVIuArn)CuEF_Mb
z)2dwWLAknWy^RA36@B`VWOIPU!NYpe*hLJmv;vI>GepaB**Kt5QKuhC4!FR$VKoYj
z8^Wp_5w;e?rI5rx6|vk`6&Sa;6Bfa7u(Ync2|f@-mkM>#=eZ-+ji}NqZuCpsK@|*!
ztGG}+NLh~v4a5`7kzjO2;+RE7^&=RO%mzOdysaM*{+x{yxE{C@7GY~}G9C%*#q&ZD
zxCV=BND6<GU0O(Gcc$v;ky7XIpirhN!E!BH^dnZQXxmSEB2UG6jo9-aQT)Kra-s3m
zI4yCwS16^9gtZ`e<SK&W&~B|FG(G@xOAhh~ix~C{7&rAhPfB976jQZ;xJ77ujB9Fx
zTCp@4sv<@CaRRbKA-IYl`@n5c)b4exNMXwuxaurXy;snXu0p^*;s{tpa2#Z&M}iFj
z{I4tNnI4E@V5`c-A}oaCAWmIHaD3oqh`1l|{ctlZ<nF5@f54jY;7|z02Y_kOVIA7&
zCnWKUnNJ9F3wk43T1c{sv%o${*n8&sJCX#HGc%x7pjSN-v<wuha|?Mx_daDCS0}EA
za|?N=0)K8HZ>ad^2J*%mz}&97^E(^~582t!M?vp-knG$`RVR?0d#UDz9xkC>ym}lF
z>+0wg@p?X`%q_T%x0bmD*C%*F=LTK}=js%%Rallp-IK-IU$Rs--_YElTg!z1@fKR2
z32djF;_FOcJ4M%D@enoh_2PlZkPVd&n5zlF&yl?pf}aDuG*VU7Iq_kH;O9gObs!^B
z+}u)R=gZxc+3j;AJ&G1Qp9}4w)_SgNj*j2C(40W$$&`8qT<{!JsYk-bIfh*5{5)Ak
zn$<eSyz#NH;vMuOiqyvF3XbQy=@GD&jm`+4PXunCqVzhVoOy!dt6(fEQrT3&@nA8H
zG=Li(jgJV0;#qla0dhP&PlYR}c%7a>0#;XEJ*Q$9R6K7_Cm;tM=~OU-BZ-~Dg~-7^
z`b^)dxy27yYa-l_1gV&iF2o+M`X`M#d!nr=Q~V=p`4em{U<jQeBCAOW8WI#^k>HmE
zkLMIE*^y*J1k6F(IbGl!B%Lz@oINRtVRoT&P;gEKNvI2}&;`!d$PP@BE>}=zPA58F
z`A%^JSj=mpa$)Ng&6tXra0CI`j)=LkJJW%!lQwd?6xd)nI1-M;!q|!6xPk(5x|T9X
z{-^lY>hegjUdI3fSTDR@906-~jIWS2m;<Ny+CZE!UAP)-ch5vLh6<*-lV-Ua?I+Oo
z@<~YL?FB8nDsM0N_JG-5&@#bnFKAg+nb|O*Y%d&p!ECP>d%<jk3_KEylUFofFgqGC
z(}w1OAQm@cK2-E&D&|A=V<s%r?O0(;2fAYqJ0k2Mh&wo!j$?d>xrDmo<IN?2jn6x8
z7>J7RKNk@;rpQ!Wi0TPDKN6&3tQ95VNa8*_moT<p(`Qy~vVGnxC-(d$i0uPYV=W|O
zWS1~@kO|H;Rm(tk1hNtD@JOhS_59;p0?oPlLx9nrXo^5HHjyJajeAm*qbtzt3k@7d
zok9hheW7sz$?my9FGDKUt)f&^1c;dn<{d{6YjkzBYe$Os**DrGMC==1PjGh^d_BS4
z9rN%A5T>+(YH}`uTg29xiegc5cpV9Uk!=&Q-7!A}Z8reqVsNA*8IeXESQavvsvyps
zd0;*eWq*pwZRn4b(L45uIR%J;0VeFIo)o1~J5<kr7E{4A>IZvFdHmH4=qSsnBgrK=
z1$K9SmpO%Y!6`Z?&~BQo%;~q5?9aSl7x5aWEU1noIwZ7<0FJfn`&si{@Q8jpunVy5
zlh&1G=UfaChJ0j--xQ{|<zkr)6S9!8s$3Q!!qne`KA}}#VWdmpzTX=W_Cm%g6J>^o
zRR(Ad2`ilJ?)~Zrr4usNIMHRlUw)#?f;@X=iuLDX#}hI(Aa|e;vAP5zACW7kqvg(T
zd;a@GnhkO`NVk%`F?JW0>`lkmsqdS2yb#@tXaO%GtrWI^K%^mxSctOetzhw_tng<e
zU1zhxBk=6<Q0YjHOkifXqAeU*=Z_kHl^(qWFb((R5V73GR$E>@8!p}<$-|%_5L<{)
zcKZv8W*_p#_Yo-y*^!|eT`d5uRS}eFAZ89xo)ax&Y=#5}VFROc$k2q&57pI(E+1x&
zWM_{XRb;IgyUgoKLvXy0s4AzirM!Q%GSI9_i^L<!wID2WM7i_{W{zYbUp4*)&59kq
z6|Or)r)r4O86viF@-q~T)XeWt?m$g`2rk%$P=!Yn$%O$|2&*HCo&mo+DaxKHs#SwZ
zE<}b=%3tI^(O?0bBf?}?tg9B$7*kOAqipc<TPi-sa`gcZiXr1DZgzyp?8H+2n|;7N
zrGZmDB)Hu*s7gb|25f9pf<LX6Orq{uuml4QwOY6_FJ5OF>}o=kwL||K67(K=<Pfpw
zyeWn#H>C!J^hY#QdSy=rOK+KCgB$nK#rK4Uc%va=(T%M%72UA17{=>Jat9P#YLzQ_
zQK{G}SMuWZr&X-vWoiO~ZGU8)rFV|DHib%8^VQTU%T=@(u%YEM$dfW=99T)PUT=6z
z2>~0$MJv#CL^!~RyF!L}p-rI<wzR4dGn1@;rp_~D0}_mRRRbo+ys80{9p;s%#T!+W
zR8;?BX9@~m*b-Jz;VTyyt}_i0d!G=o=+k@Iu{XTlg^2xdv>K4?2(rynaakM4yF=Fa
ztN2Jz-lQbAI$^a|H@?wS7{-PW79nF3;I&jHZ%8d7wuS(kZQWQ=)A1JH5XCh_Y{SM}
z6=rLV>sO)G8Xi|egolD7L+fdR+Yqbuh>(mX@siUJxjIBJL23vX60#hqR@o%2dqiqI
zA|zw!$U^=|EcZYe$sZX$!B7Lh9-(k<4Z&PfgwBFY|HzQWV4JGz*)vmJojo(v)!8xQ
zm98~n-`SOu@K?6*M}#)<`qUcN?(EbgwZ`Qu8~GzbQ#+E;%%*k^Hj}{u8*DB@#QFz6
zKvVsbAE0TNfPQDA)mCeSzq28U-V)ijM&wI-`PK-0VKILW*tRmw%DJ>>RpngVQ^29+
z;#Nqy=Sa}oqWTwmTUfuN8^Q#L{}ZB$BfmMjLJ;2?F|+LOk0|>>L;Tk8gBaN-2x@a}
z!4f|hYokH3$8U|uTNe4PaV?Kc%~)$(xdRHzhG<A3!A8*wTSNtA>lMkoV75-gJeG11
zFpnf#Zyk7f@Gfv9s9nJnTIVX2$^8+<=qiNXk>u#Y=>7<DXvY*{N7Sj1VF-F-Pjorx
z{kNd3!M@drgU85tKCKf64;m62QTBvafo_;wvZZgGm)2oa)EyaGX@6n9$$Z#LI<KuX
zr*C~^3U9ux^WG}^`UYFW5V3w<TZaz)&TH%F0@xkcS!VV}k{buj>{};#mZAL-p~LNd
zIl|{51kn>d4_yR0(X-6$kI0#g2VWX-ri?Z6nmU-wc2||dOY1etZ=JW+!Mj2yik4Y^
zqr)aAWddjg9Xx`WkVB^WtrI~HT@_$i8zK&+7OM7zzIn!sf;8xmbXn*-yJlOp@iuI_
zD<EX@6EbXZ#%rzVHUJCe6y-ps;d4mPCPqdM83qMW`Hl$5Y?H9R@vci-{bs!C+Qt6H
z%dQFg8!x-E*FPc@&f0m~wH0g7c+)kZe-bzs+UqwXJeI+JGr(h$LiC7o4Vr*~iGWHM
z0<uaM(}lozt+f%jF-0Q<?1-`5x)P9iy2zHl8Lz%(w5V@3*m&Lv47Xv^mB5IrVa|U9
z=!<NPnh{mYr2mL=g~_JB*+JFT)whX>nqeTH6yY;z|1e%`O_v74#n!asjrUq>+V_kX
zTf?Qn@B_An_*l^)n-L$I!U;7aL^fRqjF(%O`yYWbA9icw!b~f;Y!R=vvid)w?22v!
z#*3@rHekHAnpCuHluYOLGD@x!@CcoB&Lf%Tx4|1JZS&jUg|rLR4_-*SQ2pSAv{M6n
zMA^WuvpT~zKPkgr5l!yG^l)Pe5gNd2tE~1LV!3|ymo7{{h=pam-v+R-Z1>yfSn;&X
zZ)y7Tq=?0H74`u6!_Gei@rSX6Q;jw@kw(D{!J9*bl{|Q@4Fmp@%+?9w529jNyq=jp
z2#dQQ{vayu!uW%zSa$twBr@(p*mV#Z_km>27a8`qF*C{0;==2K{9{tpA>;lA$n+5j
z@(<$KF33L;y!NgJE}mSn`fr2awRa?QadhE(*aL+qw<3gkenP~`xEQ<e{or*~#{X^L
zzS^7WcPbTnmcz?x7rr07tJ3(t4PI4c{oh7jRnz$YfdoC%(LM-o6)UvO!j(m>e1p$y
zh*;R<Le{;1YAI7K-zKlBat%15Y<p8+$(CNaDa-!MywtX>Ch$@V=YTeOqiqU7+a}?%
zJOtV#T9%8z5yd{%Xp(Rw+2x2*`aqQHPfh}D5-!6_piP2hxd}A*O^1kE>Ez9}>2@&l
zX4`c2pS;;NT@NO2w&%)~1sNKy`@tlJZhR|flMq@i25k~VH~HkYNfZq)gEmJd*b!pr
zrn|x90;iL~6SBys>%ru$w&AH@@=n`yJD9lB(x;%!b*6j6p*@Lh6;HKIV%uiQf+;C)
zfyOAyA!FCMdgU?DCReXq2HM2!R4xN;IuRc!Q`_X_R9*vZ@^adw@1MM!%6Fj6I3?sc
z@JVB1pl865pff`A6BxHKl}oEtn$x$%duXFMQcIOvNYJyz#oY8f0KSP3;h<QB{m{m+
zc%^MwPGk_`U%buAg`j1;<0oaTy|Sl5{EM(zo&;?HI?I#bNU#NlFF{)b&Q*7SMciC<
z30TC<ici~CqgGWe1q}g+gPfE(d8e(q1T5TOt1bbnvr+OjXp4}yGKog%{D&qwM7g!C
z#KiU90Tw~Ad=1*-@|3edTgb(#xj^ee62mWFgSL3XrL#d>yx_{)pe@{Q<!sQF-ev1l
z<-Fm_;h-TjZji(>C*OJGQqUGcyC#<`a&k4xv!LPS<0H}|z~Tz81pI43A6<p`7w@$2
zEoh4uT1D(_i#J+%7qq2!A^8`ymDk!T%)bboE8htgv9lZu+S0QSTnySGa+Z%lTR_h8
zF=&g=KnnPKMChHa3X99W>UqKW$P1p#BN&-PKhpLn3esi4dGW1!HgH~i<&Dssz#Hxe
z&566K?g~!at++tViM!>Ja74MG$S0w>aJRe?nrmGbwL$9|R|?mv7SK4RVJIl~Psc5`
z02}19Z3?jOIPrAhrNR%SF82X|^h~8_UvOe-`5-jU)hic-=3Kl*4*<>^t^5#<C`Y^K
zvf#YX${C?KZnWj<|DCth!rOuqGb<u;^BKwfCss|-%^-~io|K^sF4Ur%f%EPfz62+k
zP0`K3d2dbkf(J5;s%{3p*kIiZe6hv488`~!y})_FEdxmmyzT`~I9+r%aKh<gQr9`~
zv^)(?(A%73a4bkscFvGOCx8*2jFg+b(B)y5Ori&y?>BNjXq)dhr6UPVRuLB1MAGy>
zKv>@ps3NTTqKiYC(V!?cfIzzF>adBU6-c^mE>5{Bv@~CSQieuUej!~SHj-=s@5Du~
z128svLWaFy6aSW?oV@QUEcFqM6tI<`I@t1BIHF+t-@FoRiv*jOAM;4?*J#X6pM?ja
z(}XRjg$NS;$-d>Za3qIfd+RE&^ZeNvQRGa8orlzx&%%+M0ylgX7>RnzXW>Y)R8~B4
z3GS^cK$`le1ml@Vd2d|-_C%-fK(J@FcIkOyPc&EfKmQmKmb=hgy$-<PVW-E!lVQ3e
z$@XUx_SR{SW^VZ`G&o!AE$pA}7*B{;cOdI6mxUwf(O_H;cJ8cO(Y#xZ{N7~hX>dc?
z3h~|Iqwg(^0Q^|?)`bDSE_>s?@SLFN(Gp$_B1(F+gg1jD$+qxf5V6%`=y)+Wk~qdT
zy%q8U@k-FK6!zwgpu@Lk%Uj_{Mx?Qg9zhOeW0?(8p{d-K&Cf*t{HyY}u=m_Dzw6kg
z_O3{soJG}lj8;*{xz-Bz(Id(x74_WECIa^(X<0JsH4JG%DoWe(IOy2Bw{KOQ8~paI
zF&~jKj9!AvkK{ozR<OH@4E%ZoED;M!rg=S&y^TZVGv7N7$4md;;fVK<AeHUpa_#Ws
z+jKbSpX2t~zEnp7^X*G5Pn5fTX}lKtvQ%s4kAlkJkD@<QHD?>PPu83ecgrWCr~Bh}
zDe*h-$q}(~EHqgH1}SSaaHz=}4U|=1&(I%7!uD-6hd})Vv&!}WryoJA0a$sT0S9>7
za8u}k?zX%XA|MvBpmnuizzNWMjk(lSZN-RpR$I{@g7YKE{`9}_7dd;n`d4fAudCjM
z-ZWLz&>iCP4urk|R-Ys4kz`Xl+C~I^B-yyCLOL2()m(5!Zulwmym)M{8YaYE^s43>
znoI26am(2W@E?eB^ouID82_TGb8p>VP%~ofxR!slEN;_Hq1ObkTW$(Ra^|5t6*{hl
zTb>FX;jeba+j}5dnF~8W%_pTJVdZ)K+-tM$b8_wFDi)fpEjzy>iY~~#;Yea<Sgvvt
z^lo}L96`&1YrzCb*t^$KrxNsTnfdj++i&?d^qMFCPH&u80ErFuS{f{mF0A<X&T1!{
zu~8}EIbztK4jy>kTlxHpn7cPDxJAf)Bv~C1_mPZ9!*}=y;*;m%X$7N2z<ne+TEyGE
zRg9LY;=CYknc#IOqjoqkbTC=$)m3VySYo2ekYK#i#wbK=c|$`9w2vek+mXtKYQ;AA
zlpPVe*K>dgvO83LN5YnOeAcFl8SO>3H$AyXLWHH>KCpCE)eKllPl+RlbuUkeBZ*yl
zud1pUXQry^#HBLN>tI(o5>}j_|JkdkoPh=tY4<iG#Vk3Uwp<~OB$_uj6yHY@<3G0=
zoafAjAzshuv|FwbM-b~(?h#Liiu#CHH&Ezw)s2-konwWCB@4VG35>MiFmVJi{_>dU
zElc1qIr^i6yE*!^c+>BA9XKL34iIw^M)!DT*pndoq+@93r2Fs@IWk4tdWnCdUA<te
zxu$zT(}<uuUsLuZgzk8AITBQyJWNM`G3f=PJy31MP|M}FgU#uP8h?}h8>%}n=rmQF
z=hB`8*%3)HrksrJIv%O^B+l-5$lB9bQ^qWsg4xNH^@Iqk9)wy)!h$;*ES%jtT1=ST
z1I5m+jkyEHP9g0M7%NM>Bgrl_)eRIoo1kt_7(1Kl#>H_Gjw_&(;CRxG?U{+7r99D{
z@biI|36S@JmSt}fkItg*1CGveKOyj_4Cam`XQ1GA=ei5H-Ld3`&~^tc%@MKtxcLno
zwmq(XLx3Bv*&j)yQiHXVsNjL<w4U~Gy`LXvd$6u#1$QJ_-O`VvHtD{PAjWD4H-p-5
z58-Ce|Lq~%40^ylbQA7rVX%jAv*CU>h?~JXcm&wl45)KVGBO-dEb1ZPY?%cci~&-P
z!BQ(aFjOiSU-l5NhS|oJg<Ma*#yy0qt)aQX)z+}V4+3jzXs@ZRhUNlSTaSOU62Q=5
ze2hGzSg=E|+JHlckhP`G>qt;<;!qmOJt2vyH-M}S%W8DhovUgHSes$^bxfOKcb7d}
zho#VwFdHDG4BfgVUL5t6DOmCL5R`_Y(jGw4ARFC7P};EOX!v#n16jDm7?#|i7W+tY
zyoID~Wr#J@i)-KjjyAZYZ`r(c7<wH^<8N}fg`?AA>{F$x#g)%4YDRG0EsM7fQ=e^H
z<>W1So2#H5DYktlu-USQ>j)NmBrFz}LKA8R6Ye&m=H$xVc2Tq8mS{rF1GhvO$Q?=c
zK(HCHfp(fhJrHFGJk*V$-UfAe$Cub9V2!V}EueLpF`hn7Rh)M|<H<ZK8Y{Fta0#@D
z)cN_ijRGPy;cd*|ElamPfJ$ws&{PtABuE8xHUVx}m~Io`9$1L7aO=4ww+V0O(*DeS
zGbD2a1-N5p*v6%t7P+4^5?P~`<Ul94wVNT<fC)MeT+d9<d0@4fpffhiXIoSECz>Yc
z9Ja~Z1fF5Oyp7-)7S7wM&I=HaZxeV1H~EpU^1Q^E!1Gw>LxEEFNOENq^~xi~LQ^rc
zO-Op+0%t{~dK~*EcnyQ_-370~-M;%~k8&mME_6L|wLTjbaYt}k-vzG+E`xom=3Mhf
z!m0sJyVIzq0|)HRgZcv#w(Q_KV8re~)&Ls23t3OX(=K>DvHCiFT8|`qs55_J`E@F`
z`-HpV?n?#Xnka*}K2K8xw<nNhpK33V<^e_z1hFr5L2md~?9PRq{ud{$N^<IU0PfFB
zm{^rvh&v(Y?n2x^rAIQ5&f(YcpYSQ$oroLJ(RLT&o)$4Ou^mp_3%jWnpw6zxtP@8)
zcE~O?4VRiNGq(=6o81Mb;hVF&oL4(scy=e6o--0`8t#Q%P<rBCD5JL{!E6wgp12tH
zrmFL5*af90AZjO+#+_@Y7sCTl_Oc-r>#SGR90;{nRg1@oUR5o^hipX!>@$CWO0k+{
z_jV-Nzlu~e8-V-?Nw!<ZHg2-J3y|ZwySo56uEZY+QfGf?!sBpm+f8sB9&lTBZbuTU
zrwNd!olh2onitk;Bk4|u4&Wm}Dn3k;mONP%w(Q$_I0t^x_;<ETYZ%^zyAijqgsV-M
ze8CrCH-T~}SGLU4da7S`6DEg>W;bGTFjMT*F+32(u(qiYz+JEjlSiPTEz`7<&QSv@
zfBFI-ZGz=10cjH`UwEyMVOodsYd2x=bW?pogcf5>Hl4`}&wsFAJLwTAmWu0OyC{6&
zKG=l97hWxzQ24@gVB^u9+QHo}3SYpm4JaH$C%XxSgA8Ri!En%}90{vlr+-@da53IZ
zpd0}yccT@`k!1S?(^EZ~1z}f7rRr|N>Cn6GCYTQ0>~4VR(B7Uj74&fC-i?cS<=<J!
zMr#Gp7Z7X{L|<?z*-bco0m3%m^u>j!^}e_e3DcqG-mPfoN>%u-!s+mf-<58x9nSMx
zHfh~)gRD;Hup^4r$Re$01gu^Cl`B?G6$(cbtX-W?oJokZE3HmC!eH$x6plDpTLx+!
z90a=xg=ZwJCq%5hM~XG$T3Ly~5e{oto#u##^^s%;0c5K%c)r@~I#ny4Eh-OhJPz$j
zRQ?=Mwmx9FpZwB+BihxLHClJvC95zwUb>#G0F*#$zqsZdA+SCYq@q>A<OqOuBy1<J
zZWYgb$CKI-v1(x5YN|T0ZZ*{ltXmDKR2fv^c3+XorJt{kpEMHLCZTpvjO<E((;g%w
zy9$pZ4%V)M;|PScWjJ;uG2^QMxo;djm53aqZ@WsJji=gO1<1jsva0}jvaReY_mU3g
zmR;c>+7bEc2vBf@zS>ogd;@#R4(#bWkNaJ8e8Svi!xF3~waqR9)1bfEMPPb^)pHl2
zX#~C6MY?K4z1l^0=ZJf?i|{n!UL8rEu!wuLivTrj0(KFehTXs}!qaJ1uwf?lq$Cz-
zS?CgwWmzg0Z-7PcdSfxkMC>`DQ?3v;tSNR8!UoynF3@L#4ssU(>|~65LX?X%NhMDj
z3m;*#c9BXO<djFkssT{TkTwIMvyLdso$+sMI2-u15M9$SrU+f{xEAapfDQYXBVqq=
zbu7|nZ`=!u@bxB=ECSfk8-Z&?%-Tho>J2Dah^==T9_%8|&kh3AEkm#lmeeC*JsWdD
zXgVWh9Rb`mJ7Q(+LO6|JS-a@e-M9%VmE%e@ZKXVs%vw*p(ri7Ev%zv}%h1aTUKmPI
zt~iXJU8usg!llUdYK2R&yvoU@5ilE?bqb1P`_1=OOLMRCy;W`QXD%}^gNdAjN9jq?
zL_w@KBg^ltYIEmwl$uD$x2tAw6F98ELUPuCZ&%GZC60t0w%;5>XlQxv)K7}C>5C;=
zHfpJrhDI$lbD&`a)Xx!}h3%V=+7Knn_hi9m37sSxn(*^T*icxb`JSqLMyg^&CPsCz
z%!x4_Ds^V_2Te|nB->9oZDpZmQ?A5~z7r}N3}hYq)d$mBhQSI^!PIiJrmN46=5XCw
zhQabp(~rlncl++BYGW|Fnzu2QUH#q|%dWcP4(GDwGH{>!PV;L6H@a_<yI5K!`zAC#
zf*vi=mDfPJ?wj@@mItA4f@MPpEZ+pnh7ef36D&Ul6KvmAbysu%VA;Zw+c)8|!Pwh(
zQN@*$p{VMLJ{DEo(942ex9lU)vLQ^CZ^kM$gvs(<RCjK5?pt-|c6cPLx<`uDavjP#
z%)tKd?#hxkJ(mU8k(}1KD^uR|9(PxR^AK=%j+CJ-ORXD`!kz%g=q}rA1F&>oswmc;
zFV%vz=Zm%EA?Pvzdn|)#9Z~#XqBm0&&+N@q_a>S?RSk&cUFKc}R}%N3w&gQ}%iPP-
zY{h-NG6m{zCq6b@CO#6RqAjMz<$$`ITIXn;@Uh`q<8G?iG1#W6^Y5&6W3UaWctmmU
zs&}J%K*)v|BJQ-;whS}kPIeb-si^h5zB~{`e>xJ`7vgGzC)1H+EiDshbHmeuJ5jYE
z3X97W%n+!>y{goTrdE}jEtQtr5H!oZs__kt*Qt!Vx62mnNMiMS<*Vososx^{<{B)l
zn@f<m+ggtl>+S3#VYj71!q;XIxi9<Dx`kTfNCwiGLCs1~=F8Qv1fMRGE;}D)xr)T{
zTaF^(@8rwXuAJDuTmzEFl`q%V7}<6$a_EqrBN`CIAg-ly=U*}lOPy#u!L?<0Ctpxa
zpLDilsthbXT6kG%)_l!Z899nlO&eln`5GFN?3%Bkad9+vp!pt+C3Ln1ZVq3AH9JOn
zsOrR`zD%Q%Sk#xP=AB&>SBoKLmdhIKNMgAxQ|-A17py}Jp23dD;ir@EA9fjqS%eky
zMaXRktL2N3+YnaES7*6+vvq|Kw^aTf0k#b2hL405RkXLMszj)duco>ZqWWsAD-&4o
z2($H(AeEf~+<rndLcmHJ+AhEit-H(m%b?wNg$6&8xR<z$y{ucLm<5n?30rp{&Q*|#
zDLEC7$?){xiXLtVrscBzGCWxL+^ROG&5?j2%kt6VNLY1FzmEi|7-mHkH*gC$Ex(Mx
zw2p)|&q%RWAkyhb#cGn3*O8owmXQNu*e4pkRA4UBDZq^|S*~c}hA>$^FW?4mgHHi&
za69-U;O-s?R+AS*pMu*R)aX8SIwN@2kzi9n@GPHXSh0M!^Ep&;ZkCTv!g9R-`4lY2
z8==EE%)qMQQ=r_+C&f@LW(BR~E%``d+Dt(7d^7baIF4{yuBhW?IB#55Uxv3=pIzkw
znoi*H;3M%VG>%wWM*=00A(oaa7`fR=X^G<j+9$9$o~V5ai(Ar0x<ZW`p1NJ8Tn73U
zpF+_H+UhjuI)cPSQ$X6V-ll*wB4POyjyA42;b=VMKaQZ|mSi?Q1*8!P>qt;HE`d`x
z8q_(S+zk&zF}OoOIs#$2LX#T;VYv*y41uqFz^3{!1NIzSRVDTuu1;bdDk!;uOUQ@d
zw<T?)58-c+68RAPMzAa&gx`on?88-e9>9+e<~S`89!D@OA4~P(aybOYVSREWcnLMc
z({jc)w=`mL*_IjXTs{({VoMmp<AxAbN5q<O*BnzdV`VDJxgoli%dpH0-_I4M++YIa
zvK+It67nI84nrazg6Lq_`V7=SGFHtHB#(yZ4h~)~A420WigHlMJSiF>U>&$O4nrzO
zT6i2`w45emHgMVXAwZtt!jFLU0*pp5azo54mwlMwmp&As#bAQwiZpH@bn_v^4c0dw
zLfqhn^ECW<QW9;cYMfzMg}4#X-4(FhFrtn)WapScU@RY1wVz^zxAB#H5O3o{x?-5y
zfC|N7GiI<P^dZEZ#)dv<dSWoa@ljMQ)~<<F<%mun8OYo)7u~ceV7|Hmr+=or+g6c?
zp5=;TZm`L8nUERmHr<5O2cWJw3ysE`^GVNOAL=HcK7e!;`us>@xyXRbuz9%2klV25
zxB<H(oR*ug`^dkt8eA)7D`o@3<%&;k;GT4vhgs~^ZUW)h&fNsU5k2cj@&YhxB(U^h
z2kb@&4u(xPL2%G;x(R|ac$S+mc(QrA!j~HuKiveuanQLDapNrXG|+q?I;C{g)X*QT
zW*o6@!r&l3JrYpL8e(O+5rl(B)fKMXK(^{(ZDtuu%T0)Ub`HKEIbepHAUUFGxe1XY
znwB%<xdl{llb418&3r^i#SUT8fy3<GO{g4(@orW1rvIrcFuK9^#${+`z+Fdz-3Wlr
z7316{_%>a}Wfl$tZo=;HDR3*VVzSAB-9i29H^jMRTrHOwnIWu}cLDVYFx#aEpTM$U
zU3^mHnJs>RWvGbf2G0to5t+g9!n=U_j0Z38!s_5z_MTnARZ<3GhIm-sb>x1oDBfkt
zZMegD7v_dTi+5t~pr7_G)Qun^-if*&Lxe1seVBp9+PhFUxURhmb+5cOcA@SC?nm!L
z-H4Lqig9kZ-8l@z4A;MtX4RP@vW3@?GkUp!Kip*wW?&ij4ji6$-IHWXI~yh-jyto<
zUd(W-_AVR_S1j+q;mhLR+?x?N%e$1~2%O~#gKqHla+!-6SlPWR$bltwyZ5Gwfowa_
zI`j|Th1OF=;fjN9Yp{z#>+p#4F0{TT+DEjWZ1>)U!@-E}y-0b1uvv}}<_7JK%ihbN
z|2dMzpA2Ndo2tR#&zm&b@CiH;R_>9)K7$Yg-Zo2hZ1YW^J7Z#b6X=GP%w^7HP_?;Y
zj~hZMJRT-p=ARYSgq0Bz%bTz=Vl#LXR))&Y;g$8ID84GAms@HLT_#@!#o|X2DLha#
zVP(gQzc*oJIJ0^aRt|4hS9EiOL#)f(%iu=)k;KP?<%_qWdhjsVhN{5|QzY{vnaIT_
ztJLdy6S#)z*PFmK!e}`L0MCF5V}2xO_mef4!TZ>o;5CAec$2alF|@o1UptQHj|j=L
z5}HnAghFu|gBg6QkAM~Df@}SD4;RG<YHo;^<xTh+@m`LE4FiglUDuJsG1vsJ@$BGD
z@EResyiuWz#|u}Ga)W>S<4x-p0ke*Tbz#Xhf$0dE<xOxJL9>n|?HCQAbX?KP4G%aD
z(=Kz|_?qB!zWI0~oPG>%N6ygX27UpTA(tV*q1UZq@LE{6I*_l0RS+6aS+02HhNmvC
zLeO{)I}%j2VPWPK5IQ4rd6lXg4{u(Dpb?SF753af@8ESwO#lvvBSPi7Mv4^!s8--<
z#CY;5JiWmt=~bW_@uFPDUxr6auk@xgMBH-4FSiZ<JEy&u?fyv!WFx?qSApyeyovDT
zhUi*e<@aa^ujO^9%vcjuI2&)sUWKy}UdtK4{0UJEw-z~qXL%*6M(8ZBrh-ofLFx@=
zBbPmwZCu$DRNN5j%EPM5K)&KtSa@SuRk<n}LRxth7)C@ZXVh`qD-zgOU`+6lAeEZP
zDk!{hf2)GR8~3*=D4aG6uAt;by9Squmx1f%BS9)VQ&dm9OH^5qfKA71xt-&h6Htx<
z1(P>dpkOjgJU$Yn@+ej4aZB<bmwlLlU&sq#@&E~u7sBL$pjpomWkmzjMIQ-Lr%;~8
zCmnq$0LcU4v%EN8^o}T2d2v+?>{(nDW4RSqy|@+@rqDrR>48{Tu0Z4ip|V`YU?W0h
zopf#t1Cg@4OsWb70%dub>_JE4rkb1hQ^sHe7EoRk<#f;{rcBk93$P3|7z?lr)`T0M
zVw4|Af(96a9YJ<!sP4G&m7y-;LRXBX0$dioR}C<kxx$AJG}C4NHP9C?gv$f{^&ruS
zKE~y(bTtK+x6;)ZT;3Fid?5an7Xs!{K#S<5sqVbem8Pn3r7I1?003H=>IVMIS@1xV
zy(D5D<rGm>G0ba9RW-3POGPDoFH}hK0h>oJ0N5ib^t==`9j^?fs8Bow7A^0ARq2Hg
zdmzY_7eMUsS;r@VhGU(tO>{jN<Z3CD`M_qeWF$6VLAo|I-2;S!Ym-l8RB)rLy;*gx
z#<jPqkM1soGauOhmh8j^_Sv=N_&8v4yHHO6%(a)AlHlt|*p!?liy_BHO~=3`JFp|k
ziWgENGE6liFL`TEjX@qei(wIu$Rf#F4J{|e9xz`1NRY}w9IC_ua;-g7iJ>n;y&LEY
z)z<?=plc6x1|EhV5t7+bQ?WBs_zDvZH5EBA!bYv|0C(xyrdlT2Z%D;w=<3Ww(*dVP
zh4x|Xu9|ZLUAwF1h0b&h+5t*ycU7BEYNY|$15r*s!tPN$QmEL`^rkW$O(zB))iLzM
z-~)K_|8MPUdUn~3<M#6_&Qe-P;deK;0b&EmBCxHjf^1^g0fMWA9T@rhdDvZ5oO7l7
z>iQ@WAidM)nHiEZ<a9Tyt4v~^6F#R=%X7j{HEDOw(5|wr(uxV^)^^pMHX2)Xr<{By
z+0L2u4`In<`b-p!NyYOR22PqdUN{A7N;vRgz?~Z+MWZt3M5JJXgH4o{n6$)aGANtC
zV8;+s#a-)u%T%I4mvg2%)j4EaFelyB7|cmYcRmvZG$wf1M3Ie2%yUK=j=8D5`4urY
z+_`6V#N2f6bQw)L<+BZRlJ4|O&TEq#=tT7Sm@iy7-BA-FY~qAmQ6OPu68xM&&TUXb
zK3_FRR+;oZClsqp0I~^^?_=Rz7TOAb`<W?MWj=MMg$FX!`i18)G;X<WnLuPSGYC(Z
zcz25<-Z>XXqaNr)WtvG4bcRxuT{X}NYIPHeY(j&|B;YxrKxKglo9#5JsRgK(H*adj
z#$6kmk$$BK5jIiU_p#t8UOv%yPvnlw>3~lpn9S*b&&)xYBt9q7R0cHIlcpR*o{?_^
z9q`#}9Pu6%<5zSK@OPWAU$f_WV-gjgS;lEbe|n<Q(<I0_Q4IQ+$)QHYsG0m}l$Dz0
zDgE=8<}{QT%*enwq1RxN?3@sxGAVXWh&-4CJ7;Q8nbbO;iA1Rh4mKf6Wt8VUhM3f5
zy47(tP0F0JgS5h=%sC-mVS<Rwo~Q6G6Fpk$<3x`Z@)#4zWHUM3nQt~>$R={q$HLnz
zJfQslCr#NSdECf<8)Z6YXik~r%_nNC4G^-~QH*3Jf4f^8@wSH1r?=e=jc4|HqGa5X
zApP|4AHMzFb6&>sY1QZLwKhMO_{3i2GiCe7Ir;m){q`^4>bLUwZ~pH;{_z3(oFy6i
zAHVsz2S0*fbT%QP09rNSkN}yrrH=t9AWb|^pr$mTZ1A}>Q5*paZc^9V0JfUweE^&{
ziOXfcY=T69!PG=fQxOhY%Aq}BI&Qv6W~_p5(<TFg3M9YHs^5guXd)Lma?`nNYlpT1
zes0?Ito3u%A$5EDlafQK71;~ZzFb9}o@rmJf*9Y#Q&4Nh)+YI#+K??W$<$PSTD8Ga
zkvg?bS$jY-P4($D!IIX6Ypo#cvaa@YjA#R*q{cpjDZyRA{A8*Kekw}*O}W~dATd)$
zw4yV{^3w`hA(QSv9p`0G&aYzA)Kp?wK>=c7z^@>dF)`BD0g#x1M!teU#YEy>0ZlNa
zH|oS-Dq&Co^RQxASSpw}OeI<s0yn10sEQZYibfo;CM)t5Yit`^k>vV<F1_k(DmcoP
z2#jlPQ!YgaPX!2YDIlnjs8}kxsCNFH;b+CB)>5%SHN2loEU-2Ae3rOYE4~9un&uT`
z`YSNy70Bx4T@w(g{w0WYMUs7q;j*ICbH#_N!u4BXf~*eu>80hhZW8Uwm#G`#<;+A>
zBq2i)9G%=Kj!XS*T<Uw3?39#G;%*aZbfM&jkuknNml=y-E9AmAk((E)NeBzuG8gm~
z|1D%?&kfqV79|Q6KdP-#^<znPnyla=y1V+yq|W#$rHl9Xil|jeqM{v_D(~cr*BXa-
zx-QmojOUfb<rq&or>&7(|B5>{4DoE-MtSLtY9u<x_$5II#lBqnt|;bsDR**^heR$q
z26=FAsCDVOU6Dws8y0nMaF9E*BS(@iNBQcXNp7z*S<nUtxhrqph9s{<sXZhpr59py
zl%Y$N15C-Lr%ev9_9@%s0ADepi2=U4LQ|4C_f?Pxm52-4x@t6wgIlHVAiW}%!?#8C
z>Z^6KIJQ@xM9Ml!<zLkrN^BUS`M09R)oc-~y>Vn!6x@shTj)<7O^=>B7!X?Es1}AL
z&8a=5^|(35R+Rk^hIo=!KL;VpjJ6U~4GZMn^h_a2kc{lGv}8rcyMP2p(39uAu~cuR
zD8xg53H?z6>v=_hs<uMbo|NZ`E<19g+f|)g$Uv-uSR`XXqMU5hMq1)H0^N$KaJ!PT
zR&0VOL)-GJdmSW)6$wBkZ>q|3$pf4R7)4WUIuaZ^HKD*;8;2wm#VAUZyJJgvOB7o?
zs?0Bey!1&b%93YoQarM>JBd5xT8d0_GVtlZkZkJY{S-`*Nq={VJ28^d!|i~I@7X|I
zhp{BI@ew28n@<ijD}$e(KFAk#Sr$QrPPE(eBBoOn^~8w2*uj!)i%eP=P_1o!!VB14
zJ)cW_PuUofc8Qh=D$=`)XCaj4cGq&>fi~Y##Or{Q?IvEYwMd5pYAy1i1Th5#>Nf?>
zI=-PVE|(_a6Ff%|)`;h1iaCU@KSIu38TN`DMY2pC;rrGOXZIFN669ha$#_+rxu`Ql
zNSa*phn9fXaPc3I*kprrQFH+@kVVuv@aNv;_M{xR#p*eZrHWvAvqD&m;mF$i){Z&%
z(q5I)EH<4&zp4gXbwveLC%04=yJo%x1IDJFZwVa^>@Yax15Vj$)@SBsXzi-2#LheX
zd{>5RR6ydDOd8nBch^oV!Y7ZlZ3H8Zlb3uzbIwi7h_{ALFqurgxd~?ieL**Yxm2`O
zRhf>!>0MdWRItNZ6jnO~&PU}tLaBFdEU$pC06*xW)Exjn`qDOYlyc~npd5{wf!Kpr
zkpt-|vaBF*@2ot)5YAhOf*}+O=|dnpcgMlO=;GQOlUUIUU<PiQSi=dxu`6aCpyYEA
zGY$kyJ_Nmkf@I)Q3t^`KR41$x!zcyYf!ZXOw>A(ixdP~c$MiEaVS?HC$sTa*T@+~p
z*&7#G8DVnJw>)nGN-1A3F_0krDOl@`kE*~S5qODjx>MdTF+>UU5kw~eBEX$HhVu<7
zIp_l6G&jcbd)P(-8-y5{7aLKCTZrtaONC4r1JS=s5LURTQYOTcylAHjB2bTul4O#I
zp=etNj0hBVn&5qL@o3D#y_Ah2`5EQ;wv}uIIK;L#&>_rVTX#;tj8WMJ8%()9#I4JX
z4a2G|bd8Oa#vKsuh`cr(A|0$?Wg<3u=l_{v*G@MSR8O{>c|Yv@T=9u_7Mb}_=4!Do
z(y>2b+R+3Nq{T>P=5S0u;JD8p{qv1npFiy5{;&FV;xHSA%pqLoSK=^NiC5wfsYNCZ
znMHZ!4f83y@`ibe@`n7}C~wHG&CMI~ZG7bo^ZDPrVLYf;+7LMmr41F#Gi}H<|D85u
zuJNV~kw>^`!^~+>1<&Nzy|aeM<wVwy-<o&U5VrwAf@S_I+NP`_cSDpl9Nd?<Swrq1
zAZr+TM0f=^Yq*qJWY%yhv&gjJ_<7neBZ}vpHdJ<rX~UpwWX_QL3^!+}yi&)=n<Q_Q
zGgNv<Im52(9!9fO<pj@FOO}h=l;PG1Oc^qva8rg#r9uJT>Qq`(NyDzx9tN}WHB{2D
z(zm`z!<`@Bn=`z5Mdl3k0F*P#U4xr3)bOv6X*4c~Oc<J|hL|uk3Bf60=*l26Uuak}
zZ@%zm_Rha6nW=ms>Qay{jFjR#TlhpuF@M2ip^~^t7Q(~7`9f~T+;rjKQg`!(tea83
z(7BnfoT0RMkTX0vMf#ktoT0{>IYWdLuasd|GLYixu^pKgLbgRaf3J+8Wbxh^LnH+<
zWtbbt&pTsCm-dx0lq8}uhRjjC6NU&yze^b6Qa549jO9CFh*ZW+7!KvF-U&lq>zy#n
ztjIfIi0sWx4kG#cU3M_r@J<fm;;-Z&5+Co}Aa-=WOAg{^N)F=il^kT+@0}Y&o0J@+
z1oh1ga)jThL0su(2Bq2XN)1Y3_@)Mxlf9`yiD%x-U{i+ZrUo^{N)0MRR(cQ`i8nbI
zGNlt5qP2*R^=1a8=zTMTN(kS?;1#TICks}o3$NUu#8+=_P|4thp%pS1xj_i|GGF-8
z->t~#DLE*~T9f9bW)x{MBJr0`>ShO}vUszDSM-=;D}K2~S1NLU7?_(Oq)INu`J`-#
z{NR>ziR|F>l5kXdP?D-j5Av0Z?4U%0l^iVG7E*T5={hhwC|0DK9lY9+S40lM2Q!4?
zsa1whJkZJziV~6;Lb;ZYGKAW|zga?wYh7V0q!^SWR66P=2{QwDg_V%YK!Q+`M@kYd
z(Vi<wxVT_tk}w*f1YuWBkqJU^>M}tnB3mU0r<Bo{Ae^FjMS_r`L`)AV*{SrPvh6oL
z$aU?e2SuyP^q{JTl_1Ot`tuBx9~8@^@`G0jh514H2{%6|KkeoRFQ-5AgOT~2?M-E`
z+@Lfelp5scL#e?loWRteRK=7V6k#!PgIAS@xj_|c-Q1w)bD0|yS+$abgE<#u2w%j_
z%nyp5RS7~8q%uFKEe|9JpGXIa${7hl(dsHe$W)~AgCd%a{9prXshE02mCo#7p@zXt
z4&r4|a?q41Ms^SspWoi;!ApIb=|K@sD?KP)_npN@n*iaP9Tc&-vV$sQQ+AMrB}xv;
zQF|u`^Cveoh!llVgQ_BAYLHxX&v&Uo5|?Fa5S(N;Gsw*0%?vVEcr%0KExVaP(z|UD
zY>}Ud*}<PD2g#FglY`&BOAL~!=_Ur5D!hq75-8!j<0kqNB?kAOCI-b+#N?outzOAN
zU5E)nB_>}9Lh@{6f)Jyk1mRYdw^D@m^AzEw*kFoKgmteJVWf0^`gT)<<P5kuLQ)Sf
zM@XIoWC$}|sPy3alk}hp{%>~h7Tq&D$P8i*<@2s4XNFMKq{<Mg6igYyNX@>ogDQ1p
zc2LEJ$_|p&PRYS{QEem#;m$p;<e&<_l^j%gD073Xbz^Q2CCm=5$Xi$XP^m#y!`*s5
zmJTvG$i$$7$?$n6231AIyr6RL$_t8j1bIORt7VjY-P$8oFfcF3teMh+bmN&8bnJj2
zCzypRxAMcXT;yj-K|x4KC|dZoF)6rJJEW|j>VlLN<cC&S!J8%|?tBOvsI;KcbuF>p
zUEt}=3(|?dc|lha5Fed4KACwz<x7<pWLE0t1yuplLAz}byH!?DV4Is4<Ywp13o;**
zxxvq8=Cgo)`<%EAobdC<9Q70B|H|B8K|U}yKE1v{hQP^cSp+!9tTIePX26UUHDL2M
ztGHg`I61da%zV?4V9GH`ggQ{RMDD}eKL!9B38-ZZ<V477+scWMRg#lQSA0ty@K}yE
zz(}_Ek#RsbZE^KUu(d6EfPiBggh7FCvPBOCc<y7!bOd-qZP9)5`OdmB4NE96zMDpx
zxa8`8!XU`!>4elkLDz2*1O;2aX)6l}8B5}eCoPf40(acE0M);bm<nD5l{$VN|8DUo
zq9M?_+TunA0BI&hIp~AG5U9Y;N@~<I>1<RQ{RX~&gU%?55?;AzU~Q>13U|y>)d%V8
zm^O<u)OQ@@oJM7{37G(r|1cE%B5|CHQ3N>tZ~i;WHV$mol^~Bsa~(#h$1%ja0Pu({
z>ZC+6&K4a+kPn-P=irH*3_H^2EaDRF9C(gjN%*YclF;ZYOWz6iT{t6O(X5}bMdS@C
zY)q_kD8ey`jG|7*q%oTN%THKv+ej;GHx%pdYil4cehla<R{SOCO9teDLN544&ONR=
z8#&~at4>xnnMm!3@Cnp%HggErjIII<fA=Q<hF?t92W|H`MBoU803%sl>I1|vE;+N+
zCI5~FN{kdA=I6ElfnqSJk?!?IRp0Fr^Z+w=Zhqo+%-zWaWCPhwtx|k01DIWK$=pv#
zPkQG!?Xk%P1$BBh`RPTRVL?h4|3c3fUuT;v?c0R(O35^epiNYB$Z}gS%>mwUH+xWc
zXk?yyzGbnZ3DStz$3!xRl1H0M8%VKuP5R;+?4KXYx7bdKtt4c{LCbHGt3(BLKen4-
z8Q6fzt%8EmE-9NHOKf5Z?EKoaLUtXc&nB(YlfTQpak;42C9tW)KH@@y)@g;DfJyJP
zmdftk?XbKJwlN?nU_oP7Atzu05LCzsSkl-%Y03UEPg8S0!$f0Ok*PWs-Uh{D*lLM!
z!hC&g%VEMw{Io)I;*I!69VakZwTveY*k8D3QcJCn88ETo9ZPmeIP$`cNGYh+teZCJ
zr&eSn-+P8pGKOnnZ#a4G9+<MF$XC>|;(%wPjB^%^8p=3l(W8RG+-qMFRh+YEWKn`S
z=wsB7MX@0eIz$I-C{V1(2^wyknX=bjC$_n42u=?102|C9*8=itLp!khCGFB0n`f`>
z(t_ejaMPXRY=oSJN<4rF>MGO(-nAN8`Zcr#%z|g+*q$_HYqd88set!>Z7%yZmhOf6
z%Aw++nvus)X$I5+Y@l?grdYst)g$m`mEfzD{_N0_kmM9Lv?PG!!p7i*QG+RNyUM!g
z0e>NOoZ}ELHugA8G4-)z>*x<uFml+CW?BW#*TijClhwn7MXZnuFz&llhy|FK?P_He
z*l4;toLlkR)jGc`p+PhwYP%XtCN{KL2d<O%b~%bL2d;<SR6QURU~)gG*36jM(7eTd
zu}LtsVi&}eT)q4BRX1h<=BOHP%WZqy8J_NIBOjjat3-%XQ3=$_sC00OSI$P2SYY4A
zBGX$F&VA4Uyp89@tg8qDk^{$bi<6>57gT`syon93*8F#Xs45f%j7)bGiUKC4yPE7k
zCZ@Z};%H`LKCc(6qotWzQ61g2mkyl)>paTFtA?b(zp}2yrJ<a&tD33hDa1Y?Ozpxc
z2t;8I4zn{$cS%S0g{Xk1E6LRg&L`^`csv!fP$o*f%6e;2>QyEYM5$MyIbhmoj0<Id
zrtaS3h<8Q}C<yh=aTc3hv`1%Y88^hSqheBAt%<fZiLO>C6<8k{1te0s=rJpcsb4sf
z8O3P4$i&E^Pz&{B*1HB}W&}sI)eBA0ryeQ;#HOSru_}DP@LhY;<UtXIQB3t1^8M3-
z!Mf;9089>>kPoR$@PvssMgS_T;H%t@gN+FE!e$^%@EBS5YHakHNcSpmh1QE6Dm+|p
z?o|-n+1+2M*jF)<?$zYUGjZ-!<f(zzVR5xIR%?`_JYiw~5Q$1-wMGN1ZTy`jfQ%U`
zx?s{ueU}#U3UFYtyIpe>tTAk;7&~iR2A+!XwZ>FL#WOJJt{zLam9P_n=bHSA4z8D|
zY=j|RrDnQ0D<6qjLcA&7zKR#|W62I?a4D2$?eJEm!CE0NY}(eU5Ggnou!&Zn>MdaK
zwU6&mQt(xqraWt{o2Gpq7hJ`@478NfJm<SL1qxUbtjTqN-~bR=4@}wETj>dhRjhoq
zuQ=im!D9_VzH^kZoGAG!s79>`f5Sp*aq?BD5LoNF35b7Q;4tFHRR4%|-K5D{vF@8R
zSu4H`k4coZ;tOI8!9veVa3JC2irTLNO=3;DR284LgHz+3!A5eCYx#jRlKoZ45*R))
z=OfrLjm7_WEG<vsIBX%}IN%6g8~;5&f+GK`@BxflqV?k;n0Wsx*mDiMe-(%rYr-m2
zY%-ac|0?v~t!aTty#te`YlW170bue}Fan#H04rF7j|D}-nAtBtUyk3qPB_Yjwd}y@
zGZ6z;$Qu|~04uhNOf-OXWGI>}fDbGQ0MsHg2=_B}2#&K@{VJHBE%DcRp%I6?2qv!>
z{VEC;kA=-epjqWV3<jEYp$8dez95VUGpkk=#0VA=uN5JL)k!E*4PgVT%29xY+oS|r
z!PIS1f~^oXFv`9@VS0fl@uO_N5UtqIv&twX_ZO`Wy>p;YGfBTzC>xlhUn|19cd<93
z*s5SAqC~4I!>b4+jS{dGNURsM6V&LpVjPZhWgzoZXc?GD2ahHDq_t(_d=`+tg6{oT
zcqazGsu`+~GcYj`R=~nuNYmIZJ;&@e+~rV{&Ej-;%aW6=8T(t!EM|q6!5gev1z*j9
znJ7^=@dnn|(KS_OR^&B~1x-Qf<5=(nkRP!k0{uF{H$>z^%`y@bo!~LV_(E>>9LGXX
zl%7b9gC|UlzlkmtZi3X=18U1MfB3$Vnyn~jITj>dk7<Shj{~|0$HE&U7%t>PfGolV
z^*(hHk*n1rbrDPigB2BnMjTs(EP|<`wNA#u#q<E+LyMNM&b%szA3Hlmgcwk~0KoWx
zDPhS3vsBdn91Hu6kho|`L9WwMqV`Ek^yv~HAS8|g+=_In6(vF;>|rVZsgvPw(JC|T
zVxN)GH4zk6q<oEvwKY``4mw)hgH!#YVZa0~NN{Eyz&T{!FrCZbRZ)NXLS3UW^kczM
zJ_xxjbH@=ohNw5$9iO!1s4JTZT$D+?wn8G|1?|S>4zi_ZfnC_&0ej&&o;auLDhnr(
zQUbHRD0{i0bINysa>ZB$T|o<AqBE?EEE!lq79!tL6=h(X#kA#Kfw?;tc9Cosc-#<4
zFcw=sVanDrSXn*!F#vz(Jig%eOc}4u^<<$Ib4k#)rbxotN?br@X>EBMA$PDSO<RGg
z0cQSzDKO?6o&(ek)>cviTYGCO!HHtN1GJApc@myq5_^x8D3zz)1RoQvLofpQs&mZN
zuJkDu2@Y#2B7^~N7z7TM_z6`9Ain_m25W0mvqIWy1!G~&4ck{$0JePBR(OG3;Y&wS
zQ>x&J@&R^nqb<b5*4Vy&R~TS}dqKta9B0MBxMV3Aey*)=K2#5ubZt)|LpD&`4_45?
zOG*Op)sk#&g|5M?zM*FO^Z|#o+#=572~##vA8=?EtgR0?R11y;7tRB`AO?MnCDGbr
z%D3oNR<w9GIXzRf;B$<FY}Va1cyYVvglv`EdgvA0T8)uZFu31fqx5M<`RkJKY=vII
zlJIOb7HVvb85ZUxy1@!L#A8t%2~OhOV|8CFtgDb+L><WkQ}j^q=!$yXrRuv1Zi3~S
zjF--aIeu`5-GUU*i!Il8IQd?d>nn_MjupzX)gW!YRJwfYUKHkoQ0-Obk~D0~mCgfG
z+p}Ez1i)V}=RN^yOO|V&0KoQR;V&jm;hX`h&2nuMK-6HVw7Pm>!A%~awU~&>l=Fmv
zRXQb`&o3tA2bRl?4*b!(WG6o*$HEVWSJdoq%6VRaq(B+Etso7o&>}b`KO_YLxxf;)
zMFre*sUW<j7Qwm%K+qys<QBXIM`HUurWu4q#$RO9^)-a{zyipsqE28*G`2cuRF^B$
z@0>4kx?e;{ELs}bT-6ofsXfPp_D&4-WluT}e+kA~!3VNT={wLht$aPQkLkB9Q4H1u
z4K5K3R`6af5e!yH5-bxmpe8JLiD<B59xUUR6e0ynJcAXqoJ%}|PX%}96477{de0@*
z*$M*CV1>e+E>D#1l;0hdDO61Ug`(J+A_Yq_v=!RbODuyGsJvy8&Z!VGSfU!NsPR~~
zc<=mY{EhzIs<x0YSf=TY^>B$$uwv0%lBKO!SeImJD<upTNCj(37%Wi=R?vAJ3+@C7
zgC!Z-3TWc7@Qn```7*h?kVjwEUngbrG{f=1I+kopW8?Hu&2QeKplsd!a{$j3^uCJ<
zuoe8j$50c8T0s)LgcGbNm06}u_Jrgt;RKIi<0K%;PgP%zN>v93Mn$eEJd<N#P2a#X
zF84w+4lkKlc7bzq!~YZfuY$9Ag<Ncu5}vNDrK!2o_gj~H48EW6eidcwYw?4a82q*F
zUOZg9wKk5TbCQOw;IKXx-X^!K)>5#$?TJI)HT}r7G$R4<U5o!7JzLsgLrqjI`!1zf
zd!44jUuE^zb$GU;)N9|T>Zt3=H}QcjtGG6n-EhR?knfwLxNzSG9fw+AH^wY%d|@`~
z|L6=MOb7!<W3z91)*D1v*CX02Y?DjW5T=CbGRbADSn?1i&nmfF?-eZ)1#?R>mo%}O
zw4&X@5w`+r$XAJLL!1{Tl*l0x3=_%hSO?3qnuzkITHa7u2X~{P%H-D1HgIc&1yyM!
zL4d*3$G&w8u;0R078r`VswKSp#qie(GI?P`As>_u!h|*qyeF=b$B6x3MZK*ImjBWF
zXb?9D3!6Ss=i79li9$*FA+3OVJ#4)EMAI+t-{ezhYWZTz8=DYP=O2Sg1EGTuCJxKu
zQ>eQ5;&V{#D5Vg>hO4t`xvGE0-dr|9Lk*;SkXG=E#8aH|W4yn_54FOX87w=k<h+#s
z(ZFwXDHflwWjE|j14lPZ1awH}eOFh#vm00Vz9BLAvC$1_kV*&>%BD9<wCQ%VTJrET
z{)uB&U(@Yq5K0LXnHUS+Ub!L-1rDtBeqcifRkB%G&?_dj28Dz$k&3aRgC;&mh$I{v
z4$(Og5JG7tOn7dPqe)Y4MYW1!-o3HITnNDP5*EBAwXwhHMm}lF=_+@nr78m{F=5#}
zks~m8c{v{qS^l))mIK#PkvR4bl3f#*pO`<^6U@{A26|V|S58=C=B;5*<Ct)Wk!z~#
zhJHfWK(@K^2vxrjPzV#pa<OYUgiqSgHI+JpH}RNo_<eOhL=?i39eo<MjKY>bvftw*
zzLUmI6upziKJe@Jxsc~EN6^^|6g=1OsRdv{7mDTt1bD*626*;ksZ<@CaA88%Hu(p(
z#t~4VuyG(+t-Vy~AG?HMU=ubboa!7}sw~8%E(gNK8z{%;u$pF{<@vP63BAa2*$R8O
zRPUY}q(P@ZzJtOZih}^MYhmKmE2$|(#1Mssag3LuRd&a42)c#!x-fdO-ejz~cC1Us
z+H&ns8AEHFy-TbJQ6C#D5LnV7sSqZ%sIv*#;(_bxTigaF7C611wB^iN{1!u0AuJq6
z&SaGw98w6p7+q7aaW1RupaH)SCbnW`S1!{m**a8v(148y6WcI3nxeRX>Oz=!zlBaq
zDy%_xA#A+kVyF2Thf-s(Ww3{qhmJ2zGxo0PZpPl}yWVn|U(yW#R>H*Iy{I|ZJ7e$i
zD$br2y-kju6&8md6P{FIH^>vQ^r3IT+;Is%=qOLnM6^w>QS}84qMc#F>}{Nule={-
zu}Q%-j0ZvhQ}Pez{Xt9~CX#>@5{hv0LZu-rym~!gcvbU%j@j_c3mikP%BnLsrkL;4
zv_FRU{Dp}Z<`kUrw>zewgzOvOXko&o@TmzCFV(*VPYRpZu}-O!pmn;<lC}ru$@A^S
zu+rf+UqWUmG#pbL(qmTrZi8Y&n7F!hPVlKY-#MEn=Ql8aVZl4n<K`p(WVChJULevC
zCXNps;VD16lh<R)&+c%Jr+n&8=lC+mbWS~i_gl9-#Al+L+Qbd827qUnzyM<$YWdxr
z;qAmnxEmtCS#^5`w-mDvb{TX|AL~vJdTK&;=SPB2|6`hYjBjP97cIDd>vW=p_ix=9
z*$Cg?AWeNtI0WI1KGvNxnY#83BG^x|aiawr)H#=eM@%_LPPD;@cW7>p!jHVF1CA|M
zJ4q@W(@X<Ke9)_g=>0L^6F-=zXoEiW;QSwSsa0oiOfe@fS<t9lT~ut)1{Z;$kN3bL
zFfPMS!^0bf!-yV&b%@u_V0vf)7>ykfY4%_&eaVUv^!}s`Pi`=t9t(%r53LEn*M}(|
z+#svem~#6^$HY}Z!7({cWCOSgjEO@$qD!7MGLTk5!6iHz<M%uZ9pi4nG2szir++Zo
zR_Q?-h_+RF&<0)e(Q$G5<wIZhvGR}uM#p?~9HI|eN5;x7=rcc--YR|62P5hsdhUVn
zc{Chh+__{7M$V(&ai?28ux1Q8<wI-6z*Vqb4Eoyx3&GO{C;pJ<J~;6QJomxa`9)d9
z*m*#DGi})kIqrk8bJt=p7&~_^27|G47n@p}C6CdKNx!=5Gd~$ScRA^kuJ(&Y3oBgM
zmd=c6rz(Lq>1(S_piR#6?&3k4nCPktXp^CH=OOy0rC>62?zxfhgbDo>&l3-MbGp^t
zaELx=6_^d5hpu%1Wol`{WyiN53!8bsF(e|tO$N+e-ugsv+?70=bg3nD-zHt^%Q`mc
zQFraAx0(KP*Cd?upF8)@+vKF9mQ0%~kFpO>o1An&@3+ZVSn&O0!hlJ8U@{a=8nk#p
zC*om&`rBkcEYbVJX@<^0OJJs>3|x0SL3+wvKKK;tn$l~No^sb`e$rd+g0{5Du$Z{~
zV;MXV-x!p?9up3;BZY;gZ89S6%B@X?#FE@;aFfHtmq6Tb%EHZzh($bn4B6oqSsXp@
zw$)*J-t^Re3i7w?aU<CqeDS8qefi-uxff?`yLq^UY1{OfUyO&zSclT-F!17)oOWEL
z7K2?P_S>SLEy#XbWNT}ZVOVsu4;|hU$6&hCtX!m(Ym`x084U}9A6$1ilEUD(#c()4
z_zj_JEuv*<OH_RP5HG~c;^KSSqEFqfR7U({@Enrr33q=?7%_Zd55>Tf$GQevJTw#x
zdN1$aV$j><j3=GYlQz7P3sG-Vki8i6Hig-XL2qOFd@Y7F0@$}@dC0Lhc23{kMbG=i
zMQGf^5X`<U`rg9Xx5e4q<k~OJ<|fa6xjM-2^g`@QWPOqpZm=KnC+MBN(#u7ys8970
zk>X`djN2;*x9E5iU4JZ*91PPXM9jrR^gL~Gzo|(LWWo6s%pOFFPukD`<7BQ{1`N}=
z@@sCK&1849!YvG;@0&5MCj7n`<LWBU-a__8vmM+jPuM0b;*G?sV-4?f)l@c4<%)3J
zKw1|THi(nCG9b5}M{EouX5r}@^1xxD3u}y`FK?xZ-BM{YLli9x{jq?yQee4e45b5D
ze-1%^$qP%*Mt-+3Vy^JJKkL-bNHa~$n%XflM$KYiIwtgE5RlfOj}^9wALYfhRv0&;
zDr0zK_)W2%=f$g8wR{*|>8j<!(v`l{p2mp0LfHFQa++3o0!H7u$`df-Tif*_b7iQP
zBh?s{SEl8S3xi<w%@~6VGT)3bcy0I5F$k|(Ka4(fl`NLghpw9S1{b<YH?J9eXaVY*
z(T9F9nqmS=5Tu!yP*tpVh)D}i%;)0_m5UN@o}qHl4x2MnE?Ws4=LS^K4%?MQ(hi%`
zi@rRo4kx<YFT2x=7NWj6J!wJeo70oNT1`$*`fLj3rMUSls>9}tsf+gAoU24p5bqgQ
z7bAO1bH>%;gLQ`0R~pK>3nd_Zb4Jxg+<wgwS{EhdouM@u7{i1P(tCjHZCDuf`N(75
zjb8obsC9bvMS5MHYX|Z4Pgu}9B?X<qb<wt)Gq@HhWOK&WWpd0BT1#o6IrqhgrEkt{
zv7&{@8Gk2n1uumT(`WIOM;vbk0|49~13Jq^=xNSqK-87TlvBAV7;!EhMZt)3@d$K4
zwup;I(bk|NR)6vRGF~rqSe)^CVitHQbXY!&Gh!D|zq#ijd>CgeP#WO=$ArE#jV0oN
z7u_&@f5GgVV{HkT{gVbXTYCV`m8CEk*(VY&+~qrL!*~EiABN3PoYck}uDWpa4O--f
z>=+G%Uip@4(9<AleoSaG&^O02aXfJnUiMwVnXCn7gHh&1tQ?HU+P&YoUAm=CbSz1s
z495aOYJ0n4*;Ieug5x)c!|$!Fd(xwB?F8(O4ha<801AI`JO`oa-daBrNuC057=;l>
zybbWvhZLGU${D{m7mhu$wem0aKx;3b^F%|g$m9Xphk+!}IqA0;3Xdh*#(9nF?M-Lm
zX}IYYKL1#9crR!5!T>A#PklNi6gCPQKPDVzb0xVK^$S~CQ4JLid&^<Ku<zZKSHiP-
zk!3qNpd{aRyknY!S+}tX#DBt)!>ODeUbeU5-p0e%?mXVwj|E4EDEGzGz0m>9Sj>$L
zOj^V2*#f0?)UNE!ExVqjEn6V9j`Eki#S4uRnJwhnvE(euN&TcLiN<qI=OZn;FQ+PL
zehX)6(S2+5PjI!4#c2ba-?4mc7d>+6K}w$g+C@?h@8y`1l-zmKm^#AXcdXId#jIU0
znVj`7&oN~)q<@D>tV@61vs!BlmmfstJ5It;E-}u~zn2+Dpl~i^SeK$+Nr!s7IHpUw
z)1X*?V6xO)Wb-H5I`yP5;l$k8vubWr^ydjnJaLz9A*$~-p>)R(Pgk(HUM!B-9c*O1
z)gD1q4di}@$Fqf&>u`%U!E!x4r|skR(7+<!bzcW*yi^Ud{BaBJ-%%mC0r-E?G;tPh
z?s!6%jvhSPPPf089b%Or(Jq^PY`XPEpCG7+veE5gS<k}KEpd=u$cx|T&vsO(LIo3+
zm@bzYAC<0~g#gDe;}ChzV^}z6=qiqL@DA0y3uwPV0RFMyD3SqNH31!}9oxxJjw0SI
zz2Y8)zHh>QL@?VWAly+Nyq%x-j!NV$z<;kjj@V92W&!PbsvADvDS>9}yoIyti2XKU
zc0Eh0x6u9_l;}HQciFo1@V1HU997&~z`Kr!bqjabBc|O1-92H5wS)x#9l`NSrT`K2
zTe>v8+pQ9Srzea1RtZ2yw7$)B?}<)mwWteyfFwXgMcx+b|Cq81(nwg*1AgE;iu$){
zH9_J3PFURoQ+7ei2~r+gusR8=YBj0p?(VFmiowd2bKBJ2bLy)wpeN%&SSF6M{X;#9
zAa0xZ=BuLz(jCZj(MDB32Rrgx1Y)Bh+`{Xvq)2SOh{$hklVmM&U|TBMJ=iGDF|OH4
zdPtkq1jmvCDOJoyfr>n;7(-3>lnC9%GWw8}u)H1IQGx3^r0kC+Up?e6Us@Keu}wwI
z<Q(K4T}Q5T8}s-bwDUVE270Df_uAYo>&U@wRSa|_YPV2z9m(7+OkD@T%Fgs-UTD09
zHbCLB$qL*d1$GQr<1<Me>by9NIDCsIxF?;=Td;Scv8I8WXzUgA0AcAC8SpV>YYn$r
z@i*_XAnBp`iroEPD%t7a*x6zPK9=l|WHhJ*vUJ~c*EcwUpWbo-*n-n_Y&LAt0v|)i
zIegI!qc4x3p-6CxD!8{4E#|x8=+c!jhPun5JJ1{*n)*_MIf>dQ=>jh~2q0fN7Ty#d
z@EUqkfWJH@zAA8m*U(FPyurPOUeS#X4jkpf5_Yfm5{LOB^^)!CILJ2X6AwY)W5Mr3
z(jvv09~fedxe_kez}sT>?bzkptLnO#vrClXy<?7o%(p|?bBoTmCwKoAn{UU?<QBN@
zIodCI^D7<=cU1(vM-ApogekdQ?85FTotF+8mksRPG1z>I&~yZZQ{QM%w|^`+iU&3Q
z4t#`%FBxluhoa^UQJRt`;c51CP6dv8IyS5~z;Wj|8=@)LF)xUXJBF0UVSf#apOj{=
z_zg95(ubT&&k#Q3oO*_EA?N)X0wb_Rp4*{%v6DRaNb1DjY$-xK5$E;}sra{e55hVD
z;ySb;_C%7aC$-`h1#XA<;GRQH7dRSsfZxthwp5ZZV0GL=zV(q>;dnL!g3VhjxE*Yg
z$HM!<K@>0Uv1IEzj<V%KvmaBupOaGz;<<Y^-MVG>nr__Cy+#s7=@1E8*MXtgQy<yU
zL)si~0bn^>Ai85opAsOtW617k4nmV;PfB)=^eAV&H^KWTIaDbk2~l?}(W9cVMtn#f
z++)bcQJ8Y=BhH9_%ng@4^qB>8YQLnK5FSFnq$dPxkIj@+2kGk``p$wEb`SZ~;EsLE
zzauytuGbz|vJE6$2iR;6eS3#dGb#>p;DvyL9Mp46IE<z$oF0h!2Jx>)Eh<~eIX>VX
z4!dtWJjB4l^=RB%rV7rXfN)oVYU#e`<1_SmO@869;HDeTL7&%w0C31@20-!Ig2nZO
zG47%7EufCaf;&%yfLBCo!t)%eo<F9%Owmc%B?+=mIGQBg?UMptLvi9n)CY{*Iqo<I
zPY;5kd&si}NAye4Yo=$qg^%k%u<pT(TL;PY7N>3p5%vx|+!6IUvtkI*ek}R2$(g3`
z*Pt(*yxm&_x*bc}9(e~yTI?ZTdLo<~M7MX)iSHp9svsQSqw2PZ=5on<V9K^Dex8Wu
zM4;OzmCxi;Pfof*v|*o|bqa?kXI;Tjv`&P$J-$*~Y`C4Gmb>fw3{Lqi^4kv9`Yj;a
zu|(@$vTF1NJErpV_?s^RJi*SXEJZa<<)GC+vTP{EI)-crzSlt2Z!y{S^>N6+H`{^c
z-x5DRmRuV;XB{Nuch{_2c=1Iy+aaL$QiFrU!Lz%j9sH)<HSJc0SzWUZ6%Zc_j$(!A
zL!YmehrA;Ex-K7f!Hts?Q%_%V3)R*a_K>$wZ5_oRo1nJ7a%u?H)=^ZlyS~P#J2@7<
zqNq;ULbdgUQ0q$I!IR#irS0&xcY2@?Ownd0r#nPHwrFTOWI=XsIEpt|G_*aVhvz%3
zJ%n4rw{?UdTg0?SS}z-;T=T+S<`z(`FDU($*IC&-MYm96*`%565x(uV^%X;ew?!k{
zQ8{%iyl(zGuZii<Hm^ys#+O(iBBSptr?Jh|A%sFr(-3uI&jv89BNX1krFE2_?Z&AX
ziafh%B0{ofH|<DwsQT=t@D|EHFDXMnbdCjmMm}JZNBEc!7PYH6h<tui3M#4rUy_KZ
z7~CL6J`N3d5{?N|0bB}O$hD3X$tG~EXA)(%sT+YUc?-(cQ3|;QWb0Wfxtknq!`2$X
zZ5_lAyA8edktW*WkL@V<++vLFprAMw_8_y_n}o1WnBp~;@*{k`*3~*Vd&H}CFl6ke
zFQq|fYzx5FL9DUG5Zi-!V~ZZPquO<Y9=4+%b~h1BcVzc=<M$K^z_%_X)GZay8eBjk
z*`6?EADNCeivvD<xO{@Ab!0fV&}qkV90=jljv-qwJxr=<D%)(>jspSgk-p5vivaeR
zqV)=hAuYCvIJ<h8@|`XJIscVe{+9|T+&+TOjv?MRfz6I3np&k=2@0HNSABoMlCvv|
zJ$n-AY~j&5l*@MIG>3B8uC7cAis4_HppICsDzoJ^kMeOK<-Y}T>khwW1LW3oUtx<6
z_84N75`L{arl$B{dvXOpiu8dc+s2PKs0nt}$J_fk%D?iS(k;#J;j^oPVW?<+EI5jn
zsOkd@I)+_`h7_|c3%MVd9H-&^^chFI33lJ=z)?Q!tDZXZQkzVz9i&%VV6&dQSX&B&
z9c)^=>dOmVvYoK92c~%Ct72cEOhT<SjxGMi!gYNGTpP{yHtt%icqrOJf#B{|ywDcc
zV4-+$DZ#D9rBGZ8v^cbQaEIdVTHK1u7uxr|_r3pnzujMwooD3CoHM(dJ<se6;!*kY
z*71Fuyg;g*sUVT7l3fJ8nIf@{9$-yzQ@c9Ai_c0&n5WzIH5(3J<@3|zS0+Y^6`>VH
zRU^Vy(tOkUQ4Tgu@-y5{s+_e0k>9ZxFw{~ih)~4^s9E%Ua;csdT*@ghKAUV>4miku
z#pC+fjZPxB>+Ton-4_t$jn(o>-QkmnowgVXv-+hSm9a1cGtuee8U<}(o~{~g?d#5W
zOHAHhq+M*t24>=^v9W!DtD&~?u-7ujbCTpN%L`>@Atk7Gpy4jc&tV1=jRY2^@Wb|y
z`mI%5-g1MBBfP8jVuBleMB}wCgsZ9S*LxDdyV+{|3|%!0{MUoWaRya-C|TvWAGJdI
zr$~E?4}PWb07uT&?RbeoG>C_T$EMh4tb!+|NUMsaZEeWBw>52cF_8}<Zh=ybp0Q^8
z*=nLF-3wej81ss89P)lHz(N`&Wx}kwNJfiLbpz_?JW$pw_CWdb)X8D35&_(|Rz=aa
zEe$L!4K2qfxliR&E!W(+*LfAga`X$(1G{Rb-pHGzYB3;3G`lWyaRNk{T()9*L3+er
zx*QC})IRqS<vRoQ70P3lc*s<3GA;2^rz9qQPCnh^C`4T@G`IxwHGSKkm&*6d`Snwx
zHn3Q}rN+;GQou}g^c#a~oblwh;vrno*cG0!uJlxM<PnfO{wMz4Zv*^^k%-GcGHV+s
z{^KVz_{x!$7YK4x<#exp@bNN;XFgo!5KkM&8e`I8l(}R&y*cJVD?b%l$hmJldOXxl
z<&j3q4ZnXhLI)JEZ%n>?L)CG23?)s*4&y7U5sa}yZUwP3%s`_L`k>}xEl9#;BUc+m
zT&9e!FJX9J#!V#qMrB2X)?fqFnl(WqYmrIW#nq9WE;SRCwzn?R3QsQVtoJ*+`5MnD
z?G;B^Y)>=6H2YhAa6;}iH?#aM^vkrKAhmy|sS2e!eCCAFbe@h}(1b05^*gpLi#n91
z7=79VZmo*BpKnE;j-*TDg{(2o(y&KFNZZ1S9VLd*=4cj?YVfU61dptcrH0u>W)x((
z$!Kh$<cmG&XMs;G5~fBY8JWiWMpi=&I@cJpcDpqKnb{gnJUH}s-y(Y=?Ca`O=(l3p
zP)5TCZr&nm)=W6Y<K{I3GtD>5K2f`LA~M;b>iJ`j@~P9Wl#o0b8<?vWlbG*ME9roy
zC!=#)*063?VQ=$sy>T#d*FC%Rs(9&POLj0@zLt%(@D1@L*Lk6ZY?2rnl^J#}enxph
zeJ%)Xh2uP{Nl4CqD?5@fzEjAwF^VyAP;XnBdeO>#5^9fQWVy&ku`tfROZ^>W-u>|x
zm1(0ST>^GBpStb3)YlKM=pkB#y-=!T?C*Sl7aQ!hSMdzk*qsRBX8Rvnepz{7*&7Ta
zG9aQAP3eEGin&BY=ilqbX(d8C#Q>v`>CH*#q{Xq?Wu6XpknlfgSuT10ZCHS?nuSMI
z<`VF=i!h(@v}-P6fA-SC@uh+bkYDhTIvGTx%ZKf<-JsnO**q%UMF4)6LtM>`+J3=5
z;7+Vv2OgBZ>HYw@Bj3zYWcI1T(Ty@+`M!!0X|vHa_g#_4f%AK<ok(R!{xy5mg2QxB
z{-<E@t=NzPYz!Kn9KmfTQQ03rYggqAH8^$XdgP<yZ5s`CMx2qGn5pY|0fkPK8(&G9
z?ZCO|8n2En^f1kDg`YfmysU4i2GTtpBI&fk;3I6NY`3aXWB8m&EpowoTOVWct8?fN
zokv%Ou_*)`oY{NRDiM3Q`0WPq*V^WVat09xxW1JLYvH&|rj4H54iYFKZWCqjm@^B%
zBjE1A2q*9UDg1L&ZU|ZASy4jm)F#?#?_7!<CDEI92=e+#m;Y;Q-ZQ(AHnIF&z$j^s
zo3pyA>~@OarAu2h^%pZFN&-H}sy`ATH~%HMPdi}<ZF=dJTNL9Y+R->}rWKX5OAZ8&
z=u`}#xs{zoS!lDNR8N4shSfy;$=I!z%#>)?s1{=jjjuM<8A2<c>)WunUWYqpw6ZA|
za?W})2dzp*mf#n1)zL?&0|}L0nUaDew);^FDXAfP(RDG3mg%8&=!v^oKMBb_StgN$
z%$tZ`Ky}(C>khoGVA+wB(TtF+d9?4MVx&|ZDP>g{&R=@icW0qY$=LUNWkcJo&A7Ym
zLPz$Xc!A7PR0H@(WqD^g8g!W+Z$c_@fZ_&rjO<~th~s-NsgUs=L;kY9-6y4#OJGOG
zNnC<jk*1GTk0sAml*G_nTMVjPkcHRT7wUk=7=;;#30%z2>?HF0lSuvIp9-Uiy!;Hm
z7XXAo07ViuJCwM{(jrIyocb+wiH*r5s_=G75tEg#oO)#6Xwl;Pyn!5onfk75?k?y>
z7(OHhlvzLB5~)nqSpZraN`m3)tS7JcXAwBuN#?N)59fBtQkQC73Y`7vCWzXC$e*>(
zE7)>nP@)52nw2yaW@3Un^1EdhudETnLF^6l(6y=Zvag3p1^K72i2$`xrFiz!v3NAp
z#E9~JZBs+S1UH<c6%|mgtweDD<_PwCOt!-X1l^tvV}6N?^}_8_7*8AQ6Mb-+E-RY<
zR1d`@a2ZKDaT`bQP=~#J0fx`X2Oa#L>4B^O%y1&G7?5OsVvJx9Z%GLB1!VagExt#;
z-37#lcLg)S`7VOe9eZiUgUBRA=5Mcj(SA~gQ`tp#fJLUg)#&GYB5{BVxYzeT13d{_
zmN~$6_*whI3;Br|`^5qjZMyt$ki2=2Qb!`NKWLNE_zF_Kj*C+f!D_!GdGYEUq@O&*
z{Uu_tGvEg8RgXSKvtQT2lOD=Ay9$Nl$fp+RH>faA?`I1iQ%9T#4u!<J+CM!%4I}Kl
zL8+HsMwRK*|J;NaQx1AzFD%=sAKK{Wu`RuWuu&1w57!VLBJz1|;c8V_hH`3qjcF5}
z&wUophSkiA>996CWt4`1OO!8qT`+!R#L|l$v<Y$AXFjyGa#!jah%;t1Wlesv<LD7O
z=$S)ek5$=h(CRVvBf*`(eQbo7hyy!l<XFf=NP=6-n|au`_O7uHtU}#ps7)H|1dHAH
z$*VbziI2T+yniGh*vz3TnV@B^i^Yew%a5TenPm{Jn2S~IvR(8B>?2k6=tnn#dd_+c
zv{{^Q7vg=Qkz=MjXt88Tk>*;~)}-8pU)77XmL6rzF^JHToy<d_$q`rk+7;LuAK|y8
zldNh615VnxN7RQS-d4-d{OR&FDi68vl*=Ejh%dRBO%|X<$@m@=*fE?_$8y#wq9#j?
z^u(k9hfMc2R1B)m7Y@gpxLcW*EV}V=VbdYrI2c*A>Ve2jl~LKM6c(0)A<Qbn%#NG5
z0^1AKt+3?t5)!n#rZ)U{BRp+CT#~omSY9EePAnwA6cVbVWHH|p>v*-cf9kqqmso**
z33Wqyg62G-|G3?6B)hAAf(|3mJ!#aG*0-V0MDjM)4gQW_PihbXxEGD}HKr&jK3-!?
zc{bdY4@h?=-1_idFoRRYfIeMuQZXQw{XiGY7IoMQV7Sw!q3Wa}iF5=MxwbrxVx$dm
z%Kof%GI$$BTr1eMOO?G+!i!pG!@knwXBH6g?SQ;nfl3o^EwuT_Dtf@dgc@Cg2L6Ae
z;^#;MwYoV3i8^YzUm1})if+-=oL8M;t1&Le%8W4!dt5->#+_{!*t(&rhFS<XIDTa#
z>ezh^P$2Del=uXz*C!x0@zgpsnPb@2C55^Okv5d88yp%Mk@aqnG*-h_>N2C+L?Yo+
zQnq~vL|!Xw=xc<240QARfUaoN$ojZvMVpL!QR4OszZ^45`7c*~A@$H5<8{g(o{;im
zY9+%2gJA51wZg~SXa?`S+mxuX>VF(MAks%M)=gCzgiC?!pDj_d$era2Fz+NZKJAx$
zankijJ~a2!8=Or(BEdVfM`K+uVR^v(TD=6yy0*LC#V?iGmlF96Phoz}sSzmfk$w9}
zT6hfWjq?c1d8-XiTP1bs`1g~a+#jg)5bP4Vm!aToip7;B(z}wUD)jmJVA$(wse=x1
z^`7f|KIn<Qhdnwe!8IV}ZU7s+pcW(xTLKEGrj++f+ziP+5diRRt`JZ~r(i2B+Yg$r
z*D>I>66M>l>pLNGpubvc053zs=eqoJwCQ!}vu%wzc0QJMO9Kb>M%!S4_E-*5oP%M7
z-mTFAvxh^1Wr{vf|JF}VX#^ThCM+QVXG5R(q;68Pf3+?L@P8#A^a$r|gCr&jdk~O)
z%O-5uD6zWfl+)Hv2!q*u(FCr3+!pL_t{`cZ!V7KiFt;#m(=1sVqNXHF)fzC}W%nBA
z>BKvQ*W`o`>r?<%vNHaCI@ER_)WU|Q6rnY+`r$)%kw=3U)lojRa8|1vo<fU<c{d^+
zd1<(S2IgQf6`}&n)9J!|hk%TT%>(DTTI*`in^Y}CS{M|<78yln<<wxkAjLM=am#=9
zp1z^<M>ymOhrD%%sLAqILb8Z6dkN0Ljw^l*jzQEeDlf!dNwH>77+IP1j1<A3>;^xS
z7XBE|Nh+^@3zcxpVntVfW|+{A5Z)2=jS8XJ8~&Vz^Y%3t@`}CcT@#`;6Bz{r+SF5=
zin7%tYREeofZAK!5RB_qi^YMc5UsV$xRT8eE(baWby5BBgTR33W=r}G{fHz2rBmbX
za^b38<J$<h0;T<W%A7VH>nXr2gw1R;k;EH~F?}A3AI=_mpMa9<>kO!=nb*gPhwXv;
zHDoOn7Jj}4HFh7&vux%mgnP|b2ep~I2`;>qLzCc5MhrV?{bdmhO(l~fsf2;p+jWLs
zMR~ObiUFXc9g8SZ2cVYW<WC*WMBm3`pXtSw6`R&U*pWM&L2Sq!?nX8MGSKoSit-Vt
z72gysAx~J|!C;F+xx3Fxr*6;qoD_|V+QN^Yx%*syX#jKHi`o6;v8gU8@Ex^gLpRi3
zReuO|F?ET+xrLuO6fNy=fLXZ!DE&=tPMNeBQ%8_2W-+j6t{g|ibuFfm^MepX-GFmQ
zXURNi5Svm65YUBadZe=iN-CL!^|2ecg<TqcA5=b65;FE2mJDpmJL01}(9jIwdd#lE
zFU6^!vOvPJ=7~uBb|R`-e~V5Tnq#0oh>1{*-7AP#arOl12-N%Hwae@Gd}NV2f<Dy_
zuLc*Spp*SUT@j>s7;Uu@=|oZvsy7>fIH}mM%l?_BWUD)-#Fs?w5Ywz`mHv))YnxB?
z%#}=yjkcaFM12jm+o)<~wG<_UqtorjZaAW<4g&bx;u0pywp>y*D&Ndk;>`W+2ZdHb
z`DG=W!p`iaOa?I~M1mncMB0%2l~l}+f^-6wdLAQ~ErPQQG=hmVwmRFRGWdyTkZg1%
z2*t5eP5G-a5?_#*wBF#^h%IS)*T`(eNE**FH!~I8tfrgcbV1=a^DH%Or6t4Z^mCPg
zrs;HwdFND>F=(YH)lm?HN2^ap_CvbubD~2bTYOO_c}PfltR<wr^HIuHO|7$p<e&^d
zV3ZmU+c!on_pQKC$Ux268)lhh8%Um&Ah+_zfn;}fA~T48@@zNLMId<jOJ|>UdSFPP
z5G#=dB%8Reokf7M)fhejn!od0&71foMt(m5=Cu_Y$hC_U%|0lMU5b2=Pm`Lce5`!w
zX?5bj^E$N6(lsfIRTK+jCpO?hlgm04_+(&NB&t=PRkjT;@p7V(yO(!z#qZ-t>h$}t
z&!gTu3(L!58@iGJDa-u^x2D7mU5QKy%SSzFn>}dnxkIe8rJbanobnA5s-kRe<TLXO
zd(&qv24<($&f%G%_WyJ>TY$|u=LAh~G}0=Fe_Zoob|PllXblqyuJw+xaBQb6*s-JA
zzlJ^933+>qVJ=7%u^jltUob9{yV&r9bKs`H1P0_yIJG98>)jHMMzPeaRl9m69|f=~
zQ%Zag<xnK?<0~nbLFJfai8P`WM>O?K%U$7((zo#O*lQpdcF41JPz!d5q6N{HljP5?
ze9J=2?ZV1Pu*yk+R=}@tLnrxlZKu7s(*v26k=z^MEIv!(yR<@H%aXjD&6=LBN60}o
zpTkle@_SQj-+Wm3(e~bO@TmRiQthYD;{4enmc2iM{Lc3>=sf@m7@z2$WzD3*ds0ja
zpQZ$1*jpk2NVfAL!?rLTg{9v>|J^#djZBjXlhsC`)m*u;E>s*AI4F{6lM2p1KP*=9
zZzig6dbkzuVR8D?x0Hk)1h%J!y*$)5-H&+b;2J^Sr1jCK)24Ix5WogYCZdpHa@Yv$
zjwVbKgphRv4x~<50rmQysO+|XJWL^~=VfZx5cj^WFL)<>e>-^(UobYY_>DT7t3>i4
z^~2iYXG25Dyz7vRjQjh|)BB5%O~}pV!NHAQHMgW#l91IspLpreH}RXJOZ@wr`s4cJ
z+G*Om%gcl2%QpL+vc;R7=G#&G`!3qMlaq|Q!&E_``Pt3v;{Dfy<6T!bT}`*Qi|?+J
zhCDX6FPrZ#x(fV9b0@lYZjbcx>f|XZ+?p#|=$1~*1AI@6?l<o*_h|3j_{JQ++S$I_
zzqmY081f$zx7)~g3vSaWNUUMdxr_-$yBwaxy|uqzw;%iAh~}K?w|mV(>`N7WOg?*M
zIXhig+3y-_xFb*D8C`$P(SYQ8GArnNVlRGsy2qnq-?E{nK1n`4L<{jY?ESSln|evY
z>rr*E5MKJ}rq=lO%r`^4(MssPS}J3g`_WSagS_mEgU4Z-62=*uu7=Qn^~)2rJvV9m
zJu=GcKHQEJ2#wAc*9tQw-^+G0VfQrotAJ9qKL3SD@R!5e<Eq#Wv-7If?Fu;dfm9Tg
z>V8X_r69WF?nZjcw?jJf;<VVybm*qe*O<jKO`x{?=2sX@t3j1`Wo3sbYyDcN{Iax;
zUK?S*lHfTEU+g^*)m>|wmG3~C#NGP1w7FT+_VS?hS1%e|-({Yyi@8yoo0NLL+pTma
ziXIL%WbX(y6YRlX()e^Nhwn^Y7m45D_}l%gAN+OnRw$(GGM%X?hC@yI=Z&aJ^{G)B
z>96#IQL78=0zbY_YB1TH+XF`-vCUV->3N{_p&@_!^{x!4bl{$=s?ed4tKHe;Q$*q0
z<4yFuQ=zPb#rr(QTN~d+B2$i=z6|uE;7$r2DsjFM=G(K)#b5Tm9rboBf?5U2yjw;t
z{jnWuE-6I$7wh0mtGWW6TVA&Srgc%<tI}G^&p3j2OxA6*o=C2+-R47-yKs_4br~1o
z$z<H?3dmGpQvrDAs&BOSVtT&!g2YX4DrXX`#5iV@j&}Gc1NMmb7GKoQ#s9=e+x89%
z-O6ur-_`Dy(WoGx`~d84;p;IoWU%n7SY#mqHLrA3*SGex*`0z<;TKAk$rVU#X*cku
zmFl8+1xi`gt<mg+5tHwc=Kg$d@nDJ?jq3msHFO!$a(KVW{52cnY<w)~XP@euYdb54
z3*>oWpKaFkrODgt+bA|O+-sK7{3d0ivob`wJF#CW?=lPIM?CI}((iukV0A{EUwf(;
zomJ(yula2A-b$$9mmYm-&M(+O_Y^AAxwhW#J2h8(sdFZ#nMk{3No;sm^zJI^l!(#<
zz6A4V(rqd<p;^@@8D3_L(Y~(-$rYiSy++Z|_|)60tAX1%j-DaXy^N;Yp79e6-}4*s
zN!`9FEOR?Eh_jQqiS5IYy{R=8FMt#9@CyI{_<{VqTz})-f8in`4^bSl?#}X>&L+<0
zfIq+kX2J;%063&20YCr;$OQf^Cial{&o_shy`A$vQd>Ode9j5rgBPpuS0Z@2zbe7?
zFJS<VR~`=L01kB%OLG7t0Qg(Dx`~rHye#0~c{x<f&A=v7_U-^ZIK&Cy6%+&jxi~oi
z2EUU_!v(|BLjXMg${_D#@8a-}%KQ=X8-2(E-#9ekqMc0aAPx`0Kpua?F96O?F6MuS
zq~WP#%w54Ca}9Z^2k@`9YM4XpU7SGX5Ws`pG_d~NG=6yaLB9{0QZ~1<bhZKr{Ht1W
zU>j$1Cjf_>4P3J_<{*2s-;(}H2n6u+2=YCY^_R)qQ}?vJ+=*ptO1Cw~Mdw9DM@5q{
z8Il=@V(BnT0|OBd;|XQbBLIj*b7hjIGV$0L#{@ctN&slE<&Q%OMu2|>u!4YQXZ!e(
z^cy$Kg+3B85_M<#3PWOkrUWlfB=-7q$bIADZPP68YlG4fxJN2YQ<{ZNhCTu#8kSo~
zRN#AYGa*i7`jt+GLL7Yd1;K+&EGhc4oYZHQ<h!jga#0I4y7my;it}OSjRfy~!%tDa
zv@n4jYVXWU;V(LR2S;yhmX~gt?Q+(z=1sk$oqZZtFqm>}mIr)1%U@=2(_Zz02vcx4
zD%$moBCbF+RX8o7m%Hqiv<7)J!`sZ$XuVY1_8ds(%@v~%_Su-R0juz}f=zeNJHRpi
zSPPlrdowC~t6kOp;LhOAeiqgqEGC^7jPH4d0>5vtW=lEx+z-S#31#JeG>j)zRC2`K
zL7095RQ%|%th_eb|Czx^qnvosNmf@kh%HVH!({bRFkYQyjS|6xDd^HPDDbs>_AYv?
zf=i`|d$lmfJ%K9TFLo=Dh4(UMJQnk1J&(nhnlq8-577AIu)G*`M3_I?F5~&*5pn#G
zU&w1qDLyMpmbMPzNt>14y%lRWr6uIEMeorF>x@3@x6$LO)T-gQY^$^kf_cp9a+I6q
zvZgCzFji`JJmXyjwT1KBB$8`<WaE1SfAHVCd4()KtSs1KliyaHa}uoObwVShJ23Ih
zlWZ<~w(6(cbaGcIeBl?PreUjht^>qf18)<V`JWK%*rlY&dK<=$Wr3_!k@!3}PPabJ
zNxl*D|Cs2Ibi=N~Bg+$7%1rf1<nC*ik=ObBq+IjIuAx1`ojE(ly}ssfdt|@5{bckS
z8^P!i!prz>r`+aLBW5A6e5~|Krzz>y!Rqw!z1Pjch&N5&&$@r%>SgeWPI7_Kd$>fW
zb!htHH7Y~RW7qIppMIUGaACcxvAgvvTG_xC5B>CNJx8WdAfPtg0<<kz*=Cy0Lekfv
ze8rX~pOHT_Q_-aK9)zt!=s5a1%P(A7<N3-2n*n|MUd3Fyt+r~w6h~6l&y>*-7h7mn
zG1Ks+)5TXMaqBvqg8W_yD!YvdmDxu;#O3r)Oy^09pWD~lMO<Gv78{fd5X=N8yj{<B
z7#1Ur^UeDhsdxD%&3Bv~8<*MHfN74d*jVQ69?qx&pVRxSncEo!P=k=+r|jqaq~tre
zQF753X~Hf^`*!j^u|3KQswdlqmS0#W(iAnU!ikL$)AtoL19ZdFSCn~$YK3Z%-*CiA
zLvoc9d%WI?{z@NQkSk%GOasqLOYtxS0otWR7((KsK~NzDN*f#(T$hk9B3vnviJh%1
zeBn`XUC&mj@Qd)RLBGlek+l50;$KTC<@U^gO1kD`C%n7#C-vRPbqd)>lLY(Tb7>`C
zqq^iY4eR_Ya@P9!da$viao>7JbSHb<T2w;;t2V+lU(m|*_UXVIa81>_wP4E$ao`gU
z;TNZ(a?I*H6>jMzR2nH=a(wnsW`(u6(+-FbzDwb#U)J?^Mpmv$=+m<Z?q@H{7{azm
z2glf6=bR}`5{G2#;)QTYXg)T_I~Hc2FM5GD?V*>p-w+b4^~u#lmY8)hOIt8|DwuD;
z;`D95^*NE^ZCB0L*-hTgD(#I?A#1nt{Tc1E%-GTdtID6FHZ@#IUWw0#4UK1~natB_
z<Yr}!Oqwl(6R35yPu{`=w0K2Hz2^!#w}1YKK_6H3gl$Pfvd9jyPG3QODT7$%y3h;T
zPNQE+bPgjGBGAbAkYqM>7NTCUfKq@->^yv<xV?tDd9NrB$jLsup+|PfRP1@yLED=_
z64CWD{bZ#~z&pK(E?q=z6fDGQT|0Hm_mxCC*F>Z0qh#Mp^sg$P12_och`HF-V)H(j
z0dwfuGYH&1;wF9K$O*LLu`t)r`*PXLi1$d!MIaQ}-0Ii10YUf^>nFg%r;N|?DKrX-
zXJ1zn*xbCRi8VWO>8q|wd>i^qWz*eKZ!-kb&%{QoT*0E7bqA~5S$n_eb=0$z_k9bS
zz)w;97Rx0VbX}B#Q&u&;ug1<;!bnH#h?o09ur04`93t${+a86uP9Gm<N&Db&z-O!u
zxuq%IA4sHlQ&npAXp^viCgfv6)U_-j2Yj?_fFewGeVzSnwOo|v+qB^A!)<y-^x7fI
z04=-O1^2lqeq9=#_qU_o_LmMPEUdG~a<hQ&gf%L%*pZn1VxNuV52fQ1c;2^#-xjkD
zhTBF;62oS{HR~`A+|%7y_vG%B&E}h+jg%394`T(mMB}BrUp;sEvecx-BEFU@KSO&w
zCZu(}>K)s*320-C@`@Hm%I%7|=HqO%F>G_DN7~Oiy*nCRZ96*XGK$)~ec?M}w0*Ec
z+f~m(9*I*O!S_KqXEYbw1a`Du#)(hic#3q_=&b;O1sgeIE6T)U=}qacei0W~A8U(S
z@YSCqD6sN8DR@<w;9BxoWG$BIz3<7ZD4J^_m#oG@xtuMDqv0c!>vP*mkCbW8u#Dz5
zGMm%r54KH!&NN)0*ytJRfZLV7o*pQff{y;FhSWCdu+(xZs-o-;>P*NW32XZcM=7>~
zlM9TOtR<mCGS8`{Kwv6r4Mv(rv+b@&1Yfi9K{MpTM<((13A?hoH@R*sXn2D2+gWE#
z<NGt;Re<fQ<Z}y8g-s74<ijf}>|}0^&BsbTj&(QuvIAu?mr*1HWm9uFvOyF_X<OCm
zJ%wUb{NIm{>s&ZyYu9VVN{7Uyb@hh&eH(|eq&4K`H!~(p5@}e{St7#^fYfQ)4U~mh
zX1Y6!0zsZ?j2R(U<f=V+Q7@DoKF4N%c%iKPIP)iFSiig?nEWL1s&|IAVk*n{YqijG
z$x)(J;$w-_wmg9bYWQq9mf2ZHT-LN1dQV6e4Y`{eH)=l^l#~(-#w+Oj$O_KY(0!b;
zJ$X~NIF0)uJ7S?@T5GTP*Z8&2F9gg?w-=)$r>ZZ>7jTRUwyFZF+D|1sH59E2-xMVY
zDd9$a_z}zSwgOL;6NYNXNrz@ihj+tfs4}2%kZ~7r8uT+_WHL8ow6x%xJVuJ7kFDhx
zWtsxf=OI?+MRISmCCtH}!$fNAUnpw5ymhAAD6eQ2Jx;_sX}z-7*4i11X{RY?u5Y@0
zS*C}s4wRJo`mk|ToLoG!Z2J7x*7zY#SaSHZB+dmk`W1WQfqeHb1Nc5hPMMpelI=ya
zr5%1K8Goj;>v&PUFs8OI$x}X$;4fA#d7mgL=Pf9fd@5o3O3)vhSZ?02ZdSQ6-)^yd
z@t~N9Z1}DuG~!18M00W|y%DcC#h0Bu6yJ(D#dOqx0yOtDM*Cz(J*91hON&is!x%Wo
z5CP$XwJ;(azkR(C--DMM{<DTI`~H&oylvk>7-wGP1G3HYk`u-F7e(~CimTvALk+cs
zHlTK06u$HO1eyd3CCG&a7?s1#CYn!JEXkYevwp%VKyI1BO3_PUHEms0QEejbJRSmH
zCsOn=9gcMbK`Op9;irDu*BggF2Va+ki!&#&t`90sJ+ps}2eXeSa*(=oyO5~GGAb*+
zQMzRE9=d08dz$K3Cl@o!kihhk_42fSgs)e31@OjuGWM2Td{TpH08BpO{lc>}&+Ai(
zx+)v_dT#7#wERN%lk^Q<^a3m)%KYjV?PAG<Ri7Pqx;+`*fA}6d%GqRI$5WJdWgsj;
zT~Uyi)VMLL-QO06mfI#-@gf^zMZ9yKu5FD@4E~P)&l{nn!mrC~-`>78KUk!&?Prnm
zEQ+QHdu-;&l1^bvfB-^3G{A&lMZDe~3pH}(Ea+?CY|!n>Yz+;3q&gc*ag~)6&T{C4
zTy*HF-L0B)r8*lU#hm8+L|OsS<9$CJYuF<d;kd{u?$ccQpSOe89~`R!#bh&r&Bw}o
z_*MLEoZt4;O!gz{D7;z=g>0&RQ(kJ>P*Pt^ZPW_{50{6seFH2E$n2^}+mC#>$ga}h
zE$1O1IU_f5Y23v}pI|Oc(7JZbmA}rxa0lH`Bj?jLgcYUQWrQ>@vW(ThX9Ww2{BA;z
zjkLPn{rX9)jhnQzwPS00dzjw}gB%upLCS4gLiY2+dY5nA<uP%~Eg^Sr-9pbh#xV=>
z*BZHh4QPhA?hBVW&PHx_HC(RskD_M0+=LJ)i!^QI*!#DD<}07|`c^wmrvBvKEO4Hq
z#keWoNN(iIAo-kQ(p`{YgPqse-YMxNjuy<|RMb!Q6<2PmJ~5_DMp-30r8y1LsbL_K
zW60t-YgS)MuVM0HLXXgwqIPrM>IS&BYBX%!Ox~hG(M!?SdF0qTx(gN)w)1%3iV<N_
z&K7xX88dwhpTKt2;xZ|E<RfFb(n{imTim=OX%R=LT*_$NY2By0%E!dXKe&GGZNO)h
z>q)<;Oj7c7blo4tz0@jn`ymZn=}Z^(+W1lJlW#{MRA35&anDzl+}&*o7r^JhmbuXt
z+^&7H0@74?$HJ({Bv%+0n6q9c?pZ+Yn&_gvV?^!js(uT^eECj6@jZ6-CB1zTy%<u?
zx8`Et+E;p)D#M}>&o^B=W)0v828E!lb30*ChDO{b#_v8ZHW6g871?=3B(vX2Vanr#
zpX3`L6Z79Tj?`GlCdEmfuTW6SuFBa2H-#8^9(Bi%840ls6s!DXX(BWd*Jf$D>$6<x
z>qf<EbV2#%_eHAdjqHUY6S<i&%M?wmVnQ3HL0ft?X0fK5S&du1^YOLDjU9=7f_t?y
zbBFni>W{M-KIw0^ydxEUH+W3`HE}N_nL!carX@Yp8b9`A=F_2Av2VUk*FpwT41_xd
z8Q;Fx$>0dDj+opd;J05O<}VKZVo+yxd&Q_UsmS~+iKBE*zplYaKht8E@}T*?Gdo2h
zByN4P)KJvuU94(qwOJ2ae=hDabn3oW05eW*MHsPkOG4j_4x9(tk`YR}i!F&$g|CH6
zjhyT!=BE`WR8=!`pA^mM10`L)@Yh>?DUg1>dZ8vxeEwa6^(Sc^uI9xXp|GFSS9p<q
z_bW=U*qk6)B3ijT9FTz2%zZ?oi1@@8J^R%z8WO?V!Y-1hY4<<KT;vVt?bv=P%=@`T
z-}~NmNkbH#w^T+f*x^r0xtSEB)LR;>X&2G;b!$#R-cQi=J9ji0tO*H5a3{qHO|@ZA
z%T<&oMW5(D;kTlhj(WSM!7<RG$7e!6{q78**gT`sb0lKG?AMpjf!yiCN3>mTCWApl
zvFJW-PYUzMdX$|WH$iO#diTxQod~y0@N50+IrW<(<Kv!j(Snagz-C!IMxF>>sz;t0
zVPJ~L$()3A*=@YhJUB~C^N}aeCTBCcROpym2g_qb3MIs*5ap+M(A)9V^8_;{`Wve8
z&}bnLtwxlWDAm)|ELL%{7n4Wv1I!+|igM>A46E!l?XJV1s+Wdpt!r#IR2HxhXL2Qr
z`e_1<1tvt6C+pu`^KL)rOKs8}xTe^bvJaTZI^$pZlRU*=onf|#bQroFLGFHuDH!e%
zY4b$Q=O-77wBp{dyGAJvi2OpdB$G{|1Tz^;&<ty0BhDu`*f|JGBa&72BEjqE;IQxc
zF40<Tsu-(}{Pwb8tg7M^Z#*xJ@+>mVE3-j~>|7<-mqdT*h+^rS6XXM82A92KwE<`$
zN>LAdO&Y_@nrfF<VxC|9t@lfVGjmc<<HRouTh!`Y$;F<DtIu<7E$9{FJ*y+T?py<n
z+nMm6;n(qVS=j3i1YA(+zM}rfBUm<~pFC%ocd3w3!r%`b37k>EB<tXqyKQ0&iwwoh
z5EVb(*gGG<Pm%wQHHO_Tc4TWLqi9|fDi0&z7q_C=d-i?&{+t=@d6i6^Ot^>eaadKj
zcj$rb$0Sf%S<V`Jzt42u1k+<VJP7`D7ex<_2TF2J;~M9Va{dwi3tYn_wMs=N-Cjof
z)o*9IdYoFu>|G7p6Ncxe>5-Qp1{`qJ@GFYpMDlC~`Musy@G&<7l8z#Bg+}0|7fO|P
zfA=S%p+KUYL0pW4oaoYp!0*6M`L`Kff%T8O>C<}5WaM#-yRmC{KB|Rx@)swN2I=||
z{8$TWMqR#U`>unySi7W$$d7WPMbPBfV#K=SNzi2Ifq$<HtH!!0LZbMz#G!JS2j#ee
zjUyh`LWe4rde?zBim3XXVM$%EJT>l%Jf;gCWHG|Sa%hCkp(Tg+D?~CB?=8Q3eT2;@
zm@mc!LV<4?!XPis#wMvmo3X%kfxx>ru#A<ZD5M3l!*r-P#^+Kfw+rUYduSbsJ3qE6
zwm@zF3iGYQ6N*S|0j8yMqy^H$MCc->yC%#Ym5Rhc24;edmw<Ljhggjsb*PJoj!%3X
zAiuQq#C3^Z@?9q97#6zJF2Cdy$I=I^&xD6{P;10y(z4RWhLDzGuYj9z)2aHdwsSO-
zD0D-~Y$LG$Jdz=4nG#GD{}txcQEbFPw||oUp(!xXQSm!c4fa&cc+WS?sqMh$pFkIh
zrc?Uh;{l*LxD}g1gu_@fsD&T%Gp8~AyQ*>|zAtV^xZtt{)SVRLy%c)yuTb9gAnyS}
z?aI&uak91bAaxqkA=G6Z#9}R%)ne2y+i0vY0}1C6(^zRq9wtF}edQnzV0?D2VnA8H
zzY(T(UHgg>DqFd6IaC&j6bqyJ&Z!0IP6-j46vo}bDL&M-iM|X*JVEJqX`y27pICZ|
zSeasMK_oJb!kuDV2L&VDslbR{9DavBoj?#X#}Q#NK1OmUres8-Ayj8Gj)jJxD(@o8
zs&KYo1|iWr;xv?yZ0f{L0T>0K=YTE(bU0OE+H)Se2;C<wkFAe^d&`I%?`cRo<gp*;
zwcR4g-Sw~0qu%rf5+Vh!b~_-p1*dpx6XSf~zfdO%e$1&2^C98<jI>X}slMHd&esB^
zcNlWOz}(_k+OHS6vE!H<9~w9~mS}E5J0P=mkv2lU!ssUXQJ<7_Zs%_(s<P0BEedg7
z7!9PN_GFN#LDZRdNoUNg$4e#`8sY&+hu9gsUKj{0dFI^XKbYp<00BBHo*$}8Dx6E`
zT1OYmBNs|;Js$Ir=SOi-AdF_q44{mS9%8^p38yQ^d=woNXd227i+Xg59s1UP3Xve-
z!(+s~h%9QwqBN-04T}((H&O#qHj2B0zdSUkK^GaOkFam*fXSIUJV&t9K0Rpl1J#P@
zGZK}+0G-5<zdjBQI=L<szl;neySXQ?L_!6CWcB>H;ThZBjqftu{Vd8&AM;%^VtiDJ
zz<>L-ADpaz`L%g@IRE9=7W{8_EbzgF{M#qZ@xT1B|8&0^#P-<*a1zL#--YYsM}&qT
zzhDe}l}AbH^SO!^;Vk+I35dL6=|FfjOrsF{W81|-aZJeCoCv?2KAi`CCD<{@#F=l2
z%P2r{>xfGzVcl51a-nHuRyj=zGkMll$I*I@v$)8AEdVcx*QU&?0uqIfg%JDA82El4
zslF7#`t@x47GHJijlye#fDXSEL!tW_6^s`=2b4;it95%lX9X8?B2qNX+~hs|q-2Za
zIBE5nMI%+g){m`&2H{f(;+y_NKbc2;y`Gp0R+N1$6rmh+#p1K}j_%f9kVI97K9!r6
zmR^%i3^OA%LfY)v*ic>ux6(!ox6*R#C8tcjl+SR|%Tn1=LCsUyvGeSMWH{a^*AQ%(
zNX|2q$tVwrO!OYO)NM#<)ZHj(C3CNT+N8K}=_9{Ef%KL6?y)0BL(K5<?c!0TrIz<Q
z#8ifS{QtJuZ%h1TG;VI*zu5ucgX8~iANn89{R6ikV-5j1fgPOfogN(Vzv%{56I(cU
zprWk%T1S>u#@yQEjf*DSrT?#ZITKs3jR%0`PZZ!G?&+UM8xu>o@1E;lDW(3f3(tX^
z@S)$&dHA>h@bR<UaF&6a>o1n!g|mqb7$j+DX=4uH{GCq{0(zh+1i1u$2OsM95Pr@D
zZ^}arrA-_Z%)ypca3%v@%x_53+1&OGK;TdQhk(N0frl2tyQ4W5;DJH-C!_E{q5QWt
z{uJk8>inBNc?IVz9yIkEl`?^t|0ZMpf0_Y1L7b(nOq~8!fU?P7VIbEZ0_H!}4ft)4
zKWB`r9h|fP+gSoQw7_<fb`bF2z;DS~U^8bc2%M$i20panfA8FUoPWjhaq|KGe;+t?
z1dsjSB|M<K{0~glpPi5Q?_+*}f6L{AcQ1bKhraZ`cRub1z6dS{_;>C<>A3j+T?QwB
z2i|yIc%OKv&jZ)<z&^nd_~$qI1SgT~U)zBnm>j^vwdS9O`|oc2z;gZRol0P{2R%Iy
zVH*FUv0NTVuYYh!z<=^&>Q44%E+9C2!~!w_JJ|z(>_A?2coSKyoShwnIN*dF9JO>Z
zaj*h|Anf)|mQVk5b!j;J=M1*DlX)QXSY(8_IJvku1-Jw_f!u;zf~=fe%$%H0|0(p}
zOyJ+-oU{qN@7r7cHu3K!{6)?EoAq*cGPl6u1OR!kIRCW);AY|G1y}(7VEh6CeDI<l
zHh|sV7*Oy*+5ZO<;DcYx{{w>u9*p!K7(Y;e2X4Us!~}S_;5z$Hj0-3T?@0fN@$(7(
zS2}+F|CS*D<odsL;THh%!Y%us<q5zq0{<5i<mCBBot>Rb;AgkfZ(dLn>}md>tA~q(
shP^%9=np#obAr9Fvw++7cfa_<1e!QG|JE+QAg7=J79*pqnjF^u0|2wDe*gdg

literal 0
HcmV?d00001

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..c1a797f1ca66b3105a20946a6d6ea0f259472f1b
GIT binary patch
literal 67483
zcmV)_K!3j_P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lxWJ8UI3-@oDxI|Em5N|g5A
z(*}YD0%XwLo&^~M9drYYQv)Z1B>z4~<XVe5<yW`tXBf7hSXXCD6eUsoShTP6{XhR;
z@Bd@%Jiq?y&*Ptt^G6%!bASE%|NrxU{QCF*$NBZ&|L?=T{-5{%{x9$U{U68w_P@XX
z;QabO4?Dm9*ROy2viQmTzwe)O|8bx8HOBd)zyJTwFYiC@_m7eA`uZ<l|LOQ`x88sB
z_g}xewI7c^B4oGUjr9Ne?_dAnACEgHcYn3^qxm`8cz2&ayp8L&uYde`{QLj*59dFu
zkN)F-JO152*pKl){p0^Q{^x)Ejsd?NsLdZ^n_V=&pPN6=kLh=HBH<6+?)Kx_K85xl
zI?eIp9&PId!XLW%9b6atN%+^X|M_uW-TV8i!+t#1Z`l9$neV;*uydas2!EKJjUV<r
zTQ?BC@AekIPf;e}58ZB~D5Dz)f9N(n1uGXIn}1XK`@DXP-$?)YZ;}4)*QY3x@Q1ne
z^Fx%;{zE70pQ22{_ubkvDazT6gg<n<--p|<S^yIMRZH-mSF_9R_gC-!<NWI#@OA$E
z1!%K>iZTg*n4Qm0Q6}LJ-QGL;LzGGQLpN*t8JW%RyVx@*Sjm18{<S+`+}_`!W$&#z
zf5-lR%MP&X{t#uf|1i60pQ22{AG*E&|A#1(@P}^grYNHu2!H5iM$y6&fbchWfSLbj
ze|-pj{TuFp$3G<*?eFJyU7vD{_V=CUxl3`h{&3IqU+($-FE|_9ggoKcnI%sDYN>zk
z&g(Zq|8G)yo=@q0{spqT>47BJcL&vbLo8lZHxb@9{J-`b81HfVc;6Ra<9&_#?-Y^0
z#gg}aAKNg|{B~~dqpZIfR-Hunwwt}r&GpaKuPEPle9OVw?^{PvzVGNGmG9~(%HLQ9
z^S2f_->1Rz{W|=ORj}E95woIvKgH|$MbL`!eaB~hEIixac4}{x<#Xwa@_onmIr_Qw
zMfn>m(cWi7fBv{5{@%^l-a6o?xE1C5NzTtF;?J+5eBbd7{c-C@!uQ>tx3YSEtcEDx
zcI@UKYtQ!IScz`uk9qg;_;)Muw^YR5?H6Gy%J<WIKlVO_ttj7jd_OKfSH39UcYHsI
zK3Bdd-*<fO&y^S9@2ti1{#Gh0->${qyE@-*%uit}%C}QoZ(9F2gp2ZhM}MNje)W>_
zeaAV2d0R(OzVCSVy;HRQ#ya@>1hzl#iNB>ZKF=?LR+Mk2whTKTf+oWE-Fp9J)r<0d
z$9IR%RWHi-9p7*L&s8tV-%*{$`!<|^+!KFKcY3R-zX)1U{vg_)dg!N)`TF|xhyNv0
zj_Llxn)rI><UHH`-f21eU#I;4t@&=pc>8hQ?Oqq^TLmmr<G=fV#TPrreYf{l=UZ1e
z*XQ5c>do7~7S#9VX-gBy7g)3=Sh6gC@iw?<%PWfGA+soNu|9&7k3EpylvFuDdH>g&
z^3gK9Duc4#ByY-FW{+P;ZGf<z8rK;={z0hWu4%OSMAz5Xv6Eb%T3Xklqy?`icu@!8
z{ZETflZ<gKQcdzLJa5VsU-+cdw8v_1|2@~YI6;qx7cC-185>`E7+dlL2W9c@O?k8B
z*eSj-rpF7<V?ar1BM8N+AkeZEoU-6l|3N00!_K2mC#4miEcnzmKE2s<1W9~)x2$*+
zE%L`;OFHpj4N6QV_R~Sqn$7!wAXkb)uH*;WxW$8f#x2Si`k`3Xaf=I<D>g34x8)MN
zDW(y{5{$V%${z}jze%nU1;^hM(};qdV~97F>>DF_1X7I1#UBg4Eed&b=8hX(Jjxxg
zDB{tXY#U8HI>DnR9-ZJ(<AyrHqFjXoq!^G%a!#<w#I$9QcpqqD*$D=nKlronp&vmo
zjX2oj+?b29<j-qc<{vMLX}s&d-fI56^$PC1Dd={kP%H|%T@MV67o_yc(|Zy6lUwgi
zS|<ly3rPsx_~b(1aTfN<!5<Dz_+;xnN2j%L5rPeG3bym2#D{4-Ta=i!b4`{4^8Vhj
zNR6Wnk$}k~DLLt`UN<J)+3CidaTbFVEN@)NG#D-d7V=HVDbgmmC^<!or96TVO)TVf
zW0EJA<hrr6Sp9c9rg&~$Y@K+mKU<%eQP=8UceJ>KS5Bw%KwgCPk$%?_#_}!-moOay
ztzXqCCevwiTa?(`9qWDsDb}dh!lx3mC|vj}w{o9stp)0%dK}T@pHGZ_uoXY&5|sSZ
zqEJv~?z-*=nmO>kb;*JEtxJwu8~#mMjPJSMkEFzw>TT<ljMv3`<yEsN6t2AM7i9_8
z5tLxHF5YWkyyw=b!%Sa)(_zU^`8yUV_}Ctb?MPO(yLv^766-Mj>%e|fuC?vjr5?%G
zMX6rFzIJWBf_-gnz4DA|bL*C)n_IUWp0uCKqs1QdO~kwokYWn19v#E;tyd0Dck$K1
zyu6GLkb--C>z2doTen!u*7PwbXD#>qk)(8})UJm{)NJdPBhsONK@n+r=;Mb%;M%!$
z%MqPhw`7<!GH7_s9$hgPZg_jt4VSk)TeldIm0;jrw!5Z=JJ)WC6RuplwqC&^E8)Q1
z`KB}+akwb0gah}YO^G)yL7V&(?mUyGcC8ET2ugJdZdhFi=ewoLVB%gfoeUGVkhw1Q
znJUhkgjRB)Z(WiJQni;}8>8>p3OCq<e9l{*G5&ep3MPH+O~@}wXPY;^nwrp&r2MRH
z-SV^Wu)Yb=z|lJ|O!nj<pL+9~W9P#jX%kxnTniHi_WAHO!4tEc(g|j2YR4ksXX2mP
zVdjTVsdy9T?<t{}IB?HP8+qb<JtY-0&xJ*)ZXsPKrDBCVEbg8u6-Sa5drwIPH2Fn=
zRJ<uUN&ZGou%u$(0zIV@&J?0WA^YLfIlER32jkhb2FrN3+J-0AbWD;8{mj?wB5(yf
zT4ZJiGj(>%&Q&yUzsE<UEzXW_==Ol)cu~lc9xc3QW}av7ztK*~Bg+)NvM3|kWJt<0
zzuA&w;fy6ITI7V`6Ve*t^|9xYTv>b~B=7*ChsRh?gPD5KvdEJiC!EM7Bq#jLQ}fGt
zFGn-ymj;(|JugZdL7<T2zIjttYdopv*`tTUh+VV@nB&Ovbx|<K@qkI4a~x1V7YRQc
z{|r8^*Hm<9T)T0DO?p*~8)I)ev&IcZ@egw3I!{KP&x^vbURYq$Sg(Ax*&|JJTo^ty
zO+3+7o8!%Z3%jL-<fAPpv@47})fWl8eN)yr-jr;;|4WiG^6p<0j%?%$-foFXzUbZ*
z9TvmUO;^as?YJoXtfy$bNocMmzX$f>aQx`tUL5eM--7};a<|(ZpF2Pb=HGl!jC{Yp
z3DIi!4V@DMo9os&F&YP^r+>Z~4K|r1<mmLg7}!%cpO*t$>JA;?04an8kMpF&50@wy
zez-*8#1E$=97)PGq$r$N!IR%U<z9P*H9A8m7(}utArE%x(c#z~mu?o%TgNUbq#l>0
zy`KQsxxVh4)#e53kbOD&9WPVEyJ1oCDzZz*27;L^HU9&oVAUmg@ziJElx)5KOHUAo
zoL>?a$4@O1qy<k|yJRTxiLvQH>I2awx@&yo<gDy_J}@>NBp%kNMHtzP|IW2g085h`
zcxuB2T{I~<Hkp##F*e;kihMD>auMlZm!2<gN{&rNChy>zbQSOKmd+J#@upamf%b@2
zV>4IuL@UG-s@kGJ?xC9<Nec0tQfNI#V^az(-qediDLoOQb4$(g)I=AFvV*H)N}cI>
zO<GwUdtL>zUb%h!y9BA<2o4HC>K9rAtsJ^87QBOPcHM-1V(hvpI>ct`rs%n&ZRjZN
zm~ool@`o_xp$&y6r43nC+XKqnC^4cDA+Sdf41bbq)-b~{(TWv(AJhETSi_;)wOwi3
zGo0i}dh>8NrKH7!VG#!ZAX?yghR-Ylm8+I-b{jOYI$oBG0%2{b0xSxc)KUdl6oZ|(
z4RBJtZ3CRt_Q8YGh7`BvU|XZ!(XhoZ7+f#!^EU6B*1<Eq0`d4<6!NLZBWF<{kL|sc
z$`sgemkg<Pt$_=A3E(AaX&uZN8ludk@ip8Xu5H$^gWi;ZcC5KSe8@FuTK;Ga^Vw!)
zKy0a3`K|Gt(Zbm5!CB{eKUi*SbBU<oT5yRdo~es6&<@`FC7tL^%Hhl8XplnJEnwJ*
zK6xZq2%)EbvLxMb2e^zB2AwCZk~YCNY7qwA#$~mznIgJK5Z?C-H9tJKtTw<oT@`q@
zF3LbVmfGvBYL0K|qA;A{u04QIT2qMHqQsJPnwtz!fF2K6gGjkl4{P|0bWm&fj4lr|
zZ0NFfnqf-W1&X@s;xL@GE>#4t*G1uhh3D&=v|8sA%OhbwAFPgq{iI|_M?G(-kA9*V
za#6<76LQhz+&IIcxd{AKXudtKn=>WIy2KoB)J5TM#L>72I3La#tvoN!k#<$<x>nAV
zg+;+aow&z4r2I?+)@nm)PF&D^>ViJ=th2JOo={M`o=9hp7KHJ{g5#1&3Pv~4%#jUE
z*Dx}@vg0+n+MF#enqIyaJU^{V#PbQd2szY_7wDo4v_nKXkNu<L3A#u*+C|Cr^Jt~U
z*r_QkLYyZu?k-BcR(r>A`vVP8_TELwpGj7)b~2y#-~LQYG1Zx*<P5n{7A1Mljq;{M
ztL6M~`E(kCdIk)xu^G6uNI5@T9R2Z}BJYhw$SIn>f^#5j$~iXNHr@289y2`k9jI*#
z+3yeR0-g58W06wMPkqU-WT!X<WlW~&Hziu+$%!++J!1cvi%LWFBE*~<Ukm+C9jh^0
zWf9`ANY&#2DQ4ZM;`RGhp!7gHIMr?l)S|@JZn%JsHwnVf@+U$N8u#gH2b&siqmEao
z$s)ce`4(t=l`K-r-^m%?L!CIo0lrO5G4-WI(G+njw5ciLo!cg+=<38NdbA9q?KltH
zq$J!O>>v7a2miU{JN)|AhCa+wq78hxsT03!xoATlhmzWcz74gaIUg%ML;Mzn--Zs}
zT;D#`D?WYU!P#hyITneX8viC&n)aD~Q93&39qu=4ygfU8X^Vu_z9=2^6f8=1f;3;0
z5FI9Xcv|`r4v?}F_<$G?Yg9Tr{6ay&&p=6N89%XP6)qlYO`~xLmW~|wXM%F_Z`g}M
ze=&m~=M7D?=@iP>Wf1TiFl;oM7J9lhjv#R`jlDP)Q!kFi^eG(Z8Gy0~xH>wV2-Z$5
z6g16tYCL(Fw37=pA9aF*ZjsmvYc(JCg2>{*XbsQNMPQ#4n`4o(Q~W!OYo_CF<~b0Q
z9NWydjL|^SCoXK0Q>McvZl+Ta2Jl7U;D)}1!KFkTW;EC@5_&}o(jdo9M~q5PFgi$s
z-L$H7*qzO&&nybN4Yb(_OG`7dA$RTw(g*^!|7_}nEl9(#-Ds`9zcg0E_OnZa#iPS?
z{6@Y;wDFVa2{%i%sgFlJ;LBd5I2-Ju6b@V+MjvJ$x4L1hw7l9S!KAI#bY_p#9gUBS
zMTjHMkngbwaZKXru=q44J7EsAkRs`Hwb=*U9%+gS3Z_8SfljkGB^nS6#JnsD&K$g^
z-;`{<|7(!-gV%)V3ZSLa24}+bA>9cGelg?gXHizCBS=9ob>dV^ogn8hQrh4|u>Vbt
z-$hD!99o_e!WCWofnd@7*W)3(+E|#hHXcdJ8TzeGIm0wJ%3;{?ObtqY)$xX0f#L@U
zDJ9N*>=%TDms5AFHv<y7bG;ppvPH=ir`NhWS6ufO9+ZoM74`Vl_%G-BF|MUMGy`Q<
zcJEjVY0I?lStkcN*H8Mhvc|fYz-8B+=s4$1x1t-5sxCGdR!kSA!}M&hWp?Lg?iAzB
z?JT!i@7&J1O*^-9kJb(D>TX38OHh&(9VX=<<zPDe9|mt-?|AH6BP%-edy~fB;fh=&
z@B*(SLw4k9hji0))H@I9oiZ>!o>`rzG(E|^^N`lP-aEL(M|kfI+-ll6h%pZmW`PHu
zF~_>+Tf^j}?zAp~awG{nj6XObos4u@lw{vVi5AwNJ(N&7Hy0_{S(IBDiddBfTh9k&
zS=<&S*9pqH$)n!WxcJddMoD>TQ@N3d7wt4C8ci09V)!;GBN-))hsHxtjwB_c(qr43
zi&bosQCR-QUAR-i>SHEVsx>j9C@lvA34tQ^Nl6E!Ndbdmvr+8fq;eC|mbMX?Ga8Jd
zZAWROk^6G)J!q*Z!mTx;wg9tBjpMw;OAP;<VqH-<HfsLo5cj|s`2IJ3o~{8F1<cFw
zb!uouATP1hXV;uaX(f0mA7`WB;jDshf0H~KQ$8pXyyWL;C3s-^SsN~;{;d6mjd7k^
ztI?RE&9x{JDw4MS7Q9;&aw@m+qJUE*q{4ROQLvgkyz=yDG@fjfsk1AOoEBMjIFt?$
zJ`c0@jQubJg=bla)gtgH>*>2}Fqi1uY;f7*a0P|efn!Q=^pbJ}iPu4Xs?}|PDYUu`
zJb#$V4jl*Wfhg!!Y0s(CpNnvcfn0=B3<S^b)NhWw;#O1lWDbU=58a%N#t)+xsohjx
zJIqAw#vbI2ya*i^Ihb`*f92KQZtlwTMjngM$F2{&DVx5~?jbD$jH0Q7ddHhUwIs*o
z>H#L*n>K@iQJZnJ=D90JixSQhDNqf06QyJ|xYwzO1;L<okt0UVyI5jU3$xQHrI0f|
zr4@3<r?kQ}A2u2>q>nb*Fr>7$>rpQVLPi;<*4r+`>y}#FE~+{-!n6y)A5^c~MMZ}S
z_?z+t1wBVb#V2+6c1?A_`d;&^o&hU;g@2!`nZc?1Yhq=u@Ew5lyLcu~v|7GjuzVMn
zcj}0^xW<z+>Fk8XqLo4qr*?6LC*}gps9s-<Mhd>rg2GOi5LMTyl{qOEQ%l2_DQ8eG
zQ!LKpD}~R_Mae#J^0fJ=6J{{$WjfI2yA%_cxBA4fb3~2|J7EFlrEXY&$%jg|@JP8e
z*oiO|J?Iw+J;?Am*o&j3LUd!aLtStut}Ge!!67+aeK=U2(6<KLv(tk{r#%Iy-Gm8~
zwi0B~lr@D}G-YvN5)G^}IX1&)q3tHJX=w1l;7r{(I9$$QB8uFaw3MFWB@Ns#Gev4m
z_Tcaa4cs(VElMcgG-<sewT9imJNW<0GPWrE76cQ{{sT5PkU9)=U?A-jGSxLi1e7_i
z!A^0M$*<8=A-iCssY13x=IE4p5ji^RhjLme5wuTcdJe6c_zg&e?3^n-2c5WhaP!Mx
z8k95~H;tvS7l(rP5p1(ZlCqa>&H>A|?ny>k$qd|vsnf`?kjUYI!I`UdsvFJ`B=M9{
znn^q|TpvLiW!i3Drfu+omJArkTN*NCKyQwikg~EjMoBeYEe=Ia*80YfC|UGZy3S26
z00h^kx(&43*gOY~F;DU?L{`r!55xfy{TTds`9ApZ@_q2z<^34RDc_tWjphx!_L7pm
z51rah--k|VZ}eDQWH^ov`F9%Ql;i|jNj%rs{6ve8Yke_zFcN)Ex|*2eBVQDfe9BwJ
zEFb!_BE=_cesXy&QgUBsXUE%1zO$9YlM6uiTI)EC<$`M+Ms6LB{Q~>x$!l;`FG}8u
zw3xJq{^&Pp^9@FhPxwsfKU|dbRMN?~5__&uZpfBS<zsVIE>imAb$oTi;~<G92xIez
zHkwb;Ynnr&_uTj;`p$JMb^6ZraDo4qKHMV{fZ)XCw-6jHKX60;^c4pog+t!tMZhej
z!FLFUoYIjI6vNRW(@(gmx%zl0^irMShfV)@V|17N=Z!`eIoaP7x!_kSP|Ci%^sO<3
zf{y&g0I#ltqCvS(L_kZE%drIwM0(KJ0}GfPlz|7U74ZR6Lq+&j1}_{SCHEQK&~Ok{
z1Vp0&rcVtRF7({uM^aLxpj6>Nu5b*d235$$%JIqJAgrS`9ux}uXt<s#G9)sC&OLgB
zSw9tU5=lQ9fuYUT7(OAjqh*q32DYqLhBq<trNNBjr}TKmR!M(QY?ZVH!_DDrWe|_)
zS8u5DirZ;+Z*e^hifYFFtX6(NZ+5862p&2>La2~_B$r-6NN)lHlp^6Lf_`8lZhWYi
zYg^#?Q&CS1PpFEFS`>y{L1^>QcOb+nDGI=9cmY?4R>RY}!nhjV@CfxfK+4bPtpwYI
zV#eMCgp;*2=2Wy<Gad`B2aMsdsi?J;<C8&8dW_Kirs%iG42qk=FHMdT1Cc+WXDH6D
zA>N9Sc&m+QKEA+C*ozd>w<x(h68IAusiFdzEriIy{2^!`3@==Sc~<=4YIj5%a&%Bo
z6~%b0%%F%0Wio6e4{gDaNFAzpNu~}}Ol71F#U@tJWjh%WDpmMoM5y%M6GnW-cQ%+9
z55vzY8k7@6jE+J`SEf)#gvwe(qvKGXabq~wkX>hmb19$|xkVN8+R_B6sMyFZ%K6C-
za>7id@Y+Smz*5)zpuH$UH*${RL{|_mla4CVH<FJ0RxI#pC*zj9uY{s|Fp&5Fh0(_Y
zZN?raPa>;m>=Db0lA*N_)I(`SCg=g9RZ{WMEAJ*l%c=TD-c5vNL(e~yc!Ox{_#=jv
zyS~rR@*FW{7}4G<>m@YW3I|`LIPMuQ9*Hm&PQFrK#ujiM$uTjin;x%4%AspAH>1j_
z2rf#FoKNOO>4=<%>3)$y2nE-{oSF)_kDQu_`9IOhcz?WH7a`>d@%$@Y=D}awm~pCf
zN(fklv84<c&3^?)vPdz-%QSo(;Yv_gl$fHD7#1aV>ZKG+17Zx)A%X%+5;G>4oWpdA
z)gD{6h0$`Tj0|Idl+rc~7%P?9VL&yh^bb?WlyXE27$22Lg7lp&*~Ab=bxkw|vs4Zc
zl6TaAn95W6E(W-Y%84;xQ6O*T04Y~i8|#KPsr(zGjZ!H(k@XWFQyiXM%<SRw!Wes{
zgdhW?LM09HCy`ThBqe?aSx2j#nN<=j02fs95(i%iPKRZDmQtX|1SL)x00b(x$^aQq
z`B%Z+JwwYf{lBufjPY8L_hmGJGA(Qo;_sC?wkS+EgD^05ODSj}O)(JY3X3q1!Dbhd
zA1dq37{;Z{xJAj?-Woa7Rwdn8=9(W{jvhA|68Vy{CHgS|h{=Jmm)D0geeeJ&aw=<W
zU?)=^qQPidxr&Bd@XTe5BjsSOBM3-!)UcSSsZ)F+idcD-i*k+1x-=wtS7PR(<nVbX
zGMA_lJQpR0?>bv16E+80nN`W#Z&AjUW*X;p{yjI;WQ5@Z8}^&BrL!9Cwn}+j6lTss
zY-q`?+*w1~cBR)Ejk`+0T{lwlNpdjZ1b^<DA!3@rNF4r31YVRjwoGB8Nm$v$Heu93
z%5hR6Nt;@jDM|a(A~H$aw1}~RBJcS?JJS7?8*R$c)&-#~ZR%KYYoAKNK9Z7O($=1i
zlyL2B<!RG!XOX9^>tN!!T`A*>l<D9u&Sa+cz<+0!c8LnJw1=)hn6Rm%zND%s1K!f8
zT{-fLkn_U<a0Dr^6V6MlOfV`X<S#<<QcA}Jkc1NZkASj16AED9PjZI0WXxiQkJt~~
zCIJjAN}x6ngJ2O7wBZ!@fxjdy1DiyQIN6DS5egBthyrYK`LA|-T0ZneNwkWlRRg*a
zUBgS21-y|QwubP*gm+l2{4(Jm7G-Pz5td2c2M{DybFo_PLqnutp-?Q1G`~s1t04~@
zNEQc32~|Psi49-}2@-><txz*;5H(^l1U3|6zc=&^gL^;-9foxA0`ag6YAl?OBb4v>
znY%g-nG3R=W0CebuH*!BG#4SRuR<nylLTGz3Y|aLAb1nYK*>TtF(j7*CFKBV$flC*
z7>QgINLwsGmPH7r2(;x`?~|sW>h*d_<e8=}d4$O$V40@AA;`p&C$QOM+_yp49^bkp
z@QiQW66VFXUJ3Fhv-^65CGyNrHwUwZx_J(9Zk<953WO)#cN<QR!Ov1yK0!Hc!~2PM
zV+`=(qtxJxDd3>>-pm1(L;%a8l|%r%=Yc8J2Elutty4nfJX@!PX5wWsaFhxh>4>-S
z^K1x82EPwMmKI^dU}CCg;WPy$PIQ4e@mbzv)-{B?7AVxBj14wwwS%9%GpsB~F<wV2
zP^5h8kswlaJ~V(x<-n2MUjSGJB!EK5f)OGCv<$ca1+Zm^xCIE;0n#X-t~7N#_Xg%g
z<A?CR3<z}v33dd@Z{mjGk8<!gd*OH&`j{cQx6sLKoMb+Yonf(A9}~`5Q2Z7Unjs>%
zpwbM^HNdGIAjPx*xMqVud36@xnvlVg)+8aj9YIQnI4PauEO@wOk%}1!LC&0*c#KwA
zlt9)Z5FHI$1y*McEF$6Ag)uC?E42ZDen$c0EmF>LvUS>qs|OQXLGLX>PFaEN=0wHQ
z^7{_@7q-0k1`XW?k7I!c!rpgm5QAY9j4wS~w_L?%>z0s+T4@KQBoPk{UoA{T+8+xw
zF(_k4Ry06G0DkcRX|aMfIi?{Oh@)Z31@yQmi5S@#xtLv~0XXhYS<?)z)q<TggpD_u
z&Me>)j}5=l08&vHmq9sq9880Y7GRmA5Ki*|Az35c&Vj*K#xWR$0p1BpaONhC*rMb_
z^&;FTkA@T6ny2J5PZT1K#t%&tz>xW8qmVzq^b@QpjoXaczz+oziH}+Ysqz_VPmEQA
z%ohwRD8~lXO2c}gxd!Fj5nqckC^>nh9)%nmqzzk^ZP@{R3XhhOL(0YZ#mbdwaHABX
z5{&lV7)8p)sKlqei&05<Hbw<LZEZ{uZVfl=e1-o@KSe<V2W9b&Ai_JL*b+{+LL(+A
z(TWYJ4~1r26t77N68T_LiVsRz6t1!;cdt(>gpjR)Ks<f!o*Q>a*|@QWeCri1ir_Xh
z`TO1^iIk0Fi--5KaSQ~2nsF_jb7Keyn;5JGeQXy4P-qCFWIVQsK@i$D(GakwZE`@$
zy~}Mz#M-CeKDEzAv}%`)2(vB0iDT<=dgHaDo`1H-o^6lC#(efI7W?@bJFk+o@3SbG
zvv0FFCZ20QTtMk~HS@fAuI+FMM%){-LaLs7V-_jNtT)rI2(&ic4Iw1YvmM6k-&Xi`
z9mb^8VH_gW%RYh=dqsxVX}lJ*pSGRGYc?z9yiVg-x<#tnYJFuzv)664ezKRb12<7G
zgNGwsW|8W;x?@CRyRPmS(b%r5J4Q6N>*~o7&F#8BV?=Yi-7Q9RZMS>!=-O`gWj0<E
zvgigw?(H&9hTPj_zJ|8)6S~xoILH@iYCypdJ2#D`TkXcwY9i}F!wX()1`6m$-E8X?
z%qSDZ8cCTafUD9Krw*;`2+~ER(c;r}<Hb4B6`f55uq(-n3gRkmA|)Zu{f-D`Dw<u9
z$5ckU;)toRc18goU#ZjvrL^3f_54(gyVVo)jF$B1<XA6rMCyTE;jL8B7lqHR6LY-v
zj7mlSSR}rqPRx;Aa)vTx;z7|B>d8k(Z)e(0@@3H#qsgaBSNJ8LH(imHd;#?)G*3R0
z7U|<D)te4tytcZ+8~Gwzl<0Kin{A~ARi9WQ#US$O*PGTpUxvN8o>7*TlSQgtIR{s-
zhB?SpfoEz*kRRT$J*^M>J2#T1)F)>!)n{bp)!3iYeKS75jn_BpL&G9mTen<<&G-<l
zvLVFjk%otZq~Q1SX+-EBmWPm*56eSH3@i_2ujn#8z@*VX3=gpZHp4?QcQZaXM1HeA
z<W1R$6hbRZ-)s+g@b=C2u=eiC0fZ|Z=APdB*5}GUsV+IXGCw$m=Vda?H_9Th+raSj
z422o1_cBiojIXZdG>9o{@+G5LWLBzM3~_GXiq-9xo?ByPzUH|b?|QG(AP$>I`#fpz
z%dy;Br*Q<K`XsZSty7HT+4>~2^xPR&WT=wgdAD~jX^1my5!4|E;*y5-TI+6GkFXOl
zfi_8N9Nwx+FvLp~aA9uN2waa|!jQ~Z6bd*l!!k+W^|um*xsh<QdFg4eO)nDnUovr}
zBeUBBPVjKZJISe`AFz@~nllfFCpa<HBLu^xaKjGY{n~n@>VTB%mn{0s%6`e}-^+9X
z&p<EJMfeVSU`^7OkRN}xKKXI^ui>TW{);1{!!&ff;OqzrJLTQqhpvn8nDjyKNqlxl
zLzqC->O;<J_+|J94Ih<;m#&>&1`NEHk*t4!6tX^OugV8>SIiLoOnpc;;EU=wnZmDx
zLsT(B^lJ4X*@%btf+nCx2qz}Of#f(_1g@9|-a+}|LXykm0q-0@6JB!Q0a)PxDQ772
z6+D5xqK4ot?1TQs<fIObc-kL9A@2u1q*DWr{XTe)q-V1aT_bq@_o0wzdPw_}#-C2q
zj>@C-vJ&g!B`+)hF=7Y7SG!1LOrDvG0><D#DkBQq!hJT07+(Za9xphU`|N1tcVyF^
z@oy3p95u7o1fh7BNhSQ?taMF3d4Q7){zx1uvjhd9fqm-n0FQj1jD>*HzR#)oK}nr5
zcBbpUR~aCN2lS~c1|bB1X?Y=%saFIRf)e^HXDA{U`qU|sCXYUehRBeJMZsWT1X&cu
zqAblzp;QREAiB+qkr|1AGZ?)QhxA2JU_8gMNC*;v#&c=mQQx3nTKI@{T5XO5wYM)_
z87Rj<FrcL5ujpYP;V6M8qzIN+T9&Ii6x7l$89x#D(k}+agtT8$9S}Pc2uOQu&5<xk
z_)_kfi>E*UDlP0K&Uj)ZGM*vKXHn>3M<`Ig^k|G=p~QiDDVnIW_A>*H`c<opsJwpF
zGDH6VS!`3kDt-o+red4YM3CTDdlXf_^^!oSRljvXARMdTQXuYA6&7C%;5q`E%M{ZU
z?7n5;K`2<i`KUy+7*W7pimy5XD(oaFWZ~9H5RqxC&7iY<YTObIM7Avo<5Up-7AR&I
zAMUGrpp{dm4G3X&i@<2Nj+5fn6%z4!fw{(Lw-EMQrvd{0`YoFfEQ0`Z+XDxQ`1VqC
z;i8atxM*%#i4dgN@BG!lvC&VCNXK3#!H9(<Qr(N8UIepyDV{PA@9?(Dn9Cq>{J1kJ
zLJM>2kNhYI3R@KM9~+=7i3k#16oyN}9`sOYMXc!}<U<tUs9lCdgsd*SKuS>D02Rn}
zKM63nhr}KULWo)8m@XqCCKBL=IUxkzE{MdU1dsZoYXhNTfzJ4llH=D6fKcFt@|aUZ
zwD7TjEiY15Col6F!jApa-a=@ySGW-Zr4|S$S&j(jK<dPx(?~)%&x(=`$WJF_f-)I<
zpO4JI302f~c2hzEqP7EY^dqv{E6#}F-!7{hV#EW*l#$)*t-jh_e{l@~pGNF`k0yfO
z^PKSW`l>MYg`?W|&&f<~Bu2w83S82RrE*#H7*g*FN@CQ#pOt?wz=O&!M)<x1b3`%z
z0U*oy4e;R64C8_c%-PiEGnv2{x`bo{533-P5dyGQ=?TFCQ~vIWi-*v+mG<DK+&0W@
z!RK-fb8arnA#yAZVeD2ShMUq4LM8Qt<cLHLFWd~Idbl-;C9^@iz$;+j^a7?pT8S6R
z1jg;A(s;~IaiBpUg(cb-3BfldxLQl(Vtf{bExhm*kVE5zr+_heVI?3LXCWyw<poLM
zE}#SRtj&uLd2(oIdXCRbP0#U}S<}nC<-`vFj#(f<BWDM~C8Op_UUIuM!Ay2o6s#vw
zq80@#x-c1~-XN=Lp;+^0ki<=>YvpFeAK`ay%t)!9NbmAWl*fO$>3U%<*&?AEa?KW=
zH@YDo%`0KOK^8JPD}N|M2EDS%Vc{ga_)8gbUMb{2H4jj7oCQd=^U4?xX!Jxk&$U97
z)uLoFUP_cJ`TJ-vak|2|m@Md(wvB|sMX5B!_>!X$lk-*ylvur136xkq1$8kW(pzOw
z##$eNB##;4K506=k!iUoZOg_C0*Ct$!=A~WxlWZ*iR-3Kv~rD<Q;CdGuN>+gLDvo|
zEt5`H8$(B8s>^bV?9~A6XP#_s@}>$;%z^dFnMR(hSI#tYX}xhHbguiwI0Ob)t*Qb{
zl<k-z^DvRw8-)n)DaR~f0X&c)ya*Q)hI18#Fo7&%-?F4fPD**29oX)^B}Gq&vy!4G
z)=cOS{ffE^<WwF5-f2i=UbSyo(s>T}mL(l?^)B28*fv?>;dm*{+qX37d_qTQ2z1Nq
z&Aawvhc?oo-7(~95tv559xbcQBzlNQj~_r%`zmG*8FOSYx`OGD9nXU2FD1}>B~2sA
z-jy`%I2U?l!y#GUJD(~{=wB3~1az>I9?k^{uv+<}z|;3iq6Vyh3q+g|Sl$biA@z9g
zN}_WpRNjRq1fT=2)arEHJF~0d2lrmU3{zd0zzxs^@4o^wtSTV<IP{2KzzjEfRVr$L
zKrF&Qi(U9_+ytG8sgZlhS|cw8X&q6Jgt#FT4yCNZ&E~T56ZT?JKCm(Jhlpfi>PBn~
zh=@)Zz;L*n1H|e$T$uR4^H>A`t8{eIZHrt<XR3GlY*2|MaYGzZ#bXH07O&jzbftI?
zzQ9AW3cWz$2Xc~Kx#2)TSp<$_s@Fg}KcdW8Bt3ekX_}xcQBnrK0>z*|Xk`zbS#S<`
zf3!e1$0jHo*!f){n8cd#PD>{7XcmPFgz6n$Iq5LK2PI`D!Ed6F4nzjvIId7m0O%Y+
z0$7i!7twl5z49+`UQ{kSEZsrDos))buk3c1v03})Md+Ya9|*1JAbn*zhel)xfD^IA
z(2Mv*?zF@b<H%hq4N#DxQW36dn1NlPrvO+A3gkO6m{<hqC5Wa)u?(jpj+4_tM5w1I
zq=X;Fo5FS4!ffdk(@I#WMIzGCqi(qk0-S0!Ibd8BE*OgoMP}S}AcrwEibCZw!Ia4|
zQ7?gMxeMq5cw0ds23cx;ixgu)HB^^Fi^yJHN&i6qT9kB|10c)`1pp9YE-x5y#@s{S
zOBga1$9fT^>_`$m<Lp5gGF%R>a~~$npx`s9Zym09U&5@p>o&NqXaRE!ih>tD9Cmv`
z5+s|j-F*j$OVQKAD6N@`zzIB%s=Pgpm!Ridk;a6lbCt0ngk4Z_QZOz$9DfIq@Vw9u
zfR*QpS0<pI3lHJu(&}Y)1JjA+(q6*ub7y>I;`>F7HO%wo+Uh+AE8pSrJ2D8+ofvX}
z8g$qFbr02YdkL!0GcfJ|iCyw1CRR$f8z2(BKpOy~=nTU?gth2SD@s}wy>K0n#Obc5
z<;{((JMl)?^{QC+5;CM06vUmoSU2X)U91->;3nNmdj}?^JMUG%R(jz{q<zp`7cDA*
zxGSoTfS4|qEkQG#C=`Izbl0Qc=~=KZN1HI5hidq}1lH*VTmeAOPfEvd0lS%J^ug+Y
zFQJLL%isjWQ7;G#ppt%4?%c=>!6n|Q%jrx^)K5zCPdY>5s=D9Bbm;Uhz&+rzx>K!q
z@ZfVH@F5kGlp}#)-Bt1gK(U{ciSgz}Cg7~gNe)oj;}_D6Z;!9Sw%yw~pHFyPXFPvl
z=(^BCh_m}iA*TqC>*N$-%8BReP7Fa}{(e%(7$D|OF(R)A;tRWy7>GgqNxAalH@J6e
zTBN|7?XI#5G@X4=xRfbL3s(7~rP1MV2Qc&Y8|~CG;nU5;(4vr`H{>CKqPIB#OS)JC
zV7m_jnMVw5=SJK~WFJ-v&`X~bG8F5Z7~029nVJ@1wW%8Iln>#f&1JQZFJgXg(u#nw
zouUl~sc*I4a%UU_Am27i`*p_w$$Y2u+G0p3BtUwR2%ugk08!TKlmHO>PH1>J>9irB
zyW=<7FGm(p;Xf&Z$K3H%Q1W#a5^mlVNkdF}ouGuR=OKFt+P;om#)H*i&3Ldn(HRb=
z6aNs>J}(7A@#`ibUjKI65YxXdB;fuZb!o9KKwWjL9Z=UH3k=kS$sz<t-l!~6P?s<Z
z8PrA1Y6rT?8PDa+H+eClt5gC;bd}n`QVS?98<Z~XBabXvHv|yHst%>Hu<}ExG~G+d
zNzV8(`AI8cX^B#uSbn0^E0(Az4XjfoDm4wIE=rYSH4JHcjNU@sTTrMp;<3cS8>L5P
zX$~rytlUwmXs0nl>S`1K$+3|Mk2+yXj#HW^7%`~#sAAOsHe0FKs8`}b24hK+Qq@`Z
zMA|$<w%p~=W6)N;2oSUtl<d^&VSz98dRUB>)nr`n1Wv;BPQYr87;gR-{#tcH1^}??
zmBjipdPuQAO}(`cj#bYw*0~AF0RsDQ@E7}FMF#cTt`(tv+X>aj$~^VNWc8kUhqA&?
zy;WHTh>zJrg@WqAn*msQ6Dt6#-pvfas<$;N7#&}HlD|~usGjXv2&vxntd&%6f7Vm-
zu#2(=Q%aud0?e*n9H6Tg2k7brvma|f$%4TWQDx;|9jP>eu*_5$Nl=O^4KxsF)T@HE
z1r&CJ_+~&AO*Sly1*6UZ68m6mH@k3Xw>puTG;2SExIh`NvO}@bR~f5V4y+7X2)inq
z7s9S~!x$@%mGunO$;!aS0%mD|V}Uam=(2iQp7YFr?zB_L&c|A6v;?BqTA2zFg0-0w
zS+A{3jx6eyCP@~3D~lxy!=+I(2L?G%EHx|4(KN~$bY(ncojTc9kE~=@23QumD=RGv
z;*}*gOXiiS7e)1UdoW7xZARk^$||!m%lDP(nI-;Uo<2ZIv$Ad^+A(P5W--AsgtOov
zP2~ql61r0ES+=n3?JR9rHhEM(EVDfdBpx*GgVbT}=eOzPz>$B`!{PciJsi%5B8ob0
z-iTH7vAh*53RxZvmW?d02TDsG@{F+jWcf{4qOyD|EMr;z7ZkeOd^D(rS$-TA%q&+A
zL#)ajlw~)|Uv#i4XL*%ax--2_EbUodDTY*)-wH8RhkRQsB3j-r)EO-Y8B39t6OGkM
z;b}WS%0<&*_}Eu@>sDY?vU0DRN_Smu=*P%@9du6~99tn(TpL?4Ra_f#NwU!EQEp3C
zgDux4E5^$EiJG!<kE-e{T&M>~eQa)4mai>O?5b`{SM5vHZ{^KJf!t&B__B&_d4*YN
z*Odj7wRp?7%xb;xKj+vW3vyC-BxTZ#-Lo)oxw%<4xLn~XE}Xt{Rv#{3I_nd=pv+Oi
zxcu>`a(tA}o~4k>t?$6JD%XFOPp;qq7Fb3A!SPj9m@CQvWtz801eS8nPz4r#u1E$H
zhd#D&2gaObrTMR{GCj5k309%5FbYPOMWDs;rE1ne$ldCUuTpfzDt}$U8>o(r0FN&f
z&_1>(5LVf)ND-Fdu4ocg^R6HimHVzp71ji=Xckxa6YqJ}8LzMy6eB;j*cpaxDZIwB
znpFkhFdnO-bWj+bkvzdJ)I3tO4-2fj0GC*Vy+VXoq@7_zhYGn@m=SBeGc<|S;9ccV
z7*bUcPADsXY++EWJYSJgtWK{$Di*M>U@QLOQ4v{=nkyBx<tV69kzI~rDHZ<ZD1~xV
zd|2?M;>R2%Oc-Fcn4Qr|UDJeERE<DKCDRIKbE8;DuoVf#TgU;J?NvT+k#cF`N7`8-
zcb>&ODku+;P+R1lHz3<ocwb2KxrYE!;wwzhQB0#^39*-sE#T0BUX=lftK|r2#ORu0
z9yz?Oc*o<#BcNg;y)kT)wnT4?+f<$V21`2wFb|zj6{Q&m+qp+_I>4<E?im!uZNf8<
zM`*@vLf7QEn^C3S7_vDz!>OoM&Ja)q6}Y-c2wdeXuPyS`v%~|UV?h{<pFKcG9_T!0
z;Fbb$<JLTl(Ym1Apdja(7j%XF#w|Yf&|u#5h#y`Q<eDPJ_y8$`U>V;T>Ps++FHWav
zk@3t_h#B&nx_3rXPj#Az1?R2Gr$U8S#{(mRsbMn7M@o{ksrw$tz1~hM!d<c6-Wlu7
zfbjL&%d{j#jK{MwhR0Vm-=_*Y=Yy7k>2%R&<oW^1Joo5!KEW#jp3ioK$%B&N?57sb
zBX?QR_Ao0{K)!ot#D2CEu#Y)ABEl>3pT?BR4WLm*=>xRjWO@OOKAC-RfD(x&%21#Q
zs<If|hg9%rF;{{E9~{`!=!eoJIC@BraxQ2oti%l1ACF4jpcylBI~=*4mHV;mt4I#X
z7I@~m@?a~hBoi8zD-DG<>`GOk^_)+sBS~Y+fq|c+(q!m|sazU&X6Tr{^l*YY-@Q_F
zD5Ol$0eGb^yaQzYI8sBA7j%FWzo6tH2g+3?7<t+om6ha(onqRO4@8;7BRb~;jJV2l
za_013eEmCe_?0o`46mxRDhCLj@~)iO_ZQ#k&U}02YWZOH*{Eq|`k9W|!Su8IQODRM
z8pCsJ(i{eoh${JPkuq;g(!u<8rLg&6wwZ4IG03c@c@K2cQL|FcnO^5iCszudGkg3J
z45b5+t8)1kB}9tpem(&7GNqUfB;O!G@JLeZnOUokq%>t3I#a@@1OgJz?8GBTnfj?)
z8K%|Bb9AJ-(omO_Omn2U$H$&J>4Q0$IzE`$trW~fi4@Gi!9mz7wbLgvFll#Rls2{$
z(M8D7rd?#UGnZ0U5NDS5)P>3{ZKbO^47iofx+uw*j@H<-VVzmoN||-ktgp0MpU7fU
zF0M}?YFEathYh%LdL5r&)~~}RTxr4n9?_OJ?8>*60;hayq#rxdt@UD=$a7N;^WiWe
zSE92k#ag=9#J!^QX%DW`q@V5FG|a+wC0OemP=d8?4J>aZdoN0;pG*jM<ye;_Fvq$?
z0ZG;_KHxSQn=DM^tCuVwXKs`%K)qoeyu+qVx66^F<Y3!+B?G0I%<GGyfgP=UeV?f0
zSXup!fW3~fL!%NVfCJpEa047Wv=ba>k?z7CaOPkOo?uZD?m_wnj)G2){vw1ipnwoO
z&yT`NaG2T)Pr>K2;Vn2K1Odu$fRtaJ)dgS1vy@5N@-{kZO$Z?32vWjKKrXIx1DJ4T
zYzu_K^H2p)1qkteFEk6sQCx@@&ctqct^6X=17!jpfTPeg960ucz~P8s6iCM+Bo}P!
zlw44W3y0@GXdsJ_e2{i};jEEQ#etgFohUSZ0R%$0B#zj~!Y*;<kqh2rQDQuVK*=9U
ze3pCb76THL%Ay2+gtp>HKNlj)`XQuK60;>JIU?O0%t)8TKPb;#@G$v9Iij(3OT?J5
zbqk!9v3)BMV`z9k{Bj}MtUrJfEz}#oh_@q~0}6W-c+R4v!qFufP__lZvnV;bw)Kk9
zwd#|DGueaU-=$Pu0HWv;3WDv(K5!9i=iEA_u+yBpC}RUJa%frwaI`4bC<r8nuV;fv
zTBHPm(u3r}u_~-3hn81(OpeTa*m#em1T$sQb!dwP{^TfMLU5?n&H>9j>rCkv#Py;i
z7}QXw;I440{JJ(AE586aUSL-a=TsqLElNUf^{rcuzi+)#7=*sHNI3zxITj(ow+P|2
zD8cf!^~v$m>+1v<P>of;?hQ@M5#L*gV-81Ip^`01AeTh-+0{yHG(9K~5nRw`9uJ2E
zMss2n5IF4!QX-?(F_1Tf)hR&4JG~|@!rRe$laL3;hW6$cA?{?cK`62S<AU%!8>ZZ%
zv_aUp1C&@Fs|%ta?kFmOF9dwMXbmF-9w@2NSS>pN?rPbAZ&!;>d^;^V@$FRIZjoXa
z3E9tYz!VAj&*6hCbiknay+a6kR>moq!9~cWJ-1%TiIc507(p2>%90FaIR{}4MUaS#
z5*x2<d<2L%X@$6R1RL0*Bhb458J#E+0&NUR3`d*(HUdB91aYyJISzi-f{=8?j~C43
zqAa$Yf`fHpQwXop@j@?5ONYO<a4$XaD};=B1R;haO%HGX!q{|_6)GG~2keEQIu{`^
zjs)ll(gynJ2!bzQP>1DVQ3l$HE&3F{+6Fbs7Wo9!c)^t}N@9=F?~vddN5P(wv_Ydf
zOd<uJ>RC6b09Hj%@!myA@LAo`H&E{h=2`?f!QcxAC~Pid1Fo!eI8pS*zZ<Y-$4ARF
z*f=E$zZRqo<JN&PQaHFpvEo&{$O})Gq{7^F`0fjrcc*j>ccIa;F5Cx2oCz>mVFd4#
zp)ZBF+&AI4igayr4+#=#@lL6UhE%b@)KL^^M|a<lle0zB=zsb8PsiHl=lfURQ@q-E
zli#P?dENd#T)+PFfBgEVFZ(**|C9gszy5rGA+0(qqhx*IXCCs4l`eS!w$n=VZ#0#y
zPnxV?hofu-ff--nYh6oG1#ubtWTrqM#1vQ}BRl{NGgEf!L_y!C3dDI1s3z_iMR!Lp
z<e|lQAmRul@65_F#MDHQ0|n(ROzK?Js&0alcf(~RVw_iDu1B^$B3{tgkKrLgg8q@$
zvE{5Wzi!J%V8Ab9-4qQy=VzpopG@wej@A&CdoF*u6EpUbg-LJDr&OZ63LW}R%8!rx
zZvK{=_s14k!kh7@J=1<8K9@3<e(Hv33cg$~wmA9ZmqQ5vyW|Q(swZ(k%h_MWmLm#o
zEvsC@#OE{<=0Lhi4hmD4cueJLs)92GCo7^2)r1SxsH)cmF5(TbCro1s#a;vgVB5D!
zCP9-S)E#Y4g>XnkK})j`Si;Z6BD%dP4uH9b2>0j;6K~JG=bM2g*GJ^*RK(a<23>T-
zF_il)z%S}*b|`O`9uNewE5ii!e7TaB-2BzSvP;Hus`c9rSE9s2l&;J@`=$d*5K`J!
zC;vtMe)A=Ysi`9=*S8%}B^1*9Q;%zj_iqM@O>o}q#$Dmxbwhpyw#v`2pnvS0zwV|T
zHrWjXVv7BBH~59Q4S&kJSsU{=9Z}m9@!CJXiZZ|J*rCO6oBzz1nU9VCn~ppmPIN5F
z{I(;^x;#dHX8h{M!Sb7qJb$J-g3{Wz9g(uaW9p|YA$4&5bw{3W=cA51@y2%@m%4@D
ze|Kt#lFBpjHytLw6dfkN^4ku94$G7EXB<xZN&DBG@;F97$xj{6--=d4Fk7D4KNC4*
zJH!9FlMZ@AC$_KOce2d)!)@?0u&nmm;jh2ME5z6d?dzLPmPyRKXMVEAYF#|P>6X_M
z&b*&>U-`G)#{9U$epcB+-D<z-h|3QVDnGyKIvn42WL+HGkw3p!{<?0>-+YmmtEnR?
z*S8%}YMyuSPa){nt^AvgxV(Wp`E$F@`}ZAh-SKOfzTNo0nOhnd*dc8*-*zA-b6&eY
z1H5*p{H`NhV?84Wu;A%gv2Q!l(gwBUXO`3bP*nc9qx6}fj-cH3T}PB4h1&D8K;HVd
zdk(tN$xdj`?>Y%-sYA3HB5q2>`psEFP3%-hQs%cE!E`8Wap2t_l;3uwrswL&q@eTL
zj?ehe2Y;p+<U>RJO-Cw{)P{=k?NEEWcYQOjwhsmLw>KLQI@k?_@4v=0owqVu_janb
z-`?48PHy-0n~T3!E5?U{{4)ZyK2_%5bfji&(nm<SzU!zcztq2fMu^!)_-!|A6jL`4
zu5Y^`2a(GC&xjZKRQG?=k*@-0M^f(d+m5q;JRW|ADdF=u@tcl(bqsX`<@;02Q74{{
zlQd`iOP(uw)tEZYU##f)K7P*iKz=`qZ7##g`#*-;st5lsc^_W_1zE-$6ev=S_oB#l
zP6*s~$#{-%v3AKeexp3nCEK_ta(ATN=?GGNKa3t%*}1bi(`9>uUaXt-+A0cSBMtp#
z*x}~0%^)d=hq_s<?N*GUNY^%_FbmFWn-M9rmQ~3%M!RmLnq!!*=Gb^lO3gZ~pL0|z
z?KCv9vO=2|D_T~vyTx4)iVtC_%{UP<E9`2sZ7WF%e>PsBv&m|RT4yNtoO6t(*b*(W
z1f_AOq808u_J{=qN(jPu#1dG)hI~+Wva2ap#R03*DpchL#@fQUqB$~E!$7{$h+;*C
z+)Ovh?hd(`Zp8C8y%!znPHo7$c%u?;#iHE#Ukm-~)`%=eB#&Z(J_m(7Lbcw}#iP8h
z7KJ?W3>|Ajp+`5Wmk)&=(Q;bxB><pqs27x!!D^Z0QB?UIau)-~y1CrLF!naDT@`}Y
z{3&5V-Cx-Z9g&&MxzA7rScnE;k*VO3G$J2CBC}8x*lUjfgFt-0<r&kMI`07MZa%k8
zX^i)|^-8^cRIiaReV8FMb|rE<^5_EYk5lYmgKtiuU(AbeQnd;-xlz*AEBxrDxwqUD
zC}Qq(RIs3Jxhh!DwkZncW=-3sP9saxs!J}UiN&aU?zLSLSCX)dNy%knNGjeei$HFj
zS!%buoKIHhrJEY{Y`Y?k(m=Eb^i-o%dcWnVM)g|cwH_cX0{%HB)32>VEQiuh=?!k7
zgV9-hv@YiqJjzX08MvK8{oZ`l1ND;S5s$&E-a1|0O+h5|i?=O~1Z8MD&u9Su6Myu0
z!51%x(wE%zt)fU!PqtTl(S;H7xqLXZrB-nyS(3fm)+q<9>=OheH03fXY9TOP2O|)2
z$miBAMtp9)V#Mv)Iz=FL6zcv;`)rK3JzIcB47lmAK=ejb1ZVrqzo0+!%F^w7BuPj_
zyVND*p~=N{v2yz!M{;JdbOw^3_NM|#80pfK*cZ_;56Y>tedb?iY$L|zTbE#5b9HG$
zsKZIfp;bJ=$YSt&AW&40M+Y4DO`b}G6E#2@GvKJTR>NY!cH257lT4j*9JYNZB(9x0
zXb>~CNZAR8aAnaU@M^(DlhdfpZjbsz$U`7XKYNfDQKyp<qp@3^(kxv8MKl&&ilx5N
zLt6Q9h~92?ZM{YUX=6LUy{yQR!!r+mQL0ZIds}D;eC)C}F#xYA_3Z*Ebzp<5*MMog
zg7ngR>D4P4Q2}PT9LFN5SAv$GibRYrS9BS!jLKNMV67r%dXnN$GKNLwcWvwP=^exK
zh&b&@Np-D~)DVy!c<+kp9MP^$$#6*w^l^aAGdMK85)c{0m$p+9lOd?BQqCsIfuFY)
z5^lwS%2%(LX2qjG)d%K&Qlf=OUkKMS05MiNuboAy*xeCr#rftG)7?2QOiw5^^3|x?
zf&&v{Q5ZR$Pn^@qejI}=q<Umra&(dcnXXutO-MqBZsmoc(A1(ZUM}OL+bQKAq10K-
z;iX{fR*7SX$6jV-GLi~zMYtfa8@A_{V!xMljm(5vdMbqxRl33iN9N$9I`vSPFt$H>
zC*V0Bg)}gr@VhSpb2|~;ZxsqNlP!zFxcFtbe#$f5@gd$dhr>wC(jTvg$d4~cX!1U`
zN{|EOtW|K#M5gE>ahm!1eN&>92Z}v<9U{YEQ8>kQblWp(hIxG0qw5EG1&hLTh#2dh
z`jAZF@p3qxXp2ONPCvjCsSo49$n=0m6+WxDm=PFCtIP_<F&>Nzw+*0pSeoS(DI~dq
z(mBSRV?7lKJyLOclhBH}-I9WlEe<Om6jsS}gAV;lrbF&R7M_WA7Or`iu#-Pg$xrYM
z-j|NjtRrc+vL6A1#9})yWeV9{xlRMWlmBugDZ5FRL@tBfdwx@P`z66i-j?H~w5Tj+
z^va~E_!;VwK!dVdcLtuEc2~X=%ma2;zEjUiOyESuK4m?p*I$HB;H`;Jlmnz#_DlKm
z2zaqeQB25iSQPR+0%;JS8c9kgJx*Kp+?wH4`HYastMVCBFj(JfNjl0R+oj-g&lc14
zQUWj8Y~=T@e8xL11a?6uL{@~Ap$yhzyR@zVzOzeq9K3Wb^|S+|n50g3AkA6jts!~B
zDsK&#a4h6@yqI6PNce-;G#4XLk)ml=B{>d^uCg4F>uFb|IgT8i6b8>0Ip-LeR0C&(
zz^Q8<&u6RLH{`7v^pTfRTi+D4VpS()jOnp99}Pc+dKC+NL|Mx?WiiV93#%MA<nr1q
zWfJIFHub1Pny{6f4{v1_S$w4@WF&=A$4E$Cq)Jf^Nt|)g1E0z!1PEAESy&PT%#qCy
z+NnbUPiIph#YBj*DJ?Sbpe*yeG8z2NI-I$h3Daa#yT3!$rVe=|PO$1}QZgoP>Z%5C
z5G%VTCD=H$zZoW1cDKx72#+v-+Ek7A7117R{mKT{&nWmyi~}$X<%VBbXCt=L$T%+W
zhc0s#{8;YMY{ixsQkxJZa#VZ?-6gAL^eZ7{q6G~p9+6h5UTtQ@Y_x!s$I9DDibWiS
z?|=xzQTPrx>qp@`;B;V(@+8?7;_^!Hg(ZTnJRcytnBwaI+j>O(b`WB@6+h^ip1|Vr
zNf;_m{}POZxe914CsXV^#Rd|&#mdr$gawo1oG>lsD(U5TaT;(v9Yuspn4OM7Lnic1
zM=>HJxaJWU95Dx-?!f6VfnYk`po;?b0q?^ER~eO)Vj*NS1aOEk>&$TG3p0}7Ba1==
zl`B-DN=3_r2NQ}rK~5HhxFQqmqu>H7<xM!y%<oEa0nf51oO8ZWO>l~UXE9h510rTM
zr3)ZnzyxqegcuW?Au(jEY>Wo%IjdZ@M4nj$98}h$l~aLET=qtU9hnO-D`0U(lK2xR
zm?Wzs;7?4oBpi7T)*nd}fO{4xz8)`2+hSHB2VKV$;DD^`k}MTxz~3XRkX72-c_Xk`
z(ew!eZE~#>ohV{{5*7(@!DYP!Fv+42n`kJAj3LYe-=0Do!Q;^cbjP}YR#|W-)~y#3
zRW4E<<{=FyF3?`MQw)A9<f(?w<6Uv$0u}rmOCl}`Cy|x|tL!<1B%AQ&0tG96x4@`?
zwiuCj7*48xG>sB(%L-jiL3cEk60>Vj2(0_hV|n#Qd>j+~%apqZfG`7o@`32pCqG71
zGzNzWrw(NyjfU9-E3-~*8gOPu#D?)ph+FSgxM(RCrVr)QqchonSZmgek3!<HnGyrv
zlxPXkEzTHa33g!M+lE5t`D<1%bosjOr^b(`^oBy0Of*)wA}pOHSj_>_2m;xJOQk(p
zk~~dpgQ<i5(3FvilB3oHR1VyhML~f7gDV7P<v`~<^H=z#^N1#410fxatze>z&WjR~
z(F9_BL(RyH#sj2aWx>{=G=nu_O=t0j)yDjQ$zlxSITDm5#zH-_!$H0%1T72|gfMn^
zXj<Xe-KdRhO*okMKo?>%LMdqi!G!<Onm{n2#W$4&?dbtDVcP}j3Oa$c@VZ$m7|hO2
z@$D=<oJ*z{aU|C)3O<gMj3(e?Bs*Cn3MLRuOz?LdNnVR02+nA6(zrfap<v?rXq_*W
zHz}H6H4^>|HhLnitTtBpqHyqtx=@PKlnBbqj5h_X>>(uL3xYv7%nO!^1mQnGVkhuE
zBdZqy(}!=w8Xt2Vf$WC#(shDmj;}QxJ((yR6pm(~7ccXkDa%1f!%@FrifDov#^col
z&et;y+nRtgudYsH4B*(Tof=PrxStwNLpPpdu+m%8Id-K2ei*zJ9l7<Z&2=($!aAM$
z5Y7P@%B=}hp#xT6MP@UdAtQN$g0v8*nw3yAANAt#kXCFnoqsS{n^JBAhXuWIg!5t_
z!cqS743rFeHtO!gOEF;-5-`Q&ap@D;L}ofOCth==Y6<}yvf9l3>H1-&!!-3F>g>c)
zneaamMe?RZ%g{xLpa>!{Q&oY9`^-$oEg(`%K~NpoFJ^!xo?IuLzKJnoiI;eQ5|YmJ
zV}gX63bA(BAx*%d13TC1ghu%^Ghr74CS_58g?_0QvCuDd;ub<FHv=|f0H`CnpHrCG
zO1{vH$UJD^v>(a`2vW2-c)Ti2aQwrO>84|UFi?N!1Vp5?nc(*m4#fojNH`ReSBz*V
zixNitB%v4QgA3ktThNe5U)mzXy<|f&53sAsIOwP_X!5rax8Ic99nk*KMoEE(B2T@x
zqt;1Ka#qeQ$v6(;o*0tEyJJVnbl06rty_q;J9_%MbD?!D(N1T=F=Oe3MPf09!ER_}
z7u{XU3TMLOXVCytvN~%#7-2G524WG&11>dnaAKMq1}x2vr=cn3eNl3agaQr3Jd>-k
z19xvxcs4jUu{3VyCe}si+{RMxJGOC0BaI>^WgpQcCKS(36PeLz-Vt45Ov&#kr+S$D
zrUWJlN{*#72Swoj0450v+9BXTz3m9+HsyFO%E0Kb2LKNq6pWYWvplvP4=Gc5?oMl)
z3G2G!GX0<!hQ|j%$IIIqTFEP2{vAe}56Wj^5P(RM>0A_8^0#g$Cc0A$KaHizXpu~;
z#agx8rF%OkF39f2UAj|p;;M_l1Ra4V^oD)96FNqW1#g#_0bsS>rnmtaXxyk9C0dY(
z#xr@Rtk|lcMBBv}w#gRA2#t6jlpH({nbyPvh*4`|0>r2pr(6V18U6tRf{+xHXyrkL
z%m0JG!9otRl>6~PIyJcLbw2vA2xK)rdum)+^Xn2DG5C|4Z>LNwGI($fF^-Hn2RH{#
z0;>9xLdFfWDLdKjAywOoo?X)^ibN-+0x;X3luluX#8E`iGR>LQ$nbpGD5tmpQ9n;{
zAv4jRM_V!XP@qF#bVb>>;*oi~<Q<ZG!!iEZ#u@a5+H^R7@(ch%#PJJ>XYofiw0@+{
zPxjCWiW4j9>){OLZ`2uzOy#G}P^48qb%rkYLQ;5yc5tDN(4z1NMdJKZM<}$I_UH)3
z^0%jHniE4bT{%DucuZFgDq#f#1V)r6S)*Y>cNZ`qw)<^S$TI-Y5e1?yNuog1MM@Ni
zx@;S&C0JT&QCyODG#EltgYk9S;McC(pFk1R4-zKg*i?vy*y^C*+b~y3@n~>!OE(E@
ziRBzGm8KzfI4BrRS1(8@B6dq{dQ+lBd4iYQ1nbjiTA+T`Xjw4k*EE2-P^mkT)Kc>!
zA9x2MlmF%osN$_RZ@?<vsvA%hTp#s<P+X6CVb<3z<rcHPa<2|PQ`^POs`B3#H>}Ek
z!(lF6n+b=Zj$@XvDM)2+*Hov0Hv3?fFevD4(1<*?NSGv-U)5VLF29Pm0$uI>dO?fN
zB`)OE^<2V2UR@6+OsGc#!hAKom#}0PG%P;3-h{7uk+sXz0aAMLM4nn5p2$-W2p5m!
z3$3=lAlu}YRxQ=ZEzQEIQL88)ycqlB7FSW!$t|uTs96^&-o*Ibi>f;-ngX@eOa)C5
zqGp2WYKTWOQ>{{9UYaQkw*e`0kuc;TqXLIK)QdwN>IC$jw%H;$Xor~rBX;%Sh^Zbu
zXa%QK%v@#(6*J$`>#?1G1>vAgB0Y;aL6b2ElAjS*jkU#1T{!SEA7SVLq*ZpShH7Hg
zVi2e{R>m)8uv3v*ZTvk=77eH|WoBEH>;x%bWR#3`jj>Qo**c4qov_&kjm)};8T}+6
zfyj(W>*C43NX<{+b<B%d6pm(~6PScN8B+jrW1Le{HK0YxBz%qqGN3r<#;B&Ia^L|L
zT~^qp5T>T$-=nD$IfJLH;;$ElpTc$+sG?A2<3=Ne%*t)R387-%3~dsKU_+I_qb%4B
zp-i-KGuNif;0;*e*7)x*oO2rjg1pS_4HZ($B;QbSbWy+v_}`7O2}w#zxK3pF+bs&+
zyj$r!NcPi!(Rk1j$31)w5C10Z(^H=v>IMEgP0gxa?TjmFad^7RL4q&S%&d~q3>#`X
z8Q~E(Lii+!-N0%(s8q+<DIGfYJWmPLXKl1|G@Ws@bHKCIy!=xTc>l#c)#%}t4=YHy
zW;(>29;%1fJGeCDE?bl|S*X%e>-0rDM5WrDa?G+ZRgY?&-pi9lnbzsP)VbF$y8Ez>
z9eRT*S+!2T_Q`<8m0XifPt(WZ{7|MzgR9z9Sc}>3ru>wn(O%MZnq~diMS#c<xuomt
zLZ!6uu%Z(R5ib%y=F#GupiK0p?{s-~$v?aW($$>Y!aH2m&LSaa^H&pT%esysjC@fN
zPOZShq}OItl&MzRO0}V19s<G02OThU`wB`5a9!oOj|`sl?I#Z)8`h}-LY5W*FX#q$
zY{e10DbY$1V>ngU;m{ZdK|^(G$SE>a^J99Bsoo#cbF52IYH)CCV*{=1FjXUL4QEQH
zx1gaSjP)C>Tr-tNM|zI2^6v}zIT6``4|j!sV23h_sy~`#2V3B+IU?mI$HMK0i?O0p
zTB|S@ENrVNm*m#bT7|i=8x~vfGL42CH!&HOQpDIq%FP~;(-iKchqS_-bf+uYso_T$
z?4-zv2DPwahFWTurYyxs!pWecTw0{u7)!%8Ly<RgU9(WrP2hJ8ZVOW(+m`PKQ|;Tx
z!O5^HXl-~SnP9*h-dg6m5AlXG*8>G_Mf1T3&<3Nqsg!Yx=dGzca!W&YP;yT2fVgBl
zAOA;?I7<dT=|WTBlT>{eHi=l16ogkv%F~p_->`_X%PkD(R}+*06L5@0*bimkn99UQ
z22PAjchLDLau6dsalbGF_y`h%2Qjh}8tORF8WEtFgFAs|#1O`IBE}KIg<4M)2-#5U
zDS{=PlnmL_y>SxcQMl>M(5XPo$kADYAG#(^JY5yK*#Ihw(9R>XbQJmdZf&SzNY7aW
z&c%WG2(db$wq|{S92OidLsAa3SsPLvk*~8TSbyZ}*l@|`iA<EC_x&%xfh%L?%J#)}
zHX({9?tF#LM!pOpXNe<7L*d}*zVc&o22}JGCB<AJyel0hxqoexjJoB+b0v&q=reER
zMadshC~{<#ct$Jp`>@R@emT-e7y*sHIRUvic{v*3Rx5CNQAV^m)ic7biH4Y7ra53|
zU4#q?pJ-)>bZ&m;lvFVIqQvf*yv{76e~uslxDm-Frt&J0S`rkhn1-TE6~T^VlZ<;e
zk;WDWZwdThlK}_@#0FCx83Ve4U77ox6h`R}v>Bq$N#QoVOq0Ta%jo|j6IMJ)DZhq#
zO?H{4iLG%p&A_9DHN9bUznUh1Sn{iB0=R)M#Mv0ou_7ZP+K{kIu{=z1vCB1qR>>C_
z8?^k(HU1W@8)E}jvt2`jXZlOY56rz6^dtl5)IwxQu+1FW6dvr&)R!sg$kdl9rXlm?
z(q|F&d@;u1u&a_`z_^RaFgIG62y+u(^vV32`~)D{?Na6(Q*qccDLFSu7p;w#qzn1!
z81wNLK&Ed(vI#%RY%BUhn3!X?=|?9FiFf1Z@rJmCh5F{N-83#RSH}dLW=Pu(>B&Rc
z81Qs=%?F06+p`q{i!TC?@^<lzf%&)O;qqt!`xmOjJ<-bkR3z+T`c=;NNK$^EX%faD
zs5`@3jJC}C(o`YHHzREh%WP)5Z!sCl=KY`*5_cDHaG1DmJ}B*iM{bcgTSQGgrzQ(o
zRxP|mLGm6r0A=-&9cz(dh7aF$MkDA$Ckl@<-V{m6T*T;nBqfJ~Jx@F7LyJzFoAD*S
zrHq!-$F*%HlM8h{O!!M4{A}i4;wNEHd#FJ!N<PLPU7f%PvIjO2n=q(6+TchgS`=^>
za8m2KG{QS$V?2BY8Pb96(b~_cTvpC;GMlxhgU^r-Y|pJJ;<>FBa%OQ3A`{r2N3*0M
z|It3rL?vM6Wjm9OPpu+A3<P#>O8m79lQ2L}M@I2rr<Q5S5He)_wo_=?NN`$|E0i_M
ztl!X<@M!?PoYEDL^xK5-Zz%HBgl%?E*@$#&45vqnYyi~yInau<_p`(!a0X6A$x_8x
zB(e>N`KN>fQ2b{J2eAF2+#X5F`QQ*hs9dD9W1zqgP+e7nojMiqSLACUtNjt1fEjQ~
zeVD+MVPRN9T5z*->(ny2pT{U7?iMLKjY18;Webyclgs{BFzX{pf#g6R=prP70ab4s
z2`qp;KL{((w;o0S2Jm4#!ZyxMfEAFRtpM3|j00w>*<cc@g|)re*g6qI0*o0qAtb;|
z6xwSH2DE`X&jC$=PQY$aw4xz|u+ep6DDu}7Nx3MQF0Yu(MIxAndWE1V9@GZGqII7O
zj8!Q!2J3%or@8?zP5uxAQdU!$8NLZxQ$3O(oryGpy)+2NVq3Sw8fp3%0K;0-g@Jl-
zG_oWm0a^OiEl1S#F`yT;UQ+{nfz0`Q05w_f`KoHFw$67`Yon&-f{0<acx%xn_0kir
zDa_u&wb2xrf5f}*Npza(L<F1alq|cpFD1*U=0&<<j__8uE_@v>Sr@(zKZYZ+Jv#ov
zlM-e>b;=PwTc^ZaI=4?H=F++KN=%5Z<Dd)l_!Up=L@TPJ00*h^Vhrw?)?4jA)b{9&
zzuJVSRJ{PF#0}U4rv(2OjR39J`2biK*;5VWP#1-pJ&g&=1RcGQ)%hfH)WDwvKl{*G
zWC33_w+|(R)l`qrv6@VwhM3ndt3Mn|PC-w{0f;drm)XFpx5?INh?H$IZ7xb+Lfu=h
zoB%uxLO1Tp)Un9HZ>k+f^G%b@a#0deOxJ#ze45JC9n4Z~GFb-YOdv8`tz%(|MSo<l
zHl-aJLVCju13}EB*5%BB9Qq@~G)NUZXp2&v5-`oRl?lu&Q=<Ve01l{^vSXW)IxW3%
zjfTY|ZD*b(N^Z^Y6Jr{@RI+ICaug4MJLr?m)97N`Sz9Lt!P>45u3n7dNVZ-Z1Cq7(
z#<ql_ySMo#=H6ZN4{R#g2aDHI8-TmeWDFFqhh7Vgg!VS*78kDvT|+cE($QMX9<*kY
z*GE&;O`0y-kcj{p%x%z3Y@QH{U^UF2ZMg0kBsnh<*#*5|46!Q#h{h1NpeUe>>G5J}
zbdbm$fWr;hhyoLlzW0}Mr<;sqhdK0%p*;<EZutE*oZyZ2G%~K+&_m7<xzUC;F(TOm
zlvBe=RL@iV0m|Ie?d{ZErmk;5Tr}0XHI&zG0uZ3#x=kM2ARKM#+|E$?Hg#@8V%yYP
zPL!&U14z3SHFA&;)6)A~6xlf)s?;1}VNo93G?9Pa1l&;V;!SMad40AvPK9RN=CyGu
z)_2|;r(${My>W^ZajGY$o{dup{Q7LH3ZU0#<5WwO++tLmzSmidN`h@{39-3sV@p!n
z#)XiYs}a$vNPU}U2vS+uL>V>WXlb|$0yzJHV8c&wGFtrce^%ONL&v8vEu1p#u8p4U
z+QHCW@7lto)P9ANs%m2qO`y>V<4}qP8dQ{9TMw9q_g$hz(zA_k$$nrPRYMGbHm;gs
zpd4FaF=8K7@v)t9ak#Nlh1EpLQH9RLe-%S3N-tqjH8uXX4lJznLxUN`<B>Uaqdfj0
zd1Yd8q(rx}u~1+GBZ~qq2rX@jXYSiAC|6zd*j=h-r#;DvciPEiOW7!h0mfk<FfpAU
z&$Ay)XH#iD9aJjb2g<Qk_~ZFjRRD1)R;56mtzA%SJb#a_ii142t196dRFy5{*<XbX
zd1avZA#Xy9!T5IXwW^|syJ)nn&?2ue7GuOs=rNe_aqpq1Bd^aGjx=Cgs8ty9z@=No
zBY7`Zfl1!oDniNoz3Nn&v%si|SyD-;f|pbzswO72jjWkz&U&L~sSPM;ZRe(C1#imw
z;Vd|6o0c`Aoq-@!m%6oG$vU%m=%!>nSt_)YtP2%KHQG2GswycpysBJEEwFDU5|$jL
ziG&45<#zm~iWuG?ox#g|rgTLe^C{D9Y|pBmgB#T=IW@OlAu^j01$8zRc*~d8(G^F_
z$5=-W=xSeCfwmr2As}{d53A(D&BR>8AFvB5XDgi45F*&^(W5F}oLwowc$7wYUB0SN
zO1sqq36->!=xoqrd#eW$k_EaFt>fK%W;x*M7E7zhOoIa46?SRB5P$zrM>E!GGn9lA
ztt-zx-uR0X&C$x?yWD)JsMt3f3F>aQv6%(d0&EtNyePU%BnQ0Xky#~kN9I|9m#D<u
zWIjV7?hpG&id4I{Ua{BORlRb!Wj;e8?#(=sI^)q5h)26mSKOW98PFMIX9#KS!oygU
z#ms(|*#cE^x?HId7~3~{2#Rla+ddT1+^x(Od4%>ZyErUmy;l`Ul;7?;A7F9oL^erR
zeT=Ygy>ftk>ot^knC%>(Z++sf=$nNkPw?Ky)-4#=>j22>KawL)nj|fMsH`L?`_t#v
zEkv--ty?T<zqVc&(Y19;mR(!7WSMN_NZ?+S&1M^SbJrD*3In~DY~Zfz&(<wR^lZIy
zM1F4FVnlv!-GWEHS<YiXUgD9*&(Xc)gSD8fdIg8PZM|a6Tn{l+SLgwYcYqR0Rz{S0
zMvE>J6qzmqN}B$=dv(aCPA~fjJP6%=>y=*~TeoC{j)w^o7E_&H>A#36Otj+D()uP!
zG`rqq5vJdLO4|l@Y8QZ*A-2CO!m7$sNdm%&(`o)V=;rBV|9~5)yDX&>=dR0bl05B0
zhEf*Z=tJ85#7R4(It0=}SBLnnqMZ!S;XX`HFc!2Kx)k6q>xykMAnEq9mmoR@x%>3Q
zg}@BPRLr>AyUOR%o!3W~I}ZmU&gJmL<x{&4Xc8<EHuNYDl!~sZ8HPeAUC4em5scS|
z&WSk#6ro(4A($13gvUC86kdqW0oDS&smV^g)8Sw36|1D0K6LHoXKry4@UM$RR^o6f
z8w@<c3sOSv-~5i$hM8LW(TCmyK&9+c?{>geFA5#pL--djg#`&DBT4b4DLr#O(JD`S
zeuQ53SeuH&nh`nLD+&u?M19JzHgRZ7$_XIDyGqT_!+-QCx7>wV^JTsP`e&aIl#Cqc
zQx^(?3pydDUy4BJQ*U=<Wp!24F`&KljMhRPS1)5u20|P`Vyr`pR>fQ7P%GXd2fD{w
z#8B@V7`A^Ia}v!aC>&S^D=WqVDpA!hA~bBjDpn>L(yxk_$=UZZ%^<R6QE0e_fu&!H
zptxpY>^uypiG8XHO$f0eRL_f1I7h(woD8wSugYI`UD0CT&V}C?6pjlc8?ZfHx1fk#
z89fxE&_)J4Qopp35rxz*hSJ&vA8%C&V~A3}q~l$<0IymS)ZMzYBsY@2s-PfavHC?L
z9OAY5#o(@3)=Mu&gnRX?oF<3~>z6k7ozIb5dmE8WU8T|)d)6_4BS|r-o8f9Pq1zbr
zhFj>C(eB2jb62!oj}X5u{ANR?n||*RcQIvwKpUXE`dtxs$fE7HLhe!o`pu9#XxX>a
zNE9gQcSYQdXz}F?;IV#JxZS|uD&#JWK)oWYP*SSj<(fwxa=&#7pn_J<$SaiU>NjI9
zVAtz+MciG7;MJlT+QwZWoH*uh-5xhAHUbG}Oy|+dD2M>8UV&IJ4-z&mDRB(kvP&Sw
z^jK(f7%<EOH}#ABkA-K40Y0gkJ+dDmC~Hv|0|_hQ0?vapAcA&LrYJGuNB$N>;`XNu
zzYmnAiqAsqR)2KDAb);QrYLb(KV4eKgQw)<TenymK-aIZs*vf2HiIXhSZND<|KEj%
z2!%ESuKJ@@%Objjb9@2vf3=gXPjE57Ccj=RHE;w$q0?(L3$ilXY4`9`Nl9n!K3A0l
z#xnUS-*p3SCNVaXviRjH$iPAju8<`Le=iCc&v>Q)^wb~C_#-6@{aU>JTszcH<mdy`
z!W9SAPLCD`mdc`^%5Xd#GgLMPpfvpS8d%zW7KsBxmC&=|)CcBFtv{mfV>*hMYOoEu
zY=#lOAAh8Tj599>)mUYnj(|}8T8T7S%44;$j@OTDa+X&v{H00WSlCOGyz_GKQ(4t8
zCc2`oSczmIz*g==j-N_nJAqW>DpJy5Ui6c>&gX*(#9%BHC|BW=MH$g%;*wD?X{cnZ
z)uP-=Cy5nM=vD(JNkHW?ZzlJ-+o@!h7(ZjV8tjjR;6--J8lEvRW0k3iCbM;Nqq`tb
zTEYY;vTt$)AzNMmAVg|#YfNZKiF27i8z8&9&^3UB;02SBpayPTcmaSWb74|3jLV5!
z0RyBLDg~g|ocIz)<}Ss@_e7=qxKcQflkY-x0GOQ%vEg7Gmn+<iVO(z78HS3t1+D-T
zKUW0W!D>q`m^fBs@<K9bCzemR1&G@61Sx1R%DMv3TBDRyt{sJ>a_#cCbGy;Xj}%Nm
z0$6&10>I+v%I}B8(QVJQ%PBrISFJd#SWIOi0Yu4VgN?Ml_+dH<QJ5<zDHBISQna^9
zzsuvqnbwcUEU&bFpsaeO@dteC5#Z&>n#6K9$v&WBU3OcPFbfKq2X~Uol-p3cxN`0h
zmgU0qjJT}$Wn}0z93rhU^cs#4!HKeRn-h|h#ofH}<-1{gol)owrpQG?Ix&k(>z+W~
ztE;5hqKvIFF@mm+Amxwb6-9*mmqM<*DK8Zjn=#e_9*jy-#;qd5GVAntCAp)PpUc$D
zdVk(3%?|)>F5`1VVLe$$n;E?q=BWMEx!x-D5Mfv&e~4e>f-A!n=0%s`y1}}*D4N;>
z_9!0^^%K1b=mS+ET+x3k%qn@L8Ws_p6(hRQO8)ST!^kZENM=v|R5E+q$NrJcp4_Q)
z_Bf_}OJ;9iP9?La93C!Y=SaVg87Q6IQ*M;YjwF6pE;|xKz3H7yFaWQFc9b4*RVHM-
z)}nBl`EvG1hF+&jLi>BymPgX3%Ua)1G{C#AKlt!n7W`v{U!k1EOVL-Z_(no3xU$<D
zT3kaE=kBI-R=7c3xZnhQa0N*=cpjbT;>3(_K>Zyr0ZVx0yJrm9A`qAZM?^1Rj#Hg@
z_raUz3btf~mJ^S?!Ns-+gu-a*G|*nBXIGx&XzG$njc8J@eE5h-UB%~#zyZCXyRI4p
z$u1HhK^&ckz(L_~abc(rGh<<Zbon$I?2oQ8pFlo|A}D0TL@$*gVVIY9ol$UnxLhF(
zJ`Jzjdblfs!XLWT4F}1%)r}*{i=$5s2*-%(0UQnP0k6FLjI?+8SQ<k3U8M#ZV0FDR
z_oIr~5fm^8CVKC*p0N<LS1$jw{8V8c0f8FjXOhBBMBHiYlz-6i9cd(p74xq0AuW?Y
zycfWcs}})|cx)8F5hWu}#{ee66{GlC*6QB7@tn}1I(bgq#8jJ8y@-o+sTbLPsTbLP
zsn>)KgrKoS0=&?zUYshVKxgr!6g(O-pCN^0aGm-i0%dX0bvmbAb`dZ@m?jVJdU{-@
zUO@RWa8+*+q<gwTi5s%k+=Z~+km|Nb93h^-&NTAK@N|VAH`q{J#fguGlBSE4T^wDA
z?d9qM!A8=b(+jr<alNy!Q<CCLR9N%EKU)W>3+4p*n_gHAC^~io3E#Tdi!(@>W}T^|
z#7QrQUqcZzRHq`$TU-z>JrkvjU4>T~tdveaVM9i!1H2}{?9ONsLl3G$L}EACBE4`U
zP~O^A0H)nQ+(dP)q%4UkXbBh}UB1W$<Kv=WhIeBpP7sNki$oAT?0MJK1!E&heZ2xF
zFxOsnI@+DfUnq)Pe%WGfE`LWWSFr#TN9rA3I2Sk8UXTDt;an8X8tP<$VcZux@fCkx
z>P0?q?FAZhbL|UMkxO58Arz``;cTEfqN_$wgQ<|E)soUNLgGonGU)Q~E=n?8_9c{e
z^up_ah0wFaIiWI>%es?c8D#mlq$H<hSVDnHhk6I_&WRBba}zKA0s}$tpsT17V+S2h
z==dSL?_AeA;sssBnTT5YN$D8ThL@T=3PvL|(B<4_Y~W6TO-LC85gT|U0Rz5kEa1hX
zu@Hv!(O8la@q?kK>st{(_)9w%LXhbvR5^XT(}wAS7wahT>Vi{QF@$aWLdcaNU^}dv
z&J>3u!wkU-!u{gaFV}xx_Q$=2WfD~U>3PNPBs>fS?XoD>_#jNK62N??)(P;rQ_Dmw
z-wUj(Hd#j`-&>3dN<|a8vN#w!xKZp>dBvB406!@g#34b+0T2H{;D=LqyIuN~qJRa&
z!ajfbm3G$f^UJM$w#0iPV*~K&lceD%S5S=ZlOkp(FNs|DNgB02fS;@O)ZnqAZAv6z
zSMTkjOhPc)C7C4UL)P%*{iKw1B_nBikzlt+Qx@U+*b9gN1LXjTJis=?qjIO%F9*Y-
zY}@z97%+?&I~v$#dH!@f?6yOJwwjHSUcfqBItp#oLDxHO?fR3ZtAKw3B;-0m<6AgX
z0jFQ5JcO#(DPI&05cgM4aI-qn7vb~R@4b%w{8AnIDIiDhb?RgF`}}O_3c%|3x&pBH
z{i4LPW<#$lfUA9xS6s(iyy80Ex;CNRGN9~DiWct#6>)&h9Tzl4_n=4BaX7h+RLFtn
zyXq7<&-W_iU{YzoOjvV{AO)dqx(NtUXmT{(q?)j@LziljKr-FCR1>hq{i{@|?k+tA
z(hRXk<*O3}vh=l1qm8So1FSZ#q7FVwRm>GaV#ratV)rRsk!-otZJ<s45=RblmE4t$
z+z~Ec>TQphc6ZfhKrDLc$Q@DR(xZ>8Ns@{*{vdaRN+!Tc<0^-Me8QmQcgIP!R3PyQ
zMp|!zj!<cqwS6g2tR5E(6pKd+79R<@^-AfZf7K(VBShGp9-uzDdQjfST6xuS8eDnR
zqZ?fLQ#0bVeriI4uM5?8LU3$6?=YpQZk!Sx<4)7xqP%71&_lA*B;%(hb?HG0X&u<-
zXEbg-mSKhLvc{<X6CylW&G(gsh4Ap@1RnJoWYwc?|37PQ)3ZyCEQjsuSDfYC#k4EQ
zB$M14ums2pL(+I<cq2hqfY7thH3ZB5-o?y_sHc0T-#&fjqJf#0c^(!&ip5AKBQr4q
z(7@iKd7t>ub$ss#@PIS^1<|J&pikQ5-h@xI$-$V=lkO;UL#1*$YyGuJ^x0L1-NU9X
z+XlH_E*Iop@tf;Gn9%90hEkas-waSViHWk?;i&gv=jjMu@*0Df3hR+%37Uh9QXNsO
zj|5|$9HX)_AsY5;0P6_W^%}`KqH4c(v_2QdsPuY>G4opFIwI3Nk}P2}kWueQs)jVT
zNvo|iDsbu?-sU}S)xkF#x9a2yzj~PJV8sM&wgV-aQZZ4%#UX$X9LT*ZHBvNH!%Rh2
zHFkzpTg+4Zjny`j#8oAf#)sLr(?~<ha1R=6-+X+7)@1%b=4U)(s!DzH$3XL8!tOys
zZLfTIf!}{7<8#>D@i_;rv_g^KzMwo2N5pCzKkRdYgxIPDAOwXiF9CKM{*EYXF%u}F
ze)*dTbls}NU+``M-{r!F><YizL0NMJ=*<L*yRK6(|En%e&@Rpel`QmvsO~3_WDiua
z_p+rUNZWfM!+emsv?)4ST}3IUUWMDz<qyeW@BI+TVebtRGFVmua7;L@I8D3d!un`c
z1#6>eW6VH$&f~z(VuR(S7^W#y2}=yLFjuH(B=&T~;y9}TVYyrZr^yC$x~Py0#th^~
zQY8*>m;T`je$7Os{*ghHm%n7WFxx5fmjBFrs8`)q*1YUn*Phvz%Bq@oo~UEG^Tbqc
z<CSMl6wN<PN6}31>P=@xc$DTHZI)r%dvk?u7{$D4vjTCf?t%{=tnN9rHEn1Vx=zld
zw%HN5gm;>XbSd47J@(#OXX@O$ecWt!q@8huhR<BTfRrYcde>@EBDBrLqU^-bFW$_b
z%#!2nO-~%W^{;iXVe9+oFDOS%CyTw_?m-VJKAUdqJJSBR0^oP}p1!yKhvLRtf81Lg
z5pMnQ1N5yv5GVIdzGX*3MnX-4-|$RuxuiLKQ@zoM?64#$2f-1LMUew=a^afn-6YDn
z!U;K|r81LzNwUk;E|&*2N72<>k&KRLlNPdT1Xv)vSUv(0PB;;@&aY&gpk?xhwq}C-
zA#e@-j><BRX9Orxi)Y~EncYQ@;WMCbD9>i{%=T95`H~d%Cb%3N!FrR?gKF3;6n4rH
z^w*6_l9P01lRIE>!d$MHN%*>pZ-mJa#f-{~Bde7&35@t$&SW#5IrH3x9@0dS;zO`M
zD1nYwVxmiF>Pu8D@mx->mS>to%3Y4Hp6;zmSziLuz_6&$E0;?xIazMJFW}JJ+B;L&
zGmsAO%#eYnhF5@DbUFBXMFn%^=DHl2VqBTQ_zGP~%Sg&{C0%nkxjvFCfr2FhpNm|^
z1Cxtfc5B!qm)+`J?J2iTJIT2EARIcf-nxRv@uPWpi;iIB#cRZ;SWHN~k_Pk<H<F)o
z5-6*4$awOSEWIL#T^~$LZ|#Grc{ZCiKG>W^ntJ)3jw~dggy#4VO-!UwCu0q)Qttlw
zX`}a0Yeh}Hh%7IEH8=B@<O<2eZ#YEkLn6ywAU%CBYRPAMiMS5{e-L#G!CzvpXB7P_
ze}OMezu=?+weGI2VZkYsBFRU7D@#jiGIxnM-_UXHrmm40tF;VT(2+Q&9I$lrz@OS;
zP7TlUI5H%{zLH{}Pa0c!Q0fXS!Q&Nmf}eFD>k9tKb6np#m5{dpeFPG+)-fZ=N?>05
zpYt@^H)(oB0Ju_uS;w)tZ<=m+KtB?!q`pbSN2y5oH%^4SY)^ha$_u~1+lSeLYT(bZ
zestUg{(Q-3k_u%F57*ay(SOY=Z%J1i6I>s6g_nhysxs7LL{9e=Qq_3d+ZR|KG{rpv
zl*;Sjg&UX&y8^M$)R@}(rlbZi)ZOwlhoi{#a~fFt(x(NpZC^v(hllub^&W0l%hh{C
zKIjbpOB;R9$iTcU=!zW7i;cdzdOxaXU8~Cn+<vrn9DZ1<X|~~qwFDiAJ#!?m^Ed*$
z^hJ#c!B>uet;2;yIN@|*xp}~JMjcrsz&S#S^d)Fu#E>P82z0d$hpK$glFQS;PtMRo
zKmhhykEPWKU&L5y8>gHe+WP(V;$q`)T9ogXGjvA0OD_+P*O6cf5ryn^D|2|^zOH8u
z9vsaECCO2UHR=^<uWS$17Q<Z7<;@Z0?^rM}QW#--=rY<7Pq2sfqESD<5@n=`knVzL
zhaDl#Px)*OuY;d6_Csh_X0V6Q=ET?zq0MQ)87HkpsD>RkNPckyrli%WB;}ncbzs0x
zv(K&8%2j7>H3o04DHRua!}?rmeU_n(Gd|^xiTTCXFsJ5smOtiHSK!7wCu3GPLap^F
z)s=AuCT>SPGoy7S0&utmr%@8m4f>8sQ)K{wshtDy+WO?i!C(QitHa2G*JoFk>w}qH
zD;5E4W*){s>PydDtlwR8+ejvH1_7ATFc}133V2{>?o-<Y!otCroDZVk|J3_Oq_{ry
z{=p9H6ZUjR=(vvOT_vL5GxoMwB@7Yv>qml8xp31l&eNEE^`YH>{`^C`0sZ+0EGa&l
z4Eb3?3qfCyBci7`<^=4+KA`5&-+u^n=<kokde##i{)aXKa1{ICMo=EoeMo-;XR#~2
zhgX>Dt8PbbJ_c_0SS+*4?H+4oI^6DcYC)>Rt7o>7Q!J-@t(Nq%&YPaiN7NX#4`506
z!TiELN5vjM4a7PbB)1(&&E&0_g!`tFy!ad(ASr!b-&<FtNQXT?uf(!Ebz_z#1ff{k
z66oyjIx`>&diV8Ft>RyVX1{g`#Ou0BvQdlOMSv35ZdBV2F9J(YVJ8B;jXF(sCH8R!
z0Pv~r2N3{#s#3N5E-|3&n~2B}hrau}#1M2#yaTV80RAp9#022A`IVxm-(Xo{V-XL`
zCu5H26u>wE-dSnGQ(E`3KB1%PKGkuL(a8jKMi0=nrXx&Y1~YkU)m(r-?+hrQyF<t2
zN7p6bk<=29Bb$S|+Ql$+h8WP*+mTdY9qmELaMHVC^f~gnc3p`%lAat1s{!>zEp|pC
z=plm+T=sj9k80JU`B5!jm@c9m+}YmeJ2XSwnxSeHMTb?e&Gn&%DlV0X>mH0trF$F)
z0k`Xx#sf~gy?<1z3DeRjj_#GBw;Cf6v07IoB36ScqAL-v<Skd1hl3-DZ`bvPBRWCv
zS{qRR`~6X=CQx@14yEacRI36_@s`2Ev&3c?Xo|MFz}4kp2dPHAU)=_HFwm4XoxH^A
zvhzDKhV&M)I6(*OEj}t$STF4sNI27#KhrammiCIErlpjf4hD0Ff!#|R?J}kx0fKsQ
zBSS#WPGh-4r|q(hA4$c@>K~P&f`wtn#I0M0nfrohS5&gX<P&+~H4!8FLx1hTj71^y
zZ<OJp%d754s{6dMa%7|Kib3yryVsizF32L&n+WC(^}owi&@0Pzmw%xn=}tHPGlRtO
zt2u!JUV|(WXLoxy0%)4@p7f%8cjkCLWk$Wzo&!{o-{z5wEUQjM!PB`nfHFpSxE!f}
zx)Oam19rTIRE>{#pdt46$rV8G?MV%>zkR6@wvWD4V7#Uki`cap&~Wcx4BND7Icoc9
ze2iHK5e-@)44eT)Oe%&3Ez>3LX!|WAM=*5eewP9RWlG(Q3Kz+Bz(AR@DFy>&zS}u&
z|NH&!=QtbR?~7!lOufoCP$s7j{-FI9)JFx%d|xCE*tbp|jEi#nPkd|z&U}qoh;(u|
zw@W?FP@3=e%TSuKZUsYWGP_Djc102G>M)~>@^jo3m=wKbU`<`tFs&44j&U|+cnGK*
z_x;nyZ}v{wGbgt~f$#lp^#~Wf-+lU(a4HdGe82lNg1+zfn3;x)BN)FZnL2kK*0v4}
z2rtuKt0V)!91*7yQPCN@!V$|j3G3=EC7Q{K0qnAi!OqgQf6OK%Eai~<$7E9SPG(wf
z+io8-wY|dqzB5G$W@_EV_pfGAs#O7dP`V6MtCHy3M5N{;!IV(KKqi+XC{BA#l9K4t
zTu30W^m)D#ln!8|KZU=Nbi%;c7J})&rbJ1`#{kabul8C7A!>_+MF-{Lc&xm=D+z6}
z|MA<uzwF!j?_d7wHv^w@FxU}jbXMQ*zx<bP|9qX!-p?a`{r^w(|Mf4|Q-1#YbLDQc
z@ogL<aC@F--~RH~>wo#@Ki_}8pSJ$;&)5I;r@#D@dHm^L{>Oj$r~mse|L*$V{&Jo9
z9&5GdnbY>X&%>XS&z$k?Km6No|NW_V9$x?ZpZ}V{cF!6Z8R+`28KmkAd?4`k8QORD
zHhuKI>g}KYkN@=l{L^3lTlI3`Q9ast+JBbP9m^k>`n%n1MHpr;8*BtW&`SjR`=Xcs
z=l}k1)Js28>1PW2ZZ@Ak;(lh;{%$83Czib=JNC1ee_N^5x=<xBp}(#Km3gGI(_f`R
z4_p`gf%zy`+b`GHzxk&z{`5b7{`uRP87;HTWoGldx#y4JcA}2`y{U2F7)MDj^6z<p
zfA@Ly!49O%cpg~V3<bY2Z>$E+*y%@gLnN|4vfiIFm*4X&%R?Fb`-|z%&-SU+^vB0%
zv!)B9v-#U=f)4RW;-*TjtZrXcD~G(d)`B+wWhD?X-&&I=lrO7c&(ZW#@W-bALAdDW
zGVWN{cl^fm|M=w7^Zp&3T=Bmg9klVcn$+{Js*ww%Y83oVHRRQNt0~dum(`}@JA^gZ
z|L|_F)t|)K-&p<kKeGBe;wZdh^Z1UX+>6Kf)*`R*%Swn(^wv_2xv#1n<qu1_s!{Me
z)u1}*1vK5Z{Shd8<QBG8sVjf~3;1^b_zP$tg1@7i{X3R&L+bRmnsTXsSq*MiZ#88m
z`?6YcaNbIw<a||y={z<4Z+_1|_60on+oO_i&fl8;f8-0WI=^Xf#xRv%jt))$Z>?$H
zv6Kz|V{bJ%lzmwZ%-6S?($ald4Sc5e6^P*ULtlU$`^MkjgueX)7_j}9D|!2OEM%BD
zR7pvjzp9i`e^q7PzYp~NS2*9lV{fd``tP<g-{tg&SN)-E|Hh*Khm@ZE%hkKTW9@$E
zffU$R8x<}V-)a(&u>S{U<V2|P@!-X`apH~qmLl>)Q<7$(x0@(_IksJv-?x$kUsf|1
z?%sN@<m-xXpZ%yP$=4OZj`^r4$q&2+JGV~r*$wvB@8JjD0t3K*^i-0shX{+%M@31#
zu9$rDk7_7?S*d~6`c``-Usr_B#z#d-e&9`HGS~gPU&N0gV*~T)qpy;DJ;?dXBjR7b
zy^^mhuGAkt>QV4@wOyv`k9v}PS+TP6ywzC#fj5y!idG-nzj_ltq#|~>9DVdtlCOt{
zOZ$(Cl6+ke=?6Y4O7eBZWxsm!ujK2Bd;RjwOYkG_;uua#S^4r^{1|j1Zs-RPO7i6p
z>BjbHNulKHiik${3B8njT@ehAkBX9fU2*l#N?H1W_mKAtzyD4AkkYvKuNK-X`EqEZ
zd;{Kk5`0|^*YqFtB>B1`7&{*oCHcByWyJWbD9MkgPKPQsfA^dCG2Lk(IMhd9CHbAD
z{YyRcmpbOp-+ukz-`wc(RhYfoN7~dR_+#qLGgD>mvdq}^8wMBuk*%B^MWDa4mFHcD
zB)>Pp@`C%QN4L1ItKGX!BdT`qFOIjYc30T<w;BY$SB(}<yoLMI!uiKv!o9|C9e@7Z
z|ACiq!(aSkcyoV^r>KZP2_F>)BmI0`5nTR{iVAM=bwwnX|EQ>R^Ium)B<%NHC^YsD
zzKr7q^&2mv{Ua{}-Yg#@lz+=tBiw6ofK`uz->HVoDsMHVTKTdX!g9XVrhR3oW;G<m
z;#=5ClJ!F`VV{U4zjX=n<L_W2iu60U?%y*wxPiXa<QMv7wL4(VVzoQIvSy*$LTEcx
zqu_U{$qZa?VEu>{_|Tn7tz7@gR$%rL;WXaC&G|ip8~vk75|zLF`3aBmQK9cIu0K(w
z&5sIg{@%}FD8^iW*opu6Odk@~zoNAfJ&etZF${`=uLl-Lqw`i<bZYprTG+2z3;Ukd
z5C!M0HrDsF2GTO;pXDEX191``|Hd2m2X_4EyiVib`j^*ftXAIGAJr^AM)#Z5;Mw_B
zldI=f)#kpTnxYy7zf%o_JiY;zfA9^=LxcH^-R2)qfadJK8r=NyB97JI-}P2g+Ql!c
z{aWRn-=*=+)@AglYOR0AQDEMit<@X2_eW!Y{0$sJ=5Krh|Ij($!!kq3mj@;gqCP6V
zk{>t~9%64D(9QmptyTtB^+#7fM89Lp{l(Ov_#=ku<E}GtYxSii=tnj(CZPG~>WAoe
zEu_C%03V_sF$6ycko{dF{h{TGxEG)6^%Z?>*h4yi&#JHJM~r*NJ;=Uir1MAYO81RB
z($}!`ihjqIF@Irm`0KY<@*~Ex<G21@<6J*vKPzhLXK!E8@0h~YuNT9I=!b6g{HM`>
ze;4`@b&m$5&(6N0-?5(m8cBY&Y5)A~Z=U`=<IXYv`HcSD!`E2XYCn0s>|YQ2|2w1p
zxQ3rU?bVj`r}iPY3zYu!KQ%pH(NfQC_y7BwxDs&iNmwaGwVa|?sXY;Nj9iw5n!i;<
z<%muvfK@(Q5p-O_H9*K=8lmeWXaHI1Se4})KS=-ES65!OKqKgM3!-oYEd}uYKZ5La
z&p%VoyS`PlfRwcQSM-rbc*GZopbHejszuNbb5)AJBS3@X9ngJumA~i_R3pVKk04Jw
zd8ARUc~_OsqheA)0Yf?_J!w|`9?!46GbRZ;Ym_tFkyMLy8xfNSnw1>+Q!eEW0UkmL
zbXR$9N5xmXN|K{c)?H-%Jc4Ru{#1{|pe6=^-_`)+1F(vz6_dG@Ryn@JWMF{`Wf7D7
zja7dHebX2GykgRGprXM&<@5JK?-+4lt?VATPzdWElko?xwa~|Nl&xH#G3g=#zI@1G
z9XUc{(hCrAKVmAZ`zjmuBY6t@e*U04$-eQ%5Xc#!<6_cr2&Dd~6e?FqCaP3>`^E$w
zuLNWgh)K61xDgyd4R2Qg-y(v@#iW12Zs-Bbvb&CnlMaM%WQfU6bK_Y@QdSeB9EizC
zV~FY!6P{+U%A7JriF4OfjGEoiZMw2N0B{Ou(=jWc6e3%}DdT}TpI3muvyXpX44AdS
zGCSq^P<I6lI)eQ7@+3J$GzXv1Bf${M|0I-td{3Rq>r2h_s98oE74ho`((eyB4?=GC
zyPUaV&|hZPxiI8*pKdY_Cg9WEQQJg}B5xx>LMYRErC~kghJVi~9rSrcs)HyG{Ogpf
z2mDg@Mh{@vKLPHtR3A1N%`xa7yLUN^g)+#)i6{n%eO9>>Qc@q(kz_ZOUHk^#q)Yz=
zNiLYdU^0f#MKMT@Gh|$dp;YGiN*Vs#82{*qDh=&zcxSGsTD`QchZ_2?l<E~l?+CCR
z8vL`4hywr?4Q6e=fkmUMC4f;H<m~RJUrlWQj1)+~kkH{sIBUQo1sAXzQ4Nj=&Gs4&
z^)5sH+CVdo_piLw2x@gC@PabL^NXQ$*Xj8d3Q=H{D54~o_<`QujDU1R)m?s}R;eRG
z%8|h_FBG%D5Z~*Opp<TZ;Y#p*19_bJnKNcsxN^PUz#eC?G(-N0@J&B&gBxM^R>OcG
zR4M#%e(Q$#X5q|MUNHo(l(6N3AO$%vq`D0SIWR;OJQCzdMpldKnAJEd8(pF2@{weB
zlx`Ugm*G<#1SYw1G$TE2I34Ez)Icl0%<e4JR$&GpQfLH2l)7++ZaI>p-#8s8kDz9k
zNurS+H<XgXkiIsMU&0W}Fe($o1yPP?sO55K3}!blxUPm0%^Xf#Su;C>DjiWyxDuhm
zPd3EJH0yW;NS<D<wV_!1M^I{|G7K3~=!Syn8<N$AG8q{->Y>p1W}YR4Brv3|4TQWu
z<@`XrsbwG<gE*McUQ3ntvPy0n3hQ9-XgHFAa=kKro5)%l3hMA2qOL5mqZ2*5HAxeF
zQ%ZBhPz)vevhtU%2cf$KcM9Teh;SK-3t<Se7z*2dB-#H8+kQcmLr~(gBN<s{+vR+4
zBxt(KD$(~lQ-zVCi0p>QouP>AM{-_%S3-D%XAGp0OF=qsh9aq(0W$kS={zCSRRE$A
z>KTGHMh`-n0TGp$&yX88GK~5uWw#iXzz{Vxln~G=pUjmav<!FrBSFi^o*N39Zq2g9
zR&gxr8BEw3&SVOYZV3MvOpKV48lJxH2I%WfZT^Vzd+GdmTh9VJ0ch*4jsV&+Ah}hD
zgEKZNu!i`L!I<P$0e3^eF{}aBI{mAy0op2B#syI=wyu@|ZJkc0hAhX?n;HkWm8JM9
zNlk21^CL@a8iz22+%SY&j!u=?D*Nq~*BY#bQ<Xx9TSkoxMGH5?jt)f&H^h;Q&Ul4}
zAk@(Xvj|ijh!}2&G#QE*Zisgsj2M2UXrdAuFE~>u4@0<(V8n3x8$_d4Z4G|<N5r4x
zgtx7>^DNf3CI*MGw$(5WV@;7_4zD@ik|KZ{Nxr3~54At&))+m=Ftj5<-)i_*iUtHD
zOXwMr(?)~#Y)B&%iu`Seh7wHyB@D@FL!rN|VyJ`ye;aPH0)f8`*=a-BjxR%s+Gvw)
z0|47p+owdm+pyL`p}(!x<CP-p5xDScgAZ-!zLe^U*dGd3V(`a|Ca-uyUZH5N=K>EK
zFU^jmx=T&_`L;u$w2j#aLczZc8$>ke*~lV$B-nm<Tc_~a)^W;Hcx^*Yg&^_Ckjpw0
z58RM3HZt6{Az5s+rX4JEJw%i4jetMVq<dqNj3(W?&n%(M$?-|?#xDFwP|7zUl^QuS
zqG>xoK-6HK_!3peO-}__Hbdz=^wtalC>5&3D!<27qMJXeMR2QSAZ3$cUVs=)dU-F)
z&ol8iigo)cy}YuV96{|3$s!2b_&d90Ql~qQjm%MRrB;OEy%<!FFe%SaPmTmT1=82V
z8<N|Qr70}<V9Npqk32d@g25y6PAG==ksPJhq<%yF3Y&Z;jFk!^W2MA}B6u5uvK|Sw
zUZiRY6PP0E>X8hTa}tLJ2$(Zo*<Xf)kzx8|E8y4>U?)J>)iB3nfpNyL7UuZ6Lm|Bl
z*~gBAjh~0=dqsM<BN-^y66o&$>wIU@q;YNt)2HY_G?N;PY*A6M%MTPe5KRHR4H4hM
zqzB`)bR?VwU>ZYuUn#0CLRt1gG?T83m~~+=0UOR`VWy^uXeNEyfoUd{IulccNufqg
z@lYUe275RXXoZebo}%d-$$5{r)Mv*jPnXq(2&_kf0H;S(1O}<k$Z-{l%5$zGZd9vr
z;)*_S`aF|05)E%D%L8brusw$GgP{oGh9Ip+!j`O}&m0k&Dl}9`af2D*k)Tu~3N;KU
zyp@Q^V6HeKwp=B)3X`S+1|3PRhC5KI!^<rldo&D2IyR!Z9tj(%WgEA?>N4+Kp}^z@
z6VQ=hn;L-2d!kfbmrgyrN_PhFGQ@z5d#Dj0<2}>}kntXBgglmkQr<%-W|1Kl=8@Ev
zg^XWEfX!zB6>nF=g^X8{VbJoxV5Gc*+WJUPs^Lj@N7UH36^z*`Z0wO>XBhy$TT1r;
z_#qZj3Pu*$5k&htBJ3{6;~t8QWH6M*ZF(-C?KVEQkgW`X7bK2KoClzrf+|@Bjg8yX
zHVmhgyCc6JSWa&NZQ7ROh8B*z?{iC^u86L4>+7C(*&?O_M;PM3&JBHf*54Q}tm9K;
zHG}bdR%+Y}qLBhVvNp&g!6VBJcGE0<B<FEcah$9o-CiZC(al!94>jFDiGq4v>CLjt
z=k_dN1FZO~b3-Y{^~EXUt43D&Ns_r$px>#mPs!(~36oxo@W68q&8nkc(v)!*b0qlE
z=g1NQ{2D^A&P~M`H$6wdrt5Q^ii2+zfi)!=d9y@0L|LSfG3`k3;EDGoRrydnpR#bb
zf-PSu!pB`n)l$OeMwU35K=-92!&T%+IQxPA3z}!3{~e|5x-8U4$#x`cbk&h|Dz23w
zlIoGL<%I$2OU_8Db4yW1B-KZ9p;*gNCTiSV9tm6CSQ%2M>$Y<uhxS#HS_sme=dK}T
z1;jo*1U@_zu}|mL2OMeroLg!!?s?~yUW}{YM}kuJbV)77W%A4@To)v#r%MKF+(;h@
z_8$Z<JrXutLqC$!@KvH*1gol?zocFxOzDx-t`{}?Q>g}yWMmn)Z&u+(Q^c_~j7Iu)
zfOEHmvq(30BnGe!&myZhx*|(8;(HzmItONjvJo7~nXS2GtVX2Hsi0yO1!!~0SdGw}
zQyB}6r1pnJb2UP5&ZW&D2F3&(9C0?M@*14TN|TAtvWWh>nyHRY1v4{*X*?2ku6Dt>
zx-177gz*U8O1Zk0tk;OIcq9YmdLuGl2a?bn5hrG$fBLc!^>8kkuMyJlNZ5ETm20l1
z#uug>7HotXoJ*=Z;s(yeV=zJj&ea$N+%mx5TvFT-`R+)v3c}P)1<x^XOQupK7&Ge~
z5x#dMTbN4*YUJ9Ri}vYkVJ@lH3%D2JS{zZ%ZwP|X(HUf07>Fq|q+i!?C!!r*CCN`X
zs9%GcGGnWCprg_<7|1CTVIYqVv3eHSa@jVI1W)at6YCSj;&~)lDtrtD!99}dm{esX
z-k8eRa3s|;nWq=<F;aP6=SvJJ&S0EOC3vs}a11HVV8PGO7rhXke1<gV`X;B6Kp4K;
zN0O!bu4l+Rjc<R}7kfdJFFkamPA19>DbtnpBqeMY=!nFZIq!hSptf9Wk{SL{srn{8
z7`x&lK`Hl#8B&D7LOBvVG=VQ<!v+myhHTiNp&SWKKnvg(vSBZPUr3!U!pc;F3ImiJ
z3A9td%?z2aD=y>=S+Uo~5QWqm7%5KHWuT(WAdllns?YeKE34rQ8L>C;Eo8*rNH%vw
z!AkX(^vwhQkEDK4e`Du?_Am>xFNiuSu;GNbDSdm_);2}0I+C2+3GKR+p(_P!DNlS;
zo`43WYAV-;LGhYmSQ&!VTysi;27hIWBW0Vk`}nAqK6$UMv<qXdl;QnD2R$MbTUOGU
z2Qg1mgy}8RO9_uXd(ekd=bl}kT8h|#Sw*&8A8U$0Co&LY9+}?eq`#<Csp7_@gpHL#
zkRmR2Fl183c`Hz~`&F1Km~4soF#Lj+sJ+n7^}e@)#T4<yE%f}=oR9@FMNrr(@<2-1
zfrYLw9HDR`O99tSHJl<XQE;U1SEI^v-6IHfU~{~>$^fG#McJhWMomhpy;hW(l+=J5
zI5jD%)*47Pk4X0ytxm8hs`icq!{ZG`Lq^IJ4G1t4r3O1PJg8Q9gU4oi?A8)LqE&BU
zs5#^C25-;X-8jI3_8NvaG~mYJ;gHtA!AS|!j|LjfBXf13arwBq(5uMNcCH>Tnp6WB
zCnW`>4Q!kgq5aO`x@N#Rj{c6#F%+KH8hnpZ#HTyQ()o0FPG^@-mj*k@16hN?C`Ekq
zU@w~<Jzlr$hV?Y$n9Yt4t^w1$O|Ai+%-TJ<$i*INNXMBnc4G1+7zZ=?4!E^6B;|ZW
zH_zd%7&Rrrn+o>pR>j4B-6)<aQrE5{srM4xFB;M!rif2oScb9n<c%qgT@TurU#e{R
zlbT<tZAVlC32qpzyz5hf<5oiw&?7^!z9(hdYMB!>1-YxXGEyG_N;ykUnJ23wt3?y@
ztyA+XP3%PJyZIvwy~0i5Sr|JE^eMvbk$#(xV5q&ui5+YYIV)0x!6Th#ir9ya&q7*R
zD`HMcuzwZlCZFYeeCKdnPxmVF$<9~CyN(80&4Z!R%^EIGQiMl4d&$#RGXgD0@2&Ex
z)`R$PVy(#U%?P$q(2l4+0I6urkbb6Qn1fkGwokB)hW01dUsL-8-)P#0jqt17W6c1+
z;?6hRZl!2IfER9r(UwG<lyGdpf$)N)S@!VO7>K-7<*t;W-#6MK@Jgd=M&Kn=z8P?r
zRQY;Pef@K59E4tJbw^Y~Q_8evMBbz6U670_V_P%=FNyOFOr8n@fx!}rr??5N5sW8^
zz^ws{CylNRm#rznuGoy-4BBd2Bdm%Ve?+4MZ#{IBhq@y|Pib8}BJ`Bxh1LkFNs@03
zkUDv^YmJaPC$E=UBdE&tyftE~`1P$3QzvY-t@SDy)<7esCdIxX<Lgr#YQ5J$heqBx
zs-bpZJt-L`+u0pg51rl7#!y3bRRU8#W!Ul>;WKIVr--;9T|EL$PM+b81Pc1>YHD(x
zyPBJr>#oKKlbLp|Ap^}*6f5D#Ffd$-v_{yRO&y3TvhCnH!@rik|CD(=XrSbzh@C0S
zoIJC&M#!A^M>TBiq~N!<tHiDlF6XW85HY6^ycJ?zDZ{qX2$}O%4*;2Cs{<P!KS}+q
zBi~Gl(1}i51+%|(BJ1FpuJuAzk^NiIdh$Vw&o;b7(fJ!VIw?XgyRlDH;9GC%6gBt;
z8d!?>Fybqy{6{dV$X<d>nlg5@;gcBB={w<dF#d7tgjc2BYrPErDPj*gRv^;xHSl~=
zz&<FT%~TgUflFQitsfAUPe22aCq)B-T24didnW>m^4~g6vZC`J3A!lVyc1oA<JrX4
z;nEvB53(fww?3=H4ij3%`){4#Iy&!fjtm2lQqT#mL+X16xXK%#b)IcU*Wh@xl|w-5
zgy7NCiQs^x6o6}*BI?+kAUmY6cVg^dvHBz>yc0Wd|DNL`cn&J&o!B|FIdozto>Ra%
zNIGi8?zu{ajj|Iu$F24Wor5OZ=0r|;1T?0ZOBp)g#LjdIXvj@xx10iwC`aqG+8zn^
zW#>VlIS;XN4LG9er%Qcz0;h=m%^N-*U+O2JQr!L{su!gqLOMyK_r_1hsnmOCpF*v5
zyaEq(lV~X?fg>7t65HqT(*s2eP3Hse92(CDUSGtOBDRn7sr&|-^Dyc<9ymc)z5=ZX
zLfI!_vlBx_^=}Rg_3=>=-E#GG)(Jjk=qe!8rTRM|)Ug#fLDZ%E`{W_QT|FR*x~mHZ
zMU|(qVNz3s){$i^Mc4|QSPSQZ<~+j6y`VWxu<|ZwzK9RX@YoQBvqYG=f@HW4G_21Q
z@X;v34%eLUD{q13gkLv3mj_lijf3c0#J7@EukCFNyNBy608&wj>WvJ7uisLS2k}=P
z2yGPp$^oH)Ym}k^0T%DA!wASmDXYzD5ToUT&;}04@<C|W?ovcG8+oEr#x7V58PShU
zd9fO{tHG0V`XO8pWhH6;gGXZJv}}Wz-KF{uVs_Cg>rn)4IwQ1!Be8rD+8|^r8)h2>
z?JoD)Bdf*Ib&41~Im>mS4X+|c$CGn9E+jk*$E)i)LnP`RK^6emol5^8Ud!pA6@lnV
zS(XnF_n}S@h`V(BK_FI=%_FKs+vQ-}27$N_6zlzw0@VgVxVvV7Al#j~X<PY9rU={J
z;2}5t6WXA;xpzH!RgsTfJWR+zp$)=qZ>mMK?bPQ-VX6EE+7OoZrWqub_I%2`&!5uf
zkwQ8}^-!qVDS@%SO+u)=585P*b{hNJ1dMiJ|D-9n%iiB6&#lbv(I!u=@<C{`POV)h
zfyq;Af4}HS5LJTEBdX;L2ZA;Uqw*kVa9mCiZ61?2DmMaV%*fD)oGjvKqnbbK&{^jl
zKB+p|)=&IN&3{|!0fAKh2yN2R+txc%KvLx?ZIhN>IV!YCB!yc-n>@UhXF@#*k6~l9
z{Wcu~CJ(Po$AC%OZ@DJmK^&dV0dsJCI0sCgUzG^8O@MEkvaC;{uY3~PB>pxT_b1P=
z@>6J&@O%6e>QPZ8&MwiHehUrsrIcVJngrighP$g|wWQ_F&?fM==>RclL2l3*Chf=V
zJwQwXGW{9a<f&Os4GpH8r=&x~Butm>g3rQuwP8&B1e@R_a?7isO(J)>HC!da=yY6|
z!0DzvW)i36%+P{3U8bB1GK^2x0zsUnQ$ve_X{C>CL6}aThN}fpy6HwB2-3~eK2ciE
z4-F}tQ^Y9`;|t|kB#6>-e`vu|bJHOr3WA$%5nB+0<-X8@7@Y14Er6`1vq2D9ZIeOP
zg3xNZBnTp_>5?FbtX88vsA{?&V1DD2aY6{IrV~aKtQuX1kD%t!su7x^?M3+j`qI;(
z#mrLui4|p1{)4beFNPN7Dx4CIZ?ai^`bbKfBJ4E*$W)5lR{WByWOzEyt#Ws0L0~oA
z1O&m=^!Y~~+myPi1&zhVqd?GBtYo__aNdQ>LyJOI>$t^jLG!Lje@E`l6lJA#R{<Sa
zgjPB<Tq(mW%DBIXt;*7SMChRO`2}n>xd<OoeX9tF*%l9|@{VYWV5{uDZ4qtl)%{n&
zt^6a};wcus4{g!-Ytrc#48X|$bCn36fpq%SIF?%vXY62U^ox*OJ`mL>Lb5@rUj$^6
z)qfF?jXM1*K!#VuRg!vha*Sw;kSx!Lwg}0$RQg3ozG?Jd0AzVav_(LsYeZW-?B25a
zFGBSFTKyMM`j+m$MiudyFCwzMBU;{Ory$$9+9LMeQs@^?!}5qYnN+LW(%l!q_YQ5K
zi|Bg?heGhZrN1wNZ#qV_b&yw15v{0ESIIaGVz2xnj;L1rtqXuf=w<TdmJ}*H3R~qO
z^rmY>TLj))cK~Z)q`CxH1+rJl*cee(9ujTwSbOUdU=c6n;LyOrP0?EsebPO^CSazE
z!ztDpy@lVqkdfgxN`ghIYk*C3ymbw*iH^7K0l=*}q6=kAw=jJZ8R;C+Hj(kxJ;28K
z^=`Ui-aN0~I!kOCqUAHuHqWBB&H<Z8(eih=Agec{JAzHfymd#giI_K!23yg)?{}^`
zr(CCl?d+<yhVAUCt_e1Q^H!qyBOBkgoGLP#^E1{XK@X5qVC#$l%KnB=Mcbf@?5!h4
zk*fCA4FT9vd-LD`uGE%aMFZ<;Z#g3}i*<@HwG(aYB4F3Ix#2d^(m^7N)t5|Xb0&Ik
z>HoVng1x2w??C^g{eva7l}Y<~(8?kkF3aVH14aWu>XbPPg}g_?hF87CEgy_lGqUA@
z(J*Oy!}yO`-CGF1H@Z*Lf4}diM5X;?Ca<1RX=kqTBdM>uW9=MC?FyYMY}2`-*DBod
zt>{>(Tiz8N%lSyyxS{)<=JpP<)0T%tPpZ?Fe?<q=Y46Ua4R4;-{;PxMw0BeE4X>V`
zdM}#OmXAfR&p9P*y4CVJA`Yu#5G<WXm@0Ji&D7hD&Y9-Fqi@u-JD5v*8%o))TOD<*
z$y+`3I$azQTXrnUTP-^lB@O=luE(;~fyuuw6m#O`PjMt8%WSodm3wV9T9CR)4!kl*
zVy-u(Iq!hCElyv5@bHw_t2%<d$pd=17G6h$V!js<_d57XdqExVMPAw~-X?1G6@1nJ
z%e1%UP|-^_*eld<X%Aa0z77>*!-3*TNlxpUYODU;vCuY#Gu2ETX}0_+PQt3(Q@28x
zcW{)pNOwI|xl=}0;PSfV3vndX6^G{C&9a1!nV~DCsGo9m#MOpjYF%A}A#2N>;)rr`
zyV^BOE-dyPJf|&hiVhX}NYJx}<<-@8`>CGFmKzpRQ#<wb?w5(z5ijV7Sglv@n!1aO
ziel4sxLNN-%Y0@ZtNxjK?C79jvJ&i;sk;EXWop^W?vSFJKdK(zYI|VSQGf5nY}#_U
z=-@S7M>HU)LF!uuscF;Uq8lJlE*IVAxBa?XbeuDHY&CPRXN#+M$~mCeY6TEV*NSJF
z3Ls;t^T0<@@Qx%q8%qxcKE~36agyG2ujp3KVBZ0c5t=ptq$qkF=k*<ORqi;`?+7(r
z04W!Y4i?jnV8dmz+&F6IngWO>+3%EUgw)h~yR%gFVdvOl?{!3SxOVzdoMLu?X7?kg
zE>NfL4L~SHUI#zvNMLjCpeOD6!jhS^=|+*|dU>?Bckq&qgbiD*hAqloN63sVXNx1L
zX?2upM!OoStSRv#bZZz7?e9I=L{AxiSI6`fgIcuVAn^!1p>WIjp(D1*j;2X<tSWuh
zpdRfoJ=nRbj87hzSX0*ka$%YR;9QtmPn-+s-yK%gO_zxdmeCRLxwAfuTaTR>0+i}!
zT{QsP+^SX3v*82L5eR6@<DtV=z2)(6B=r{O(!haabFqH~WTL<wLH1^@pZJ5E&a$jt
z5aoQzZQ@9BPnk<?pMMwXf^)PdHSAveqANuMf*KGt>R#NUBVa3ad^i%cf-p#XiYVWc
zHMD1G%coRbrM7$|)m46$z3O8>sY{j9FKWsiH!pkAT;6d#vnQ?Py)JQ5f`?Y$<*eLs
z7j#5u7sxk<+6MAXSJQyLDQD%L1f(Ni%VkF0qSbX!jrOF14WiMW(y+lZ+EW@fB6RI3
z4I7taTfDknalVd#Efro~M}!Tk12895><)08(x-dE<CHcH+R>h3&UDa@_LM%|0gtn(
zCBWlsY^l(3Hf_(it=zNW-)kkCS_U>w(+~lUQ+oLc!*+^nbz&tOTb&r6baGt7?kNne
zyV^Zv{O-8W-ShsaRlU2jbn-<BZ$TtF66_hpBf3(Ay{H4_#?~VNa)VXQ+Z#)x2fz*b
z&~yaq+e7+x#q!(AVACri;E|w|(<NSAcOLJCRO6!kY;oZ_SU-DA)dH*y7`=N2PTXT^
z!oY*rVz_mXC60v8Jv|wECID*;KC^MoXzD(qnlmZW4j2;!?ntuxLk*YSdF|nRa%rY}
zNPkYQ$p-nY7guKwD!qvOvxnSGI><Xm#Ggb}VK*F;Cao9LoFl0TxH|Yddk8`um?frK
z&w!tMkiUM)HM0#Z59p?&scoRzkm~G!H8I<I5r6iO>g-@AAJKrI7K;>Pk1W-P1fI?w
zQg=Pjv-_PUfZTw->w%u>TXP`XpuX#ca6{^@gU#_&R9^vdzSTA`&ZPu9FiuRh?)C57
z;lb?LzS%NPZ@$%ZeZbq7S_bU-(hgs=o-M9h2VZA9RbY&EyVPJ1__k9GzB*`rTg0}G
zAE5W34ju`n4sn8y1nnR)^O3M209~@zdeL#V&$o$Mr9Rbpz+ADuE{JM8Q!NAMoS>YG
zaf`^-v0NVsO0`6Ns9}Jf4>b(bbE(s#V|-GlN9O>gPY(c?OFbSq@QKpa^SeIfw@&rW
zrGtYV`-o7g-bpz|!0b)xS}&H)DYKEmWlCFhN0^`OT`dE_ylbX_V4gZPHplIa*3OO{
zbUT%5@QAlJHJ#@@Z)z8(JExL;b<mi%OUniyXS=jxP;$1&Xnm|Ku?7e^+i99UqIyNt
zp8-YNr7joudpk|gM^IgnmvJ8eGQZVU0a@Q_35T`5*%Hj19Xj`wq8t*~W~ZD3>a;-j
z2d#IP3J(6x?$oX)(NH|I4i?Vtg3Ki0>@L+9+Q{zlQD>n}0rji`I{~EY(v*=DV2csf
z;d`(<Ezf;6_HC-=g1SD{Fb-@T>NNN}yGxx0eP<`R?1H2QD4jalJG)DvhSs?|lx66p
zTja9Nh(WtcIi7F2OFpI`vdbVn0g+wGG4h{ZyGuKsfXFV3^aMn9>dUFbziBi()coBQ
z6r|%Ua71hz7%9G4$Dv|(>C1KI*r4=ZC8<?Nbs6NG-Md<c5wuHz1~q4sv-Ygi8Chh@
zI6ii%&p1^b2}ccZ?Lu%mIPG4=!p$yC7->beGX8Z?Yj!7wgIKe9iYifcww`hRQRZnd
zYIc`-8ibl7VXHhSc0oK&#VNV@qg)Eora`cIB&P&!&2F2tj9&h0yU9cyz*LdkdH^7s
zG-e$9H+X4RN>0N~CTZ9hjs#tS9paIol*><KvtDGGD@C<yBv)oPS){>~*^Nx|4x-F%
zGDt_y5@#K8D7Khq9pNi>qlyh9%n`7iI^VS^lRR88kBIF69z{AklIn|eXs}{7xnk!*
zg>FqIX_&NjlSvw8uOmSRfo)B=TRyE<is~nTw<fc60Nt9*(gApDvPwt7Tg9fnAgBo@
z7zY5a$tn%X&2G@oVFcWb3i{Q{P<SM48Hc>q)iMrw;)ZpE0Xh=ag7@(jqw9#OfA&$W
zI!L>8N5q=lWR|X|Hdl%U1ld99->~0qa=AK8yhp&M0f9|a@eV@H5uxpMSNh;;7lfQ6
z87S8f^#K<b=SorIZ)!10OD`tQHtFb~-E5Oa4tx48e%J+3zHF0a8vgA^f~L+t%PPHq
zo#K5RNgWeSX6Xg+G?}GAx7oJz)atG@a@<913r!rTHru3;;|gP2sCA&HNl#Cz&4%^-
zd`q}0*+w-TJewn6<3QM?nRPI1wn<H2&M`_)UxlVd4IFnx+oXfzKIxI5bbdbGsRv4m
zHP%6!ITGw1V9ji$Gw%pP@kmfgyOhaV4GPVXu%kdovC29KG}~mXF8)kCh)oB2?`k?Q
z`HoUeyj1iP$0N(Ijuh+V5ui~0(n%W>m~GUn*Ukdl-%xf<mTCl!+a?_vx1rl)sRlh}
zo9U_bp2QkIl8s6j{=PA(QpI<{ok<hNjqo-`#_YH?J`&99wk+|XfJ4#3I%3)ETadZI
zbvvQ~!N?K@h~Pf^mPH!3>RSY@zI&E<<llg@8wTl(Q{27O4?x>3d-MjjA?QR7ufR<V
zt`6qPkqne`0o>B7i?nh}t1hC$RU!-+Fm_8J-UChZL)xPno*#8;+J<(94IH~=Vg{LG
z-!d_S@Ud@b%}EH^qFePn**jX8$!oc#M3dKYONl10<(3u=X3OpG8vu@pwAIODxv4Uf
z#&Sz(&I&RwZyxn-Da<6Yh_BT%)afa+6~Nvt>+%Nd-E`RO8z;S6h`I~qM9eyZ>W%bc
zGFuRe<|<K*NDA@>%-ygr`(eM_#AGM?MWxzMZyJ}K)R&vaWk<}}BdHNOs4q7)Y6tb@
z+M;<mxi2>j%tw+V<Ud!(Z#@*J#rr0K!S5>aiNL)3))R4Fyl<3FKiA&sdCN_3iJj$$
z34A2AKRD<uN5Xar-HwFqAPV`~tTLXzm!_<cZIQm^SS@QWwOdPS?ez|>cJ#HE8ZIDM
zm{X*;-&DCBgq0&<$I{7RiK*rI?$(|km8vh3oy#wL?Wtx9tJYSqB?qTv?WqSBSgk$u
z;EAamd~jeU6@J>W2^|rqJ1_<ssy#QdQ?|`t)Kod2yGkKk+cll5#!&jSgQ2o^SLb$>
zFv5+gmf_k#Q8}W4a?N&EKQ<<=YYsMghL868=3o*Z5!x!Q@!B+0A3;rT8LAy&+t;R@
z`bhEyX>DrL4x-Bv4a@CRp(5=7%_A8oSN9cO#S41ZhLY^yqpW?aXAM2Mf8sCd9aG~y
zl2r@;=2LnW*r@`!wYEA|Fn1)Jkb=1*;pAK4+!C+Ki_@~!R?GD&*V=5j&Or+S3Ul%c
z3fEd{y})p-rPj|9S>k3n_$q5HJ{SDVBjKn9#t?e$z!<0kdwC+P6&e9zb*vQ{!$g;Z
zZB2AoA8;jbI1-f3GbfMx4#vt_Q~fV+Tx+V~i4je;Tj02s?xDPt?jvEt)yqeMQm%wG
zG`@n$BVo&+v>XweURlDYZ40BL-t0K9tmS&hLT8<Npw|g!Emy6LuDLq9(LG10y4Ka%
z&931j?Cs71whK^L)}l$;L19^oCTT|uowXEM-jUVh5uucCoSL(P=CW2}qlS5JYPdL%
zYc(}&7z)*ChcD9-pUc5eSxaErVDwz#VtLV2*0PUU)ty@%1hlQ29qd?bFT|!{;0Ul6
z!E|sWY^bLBNZ68pTd~y&ZV!$K&D5)0VqzUhjwnjMcGyN%Y_*%a{R%l<I*cwWmRc%|
zSR!XRcq>Q3zLmbZLg!a6=E{mtEdXAG`Zv*^K>ud-Ce*!IR+kl_c>&y!SCx|LAC1+H
z^iM0M+D^2Ksl5;>q*hEcUEN$U)iwZ;j4THm<_JLl_2R><7;3q8ydz<qe2d~_IilyR
zaMejqmKCnfZuHGHQ2<48u8yR7N5i!D8#`)1%|4Rs9kpzSQFH}0ZHMJ_g+LqD)%6mw
z946Qm)U~}=6}DWu=8DdS4P)$T8FzzA$-*5Zm?Ob{QZ$$&z_ta_%aO3DRzqTxLx+ia
ziP7aSV?UBCJ-`{#ppi6gg;Z!}mRq7}Imj(5q(Xz-@<>q1Zr<uQKr`-l$^e_n8Ga<S
zN_j+fa9xgsEhlQm%>Y}DyNO4Hf6i4fw^|0QDv!9AGkr-g^)Q1jB?tEoge0%a^Ty^B
z*%1KXT$%y^;H=LF7eh;=Eyv~2n!#rl_RUa7fPL`t&G7*MXQ*WWpmKmauD+IdT;73r
z6T0<vBsrCHs<D+Lnwso|5lR0>e1|n@oA!>|`89_g0|*3D%l*#3(Gds0O`4_M0dSK{
zX~$LM5(mo>>*h%COmu{1X-AsRBY}^iBOb>Qv2m;UmGX^rp-ZH!BdN)Rw(SPMo?T6~
zEMW$4WxJ-7@1nsx5`DLbZnLI>6FN99Yf5bf$7N0Xs8%y+>Rm_gOuI5}yw`+&?Vf+L
zuQ<AqP35>#KLWOk{OW7oY8aq5Z#7(?H>Ht-Ewhkj+`*Mu%-vF=8X`4vP-WJXR-ROu
zHKda}j)2NfemSTyOJprC4#OJMw-KOcjjhKPC@LelJ3(<sy+#t@BjIxaii1YzBgqaA
zs^FfOI2OJC9SoW^`1|U<lyA^Q)(Eu=NF36~lXY^XgzZ)j7W0=o=rc>4F9&($k)V`|
zV7v->wkl=ZH^wGq+&9K1W&H4Ns(kYoxyaU#E)M$6BRQpF04?P+chF{**j^6W%#l#R
z2W{qv@KnUmdL&soKc{)xL84j8X6^%d0hh>NK5)hyu6BWxL%Mn~Y1WXc4kpd@h_cx5
zUZks6GVw)HnU8)7^%puN4SNt1N7JvXy`~NT@|2U@!Gu{u`ZSm@tNM09RPV|7;6%J(
z8ax1Rm<I2dPvZ0CqpD!f!uwf+>NW^_OF7EDNPP=5Fi*nDa%OLFgwI=IZ#gI|%b_^e
z+C4>%4OpgR;+NwaSgsFsBor=RdMu#K7am*s^Ku%ek0dwM<xArOwkf^%k(|fsm<&qG
za;VYRJC-Zfh}ZtIlzrSmXj$TFImo3;$;2H&XBK!?S4u{f-#RsOQh>3`E~jnUu@f(+
zZQ3XD$t`3P_u9~xm{tx3?U6M8q9%8!X<(bXP8=Y<91+{D659p3xwL5TT$WR1Ce3BJ
zl;)zjESJs<n#&SB%K@Ovr67aid>s+T1ORku$)HLvr6fO+8bE%S^8r5>X~PlIbh*@H
zL_S^K)GQ8sE`=FHn8k$TmlqLciJj%pULHx7fPF60G&nHJWtyJI`hG-gIl)gE%N;D3
zC4QHK^72TsG%=c6n>>`YrHthcb#95y<)!j1m&!b04uvXqte;R6AJMle<>%9-BBu|*
z>Qa!wZ8;LQ0&dF@u^nJvmvtIRA07!xX9+7Wxr6_*I{DHL{>$nzPlEun`clilzAjZ9
z4jQX38A#y8vHC)(1}Ie=!IhVClY8-3R+kDL&}>$pAGNA`v{>VSv$~Y%sDH-xfb-Fj
zP!Yr-YIPZ~;SaOA4A}6QITEx}8sX}%0UIH$7dT%Yz_Tv%brha;*{^YGTufN*K_jXN
zUJeq=Qc`j+63Y@X%fVqe5>_f;yN+l;P*pfYN6S)?;Xbvx%+uLO*`{-RIHh$Mr{SQr
zx{T9^tG<+M+!1_ziGp=`g=k-0N;dc`M>0^ZwILlk?H!90ERTvUy^vP?l&e|Uq9f4k
z{Z`3FrS}F<t;s3SVHjFX=IFqgO%$pl$-Xt|!jZVvHn|H9Cd(0_ZJgPfv||uiR+BLr
z>6w;@SeF--Wi{!`;Hj)eT^KBtrOe~L?o+D2>SZ;B>2VnDjtEaom&#MdSm1SeB$!Az
zW-ewTzZ}k+tLZz1gXbebDZ5P~h9jTWYEp$4vhJ)VU3dW)m5AJt+hK{9<*Q0;6}Z^u
zg<>woCaW~;s7Jzfap|YD<X-031zy)xl3EusOe1^QYSNaGFJm=n#0#hhTV+1Tv&e@4
z2b+{%*svc7O4V7xGp*i>j4dzv$|++f27l#9u-AdVawKdRIM`lOHJqqdCL#AExvVBV
z8XT9^s78b0vYIT_Yd#xGlbIS91xLb0C&s3I0MwMFB;yWh%C*GR@?@i|CM)#<#x+@~
zk&0$Ds?E4|SxrGb9CtGd+$^u#n^R;n0J$c!HFzyY0yh({goVpwx<+Q6#k}H<>^)0l
zEk}x<Wl+GG256Z~*DFtWw$(C@b4p0=xE@>LZ#j4@%M{PgL1bAbb$VNtSOq9&vRWgW
z%QC3jo3>4p-Fg?TZYkaPkt|fg27_D0WinfDWY}9KyY()Zv#G{m?=;x05kq2`U>R{H
zmXTxaAk7>J+kQ@eCY>FOn1zhx4nE8>>Ejy_&z2IDJ7RP!QLP+tJdOl=0&=7t$@`!J
zWuwNuM;6#I0HacrA4$!&K4;u&FMBQ2xcgov1-!1ukAN)?EIO*+xMW|<V}7NmR$a#r
z^5ZrcsFOsqObR#%GRsK%D1OY95^PR8(Eo-~c1wCQXa-C9%Y6eo&17Xj&faCRNF%TB
zBSGmrR0e5KVV2$MDFXd3WiNN+7hd9QIoL5rg59UsF-O35kst99p_s4ymPHyYkaY{^
z!HikreT|CrlM>vA9Z~jJsmhNeKbRXf>QOwFQ?AYp@L-Mv_VNL)%*r(617w$VQ!^eQ
zyR19-&?>NF_13O+lRG`Yby><nJ`lZSiRm@SfVrt&j|%Fv?n%qX0ORP0&@!;_o@%|<
z0H@mS7~mu`dXT+x57h$rf#@|VIru5EFMzh&H4CG5zr{r210h=0O;vf2^m6-8{Kd#p
z$LkrGTc`3r5b^7X*z|l#UCjdAMCuwC>bg4`nE>j$tDQRV-CdK71D_I)4-#NR>N=8i
zk6X$sK1gp7C2N4pa+`VsFuP5Yu<&9LLwnR>T*@Inz)V~>6zT!;;t{YNK-qnhzH&r0
zxwqO*FuQNHj4MF#v<6u)H}vpfyzjfIiH{<|#HI;)fCLjtM?UcVhuB&Jo5~e?>p3;P
zPzv&q5eGxut5ZJxJCgS?r->s0$9Eud;Str|Hmqj<NHB<2Jzi?Mp~w7vJ}h>q<=TB?
zhgz=vIX0E=@$BERLyeY!GnA!#fGrbZbPcd&9tlb_yE)ZrYK}+1M!mkFP-^p0kQQQi
z4ZvRPsb(CrKeKdxJxD4XpgD(FTLX-k*h7yT=;zQQ2l_ftI@X5RuAUd}h4PgT@MA)}
zt^tBfY*)*(^sU&gre`hzSHlxaz)`B#-_>wrscz_o1-jW)KWa+#9b2HMRG>$xX(_3F
z>X7WOEVEM!ozRC4WiNKqa~GDO>ACQA2qx1U#fFJ(nv#uoXPT0Ycc+gZjF=<g9tb5j
zHZ|`7)i{_)b3l6z<<T6eUI*x41LT!hn-vP@Vo^IDV6(*9sM7Lpwpb_@rDk6c<w6oc
zYv9ZgYw4k7o(SZ>JmrNtL?1Y!#G-L}v_i2^^2<@NjYA}^fe6X50?$RRnNXg~@f_Sj
zIW7kdb}7LGB~AtMR1SCnMNzM6fCYE4K-L)WCJJS#95||ml2i^HX9MT7t3(Ucu$Q!%
zC4A#JGzarj4xFiD4Rv;wRujrjIlyxXC8r$4bO|xE21qQy#FGOYmMC|O3!+n}>#>11
zrf&}Bi%`zV0bjFV%E{|U>dklcc%ge8rR-Y!cxX*`Q)f3eKjowx6}CMkY<Xh<jU(DW
z)pM}{fadZ@E);9MnHt_$ZZtd(7@b0CC`Xy4Vk!U4faxkk;~Jo}JQ9@Z6;oXv-Lk|s
z@HK}LlMk5BVo_BdX<!Sbusr1&3pM2<so`YQy8)|RC<pl{DoYCLHGs+z%4j)2WeFs-
zyh@Z~Q9{cBzs`uN@<5-cTLXNT2rAK}yM*#s4$xg9mYN0pg;edLyo7R;k8*B(lm=12
z1~M{)l8_IiZ3vOKMju&X4FF!eYBJJ81e0A37==T*E=SpoLqx3s({jN0c{VE8pF?>r
zM+d|y(dB?4JDBHkBnc*z<8pMc#R6omBUq@xrXx!nU0^1uR(F72$U9<yyAnYq`9FU9
z_t#m8_tUFqIYk@KBc21&{e1b|{M&!{x8MHzH~V%!|JDEg=f7Tv*B0P${q@_f9V`^z
z#SqvzTuIa6gBe{}z8!{(V6<_=9eYTXwrJm`=)qQ$+RU<^f=ti*4e5F_Iw}k&l`1l)
zrFF)P9*RlqOl;+ffQ|Hfb~h0cS}@AK%nofU{_`7c60t~;R=6WAz)k{KFCYF2G4sYs
zs8|;A9RVq8x7U9V?xdz$%Nst8TiU;u``Z#wd2S0Y5ALOIy!VYauQ7RL0{ejM>mL>!
z9tL2lQ+(eSc7xhuEh8W6SV5mZ`aYRQAD!d2J?-mNRKWkaihi+z2xFfs$o_T()q8xG
zkTTh03E|(lgp~B*T|#{A?;28E;$N(xT6&*rs8+(q8hXR^zH3NnTsFg?Dt^ny5^BF(
zLo&i(Aypirs-<-#=b?{v^twUP+i<~}gM;8^Jmq&8{bC8d1R<=U_xia`@A|agH6(lQ
z$0FkC`&~rTK{~Wx>43F}_I*~-vvzErP3ZY!xLM5aTSP$3Kz>``YACxcU^fD4!K&Zl
z-6M5$D5ot@Jc7scW!PkSN?(Rew(h)^)d@%x&t-rI9MKn%n5%dJh{+gRL|p|ES_EBc
z1Yop>^3#I!9wK5ECH|CEBUfZ7IW6Lz22;}_G-@a@EuyDBf-0QH=}rrY&13Qa4&5@8
zi+0uT(HNk1;@}Nuftb2ghC{(4sX`5h$L>|2s|>aa0IPJhOc@`da#lL}N5GpYY?C2U
zW^Dx_N+w)5qPPK9N%B=>e%T7b8%i#VFukGVvN(i<=$mV?Q~XqLm<eT?&C^ay9;fjs
zJc26JlsZWmaCwOdgojs5Odh4nZzhzY7D0_8v(F;paZJS$*f%DfmrU>y3gwhV!1)j(
z6XE7#@|3*6rU_=0E!U$^I$6Ys4keUD80nbYIJcpfqI7OUR|z@$6nKE%IAKm4pK%^P
zWi*L^^#LO1Zdgx*&N|V@B#R6FU%@oAh{7FH-yq_22RNGB^G|dRCr0I!h1DVkzfV{;
zt`Hd$){j6+*>Zae<&)hwV=ABQ#tCz5ULC=AF0?hnxh_Q2%xLMMWV64(*ImcZD->c6
z(bhw>PQ+sm=?^e1g-D&dKBX9oFok&XAx0)*&L08Zex4!+KT`y)53w;f$S;v>%pK?y
zbvKymg2DI7lox|$Y#94uC@x4@1XF@0Yk(mtChUrlOw7G8(bUutd;SW>=0ouLP-MOg
z`X3@{0@p*NOc+Fu0PoIj;F36%M^c?&ED+0QP)|2_)W)De+ioZaL009F)S}`w@{#1a
zqCwjbF+LQT&tQ^{ip+OGl#|-j6wZcZWEz~2j{w>{9F_x-`RoS&B@~&@?w%#K3lJk2
z({6y+Aha6n{V{ItSe6$8p|E>~c<?dqk4g)b>aq2E_5qQHW8CTpz(_&&jwHLLn0tl`
zk5J6LBYC=gg;<+MlHV*?n|1@Fe5-M2unf9qxLOI{)Ig5t>9At%opR~H3r_`%IX^<X
zfm;f&XE#!Ghe(=MS5D!f{sX=|)PLZYqV5@D6kMUOdxk&;!LWOlkq$yUPP+kNKGigE
z%#||EZUC7g?-?@VgikeISf;pph73C)KIoC;DikBsaPJplgc|M!L(%u1lSP)$a9u85
zDMHH#8WAFd8e-Ci_@9P6MUUj$-yBwQh{$#nVuKz@4v3drhD+B#u35viY&h?$uOq7Q
zz%F+LH5^w@PKic2Lky2lO4%bRFw}X|kZ3Ag=j^(c4&{n9++2s~o`%cqE5!FSgKbrO
zPs25Nknd^cSzup*ly2`l0V_rLG(<)T5k3vkQ$l=CtGr#|vb!Bgt!HD)Kuo2QHRS&a
zH<aov-)cDh>W_f!4!q=B<C|GR3$VsIt!{>B^pB+aRA$z`)$KYDg%ZF%2b=0;e@!QV
zP*Odw6lGWY#t+Uzm%0rI?MwZxuRKKcGzRtwaXk&ue?nYOtN1|Cmxco{?JVW;e6zwD
z0udci?crd*L=Ux`;F!r>4FsDI>+?to?MeHzin0`)Xl;nZ6w3d4B-Ig`*N&w6F$5G1
zcuJn9HOm6Jh5Ua<LIV|!dP)&%jphZ>JPiS>j)YAEP)YnWM8Y}(wpDQ2oqPjBip1!=
z(6$Cssj|Hqm|p?jrxklFMEtz0f`UCF;WWaAg_xg)&|=XUnZOW!EI|IWh9oN?_NRdk
z7h-=}1E}_<agVgb&^80a?6|5vg8XDf{XCMWI(#PZ^0ntQAZD-a^!oYl8GRZsv)><v
zp^;^L5XeIsiqv;m!~LK_^%-)ShN!02fUGoy83NXYxTe;EE8<2m2idloE|?X~)R4_J
z$RRake2unw$~4ePqY2XM*P%##23Be)QlEjh8jYpWwnPcFr;DMmeAaOfsIYw2fpQAV
zXUW2iH!$B3<U}SP^ptWAMF=&#f?$|F!&?f4>9daOM8@e$NiME7QObqYsBT-wVNEPe
ztK7!XUiBGV=TJaCLkP-XKt8J=m7#cihCr49uk^F8BG_e!-DwDj8H&hf$j}^$$Y=e5
zv?eXQ!x28n?mUuQHllYL@<4~^orcXJ6p_zr|A-36SAzsxk-ur6pNIIHmIU=v=D*kL
z(uZ6T;;$5OJTpri3m~kS#sdgzRLjA?k0w9KBdXrpPy9*tUEex3_-Ojr!Tk?$LN7xE
z*bphy5G6JgtnWxhma%yu%xr)XYMrM=kwOi5%tNG5L$dP_Dby+-dMI9>RnqiFxiKmD
z0M8IB)DVL{L;|&r!y@DLSq9$?Therq4L)q?DL5V)6ndnU55?;<q@EAP>$|K}j!?ip
zgGLgfjT+omLex=%9uuOD8ogaY0sG9W3R?y$GFqR(e<s8mwG4I-gZl+R^`Dyn)V(9%
zO-})!X%B$H7$$0&At-bxwW}d;bbuFX6@5BP(CffI(=Ono#puSyN^=gA)(!1Ckk-}U
zjuj>>Ml|g(e+LQtGwlL?9xAmP#_&Me*Hf;=qwm{6jWHd(9r#BE=pzAeDOamGaElaA
z!?EfLlTz)0nG+g2fXhs?fV)A{+1d*lu0S@|BgpABEe4zrjT$vv0K?u37@(Ue;HJTu
zFqFvE^5hz(Zx{}VAug!lv>VLW`Yd=rq6vEI%p6MCY7R(LzE(r9`w;o_NRp!)w^VQk
zMMn8rZPd09OxJ3#7R0SXc-j)8*r68$IR>R>HJBuh1T77qqjI&{06Z4=?<z^FCj;vS
z&V)BhH6j|qkEHImg!2Pl^`TU*mYvr}4JX+UhxABtHDtn8gAFI{`3?`{8>MVDgscx`
zY&C?e4-rO>BnLA|7dVm{jdb?`$jx-E1_$9#ZdMy!rF!Xu;Cf3<hs7+Er`6!89Jdq(
zcr!l|l+MDw{T&|8iX@=gz*+H@wtx&8p+v8SBpU(7>s6wGYHS&to=o#<2yY)Ep&IOz
zp=7N#Dr5G?g(dD7<Ca>FY$U;Ctw&(EC})2QI<L5)42(q1TRX`Ba*C6BB=wS|4Gci%
zEthE<z|NcMK>6>7SgM9}D{*5VK@j}VJ+&ccOWe{125?hpUJZus5GU0T$slf__5|g0
zieYLM4`J#m)sV;LNYKAo+ss62)>A$&Wo`u>vRVI(od&l8Q}k2Ay}{f|&78qbC2BPW
zk(e8(jyMx@)3@3Xi(-;|Y6w>`#Xhyl4m7u-7+IwmN)hW+=k;~t(s?Qg>ygAr!GNZP
zARSX=Q9~5_BSB}pnwBN4qS`+aS<)sBigU}9HXYs5_lwJ_xn)h8BTH<!KGLZ?t%kd>
zxn*0!b=lklr5d2C)lma<HHzE6$uzBo6k1b!(Ic7JaMxody4v-e$Px&|h9EFgIav+2
zi*xhB%n(gxidbrhIP*wQI%|I_AFCl|%~V2GLn5-Ngsg^SWpne+%$U(^ihOFB^la{?
zh8ITIP^tweyV_h>fJVm^!)5Oj@zm-%c#3ywxI&&v<7ySZer`h{w~DDeu7&{ila$jV
z7+FNe>t;J8cx2q@Y_io1cj0sKLd|enKFLb8x=x>q^fkkU`+Re>8UioPCEHpQdd{`g
za!t<^fAv><kwAd$xt98JcG$TVds3E_DH?+z;Qa)Z)rycam%P3V!K<cHy&4!7b4h)#
z2v{lMb36K)o52~NX8{{b)LNgSvKrDKPUU$uq)41g*7<;U;t{dsgvBFZ!-ba<3|NbT
z%Ts3C1($Qt>&p;wY%c96F`p82d8Cz`qP8AM^%Wc#ivq?e)~XdzFD2|)pd<A8GLZd_
zgbzj-ib-y(WxTh!WI;znxG8F@A!^)QU2O-Jq`bZibi}!2R|ki2lI?1sIZlyXt*DT5
zDVV5%E;+?`HAK*xODcYB^e0P|9d(L@Y76f4b4hsz4`wbZ?_k2rrSBM2n7Qg1hN)CU
z1Vh-tDRQbIV*M01)iRCjR0dZ=qS;Aq>Xo9Jy0n>LP%~sRD+0_EHPt}koyy^A3yv65
z<W#GOjgLfja71;SWSbgTF;mo1!~49ZxTS`dK1D7yER08jQua<?DpuBvKx75O>YE{J
z8;I32WNll(MbT4j)l=Ch?j@)AsRl~SBpKB}i#Y<eQ%ERw>Jj8(3Izc*aAhX>sVON6
z93DH-S*hI%$QabRFI$mCeC`NkIz>J;WSf48b+&+viZo~o*OF8DU9CtpQ|Vm|-2TZZ
zf(FXWR2V_aZS^VF=nAjMc{FVQGla*0h?#j?tpH>y>YptFnBxA~27ra|c;D!iF1q%O
zZV8Ulfnru5zzc%>6p{#PVA9MG9)n6VL-$-8D5r>lhIHyvd0h=;nHl`|dQ(E*U8Q=p
zP!1*%x?UyfsKF;Do+%8VA&Bt|!876<&x`|T6$tt1)D%1;CH<U)=So^X6$a3tL(QoV
z7>t@(S#&Ola%@xZ3~g;HPps_+^OPdipx;e~610tE5l6zNfq7Hg0LV8}5eKdKH&aPs
z4FsHPDod<EL7fUZXsN`WD`r|}py#FptCb#BN0#Mz{`q~u1%xT$(wbnFGKjN*XOj}G
zt_iZ~=5r#u@-Boz%M@{a1!%1MCUMum*hv{XP%1@<FhB7Vp3WCjn0Z9GKfpuI?xlS_
z8(-ShE2@5pICyesskEI3ZS+ymn+*({5@A+%v3B1VxY3`r7>UPlDm*g$Walg@o^ylm
zVv2J8wDNCEK{a(9QN7f~-MqmsGDRT&7M(UFHAM}F+Y~|ZYd8WwvdIPwlfAgBw>(Lw
zfXx{Pr)|B#aWrM%u!E(OWM)39v7?`a=UH74S)n2SK+3>$zk3zIq6b?iMQuQWPSwtQ
zl?<JtD%B7JKSi8%#~f2}Iui7})2FH-fkVpBqO<2+bL{MR&tg8dsUd)B$~ch0HP_Vo
z;MlmmH<+MGbn{mS?^DFq2j6ftH@S38J(zsorVhYuEM@G$<XBDbJlIcpGQcgoM0lCO
zPTlHfuv54Cx!AEA#p;xFuy*5knKCTQm8(z=LJiEG6tR<wRQavuSFNg)vHgutKQ@Xr
zG<gcO^2IL^ny+@R6tM@pzA-6u&2EfL>e~@vblkZc&C`!e-z$vRDZ=+thVGQGqG4Tz
zc>jiwHz}*Gf|HXH_N%d9JR%(t`lS!nnr3~f$?`{#qtFpx+6UWfoOODK91%xYC#;5B
zg%q#{9pfA7K*zd!U1}KCqGXsW=i700)A4~Qm~+FOON!o#>{eG-2Rqi$Q=n*cb(Am~
zT|FI|cAlk<to8#%bv`1zil#oyDzf>>JpnEP&4{;h5@<%irJF!A!fiA)Kk@C!Tc8=i
z6y5;M2&M7|XjV{4e}IOV`&WwiXrk%sf?_!zw_X#`biD(3WKGjQ9PGxnxv_2AyRmKC
z$!25Qw(X5=+qSc@zsZf~eZK2`|8uUXnX0Z<b)R!)>UX+2zGWju7b7&=!4PAxBH=fC
zv__uRW4ZM>E20adq)~5yN$3@a`mZbMUULf{*%N)(?mGp>u#q_gEk2{yAK7Rvv%zUI
z16bA(3XVxTGgvu_&#D%EGZIvi76AouqVWsC1(-qb@TE>%LR$1b3v&lR>T;o1lA((?
z;)Oo-h?<9eSHa~9*aD|Y<%{q;a*_zD6~9oghD<%JFl+d};$UpMm?N7C>-dLFfa~GZ
z*VT){H*ze2c3sDZPC*RLO7xjU*m5_}Fz?j(N;QdcXVwqZyEn!aFLs@ZV{-C~XIA1N
z#1=IsiHcVO&7vDNxSIA@MMQHKXcBPnhq6QVtuAk<uyJ4=!_$-wfq(U&<;g)T7<K%a
z0HL)g3ycMLoJY02v5D{=%e?1F9%4noT#(pS?wm9mxd5V0t(hmn{VGPc<cdO-v}t8i
zY400S_F;uH0(Ft$-8)ye%lBcx;vcShsc&WEUu_!HxUQlDfvl$iMV=~eKvp1Efj1?=
zHCI9xLFcMB3t@rC_Y?->(zhKG7UW=ScaiVcA$JC`Cdt0yaZ~xwCn3Q#PI-JO@vcBF
z-`}3<(w3Y))m7b$NJml!tY|y>E}TakXAV^OBXo*{s39F0Ye%k7JcCFPo&r30Ka0rH
zEkm3q@ENka5_=AsXzX_#vY*1m$(I~=l+#=%5T|~_O0sdvIyYbXH*9q>2zWE(j9`rm
z=-(TN#~(2)<BHW%fCwrld?J^<QzgpG0}Iy}vPeHvtYIpUol)IdoN_M^#(z8YT+llK
zRa5;80`vV5YTm^S1MguHvQ&;SSAm=s#2l=>#4R3cnNhUaYcvGT0pAH&BmiNVmb)T@
zb45KEbl`6?z|6<EQ+H#znSOQl4X}*XDefJ996CeiA&9tSo)SKoxU|1?YGFKNQkGc2
zVW*A?<huh<y(dZPP4HQm))u7N1@buLPG#8AL7!dHb=NV<8DJ$%{64&$@R8S?pHHK`
zqp56tLYa_*Z-s&kV0qstR}Dw^f(hD9jnF#r#K_`y@Kzo7+~ZaUtxeE@usYdbE{D&;
zaE<9zHG3{K+7PdLd8<1;gQ6NDeGf_vsJ}khY%Z!7#mhHMm)z3Ps1@M6jd`h_;!*ys
zW=Af@_!{bfKe7;BJipuN6$MJM7t}(V3ArZAp%}e{lR3Q7BALph;=n<V5r->EU<FGQ
zG6uy`kj6&Izd3nT>Jk<}Xa=$d=gV#gV++s9`dI<!#O^y#s<Q40bgsJwE*3Ayevyw>
zHJ0{agc)|9L_nssAOEtO*a}!wQ7HC0SY(mb2-lGi#f~zQtKs=CSwzlO$GdIv1wl+<
z+58BO6;yfP{O}4lS(~gA;+Q(26ny`2+KrtUJ^QB;xE|xI6JXsssVw|2eW46q1z&cj
zg4lyyLJ8Nw&f2u_r?NAeS}jfd0ykuFTje40eY}VyolBPd$d`3cJrGD+JNgBZ&t_`C
z@%kc>$-)A>5{mCLD{o#1WGNk;u>FTCCmn!Dscxn3LJ*eRxbcPg1B$Hk5UT5Z*u=Qj
z<`1-tV1NN3(*5<Mdk8_50qg3<Ear$u;17nrSH4TOW(rGle5;q}iWd?DJwKAf<l^r;
zlW#E*Fix_wL1LIC%aO??(E^cFwovqjv_hgyL%D;jw`9DO0nsaCB1rFG5{DWTMX*#H
zHOWxiZ;jStsP)6wV<7!e^CKmbJ848HM~2^M_O~YzW!mGQ6%tii{jo%~CF81$K8Y9V
z3XW1wziL|FXke8W5=~m<Mcm*FDK=i@CIu0rw7x-}Hm@6)6=#K?_ieDDN7^s_Yv|Rz
zUv<YXS=_d)<TJ?R<RAX50F?H*3h$bJ*)T0lxQEop9SIU!+9CKL8ssD^?)#EyQdYR#
z%&pnv>o49@iDLh<o_W%k+GA>5;Wp9$cBt!A-Wh@&7Pt2X0QD{qaI}#B8G}V2k_@y~
zQW(r7g|MC4F$&bf;+4?dtDl#M!%f@x5`ia-6Q3jiy^}qBh3BNp?3LWztM`mD7Z;o$
z8mSMhTcDKT=W>f?x^1aCxN3`)8nItaqs0p0L<%6z_GqR8<y29>PH?6t4AtSYGmiVP
zxrx=YRYylou$v{7M@I_X`Gw=j1j5ur&JenZb7fF!P}AnNfON6=ME1<2A+w-tnU7l$
z+wvLA+5{Zye-Uw(U$Q}j59HaFQ;xIcD|$_nS^@Y2^NcRj$^ppm@K?23EOixdS0B$j
z*soE5Kf^@Zvl~^MP&5(LduVOnS#WdhwBmEIHd@LQvrgyH80K^}bcDbEX08YLFfww`
zBYK)ye@iO+<(bH9`2YCLQr|B`nvStTq`Tsws~wO`n&64ZAjA1YWS;6A-k+!c+fOGt
zCyy~fW#?DyTsU2Bz9;Gmk>rL(=={mii%jVsM5Rj`^0l(++r*ak;DY^f+l1m4ZwnVy
z=9dw_9Gb7RvxM%z+Nau=zQqHcy_}s8mG=6kVO#DFy=r~R2WPysp7zCV`o}avp7Ov7
zKI=w^62~pJ1(r2<SiL!a5;r<ri{qOFHMkWQ`cJ-MK35pr6Mfm7TUSvGL6!jO2!h!T
zgYdM7QsYh^iOQi#^|ZllK#zXLTj55}c`jt|Ml7~b+od}1j>-1tec_VAHj;*@(%4U$
zLZfLpPM$)8D`-M-oynFD^wPii?tbduZnl{KDzxf<-kO&zXFbEq#_+O0@=9tr`YXo@
zPyVv-K4RB2m&ekV)f}<PW_gC~Disgf3cXJsC}P0m39nuTnMNqL0oGM1zO&H{rM<v4
zjv|xsj98c6$g*i%$7ro_-0z-N<Q#$*qzCtHHv+;%7!y&}8iuBB<C5lOMKrjX=4OSq
z3t(AL3@MFFm<j-msmK1CLP%lTIaDIe7uQ2}ebt>!$vIE?O08C%%IXcXFrtic4kkML
zNqIjhamls6dcVl(#u_Z;t^m}dG6>JCN@j1GdknOe$GK@X;W<p0m!w^x_~yB`tDg|G
z!!D|%PBzo9vf)`Ey?_UNyt%Rwt`Nj64O?KK;#UtTouh}0e)9(ky#<_tR0bpq_lnK&
z>P4OqVYzF;95k5gHb237%*_^+wJaKRzepRqkB^EBnX2=an9RdxR1;J9Gx5?~RTkK2
zYXZzK8EfIb(k;_)2uptKrnj4uM5iS#Ryvz?UhbQXz%SMJx#E(!q4@BdCqiI@tV$*A
zYgSH_6a_X`IGQ7gO{^2F1(BFbW?r4NEECN-Ns>*Qi%z5SSmZzMyFs`#B(6O->8nWR
zo^(CDnCd2BF!aFWB^N}Ke+dt-I4A!)Go>?HVv_*}Ni^DI#>Jrb6gu(u+2&_-gj*Wv
z&4+`;&?e{jrc1!T?7p~KtAjACg|94j+gJjfRi)Uf=7%8JR~fN{R3ZcdMjy}lP4`NW
z0`mtI+j}i{i?!l;0nf1QmN+gFJsdA-(3kMM7=WIrV}xabCD-Ys3Sa9V4T@<?KNQIj
zW9;lH4N7ELa^ST{#tL+KkfqV@GG`Me>7p{YAoM*+ZPZ*1yedQs;RIhX+rf-c@r*PO
z?AmF~7s_-;Yjs8~eXZ1-$5-62@>bU#QyE@m5G@BVIE2D<2E;l0tCsOBi?&z{_%rnv
z%dfJHmMP-d6w*^svEp;*VBWG|oYYivP;!k?69{%`<VU2xISqBO(`VSllpds0Vu+!y
z7cJJD85Ff@;$+NK!A_C)x2f5Q0`@D2wBD7lZ?I|9U`5EYTpOod%XDP}r5h<>XBenw
z3}{`p*hv9dhY`t6e`W_lFZkYMqy}p_H4f1g&l#(W(>S?|yLrOx9cs!Hd3HD#o5~<F
z$??+TDu^psU1mRptA-~IZ0nq}n?$q)<4gXv3lr!E>$`CPe1R+p1`+=#W2yP0RJSdd
zZoK|>crZ8x(u6AV@XkhLtzwuv;&@kx{A((zT)gihOgg#Rjw&zUqlkD}vu+^0{lO9&
zTQY-#J~3auJ`I({(NZDF@%o$0eCzLiQ2{m^p*(9*0{=B=PVhwY*pe&z>fE(*VZlbD
z=*s5@vMqZ0ta#Z9)Pp!q4c+g&6wKqgp0&%&R6U2Lg!<BVFnfuR-qHH=i3KMvCnX5A
zEZ8a<i8XO;%+%q9;tfX2>zdgswR5lw&Pl)zd)!K{ZtA$Q^hAip__FjzSw>UXzp4U^
zn3%2qNF?yMl&)&Vb<Ih9u`tW_6ubo8c!-(pw6LK1wOJ0rUpRq*fyDo0dgzu?+NiMD
zUk7E*w6J^AeYttJSjj0bM3Fj9;Mur;hJTKJ9W!fUqN~=j<pmz)xp!;BP1T(C>q~(t
zn;*mo*apmcj^{??PhvrerST;)iD_%&McMhUwgdVri3J@R<MlLv=ehLfVY<iyN-=}w
zLKT@HvOMc!j0t#`%Tuko$i9|hwy0CcjstoBIlk=CJF_XEXE8vg7Aa9Xk1xPrA*S!C
z{a(+I?s{uf+y(J;G|F$fjM8gtiCbvO4EpZIGa#90fnsEQ##czd1bVcbSoc#wP8?hw
zCYLPhxqFl@l#a<TP(C=N#xHfUM1Pcy_vGVjp@W($Kmn&DEKvc))7X}eqdve2h>Id}
zY|E*ZfsqP^EFcIIMV1xU+4B01vdvmdxx3xLYUs%*PA_n06MXuoP{=nD|5nuXMVe@|
z%BQCvo49J-I44$H9Ha6bxu(Bx{-ktqaLgrb!6g<{Y3N)SxrHJy52YJny&9gOWMEK|
z^#@{pmyOgeWYnoTm`Yx?vjoziYVRb?gFi^!ZTR9qGrDB9a0Zh}8ss&kxbIv=o=Mv8
zgvmZ$>m!d<Kg@Vt`+G5BHhDP%+vUOO+Fa<ZFpqSvc~1NwN(l5ASAjQZU|N@vW2FFO
zWUu-5iAt8VWO;Ow*~>`$g&LGtI^RnhP5y<n_1+zpXVK9KnpsD|GLaBEO|TB;(M$tl
z6rHevT8p_Oq;NM;lLuOqwBIm=I5`fFvc;Pp9VkZvs%smfrq<V_Ry^zO+mCY@l`KrM
zh7;6mqmon^c_k`X-NEIC6U4LkhQKP&kDd1Mdg_<Lmpu8DvvxCT&`32>PJ<eTV<D1V
ze^1BmM}pw8b;0!L9x9Am>Cl1NikkGwiC}iQmIo(~z{5&qOsgq#B+BVgK{mQ6#`Sq$
zdor<>5?JY@HuMxARt4R}?u9cTviw2WyHY6KaYiTT<eA?kriG4``;@#aqdlJ4)v55n
z^k9`zr450?a+3861U9uI7Ex9!I{Lu61L!OwJ~UD+H>653ii1@)_JH(9%OYWm2sw`y
z<0&9EieWXXwF7eGCMM@ni$Jlsqw?+FpO!0Gd5Hs3j2m}Xd+Mn7ME}9ID$mlp+dz9>
zBjd7v;%n!zz~QVREu_!wpx(M7kRjhwe{X+5A)^l3EFm$4)%(k6yWb~HBJEl6*Kj@r
z{c61Q%4>8<X>JwJl~?1{nVwuhi@x-_v<~nNYQCAJl(--BxIWcMca4me<M;+ZOrC0K
zr0$m^Q8G&_)nK=Egzs4}Oky)eS|Du!!(ZoQ8o^*5ipvG#NlL<HAsnfi*dgmCI?J}z
z%>;#92TnM_EaQc5>`AKgzJ(Q2)xhJfQ$m~alqqpFgK<#=!C)X64ble_O<G`U!BQg*
zwj-uinj#$q2^@>mtd;1FyRr(pn}5aNabTX!%|kA`QeaO8I|t)2*)c;a*^h`W>#SP}
zcCVYglars(Le9G&tA)b1n!Qvbqx3>54+BD`(Xx>F?9dbtFz@17!t0pT<crXKl#jvS
zH$AKY8k8z{SYZcRcSfwSxsV)uxZXNFT8riOKsv{GCK^h_M6|l6fwBm(b;lU90{a@h
zzd}*UdA;1kON|U$*T$0SGc#;FVOf=x|HU>!!Pm`#x|^Y=&B=eYus!xUJew&dB7vs&
zT~ZvxMeStZM2gXa)Ww3IVe~GPifJLY7LhT{bzVa!q}?;2Dbfi;O4IF>3fMI+wwq-s
z%^#nsIZYVNy<I1rM<!$oE6ko^XiT+P3UV7O%ww6ed9XG-<3K6XRrshjp)##33dB-&
z0}Df1FqKXLUF)Vp1JrN0?Q($)n3b%19EP6kQo|rx4YLKKtu)>)Vt=Xa4$^02SR=~^
zk|Ty_A(3K8nPgY2z`vEc^*QMo-1;^#xG={v&UYThDLo#gQegL+d^6hNJDUq5ghljt
zF=pAm+i6`_sJr%MwF7mL<kv-WEnd2eJ9_%`HdRU?c5*r|lx+K2B|BKaC8r8^VELi#
zR!R4gkgg)Dh9@Se#Z57^>PL1%Z0rO}BX_MHyWf%o<i0vE7sdVfmeZfq6@y=k5;-<t
z6>&2oEV>z%6`HHnvXT@J^tu^qQ)%7Ddw0dUnvKD123+Q9Et<E|i6zj^cp6p3Uu9oU
z>I|sPH0EWb4AUBiLDt}4lzv|mDkyyqGq&t2=yQN&siMAKGr(S0rM}km8yJ?thu2NF
z;&@@ZEA|k#!yunvblQ$H$-V^lNDLXOtSL)DTGmQrf#`I%%brT{7u6UpO)Gr+<znTf
z73TC-2B`^JAaQ(v^-V?_Yk^ohR(^uzTM*Lznt{f>RFN$HaD~;z*q^<H(n%AJ38^^0
zFN))6BP@H`^0z7bW!4~*F#dq>8maSzo|&*A7%%s3=9-fW@1ug|Z`$o}ZrLb^#*n9V
zGK%ZYrF6k@+*}Qp*}_&yMw{I?>!5YUaTMHRq2@yhrzRmmYm|)(ePbmT2@P@Nlw(*a
z9Q&zh-iRX&)JoQ^>o`hhQ>pqpcm)y`As+Fh=e3IKbFD}Zu5j|L)+>#I9ZVXr3#r~Q
z-zrEZe#F*;z1in4(NQsyig;t*j@520>stRg!}KI(Dr#TF;9B0_!tMX12H<e+(0FA^
zmed<<;=?Nlvr=gcEKDm4qv=NNBV#LAt_rzPu_v$!Vyr7zBpsjx%;F0P>2(Okmpzuf
z8(oC!7l7M&zo=L(h~_qIw2hb0Cta}?P1tdKU*>8i<$H(j)pBd0MW;CnxHL!sOKD+c
zAG}etvW?WAe0BPb;Br7V!GOhmlY7*d6IS_xC%(&RDQ8%^_Ex-8k#NerJ@j4T4$gnh
z4)?o>T8s4^?|{b2f}06(Q7y;(u@}wZKK!0dyStd7jTNped}w+LgC7(nHSL-lK)?Z@
zbdC5O(^=7>l|t{-qXf9EEm0Ta*$Iz&e9O~NB}eXhe1wQvhZZOt-kWZv@8>0N>2sZ^
z_DM!sy-r!AN)AeiN2SXiYH;qY)aCXZs&e(>mFV-x$E8+YGsH6U6_f9^j@v&rkD@Ir
zd+&rP&CgP}=4mAHyunGqPDARoL0y_NhcraUCOcFfa0(ux?JIT2P?f)^h$-<luB7Um
z>YSJ0hLhzt9O!Zr9*xoYzWaZ%X=l$gB5c^~-dMB8$c&yy?Y$NrF2_wi!9CNyu;nI<
zX)wYxJdL&4NQ|4iuOp0L>9j0rS^HB*sH6!#6aukN&WA8v#N-vVFDP$5VM<4&7~y_L
z#Mz)j6SC;u%R0?yJ|Phr9llb_{`(m$z6{o^*ezo^`1_Ysqmt(b$&FCuHXB3eVh)CH
z!8&cC6E9I(EV;!W{g-77QKk1&*<wm%He!8wrB<CSFs14o3&CPaRD)OyEyecbggmUB
z`b8}mAbp}R3CQ(@==Yw3kZQ-YB(B_*tY9?uJTuuM07p97eEp_{HQMy9v&l1n-W#Oc
zzhG3>#-XK-$fgeI_FOuUJ<_kUuLNV&(FwI<@EE%&`VzU5Z}amY@+4pRy5}03gD1K(
zxKCV47bg`!cNU*loNCS~_rQ3o)Y93{`q65Aslp6L>2e@qrd@KK_>tJMOf4gPyS1U#
zu9`>-S%q07sqbf)0v1@K;8he(wpp`clgCjcd2ho|H%ZA}6RE$mr3Mzd?BHZlLT+4)
zwTdYFHG+=*aH-Ix@U3V3C^Wt|jAMSw-m`A-5iS5(!NAibg!({H4b{q1Ho@N`y-uo!
zOSbK$M&?C!Vi>+uAWCxM!r`7-x4`8v`Mk*{vZC({vc7HtL&5rKLh}07*35w%oHqim
zc|lqSQiUXx1&U&wld5WTrb3Rg5JG7J%X$oN%Y){6;0(B<4(hcwdd16`we@5mpP>+k
zRV>cnJ~2bXXuH)Ay(%K6bTHq`jjoNfP?OtLrXH?JXwjdXwW{GBq2HNWYF^W8>B?tj
z$BD_>g07cCQ(9d7;i^Yh&@|1j+kcAHgpU}@%E6giFxSEwCpO$IMsqPf%><vMaE+Tl
zhMcyQI2ZZmjOAxjciK!w;-fF2n-&?Eo~4_X2|76*ha1)Y@OMWS6Bi1U@%3fjP_nz+
zt$CD~^@xVKXrxMXA!MW;CyZ3rz1NtDkRpYbv}baN{Jbp$Ij*1gCp$4WP1(-&?}1sn
z+&4c8YhbnLBQH|&@5jCOR$$2<>P?!??uQ%DOOZpLE}}WEi_5Ti&tve#>~<jn%v_ue
zc4IW|<DSFemrHr=$NcelazPtCM95&jTDlM=2MRWFz4VXvxMcC{8y%}*yiAPF6;#Eq
zF}^HZ*J~JCaN#+*k<nUmHycA_xbCG|6!GA>8MB_{8MJf3OfpvUp82O}6+VYt{&ZnU
zfuKx&sZ|``^IvZ@{?lU%Bf#%MH$#XrwZ82lNVtycLndjy-K996qyx64mPqT_+9{^J
zoC1#Y=vBb>&<dl)irih)${sGq{bw}bu}>UT)5Z`67viqxhi~u|Ts2bY<wfMBg3p7|
zGOT>~gF%XO7)pbe+JNj$i4Q{P^aeH{+C_1T^sK>9ju1qDv=|+L$KST^%ECA=*Yiuv
zDKcptuX`6+-!FFAI!m|+-DMigD|Ki}3?aHonUQhmaUG02xCoH%Kl;iWgdW<%4=4Q+
zf$Oz5`YTX>=nY=;V2bP)jus`s-l(vB=bR8IP;idXwlgpcjTE|uwG;XGav_+2ojxvZ
zbr@Kn>=pf?PQMN-=m)PQ*?W;>a=2NMtGZrsB_o!H3n`Hxp9kLnLBuUwRdUg)1CH{k
zTE}kJb;1<SAhZ+v#zov`P9G={u@ILFQy7|q_KQcvUHKgLwHykbN$PLO2U|Q0%-G<U
z9D@3$qs;emkB-2%{uU9i*<@`=OJKZ<H(t9bl1Qi<We)znJzSjJ+a)X8cI|R8INFA0
z&1maBa!CQXb}f~^Ub~KwIJ^riJa=<yn?~=x53{Q+&Sh4~k=wQj-T7Nct?AhdF>JnZ
zxP(%RpZZ%k!A_Z|fgQ8-*wIv818bw543Kf6oUK2F2l=+YfGT40DmuGq;!|QpotAe2
z^9I2uM07e;bOA#L>~y}=$yeIjHTmA-sFHs<f0}()#xj53vh#{wnN-b!;m?WoP8EU*
zIQ1{yO&8M4@{0~SO#^m$uZ=DpFb%zWtcklLo!2F4)J|nehSYPN@F8pC`;vAB35Fqt
zd9u82PL3?P$PQFXrpc3mxLk{J_M6%XetsTvFaUznq!@ih_XZ0t5M>GOa7n1XG1c$F
zAA@W2XhL#vbF_|y?oebOXLZH~5jsyikK>E1IQTfE8e*b36J8a>Z_wGwkl}($WOBkB
z=EG=7jP^&p71NVGxt(&EH`g6dk#RQ}zMj3wlz}gRdxbEWB`eYP&B|~GX;{&Wl0%=p
zV5r%sd_tbaWLa5ZWQ4bKy=H1spR+jiI7dGUl9U5T4Yd?}VlrW1i4O7%Nx1i0YFl9b
z9F8oRrDKh<#<t$cth7(>TvZA|klA@VdxlZAR1Y9HlDq|6F><W>4eW_O5T^+ufi#cp
z!lsA!c&(uLk8w43h*L<`8aKh}bmY!Mz`c<y0!iMXI+I?evfI4}E7GYtvs&XTpKFBi
zzNY~XmBb;~DP*g}Je6&UW_m8gMS7h(vb@fX`WB>F6-N<T(*B%W={uD1E>18^-tNTt
zq%>`sQbqHA?Y6_tMF&ra3PRH}>zM4??KzRNa_y$xf~1X;vrmSRSrJ4Ha+4=(pX}Pn
zncW4-zP&q(b&ERzH*(YSvo=<^25!cDZ}a@LnqIgD5AGc4MyeT{1t877+<jONc}E}c
z%jJ=&Z(6yfEv0W7XO8sZVp(LR@2w5Ggv_<f1Q~<o!ez3ucjj|Y_?^}qEh9Cnm@lCQ
zYm@dbvgTxmD<*KO%#JD|aiuv)$`8J?*jX@7#Co(D&7~_nHP73zsnpF}O5gF%Idq%n
z?$5wQnH06?Ken%mEA`J=EhhwPtS4rK8Kkr<*}EetI5_j~TxgHNNv@qVZ86i03fTW_
zw02snAVPR3uumb|ILRl6x0L#^1NQ^DDRG!mULP<Bh?2n?c{Y70I~VQMy+1UAHAW48
zRkg{<SA|K6k0UxkP?XR}$)M3$1qrNELz4&r$Zk-sb>c63$Z*HLc@Ae#I;)bJYjl;U
z{$=d&GBd@=k*U#^V(mVqubPTlc^7?A+U@zuh=qb!7Ng&VkV48iwuO=cY=E%~?99f)
z$LEf8&odj5c~br7Lc*-!%8--XIm%@<v6B5xs7KZOYthS)7r*}=gVhKa|Iw`m#!0{~
zhj6hz+ZuqCOq_`%uX%%$uv56j+F!;2Mf0N+#3(tT=n_%;2X(5@jsJJ%paaP7^?A}S
zM*bo<5s?1k%;4W30z6z){k}K5*l?sZ*B`^yBP1pEIn01qS&(ERmRc3y|G6Eav1nOR
zOtWDpLy&OjK@0L>0bdV>ySp%j2+(B)?}O~Ob74>aj^h&48*(}qz;TTzQx5BzfKbD#
zt1dXV;^P4s;H;BaGaF8jsQ0i3x56vi_>u3+8d?u&mJKVO=A+`;UcB2kospx--ZEYa
z`-uL-boBfFJ=#3`FATx!`K04Y&3Trj9Ldc5`v~OHM(URVR9t)AmCF{8%BWeF5i^)~
zb8vZl*bxXrY!fT6pl`#Xd5ln1yrFI!;2)Kg&6V`U0yb1pDr$syRtR%EeR;4%ok6zs
z0$xJgE9_58eab`{!(M(K`|ivLvyLmKcn8d=;k%Ul=Us|6;U#<LZQm4Fu~HFp0K|;{
ze5ugArAeDR8Uqn<ZD?xQzBXF6I;tZctW_kYZTE0(zL`m|vklGXjedg8u20yIyON)N
zY`!^3${gNuJHG4h&1moAIWiR^uYWF{XoiVj!x>lGJ(@-sU&eI<${C1^a?veW6vBOK
z>5vI9#_wWP$TiMm#%u~uvG<CJwA#WAs>_gP!R~5iYR%JeN-Gi`7xg+Y7PXOp1=^%g
zssq+wVp3G(7^L`7_rr6%F}`u98SsnQOEk<k{yg-~_mN-EL2}MgvpiL{BsBtQJOzmb
zn}D;9WgM)-Omfyz%^CDiptSVq2q{l~?LdG9e;;4*j*#U+3%_(W8>-!t<!WC6$^`T$
zABin1t#Kd|_^=YJ7jJ0Wa$*NIe3X1vw8aHVZ>~x#_R-zoTOEa0-H+a!<!571Rb$G>
z=i0Nvk~pDJ>5@!X)0E{>lf3WA6!Ue!P<7PO$zbGT@h8i==^P{;jnq!)YNdD&!!m8|
zJuTAcznf=qmQ~T*pLnMjNIX~(7&2)*Sgn;gOzxlO$&YtK&X${X&@Gqix`Tg8-dlFn
zkHzwEHR^3XiYw&?Vk`8R_|38aD5%%ra*xTWAWL(~w8Gkt*-VP<y6!PkB2U(2E*Z!y
zn$de-g%J}!$i?`p<>t496X2WX3|85MQ)aV;A)BraX|o)fQTL2*0j%G5GIPhlR#=fK
zK2M@w5>J+DV0>8lemb`SS(4Y)K0}566JX%opR}mo7zXub%13}fPU+`uwGIF17@8RN
z6r;j4A9(dxJo^ezath)4bxlZ03H>RR7M<Tm2c1ThpalnvGPbc8IPUnIG(|Zq%65^y
zADrx|%(Z@=;$D&BJXjgoV0`&XF-zhb@yLjl){~{OeW9;6oNC&#UEio8%LT=aPeV#~
zu^Wmx6KbHB&x$lrY85)(hOwli6@fNWK>=%*RpE{oTp5nmmC|O)a`#G7|4?^OgkOn5
z%z{|OpiD?M?82Eb{u`yj{KZ;H5}Shbot`U`$PG?4tHOzKFNU6sM0$jLjvAW$sT&2v
zi*AgATFc!X$XE%zR$iiHQI9KJqQW7J{EIgv9yY6UX@`lE^>cFC16F!jCK5Sz7en3G
zkpb<9Oa-{uyAzJAhX{A_TEb{Oy2X5g^j=ani(3}52T4D(G_R^X5m<OqYfH8JH}i1A
zYGXb!|Dm5B_wa*vR&NiJA1|vS!Nt%d&571}THBL=y@%ij-NhzVNPfP5RGocX7wsl^
zzdg8IpQnzJbkH_v_VH-jEHq`kJH7_-y<WVoKT)0)@!@>ju<^a!|9MK|`xxc>xc~Wf
zn+4b&Z?=ZBFBmYbyed5>oSc4Yf23@_uWtT)>8$cRJ-O@rxGmb%7dvjbADPbT&>}II
z4>VtgS9S%5d8+T}e5(3*{P2F6{U`|qTdZ}9QVF4(^yuK_aeks(xDDJ?kl}h9L#J#J
zG3Tv1`go-KSrq!*lG9<GzaJ{|Y=3gtAROmilDQD0(wZriZc3%`Gbb0?e5~^t>UG^_
z@NvBJ^*U-(IpGe?u=DF;-Nnf%ey<MQ{>`XUB`8^`y+SFU;{M{-Dw_}Y*E<nNHjjws
zwe}0)<I1M(O-HhYC996iRd-;t$E#7fbC=4X`}Gm;&fGp!^{8^kK{^pEb(S~p0W5m2
zp+)GyEEB5fS@`7%&!0a!($33!sV*%|vW%a&HE7OHDWcy`gjA=8bvFBSJR$C>@Op+L
zPlFC5dM<D736X9HcaNOnCz+n#Zjj#IbC9MPAESSqfMuB&wmf*FaZbPV2i3@ucpmDl
zbsp$dPhIB(s6RiJ2Mlwd>`UQFKQUwLLtI+Y06n`k3X1a@dbnHd&su6%c4P?_bv_~_
zZY|zqRL$JonM8;8Z$!-E-4#Xb@(*yWdU>0!yVTX#KTJ5^x1H2kdWA~^wjdqh9Y-@s
zQnqNc^Cmw7oKjWXi)}<FSHpA<zBY%8S^U`|H`Z%6uj0FbUPHB*?Q%amO5$C>2omJ#
z+6s#=VIFRpygS(N9jlf@A6GK8v3WaRD}TPAUb<Jom;Si?+B=EG%8_w5QMjv~WxVUz
z!<7a{?U@SOQ0c<@mG+$(yWU~*L-yx2<XFIq_aWqKDBb&)16MX#$HAfq1MJ%jnU~xw
zV`97!E)8(;C+5{&?TT6+&ZQ?aR>S%iNbcDA_Zei@1?qP$oirT=Ab0+^jR=o3F)VP<
zmkCnx`&mmq{6D;W%sXDzr-VGq)-Uw=AJ(k*ytiNK)gBwjs?k0=XTiPaxwm-qV)mac
z`G-IzgTie_-)!)gXjG{z^E>}kF_C^m(w+;Jp9m@OCG%SCv3%?-M868&D5sq*%U#{v
zzr9o8*S?enOu#F>=|0y7uz_3g8hfR6OwFL;v;HhD&~evV_IQ2l=#a^3oCCVx`#X(9
zj;j*i?D!@ik&`PAzx1X1)=Y{c=Z2w(TF3N|x9VQ#JiMwN8Ry8rYO_#ol|wg-&k#_$
zpwwdMMRn&J>hp-LjsM5%-HYz?>-Za$+@HFrd;HF~`T0}%58KzD;pG&;P)62<4vzLl
zdRCv`Z1l~cSP19|K0gTv2v|7S*y#V2GyNmy=Kf5g6LEDEQ*hLCG$Qz0@F~-y2QUP5
zLIMN~1at;^0Lshzsr)yk6Sc8+{4Z@|8hRRf0#-n=^8Y9S^!{lC<9{k6pi^|SH6oz<
zu4iIIKtjOqSLNUJ?2Q0rG5njCPR7X4Oi$3pl|Ta^q6ajbgMfjNo}NJKFLfb6#Q=Q=
z0_Oi@5VN;&vi+~d{9Vak($6e_7o7s2YI{9v2iwoe4BY+|OAt8PI~o1U2?4Z(jhxL4
zjO4`xKZXDFRo=+K#>w8m$bsO~Zt_t7(=|2#|7qV(OGz79n>d;hu>Yr7qGpzkM)m}B
zqLu*53L6>N82(k$KZ*<lY|I?2pJn|sWUlGwsvfQ=B8^oi3iCYcJUp{JDUjb%z9GjF
zLRR_v0|Cb)3TK8903)we3+M~SLqq&QP}7zo@Ch`Ty22tM@U3O2MZh~f`GX{+>;kzl
zii(c<-I2If8-<ND!NVPdw)Mf`qkZ$OW0gfotE!T->N!I}h@4QEI1D1XE58J}=;!0>
z0w1z|1)(q&pV@smkQ+5`QgpGXU@>{h`_UXGkFgwKUyxPp!!+4Jg6D;HTGX8iBm<qC
zx1oN`Hm+x2^wD8W)uG`TeIr%Dk~jV;MO@KD>Wg6k1I8*_wbpB2y#z8O$8=P*^F3Bv
zk!(6wM#2bF^&46v=xmm!p}Wq0m8#VP1ED8ljCe?~E=d~{AkLlT(6BebANaX$bjff-
z92?U!*|ETZz=1Jxs$nQnH3^b%=1KqN1FBp>JFk!NID5{V{ABHTG)XBt*i)coA_mE1
zw{7XY*|FkpI`TCri}oVw>H*Yoau9mEPaN^z$@j2<^hg7q^aK2r#B$HTW5u27^jsUb
z=spl+0UMW@a&LqS8!{WOR}W+Gl6Gc;u3v(&#X)(HsBx1eTW!Pn!XeX5iER}0rk34T
zrwEw`F=wm_oxSn)>Ek1^T7eJChYUpDk6CIk)~PhoJ@wX^1a!Hrs?*iz=Tl`$Ly**|
z_EWO#8uW&;Ster2CsVU3Qz=27zbb<AO-plhTNd_~<=q6Tc--I#s*f);xudV;t^z`v
zE~gAu<-pMDbWEFiJCCCbj$0&>u@NDhTBl}+cxuPa<rtXDg0Q+D+#V&b2`KaWCMVh^
zz0%4si!cXQk>R9qzgG<Ecs#5xigqRsPM#y4u36iik9LOIfc|Q^NC9uO<cOX@e2O2k
z&+kmvA>%X?ixv7|za-Q%(U3WRuGGl|{MylcKXeDHk;Tfh$Y=&W%*eB>hBq27Ul(i?
zy9Zb{U$Ii_MD^Zi{r0PL=K!8BI8AXsPq>}k?{}uL!HGa!uYMsp>S(|8Gaz1XR^jAI
zZHH920kj&T-K<j1uTUX*nw<q|E#kiO+O<9_Raw6!x}==r)Y%y)E1#S)(&;Dr#|kMv
z^A?z*!V!KP>w^WERU~GV8e$^-b+j@Xn^x<vmq)uYt;%tPmB0jx{ao8=UX-|>1<8>b
zPs$lT=V_r~$sDyv*9gmWg)PouX2n_U!*f>NR>Te3IJMJqY1q&(Phq1(qaiZ5oRTiA
z#k^vNr8i`6PP9$RsTMLM<xN9Tbb&K3#1;J1Lo;`zSvY@l{svX1ixqOnmrfk^u;97N
zoY)Ypq*}}{TNe^!{uV&cC&>LRC_dW2hf^He62=MEDX5&AF*P!Apog3_G%9Y8au)}_
z6yDt6u4V#6<(EgilAu)n@QOj@;F`#S=b+}IrVFN83GHkW$7ndCO3KSur@W47wc}Dp
zm1Cue_R97P^HZMF+<9{zd2y)UVa|mdruuIb<H}}@_1=4dCJTHFM08vdw>+X`-<fM&
zGAnW9QwK#^ZG6bY_ttLv9XR2gN@joMyfl+gG1mD|+=nqy{;2*Ia)LH7N3E21FSUpg
zl&cOG#K^CJVFdSwi*~(K0&dw&BjchiC{QKMSx*FoYBNWbBX=o~b=>&YV$A#jS@LbL
zv10X*WuRX5V3yO|rRHKq^*%ecD#5hwc-FF!QOYBcW?EZ!b(z#CqfvBKL`SdFm@5HS
zUG>JIi(Q3<2hDS>XyD{{Dh7OB*1hXU$RP*)GUry&;ZE9sd~FcCr1v)Z2min{NC^<0
zuor4}$3V%~XL5s7h9p{M)>+sQZS?|0>`P4a2xVeWr)<e#%6|NjEYz^U<IJ0#YIe`e
z4#G@sxmhz#D)Zk<e^@I}h4S^}>yrgWe}GrW6#LO3#Gx=!@5L5G7&7D$_GKZsB*P}9
z(dGGDGaDPpYm`5AlE5JeI<W_X8kydmXd#3WnG-RTP>@g-V#ybkttvGjSiVX$#v0x`
zjW)C-S_D(d9J-ol90o!D(zE2P5jP&9I)$onRJ|xwilR&nAKf@)NQ+`K-mZio9K@bj
zGHv{+ICoDTf;MA~vOO9EZSrDi8)gmOixlL%{O3=OkQW?X*vUcA8(!JPcp{c^eU%~7
zA>!CdP;x@liwGj!G4>xn$u5!oeOikK(I|I|jKGtt6JiqZ-;*YOD%PtTu4_?j>UhlI
zZ?m2@PqsJYRI7hPR|!HB_HfW+XJRhOybe+#s^%BqJl{&1HghhgduJ*WLspwQ)kwxa
z2w%;I^G~Z+3-!Qesu9etV%Zsa;srewX`ITpI#kH{_VUG6@c+zls=Vxa#`Yc(^pZq*
zMDu~<55~N((zjb`_c{`TT;$xoU(fFLUSAICL><0K{9MsFxje-mY$eBxglPz4jgZcp
z%{S{Xvoqg@iBF}Y0C{is6nE$f)NzEC6pn||Skl}r=VRZW>y6v^skw$wWa@rXq*#*R
zTv^P$7fTxc^F}cW?}gJTr@cfp?}-0;`da4Y!K%(Jb=f^6tFsr~@-{lcs)Jx41D1hz
z_WtX*%d@YBhCvDzAu)x#;K|o%!R?-}k|L*HSAr%`srn@B1gVQ|9wB~ERR&KA)8Gmk
znBm~cli(q(_Bmf8ROG@NtYA)G>&4q7oQbHv=DU!C!Evmg<lJ}6U#v9CF!b$Wu5D0o
z>0gG4h1S+u3%~v`nyYgAqkix!*Ixv3`wKsZNO~S!t^w9{#!<uf;S%0@w&p*7TAb)s
zfA9b1t(xQ$QrDOq``JF3BP1`newekWmxxE6Ngf$`$$*=o+J;?{W2k;g!XDr*N0Jrv
zj43-@5G5gPTO6AkAt5b|k$nsqGA1TzhIy0tJhFmcyOg6_(ZER~FpIp4@`pdYw}8D3
z7p!2}Bsb@p(HuWZg9vp~o2j$?;CF;pWfj6iytvv_PGG*gI!5Zr;%m$1GHgU{*hc@d
z%6Zw{{0rwD5M;KC#O%zi><`Qh7@eY{djI;qTYh(WN%Ior(j-nP*r<r9*l!lKaI*AW
zU#;m0!So5?Ua7TZ#>FqQ-otJKj>Bda^MhuqikieAQU$!MOy;mN#F2|9smL}lJq@=Y
zCyu9)<!H;XetUSTE%#zS<8Qj%@D1R5<nHbDk(A*tW3Rlt4*n!xo_xNPk{TU_hLy2*
za?i0G{k6Bp=3oyc3XhNKSY)YLdp_^a`tie$H92z0NG~1zJeoS=Dxz|pQtiy{v0-CQ
z?m~dMW*x|vw?^P2Q9#s_gE!@tUtf{K7aB!$-L7R-x~|ZAvu5+M3>kg;y)roLRr5w+
zaWb<Vt}OK@Ep0HoDOsxitSy$o8byri&FS~l-W^62YPADhhKX-s4y;|>BtU;Gln&yD
z;qpU|8wqnip2!}0FKoGB)@33<EomxmB;zGYiPa@{%_6ns<u-a5R9m9p9m5mw5{#uB
z9_7ux(z#ehvvTn!c`_DjChQW3Zey8BdWi34?8{2ZEyO*<JH$&L@?a3cn1>;x!wVs%
zjo~XDTpdp+RfqDCB~k59NG?&@D8Y5v#3S1ZKDj*d|Ax}3E_;=FBK4g7Aa$Wg|J5QI
zGyN@r^as_`ZR-r{i24qJvgcy#8!g|WJn6U@=8UI=dsTr)TIF|HYRvuo*xP8ajUl4U
z0~YWiC{FCc28ll26vX;syVD`}Z{ZQmv9t6YMlH;x1<zVs{J6D61xf7(tEywYabWqq
z0<{vk5IcMW>x8{~guJ2X*T=7%NhKBAdrcM=MwgpdR%7I%?xoRqAsB{s<e6By2tWov
zz*>+FP+>|ZbHO^!^hKj>^lj>c**(GjNV2Q3SkF00q2yQgpru#Nszb7Q&$6pAf@B$v
zL_*@gZsB8uR3S(*Tyc^0Ot<;O$8Qra5q9<dydqhFMsw9(Y%;!<juyj>i(|lQ;);90
z4u`T$(p%jJQr|bz+co^nrfY(!n+P_>h0kP!Y-S=JbL-_<YM2pF?=kh9+Rxy@7s#p-
zR9>9(#a{9tTn%1vK@0KQLQ2!Evw}J|$pLGpn}7o%oArpHL3a0tl!#(2U4(?p?Rxt9
zLVoRh6NMr!N`321$fdbzb!r-_iHY0p4tlq634Z9Ghb$`GYiGI}R|s;x;HtJ;jXWG|
zd)gbD{hIaT&;dc3yW=3w#<$yGy^eC^XM^2h`Z3dCk>eUZ#B0q#N;_*7YH^<4P*Ij8
zbiqL1fPe=dSl~DN(lPW3Ska}{#F%PfX_?&A&J0NVw()GbN#j2`tD1ruZHtc!8i+r!
zejl!zzB26X>P(w=Vs^`5jbM!qT-%Mzo|*A-S-XYzK!oYlP)EL)#4P_&sA1YQeoBg-
zNhYb0+DUwLiCecr13bVYnmQYI+miNPhk=qZ#dv&vfan@BocUOnB=ytI`C=CKNu|VP
zN{C@+Ad|=AV5-5Z&>D-gNWZI#X}zxU{r!-uXfUi(_*I?b<Tufdfr7X<If*2xXi1!Z
z-hMTodl9B{qLb>W4z8o~_csQ}AKv1UfDlSg#5PI9ydZf^on;Jr6~s>U+NDA6%7dqd
zZDtGK!~>2Vthso;wZnFhG<!K&hM~vS<`$Hqt~OP5NzWsuiM2T_tT!E8%aNlm@}bh~
zVBw1FidqJC1nIb655=JCa8i$#$sCh+AnNd`l6Sn1n(T}YeT8dx`qK2PT(Cn~<WZ6o
z(@>Xu3GcULLNBCNZ)O8znSzU9qf4RVpBMR8YgC&A*9J$jexnuHsrwaHp(ZPqnc82k
zaHPJCaS{S#24Q^qmBYC5Q|H3#nLbdl$`#AM9mZ3&xcVnZEF?~|=t3L97S9pbY&KBX
z$^y%^S`6QwNu(Af$taWPs@61H+Uzy6ji<3MJ3j_;Q~879_7AJHd33yEWz!oBhpET%
zVYhvjK1SFf<3xA3fUA!9H4O>P3Ji{fIg{RFE8}D((Lr!QQ-1OOQi<cNZ(R9Eil+DS
zLEC=x)!6;Pp82x-D94BL(9BPDjMf6H@Tklga*X>77diT|Bh?j~7a)R+FIoU&z%ID*
z5!TMlw@|KOvpa}~%JEh*h)R+1F@^3VrbTQ`eJ8&D%O(2b=lh_LgE&ohUD$>-{IZ~n
zUfGvc6J0sgQo_+8g(ZjZ1;R1M{tm4@PL439q&Uu{UI<*#+M1;38%-iMQ@rIUi#>U|
z@qP_fJ>q5Wd!RC-tUC9ZuyMn?^5F6O<trroK^MJ=0OVM3FBhVc0`y^NdyEbrOZJfq
zBU*dJ6FvCfzOD3{ossczl#KXh*E42@Im|llKpwK!?(!jKSdoi)37H}%aI*z_IBs~!
z%>I^nhtXA>e{j{H+-3y71X-4RIpzznnBRR!FeD{@#hDL|<}|>UkMiKbq1er#;zO5M
zypA6ybIX?$eW?7lOWWAzJZ(__LtCzAkNOqIxGTsJQ_8q?89{!76quZ7zuCFqEkaZ9
zknqwu)uxJeTu;Oi{>c{=uzAo5nPsHy<l7AB&<{wCP`5}+A~~;PMsgv^^J!Q4Di{OI
zN1n=TYW_;d6fh1$sD*<#ulzvA04VuLK*W{=kL$~;QJOR4z2E7)R9<2y+uE_Rl1nV{
zEO^qZpm>Ug6a2aPQeEYVzCvMTLU}i!mnh$y&i}}b`;>es9WFLE(9Ujba8l%Tukba$
zs0z%^OZ^(h_f*m?*W!%HOUd_ro$+WxqYRF+1^s1U&tTqKkL@15g^khJ2C%>0BeuFC
zZZb1R^^9i9nn}Tvcvj^%U!NKO6&XnMe!8`{4w8__VAw1kzCQ=&599EuV$D!<(0#nu
zRyx9xMy0`GT?lM^rda2c&GR1*WMDM)!Y#s~Zd`vt>O(z)FRhZ33^J<o_GrhvmJ1e0
zF+|}U;FkxnhGE>kqzt$3(Vt2eUc*bkYA4CnN!qKAkl5@t-K%TRtLV}Www)|!Kj>#h
zJ{f$2F{__e#F|dT%>5>IJ`!y9hv^%Lnj~ngy#JHOmwL~!p)}-4f8^5%ScrtY=&B9>
zW(L4BfLR{?tr$bZ8N-IcVlcWx(2dN=a-jokWeI2j>OT>t_5wP;Zog1Bs{wER-qHYO
z`|_%S&|%lDL$&3O(4p-H|DoR10QFc3f|a&KCv#QcL-*V@4}A68XR>x{WS`+x@~h@R
zNYY?efgICg0qG+%C@<nwjZc``l?k1vA~5<F&!b--nm~t9T|Xfnfr@@s15L2N92}zY
z_v*606tR0NcV+EtMS*OfUuF96K@?Z{FgZcKhWoU9ab<&+g=YUfwnO%2ON12(%}%=Y
z0J4F0mFTkx>8j9W^A!ixR=7(K8ZH6si4eE}JnBjv7#tqukDu7q7LoH7n}ByV{Tvjy
z;2E3165Un=R59XJi;p>QCt7tChPFd@nTOx&y#7+_VDAH%UKF^tK(3CN?>dM!TD4S{
zEW9G*(sgXu<&bZZ=9NB!znx?=Ag1+F<NR<F<kE>hO`5@DqW+Sm*`INS?`A#FSlo2F
z3IW}0kj3=6#NPEaAgtvs*RW>Q8(&XTb<b0YJu7@z_5(b}5moDg6Zp{g_5;4-=}&&$
zRs$|maoR2WT7CjX6*Hdjz`qQYk>sWq05@7=;KmT2n=k2CJ?5(esoK)FBlVTKMz_XC
z1OyEVqT$`X8{}OI7#gjMsh^&2a_|s*+YI>T%a~I)4%yhk76ou!s;)6I_wpB}RNWRI
zGmv+gE@X+TW*>?LAYLOFZc^PpAg(CbBp`T*->G$DeS*G9pMi?V(04-yfZ!p~Yx4_q
z3_zz6==g!>89e%_(aUzJuDP874c&BOnEzoo-v*`&$3yEEgT^T6eFG7FAKN4T`a0&1
z2oktEWDDFInChvD0u#aZ_#HVAgI=}E3zfbY<N}rc`^gA6Yqt-v?W8RP<PqK0MJxBK
zHQn0$<oM+u{>~1tOLTK5Asx_Xh#}Oe)}*8dYhP_1nT=6s9tX#bS$`Z{_iy}-z-sGG
znIze*a4DFalgtD{LDpJI8{__!l#au`6B)j34h)Wx4_C4R;t%}l=Fvs#pd|uF7;|o7
zY+szj5u>TI{jg)BC%?ge2_>w7M2ZgZ*AHgvibA@D4z}=J0!HwQzyLlE%fXc_&G0dO
zCFcb51Ze}w{o-otE9Mi>rViSr33Q=v3rU|oy@s&Ww>)7w_0^QL7zBrXoRI(8R}%&X
z98=u~z8d{YZs%}8CBF;-h$#(?_C59a>(6b%kJT@)qh#-$!0}P3?El-Z{pn==*RRb?
z&-kyWnd5)EV;MeO$bb2y>HaT&?0>sowPHuD{pb-y9^OOM3d4efKqW~06$`M@yo&4b
zf$pP;Pz^9^w=TJML*z@KlY1XG%3^}{*0|ZMH3{9|>&)x|^c-2Y7<K#vj;<Lw6ZUn*
z>NYxdR;4pkAX8SY)a=aH=*vod_x#|JSS+hOY8|5Bp@3qWbQ!`gKw7IDs4DJH-r!}A
zl*N^_{Q7_GXmft7$UsOiUt&ug?zWr{-xocuaSP&gGGPvnp`mYL!eq2&m(J7&nq!y;
zOuTcA!s{P{->iRC+E2_klN3?n43iFcCimL&CVcbdK$TS^PG`c$CsrWjh0F>L6EdWn
zn=Hs;k~)ZClG=`aq8Ba{^qNlkQ6*Bvp>QiQ_mF#;0+6?hwgs9bVlq!=lZZJ)CVGxP
zskf!Js~;5gpu4tGbVzPId5IlhfmD#aW7yHP#Y}I%ZC=-zsCaq<r++Ji|KDTw*GT*`
zXiQ8j|Be~Mr{n)$ANt>(`%i2^*vP@a-ptm~#{Sb0{}<dKt7iqk4rHX&mDEJ2gpJJg
zl${g+F8%+ci|SdKS-KIB|D8nenMUz<qNSb*z<1C1A5Fo((FGa?dPaHz8fI2T0tPk?
zCIHI7#P|=&AmONIX=Wf`ZDMIeK>t@h0SALmn1X|m{V(>jeV;rHBcLmvEfmtT6*n?7
zF$EwQfMWg<DL5KgDHE{&o&S>&|CjmfAz(ThF%o<t2>*>Jd_pMy+Zult=cMoW7kr`!
zz$`v3^_Nso&%x*~Fy{Yd88dqaM<G)^`+p4}t@jVl!1y-+^Zz$D!CwRN_ZcH%4FE07
ztW5~$RLraetR2k$75r7RikYFKsRIC|VPg2~#s7UUvC{vO&dS6}@c()Ppd&!)|6RhT
zl!fgR$@=?XW%>6z8~gv%%L<rYY)qeX>Hj`hnLhC%Ks^lq=Kfock?nuVpeJAkbe;t;
zCqCQriS>M<PXGzv{TKKI0Fi8ztj#`=9D>hl&3_Nv|DML5DA(V!Q_9Tn(@vj2nEZcW
zET>P<>%XuhhX2ONzT4XvIvD`aBXR>hGkY5X23iIdT0j@cO&uL=Iq3j^96)MfuV-s&
zX5c_;V{Zb8zw_5D1fYM8W;WKspI{!jFef8DBP0F)SC-l1APmD$c+V-aR0y%yC3T${
zfy9IaC+N^3mR5>7RGc0=Ewl;Q@?_=beQ}n@B?F>&e1LKXu-|UFCV}5@?$pTJAD(f!
zc!edJTT`zow4DKq&cJV2!E&r@XJ?IwSsc+}`$dx=&x`q)#w_3yO(qH{(JIf<rKv{b
zoFGc-2uc*tsaDnc_vD%aPBlW8pM?lXNN08azpe(_tT%>6x;w;N@bP-L>XqWT4}(Bg
d&*uia_MNbe?_y2@n=nRqsYWDI6zAK;d;rFh<-`C0

literal 0
HcmV?d00001

-- 
GitLab


From 99ed3c561be99af647146a6000bba10ab918361f Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 29 Aug 2022 08:45:45 +0200
Subject: [PATCH 181/324] formatting files

---
 .../Component.cpp                                           | 6 ++++--
 1 file changed, 4 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
index 6b89eb56..daa7ec84 100644
--- a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
@@ -45,8 +45,8 @@
 
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
-#include <armarx/navigation/memory/client/costmap/Reader.h>
 #include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
 
 // Include headers you only need in function definitions in the .cpp.
 
@@ -88,7 +88,9 @@ namespace armarx::navigation::components::dynamic_distance_to_obstacle_costmap_p
         def->required(properties.staticCostmap.providerName, "p.staticCostmap.providerName", "");
 
         def->optional(properties.laserScannerFeatures.name, "p.laserScannerFeatures.name", "");
-        def->optional(properties.laserScannerFeatures.providerName, "p.laserScannerFeatures.providerName", "");
+        def->optional(properties.laserScannerFeatures.providerName,
+                      "p.laserScannerFeatures.providerName",
+                      "");
 
         def->optional(properties.robot.name, "p.robot.name", "");
 
-- 
GitLab


From dc85d8b15221cb3ef5504858f6a9790deb416761 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 29 Aug 2022 08:45:53 +0200
Subject: [PATCH 182/324] fix: moving query description inside loop. otherwise,
 the timestamp will never be updated

---
 .../Component.cpp                                     |  9 +++++----
 .../server/scene_provider/SceneProvider.cpp           | 11 +++++++----
 2 files changed, 12 insertions(+), 8 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
index daa7ec84..5a317a1a 100644
--- a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
@@ -174,13 +174,14 @@ namespace armarx::navigation::components::dynamic_distance_to_obstacle_costmap_p
     bool
     Component::readStaticCostmap()
     {
-        const memory::client::costmap::Reader::Query query{
-            .providerName = properties.staticCostmap.providerName,
-            .name = properties.staticCostmap.name,
-            .timestamp = armarx::core::time::Clock::Now()};
 
         while (true)
         {
+            const memory::client::costmap::Reader::Query query{
+                .providerName = properties.staticCostmap.providerName,
+                .name = properties.staticCostmap.name,
+                .timestamp = armarx::core::time::Clock::Now()};
+
             const auto result = costmapReader.query(query);
 
             if (result.costmap.has_value())
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index 26d9cd41..d9977c6e 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -84,10 +84,6 @@ namespace armarx::navigation::server::scene_provider
         ARMARX_INFO << objects->getSize() << " objects in the scene";
 
         ARMARX_INFO << "Retrieving costmap in memory";
-        const memory::client::costmap::Reader::Query query{.providerName =
-                                                               config.staticCostmapProviderName,
-                                                           .name = config.staticCostmapName,
-                                                           .timestamp = armarx::Clock::Now()};
 
         ARMARX_TRACE;
 
@@ -96,10 +92,17 @@ namespace armarx::navigation::server::scene_provider
             // waiting for static costmap to become available
             while (true)
             {
+                const memory::client::costmap::Reader::Query query{
+                    .providerName = config.staticCostmapProviderName,
+                    .name = config.staticCostmapName,
+                    .timestamp = armarx::Clock::Now()};
+
+
                 if (const memory::client::costmap::Reader::Result costmap =
                         srv.costmapReader->query(query))
                 {
                     ARMARX_CHECK(costmap.costmap.has_value());
+                    ARMARX_INFO << "Static costmap available.";
                     return costmap.costmap.value();
                 }
 
-- 
GitLab


From b284e3a29289301a4f3cd02e0302c9c90fabae93 Mon Sep 17 00:00:00 2001
From: Lennart Grosskreutz <lennart.grosskreutz@student.kit.edu>
Date: Mon, 29 Aug 2022 18:46:17 +0200
Subject: [PATCH 183/324] Provide costmap to homotopy class planner

---
 source/armarx/navigation/algorithms/Costmap.h |  6 +++--
 .../navigation/local_planning/CMakeLists.txt  |  1 +
 .../local_planning/TimedElasticBands.cpp      | 21 ++++++++++++++--
 .../local_planning/TimedElasticBands.h        |  2 ++
 .../local_planning/ros_conversions.cpp        | 25 +++++++++++++++++++
 .../local_planning/ros_conversions.h          |  4 +++
 6 files changed, 55 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/algorithms/Costmap.h b/source/armarx/navigation/algorithms/Costmap.h
index 6f452b7d..d168ef7d 100644
--- a/source/armarx/navigation/algorithms/Costmap.h
+++ b/source/armarx/navigation/algorithms/Costmap.h
@@ -68,8 +68,10 @@ namespace armarx::navigation::algorithms
         centerPose() const
         {
             const Eigen::Vector2f costmap_P_center{
-                (getLocalSceneBounds().max.x() - getLocalSceneBounds().min.x())/2 + getLocalSceneBounds().min.x(),
-                (getLocalSceneBounds().max.y() - getLocalSceneBounds().min.y())/2 + getLocalSceneBounds().min.y()};
+                (getLocalSceneBounds().max.x() - getLocalSceneBounds().min.x()) / 2 +
+                    getLocalSceneBounds().min.x(),
+                (getLocalSceneBounds().max.y() - getLocalSceneBounds().min.y()) / 2 +
+                    getLocalSceneBounds().min.y()};
 
             return global_T_costmap * Eigen::Translation2f(costmap_P_center);
         }
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index ae184519..4b5d36b1 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -10,6 +10,7 @@ armarx_add_library(local_planning
         ArViz
         armarx_navigation::core
         armarx_navigation::conversions
+        armarx_navigation::algorithms
         armarx_navigation::local_planning_aron
         armarx_navigation::teb_human
         teb_extension::obstacles
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 91483e74..1b86f5d3 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -67,8 +67,12 @@ namespace armarx::navigation::local_planning
 
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
         hcp_->initialize(
-            cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);
-
+            cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);       
+        //set member teb_costmap
+        setTebCostmap();
+        if (teb_costmap) {
+            hcp_->setCostmap(&teb_costmap.value());
+        }
         ros::Time::init(); // we have to init time before we can use the planner
     }
 
@@ -198,4 +202,17 @@ namespace armarx::navigation::local_planning
         ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";
     }
 
+    //export algorithms::Costmap to costmap type of teb local planner and provide costmap to planner
+    void
+    TimedElasticBands::setTebCostmap()
+    {
+        if (!scene.staticScene)
+            return;
+        if (!scene.staticScene->distanceToObstaclesCostmap)
+            return;
+        const algorithms::Costmap& navigationCostmap =
+            scene.staticScene->distanceToObstaclesCostmap.value();
+        teb_costmap.emplace(conv::toRos(navigationCostmap));
+    }
+
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 9eba4d52..1c1db279 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -61,6 +61,7 @@ namespace armarx::navigation::local_planning
     private:
         void readDefaultConfig(arondto::TimedElasticBandsParams& target);
         void fillObstacles();
+        void setTebCostmap();
 
     protected:
         Params params;
@@ -72,6 +73,7 @@ namespace armarx::navigation::local_planning
         teb_local_planner::ObstContainer teb_obstacles;
         TebObstacleManager obstManager;
         teb_local_planner::PoseSequence teb_globalPath;
+        std::optional<teb_local_planner::Costmap> teb_costmap;
         std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{nullptr};
     };
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 86fd6a2c..91736c32 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -164,4 +164,29 @@ namespace armarx::navigation::conv
         return {.a = ellipse.b / 1000, .b = ellipse.a / 1000}; // [mm] to [m]
     }
 
+    teb_local_planner::Costmap
+    toRos(const algorithms::Costmap& costmap)
+    {
+        const algorithms::Costmap::Parameters& params = costmap.params();
+        const teb_local_planner::Costmap::Parameters teb_params = {
+            params.binaryGrid, params.cellSize / 1000}; // [mm] to [m]
+
+        const algorithms::SceneBounds& bounds = costmap.getLocalSceneBounds();
+        const teb_local_planner::Costmap::SceneBounds teb_bounds = {
+            toRos2D(bounds.min).cast<float>(), toRos2D(bounds.max).cast<float>()};
+
+        const std::optional<algorithms::Costmap::Mask>& mask = costmap.getMask();
+        boost::optional<teb_local_planner::Costmap::Mask> teb_mask = boost::none;
+        if (mask)
+        {
+            teb_mask = mask.value();
+        }
+
+        teb_local_planner::Costmap::Pose2D teb_origin = costmap.origin();
+        teb_origin.translation() /= 1000; // [mm] to[m]
+
+        return teb_local_planner::Costmap{
+            costmap.getGrid(), teb_params, teb_bounds, teb_mask, teb_origin};
+    }
+
 } // namespace armarx::navigation::conv
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 548dce73..05b52e77 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -27,6 +27,8 @@
 #include <geometry_msgs/Twist.h>
 #include <teb_local_planner/pose_se2.h>
 #include <teb_local_planner/timed_elastic_band.h>
+#include <teb_local_planner/costmap.h>
+#include <armarx/navigation/algorithms/Costmap.h>
 
 namespace armarx::navigation::conv
 {
@@ -49,4 +51,6 @@ namespace armarx::navigation::conv
 
     human::shapes::Ellipse toRos(const human::shapes::Ellipse& ellipse);
 
+    teb_local_planner::Costmap toRos(const algorithms::Costmap& costmap);
+
 } // namespace armarx::navigation::conv
-- 
GitLab


From 11a5e219e602abb69c03d6de7760c116621e42df Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 29 Aug 2022 20:05:28 +0200
Subject: [PATCH 184/324] Debugging kalman test

Try periodic clamping of observation orientation.
Plot covariance of kalman filter.
---
 .../human/test/kalmanFilterTest.cpp           | 42 +++++++++++++++++--
 1 file changed, 39 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
index 1ccc3114..22e37372 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -25,6 +25,8 @@
 #include <cstdlib> /* srand, rand */
 #include <ctime> /* time */
 
+#include <SimoxUtility/math/periodic/periodic_clamp.h>
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/util/time.h>
@@ -124,7 +126,24 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 (obs - true_obs).norm() < std::numeric_limits<T>::epsilon(),
                 "observation differs too much from real observation: " << (obs - true_obs).norm());
 
-            observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
+            //observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
+            //continue;
+
+            obs += obs_noise_std * SystemModelT::ObsT::Random();
+
+
+            SystemModelT::StateT noisyState;
+            noisyState.orientation = manif::SO2<T>(obs(0));
+            noisyState.position = obs.segment(1, 2);
+
+            constexpr T eps = 0.1;
+            SystemModelT::ObsT noisyObs = SystemModelT::observationFunction(noisyState);
+
+            //noisyObs(0) = std::clamp(noisyObs(0), -M_PI + eps, M_PI - eps);
+
+            noisyObs(0) = simox::math::periodic_clamp(noisyObs(0), -M_PI, M_PI);
+
+            observations.push_back(noisyObs);
         }
     }
 
@@ -172,6 +191,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         std::vector<T> x_true, y_true, x_obs, y_obs, x_ukf, y_ukf;
         std::vector<T> a_true, a_obs, a_ukf;
         std::vector<T> x_ukf_full, y_ukf_full, a_ukf_full;
+        std::vector<T> ukf_pos_var, ukf_rot_var, ukf_var;
 
         for (int i = 1; i < num_timesteps; i++)
         {
@@ -227,6 +247,12 @@ namespace armarx::navigation::components::dynamic_scene_provider
             ukf_states.push_back(ukf.getCurrentState());
             ukf_Ps.push_back(ukf.getCurrentStateCovariance());
 
+            ukf_pos_var.push_back(
+                ukf.getCurrentStateCovariance().block<2, 2>(1, 1).cwiseAbs().maxCoeff());
+            ukf_rot_var.push_back(
+                ukf.getCurrentStateCovariance().block<1, 1>(0, 0).cwiseAbs().maxCoeff());
+            ukf_var.push_back(ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+
             TIMING_END(LOOP);
         }
 
@@ -257,12 +283,22 @@ namespace armarx::navigation::components::dynamic_scene_provider
         orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
         orientation_plot.drawCurve(x_t, a_ukf_full).label("Full UKF").lineWidth(1);
 
+        sciplot::Plot2D error_plot;
+        error_plot.xlabel("x");
+        error_plot.ylabel("y");
+        error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        error_plot.xrange(-0.1, 1.1).yrange(-1e-3, 1e-3);
+
+        error_plot.drawCurve(x_t, ukf_pos_var).label("Pos cariance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_rot_var).label("Rot variance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_var).label("Total variance").lineWidth(1);
+
 
         // Create figure to hold plot
-        sciplot::Figure fig = {{pos_plot}, {orientation_plot}};
+        sciplot::Figure fig = {{pos_plot, orientation_plot}, {error_plot}};
         // Create canvas to hold figure
         sciplot::Canvas canvas = {{fig}};
-        canvas.size(600, 1200);
+        canvas.size(1000, 1000);
 
         // Show the plot in a pop-up window
         canvas.show();
-- 
GitLab


From 73be85a1b9ae3e1e9bdfc10e46339ba2d8bf72a7 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 29 Aug 2022 21:36:59 +0200
Subject: [PATCH 185/324] Fix kalman test

---
 .../human/test/kalmanFilterTest.cpp           | 71 +++++++------------
 1 file changed, 27 insertions(+), 44 deletions(-)

diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
index 22e37372..9a80c9ec 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/kalmanFilterTest.cpp
@@ -25,8 +25,6 @@
 #include <cstdlib> /* srand, rand */
 #include <ctime> /* time */
 
-#include <SimoxUtility/math/periodic/periodic_clamp.h>
-
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/util/time.h>
@@ -38,23 +36,24 @@
 #include <manif/SO2.h>
 #include <sciplot/sciplot.hpp>
 
-
 namespace armarx::navigation::components::dynamic_scene_provider
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
 
+    constexpr T RAD = 8000;
     constexpr long num_timesteps = 3000;
     constexpr T max_time = 1;
     constexpr T dt = max_time / num_timesteps;
     constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
 
-    constexpr T rot_noise_std = 0.01;
-    constexpr T pos_noise_std = 0.01;
-    constexpr T obs_noise_std = 0.01;
-    constexpr T initial_offset_angle = 0.1 * 10 * M_PI / 180;
-    const Vector initial_offet_pos = 0.1 * Vector(1, 0.5);
+    constexpr T rot_noise_std = 0.2;
+    constexpr T pos_noise_std = 200;
+    constexpr T obs_rot_noise_std = 0.2;
+    constexpr T obs_pos_noise_std = 200;
+    constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
+    const Vector initial_offet_pos = 0.8 * RAD * Vector(1, 0.5);
 
 
     void
@@ -64,7 +63,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         constexpr T startAngle = 0;
 
         SystemModelT::StateT state;
-        state.position = Vector{1, 0};
+        state.position = Vector{RAD, 0};
         state.orientation = manif::SO2<T>(startAngle);
         states.push_back(state);
 
@@ -76,9 +75,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
             const Vector last_pos = states.at(i - 1).position;
             //const Vector pos(angle, std::cos(angle));
-            const Vector pos(std::cos(angle), std::sin(angle));
+            const Vector pos = RAD * Vector(std::cos(angle), std::sin(angle));
 
-            BOOST_TEST(((last_pos - pos).norm() < 0.1),
+            BOOST_TEST(((last_pos - pos).norm() < 0.1 * RAD),
                        "position differs too much from last step: " << (last_pos - pos).norm());
 
             SystemModelT::ControlT control;
@@ -94,11 +93,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
             state.orientation = manif::SO2<T>(angle + startAngle);
 
             T pos_diff = (propagated.position - state.position).norm();
-            BOOST_TEST(pos_diff < 2e-5,
+            BOOST_TEST(pos_diff < 2e-10,
                        "propagated position differs too much from real position: " << pos_diff);
 
             T rot_diff = propagated.orientation.angle() - state.orientation.angle();
-            BOOST_TEST(rot_diff < 2e-5,
+            BOOST_TEST(rot_diff < 2e-10,
                        "propagated rotation differs too much from real orientation: " << rot_diff);
 
             states.push_back(propagated);
@@ -126,24 +125,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 (obs - true_obs).norm() < std::numeric_limits<T>::epsilon(),
                 "observation differs too much from real observation: " << (obs - true_obs).norm());
 
-            //observations.push_back(obs + obs_noise_std * SystemModelT::ObsT::Random());
-            //continue;
-
-            obs += obs_noise_std * SystemModelT::ObsT::Random();
-
-
-            SystemModelT::StateT noisyState;
-            noisyState.orientation = manif::SO2<T>(obs(0));
-            noisyState.position = obs.segment(1, 2);
-
-            constexpr T eps = 0.1;
-            SystemModelT::ObsT noisyObs = SystemModelT::observationFunction(noisyState);
+            SystemModelT::ObsT noise = SystemModelT::ObsT::Random();
+            noise.segment(0, 1) *= obs_rot_noise_std;
+            noise.segment(1, 2) *= obs_pos_noise_std;
 
-            //noisyObs(0) = std::clamp(noisyObs(0), -M_PI + eps, M_PI - eps);
-
-            noisyObs(0) = simox::math::periodic_clamp(noisyObs(0), -M_PI, M_PI);
-
-            observations.push_back(noisyObs);
+            observations.push_back(obs + noise);
         }
     }
 
@@ -167,15 +153,19 @@ namespace armarx::navigation::components::dynamic_scene_provider
         Q.block<2, 2>(1, 1) *= pos_noise_std * pos_noise_std;
 
         UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
-            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std *
-            obs_noise_std;
+            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity();
+        R.block<1, 1>(0, 0) *= obs_rot_noise_std * obs_rot_noise_std;
+        R.block<2, 2>(1, 1) *= obs_pos_noise_std * obs_pos_noise_std;
+
         UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
             UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
         P0.block<1, 1>(0, 0) *= initial_offset_angle * initial_offset_angle;
         P0.block<2, 2>(1, 1) *= initial_offet_pos.norm() * initial_offet_pos.norm();
 
-        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
-            UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
+        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha;
+        alpha(0) = 0.8; // state
+        alpha(1) = 0.1; // control
+        alpha(2) = 0.1; // update
 
         SystemModelT::StateT state0;
         state0.orientation = manif::SO2<T>(states.at(0).orientation.angle() + initial_offset_angle);
@@ -200,14 +190,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
             TIMING_START(PROPAGATION);
             ukf.propagation(omegas.at(i - 1), dt);
             TIMING_END(PROPAGATION);
-            if ((i - 1) % 101 == 0)
+            if ((i - 1) % 50 == 0)
             {
-                // dirty hack
-                //if (std::abs(M_PI - std::abs(observations.at(i)(0))) < 0.1)
-                //{
-                //   continue;
-                //}
-
                 TIMING_START(UPDATE);
                 ukf.update(observations.at(i));
                 TIMING_END(UPDATE);
@@ -256,12 +240,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
             TIMING_END(LOOP);
         }
 
-
         sciplot::Plot2D pos_plot;
         pos_plot.xlabel("x");
         pos_plot.ylabel("y");
         pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
-        pos_plot.xrange(-1.6, 1.6).yrange(-1.6, 1.6);
+        pos_plot.xrange(-RAD * 1.1, RAD * 1.1).yrange(-RAD * 1.1, RAD * 1.1);
         //pos_plot.xrange(-4, 4).yrange(-4, 4);
 
         pos_plot.drawCurve(x_true, y_true).label("True");
@@ -287,7 +270,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         error_plot.xlabel("x");
         error_plot.ylabel("y");
         error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
-        error_plot.xrange(-0.1, 1.1).yrange(-1e-3, 1e-3);
+
 
         error_plot.drawCurve(x_t, ukf_pos_var).label("Pos cariance").lineWidth(1);
         error_plot.drawCurve(x_t, ukf_rot_var).label("Rot variance").lineWidth(1);
-- 
GitLab


From e43c53529a68b0461cb3dcd15a90bfe276fc136a Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 31 Aug 2022 11:32:46 +0200
Subject: [PATCH 186/324] new event handling for failure in local planning

---
 .../services/EventSubscriptionInterface.h     |  7 +++-
 .../client/services/SimpleEventHandler.cpp    | 16 ++++++++
 .../client/services/SimpleEventHandler.h      |  3 ++
 source/armarx/navigation/core/aron/Events.xml |  6 +++
 .../navigation/core/aron_conversions.cpp      | 19 +++++++--
 .../armarx/navigation/core/aron_conversions.h |  6 +++
 source/armarx/navigation/core/events.h        |  6 +++
 .../memory/client/events/Writer.cpp           |  8 ++++
 .../navigation/memory/client/events/Writer.h  |  1 +
 source/armarx/navigation/server/Navigator.cpp | 40 +++++++++++++------
 .../EventPublishingInterface.h                |  1 +
 .../event_publishing/MemoryPublisher.cpp      |  5 +++
 .../server/event_publishing/MemoryPublisher.h |  2 +
 13 files changed, 103 insertions(+), 17 deletions(-)

diff --git a/source/armarx/navigation/client/services/EventSubscriptionInterface.h b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
index 115babcf..e225f675 100644
--- a/source/armarx/navigation/client/services/EventSubscriptionInterface.h
+++ b/source/armarx/navigation/client/services/EventSubscriptionInterface.h
@@ -13,12 +13,15 @@ namespace armarx::navigation::client
 
     using GlobalTrajectoryUpdatedCallback =
         std::function<void(const global_planning::GlobalPlannerResult&)>;
-    using LocalTrajectoryUpdatedCallback = std::function<void(const local_planning::LocalPlannerResult&)>;
+    using LocalTrajectoryUpdatedCallback =
+        std::function<void(const local_planning::LocalPlannerResult&)>;
     using TrajectoryControllerUpdatedCallback =
         std::function<void(const traj_ctrl::local::TrajectoryControllerResult&)>;
     using GlobalPlanningFailedCallback =
         std::function<void(const core::GlobalPlanningFailedEvent&)>;
 
+    using LocalPlanningFailedCallback = std::function<void(const core::LocalPlanningFailedEvent&)>;
+
     using OnMovementStartedCallback = std::function<void(const core::MovementStartedEvent&)>;
 
     using OnGoalReachedCallback = std::function<void(const core::GoalReachedEvent&)>;
@@ -49,6 +52,8 @@ namespace armarx::navigation::client
         virtual void onInternalError(const OnInternalErrorCallback& callback) = 0;
 
         virtual void onGlobalPlanningFailed(const GlobalPlanningFailedCallback& callback) = 0;
+        virtual void onLocalPlanningFailed(const LocalPlanningFailedCallback& callback) = 0;
+
 
         // Non-API.
         virtual ~EventSubscriptionInterface() = default;
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.cpp b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
index c849f30a..8406a840 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.cpp
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.cpp
@@ -61,6 +61,13 @@ armarx::navigation::client::SimpleEventHandler::onGlobalPlanningFailed(
     subscriptions.globalPlanningFailedCallbacks.push_back(callback);
 }
 
+void
+armarx::navigation::client::SimpleEventHandler::onLocalPlanningFailed(
+    const LocalPlanningFailedCallback& callback)
+{
+    subscriptions.localPlanningFailedCallbacks.push_back(callback);
+}
+
 void
 armarx::navigation::client::SimpleEventHandler::goalReached(const core::GoalReachedEvent& event)
 {
@@ -163,6 +170,15 @@ namespace armarx::navigation::client
         }
     }
 
+    void
+    SimpleEventHandler::localPlanningFailed(const core::LocalPlanningFailedEvent& event)
+    {
+        for (const auto& callback : subscriptions.localPlanningFailedCallbacks)
+        {
+            callback(event);
+        }
+    }
+
     void
     SimpleEventHandler::movementStarted(const core::MovementStartedEvent& event)
     {
diff --git a/source/armarx/navigation/client/services/SimpleEventHandler.h b/source/armarx/navigation/client/services/SimpleEventHandler.h
index 6bb0e690..a76a4a61 100644
--- a/source/armarx/navigation/client/services/SimpleEventHandler.h
+++ b/source/armarx/navigation/client/services/SimpleEventHandler.h
@@ -27,12 +27,14 @@ namespace armarx::navigation::client
 
         void onMovementStarted(const OnMovementStartedCallback& callback) override;
         void onGlobalPlanningFailed(const GlobalPlanningFailedCallback& callback) override;
+        void onLocalPlanningFailed(const LocalPlanningFailedCallback& callback) override;
 
         // EventPublishingInterface
         void globalTrajectoryUpdated(const global_planning::GlobalPlannerResult& event) override;
         void localTrajectoryUpdated(const local_planning::LocalPlannerResult& event) override;
         // void trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& event) override;
         void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) override;
+        void localPlanningFailed(const core::LocalPlanningFailedEvent& event) override;
 
         void movementStarted(const core::MovementStartedEvent& event) override;
         void goalReached(const core::GoalReachedEvent& event) override;
@@ -49,6 +51,7 @@ namespace armarx::navigation::client
             std::vector<LocalTrajectoryUpdatedCallback> localTrajectoryUpdatedCallbacks;
             std::vector<TrajectoryControllerUpdatedCallback> trajectoryControllerUpdatedCallbacks;
             std::vector<GlobalPlanningFailedCallback> globalPlanningFailedCallbacks;
+            std::vector<LocalPlanningFailedCallback> localPlanningFailedCallbacks;
 
             std::vector<OnMovementStartedCallback> movementStartedCallbacks;
             std::vector<OnGoalReachedCallback> goalReachedCallbacks;
diff --git a/source/armarx/navigation/core/aron/Events.xml b/source/armarx/navigation/core/aron/Events.xml
index ca7c8603..20d53656 100644
--- a/source/armarx/navigation/core/aron/Events.xml
+++ b/source/armarx/navigation/core/aron/Events.xml
@@ -46,6 +46,12 @@
             </ObjectChild>
         </Object>
 
+        <Object name='armarx::navigation::core::arondto::LocalPlanningFailedEvent'>
+            <ObjectChild key='message'>
+                <String />
+            </ObjectChild>
+        </Object>
+
         <Object name='armarx::navigation::core::arondto::SafetyThrottlingTriggeredEvent'>
             <ObjectChild key='pose'>
                 <Pose />
diff --git a/source/armarx/navigation/core/aron_conversions.cpp b/source/armarx/navigation/core/aron_conversions.cpp
index 5da2122f..2a720332 100644
--- a/source/armarx/navigation/core/aron_conversions.cpp
+++ b/source/armarx/navigation/core/aron_conversions.cpp
@@ -1,8 +1,5 @@
 #include "aron_conversions.h"
 
-#include <range/v3/range/conversion.hpp>
-#include <range/v3/view/transform.hpp>
-
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/core/Trajectory.h>
@@ -10,6 +7,8 @@
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/aron/Trajectory.aron.generated.h>
 #include <armarx/navigation/core/types.h>
+#include <range/v3/range/conversion.hpp>
+#include <range/v3/view/transform.hpp>
 
 namespace armarx::navigation::core
 {
@@ -272,4 +271,18 @@ namespace armarx::navigation::core
         aron::fromAron(dto.pose, bo.pose.matrix());
     }
 
+    void
+    fromAron(const armarx::navigation::core::arondto::LocalPlanningFailedEvent& dto,
+             armarx::navigation::core::LocalPlanningFailedEvent& bo)
+    {
+        aron::fromAron(dto.message, bo.message);
+    }
+
+    void
+    toAron(armarx::navigation::core::arondto::LocalPlanningFailedEvent& dto,
+           const armarx::navigation::core::LocalPlanningFailedEvent& bo)
+    {
+        aron::toAron(dto.message, bo.message);
+    }
+
 } // namespace armarx::navigation::core
diff --git a/source/armarx/navigation/core/aron_conversions.h b/source/armarx/navigation/core/aron_conversions.h
index 2fd54753..408385df 100644
--- a/source/armarx/navigation/core/aron_conversions.h
+++ b/source/armarx/navigation/core/aron_conversions.h
@@ -82,6 +82,12 @@ namespace armarx::navigation::core
     void toAron(armarx::navigation::core::arondto::GlobalPlanningFailedEvent& dto,
                 const armarx::navigation::core::GlobalPlanningFailedEvent& bo);
 
+      void fromAron(const armarx::navigation::core::arondto::LocalPlanningFailedEvent& dto,
+                  armarx::navigation::core::LocalPlanningFailedEvent& bo);
+
+    void toAron(armarx::navigation::core::arondto::LocalPlanningFailedEvent& dto,
+                const armarx::navigation::core::LocalPlanningFailedEvent& bo);
+
     void fromAron(const armarx::navigation::core::arondto::MovementStartedEvent& dto,
                   armarx::navigation::core::MovementStartedEvent& bo);
 
diff --git a/source/armarx/navigation/core/events.h b/source/armarx/navigation/core/events.h
index 09ef7781..594f1301 100644
--- a/source/armarx/navigation/core/events.h
+++ b/source/armarx/navigation/core/events.h
@@ -13,6 +13,7 @@ namespace armarx::navigation::core
     namespace event_names
     {
         inline const std::string GlobalPlanningFailed = "GlobalPlanningFailedEvent";
+        inline const std::string LocalPlanningFailed = "LocalPlanningFailedEvent";
         inline const std::string MovementStarted = "MovementStartedEvent";
         inline const std::string GoalReached = "GoalReachedEvent";
         inline const std::string WaypointReached = "WaypointReachedEvent";
@@ -31,6 +32,11 @@ namespace armarx::navigation::core
     {
         std::string message;
     };
+    
+    struct LocalPlanningFailedEvent : public Event
+    {
+        std::string message;
+    };
 
     struct MovementStartedEvent : Event
     {
diff --git a/source/armarx/navigation/memory/client/events/Writer.cpp b/source/armarx/navigation/memory/client/events/Writer.cpp
index 83009655..ebfb0449 100644
--- a/source/armarx/navigation/memory/client/events/Writer.cpp
+++ b/source/armarx/navigation/memory/client/events/Writer.cpp
@@ -89,6 +89,14 @@ namespace armarx::navigation::memory::client::events
             event, core::event_names::GlobalPlanningFailed, clientID);
     }
 
+        bool
+    Writer::store(const core::LocalPlanningFailedEvent& event, const std::string& clientID)
+    {
+        return storeImpl<core::arondto::LocalPlanningFailedEvent>(
+            event, core::event_names::LocalPlanningFailed, clientID);
+    }
+
+
     bool
     Writer::store(const core::MovementStartedEvent& event, const std::string& clientID)
     {
diff --git a/source/armarx/navigation/memory/client/events/Writer.h b/source/armarx/navigation/memory/client/events/Writer.h
index 7ad07d7d..ddbfad49 100644
--- a/source/armarx/navigation/memory/client/events/Writer.h
+++ b/source/armarx/navigation/memory/client/events/Writer.h
@@ -42,6 +42,7 @@ namespace armarx::navigation::memory::client::events
         bool store(const core::InternalErrorEvent& event, const std::string& clientID);
         bool store(const core::UserAbortTriggeredEvent& event, const std::string& clientID);
         bool store(const core::GlobalPlanningFailedEvent& event, const std::string& clientID);
+        bool store(const core::LocalPlanningFailedEvent& event, const std::string& clientID);
         bool store(const core::MovementStartedEvent& event, const std::string& clientID);
         bool store(const core::SafetyThrottlingTriggeredEvent& event, const std::string& clientID);
         bool store(const core::SafetyStopTriggeredEvent& event, const std::string& clientID);
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 6c4c51b9..db09b85f 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -2,6 +2,7 @@
 
 #include <algorithm>
 #include <chrono>
+#include <cstddef>
 #include <optional>
 #include <thread>
 
@@ -805,9 +806,10 @@ namespace armarx::navigation::server
                 armarx::core::time::StopWatch::measure([&]() { updateScene(); });
 
             ARMARX_DEBUG << deactivateSpam(0.2)
-                           << "Scene update: " << duration.toMilliSecondsDouble() << "ms.";
+                         << "Scene update: " << duration.toMilliSecondsDouble() << "ms.";
 
-            srv.debugObserverHelper->setDebugObserverDatafield("scene update [ms]", duration.toMilliSecondsDouble());
+            srv.debugObserverHelper->setDebugObserverDatafield("scene update [ms]",
+                                                               duration.toMilliSecondsDouble());
         }
 
         // global planner update if goal has changed
@@ -882,9 +884,10 @@ namespace armarx::navigation::server
                     }
                 });
             ARMARX_DEBUG << deactivateSpam(0.2)
-                           << "Local planner update: " << duration.toMilliSecondsDouble() << "ms.";
+                         << "Local planner update: " << duration.toMilliSecondsDouble() << "ms.";
 
-            srv.debugObserverHelper->setDebugObserverDatafield("local planner update [ms]", duration.toMilliSecondsDouble());
+            srv.debugObserverHelper->setDebugObserverDatafield("local planner update [ms]",
+                                                               duration.toMilliSecondsDouble());
         }
 
         // monitor update
@@ -895,9 +898,10 @@ namespace armarx::navigation::server
                 armarx::core::time::StopWatch::measure([&]() { updateMonitor(); });
 
             ARMARX_DEBUG << deactivateSpam(0.2)
-                           << "Monitor update: " << duration.toMilliSecondsDouble() << "ms.";
+                         << "Monitor update: " << duration.toMilliSecondsDouble() << "ms.";
 
-            srv.debugObserverHelper->setDebugObserverDatafield("monitor update [ms]", duration.toMilliSecondsDouble());
+            srv.debugObserverHelper->setDebugObserverDatafield("monitor update [ms]",
+                                                               duration.toMilliSecondsDouble());
         }
     }
 
@@ -913,18 +917,28 @@ namespace armarx::navigation::server
     {
         ARMARX_CHECK(hasLocalPlanner());
 
-        localPlan = config.stack.localPlanner->plan(globalPlan->trajectory);
-
-        if (localPlan.has_value())
+        try
         {
-            srv.publisher->localTrajectoryUpdated(localPlan.value());
+            localPlan = config.stack.localPlanner->plan(globalPlan->trajectory);
+            if (localPlan.has_value())
+            {
+                srv.publisher->localTrajectoryUpdated(localPlan.value());
+            }
+            return localPlan;
         }
-        else
+        catch (...)
         {
-            // srv.publisher->localTrajectoryPlanningFailed();
+            ARMARX_WARNING << "Failure in local planner: " << GetHandledExceptionString();
+            srv.publisher->localPlanningFailed(core::LocalPlanningFailedEvent{
+                {.timestamp = armarx::Clock::Now()}, {GetHandledExceptionString()}});
+
+            return std::nullopt;
         }
 
-        return localPlan;
+        srv.publisher->localPlanningFailed(core::LocalPlanningFailedEvent{
+            {.timestamp = armarx::Clock::Now()}, {"Unknown reason"}});
+
+        return std::nullopt;
     }
 
     void
diff --git a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
index 6ead929f..c9cf86ac 100644
--- a/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
+++ b/source/armarx/navigation/server/event_publishing/EventPublishingInterface.h
@@ -24,6 +24,7 @@ namespace armarx::navigation::server
         // trajectoryControllerUpdated(const traj_ctrl::local::TrajectoryControllerResult& res) = 0;
 
         virtual void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) = 0;
+        virtual void localPlanningFailed(const core::LocalPlanningFailedEvent& event) = 0;
 
 
         virtual void movementStarted(const core::MovementStartedEvent& event) = 0;
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
index 36f4e960..0ea9699c 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
@@ -70,6 +70,11 @@ namespace armarx::navigation::server
     {
         eventsWriter->store(event, clientId);
     }
+    
+    void MemoryPublisher::localPlanningFailed(const core::LocalPlanningFailedEvent& event) 
+    {
+        eventsWriter->store(event, clientId);
+    }
 
     void
     MemoryPublisher::movementStarted(const core::MovementStartedEvent& event)
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
index 831510f4..edf5ff0d 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.h
@@ -22,6 +22,8 @@ namespace armarx::navigation::server
         //     const traj_ctrl::local::TrajectoryControllerResult& res) override;
 
         void globalPlanningFailed(const core::GlobalPlanningFailedEvent& event) override;
+        void localPlanningFailed(const core::LocalPlanningFailedEvent& event) override;
+
 
         void movementStarted(const core::MovementStartedEvent& event) override;
         void goalReached(const core::GoalReachedEvent& event) override;
-- 
GitLab


From 894c991993021d499b4e710d234d63a7e227464c Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 31 Aug 2022 11:33:52 +0200
Subject: [PATCH 187/324] PlatformController: activating controller if it's not
 active yet

---
 .../server/execution/PlatformControllerExecutor.cpp          | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index ef507743..e7bb44d8 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -80,6 +80,11 @@ namespace armarx::navigation::server
 
         // sends the updated config to the controller and stores it in the memory
         ctrl->updateConfig();
+
+        if(not ctrl->ctrl()->isControllerActive())
+        {
+            start();
+        }
     }
 
     void
-- 
GitLab


From eb746bec7dcfa6456bba78707ac99e6ba1b71a03 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 31 Aug 2022 11:34:21 +0200
Subject: [PATCH 188/324] goal reaching: higher angular precision need (5deg ->
 3deg)

---
 source/armarx/navigation/server/monitoring/GoalReachedMonitor.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/server/monitoring/GoalReachedMonitor.h b/source/armarx/navigation/server/monitoring/GoalReachedMonitor.h
index 34f9e49d..ddfdc0bc 100644
--- a/source/armarx/navigation/server/monitoring/GoalReachedMonitor.h
+++ b/source/armarx/navigation/server/monitoring/GoalReachedMonitor.h
@@ -34,7 +34,7 @@ namespace armarx::navigation::server
     struct GoalReachedMonitorConfig
     {
         float posTh{70.F};                                  // [mm]
-        float oriTh{VirtualRobot::MathTools::deg2rad(5.F)}; // [rad]
+        float oriTh{VirtualRobot::MathTools::deg2rad(3.F)}; // [rad]
 
         float linearVelTh{100.F};                                  // [mm/s]
         float angularVelTh{VirtualRobot::MathTools::deg2rad(5.F)}; // [rad/s]
-- 
GitLab


From e0cfc92da4fb08014e26e40277a056f4c74c9f62 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 31 Aug 2022 11:35:08 +0200
Subject: [PATCH 189/324] scneario update

---
 .../PlatformNavigation/PlatformNavigation.scx |  2 +-
 .../config/ObjectMemory.cfg                   | 25 +++++++++++++------
 .../config/example_client.cfg                 | 13 ++++++----
 .../config/navigation_memory.cfg              | 13 ++++++----
 .../PlatformNavigation/config/navigator.cfg   | 18 -------------
 5 files changed, 34 insertions(+), 37 deletions(-)

diff --git a/scenarios/PlatformNavigation/PlatformNavigation.scx b/scenarios/PlatformNavigation/PlatformNavigation.scx
index a290831f..cc0fcea7 100644
--- a/scenarios/PlatformNavigation/PlatformNavigation.scx
+++ b/scenarios/PlatformNavigation/PlatformNavigation.scx
@@ -6,7 +6,7 @@
 	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index be7ed818..773e4812 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -259,6 +259,15 @@
 # ArmarX.ObjectMemory.mem.inst.calibration.offset = 0
 
 
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName:  Name of robot whose note can be calibrated.
+# If not given, the 'fallbackName' is used.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.calibration.robotName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.calibration.robotNode:  Robot node which can be calibrated.
 #  Attributes:
 #  - Default:            Neck_2_Pitch
@@ -341,6 +350,14 @@
 # ArmarX.ObjectMemory.mem.inst.head.maxJointVelocity = 0.0500000007
 
 
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName:  Robot name to use as fallback if the robot name is not specified in a provided object pose.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.robots.FallbackName = ""
+
+
 # ArmarX.ObjectMemory.mem.inst.scene.10_Package:  ArmarX package containing the scene snapshots.
 # Scene snapshots are expected to be located in Package/data/Package/Scenes/*.json.
 #  Attributes:
@@ -572,14 +589,6 @@
 # ArmarX.ObjectMemory.prediction.TimeWindow = 2
 
 
-# ArmarX.ObjectMemory.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ObjectMemory.robotName = Armar6
-
-
 # ArmarX.ObjectMemory.tpc.pub.DebugObserver:  Name of the `DebugObserver` topic to publish data to.
 #  Attributes:
 #  - Default:            DebugObserver
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index f459b030..9d58c818 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -76,6 +76,14 @@
 # ArmarX.EnableProfiling = false
 
 
+# ArmarX.ExampleClient.nav.NavigatorName:  No Description
+#  Attributes:
+#  - Default:            navigator
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.ExampleClient.nav.NavigatorName = navigator
+
+
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
@@ -253,8 +261,3 @@ ArmarX.example_client.mode = standard
 # ArmarX.example_client.robotName = Armar6
 
 
-# ArmarX.ExampleClient.nav.NavigatorName:  
-#  Attributes:
-ArmarX.ExampleClient.nav.NavigatorName = navigator
-
-
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index 74b205e7..751247e4 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,6 +92,14 @@
 # ArmarX.LoggingGroup = ""
 
 
+# ArmarX.NavigationMemory.p.snapshotToLoad:  No Description
+#  Attributes:
+#  - Default:            ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+
+
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -288,8 +296,3 @@
 # ArmarX.navigation_memory.p.snapshotToLoad = ""
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  
-#  Attributes:
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
-
-
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 5bf206ad..36c97cb0 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -225,14 +225,6 @@ ArmarX.navigator.ObjectName = navigator
 ArmarX.navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.navigator.cmp.PlatformUnit:  No Description
-#  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
-
-
 # ArmarX.navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
 #  Attributes:
 #  - Default:            RemoteGuiProvider
@@ -412,13 +404,3 @@ ArmarX.navigator.cmp.PlatformUnit = Armar6PlatformUnit
 ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
-# ArmarX.Navigator.ObjectName:  
-#  Attributes:
-ArmarX.Navigator.ObjectName = navigator
-
-
-# ArmarX.Navigator.RobotUnitName:  
-#  Attributes:
-ArmarX.Navigator.RobotUnitName = Armar6Unit
-
-
-- 
GitLab


From a22a554601a9e6f034dae45af1fa8308766982b3 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 1 Sep 2022 12:44:12 +0200
Subject: [PATCH 190/324] some checks

---
 source/armarx/navigation/global_planning/SPFA.cpp | 3 +++
 1 file changed, 3 insertions(+)

diff --git a/source/armarx/navigation/global_planning/SPFA.cpp b/source/armarx/navigation/global_planning/SPFA.cpp
index 9491705a..62b42068 100644
--- a/source/armarx/navigation/global_planning/SPFA.cpp
+++ b/source/armarx/navigation/global_planning/SPFA.cpp
@@ -91,6 +91,9 @@ namespace armarx::navigation::global_planning
         // FIXME check if costmap is available
 
         algorithms::spfa::ShortestPathFasterAlgorithm::Parameters spfaParams;
+
+        ARMARX_CHECK(scene.staticScene.has_value());
+        ARMARX_CHECK(scene.staticScene->distanceToObstaclesCostmap.has_value());
         algorithms::spfa::ShortestPathFasterAlgorithm planner(*scene.staticScene->distanceToObstaclesCostmap,
                                                               spfaParams);
 
-- 
GitLab


From 83f37145ec0dcebe1371be6c1af624097ac0fb0e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 1 Sep 2022 12:44:31 +0200
Subject: [PATCH 191/324] new library for simulated humans

---
 .../navigation/simulation/SimulatedHuman.cpp  | 174 ++++++++++++++++++
 .../navigation/simulation/SimulatedHuman.h    |  72 ++++++++
 .../navigation/simulation/simulation.cpp      |  28 +++
 .../armarx/navigation/simulation/simulation.h |  45 +++++
 .../simulation/test/simulationTest.cpp        |  36 ++++
 5 files changed, 355 insertions(+)
 create mode 100644 source/armarx/navigation/simulation/SimulatedHuman.cpp
 create mode 100644 source/armarx/navigation/simulation/SimulatedHuman.h
 create mode 100644 source/armarx/navigation/simulation/simulation.cpp
 create mode 100644 source/armarx/navigation/simulation/simulation.h
 create mode 100644 source/armarx/navigation/simulation/test/simulationTest.cpp

diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
new file mode 100644
index 00000000..56f0d60d
--- /dev/null
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -0,0 +1,174 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include "SimulatedHuman.h"
+
+#include <Eigen/src/Core/Matrix.h>
+
+#include <VirtualRobot/Random.h>
+
+#include "ArmarXCore/core/logging/Logging.h"
+
+#include "armarx/navigation/conversions/eigen.h"
+#include "armarx/navigation/core/StaticScene.h"
+#include "armarx/navigation/core/types.h"
+#include "armarx/navigation/global_planning/SPFA.h"
+#include "armarx/navigation/human/types.h"
+
+namespace armarx::navigation::human::simulation
+{
+
+
+    human::Human
+    SimulatedHuman::update()
+    {
+        switch (state_)
+        {
+            case State::Idle:
+                ARMARX_DEBUG << "State:Idle";
+                initialize();
+                state_ = State::Walking;
+                break;
+            case State::Walking:
+            {
+                ARMARX_DEBUG << "State:Walking";
+
+                step();
+
+                const Eigen::Vector2f goal =
+                    conv::to2D(globalTrajectory_.points().back().waypoint.pose.translation());
+
+                if ((goal - human_.pose.translation()).norm() < params_.goalDistanceThreshold)
+                {
+                    state_ = State::GoalReached;
+                }
+
+                break;
+            }
+            case State::GoalReached:
+                ARMARX_DEBUG << "State:GoalReached";
+
+                state_ = State::GoalReached;
+                break;
+        }
+
+        return human_;
+    }
+
+    void
+    SimulatedHuman::initialize()
+    {
+        global_planning::SPFA::Params params;
+        core::Scene scene;
+
+        scene.staticScene.emplace(core::StaticScene{nullptr, std::nullopt});
+        scene.staticScene->distanceToObstaclesCostmap.emplace(distanceField_);
+
+        global_planning::SPFA planner(params, scene);
+
+        const auto start = sampleValidPositionInMap();
+
+        while (true)
+        {
+            const auto goal = sampleValidPositionInMap();
+
+            const auto plan = planner.plan(conv::to3D(start), conv::to3D(goal));
+
+            // check if plan could be created. otherwise try another goal
+            if (plan.has_value())
+            {
+                globalTrajectory_ = plan->trajectory;
+
+                human_ = human::Human{.pose = start,
+                                      .linearVelocity = Eigen::Vector2f::Zero(),
+                                      .detectionTime = Clock::Now()};
+                return;
+            }
+        }
+    }
+
+    void
+    SimulatedHuman::step()
+    {
+        const auto updateTime = Clock::Now();
+
+        const auto duration = updateTime - human_.detectionTime;
+
+        // move according to old state
+        human_.pose.translation() += duration.toSecondsDouble() * human_.linearVelocity;
+
+        const auto projection =
+            globalTrajectory_.getProjection(conv::to3D(human_.pose.translation()),
+                                            core::VelocityInterpolation::LinearInterpolation);
+
+        human_.pose = conv::to2D(projection.projection.waypoint.pose);
+
+        const auto wpBefore = projection.wayPointBefore.waypoint.pose.translation();
+        const auto wpAfter = projection.wayPointAfter.waypoint.pose.translation();
+
+        human_.linearVelocity =
+            (wpAfter - wpBefore).head<2>().normalized() * projection.projection.velocity;
+
+        human_.detectionTime = updateTime;
+    }
+
+    core::Pose2D
+    SimulatedHuman::sampleValidPositionInMap() const
+    {
+
+        const auto now = Clock::Now();
+
+
+        const auto sizeX = distanceField_.getGrid().cols();
+        const auto sizeY = distanceField_.getGrid().rows();
+
+        // sample a valid pose in the costmap
+        const core::Pose2D pose = [this, &sizeX, &sizeY]()
+        {
+            while (true)
+            {
+                const float iX = VirtualRobot::RandomFloat() * static_cast<float>(sizeX);
+                const float iY = VirtualRobot::RandomFloat() * static_cast<float>(sizeY);
+
+                algorithms::Costmap::Index idx(iX, iY);
+
+                if (not distanceField_.isValid(idx))
+                {
+                    continue;
+                }
+
+                core::Pose2D pose = core::Pose2D::Identity();
+                pose.translation() = distanceField_.toPositionGlobal(idx);
+                return pose;
+            }
+        }();
+
+        // return human::Human human{
+        //     .pose = pose, .linearVelocity = Eigen::Vector2f::Zero(), .detectionTime = now};
+
+        return pose;
+    }
+
+    SimulatedHuman::SimulatedHuman(const algorithms::Costmap& distanceField, const Params& params) :
+        distanceField_(distanceField), params_(params)
+    {
+    }
+} // namespace armarx::navigation::human::simulation
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.h b/source/armarx/navigation/simulation/SimulatedHuman.h
new file mode 100644
index 00000000..08f8a150
--- /dev/null
+++ b/source/armarx/navigation/simulation/SimulatedHuman.h
@@ -0,0 +1,72 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "armarx/navigation/algorithms/Costmap.h"
+#include "armarx/navigation/core/Trajectory.h"
+#include "armarx/navigation/core/basic_types.h"
+#include "armarx/navigation/human/types.h"
+
+namespace armarx::navigation::human::simulation
+{
+
+
+    class SimulatedHuman
+    {
+    public:
+        struct Params
+        {
+            float goalDistanceThreshold = 100;
+        };
+
+        SimulatedHuman(const algorithms::Costmap& distanceField, const Params& params = Params());
+
+        Human update();
+
+    protected:
+        void initialize();
+
+        void step();
+
+        enum class State
+        {
+            Idle,
+            Walking,
+            GoalReached
+        };
+
+    private:
+        const algorithms::Costmap distanceField_;
+
+        State state_ = State::Idle;
+
+        human::Human human_;
+
+
+        core::Pose2D sampleValidPositionInMap() const;
+
+        core::GlobalTrajectory globalTrajectory_;
+
+        const Params params_;
+    };
+
+} // namespace armarx::navigation::human::simulation
diff --git a/source/armarx/navigation/simulation/simulation.cpp b/source/armarx/navigation/simulation/simulation.cpp
new file mode 100644
index 00000000..fee4cfba
--- /dev/null
+++ b/source/armarx/navigation/simulation/simulation.cpp
@@ -0,0 +1,28 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::simulation
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include "simulation.h"
+
+namespace armarx
+{
+
+}
diff --git a/source/armarx/navigation/simulation/simulation.h b/source/armarx/navigation/simulation/simulation.h
new file mode 100644
index 00000000..36a6c6b3
--- /dev/null
+++ b/source/armarx/navigation/simulation/simulation.h
@@ -0,0 +1,45 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::simulation
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+
+namespace armarx
+{
+    /**
+    * @defgroup Library-simulation simulation
+    * @ingroup navigation
+    * A description of the library simulation.
+    *
+    * @class simulation
+    * @ingroup Library-simulation
+    * @brief Brief description of class simulation.
+    *
+    * Detailed description of class simulation.
+    */
+    class simulation
+    {
+    public:
+
+    };
+
+}
diff --git a/source/armarx/navigation/simulation/test/simulationTest.cpp b/source/armarx/navigation/simulation/test/simulationTest.cpp
new file mode 100644
index 00000000..eb077826
--- /dev/null
+++ b/source/armarx/navigation/simulation/test/simulationTest.cpp
@@ -0,0 +1,36 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::simulation
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE navigation::ArmarXLibraries::simulation
+
+#define ARMARX_BOOST_TEST
+
+#include <navigation/Test.h>
+#include "../simulation.h"
+
+#include <iostream>
+
+BOOST_AUTO_TEST_CASE(testExample)
+{
+
+    BOOST_CHECK_EQUAL(true, true);
+}
-- 
GitLab


From e0c621e63744ff7bda2ce981e77ed64fe6ffe052 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 1 Sep 2022 12:44:55 +0200
Subject: [PATCH 192/324] cmakelists

---
 .../navigation/simulation/CMakeLists.txt      | 23 +++++++++++++++++++
 1 file changed, 23 insertions(+)
 create mode 100644 source/armarx/navigation/simulation/CMakeLists.txt

diff --git a/source/armarx/navigation/simulation/CMakeLists.txt b/source/armarx/navigation/simulation/CMakeLists.txt
new file mode 100644
index 00000000..774fdf64
--- /dev/null
+++ b/source/armarx/navigation/simulation/CMakeLists.txt
@@ -0,0 +1,23 @@
+armarx_add_library(simulation
+    SOURCES
+        simulation.cpp
+        SimulatedHuman.cpp
+    HEADERS
+        simulation.h
+        SimulatedHuman.h
+    DEPENDENCIES_PUBLIC
+        ArmarXCoreInterfaces
+        ArmarXCore
+        # armarx_navigation
+        armarx_navigation::core
+        armarx_navigation::conversions
+        armarx_navigation::global_planning
+)
+
+ 
+armarx_add_test(simulationTest 
+    TEST_FILES
+        test/simulationTest.cpp
+    DEPENDENCIES
+        navigation::simulation
+)
-- 
GitLab


From 1be58a10d4af4567ceb786eecb2da629458c2a5c Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 1 Sep 2022 12:45:21 +0200
Subject: [PATCH 193/324] human simulator component

---
 source/armarx/navigation/CMakeLists.txt       |   1 +
 .../navigation/components/CMakeLists.txt      |   2 +
 .../components/human_simulator/CMakeLists.txt |  26 ++
 .../components/human_simulator/Component.cpp  | 306 ++++++++++++++++++
 .../components/human_simulator/Component.h    | 173 ++++++++++
 .../human_simulator/ComponentInterface.ice    |  35 ++
 6 files changed, 543 insertions(+)
 create mode 100644 source/armarx/navigation/components/human_simulator/CMakeLists.txt
 create mode 100644 source/armarx/navigation/components/human_simulator/Component.cpp
 create mode 100644 source/armarx/navigation/components/human_simulator/Component.h
 create mode 100644 source/armarx/navigation/components/human_simulator/ComponentInterface.ice

diff --git a/source/armarx/navigation/CMakeLists.txt b/source/armarx/navigation/CMakeLists.txt
index 60936986..ec9f8748 100644
--- a/source/armarx/navigation/CMakeLists.txt
+++ b/source/armarx/navigation/CMakeLists.txt
@@ -16,6 +16,7 @@ add_subdirectory(location)
 add_subdirectory(memory)
 add_subdirectory(server)
 add_subdirectory(platform_controller)
+add_subdirectory(simulation)
 
 # Components.
 add_subdirectory(components)
diff --git a/source/armarx/navigation/components/CMakeLists.txt b/source/armarx/navigation/components/CMakeLists.txt
index 317b56b4..028e7732 100644
--- a/source/armarx/navigation/components/CMakeLists.txt
+++ b/source/armarx/navigation/components/CMakeLists.txt
@@ -17,3 +17,5 @@ add_subdirectory(distance_to_obstacle_costmap_provider)
 # others
 # ===================================
 add_subdirectory(dynamic_scene_provider)
+
+add_subdirectory(human_simulator)
\ No newline at end of file
diff --git a/source/armarx/navigation/components/human_simulator/CMakeLists.txt b/source/armarx/navigation/components/human_simulator/CMakeLists.txt
new file mode 100644
index 00000000..3ea4392a
--- /dev/null
+++ b/source/armarx/navigation/components/human_simulator/CMakeLists.txt
@@ -0,0 +1,26 @@
+armarx_add_component(human_simulator
+    ICE_FILES
+        ComponentInterface.ice
+    ICE_DEPENDENCIES
+        ArmarXCoreInterfaces
+    SOURCES
+        Component.cpp
+    HEADERS
+        Component.h
+    DEPENDENCIES
+         # ArmarXCore
+         ArmarXCore
+         # RobotAPI
+         armem
+         armem_robot
+         armem_robot_state
+         # VisionX
+         armem_human
+         armem_vision
+         # navigation
+         armarx_navigation::util
+         armarx_navigation::memory
+         armarx_navigation::dynamic_scene
+         armarx_navigation::teb_human
+         armarx_navigation::simulation
+)
diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
new file mode 100644
index 00000000..c53b89e5
--- /dev/null
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -0,0 +1,306 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::human_simulator
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#include "Component.h"
+
+#include <cstdlib>
+
+#include <VirtualRobot/Random.h>
+
+#include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
+
+#include "armarx/navigation/algorithms/Costmap.h"
+#include "armarx/navigation/core/basic_types.h"
+#include "armarx/navigation/human/types.h"
+#include "armarx/navigation/simulation/SimulatedHuman.h"
+
+// Include headers you only need in function definitions in the .cpp.
+
+// #include <Eigen/Core>
+
+// #include <SimoxUtility/color/Color.h>
+
+
+namespace armarx::navigation::components::human_simulator
+{
+    Component::Component()
+    {
+        addPlugin(virtualRobotReaderPlugin);
+        addPlugin(costmapReaderPlugin);
+        addPlugin(humanWriterPlugin);
+    }
+
+
+    const std::string Component::defaultName = "human_simulator";
+
+
+    armarx::PropertyDefinitionsPtr
+    Component::createPropertyDefinitions()
+    {
+        armarx::PropertyDefinitionsPtr def =
+            new armarx::ComponentPropertyDefinitions(getConfigIdentifier());
+
+        // Publish to a topic (passing the TopicListenerPrx).
+        // def->topic(myTopicListener);
+
+        // Subscribe to a topic (passing the topic name).
+        // def->topic<PlatformUnitListener>("MyTopic");
+
+        // Use (and depend on) another component (passing the ComponentInterfacePrx).
+        // def->component(myComponentProxy)
+
+
+        // Add a required property. (The component won't start without a value being set.)
+        // def->required(properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
+
+        // Add an optionalproperty.
+        def->optional(
+            properties.taskPeriodMs, "p.taskPeriodMs", "");
+        def->optional(properties.nHumans, "p.nHumans", "Number of humans to spawn.");
+
+        return def;
+    }
+
+
+    void
+    Component::onInitComponent()
+    {
+        // Topics and properties defined above are automagically registered.
+
+        // Keep debug observer data until calling `sendDebugObserverBatch()`.
+        // (Requies the armarx::DebugObserverComponentPluginUser.)
+        // setDebugObserverBatchModeEnabled(true);
+    }
+
+
+    void
+    Component::onConnectComponent()
+    {
+        // Do things after connecting to topics and components.
+
+        /* (Requies the armarx::DebugObserverComponentPluginUser.)
+        // Use the debug observer to log data over time.
+        // The data can be viewed in the ObserverView and the LivePlotter.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        {
+            setDebugObserverDatafield("numBoxes", properties.numBoxes);
+            setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+            sendDebugObserverBatch();
+        }
+        */
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        // Draw boxes in ArViz.
+        // (Before starting any threads, we don't need to lock mutexes.)
+        drawBoxes(properties, arviz);
+        */
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        // Setup the remote GUI.
+        {
+            createRemoteGuiTab();
+            RemoteGui_startRunningTask();
+        }
+        */
+
+
+        /// 
+
+        //
+        //  Costmaps
+        //
+
+        ARMARX_INFO << "Querying costmap";
+
+        const auto timestamp = Clock::Now();
+
+        const memory::client::costmap::Reader::Query costmapQuery{
+            .providerName = "distance_to_obstacle_costmap_provider", // TODO check
+            .name = "distance_to_obstacles",
+            .timestamp = timestamp};
+
+        const memory::client::costmap::Reader::Result costmapResult =
+            costmapReaderPlugin->get().query(costmapQuery);
+
+        ARMARX_CHECK_EQUAL(costmapResult.status, memory::client::costmap::Reader::Result::Success);
+
+        ARMARX_TRACE;
+        ARMARX_CHECK(costmapResult.costmap.has_value());
+        const auto grid = costmapResult.costmap->getGrid();
+
+        ///
+        
+        for(std::size_t i = 0; i< properties.nHumans ; i++)
+        {
+            simulatedHumans.emplace_back(costmapResult.costmap.value());
+        }
+
+
+        ///
+
+        task = new PeriodicTask<Component>(
+            this, &Component::runPeriodically, properties.taskPeriodMs, false, "runningTask");
+        task->start();
+    }
+
+
+    void
+    Component::onDisconnectComponent()
+    {
+        task->stop();
+    }
+
+
+    void
+    Component::onExitComponent()
+    {
+    }
+
+
+    std::string
+    Component::getDefaultName() const
+    {
+        return Component::defaultName;
+    }
+
+
+    std::string
+    Component::GetDefaultName()
+    {
+        return Component::defaultName;
+    }
+
+    void
+    Component::runPeriodically()
+    {
+        // obtain data from perception
+
+        const DateTime timestamp = Clock::Now();
+
+        //
+        // Robot
+        //
+
+        // ARMARX_CHECK(virtualRobotReaderPlugin->get().synchronizeRobot(*robot, timestamp));
+        // const core::Pose global_T_robot(robot->getGlobalPose());
+
+        // ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
+
+     
+
+        human::Humans humans;
+
+        for (auto& simulatedHuman : simulatedHumans)
+        {
+            humans.push_back(simulatedHuman.update());
+        }
+
+        ARMARX_INFO << "Updating humans.";
+        humanWriterPlugin->get().store(humans, getName(), timestamp);
+    }
+
+
+    /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+    void
+    Component::createRemoteGuiTab()
+    {
+        using namespace armarx::RemoteGui::Client;
+
+        // Setup the widgets.
+
+        tab.boxLayerName.setValue(properties.boxLayerName);
+
+        tab.numBoxes.setValue(properties.numBoxes);
+        tab.numBoxes.setRange(0, 100);
+
+        tab.drawBoxes.setLabel("Draw Boxes");
+
+        // Setup the layout.
+
+        GridLayout grid;
+        int row = 0;
+        {
+            grid.add(Label("Box Layer"), {row, 0}).add(tab.boxLayerName, {row, 1});
+            ++row;
+
+            grid.add(Label("Num Boxes"), {row, 0}).add(tab.numBoxes, {row, 1});
+            ++row;
+
+            grid.add(tab.drawBoxes, {row, 0}, {2, 1});
+            ++row;
+        }
+
+        VBoxLayout root = {grid, VSpacer()};
+        RemoteGui_createTab(getName(), root, &tab);
+    }
+
+
+    void
+    Component::RemoteGui_update()
+    {
+        if (tab.boxLayerName.hasValueChanged() || tab.numBoxes.hasValueChanged())
+        {
+            std::scoped_lock lock(propertiesMutex);
+            properties.boxLayerName = tab.boxLayerName.getValue();
+            properties.numBoxes = tab.numBoxes.getValue();
+
+            {
+                setDebugObserverDatafield("numBoxes", properties.numBoxes);
+                setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
+                sendDebugObserverBatch();
+            }
+        }
+        if (tab.drawBoxes.wasClicked())
+        {
+            // Lock shared variables in methods running in seperate threads
+            // and pass them to functions. This way, the called functions do
+            // not need to think about locking.
+            std::scoped_lock lock(propertiesMutex, arvizMutex);
+            drawBoxes(properties, arviz);
+        }
+    }
+    */
+
+
+    /* (Requires the armarx::ArVizComponentPluginUser.)
+    void
+    Component::drawBoxes(const Component::Properties& p, viz::Client& arviz)
+    {
+        // Draw something in ArViz (requires the armarx::ArVizComponentPluginUser.
+        // See the ArVizExample in RobotAPI for more examples.
+
+        viz::Layer layer = arviz.layer(p.boxLayerName);
+        for (int i = 0; i < p.numBoxes; ++i)
+        {
+            layer.add(viz::Box("box_" + std::to_string(i))
+                      .position(Eigen::Vector3f(i * 100, 0, 0))
+                      .size(20).color(simox::Color::blue()));
+        }
+        arviz.commit(layer);
+    }
+    */
+
+
+    ARMARX_REGISTER_COMPONENT_EXECUTABLE(Component, Component::GetDefaultName());
+
+} // namespace armarx::navigation::components::human_simulator
diff --git a/source/armarx/navigation/components/human_simulator/Component.h b/source/armarx/navigation/components/human_simulator/Component.h
new file mode 100644
index 00000000..8ee5f54b
--- /dev/null
+++ b/source/armarx/navigation/components/human_simulator/Component.h
@@ -0,0 +1,173 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    navigation::ArmarXObjects::human_simulator
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+
+#pragma once
+
+
+// #include <mutex>
+
+#include "ArmarXCore/core/services/tasks/PeriodicTask.h"
+#include <ArmarXCore/core/Component.h>
+#include "RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h"
+
+#include "RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h"
+
+// #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h>
+
+// #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
+
+// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
+
+#include "armarx/navigation/simulation/SimulatedHuman.h"
+#include "armarx/navigation/memory/client/costmap/Reader.h"
+#include "armarx/navigation/memory/client/human/Writer.h"
+#include <armarx/navigation/components/human_simulator/ComponentInterface.h>
+
+
+namespace armarx::navigation::components::human_simulator
+{
+
+    class Component :
+        virtual public armarx::Component,
+        virtual public armarx::navigation::components::human_simulator::ComponentInterface
+    // , virtual public armarx::DebugObserverComponentPluginUser
+    // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
+    // , virtual public armarx::ArVizComponentPluginUser
+    {
+    public:
+        Component();
+
+        /// @see armarx::ManagedIceObject::getDefaultName()
+        std::string getDefaultName() const override;
+
+        /// Get the component's default name.
+        static std::string GetDefaultName();
+
+
+    protected:
+        /// @see PropertyUser::createPropertyDefinitions()
+        armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
+
+        /// @see armarx::ManagedIceObject::onInitComponent()
+        void onInitComponent() override;
+
+        /// @see armarx::ManagedIceObject::onConnectComponent()
+        void onConnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onDisconnectComponent()
+        void onDisconnectComponent() override;
+
+        /// @see armarx::ManagedIceObject::onExitComponent()
+        void onExitComponent() override;
+
+
+        /* (Requires armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// This function should be called once in onConnect() or when you
+        /// need to re-create the Remote GUI tab.
+        void createRemoteGuiTab();
+
+        /// After calling `RemoteGui_startRunningTask`, this function is
+        /// called periodically in a separate thread. If you update variables,
+        /// make sure to synchronize access to them.
+        void RemoteGui_update() override;
+        */
+
+
+    private:
+        // Private methods go here.
+
+        // Forward declare `Properties` if you used it before its defined.
+        // struct Properties;
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+        /// Draw some boxes in ArViz.
+        void drawBoxes(const Properties& p, viz::Client& arviz);
+        */
+
+        void runPeriodically();
+
+
+
+    private:
+        static const std::string defaultName;
+
+        PeriodicTask<Component>::pointer_type task;
+
+
+
+        // Private member variables go here.
+
+
+        /// Properties shown in the Scenario GUI.
+        struct Properties
+        {
+            int taskPeriodMs = 100;
+
+
+            std::size_t nHumans = 4;
+        };
+        Properties properties;
+        /* Use a mutex if you access variables from different threads
+         * (e.g. ice functions and RemoteGui_update()).
+        std::mutex propertiesMutex;
+        */
+
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// Tab shown in the Remote GUI.
+        struct RemoteGuiTab : armarx::RemoteGui::Client::Tab
+        {
+            armarx::RemoteGui::Client::LineEdit boxLayerName;
+            armarx::RemoteGui::Client::IntSpinBox numBoxes;
+
+            armarx::RemoteGui::Client::Button drawBoxes;
+        };
+        RemoteGuiTab tab;
+        */
+
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+         * When used from different threads, an ArViz client needs to be synchronized.
+        /// Protects the arviz client inherited from the ArViz plugin.
+        std::mutex arvizMutex;
+        */
+
+        template <typename T>
+        using ReaderWriterPlugin = armem::client::plugins::ReaderWriterPlugin<T>;
+
+
+        ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin =
+            nullptr;
+
+        ReaderWriterPlugin<memory::client::costmap::Reader>* costmapReaderPlugin = nullptr;
+
+
+        ReaderWriterPlugin<memory::client::human::Writer>* humanWriterPlugin = nullptr;
+
+    
+        std::vector<human::simulation::SimulatedHuman> simulatedHumans;
+
+
+    };
+
+} // namespace armarx::navigation::components::human_simulator
diff --git a/source/armarx/navigation/components/human_simulator/ComponentInterface.ice b/source/armarx/navigation/components/human_simulator/ComponentInterface.ice
new file mode 100644
index 00000000..338669c4
--- /dev/null
+++ b/source/armarx/navigation/components/human_simulator/ComponentInterface.ice
@@ -0,0 +1,35 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * package    navigation::human_simulator
+ * author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * date       2022
+ * copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *            GNU General Public License
+ */
+
+
+#pragma once
+
+
+module armarx {  module navigation {  module components {  module human_simulator 
+{
+
+    interface ComponentInterface
+    {
+	// Define your interface here.
+    };
+
+};};};};
-- 
GitLab


From 48ce7dce8b5ccc8c241927befbbc69bdfb2e5613 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 1 Sep 2022 12:45:39 +0200
Subject: [PATCH 194/324] adding human simulator to humanawarenavigation
 scenario

---
 .../HumanAwareNavigation.scx                  |   3 +-
 .../config/human_simulator.cfg                | 278 ++++++++++++++++++
 2 files changed, 280 insertions(+), 1 deletion(-)
 create mode 100644 scenarios/HumanAwareNavigation/config/human_simulator.cfg

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
index 570cffa4..942bdb1b 100644
--- a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -9,9 +9,10 @@
 	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="dynamic_scene_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="HumanMemoryApp" instance="" package="VisionX" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="human_simulator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
 
diff --git a/scenarios/HumanAwareNavigation/config/human_simulator.cfg b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
new file mode 100644
index 00000000..c0a571fa
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
@@ -0,0 +1,278 @@
+# ==================================================================
+# human_simulator properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
+# ArmarX.human_simulator.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.human_simulator.EnableProfiling = false
+
+
+# ArmarX.human_simulator.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.human_simulator.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.human_simulator.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.ObjectName = ""
+
+
+# ArmarX.human_simulator.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.human_simulator.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.nav.costmap.Memory = Navigation
+
+
+# ArmarX.human_simulator.mem.nav.human.CoreSegment:  
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.nav.human.CoreSegment = Human
+
+
+# ArmarX.human_simulator.mem.nav.human.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.nav.human.Memory = Navigation
+
+
+# ArmarX.human_simulator.mem.nav.human.Provider:  Name of this provider
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.nav.human.Provider = ""
+
+
+# ArmarX.human_simulator.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.human_simulator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.human_simulator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.human_simulator.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.human_simulator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.human_simulator.p.nHumans:  Number of humans to spawn.
+#  Attributes:
+#  - Default:            4
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.p.nHumans = 4
+
+
+# ArmarX.human_simulator.p.taskPeriodMs:  
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.human_simulator.p.taskPeriodMs = 100
+
+
-- 
GitLab


From 837596d9d10b44b72a37da5e62646f29018be5ff Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 1 Sep 2022 20:10:29 +0200
Subject: [PATCH 195/324] Add SE2 SystemModel

---
 .../navigation/human/HumanSystemModel.cpp     | 48 +++++++++++++++++++
 .../navigation/human/HumanSystemModel.h       | 48 +++++++++++++++++++
 2 files changed, 96 insertions(+)

diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index 7a613595..2aabff49 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -65,4 +65,52 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     template struct SystemModelSO2xR2<float>;
     template struct SystemModelSO2xR2<double>;
 
+
+    // ------------------------------ SE2 -----------------------------------------
+
+    template <typename floatT>
+    typename SystemModelSE2<floatT>::ObsT
+    SystemModelSE2<floatT>::observationFunction(const SystemModelSE2::StateT& state)
+    {
+        ObsT observation = state.pose.log().coeffs();
+        return observation;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2<floatT>::StateT
+    SystemModelSE2<floatT>::propagationFunction(const SystemModelSE2::StateT& state,
+                                                const SystemModelSE2::ControlT& control,
+                                                const SystemModelSE2::ControlNoiseT& noise,
+                                                FloatT dt)
+    {
+        StateT new_state;
+        new_state.pose = state.pose.template rplus(control.velocity * dt);
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2<floatT>::StateT
+    SystemModelSE2<floatT>::retraction(const SystemModelSE2::StateT& state,
+                                       const SystemModelSE2::SigmaPointsT& sigmaPoints)
+    {
+        StateT new_state;
+        manif::SE2Tangent<FloatT> tan;
+        tan.coeffs() << sigmaPoints;
+        new_state.pose = state.pose.lplus(tan);
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2<floatT>::SigmaPointsT
+    SystemModelSE2<floatT>::inverseRetraction(const SystemModelSE2::StateT& state1,
+                                              const SystemModelSE2::StateT& state2)
+    {
+        SigmaPointsT sigma;
+        sigma = state2.pose.lminus(state1.pose).coeffs();
+        return sigma;
+    }
+
+    template struct SystemModelSE2<float>;
+    template struct SystemModelSE2<double>;
+
 } // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
diff --git a/source/armarx/navigation/human/HumanSystemModel.h b/source/armarx/navigation/human/HumanSystemModel.h
index fc0b8658..fb0309e1 100644
--- a/source/armarx/navigation/human/HumanSystemModel.h
+++ b/source/armarx/navigation/human/HumanSystemModel.h
@@ -21,6 +21,7 @@
  */
 #pragma once
 
+#include <manif/SE2.h>
 #include <manif/SO2.h>
 
 namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
@@ -73,4 +74,51 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     extern template struct SystemModelSO2xR2<float>;
     extern template struct SystemModelSO2xR2<double>;
 
+
+    //----------- SE2 -----------------
+
+    template <typename floatT>
+    struct StateSE2
+    {
+        manif::SE2<floatT> pose;
+    };
+
+    template <typename floatT>
+    struct ControlSE2
+    {
+        typename manif::SE2<floatT>::Tangent velocity;
+    };
+
+    template <typename floatT>
+    struct SystemModelSE2
+    {
+        static_assert(std::is_floating_point_v<floatT>);
+        struct dim
+        {
+            static constexpr long state = 3, control = 3, obs = 3;
+        };
+
+        using FloatT = floatT;
+        using StateT = StateSE2<FloatT>;
+        using ControlT = ControlSE2<FloatT>;
+        using ObsT = Eigen::Matrix<FloatT, dim::obs, 1>;
+        using ControlNoiseT = Eigen::
+            Matrix<FloatT, dim::control, 1>; // todo: correct name? Is it the same as ControlT?
+        using SigmaPointsT = Eigen::Matrix<FloatT, dim::state, 1>; // todo: rename
+
+        static ObsT observationFunction(const StateT& state);
+
+        static StateT propagationFunction(const StateT& state,
+                                          const ControlT& control,
+                                          const ControlNoiseT& noise,
+                                          FloatT dt);
+
+        static StateT retraction(const StateT& state, const SigmaPointsT& sigmaPoints);
+
+        static SigmaPointsT inverseRetraction(const StateT& state1, const StateT& state2);
+    };
+
+    extern template struct SystemModelSE2<float>;
+    extern template struct SystemModelSE2<double>;
+
 } // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
-- 
GitLab


From 537c8b70c1ac3cc09b1a2f70e2fb91009205c58e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Sat, 3 Sep 2022 23:27:27 +0200
Subject: [PATCH 196/324] Add SE2xV system model

---
 .../navigation/human/HumanSystemModel.cpp     | 55 +++++++++++++++++++
 .../navigation/human/HumanSystemModel.h       | 47 ++++++++++++++++
 2 files changed, 102 insertions(+)

diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index 2aabff49..32b18fd1 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -113,4 +113,59 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     template struct SystemModelSE2<float>;
     template struct SystemModelSE2<double>;
 
+
+    // ------------------------------ SE2xV -----------------------------------------
+
+    template <typename floatT>
+    typename SystemModelSE2xV<floatT>::ObsT
+    SystemModelSE2xV<floatT>::observationFunction(const SystemModelSE2xV::StateT& state)
+    {
+        ObsT observation = state.pose.log().coeffs();
+        return observation;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2xV<floatT>::StateT
+    SystemModelSE2xV<floatT>::propagationFunction(const SystemModelSE2xV::StateT& state,
+                                                  const SystemModelSE2xV::ControlT& control,
+                                                  const SystemModelSE2xV::ControlNoiseT& noise,
+                                                  FloatT dt)
+    {
+        StateT new_state;
+        new_state.pose = state.pose.template rplus(state.velocity * dt);
+        new_state.velocity = state.velocity;
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2xV<floatT>::StateT
+    SystemModelSE2xV<floatT>::retraction(const SystemModelSE2xV::StateT& state,
+                                         const SystemModelSE2xV::SigmaPointsT& sigmaPoints)
+    {
+        StateT new_state;
+        manif::SE2Tangent<FloatT> tan;
+        tan.coeffs() << sigmaPoints.segment(0, 3);
+        new_state.pose = state.pose.lplus(tan);
+        tan.coeffs() << sigmaPoints.segment(3, 3);
+        // TODO: this is probably not correct, i.e. there needs to be some interaction between velocity and pose
+        new_state.velocity += tan;
+        return new_state;
+    }
+
+    template <typename floatT>
+    typename SystemModelSE2xV<floatT>::SigmaPointsT
+    SystemModelSE2xV<floatT>::inverseRetraction(const SystemModelSE2xV::StateT& state1,
+                                                const SystemModelSE2xV::StateT& state2)
+    {
+        SigmaPointsT sigma;
+        sigma.segment(0, 3) = state2.pose.lminus(state1.pose).coeffs();
+        // TODO: this is probably not correct; probably one cannot subtract two tangent vectors at two different poses
+        //  from each other
+        sigma.segment(3, 3) = (state2.velocity - state1.velocity).coeffs();
+        return sigma;
+    }
+
+    template struct SystemModelSE2xV<float>;
+    template struct SystemModelSE2xV<double>;
+
 } // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
diff --git a/source/armarx/navigation/human/HumanSystemModel.h b/source/armarx/navigation/human/HumanSystemModel.h
index fb0309e1..8cbda525 100644
--- a/source/armarx/navigation/human/HumanSystemModel.h
+++ b/source/armarx/navigation/human/HumanSystemModel.h
@@ -121,4 +121,51 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     extern template struct SystemModelSE2<float>;
     extern template struct SystemModelSE2<double>;
 
+
+    //----------- SE2xV -----------------
+
+    template <typename floatT>
+    struct StateSE2xV
+    {
+        manif::SE2<floatT> pose;
+        typename manif::SE2<floatT>::Tangent velocity;
+    };
+
+    template <typename floatT>
+    struct ControlSE2xV
+    {
+    };
+
+    template <typename floatT>
+    struct SystemModelSE2xV
+    {
+        static_assert(std::is_floating_point_v<floatT>);
+        struct dim
+        {
+            static constexpr long state = 6, control = 0, obs = 3;
+        };
+
+        using FloatT = floatT;
+        using StateT = StateSE2xV<FloatT>;
+        using ControlT = ControlSE2xV<FloatT>;
+        using ObsT = Eigen::Matrix<FloatT, dim::obs, 1>;
+        using ControlNoiseT = Eigen::
+            Matrix<FloatT, dim::control, 1>; // todo: correct name? Is it the same as ControlT?
+        using SigmaPointsT = Eigen::Matrix<FloatT, dim::state, 1>; // todo: rename
+
+        static ObsT observationFunction(const StateT& state);
+
+        static StateT propagationFunction(const StateT& state,
+                                          const ControlT& control,
+                                          const ControlNoiseT& noise,
+                                          FloatT dt);
+
+        static StateT retraction(const StateT& state, const SigmaPointsT& sigmaPoints);
+
+        static SigmaPointsT inverseRetraction(const StateT& state1, const StateT& state2);
+    };
+
+    extern template struct SystemModelSE2xV<float>;
+    extern template struct SystemModelSE2xV<double>;
+
 } // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
-- 
GitLab


From fbdab7b972b3eae9d8ae2cdf70e478e40aef8189 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 16:34:47 +0200
Subject: [PATCH 197/324] fix: stopping controller and returning if trajectory
 is invalid

---
 source/armarx/navigation/server/Navigator.cpp | 1 +
 1 file changed, 1 insertion(+)

diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index db09b85f..b28f8886 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -961,6 +961,7 @@ namespace armarx::navigation::server
         {
             ARMARX_INFO << "Local plan is invalid!";
             srv.executor->stop();
+            return;
         }
 
 
-- 
GitLab


From b7b4b63405c74c55fcbd10f44d9811cdd923e085 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 16:35:19 +0200
Subject: [PATCH 198/324] fix: viso of teb obstacles

---
 source/armarx/navigation/local_planning/TebObstacleManager.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 35d3afb4..8f82f74d 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -87,7 +87,7 @@ namespace armarx::navigation::local_planning
             // visualize proxemic zone if layer is available
             if (visLayer != nullptr)
             {
-                const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 0);
+                const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 10.f-i);
                 const core::Pose pose3d = conv::to3D(proxemicZone.pose);
 
                 visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(visualizationIndex++))
-- 
GitLab


From f51a57b8c77d215f0cf622d0abda4d3ad3eaa1f5 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 16:35:48 +0200
Subject: [PATCH 199/324] teb: checking whether no trajectory is available

---
 .../navigation/local_planning/TimedElasticBands.cpp       | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 91483e74..c67b6256 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,4 +1,5 @@
 #include "TimedElasticBands.h"
+#include <optional>
 
 #include <SimoxUtility/algorithm/apply.hpp>
 #include <SimoxUtility/json/json.hpp>
@@ -124,6 +125,13 @@ namespace armarx::navigation::local_planning
             ARMARX_DEBUG << "Caugth exception while planning: " << e.what();
             return {};
         }
+
+        if(hcp_->getTrajectoryContainer().empty())
+        {
+            ARMARX_VERBOSE << "Did not find any trajectory!";
+            return std::nullopt;
+        }
+
         ARMARX_VERBOSE << "Planned successfully (found " << hcp_->getTrajectoryContainer().size()
                        << " Trajectories)";
 
-- 
GitLab


From ea0be177a6c8d904999b1ef8d7c6f2706a591c34 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 18:27:41 +0200
Subject: [PATCH 200/324] dynamic scene provider: waiting for robot to become
 available

---
 .../components/dynamic_scene_provider/Component.cpp   | 11 ++++++++++-
 1 file changed, 10 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 4a1cd5e8..972cabd8 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -137,7 +137,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
         }
         */
 
-        robot = virtualRobotReaderPlugin->get().getRobot(properties.robot.name);
+        while(true)
+        {
+            robot = virtualRobotReaderPlugin->get().getRobot(properties.robot.name);
+            if(robot != nullptr)
+            {
+                break;
+            }
+
+            Clock::WaitFor(Duration::MilliSeconds(100));
+        }
         ARMARX_CHECK_NOT_NULL(robot);
 
         humanTracker.reset();
-- 
GitLab


From 8c542ff37d0149c7b01b1e4698a5af33ede6cb10 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 18:28:07 +0200
Subject: [PATCH 201/324] human simulator: params

---
 .../components/human_simulator/Component.cpp  | 57 ++++++++++++-------
 .../components/human_simulator/Component.h    |  2 +
 2 files changed, 39 insertions(+), 20 deletions(-)

diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
index c53b89e5..c0e55b1a 100644
--- a/source/armarx/navigation/components/human_simulator/Component.cpp
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -27,6 +27,7 @@
 
 #include <VirtualRobot/Random.h>
 
+#include "ArmarXCore/core/logging/Logging.h"
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
 #include "armarx/navigation/algorithms/Costmap.h"
@@ -74,9 +75,12 @@ namespace armarx::navigation::components::human_simulator
         // def->required(properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
 
         // Add an optionalproperty.
-        def->optional(
-            properties.taskPeriodMs, "p.taskPeriodMs", "");
+        def->optional(properties.taskPeriodMs, "p.taskPeriodMs", "");
         def->optional(properties.nHumans, "p.nHumans", "Number of humans to spawn.");
+        
+        def->optional(properties.humanParams.goalDistanceThreshold, "p.human.goalDistanceThreshold", "");
+        def->optional(properties.humanParams.minLinearVelocity, "p.human.maxLinearVelocity", "");
+        def->optional(properties.humanParams.maxLinearVelocity, "p.human.maxLinearVelocity", "");
 
         return def;
     }
@@ -124,7 +128,7 @@ namespace armarx::navigation::components::human_simulator
         */
 
 
-        /// 
+        ///
 
         //
         //  Costmaps
@@ -132,27 +136,41 @@ namespace armarx::navigation::components::human_simulator
 
         ARMARX_INFO << "Querying costmap";
 
-        const auto timestamp = Clock::Now();
+        const algorithms::Costmap costmap = [&]() -> algorithms::Costmap
+        {
+            while (true)
+            {
+                const auto timestamp = Clock::Now();
+
+                const memory::client::costmap::Reader::Query costmapQuery{
+                    .providerName = "distance_to_obstacle_costmap_provider", // TODO check
+                    .name = "distance_to_obstacles",
+                    .timestamp = timestamp};
 
-        const memory::client::costmap::Reader::Query costmapQuery{
-            .providerName = "distance_to_obstacle_costmap_provider", // TODO check
-            .name = "distance_to_obstacles",
-            .timestamp = timestamp};
+                const memory::client::costmap::Reader::Result costmapResult =
+                    costmapReaderPlugin->get().query(costmapQuery);
 
-        const memory::client::costmap::Reader::Result costmapResult =
-            costmapReaderPlugin->get().query(costmapQuery);
+                // if costmap is not available yet, wait
+                if (costmapResult.status != memory::client::costmap::Reader::Result::Success)
+                {
+                    Clock::WaitFor(Duration::MilliSeconds(100));
+                    continue;
+                }
 
-        ARMARX_CHECK_EQUAL(costmapResult.status, memory::client::costmap::Reader::Result::Success);
+                ARMARX_CHECK_EQUAL(costmapResult.status,
+                                   memory::client::costmap::Reader::Result::Success);
 
-        ARMARX_TRACE;
-        ARMARX_CHECK(costmapResult.costmap.has_value());
-        const auto grid = costmapResult.costmap->getGrid();
+                ARMARX_TRACE;
+                ARMARX_CHECK(costmapResult.costmap.has_value());
+                return costmapResult.costmap.value();
+            };
+        }();
 
-        ///
-        
-        for(std::size_t i = 0; i< properties.nHumans ; i++)
+        /// create humans
+
+        for (std::size_t i = 0; i < properties.nHumans; i++)
         {
-            simulatedHumans.emplace_back(costmapResult.costmap.value());
+            simulatedHumans.emplace_back(costmap);
         }
 
 
@@ -206,7 +224,6 @@ namespace armarx::navigation::components::human_simulator
 
         // ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
 
-     
 
         human::Humans humans;
 
@@ -215,7 +232,7 @@ namespace armarx::navigation::components::human_simulator
             humans.push_back(simulatedHuman.update());
         }
 
-        ARMARX_INFO << "Updating humans.";
+        ARMARX_VERBOSE << "Updating humans.";
         humanWriterPlugin->get().store(humans, getName(), timestamp);
     }
 
diff --git a/source/armarx/navigation/components/human_simulator/Component.h b/source/armarx/navigation/components/human_simulator/Component.h
index 8ee5f54b..52e7aadf 100644
--- a/source/armarx/navigation/components/human_simulator/Component.h
+++ b/source/armarx/navigation/components/human_simulator/Component.h
@@ -125,6 +125,8 @@ namespace armarx::navigation::components::human_simulator
 
 
             std::size_t nHumans = 4;
+
+            human::simulation::SimulatedHumanParams humanParams;
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
-- 
GitLab


From 0dd8a5a01b7672431cc91851fb607a68a1c24969 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 18:28:35 +0200
Subject: [PATCH 202/324] simulated human: params and fix for state machine
 (last state)

---
 .../armarx/navigation/simulation/SimulatedHuman.cpp  | 11 +++++++++--
 source/armarx/navigation/simulation/SimulatedHuman.h | 12 ++++++++----
 2 files changed, 17 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index 56f0d60d..c70ce7a7 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -58,6 +58,7 @@ namespace armarx::navigation::human::simulation
 
                 if ((goal - human_.pose.translation()).norm() < params_.goalDistanceThreshold)
                 {
+                    ARMARX_INFO << "Human reached goal";
                     state_ = State::GoalReached;
                 }
 
@@ -66,7 +67,8 @@ namespace armarx::navigation::human::simulation
             case State::GoalReached:
                 ARMARX_DEBUG << "State:GoalReached";
 
-                state_ = State::GoalReached;
+                // TODO(fabian.reister): simulate "perform action at goal": wait a while until movement is started again.
+                state_ = State::Idle;
                 break;
         }
 
@@ -77,6 +79,8 @@ namespace armarx::navigation::human::simulation
     SimulatedHuman::initialize()
     {
         global_planning::SPFA::Params params;
+        params.linearVelocity = this->params_.maxLinearVelocity;
+
         core::Scene scene;
 
         scene.staticScene.emplace(core::StaticScene{nullptr, std::nullopt});
@@ -84,7 +88,7 @@ namespace armarx::navigation::human::simulation
 
         global_planning::SPFA planner(params, scene);
 
-        const auto start = sampleValidPositionInMap();
+        const auto start = human_.pose;
 
         while (true)
         {
@@ -127,6 +131,8 @@ namespace armarx::navigation::human::simulation
         human_.linearVelocity =
             (wpAfter - wpBefore).head<2>().normalized() * projection.projection.velocity;
 
+        human_.linearVelocity = human_.linearVelocity.normalized() * std::clamp(human_.linearVelocity.norm(), params_.minLinearVelocity, params_.maxLinearVelocity);
+
         human_.detectionTime = updateTime;
     }
 
@@ -170,5 +176,6 @@ namespace armarx::navigation::human::simulation
     SimulatedHuman::SimulatedHuman(const algorithms::Costmap& distanceField, const Params& params) :
         distanceField_(distanceField), params_(params)
     {
+        human_.pose = sampleValidPositionInMap();
     }
 } // namespace armarx::navigation::human::simulation
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.h b/source/armarx/navigation/simulation/SimulatedHuman.h
index 08f8a150..fb96a1d9 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.h
+++ b/source/armarx/navigation/simulation/SimulatedHuman.h
@@ -29,14 +29,18 @@
 namespace armarx::navigation::human::simulation
 {
 
+    struct SimulatedHumanParams
+    {
+        float goalDistanceThreshold = 100;
+
+        float minLinearVelocity = 100;
+        float maxLinearVelocity = 200;
+    };
 
     class SimulatedHuman
     {
     public:
-        struct Params
-        {
-            float goalDistanceThreshold = 100;
-        };
+        using Params = SimulatedHumanParams;
 
         SimulatedHuman(const algorithms::Costmap& distanceField, const Params& params = Params());
 
-- 
GitLab


From 134bb6d0264f622479764d4830899eb35c4a4de7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 18:29:01 +0200
Subject: [PATCH 203/324] arviz introspector: clearing layer once goal is
 reached

---
 .../introspection/ArvizIntrospector.cpp       | 37 +++++++++++++++----
 .../server/introspection/ArvizIntrospector.h  |  4 +-
 2 files changed, 32 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index d4efe2e1..0c0ef228 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -6,6 +6,7 @@
 #include <Eigen/Geometry>
 
 #include <SimoxUtility/algorithm/apply.hpp>
+#include <SimoxUtility/algorithm/get_map_keys_values.h>
 #include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/ColorMap.h>
 #include <SimoxUtility/color/cmaps/colormaps.h>
@@ -45,7 +46,7 @@ namespace armarx::navigation::server
         ARMARX_DEBUG << "ArvizIntrospector::onGlobalPlannerResult";
 
         drawGlobalTrajectory(result.trajectory);
-        arviz.commit(layers);
+        arviz.commit(simox::alg::get_values(layers));
 
 
         visualization.visualize(result.trajectory);
@@ -55,7 +56,7 @@ namespace armarx::navigation::server
     ArvizIntrospector::onLocalPlannerResult(const local_planning::LocalPlannerResult& result)
     {
         drawLocalTrajectory(result.trajectory);
-        arviz.commit(layers);
+        arviz.commit(simox::alg::get_values(layers));
     }
 
     // void
@@ -84,7 +85,7 @@ namespace armarx::navigation::server
 
         visualization.setTarget(goal);
     }
-
+    
     void
     ArvizIntrospector::onGlobalShortestPath(const std::vector<core::Pose>& path)
     {
@@ -143,7 +144,7 @@ namespace armarx::navigation::server
                     .color(cmap.at(tp.velocity / maxVelocity)));
         }
 
-        layers.emplace_back(std::move(layer));
+        layers.emplace(layer.data_.name, std::move(layer));
     }
 
     void
@@ -182,8 +183,8 @@ namespace armarx::navigation::server
                 viz::Sphere("velocity_" + std::to_string(i)).position(pos).radius(50).color(color));
         }
 
-        layers.emplace_back(std::move(layer));
-        layers.emplace_back(std::move(velLayer));
+        layers.emplace(layer.data_.name, std::move(layer));
+        layers.emplace(velLayer.data_.name, std::move(velLayer));
     }
 
     void
@@ -196,7 +197,7 @@ namespace armarx::navigation::server
                               core::Pose(robot->getGlobalPose()) * twist.linear)
                       .color(simox::Color::orange()));
 
-        layers.emplace_back(std::move(layer));
+        layers.emplace(layer.data_.name, std::move(layer));
     }
 
     void
@@ -209,7 +210,7 @@ namespace armarx::navigation::server
                               core::Pose(robot->getGlobalPose()) * twist.linear)
                       .color(simox::Color::green()));
 
-        layers.emplace_back(std::move(layer));
+        layers.emplace(layer.data_.name, std::move(layer));
     }
 
     ArvizIntrospector::ArvizIntrospector(ArvizIntrospector&& other) noexcept :
@@ -220,6 +221,22 @@ namespace armarx::navigation::server
     {
     }
 
+    void ArvizIntrospector::clear()
+    {
+        // clear all layers
+        for(auto& [name, layer]: layers)
+        {
+            layer.markForDeletion();
+        }
+        arviz.commit(simox::alg::get_values(layers));
+        layers.clear();
+
+        // some special internal layers of TEB
+        arviz.commitDeleteLayer("local_planner_obstacles");
+        arviz.commitDeleteLayer("local_planner_velocity");
+        arviz.commitDeleteLayer("local_planner_path_alternatives");
+    }
+
     ArvizIntrospector&
     ArvizIntrospector::operator=(ArvizIntrospector&&) noexcept
     {
@@ -262,11 +279,15 @@ namespace armarx::navigation::server
     void
     ArvizIntrospector::success()
     {
+        clear();
+        
         visualization.success();
     }
     void
     ArvizIntrospector::failure()
     {
+        clear();
+
         visualization.failed();
     }
 
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index c784e0de..a0a5bfc1 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -69,6 +69,8 @@ namespace armarx::navigation::server
         ArvizIntrospector(ArvizIntrospector&& other) noexcept;
         ArvizIntrospector& operator=(ArvizIntrospector&&) noexcept;
 
+        void clear();
+
     private:
         void drawGlobalTrajectory(const core::GlobalTrajectory& trajectory);
         void drawLocalTrajectory(const core::LocalTrajectory& trajectory);
@@ -78,7 +80,7 @@ namespace armarx::navigation::server
         viz::ScopedClient arviz;
         const VirtualRobot::RobotPtr robot;
 
-        std::vector<viz::Layer> layers;
+        std::map<std::string, viz::Layer> layers;
 
         util::Visualization visualization;
     };
-- 
GitLab


From 6c4ae5d315711254bdeb64b2f26087711340738a Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 18:29:31 +0200
Subject: [PATCH 204/324] navigation memory: visu update at 10hz

---
 .../armarx/navigation/components/navigation_memory/Component.h  | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Component.h b/source/armarx/navigation/components/navigation_memory/Component.h
index fcbcb08d..b1bbf3ea 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -101,7 +101,7 @@ namespace armarx::navigation::components::navigation_memory
                 bool visuCostmaps = true;
                 bool visuHumans = true;
                 
-                float visuFrequency = 2;
+                float visuFrequency = 10;
             };
             LocationGraph locationGraph;
         };
-- 
GitLab


From 459ff4655cc42d4729fa59bb18080bacbc4886db Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 19:04:03 +0200
Subject: [PATCH 205/324] nav memory: scoped arviz

---
 source/armarx/navigation/components/navigation_memory/Visu.h | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.h b/source/armarx/navigation/components/navigation_memory/Visu.h
index 123a865d..71c057df 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.h
+++ b/source/armarx/navigation/components/navigation_memory/Visu.h
@@ -25,6 +25,7 @@
 #include <memory>
 #include <vector>
 
+#include "RobotAPI/components/ArViz/Client/ScopedClient.h"
 #include "RobotAPI/libraries/armem/server/wm/memory_definitions.h"
 #include <RobotAPI/components/ArViz/Client/Client.h>
 #include <RobotAPI/libraries/armem/core/forward_declarations.h>
@@ -57,8 +58,7 @@ namespace armarx::navigation::memory
         void drawHumans(std::vector<viz::Layer>& layers, bool enabled);
 
 
-    public:
-        viz::Client arviz;
+        viz::ScopedClient arviz;
 
         const armem::server::wm::CoreSegment& locSegment;
         const armem::server::wm::CoreSegment& graphSegment;
-- 
GitLab


From 5b3d20c10d2c13ee65252da8d9393b1b8919c197 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sun, 4 Sep 2022 19:04:14 +0200
Subject: [PATCH 206/324] fix: human simulator: clearing humans on connect

---
 .../armarx/navigation/components/human_simulator/Component.cpp  | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
index c0e55b1a..3410013c 100644
--- a/source/armarx/navigation/components/human_simulator/Component.cpp
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -168,6 +168,8 @@ namespace armarx::navigation::components::human_simulator
 
         /// create humans
 
+        simulatedHumans.clear();
+
         for (std::size_t i = 0; i < properties.nHumans; i++)
         {
             simulatedHumans.emplace_back(costmap);
-- 
GitLab


From b30861a097a3eda09149745e8c993ec7b6c63273 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Sep 2022 19:17:10 +0200
Subject: [PATCH 207/324] Some kalman filter updates

---
 source/armarx/navigation/human/CMakeLists.txt |  35 +-
 .../human/UnscentedKalmanFilter_impl.cpp      |   3 +
 .../navigation/human/test/manifKalmanTest.cpp | 462 ++++++++++++++++++
 .../human/test/se2KalmanFilterTest.cpp        | 295 +++++++++++
 .../human/test/se2xVkalmanFilterTest.cpp      | 295 +++++++++++
 ...FilterTest.cpp => so2kalmanFilterTest.cpp} |  11 +-
 6 files changed, 1094 insertions(+), 7 deletions(-)
 create mode 100644 source/armarx/navigation/human/test/manifKalmanTest.cpp
 create mode 100644 source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
 create mode 100644 source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
 rename source/armarx/navigation/human/test/{kalmanFilterTest.cpp => so2kalmanFilterTest.cpp} (98%)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index f3b7cc38..2ffaa3d1 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -30,9 +30,9 @@ armarx_add_library(teb_human
 
 find_package(sciplot)
 
-armarx_add_test(kalman_test
+armarx_add_test(so2_kalman_test
     TEST_FILES
-        test/kalmanFilterTest.cpp
+        test/so2kalmanFilterTest.cpp
     DEPENDENCIES
         PUBLIC
             ArmarXCore
@@ -40,6 +40,37 @@ armarx_add_test(kalman_test
             sciplot::sciplot
 )
 
+armarx_add_test(se2_kalman_test
+    TEST_FILES
+        test/se2KalmanFilterTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::teb_human
+            sciplot::sciplot
+)
+
+armarx_add_test(se2xV_kalman_test
+    TEST_FILES
+        test/se2xVkalmanFilterTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::teb_human
+            sciplot::sciplot
+)
+
+armarx_add_test(manif_kalman_test
+    TEST_FILES
+        test/manifKalmanTest.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::teb_human
+            sciplot::sciplot
+)
+
+
 armarx_add_test(se3_kalman_test
     TEST_FILES
         test/UnscentedKalmanFilterTest.cpp
diff --git a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
index 672e487f..168a9e03 100644
--- a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
+++ b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
@@ -7,3 +7,6 @@ template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_sce
                                          kalman_filter::SystemModelSO2xR2<float>>;
 template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
                                          kalman_filter::SystemModelSO2xR2<double>>;
+
+template class UnscentedKalmanFilter<
+    armarx::navigation::components::dynamic_scene_provider::kalman_filter::SystemModelSE2<double>>;
diff --git a/source/armarx/navigation/human/test/manifKalmanTest.cpp b/source/armarx/navigation/human/test/manifKalmanTest.cpp
new file mode 100644
index 00000000..4940ab7c
--- /dev/null
+++ b/source/armarx/navigation/human/test/manifKalmanTest.cpp
@@ -0,0 +1,462 @@
+/**
+ * \file se2_localization_ukfm.cpp
+ *
+ *  Created on: Dec 10, 2018
+ *     \author: artivis
+ *
+ *  ---------------------------------------------------------
+ *  This file is:
+ *  (c) 2021 Jeremie Deray
+ *
+ *  This file is part of `manif`, a C++ template-only library
+ *  for Lie theory targeted at estimation for robotics.
+ *  Manif is:
+ *  (c) 2018 Jeremie Deray @ IRI-UPC, Barcelona
+ *  ---------------------------------------------------------
+ *
+ *  ---------------------------------------------------------
+ *  Demonstration example:
+ *
+ *  2D Robot localization based on fixed beacons.
+ *
+ *  See se3_localization.cpp for the 3D equivalent.
+ *  See se3_sam.cpp for a more advanced example performing smoothing and mapping.
+ *  ---------------------------------------------------------
+ *
+ *  This demo showcases an application of an Unscented Kalman Filter on Manifold,
+ *  based on the paper
+ *  'A Code for Unscented Kalman Filtering on Manifolds (UKF-M)'
+ *  [https://arxiv.org/pdf/2002.00878.pdf], M. Brossard, A. Barrau and S. Bonnabel.
+ *
+ *  The following is an abstract of the example hereafter.
+ *  Please consult the aforemention paper for better UKF-M reference
+ *  and the paper Sola-18, [https://arxiv.org/abs/1812.01537] for general
+ *  Lie group reference.
+ *
+ *
+ *  We consider a robot in the plane surrounded by a small
+ *  number of punctual landmarks or _beacons_.
+ *  The robot receives control actions in the form of axial
+ *  and angular velocities, and is able to measure the location
+ *  of the beacons w.r.t its own reference frame.
+ *
+ *  The robot pose X is in SE(2) and the beacon positions b_k in R^2,
+ *
+ *          | cos th  -sin th   x |
+ *      X = | sin th   cos th   y |  // position and orientation
+ *          |   0        0      1 |
+ *
+ *      b_k = (bx_k, by_k)           // lmk coordinates in world frame
+ *
+ *  The control signal u is a twist in se(2) comprising longitudinal
+ *  velocity v and angular velocity w, with no lateral velocity
+ *  component, integrated over the sampling time dt.
+ *
+ *      u = (v*dt, 0, w*dt)
+ *
+ *  The control is corrupted by additive Gaussian noise u_noise,
+ *  with covariance
+ *
+ *    Q = diagonal(sigma_v^2, sigma_s^2, sigma_w^2).
+ *
+ *  This noise accounts for possible lateral slippage u_s
+ *  through a non-zero value of sigma_s,
+ *
+ *  At the arrival of a control u, the robot pose is updated
+ *  with X <-- X * Exp(u) = X + u.
+ *
+ *  Landmark measurements are of the range and bearing type,
+ *  though they are put in Cartesian form for simplicity.
+ *  Their noise n is zero mean Gaussian, and is specified
+ *  with a covariances matrix R.
+ *  We notice the rigid motion action y = h(X,b) = X^-1 * b
+ *  (see appendix C),
+ *
+ *      y_k = (brx_k, bry_k)       // lmk coordinates in robot frame
+ *
+ *  We consider the beacons b_k situated at known positions.
+ *  We define the pose to estimate as X in SE(2).
+ *  The estimation error dx and its covariance P are expressed
+ *  in the tangent space at X.
+ *
+ *  All these variables are summarized again as follows
+ *
+ *    X   : robot pose, SE(2)
+ *    u   : robot control, (v*dt ; 0 ; w*dt) in se(2)
+ *    Q   : control perturbation covariance
+ *    b_k : k-th landmark position, R^2
+ *    y   : Cartesian landmark measurement in robot frame, R^2
+ *    R   : covariance of the measurement noise
+ *
+ *  The motion and measurement models are
+ *
+ *    X_(t+1) = f(X_t, u) = X_t * Exp ( w )     // motion equation
+ *    y_k     = h(X, b_k) = X^-1 * b_k          // measurement equation
+ *
+ *  The algorithm below comprises first a simulator to
+ *  produce measurements, then uses these measurements
+ *  to estimate the state, using a Lie-based error-state Kalman filter.
+ *
+ *  This file has plain code with only one main() function.
+ *  There are no function calls other than those involving `manif`.
+ *
+ *  Printing simulated state and estimated state together
+ *  with an unfiltered state (i.e. without Kalman corrections)
+ *  allows for evaluating the quality of the estimates.
+ */
+
+#include <iomanip>
+#include <iostream>
+#include <tuple>
+#include <vector>
+
+#include <Eigen/Cholesky>
+
+#include "manif/SE2.h"
+#include <sciplot/sciplot.hpp>
+
+using std::cout;
+using std::endl;
+
+using namespace Eigen;
+
+typedef Array<double, 2, 1> Array2d;
+typedef Array<double, 3, 1> Array3d;
+
+template <typename Scalar>
+struct Weights
+{
+    Weights() = default;
+    ~Weights() = default;
+
+    Weights(const Scalar l, const Scalar alpha)
+    {
+        using std::sqrt;
+
+        const Scalar m = (alpha * alpha - 1) * l;
+        const Scalar ml = m + l;
+
+        sqrt_d_lambda = sqrt(ml);
+        wj = Scalar(1) / (Scalar(2) * (ml));
+        wm = m / (ml);
+        w0 = m / (ml) + Scalar(3) - alpha * alpha;
+    }
+
+    Scalar sqrt_d_lambda;
+    Scalar wj;
+    Scalar wm;
+    Scalar w0;
+};
+
+using Weightsd = Weights<double>;
+
+template <typename Scalar>
+std::tuple<Weights<Scalar>, Weights<Scalar>, Weights<Scalar>>
+compute_sigma_weights(const Scalar state_size,
+                      const Scalar propagation_noise_size,
+                      const Scalar alpha_0,
+                      const Scalar alpha_1,
+                      const Scalar alpha_2)
+{
+    assert(state_size > 0);
+    assert(propagation_noise_size > 0);
+    assert(alpha_0 >= 1e-3 && alpha_0 <= 1);
+    assert(alpha_1 >= 1e-3 && alpha_1 <= 1);
+    assert(alpha_2 >= 1e-3 && alpha_2 <= 1);
+
+    return std::make_tuple(Weights<Scalar>(state_size, alpha_0),
+                           Weights<Scalar>(propagation_noise_size, alpha_1),
+                           Weights<Scalar>(state_size, alpha_2));
+}
+
+int
+main()
+{
+    std::srand((unsigned int)time(0));
+
+    // START CONFIGURATION
+    //
+    //
+    const int NUMBER_OF_LMKS_TO_MEASURE = 3;
+    constexpr int DoF = manif::SE2d::DoF;
+    constexpr int SystemNoiseSize = manif::SE2d::DoF;
+    // Measurement Dim
+    constexpr int Rp = 2;
+
+    // Define the robot pose element and its covariance
+    manif::SE2d X = manif::SE2d::Identity(), X_simulation = manif::SE2d::Identity(),
+                X_unfiltered = manif::SE2d::Identity();
+    Matrix3d P = Matrix3d::Identity() * 1e-6;
+
+    // Define a control vector and its noise and covariance
+    manif::SE2Tangentd u_simu, u_est, u_unfilt;
+    Vector3d u_nom, u_noisy, u_noise;
+    Array3d u_sigmas;
+    Matrix3d U, Uchol;
+
+    u_nom << 0.1, 0.0, 0.05;
+    u_sigmas << 0.1, 0.1, 0.1;
+    U = (u_sigmas * u_sigmas).matrix().asDiagonal();
+    Uchol = U.llt().matrixL();
+
+    // Define three landmarks in R^2
+    Eigen::Vector2d b;
+    const std::vector<Eigen::Vector2d> landmarks{
+        Eigen::Vector2d(2.0, 0.0), Eigen::Vector2d(2.0, 1.0), Eigen::Vector2d(2.0, -1.0)};
+
+    // Define the beacon's measurements
+    Vector2d y, y_bar, y_noise;
+    Matrix<double, Rp, 2 * DoF> yj;
+    Array2d y_sigmas;
+    Matrix2d R;
+    std::vector<Vector2d> measurements(landmarks.size());
+
+    y_sigmas << 0.01, 0.01;
+    R = (y_sigmas * y_sigmas).matrix().asDiagonal();
+
+
+    // Declare UFK variables
+    Array3d alpha;
+    alpha << 1e-3, 1e-3, 1e-3;
+
+    Weightsd w_d, w_q, w_u;
+    std::tie(w_d, w_q, w_u) = compute_sigma_weights<double>(DoF, Rp, alpha(0), alpha(1), alpha(2));
+
+    // Declare some temporaries
+
+    manif::SE2d X_new;
+    Matrix3d P_new;
+    manif::SE2d s_j_p, s_j_m;
+    Vector3d xi_mean;
+    Vector3d w_p, w_m;
+
+    Matrix2d P_yy;
+    Matrix<double, DoF, 2 * DoF> xij;
+    Matrix<double, DoF, 2> P_xiy;
+
+    Vector2d e, z; // expectation, innovation
+    Matrix<double, 3, 2> K; // Kalman gain
+    manif::SE2Tangentd dx; // optimal update step, or error-state
+
+    Matrix<double, DoF, DoF> xis;
+    Matrix<double, DoF, DoF * 2> xis_new;
+    Matrix<double, DoF, SystemNoiseSize * 2> xis_new2;
+
+    //
+    //
+    // CONFIGURATION DONE
+
+
+    // DEBUG
+    cout << std::fixed << std::setprecision(4) << std::showpos << endl;
+    cout << "X STATE     :    X      Y    THETA" << endl;
+    cout << "----------------------------------" << endl;
+    cout << "X initial   : " << X_simulation.log().coeffs().transpose() << endl;
+    cout << "----------------------------------" << endl;
+    // END DEBUG
+
+
+    std::vector<double> X_simulated_x, X_simulated_y, X_simulated_theta;
+    std::vector<double> X_estimated_x, X_estimated_y, X_estimated_theta;
+    std::vector<double> X_unfiltered_x, X_unfiltered_y, X_unfiltered_theta;
+
+    // START TEMPORAL LOOP
+    //
+    //
+
+    // Make 10 steps. Measure up to three landmarks each time.
+    for (int t = 0; t < 10; t++)
+    {
+        //// I. Simulation ###############################################################################
+
+        /// simulate noise
+        u_noise = u_sigmas * Array3d::Random(); // control noise
+        u_noisy = u_nom + u_noise; // noisy control
+
+        u_simu = u_nom;
+        u_est = u_noisy;
+        u_unfilt = u_noisy;
+
+        /// first we move - - - - - - - - - - - - - - - - - - - - - - - - - - - -
+        X_simulation = X_simulation + u_simu; // overloaded X.rplus(u) = X * exp(u)
+
+        /// then we measure all landmarks - - - - - - - - - - - - - - - - - - - -
+        for (std::size_t i = 0; i < landmarks.size(); i++)
+        {
+            b = landmarks[i]; // lmk coordinates in world frame
+
+            /// simulate noise
+            y_noise = y_sigmas * Array2d::Random(); // measurement noise
+
+            y = X_simulation.inverse().act(b); // landmark measurement, before adding noise
+            y = y + y_noise; // landmark measurement, noisy
+            measurements[i] = y; // store for the estimator just below
+        }
+
+
+        //// II. Estimation ###############################################################################
+
+        /// First we move - - - - - - - - - - - - - - - - - - - - - - - - - - - -
+
+        X_new = X + u_est; // X * exp(u)
+
+        // set sigma points
+        xis = w_d.sqrt_d_lambda * P.llt().matrixL().toDenseMatrix();
+
+        // sigma points on manifold
+        for (int i = 0; i < DoF; ++i)
+        {
+            s_j_p = X + manif::SE2Tangentd(xis.col(i));
+            s_j_m = X + manif::SE2Tangentd(-xis.col(i));
+
+            xis_new.col(i) = (X_new.lminus(s_j_p + u_est)).coeffs();
+            xis_new.col(i + DoF) = (X_new.lminus(s_j_m + u_est)).coeffs();
+        }
+
+        // compute covariance
+        xi_mean = w_d.wj * xis_new.rowwise().sum();
+        xis_new.colwise() -= xi_mean;
+
+        P_new = w_d.wj * xis_new * xis_new.transpose() + w_d.w0 * xi_mean * xi_mean.transpose();
+
+        // sigma points on manifold
+        for (int i = 0; i < SystemNoiseSize; ++i)
+        {
+            w_p = w_q.sqrt_d_lambda * Uchol.col(i);
+            w_m = -w_q.sqrt_d_lambda * Uchol.col(i);
+
+            xis_new2.col(i) = (X_new.lminus(X + (u_est + w_p))).coeffs();
+            xis_new2.col(i + SystemNoiseSize) = (X_new.lminus(X + (u_est + w_m))).coeffs();
+        }
+
+        xi_mean = w_q.wj * xis_new2.rowwise().sum();
+        xis_new2.colwise() -= xi_mean;
+
+        U = w_q.wj * xis_new2 * xis_new2.transpose() + w_q.w0 * xi_mean * xi_mean.transpose();
+
+        P = P_new + U;
+
+        X = X_new;
+
+        /// Then we correct using the measurements of each lmk - - - - - - - - -
+        for (int i = 0; i < NUMBER_OF_LMKS_TO_MEASURE; i++)
+        {
+            // landmark
+            b = landmarks[i]; // lmk coordinates in world frame
+
+            // measurement
+            y = measurements[i]; // lmk measurement, noisy
+
+            // expectation
+            e = X.inverse().act(b);
+
+            // set sigma points
+            xis = w_u.sqrt_d_lambda * P.llt().matrixL().toDenseMatrix();
+
+            // compute measurement sigma points
+            for (int d = 0; d < DoF; ++d)
+            {
+                s_j_p = X + manif::SE2Tangentd(xis.col(d));
+                s_j_m = X + manif::SE2Tangentd(-xis.col(d));
+
+                yj.col(d) = s_j_p.inverse().act(b);
+                yj.col(d + DoF) = s_j_m.inverse().act(b);
+            }
+
+            // measurement mean
+            y_bar = w_u.wm * e + w_u.wj * yj.rowwise().sum();
+
+            yj.colwise() -= y_bar;
+            e -= y_bar;
+
+            // compute covariance and cross covariance matrices
+            P_yy = w_u.w0 * e * e.transpose() + w_u.wj * yj * yj.transpose() + R;
+
+            xij << xis, -xis;
+            P_xiy = w_u.wj * xij * yj.transpose();
+
+            // Kalman gain
+            K = P_yy.colPivHouseholderQr().solve(P_xiy.transpose()).transpose();
+
+            // innovation
+            z = y - y_bar;
+
+            // Correction step
+            dx = K * z; // dx is in the tangent space at X
+
+            // Update
+            X = X + dx; // overloaded X.rplus(dx) = X * exp(dx)
+            P = P - K * P_yy * K.transpose();
+        }
+
+
+        //// III. Unfiltered ##############################################################################
+
+        // move also an unfiltered version for comparison purposes
+        X_unfiltered = X_unfiltered + u_unfilt;
+
+
+        //// IV. Results ##############################################################################
+
+        // DEBUG
+        cout << "X simulated : " << X_simulation.log().coeffs().transpose() << "\n";
+        cout << "X estimated : " << X.log().coeffs().transpose() << "\n";
+        cout << "X unfilterd : " << X_unfiltered.log().coeffs().transpose() << "\n";
+        cout << "----------------------------------" << endl;
+
+        const auto& X_simu = X_simulation.log().coeffs().transpose();
+        const auto& X_est = X.log().coeffs().transpose();
+        const auto& X_unf = X_unfiltered.log().coeffs().transpose();
+        X_simulated_x.push_back(X_simu(0));
+        X_simulated_y.push_back(X_simu(1));
+        X_simulated_theta.push_back(X_simu(2));
+        X_estimated_x.push_back(X_est(0));
+        X_estimated_y.push_back(X_est(1));
+        X_estimated_theta.push_back(X_est(2));
+        X_unfiltered_x.push_back(X_unf(0));
+        X_unfiltered_y.push_back(X_unf(1));
+        X_unfiltered_theta.push_back(X_unf(2));
+        // END DEBUG
+    }
+
+    sciplot::Plot2D pos_plot;
+    pos_plot.xlabel("x");
+    pos_plot.ylabel("y");
+    pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+    pos_plot.xrange("*", "*").yrange("*", "*");
+
+    pos_plot.drawCurve(X_simulated_x, X_simulated_y).label("Simulated");
+    pos_plot.drawCurve(X_estimated_x, X_estimated_y).label("Estimated");
+    pos_plot.drawCurve(X_unfiltered_x, X_unfiltered_y).label("Unfiltered");
+
+
+    sciplot::Plot2D orientation_plot;
+    orientation_plot.xlabel("t");
+    orientation_plot.ylabel("rot");
+    orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+    orientation_plot.xrange("*", "*").yrange("*", "*");
+
+    sciplot::Vec x = sciplot::linspace(0.0, 1.0, X_estimated_theta.size());
+    orientation_plot.drawCurve(x, X_simulated_theta).label("Simulated");
+    orientation_plot.drawCurve(x, X_estimated_theta).label("Estimated");
+    orientation_plot.drawCurve(x, X_unfiltered_theta).label("Unfiltered");
+
+    // Create figure to hold plot
+    sciplot::Figure fig = {{pos_plot, orientation_plot}};
+    // Create canvas to hold figure
+    sciplot::Canvas canvas = {{fig}};
+    canvas.size(1000, 500);
+
+    // Show the plot in a pop-up window
+    canvas.show();
+
+    // Save the plot to a PDF file
+    canvas.save("manif_kalman_output.pdf");
+
+
+    //
+    //
+    // END OF TEMPORAL LOOP. DONE.
+
+    return 0;
+}
diff --git a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
new file mode 100644
index 00000000..61d37530
--- /dev/null
+++ b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
@@ -0,0 +1,295 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
+#define ARMARX_BOOST_TEST
+
+#include <cstdlib> /* srand, rand */
+#include <ctime> /* time */
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/util/time.h>
+
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
+
+#include <armarx/navigation/Test.h>
+#include <armarx/navigation/human/HumanSystemModel.h>
+#include <manif/SO2.h>
+#include <sciplot/sciplot.hpp>
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+    using T = double; //TODO double or float?
+    using Vector = Eigen::Matrix<T, 2, 1>;
+    using SystemModelT = kalman_filter::SystemModelSE2<T>;
+
+    constexpr T RAD = 1;
+    constexpr long num_timesteps = 3000;
+    constexpr T max_time = 1;
+    constexpr T dt = max_time / num_timesteps;
+    constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
+
+    constexpr T rot_noise_std = 0.1;
+    constexpr T pos_noise_std = 0.1;
+    constexpr T obs_rot_noise_std = 0.1;
+    constexpr T obs_pos_noise_std = 0.1;
+    constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
+    const Vector initial_offet_pos = 0.4 * RAD * Vector(1, 0.5);
+
+
+    void
+    simulate_trajectory(std::vector<SystemModelT::StateT>& states,
+                        std::vector<SystemModelT::ControlT>& omegas)
+    {
+        constexpr T startAngle = 0;
+
+        SystemModelT::StateT state;
+        state.pose = manif::SE2<T>(RAD, 0, startAngle);
+        states.push_back(state);
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            const T t = dt * i;
+            const T angle = t * c;
+
+            const Vector last_pos = states.at(i - 1).pose.translation();
+            //const Vector pos(angle, std::cos(angle));
+            const Vector pos = RAD * Vector(std::cos(angle), std::sin(angle));
+
+            BOOST_TEST(((last_pos - pos).norm() < 0.1 * RAD),
+                       "position differs too much from last step: " << (last_pos - pos).norm());
+
+            Eigen::Vector2d euclidean_velocity = Eigen::Vector2d{0, c};
+            SystemModelT::ControlT control;
+            //control.velocity.coeffs() << (pos - last_pos) / dt, c;
+            control.velocity.coeffs() << euclidean_velocity, c;
+
+            const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
+                state, control, SystemModelT::ControlNoiseT::Zero(), dt);
+
+            state.pose = manif::SE2<T>(pos.x(), pos.y(), angle + startAngle);
+
+            T pos_diff = (propagated.pose.translation() - state.pose.translation()).norm();
+            BOOST_TEST(pos_diff < 2e-10,
+                       "propagated position differs too much from real position: " << pos_diff);
+
+            T rot_diff = propagated.pose.angle() - state.pose.angle();
+            BOOST_TEST(rot_diff < 2e-10,
+                       "propagated rotation differs too much from real orientation: " << rot_diff);
+
+            states.push_back(propagated);
+
+
+            // add noise
+            control.velocity.coeffs().segment(0, 2) += pos_noise_std * Vector::Random();
+            control.velocity.coeffs().segment(2, 1) +=
+                rot_noise_std * Eigen::Matrix<T, 1, 1>::Random();
+            omegas.push_back(control);
+        }
+    }
+
+    void
+    simulate_observation(const std::vector<SystemModelT::StateT>& states,
+                         std::vector<SystemModelT::ObsT>& observations)
+    {
+        for (const auto& state : states)
+        {
+            SystemModelT::ObsT obs = SystemModelT::observationFunction(state);
+
+            SystemModelT::ObsT noise = SystemModelT::ObsT::Random();
+            noise.segment(0, 2) *= obs_pos_noise_std;
+            noise.segment(2, 1) *= obs_rot_noise_std;
+
+            BOOST_TEST_MESSAGE("SALT TEST: noise " << noise);
+
+            observations.push_back(obs + noise);
+
+            BOOST_TEST_MESSAGE("SALT TEST: state:\n"
+                               << state.pose.x() << "\n"
+                               << state.pose.y() << "\n"
+                               << state.pose.angle());
+
+            BOOST_TEST_MESSAGE("SALT TEST: state.log:\n" << state.pose.log().coeffs());
+
+            BOOST_TEST_MESSAGE("SALT TEST: noisy obs:\n" << (obs + noise));
+
+            SystemModelT::ObsT diff =
+                (obs + noise) -
+                SystemModelT::ObsT(state.pose.x(), state.pose.y(), state.pose.angle());
+
+            BOOST_TEST_MESSAGE("\nSALT TEST: diff:\n" << diff);
+        }
+    }
+
+
+    BOOST_AUTO_TEST_CASE(se2KalmanFilterTest)
+    {
+        srand(time(NULL));
+
+        std::vector<SystemModelT::StateT> states;
+        std::vector<SystemModelT::ControlT> omegas;
+        std::vector<SystemModelT::ObsT> observations;
+        simulate_trajectory(states, omegas);
+        simulate_observation(states, observations);
+
+        ARMARX_INFO << "Num States: " << states.size() << " Num Controls: " << omegas.size()
+                    << " Num Obs: " << observations.size();
+
+        UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+            UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+        Q.block<2, 2>(0, 0) *= pos_noise_std * pos_noise_std;
+        Q.block<1, 1>(2, 2) *= rot_noise_std * rot_noise_std;
+
+        UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity();
+        R.block<2, 2>(0, 0) *= obs_pos_noise_std * obs_pos_noise_std;
+        R.block<1, 1>(2, 2) *= obs_rot_noise_std * obs_rot_noise_std;
+
+        UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+            UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+        P0.block<2, 2>(0, 0) *= initial_offet_pos.norm() * initial_offet_pos.norm();
+        P0.block<1, 1>(2, 2) *= initial_offset_angle * initial_offset_angle;
+
+        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha;
+        alpha(0) = 0.5; //0.8; // state
+        alpha(1) = 0.5; //0.1; // control
+        alpha(2) = 0.5; //0.1; // update
+
+        SystemModelT::StateT state0;
+        const Vector startPos = states.at(0).pose.translation() + initial_offet_pos;
+        state0.pose = manif::SE2<T>{
+            startPos.x(), startPos.y(), states.at(0).pose.angle() + initial_offset_angle};
+
+        UnscentedKalmanFilter<SystemModelT> ukf(Q, R, alpha, state0, P0);
+
+        std::vector<SystemModelT::StateT> ukf_states;
+        std::vector<UnscentedKalmanFilter<SystemModelT>::StateCovT> ukf_Ps;
+        ukf_states.push_back(state0);
+        ukf_Ps.push_back(P0);
+
+        std::vector<T> x_true, y_true, x_obs, y_obs, x_ukf, y_ukf;
+        std::vector<T> a_true, a_obs, a_ukf;
+        std::vector<T> x_ukf_full, y_ukf_full, a_ukf_full;
+        std::vector<T> ukf_pos_var, ukf_rot_var, ukf_var;
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            // propagate
+            TIMING_START(LOOP);
+            TIMING_START(PROPAGATION);
+            ukf.propagation(omegas.at(i - 1), dt);
+            TIMING_END(PROPAGATION);
+            if ((i - 1) % 50 == 0)
+            {
+                TIMING_START(UPDATE);
+                ukf.update(observations.at(i));
+                TIMING_END(UPDATE);
+                TIMING_START(REST);
+
+                BOOST_TEST_MESSAGE("Max Cov "
+                                   << ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+                BOOST_TEST_MESSAGE("Diag: " << (ukf.getCurrentStateCovariance() -
+                                                Eigen::Matrix<T, 3, 3>::Identity())
+                                                   .norm());
+
+                x_obs.push_back(observations.at(i)(0));
+                y_obs.push_back(observations.at(i)(1));
+                a_obs.push_back(observations.at(i)(2));
+
+                x_ukf.push_back(ukf.getCurrentState().pose.x());
+                y_ukf.push_back(ukf.getCurrentState().pose.y());
+                a_ukf.push_back(ukf.getCurrentState().pose.angle());
+
+                TIMING_END(REST);
+            }
+            x_true.push_back(states.at(i).pose.x());
+            y_true.push_back(states.at(i).pose.y());
+            a_true.push_back(states.at(i).pose.angle());
+
+            x_ukf_full.push_back(ukf.getCurrentState().pose.x());
+            y_ukf_full.push_back(ukf.getCurrentState().pose.y());
+            a_ukf_full.push_back(ukf.getCurrentState().pose.angle());
+
+            ukf_states.push_back(ukf.getCurrentState());
+            ukf_Ps.push_back(ukf.getCurrentStateCovariance());
+
+            ukf_pos_var.push_back(
+                ukf.getCurrentStateCovariance().block<2, 2>(0, 0).cwiseAbs().maxCoeff());
+            ukf_rot_var.push_back(
+                ukf.getCurrentStateCovariance().block<1, 1>(2, 2).cwiseAbs().maxCoeff());
+            ukf_var.push_back(ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+
+            TIMING_END(LOOP);
+        }
+
+        sciplot::Plot2D pos_plot;
+        pos_plot.xlabel("x");
+        pos_plot.ylabel("y");
+        pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        pos_plot.xrange(-RAD * 1.1, RAD * 1.1).yrange(-RAD * 1.1, RAD * 1.1);
+        //pos_plot.xrange(-4, 4).yrange(-4, 4);
+
+        pos_plot.drawCurve(x_true, y_true).label("True");
+        pos_plot.drawCurve(x_obs, y_obs).label("Obs");
+        pos_plot.drawCurveWithPoints(x_ukf, y_ukf).label("UKF");
+        pos_plot.drawCurve(x_ukf_full, y_ukf_full).label("Full UKF");
+
+
+        sciplot::Plot2D orientation_plot;
+        orientation_plot.xlabel("x");
+        orientation_plot.ylabel("y");
+        orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        orientation_plot.xrange(-0.1, 1.1).yrange(-4, 4);
+
+        sciplot::Vec x = sciplot::linspace(0.0, 1.0, a_obs.size());
+        sciplot::Vec x_t = sciplot::linspace(0.0, 1.0, a_true.size());
+        orientation_plot.drawCurve(x_t, a_true).label("True").lineWidth(1);
+        orientation_plot.drawCurve(x, a_obs).label("Obs").lineWidth(1);
+        orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
+        orientation_plot.drawCurve(x_t, a_ukf_full).label("Full UKF").lineWidth(1);
+
+
+        sciplot::Plot2D error_plot;
+        error_plot.xlabel("x");
+        error_plot.ylabel("y");
+        error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        error_plot.xrange(-0.1, 1.1).yrange("*", "*");
+
+        error_plot.drawCurve(x_t, ukf_pos_var).label("Pos variance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_rot_var).label("Rot variance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_var).label("Total variance").lineWidth(1);
+
+
+        // Create figure to hold plot
+        sciplot::Figure fig = {{pos_plot, orientation_plot}, {error_plot}};
+        // Create canvas to hold figure
+        sciplot::Canvas canvas = {{fig}};
+        canvas.size(1000, 1000);
+
+        // Show the plot in a pop-up window
+        canvas.show();
+
+        // Save the plot to a PDF file
+        canvas.save("se2_kalman_output.pdf");
+    }
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
new file mode 100644
index 00000000..5187e87a
--- /dev/null
+++ b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
@@ -0,0 +1,295 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
+#define ARMARX_BOOST_TEST
+
+#include <cstdlib> /* srand, rand */
+#include <ctime> /* time */
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/util/time.h>
+
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
+
+#include <armarx/navigation/Test.h>
+#include <armarx/navigation/human/HumanSystemModel.h>
+#include <manif/SO2.h>
+#include <sciplot/sciplot.hpp>
+
+namespace armarx::navigation::components::dynamic_scene_provider
+{
+    using T = double; //TODO double or float?
+    using Vector = Eigen::Matrix<T, 2, 1>;
+    using SystemModelT = kalman_filter::SystemModelSE2xV<T>;
+
+    constexpr T RAD = 1;
+    constexpr long num_timesteps = 3000;
+    constexpr T max_time = 1;
+    constexpr T dt = max_time / num_timesteps;
+    constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
+
+    constexpr T obs_rot_noise_std = 0.01;
+    constexpr T obs_pos_noise_std = 0.01;
+    constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
+    const Vector initial_offet_pos = 0.8 * RAD * Vector(1, 0.5);
+    const Vector initial_offet_vel = 0.8 * RAD * Vector(1, 0.5);
+
+
+    void
+    simulate_trajectory(std::vector<SystemModelT::StateT>& states)
+    {
+        constexpr T startAngle = 0;
+
+        SystemModelT::StateT state;
+        state.pose = manif::SE2<T>(RAD, 0, startAngle);
+        state.velocity = manif::SE2Tangent<T>(0, c, c);
+        states.push_back(state);
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            const T t = dt * i;
+            const T angle = t * c;
+
+            const Vector last_pos = states.at(i - 1).pose.translation();
+            //const Vector pos(angle, std::cos(angle));
+            const Vector pos = RAD * Vector(std::cos(angle), std::sin(angle));
+
+            BOOST_TEST(((last_pos - pos).norm() < 0.1 * RAD),
+                       "position differs too much from last step: " << (last_pos - pos).norm());
+
+            SystemModelT::ControlT control;
+
+            const SystemModelT::StateT propagated = SystemModelT::propagationFunction(
+                state, control, SystemModelT::ControlNoiseT::Zero(), dt);
+
+            state.pose = manif::SE2<T>(pos.x(), pos.y(), angle + startAngle);
+            state.velocity = manif::SE2Tangent<T>(0, c, c);
+
+            T pos_diff = (propagated.pose.translation() - state.pose.translation()).norm();
+            BOOST_TEST(pos_diff < 2e-10,
+                       "propagated position differs too much from real position: " << pos_diff);
+
+            T rot_diff = propagated.pose.angle() - state.pose.angle();
+            BOOST_TEST(rot_diff < 2e-10,
+                       "propagated rotation differs too much from real orientation: " << rot_diff);
+
+            T vel_diff = (propagated.velocity.coeffs() - state.velocity.coeffs()).norm();
+            BOOST_TEST(vel_diff < 2e-10,
+                       "propagated velocity differs too much from real velocity: " << vel_diff);
+
+            states.push_back(state);
+        }
+    }
+
+    void
+    simulate_observation(const std::vector<SystemModelT::StateT>& states,
+                         std::vector<SystemModelT::ObsT>& observations)
+    {
+        for (const auto& state : states)
+        {
+            SystemModelT::ObsT obs = SystemModelT::observationFunction(state);
+
+            SystemModelT::ObsT noise = SystemModelT::ObsT::Random();
+            noise.segment(0, 2) *= obs_pos_noise_std;
+            noise.segment(2, 1) *= obs_rot_noise_std;
+
+            observations.push_back(obs + noise);
+        }
+    }
+
+
+    BOOST_AUTO_TEST_CASE(se2xVkalmanFilterTest)
+    {
+        srand(time(NULL));
+
+        std::vector<SystemModelT::StateT> states;
+        std::vector<SystemModelT::ObsT> observations;
+        simulate_trajectory(states);
+        simulate_observation(states, observations);
+
+        ARMARX_INFO << "Num States: " << states.size() << " Num Obs: " << observations.size();
+
+        UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+            UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+
+        UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity();
+        R.block<2, 2>(0, 0) *= obs_pos_noise_std * obs_pos_noise_std;
+        R.block<1, 1>(2, 2) *= obs_rot_noise_std * obs_rot_noise_std;
+
+        UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+            UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+        P0.block<2, 2>(0, 0) *= initial_offet_pos.norm() * initial_offet_pos.norm();
+        P0.block<1, 1>(2, 2) *= initial_offset_angle * initial_offset_angle;
+        P0.block<3, 3>(3, 3) *= initial_offet_vel.norm() * initial_offet_vel.norm();
+
+        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha;
+        alpha(0) = 0.001; // state
+        alpha(1) = 0.001; // control
+        alpha(2) = 0.001; // update
+
+        SystemModelT::StateT state0;
+        const Vector startPos = states.at(0).pose.translation() + initial_offet_pos;
+        state0.pose = manif::SE2<T>{
+            startPos.x(), startPos.y(), states.at(0).pose.angle() + initial_offset_angle};
+        state0.velocity = states.at(0).velocity + initial_offet_vel;
+
+        UnscentedKalmanFilter<SystemModelT> ukf(Q, R, alpha, state0, P0);
+
+        std::vector<SystemModelT::StateT> ukf_states;
+        std::vector<UnscentedKalmanFilter<SystemModelT>::StateCovT> ukf_Ps;
+        ukf_states.push_back(state0);
+        ukf_Ps.push_back(P0);
+
+        std::vector<T> x_true, y_true, x_obs, y_obs, x_ukf, y_ukf;
+        std::vector<T> a_true, a_obs, a_ukf;
+        std::vector<T> vel_x_true, vel_y_true, vel_a_true;
+        std::vector<T> vel_x_ukf_full, vel_y_ukf_full, vel_a_ukf_full;
+        std::vector<T> x_ukf_full, y_ukf_full, a_ukf_full;
+        std::vector<T> ukf_pos_var, ukf_rot_var, ukf_var;
+
+        for (int i = 1; i < num_timesteps; i++)
+        {
+            // propagate
+            TIMING_START(LOOP);
+            TIMING_START(PROPAGATION);
+            ukf.propagation(SystemModelT::ControlT{}, dt);
+            TIMING_END(PROPAGATION);
+            if ((i - 1) % 5 == 0)
+            {
+                TIMING_START(UPDATE);
+                ukf.update(observations.at(i));
+                TIMING_END(UPDATE);
+                TIMING_START(REST);
+                const SystemModelT::StateT& current_state = ukf.getCurrentState();
+
+                BOOST_TEST_MESSAGE("Max Cov "
+                                   << ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+                BOOST_TEST_MESSAGE("Diag: " << (ukf.getCurrentStateCovariance() -
+                                                Eigen::Matrix<T, 3, 3>::Identity())
+                                                   .norm());
+
+                x_obs.push_back(observations.at(i)(0));
+                y_obs.push_back(observations.at(i)(1));
+                a_obs.push_back(observations.at(i)(2));
+
+                x_ukf.push_back(ukf.getCurrentState().pose.x());
+                y_ukf.push_back(ukf.getCurrentState().pose.y());
+                a_ukf.push_back(ukf.getCurrentState().pose.angle());
+
+                TIMING_END(REST);
+            }
+
+            x_true.push_back(states.at(i).pose.x());
+            y_true.push_back(states.at(i).pose.y());
+            a_true.push_back(states.at(i).pose.angle());
+
+            vel_x_true.push_back(states.at(i).velocity.x());
+            vel_y_true.push_back(states.at(i).velocity.y());
+            vel_a_true.push_back(states.at(i).velocity.angle());
+
+            x_ukf_full.push_back(ukf.getCurrentState().pose.x());
+            y_ukf_full.push_back(ukf.getCurrentState().pose.y());
+            a_ukf_full.push_back(ukf.getCurrentState().pose.angle());
+
+            vel_x_ukf_full.push_back(ukf.getCurrentState().velocity.x());
+            vel_y_ukf_full.push_back(ukf.getCurrentState().velocity.y());
+            vel_a_ukf_full.push_back(ukf.getCurrentState().velocity.angle());
+
+            ukf_states.push_back(ukf.getCurrentState());
+            ukf_Ps.push_back(ukf.getCurrentStateCovariance());
+
+            ukf_pos_var.push_back(
+                ukf.getCurrentStateCovariance().block<2, 2>(0, 0).cwiseAbs().maxCoeff());
+            ukf_rot_var.push_back(
+                ukf.getCurrentStateCovariance().block<1, 1>(2, 2).cwiseAbs().maxCoeff());
+            ukf_var.push_back(ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
+
+            TIMING_END(LOOP);
+        }
+
+        sciplot::Plot2D pos_plot;
+        pos_plot.xlabel("x");
+        pos_plot.ylabel("y");
+        pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        pos_plot.xrange(-RAD * 1.1, RAD * 1.1).yrange(-RAD * 1.1, RAD * 1.1);
+
+        pos_plot.drawCurve(x_true, y_true).label("True");
+        pos_plot.drawCurve(x_obs, y_obs).label("Obs");
+        pos_plot.drawCurveWithPoints(x_ukf, y_ukf).label("UKF");
+        pos_plot.drawCurve(x_ukf_full, y_ukf_full).label("Full UKF");
+
+
+        sciplot::Plot2D orientation_plot;
+        orientation_plot.xlabel("t");
+        orientation_plot.ylabel("rot");
+        orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        orientation_plot.xrange(-0.1, 1.1).yrange(-4, 4);
+
+        sciplot::Vec x = sciplot::linspace(0.0, 1.0, a_obs.size());
+        sciplot::Vec x_t = sciplot::linspace(0.0, 1.0, a_true.size());
+        orientation_plot.drawCurve(x_t, a_true).label("True").lineWidth(1);
+        orientation_plot.drawCurve(x, a_obs).label("Obs").lineWidth(1);
+        orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
+        orientation_plot.drawCurve(x_t, a_ukf_full).label("Full UKF").lineWidth(1);
+
+
+        sciplot::Plot2D velocity_plot;
+        orientation_plot.xlabel("t");
+        orientation_plot.ylabel("vel");
+        orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        orientation_plot.xrange(-0.1, 1.1).yrange("*", "*");
+
+        orientation_plot.drawCurve(x_t, vel_x_true).label("x True").lineWidth(1);
+        orientation_plot.drawCurve(x_t, vel_y_true).label("y True").lineWidth(1);
+        orientation_plot.drawCurve(x_t, vel_a_true).label("a True").lineWidth(1);
+        orientation_plot.drawCurve(x_t, vel_x_ukf_full).label("x Ukf").lineWidth(1);
+        orientation_plot.drawCurve(x_t, vel_y_ukf_full).label("y Ukf").lineWidth(1);
+        orientation_plot.drawCurve(x_t, vel_a_ukf_full).label("a Ukf").lineWidth(1);
+
+
+        sciplot::Plot2D error_plot;
+        error_plot.xlabel("t");
+        error_plot.ylabel("err");
+        error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        error_plot.xrange(-0.1, 1.1).yrange("*", "*");
+
+        error_plot.drawCurve(x_t, ukf_pos_var).label("Pos variance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_rot_var).label("Rot variance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_var).label("Total variance").lineWidth(1);
+
+
+        // Create figure to hold plot
+        sciplot::Figure fig = {{pos_plot, orientation_plot}, {velocity_plot, error_plot}};
+        // Create canvas to hold figure
+        sciplot::Canvas canvas = {{fig}};
+        canvas.size(1000, 1000);
+
+        // Show the plot in a pop-up window
+        //canvas.show();
+
+        // Save the plot to a PDF file
+        canvas.save("kalman_output.pdf");
+    }
+
+} // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/human/test/kalmanFilterTest.cpp b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
similarity index 98%
rename from source/armarx/navigation/human/test/kalmanFilterTest.cpp
rename to source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
index 9a80c9ec..d6778e2e 100644
--- a/source/armarx/navigation/human/test/kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
@@ -42,7 +42,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
 
-    constexpr T RAD = 8000;
+    constexpr T RAD = 40;
     constexpr long num_timesteps = 3000;
     constexpr T max_time = 1;
     constexpr T dt = max_time / num_timesteps;
@@ -134,7 +134,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
     }
 
 
-    BOOST_AUTO_TEST_CASE(kalmanFilterTest)
+    BOOST_AUTO_TEST_CASE(so2KalmanFilterTest)
     {
         srand(time(NULL));
 
@@ -266,13 +266,14 @@ namespace armarx::navigation::components::dynamic_scene_provider
         orientation_plot.drawCurve(x, a_ukf).label("UKF").lineWidth(1);
         orientation_plot.drawCurve(x_t, a_ukf_full).label("Full UKF").lineWidth(1);
 
+
         sciplot::Plot2D error_plot;
         error_plot.xlabel("x");
         error_plot.ylabel("y");
         error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        error_plot.xrange(-0.1, 1.1).yrange("*", "*");
 
-
-        error_plot.drawCurve(x_t, ukf_pos_var).label("Pos cariance").lineWidth(1);
+        error_plot.drawCurve(x_t, ukf_pos_var).label("Pos variance").lineWidth(1);
         error_plot.drawCurve(x_t, ukf_rot_var).label("Rot variance").lineWidth(1);
         error_plot.drawCurve(x_t, ukf_var).label("Total variance").lineWidth(1);
 
@@ -284,7 +285,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.size(1000, 1000);
 
         // Show the plot in a pop-up window
-        canvas.show();
+        //canvas.show();
 
         // Save the plot to a PDF file
         canvas.save("kalman_output.pdf");
-- 
GitLab


From cbc24d2e151398559d020555ea84b3fe1c989d16 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Sep 2022 19:50:48 +0200
Subject: [PATCH 208/324] Fix kalman tests

---
 .../navigation/human/HumanSystemModel.h       |  2 +-
 .../human/UnscentedKalmanFilter_impl.cpp      |  2 ++
 .../human/test/se2KalmanFilterTest.cpp        | 33 ++++++++++---------
 .../human/test/se2xVkalmanFilterTest.cpp      | 31 ++++++++---------
 4 files changed, 34 insertions(+), 34 deletions(-)

diff --git a/source/armarx/navigation/human/HumanSystemModel.h b/source/armarx/navigation/human/HumanSystemModel.h
index 8cbda525..036ed537 100644
--- a/source/armarx/navigation/human/HumanSystemModel.h
+++ b/source/armarx/navigation/human/HumanSystemModel.h
@@ -142,7 +142,7 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
         static_assert(std::is_floating_point_v<floatT>);
         struct dim
         {
-            static constexpr long state = 6, control = 0, obs = 3;
+            static constexpr long state = 6, control = 1, obs = 3;
         };
 
         using FloatT = floatT;
diff --git a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
index 168a9e03..37360a4b 100644
--- a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
+++ b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
@@ -10,3 +10,5 @@ template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_sce
 
 template class UnscentedKalmanFilter<
     armarx::navigation::components::dynamic_scene_provider::kalman_filter::SystemModelSE2<double>>;
+template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
+                                         kalman_filter::SystemModelSE2xV<double>>;
diff --git a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
index 61d37530..3746662d 100644
--- a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
@@ -42,18 +42,18 @@ namespace armarx::navigation::components::dynamic_scene_provider
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSE2<T>;
 
-    constexpr T RAD = 1;
+    constexpr T RAD = 10;
     constexpr long num_timesteps = 3000;
     constexpr T max_time = 1;
     constexpr T dt = max_time / num_timesteps;
     constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
 
-    constexpr T rot_noise_std = 0.1;
-    constexpr T pos_noise_std = 0.1;
-    constexpr T obs_rot_noise_std = 0.1;
-    constexpr T obs_pos_noise_std = 0.1;
-    constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
-    const Vector initial_offet_pos = 0.4 * RAD * Vector(1, 0.5);
+    constexpr T rot_noise_std = 0.2;
+    constexpr T pos_noise_std = 2;
+    constexpr T obs_rot_noise_std = 0.2;
+    constexpr T obs_pos_noise_std = 2;
+    constexpr T initial_offset_angle = 0.1 * 10 * M_PI / 180;
+    const Vector initial_offet_pos = 0.1 * RAD * Vector(1, 0.5);
 
 
     void
@@ -78,7 +78,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
             BOOST_TEST(((last_pos - pos).norm() < 0.1 * RAD),
                        "position differs too much from last step: " << (last_pos - pos).norm());
 
-            Eigen::Vector2d euclidean_velocity = Eigen::Vector2d{0, c};
+            Eigen::Vector2d euclidean_velocity = RAD * Eigen::Vector2d{0, c};
             SystemModelT::ControlT control;
             //control.velocity.coeffs() << (pos - last_pos) / dt, c;
             control.velocity.coeffs() << euclidean_velocity, c;
@@ -211,9 +211,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
                                                 Eigen::Matrix<T, 3, 3>::Identity())
                                                    .norm());
 
-                x_obs.push_back(observations.at(i)(0));
-                y_obs.push_back(observations.at(i)(1));
-                a_obs.push_back(observations.at(i)(2));
+                manif::SE2Tangent<T> obs{observations.at(i)};
+                x_obs.push_back(obs.exp().x());
+                y_obs.push_back(obs.exp().y());
+                a_obs.push_back(obs.exp().angle());
 
                 x_ukf.push_back(ukf.getCurrentState().pose.x());
                 y_ukf.push_back(ukf.getCurrentState().pose.y());
@@ -245,7 +246,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         pos_plot.xlabel("x");
         pos_plot.ylabel("y");
         pos_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
-        pos_plot.xrange(-RAD * 1.1, RAD * 1.1).yrange(-RAD * 1.1, RAD * 1.1);
+        pos_plot.xrange(-RAD * 1.2, RAD * 1.2).yrange(-RAD * 1.2, RAD * 1.2);
         //pos_plot.xrange(-4, 4).yrange(-4, 4);
 
         pos_plot.drawCurve(x_true, y_true).label("True");
@@ -255,8 +256,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
 
         sciplot::Plot2D orientation_plot;
-        orientation_plot.xlabel("x");
-        orientation_plot.ylabel("y");
+        orientation_plot.xlabel("t");
+        orientation_plot.ylabel("rot");
         orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
         orientation_plot.xrange(-0.1, 1.1).yrange(-4, 4);
 
@@ -269,8 +270,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
 
         sciplot::Plot2D error_plot;
-        error_plot.xlabel("x");
-        error_plot.ylabel("y");
+        error_plot.xlabel("t");
+        error_plot.ylabel("err");
         error_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
         error_plot.xrange(-0.1, 1.1).yrange("*", "*");
 
diff --git a/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
index 5187e87a..fa182266 100644
--- a/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
@@ -52,7 +52,8 @@ namespace armarx::navigation::components::dynamic_scene_provider
     constexpr T obs_pos_noise_std = 0.01;
     constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
     const Vector initial_offet_pos = 0.8 * RAD * Vector(1, 0.5);
-    const Vector initial_offet_vel = 0.8 * RAD * Vector(1, 0.5);
+    const Eigen::Matrix<T, 3, 1> initial_offet_vel =
+        0.8 * RAD * Eigen::Matrix<T, 3, 1>(1, 0.5, 0.5);
 
 
     void
@@ -181,13 +182,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 ukf.update(observations.at(i));
                 TIMING_END(UPDATE);
                 TIMING_START(REST);
-                const SystemModelT::StateT& current_state = ukf.getCurrentState();
 
                 BOOST_TEST_MESSAGE("Max Cov "
                                    << ukf.getCurrentStateCovariance().cwiseAbs().maxCoeff());
-                BOOST_TEST_MESSAGE("Diag: " << (ukf.getCurrentStateCovariance() -
-                                                Eigen::Matrix<T, 3, 3>::Identity())
-                                                   .norm());
 
                 x_obs.push_back(observations.at(i)(0));
                 y_obs.push_back(observations.at(i)(1));
@@ -255,17 +252,17 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
 
         sciplot::Plot2D velocity_plot;
-        orientation_plot.xlabel("t");
-        orientation_plot.ylabel("vel");
-        orientation_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
-        orientation_plot.xrange(-0.1, 1.1).yrange("*", "*");
+        velocity_plot.xlabel("t");
+        velocity_plot.ylabel("vel");
+        velocity_plot.legend().atOutsideBottom().displayHorizontal().displayExpandWidthBy(2);
+        velocity_plot.xrange(-0.1, 1.1).yrange("*", "*");
 
-        orientation_plot.drawCurve(x_t, vel_x_true).label("x True").lineWidth(1);
-        orientation_plot.drawCurve(x_t, vel_y_true).label("y True").lineWidth(1);
-        orientation_plot.drawCurve(x_t, vel_a_true).label("a True").lineWidth(1);
-        orientation_plot.drawCurve(x_t, vel_x_ukf_full).label("x Ukf").lineWidth(1);
-        orientation_plot.drawCurve(x_t, vel_y_ukf_full).label("y Ukf").lineWidth(1);
-        orientation_plot.drawCurve(x_t, vel_a_ukf_full).label("a Ukf").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_x_true).label("x True").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_y_true).label("y True").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_a_true).label("a True").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_x_ukf_full).label("x Ukf").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_y_ukf_full).label("y Ukf").lineWidth(1);
+        velocity_plot.drawCurve(x_t, vel_a_ukf_full).label("a Ukf").lineWidth(1);
 
 
         sciplot::Plot2D error_plot;
@@ -286,10 +283,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.size(1000, 1000);
 
         // Show the plot in a pop-up window
-        //canvas.show();
+        canvas.show();
 
         // Save the plot to a PDF file
-        canvas.save("kalman_output.pdf");
+        canvas.save("se2xV_kalman_output.pdf");
     }
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From 184017938d102e0fd461251d93bc57f3b6799c12 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Sep 2022 07:59:07 +0200
Subject: [PATCH 209/324] moving function to utils

---
 source/armarx/navigation/algorithms/util.cpp  | 43 +++++++++++++--
 source/armarx/navigation/algorithms/util.h    |  2 +
 .../navigation/simulation/SimulatedHuman.cpp  | 53 +++++--------------
 .../navigation/simulation/SimulatedHuman.h    |  3 --
 4 files changed, 52 insertions(+), 49 deletions(-)

diff --git a/source/armarx/navigation/algorithms/util.cpp b/source/armarx/navigation/algorithms/util.cpp
index fe71db5a..6bc07a84 100644
--- a/source/armarx/navigation/algorithms/util.cpp
+++ b/source/armarx/navigation/algorithms/util.cpp
@@ -22,10 +22,9 @@
 #include "util.h"
 
 #include <algorithm>
+#include <cstddef>
 #include <iterator>
 
-#include <range/v3/all.hpp>
-
 #include <opencv2/core.hpp>
 #include <opencv2/core/eigen.hpp>
 #include <opencv2/imgproc.hpp>
@@ -33,16 +32,18 @@
 #include <SimoxUtility/algorithm/apply.hpp>
 #include <VirtualRobot/BoundingBox.h>
 #include <VirtualRobot/CollisionDetection/CollisionModel.h>
+#include <VirtualRobot/Random.h>
 #include <VirtualRobot/SceneObjectSet.h>
 #include <VirtualRobot/Workspace/WorkspaceGrid.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
-#include <armarx/navigation/algorithms/persistence.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/CostmapBuilder.h>
+#include <armarx/navigation/algorithms/persistence.h>
 #include <armarx/navigation/algorithms/types.h>
+#include <range/v3/all.hpp>
 
 
 namespace armarx::navigation::algorithms
@@ -217,7 +218,8 @@ namespace armarx::navigation::algorithms
         const auto grid = CostmapBuilder::createUniformGrid(costmaps.front().getLocalSceneBounds(),
                                                             costmaps.front().params());
 
-        Costmap mergedCostmap(grid, costmaps.front().params(), costmaps.front().getLocalSceneBounds());
+        Costmap mergedCostmap(
+            grid, costmaps.front().params(), costmaps.front().getLocalSceneBounds());
 
         const auto addMode = [&]() -> Costmap::AddMode
         {
@@ -257,7 +259,8 @@ namespace armarx::navigation::algorithms
         const auto grid = CostmapBuilder::createUniformGrid(costmaps.front().getLocalSceneBounds(),
                                                             costmaps.front().params());
 
-        Costmap mergedCostmap(grid, costmaps.front().params(), costmaps.front().getLocalSceneBounds());
+        Costmap mergedCostmap(
+            grid, costmaps.front().params(), costmaps.front().getLocalSceneBounds());
 
         // foreach pair (costmap, weight): add it to there merged costmap
         ranges::for_each(ranges::views::zip(costmaps, weights),
@@ -328,4 +331,34 @@ namespace armarx::navigation::algorithms
     }
 
 
+    std::optional<core::Pose2D>
+    sampleValidPositionInMap(const algorithms::Costmap& costmap)
+    {
+        const auto sizeX = costmap.getGrid().cols();
+        const auto sizeY = costmap.getGrid().rows();
+
+        constexpr std::size_t maxIterations = 1000;
+
+        // sample a valid pose in the costmap
+
+        for (std::size_t iteration = 0; iteration < maxIterations; iteration++)
+        {
+            const float iX = VirtualRobot::RandomFloat() * static_cast<float>(sizeX);
+            const float iY = VirtualRobot::RandomFloat() * static_cast<float>(sizeY);
+
+            algorithms::Costmap::Index idx(iX, iY);
+
+            if (not costmap.isValid(idx))
+            {
+                continue;
+            }
+
+            core::Pose2D pose = core::Pose2D::Identity();
+            pose.translation() = costmap.toPositionGlobal(idx);
+            return pose;
+        }
+
+        ARMARX_ERROR << "Failed to sample pose in costmap!";
+        return std::nullopt;
+    }
 } // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/algorithms/util.h b/source/armarx/navigation/algorithms/util.h
index ec8d9ae6..90c61b26 100644
--- a/source/armarx/navigation/algorithms/util.h
+++ b/source/armarx/navigation/algorithms/util.h
@@ -64,4 +64,6 @@ namespace armarx::navigation::algorithms
 
     Costmap scaleCostmap(const Costmap& costmap, float cellSize);
 
+    std::optional<core::Pose2D> sampleValidPositionInMap(const algorithms::Costmap& costmap);
+
 } // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index c70ce7a7..0a4d735d 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -21,12 +21,12 @@
 
 #include "SimulatedHuman.h"
 
-#include <Eigen/src/Core/Matrix.h>
-
 #include <VirtualRobot/Random.h>
 
 #include "ArmarXCore/core/logging/Logging.h"
 
+#include "armarx/navigation/algorithms/Costmap.h"
+#include "armarx/navigation/algorithms/util.h"
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/StaticScene.h"
 #include "armarx/navigation/core/types.h"
@@ -92,7 +92,9 @@ namespace armarx::navigation::human::simulation
 
         while (true)
         {
-            const auto goal = sampleValidPositionInMap();
+            const auto sampledPose = algorithms::sampleValidPositionInMap(distanceField_);
+            ARMARX_CHECK(sampledPose.has_value());
+            const auto& goal = sampledPose.value();
 
             const auto plan = planner.plan(conv::to3D(start), conv::to3D(goal));
 
@@ -131,51 +133,20 @@ namespace armarx::navigation::human::simulation
         human_.linearVelocity =
             (wpAfter - wpBefore).head<2>().normalized() * projection.projection.velocity;
 
-        human_.linearVelocity = human_.linearVelocity.normalized() * std::clamp(human_.linearVelocity.norm(), params_.minLinearVelocity, params_.maxLinearVelocity);
+        human_.linearVelocity =
+            human_.linearVelocity.normalized() * std::clamp(human_.linearVelocity.norm(),
+                                                            params_.minLinearVelocity,
+                                                            params_.maxLinearVelocity);
 
         human_.detectionTime = updateTime;
     }
 
-    core::Pose2D
-    SimulatedHuman::sampleValidPositionInMap() const
-    {
-
-        const auto now = Clock::Now();
-
-
-        const auto sizeX = distanceField_.getGrid().cols();
-        const auto sizeY = distanceField_.getGrid().rows();
-
-        // sample a valid pose in the costmap
-        const core::Pose2D pose = [this, &sizeX, &sizeY]()
-        {
-            while (true)
-            {
-                const float iX = VirtualRobot::RandomFloat() * static_cast<float>(sizeX);
-                const float iY = VirtualRobot::RandomFloat() * static_cast<float>(sizeY);
-
-                algorithms::Costmap::Index idx(iX, iY);
-
-                if (not distanceField_.isValid(idx))
-                {
-                    continue;
-                }
-
-                core::Pose2D pose = core::Pose2D::Identity();
-                pose.translation() = distanceField_.toPositionGlobal(idx);
-                return pose;
-            }
-        }();
-
-        // return human::Human human{
-        //     .pose = pose, .linearVelocity = Eigen::Vector2f::Zero(), .detectionTime = now};
-
-        return pose;
-    }
 
     SimulatedHuman::SimulatedHuman(const algorithms::Costmap& distanceField, const Params& params) :
         distanceField_(distanceField), params_(params)
     {
-        human_.pose = sampleValidPositionInMap();
+        const auto sampledPose = algorithms::sampleValidPositionInMap(distanceField_);
+        ARMARX_CHECK(sampledPose.has_value());
+        human_.pose = sampledPose.value();
     }
 } // namespace armarx::navigation::human::simulation
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.h b/source/armarx/navigation/simulation/SimulatedHuman.h
index fb96a1d9..fa4ed6a8 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.h
+++ b/source/armarx/navigation/simulation/SimulatedHuman.h
@@ -65,9 +65,6 @@ namespace armarx::navigation::human::simulation
 
         human::Human human_;
 
-
-        core::Pose2D sampleValidPositionInMap() const;
-
         core::GlobalTrajectory globalTrajectory_;
 
         const Params params_;
-- 
GitLab


From 780e63566ff80f52564243dd6521c5a568271b57 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Sep 2022 07:59:50 +0200
Subject: [PATCH 210/324] human visu: mmm

---
 .../components/navigation_memory/Visu.cpp     | 26 ++++++++++++++-----
 1 file changed, 20 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index f3ae9cbc..2b5e1aa0 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -21,12 +21,15 @@
  */
 
 #include "Visu.h"
+#include <Eigen/src/Geometry/Translation.h>
 
 #include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/cmaps/colormaps.h>
 
 #include "RobotAPI/components/ArViz/Client/Elements.h"
 #include "RobotAPI/components/ArViz/Client/Layer.h"
+#include "RobotAPI/components/ArViz/Client/elements/Color.h"
+#include "RobotAPI/components/ArViz/Client/elements/Robot.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 #include "armarx/navigation/conversions/eigen.h"
@@ -176,18 +179,29 @@ namespace armarx::navigation::memory
         void
         visualize(const human::Humans& humans, viz::Layer& layer)
         {
+
+            const Eigen::Translation3f human_T_mmm(Eigen::Vector3f{0,0, 1000});
+
             ARMARX_INFO << "Visualizing " << humans.size() << " humans";
             for (const auto& human : humans)
             {
-                viz::Cylinder cylinder(std::to_string(layer.size()));
-                cylinder.fromTo(conv::to3D(human.pose.translation()),
-                                conv::to3D(human.pose.translation()) + Eigen::Vector3f{0, 0, 10});
+                // viz::Cylinder cylinder(std::to_string(layer.size()));
+                // cylinder.fromTo(conv::to3D(human.pose.translation()),
+                //                 conv::to3D(human.pose.translation()) + Eigen::Vector3f{0, 0, 10});
+
+
+                // cylinder.color(simox::Color::orange());
+                // cylinder.radius(300);
+                // layer.add(cylinder);
 
 
-                cylinder.color(simox::Color::orange());
-                cylinder.radius(300);
+                viz::Robot mmm(std::to_string(layer.size()));
+                mmm.file("RobotAPI", "RobotAPI/robots/MMM/mmm.xml");
+                mmm.pose(conv::to3D(human.pose) * human_T_mmm);
+                mmm.scale(1.7); // 1.7m 
+                mmm.overrideColor(viz::Color::orange(255, 100));
+                layer.add(mmm);
 
-                layer.add(cylinder);
             }
         }
 
-- 
GitLab


From 5cb657b5c43177475894a5088fff00e98f05ea16 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Sep 2022 08:00:06 +0200
Subject: [PATCH 211/324] fix: visu layers

---
 .../optimization/OrientationOptimizer.cpp              |  2 --
 .../server/introspection/ArvizIntrospector.cpp         | 10 +++++-----
 2 files changed, 5 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
index 4b2182bf..d7ac3128 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
@@ -15,8 +15,6 @@
 #include <ceres/rotation.h>
 #include <ceres/sized_cost_function.h>
 
-#include <Eigen/src/Geometry/Rotation2D.h>
-
 #include <SimoxUtility/math/convert/mat4f_to_xyyaw.h>
 #include <SimoxUtility/math/convert/rpy_to_mat3f.h>
 #include <SimoxUtility/math/periodic/periodic_clamp.h>
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 0c0ef228..6ff9fe14 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -144,7 +144,7 @@ namespace armarx::navigation::server
                     .color(cmap.at(tp.velocity / maxVelocity)));
         }
 
-        layers.emplace(layer.data_.name, std::move(layer));
+        layers[layer.data_.name] = std::move(layer);
     }
 
     void
@@ -183,8 +183,8 @@ namespace armarx::navigation::server
                 viz::Sphere("velocity_" + std::to_string(i)).position(pos).radius(50).color(color));
         }
 
-        layers.emplace(layer.data_.name, std::move(layer));
-        layers.emplace(velLayer.data_.name, std::move(velLayer));
+        layers[layer.data_.name] = std::move(layer);
+        layers[velLayer.data_.name] = std::move(velLayer);
     }
 
     void
@@ -197,7 +197,7 @@ namespace armarx::navigation::server
                               core::Pose(robot->getGlobalPose()) * twist.linear)
                       .color(simox::Color::orange()));
 
-        layers.emplace(layer.data_.name, std::move(layer));
+        layers[layer.data_.name] = std::move(layer);
     }
 
     void
@@ -210,7 +210,7 @@ namespace armarx::navigation::server
                               core::Pose(robot->getGlobalPose()) * twist.linear)
                       .color(simox::Color::green()));
 
-        layers.emplace(layer.data_.name, std::move(layer));
+        layers[layer.data_.name] = std::move(layer);
     }
 
     ArvizIntrospector::ArvizIntrospector(ArvizIntrospector&& other) noexcept :
-- 
GitLab


From 131e3143440bd23ce78a5e5ea512387013adc2e5 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Sep 2022 08:01:53 +0200
Subject: [PATCH 212/324] example: wandering around

---
 .../components/example_client/CMakeLists.txt  |   1 +
 .../components/example_client/Component.cpp   | 101 +++++++++++++++++-
 .../components/example_client/Component.h     |  22 +++-
 3 files changed, 114 insertions(+), 10 deletions(-)

diff --git a/examples/components/example_client/CMakeLists.txt b/examples/components/example_client/CMakeLists.txt
index 01f000d5..5d89c439 100644
--- a/examples/components/example_client/CMakeLists.txt
+++ b/examples/components/example_client/CMakeLists.txt
@@ -12,6 +12,7 @@ armarx_add_component(example_client
         armem_robot_state
         armem_robot
         armarx_navigation::client
+        armarx_navigation::memory
         Simox::SimoxUtility
         Eigen3::Eigen
 )
diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index 4bb1c1f7..11261fa1 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -33,6 +33,8 @@
 #include <ArmarXCore/core/time/forward_declarations.h>
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
+#include "armarx/navigation/algorithms/util.h"
+#include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/types.h"
 #include "armarx/navigation/global_planning/SPFA.h"
 #include "armarx/navigation/local_planning/TimedElasticBands.h"
@@ -49,13 +51,11 @@ namespace armarx::navigation::components::example_client
     Component::Component()
     {
         addPlugin(virtualRobotReaderPlugin);
+        addPlugin(costmapReaderPlugin);
     }
 
 
-    Component::~Component()
-    {
-        // pass
-    }
+    Component::~Component() = default;
 
 
     void
@@ -124,6 +124,10 @@ namespace armarx::navigation::components::example_client
                 ARMARX_IMPORTANT << "Running `Mode::UpdateNavigator`";
                 exampleNavigationUpdateNavigator();
                 break;
+            case Mode::WanderAround:
+                ARMARX_IMPORTANT << "Running `Mode::WanderAround`";
+                exampleNavigationWanderAround();
+                break;
         }
     }
 
@@ -426,6 +430,92 @@ namespace armarx::navigation::components::example_client
         getNavigator().pause();
     }
 
+    void
+    Component::exampleNavigationWanderAround()
+    {
+        // Import relevant namespaces.
+        using namespace armarx::navigation;
+
+        ARMARX_INFO << "Configuring navigator";
+
+        // Create an example configuration valid for the following move* calls.
+        configureNavigator(
+            client::NavigationStackConfig()
+                .general({} /*{.maxVel = VelocityLimits{.linear = 400 , .angular = 0.1}}*/)
+                .globalPlanner(global_planning::SPFAParams())
+                .localPlanner(local_planning::TimedElasticBandsParams())
+                .trajectoryController(
+                    traj_ctrl::local::TrajectoryFollowingControllerParams())); // FIXME
+
+        Clock::WaitFor(Duration::Seconds(1));
+
+        const algorithms::Costmap costmap = [&]() -> algorithms::Costmap
+        {
+            while (true)
+            {
+                const auto timestamp = Clock::Now();
+
+                const memory::client::costmap::Reader::Query costmapQuery{
+                    .providerName = "distance_to_obstacle_costmap_provider", // TODO check
+                    .name = "distance_to_obstacles",
+                    .timestamp = timestamp};
+
+                const memory::client::costmap::Reader::Result costmapResult =
+                    costmapReaderPlugin->get().query(costmapQuery);
+
+                // if costmap is not available yet, wait
+                if (costmapResult.status != memory::client::costmap::Reader::Result::Success)
+                {
+                    Clock::WaitFor(Duration::MilliSeconds(100));
+                    continue;
+                }
+
+                ARMARX_CHECK_EQUAL(costmapResult.status,
+                                   memory::client::costmap::Reader::Result::Success);
+
+                ARMARX_TRACE;
+                ARMARX_CHECK(costmapResult.costmap.has_value());
+                return costmapResult.costmap.value();
+            };
+        }();
+
+
+        while (true)
+        {
+
+            ARMARX_INFO << "Moving to goal pose";
+            // Start moving to goal position using above config.
+            const auto sampledPose = algorithms::sampleValidPositionInMap(costmap);
+            ARMARX_CHECK(sampledPose.has_value());
+            core::Pose goal = conv::to3D(sampledPose.value());
+
+            getNavigator().moveTo(goal, core::NavigationFrame::Absolute);
+
+            // Wait until goal is reached
+            armarx::navigation::client::StopEvent se = getNavigator().waitForStop();
+            if (se)
+            {
+                ARMARX_INFO << "Goal reached.";
+            }
+            else
+            {
+                if (se.isSafetyStopTriggeredEvent())
+                {
+                    ARMARX_ERROR << "Safety stop was triggered!";
+                }
+                else if (se.isUserAbortTriggeredEvent())
+                {
+                    ARMARX_ERROR << "Aborted by user!";
+                }
+                else if (se.isInternalErrorEvent())
+                {
+                    ARMARX_ERROR << "Unknown internal error occured! "
+                                 << se.toInternalErrorEvent().message;
+                }
+            }
+        }
+    }
+
 
     void
     Component::goalReached()
@@ -450,7 +540,8 @@ namespace armarx::navigation::components::example_client
             .map({{"standard", Mode::Standard},
                   {"complex", Mode::Complex},
                   {"point_to_point", Mode::PointToPoint},
-                  {"update_navigator", Mode::UpdateNavigator}});
+                  {"update_navigator", Mode::UpdateNavigator},
+                  {"wander_around", Mode::WanderAround}});
 
         return def;
     }
diff --git a/examples/components/example_client/Component.h b/examples/components/example_client/Component.h
index 3c6748d3..f8b5bb83 100644
--- a/examples/components/example_client/Component.h
+++ b/examples/components/example_client/Component.h
@@ -26,10 +26,12 @@
 
 #include <ArmarXCore/util/tasks.h>
 
-#include <armarx/navigation/client.h>
+#include <RobotAPI/libraries/armem/client/plugins.h>
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
 #include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h>
-#include <RobotAPI/libraries/armem/client/plugins.h>
+
+#include "armarx/navigation/memory/client/costmap/Reader.h"
+#include <armarx/navigation/client.h>
 
 
 namespace armarx::navigation::components::example_client
@@ -40,7 +42,8 @@ namespace armarx::navigation::components::example_client
         Standard,
         Complex,
         PointToPoint,
-        UpdateNavigator
+        UpdateNavigator,
+        WanderAround
     };
 
     /**
@@ -105,10 +108,13 @@ namespace armarx::navigation::components::example_client
 
         void exampleNavigationUpdateNavigator();
 
+        void exampleNavigationWanderAround();
+
     private:
         void goalReached();
 
-        struct{
+        struct
+        {
             std::string robotName = "Armar6";
             float relativeMovement = 200; // [mm]
 
@@ -117,9 +123,15 @@ namespace armarx::navigation::components::example_client
 
         armarx::RunningTask<Component>::pointer_type task;
 
-        armem::client::plugins::ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin = nullptr;
+        template <typename T>
+        using ReaderWriterPlugin = armem::client::plugins::ReaderWriterPlugin<T>;
+
 
+        ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin =
+            nullptr;
 
+        // for exampleNavigationWanderAround
+        ReaderWriterPlugin<memory::client::costmap::Reader>* costmapReaderPlugin = nullptr;
     };
 
 } // namespace armarx::navigation::components::example_client
-- 
GitLab


From 0d96e80536c49b38d513647b497fcec6bfd48b20 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 7 Sep 2022 08:27:32 +0200
Subject: [PATCH 213/324] adding missing field initializer

---
 .../navigation/components/dynamic_scene_provider/Component.cpp  | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 972cabd8..23a58b26 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -206,7 +206,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ARMARX_INFO << "Querying humans";
 
         const armem::human::client::Reader::Query humanPoseQuery{.providerName = properties.humanPoseProvider,
-                                                                 .timestamp = timestamp};
+                                                                 .timestamp = timestamp, .maxAge = Duration::MilliSeconds(500)};
 
         const armem::human::client::Reader::Result humanPoseResult =
             humanPoseReaderPlugin->get().query(humanPoseQuery);
-- 
GitLab


From bc8479cc3d1cde27eeb9d662447e315b17a2c28e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 7 Sep 2022 18:49:31 +0200
Subject: [PATCH 214/324] cmake update

---
 CMakeLists.txt | 24 +++++++++++++-----------
 1 file changed, 13 insertions(+), 11 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index b41b5959..308bddb1 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -12,26 +12,34 @@ armarx_project(navigation NAMESPACE armarx)
 
 # Specify each ArmarX Package dependency with the following macro
 
-# - required
+# Required ArmarX dependencies.
+# ===================================
+
 armarx_find_package(PUBLIC RobotAPI REQUIRED)
 
-# - optional
+# Optional ArmarX dependencies.
+# ===================================
+
 armarx_find_package(PUBLIC armarx::control)
 armarx_find_package(PUBLIC ArmarXGui)
 armarx_find_package(PUBLIC MemoryX QUIET)
 armarx_find_package(PUBLIC VisionX QUIET)
 armarx_find_package(PUBLIC ArmarXSimulation QUIET)
 
-# System dependencies
-# - required
+# Required system dependencies.
+# ===================================
+
+
+# Optional system dependencies.
+# ===================================
 
-# - optional
 armarx_find_package(PUBLIC OpenMP QUIET)
 armarx_find_package(PUBLIC Ceres QUIET)
 armarx_find_package(PUBLIC VTK QUIET)
 armarx_find_package(PUBLIC SemanticObjectRelations QUIET)
 armarx_find_package(PUBLIC OpenCV QUIET)  # Required as RobotAPI is a legacy project.
 armarx_find_package(PUBLIC range-v3 QUIET)
+
 # human aware navigation
 armarx_find_package(PUBLIC teb_local_planner QUIET)
 armarx_find_package(PUBLIC teb_extension QUIET)
@@ -45,12 +53,6 @@ add_subdirectory(etc)
 # )
 # FetchContent_MakeAvailable(inotify_cpp)
 
-add_definitions(-Werror=init-self)
-add_definitions(-Werror=uninitialized)
-add_definitions(-Werror=missing-field-initializers)
-add_definitions(-Werror=reorder)
-add_definitions(-Werror=narrowing)
-
 add_subdirectory(source)
 add_subdirectory(examples)
 
-- 
GitLab


From bf8174f7a42a365f54f4983236c6f84aee12fc2e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 8 Sep 2022 10:57:42 +0200
Subject: [PATCH 215/324] Adjust so2 kalman test parameters

---
 .../navigation/human/test/so2kalmanFilterTest.cpp  | 14 +++++++-------
 1 file changed, 7 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
index d6778e2e..7dbf4d9e 100644
--- a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
@@ -49,9 +49,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
     constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
 
     constexpr T rot_noise_std = 0.2;
-    constexpr T pos_noise_std = 200;
+    constexpr T pos_noise_std = 5;
     constexpr T obs_rot_noise_std = 0.2;
-    constexpr T obs_pos_noise_std = 200;
+    constexpr T obs_pos_noise_std = 5;
     constexpr T initial_offset_angle = 1 * 10 * M_PI / 180;
     const Vector initial_offet_pos = 0.8 * RAD * Vector(1, 0.5);
 
@@ -163,9 +163,9 @@ namespace armarx::navigation::components::dynamic_scene_provider
         P0.block<2, 2>(1, 1) *= initial_offet_pos.norm() * initial_offet_pos.norm();
 
         UnscentedKalmanFilter<SystemModelT>::AlphaT alpha;
-        alpha(0) = 0.8; // state
-        alpha(1) = 0.1; // control
-        alpha(2) = 0.1; // update
+        alpha(0) = 0.5; // state
+        alpha(1) = 0.5; // control
+        alpha(2) = 0.5; // update
 
         SystemModelT::StateT state0;
         state0.orientation = manif::SO2<T>(states.at(0).orientation.angle() + initial_offset_angle);
@@ -285,10 +285,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.size(1000, 1000);
 
         // Show the plot in a pop-up window
-        //canvas.show();
+        canvas.show();
 
         // Save the plot to a PDF file
-        canvas.save("kalman_output.pdf");
+        canvas.save("so2_kalman_output.pdf");
     }
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
-- 
GitLab


From a54fd52e9d61ea75d47dab767a43a7a736530077 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 12 Sep 2022 16:44:13 +0200
Subject: [PATCH 216/324] Move HumanTracker.* from dsp to human and adjust
 namespaces

---
 .../dynamic_scene_provider/CMakeLists.txt     |  2 -
 .../dynamic_scene_provider/Component.cpp      | 48 +++++++++++--------
 .../dynamic_scene_provider/Component.h        |  4 +-
 source/armarx/navigation/human/CMakeLists.txt |  2 +
 .../navigation/human/HumanSystemModel.cpp     |  4 +-
 .../navigation/human/HumanSystemModel.h       |  4 +-
 .../HumanTracker.cpp                          |  4 +-
 .../HumanTracker.h                            |  4 +-
 .../human/UnscentedKalmanFilter_impl.cpp      | 14 +++---
 .../human/test/se2KalmanFilterTest.cpp        |  4 +-
 .../human/test/se2xVkalmanFilterTest.cpp      |  4 +-
 .../human/test/so2kalmanFilterTest.cpp        |  4 +-
 12 files changed, 53 insertions(+), 45 deletions(-)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/HumanTracker.cpp (98%)
 rename source/armarx/navigation/{components/dynamic_scene_provider => human}/HumanTracker.h (95%)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
index e061ea23..52e4efdc 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
+++ b/source/armarx/navigation/components/dynamic_scene_provider/CMakeLists.txt
@@ -9,11 +9,9 @@ armarx_add_component(dynamic_scene_provider
     SOURCES
         Component.cpp
         ArVizDrawer.cpp
-        HumanTracker.cpp
     HEADERS
         Component.h
         ArVizDrawer.h
-        HumanTracker.h
     DEPENDENCIES
         # ArmarXCore
         ArmarXCore
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 23a58b26..29c23bbf 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -76,18 +76,23 @@ namespace armarx::navigation::components::dynamic_scene_provider
         // def->required(properties.boxLayerName, "p.box.LayerName", "Name of the box layer in ArViz.");
 
         // Add an optionalproperty.
-        def->optional(properties.taskPeriodMs, "p.taskPeriodMs", "Update rate of the running task.");
-        
-        def->optional(properties.laserScannerFeatures.providerName, "p.laserScannerFeatures.providerName", "");
+        def->optional(
+            properties.taskPeriodMs, "p.taskPeriodMs", "Update rate of the running task.");
+
+        def->optional(properties.laserScannerFeatures.providerName,
+                      "p.laserScannerFeatures.providerName",
+                      "");
         def->optional(properties.laserScannerFeatures.name, "p.laserScannerFeatures.name", "");
-        
+
         def->optional(properties.robot.name, "p.robot.name", "");
-        
+
         def->optional(properties.occupancyGrid.providerName, "p.occupancyGrid.providerName", "");
         def->optional(properties.occupancyGrid.name, "p.occupancyGrid.name", "");
-        def->optional(properties.occupancyGrid.freespaceThreshold, "p.occupancyGrid.freespaceThreshold", "");
-        def->optional(properties.occupancyGrid.occupiedThreshold, "p.occupancyGrid.occupiedThreshold", "");
-        
+        def->optional(
+            properties.occupancyGrid.freespaceThreshold, "p.occupancyGrid.freespaceThreshold", "");
+        def->optional(
+            properties.occupancyGrid.occupiedThreshold, "p.occupancyGrid.occupiedThreshold", "");
+
         def->optional(properties.humanPoseProvider, "p.humanPoseProvider", "");
 
         return def;
@@ -137,10 +142,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
         }
         */
 
-        while(true)
+        while (true)
         {
             robot = virtualRobotReaderPlugin->get().getRobot(properties.robot.name);
-            if(robot != nullptr)
+            if (robot != nullptr)
             {
                 break;
             }
@@ -205,12 +210,15 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << "Querying humans";
 
-        const armem::human::client::Reader::Query humanPoseQuery{.providerName = properties.humanPoseProvider,
-                                                                 .timestamp = timestamp, .maxAge = Duration::MilliSeconds(500)};
+        const armem::human::client::Reader::Query humanPoseQuery{
+            .providerName = properties.humanPoseProvider,
+            .timestamp = timestamp,
+            .maxAge = Duration::MilliSeconds(500)};
 
         const armem::human::client::Reader::Result humanPoseResult =
             humanPoseReaderPlugin->get().query(humanPoseQuery);
-        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success) << humanPoseResult.errorMessage;
+        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success)
+            << humanPoseResult.errorMessage;
 
         ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
 
@@ -265,10 +273,10 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << "Querying costmap";
 
-        const memory::client::costmap::Reader::Query costmapQuery{.providerName =
-                                                                      "distance_to_obstacle_costmap_provider", // TODO check
-                                                                  .name = "distance_to_obstacles",
-                                                                  .timestamp = timestamp};
+        const memory::client::costmap::Reader::Query costmapQuery{
+            .providerName = "distance_to_obstacle_costmap_provider", // TODO check
+            .name = "distance_to_obstacles",
+            .timestamp = timestamp};
 
         const memory::client::costmap::Reader::Result costmapResult =
             costmapReaderPlugin->get().query(costmapQuery);
@@ -343,11 +351,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << "Running human tracker";
 
-        humanTracker.update(HumanTracker::Measurements{.detectionTime = timestamp,
-                                                       .humanPoses = humanPoseResult.humanPoses});
+        humanTracker.update(human::HumanTracker::Measurements{
+            .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
 
 
-        humanWriterPlugin->get().store(humanTracker.getTrackedHumans(),getName(), timestamp);
+        humanWriterPlugin->get().store(humanTracker.getTrackedHumans(), getName(), timestamp);
     }
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index bcc3ad7d..7d58e1bd 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -47,7 +47,7 @@
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
 #include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
-#include "armarx/navigation/components/dynamic_scene_provider/HumanTracker.h"
+#include "armarx/navigation/human/HumanTracker.h"
 #include "armarx/navigation/memory/client/costmap/Reader.h"
 #include "armarx/navigation/memory/client/human/Writer.h"
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
@@ -205,7 +205,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ReaderWriterPlugin<memory::client::human::Writer>* humanWriterPlugin = nullptr;
 
 
-        HumanTracker humanTracker;
+        human::HumanTracker humanTracker;
     };
 
 } // namespace armarx::navigation::components::dynamic_scene_provider
diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 2ffaa3d1..4f772ebf 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -20,12 +20,14 @@ armarx_add_library(teb_human
         ProxemicZoneCreator.cpp
         HumanSystemModel.cpp
         UnscentedKalmanFilter_impl.cpp
+        HumanTracker.cpp
     HEADERS
         types.h
         aron_conversions.h
         shapes.h
         ProxemicZoneCreator.h
         HumanSystemModel.h
+        HumanTracker.h
 )
 
 find_package(sciplot)
diff --git a/source/armarx/navigation/human/HumanSystemModel.cpp b/source/armarx/navigation/human/HumanSystemModel.cpp
index 32b18fd1..80f68205 100644
--- a/source/armarx/navigation/human/HumanSystemModel.cpp
+++ b/source/armarx/navigation/human/HumanSystemModel.cpp
@@ -1,6 +1,6 @@
 #include "HumanSystemModel.h"
 
-namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+namespace armarx::navigation::human::kalman_filter
 {
 
     // ------------------------------ SO2xR2 -----------------------------------------
@@ -168,4 +168,4 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     template struct SystemModelSE2xV<float>;
     template struct SystemModelSE2xV<double>;
 
-} // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+} // namespace armarx::navigation::human::kalman_filter
diff --git a/source/armarx/navigation/human/HumanSystemModel.h b/source/armarx/navigation/human/HumanSystemModel.h
index 036ed537..05de1fdc 100644
--- a/source/armarx/navigation/human/HumanSystemModel.h
+++ b/source/armarx/navigation/human/HumanSystemModel.h
@@ -24,7 +24,7 @@
 #include <manif/SE2.h>
 #include <manif/SO2.h>
 
-namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+namespace armarx::navigation::human::kalman_filter
 {
     //----------- SO2xR2 -----------------
 
@@ -168,4 +168,4 @@ namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
     extern template struct SystemModelSE2xV<float>;
     extern template struct SystemModelSE2xV<double>;
 
-} // namespace armarx::navigation::components::dynamic_scene_provider::kalman_filter
+} // namespace armarx::navigation::human::kalman_filter
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
similarity index 98%
rename from source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
rename to source/armarx/navigation/human/HumanTracker.cpp
index ec7fca6e..6db5b4b3 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -7,7 +7,7 @@
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
 
-namespace armarx::navigation::components::dynamic_scene_provider
+namespace armarx::navigation::human
 {
 
     //TODO which values are appropriate?
@@ -274,4 +274,4 @@ namespace armarx::navigation::components::dynamic_scene_provider
         trackedHumans.clear();
     }
 
-} // namespace armarx::navigation::components::dynamic_scene_provider
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
similarity index 95%
rename from source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
rename to source/armarx/navigation/human/HumanTracker.h
index 5b015f7f..099aca7b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -32,7 +32,7 @@
 #include <armarx/navigation/human/HumanSystemModel.h>
 #include <armarx/navigation/human/types.h>
 
-namespace armarx::navigation::components::dynamic_scene_provider
+namespace armarx::navigation::human
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
@@ -89,4 +89,4 @@ namespace armarx::navigation::components::dynamic_scene_provider
         std::vector<TrackedHuman> trackedHumans;
         Parameters parameters;
     };
-} // namespace armarx::navigation::components::dynamic_scene_provider
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
index 37360a4b..5818d6ed 100644
--- a/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
+++ b/source/armarx/navigation/human/UnscentedKalmanFilter_impl.cpp
@@ -3,12 +3,12 @@
 #include <armarx/navigation/human/HumanSystemModel.h>
 
 
-template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
-                                         kalman_filter::SystemModelSO2xR2<float>>;
-template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
-                                         kalman_filter::SystemModelSO2xR2<double>>;
+template class UnscentedKalmanFilter<
+    armarx::navigation::human::kalman_filter::SystemModelSO2xR2<float>>;
+template class UnscentedKalmanFilter<
+    armarx::navigation::human::kalman_filter::SystemModelSO2xR2<double>>;
 
 template class UnscentedKalmanFilter<
-    armarx::navigation::components::dynamic_scene_provider::kalman_filter::SystemModelSE2<double>>;
-template class UnscentedKalmanFilter<armarx::navigation::components::dynamic_scene_provider::
-                                         kalman_filter::SystemModelSE2xV<double>>;
+    armarx::navigation::human::kalman_filter::SystemModelSE2<double>>;
+template class UnscentedKalmanFilter<
+    armarx::navigation::human::kalman_filter::SystemModelSE2xV<double>>;
diff --git a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
index 3746662d..011d96b8 100644
--- a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
@@ -36,7 +36,7 @@
 #include <manif/SO2.h>
 #include <sciplot/sciplot.hpp>
 
-namespace armarx::navigation::components::dynamic_scene_provider
+namespace armarx::navigation::human
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
@@ -293,4 +293,4 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.save("se2_kalman_output.pdf");
     }
 
-} // namespace armarx::navigation::components::dynamic_scene_provider
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
index fa182266..9693e0f8 100644
--- a/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/se2xVkalmanFilterTest.cpp
@@ -36,7 +36,7 @@
 #include <manif/SO2.h>
 #include <sciplot/sciplot.hpp>
 
-namespace armarx::navigation::components::dynamic_scene_provider
+namespace armarx::navigation::human
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
@@ -289,4 +289,4 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.save("se2xV_kalman_output.pdf");
     }
 
-} // namespace armarx::navigation::components::dynamic_scene_provider
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
index 7dbf4d9e..48529d44 100644
--- a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
@@ -36,7 +36,7 @@
 #include <manif/SO2.h>
 #include <sciplot/sciplot.hpp>
 
-namespace armarx::navigation::components::dynamic_scene_provider
+namespace armarx::navigation::human
 {
     using T = double; //TODO double or float?
     using Vector = Eigen::Matrix<T, 2, 1>;
@@ -291,4 +291,4 @@ namespace armarx::navigation::components::dynamic_scene_provider
         canvas.save("so2_kalman_output.pdf");
     }
 
-} // namespace armarx::navigation::components::dynamic_scene_provider
+} // namespace armarx::navigation::human
-- 
GitLab


From 212ac40ab1531ab18593c558ac8607727839eb89 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 12 Sep 2022 16:47:31 +0200
Subject: [PATCH 217/324] Create new class HumanFilter

---
 source/armarx/navigation/human/CMakeLists.txt |  2 ++
 .../armarx/navigation/human/HumanFilter.cpp   | 10 ++++++
 source/armarx/navigation/human/HumanFilter.h  | 34 +++++++++++++++++++
 .../human/test/se2KalmanFilterTest.cpp        | 10 +++---
 4 files changed, 51 insertions(+), 5 deletions(-)
 create mode 100644 source/armarx/navigation/human/HumanFilter.cpp
 create mode 100644 source/armarx/navigation/human/HumanFilter.h

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 4f772ebf..14deaae1 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -21,6 +21,7 @@ armarx_add_library(teb_human
         HumanSystemModel.cpp
         UnscentedKalmanFilter_impl.cpp
         HumanTracker.cpp
+        HumanFilter.cpp
     HEADERS
         types.h
         aron_conversions.h
@@ -28,6 +29,7 @@ armarx_add_library(teb_human
         ProxemicZoneCreator.h
         HumanSystemModel.h
         HumanTracker.h
+        HumanFilter.h
 )
 
 find_package(sciplot)
diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
new file mode 100644
index 00000000..436a9ceb
--- /dev/null
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -0,0 +1,10 @@
+#include "HumanFilter.h"
+
+namespace armarx::navigation::human
+{
+
+    HumanFilter::HumanFilter()
+    {
+    }
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
new file mode 100644
index 00000000..9f4cf3ec
--- /dev/null
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -0,0 +1,34 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
+ * @author     Corvin Navarro Ecker ( corvin dot ecker at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+namespace armarx::navigation::human
+{
+
+    class HumanFilter
+    {
+    public:
+        HumanFilter();
+    };
+
+} // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
index 011d96b8..c83f4db5 100644
--- a/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/se2KalmanFilterTest.cpp
@@ -48,10 +48,10 @@ namespace armarx::navigation::human
     constexpr T dt = max_time / num_timesteps;
     constexpr T c = (1 / max_time) * 2 * M_PI; // rotation per time
 
-    constexpr T rot_noise_std = 0.2;
-    constexpr T pos_noise_std = 2;
-    constexpr T obs_rot_noise_std = 0.2;
-    constexpr T obs_pos_noise_std = 2;
+    constexpr T rot_noise_std = 0.1;
+    constexpr T pos_noise_std = 1;
+    constexpr T obs_rot_noise_std = 0.1;
+    constexpr T obs_pos_noise_std = 1;
     constexpr T initial_offset_angle = 0.1 * 10 * M_PI / 180;
     const Vector initial_offet_pos = 0.1 * RAD * Vector(1, 0.5);
 
@@ -198,7 +198,7 @@ namespace armarx::navigation::human
             TIMING_START(PROPAGATION);
             ukf.propagation(omegas.at(i - 1), dt);
             TIMING_END(PROPAGATION);
-            if ((i - 1) % 50 == 0)
+            if ((i - 1) % 1 == 0)
             {
                 TIMING_START(UPDATE);
                 ukf.update(observations.at(i));
-- 
GitLab


From f245fd9f893f58c47c4bd6172659d0582a840482 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 12 Sep 2022 19:05:05 +0200
Subject: [PATCH 218/324] Implement HumanFilter and move functionality from
 HumanTracker

---
 .../armarx/navigation/human/HumanFilter.cpp   | 111 +++++++++++++++++-
 source/armarx/navigation/human/HumanFilter.h  |  41 ++++++-
 .../armarx/navigation/human/HumanTracker.cpp  | 105 ++---------------
 source/armarx/navigation/human/HumanTracker.h |   4 +-
 4 files changed, 162 insertions(+), 99 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index 436a9ceb..3c25d4ae 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -3,8 +3,117 @@
 namespace armarx::navigation::human
 {
 
-    HumanFilter::HumanFilter()
+    HumanFilter::HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime)
     {
+        //initialize new human for detected human
+        human.pose = pose0;
+        human.linearVelocity = Eigen::Vector2f::Zero();
+        human.detectionTime = detectionTime;
+
+
+        //initialize new kalman filter for new detected human
+
+        UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
+            UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
+        Q.block<2, 2>(0, 0) *= params.control_pos_cov * params.control_pos_cov;
+        Q.block<1, 1>(2, 2) *= params.control_rot_cov * params.control_rot_cov;
+
+        UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
+            UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity();
+        R.block<2, 2>(0, 0) *= params.obs_pos_cov * params.obs_pos_cov;
+        R.block<1, 1>(2, 2) *= params.obs_rot_cov * params.obs_rot_cov;
+
+        UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
+            UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
+        P0.block<2, 2>(0, 0) *= params.initial_state_pos_cov * params.initial_state_pos_cov;
+        P0.block<1, 1>(2, 2) *= params.initial_state_rot_cov * params.initial_state_rot_cov;
+
+        UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
+            UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * params.alpha;
+
+        //initial position and orientation according to detected human
+        SystemModelT::StateT state0 = toUkfState(pose0);
+
+        ukf = std::make_unique<UnscentedKalmanFilter<SystemModelT>>(Q, R, alpha, state0, P0);
+    }
+
+    void
+    HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
+    {
+        double dt = (detectionTime - human.detectionTime).toSecondsDouble();
+        oldPose = human.pose;
+
+        SystemModelT::ControlT control = toUkfControl(human.linearVelocity);
+        ukf->propagation(control, dt);
+
+        human.pose = fromUkfState(ukf->getCurrentState());
+    }
+
+    void
+    HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
+    {
+        double dt = (detectionTime - human.detectionTime).toSecondsDouble();
+
+        SystemModelT::ObsT observation = toUkfObs(pose);
+        ukf->update(observation);
+
+        core::Pose2D newPose = fromUkfState(ukf->getCurrentState());
+
+        // calculate velocity
+        Eigen::Vector2f ds = newPose.translation() - oldPose.translation();
+        Eigen::Vector2f linVelocity = ds / dt;
+        Eigen::Vector2f newVelocity =
+            params.velocityAlpha * linVelocity + (1 - params.velocityAlpha) * human.linearVelocity;
+
+        human.detectionTime = detectionTime;
+        human.pose = newPose;
+        human.linearVelocity = newVelocity;
     }
 
+    const Human&
+    HumanFilter::get() const
+    {
+        return human;
+    }
+
+
+    HumanFilter::SystemModelT::StateT
+    HumanFilter::toUkfState(const core::Pose2D& pose)
+    {
+        // [mm] to [m]
+        return {{pose.translation().x() / 1000,
+                 pose.translation().y() / 1000,
+                 Eigen::Rotation2Df(pose.linear()).angle()}};
+    }
+
+    core::Pose2D
+    HumanFilter::fromUkfState(const SystemModelT::StateT& pose)
+    {
+        core::Pose2D pose2d;
+        // [m] to [mm]
+        pose2d.translation().x() = pose.pose.x() * 1000;
+        pose2d.translation().y() = pose.pose.y() * 1000;
+        pose2d.linear() = Eigen::Rotation2Df(pose.pose.angle()).toRotationMatrix();
+
+        return pose2d;
+    }
+
+    HumanFilter::SystemModelT::ControlT
+    HumanFilter::toUkfControl(const Eigen::Vector2f& vel)
+    {
+        // convert velocity from global frame to human frame (required by kalman filter)
+        const auto& global_R_human = human.pose.linear();
+        const auto& human_V_vel = global_R_human.inverse() * vel;
+
+        // [mm] to [m]
+        return {{human_V_vel.x() / 1000, human_V_vel.y() / 1000, 0}};
+    }
+
+    HumanFilter::SystemModelT::ObsT
+    HumanFilter::toUkfObs(const core::Pose2D& pose)
+    {
+        return SystemModelT::observationFunction(toUkfState(pose));
+    }
+
+
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index 9f4cf3ec..14be9eb1 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -22,13 +22,52 @@
 
 #pragma once
 
+#include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
+
+#include <armarx/navigation/human/HumanSystemModel.h>
+#include <armarx/navigation/human/types.h>
+
 namespace armarx::navigation::human
 {
 
     class HumanFilter
     {
+
     public:
-        HumanFilter();
+        struct Parameters
+        {
+            //TODO which values are appropriate?
+            double control_pos_cov = 0.01;
+            double control_rot_cov = 0.01;
+            double obs_pos_cov = 0.01;
+            double obs_rot_cov = 0.01;
+            double initial_state_pos_cov = 0.01;
+            double initial_state_rot_cov = 0.01;
+            double alpha = 0.5;
+
+            float velocityAlpha = 0.7;
+        };
+
+        HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime);
+
+        void propagation(const DateTime& detectionTime);
+        void update(const core::Pose2D& pose, const DateTime& detectionTime);
+
+        const Human& get() const;
+
+    private:
+        using SystemModelT = kalman_filter::SystemModelSE2<double>;
+
+        SystemModelT::StateT toUkfState(const core::Pose2D& pose);
+        core::Pose2D fromUkfState(const SystemModelT::StateT& pose);
+        SystemModelT::ControlT toUkfControl(const Eigen::Vector2f& vel);
+        SystemModelT::ObsT toUkfObs(const core::Pose2D& pose);
+
+    private:
+        Parameters params;
+        core::Pose2D oldPose;
+        Human human;
+        std::unique_ptr<UnscentedKalmanFilter<SystemModelT>> ukf;
     };
 
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 6db5b4b3..aecbfeda 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -10,13 +10,6 @@
 namespace armarx::navigation::human
 {
 
-    //TODO which values are appropriate?
-    constexpr T pos_noise_std = 0.01;
-    constexpr T rot_noise_std = 0.01;
-    constexpr T obs_noise_std = 0.01;
-    constexpr T initial_pos_state_cov = 0.01;
-    constexpr T initial_rot_state_cov = 0.01;
-
     HumanTracker::DetectedHuman
     convertHumanPoseToPosition(const DateTime& time, const armem::human::HumanPose& humanPose)
     {
@@ -49,7 +42,7 @@ namespace armarx::navigation::human
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
-            if ((measurements.detectionTime - human.human.detectionTime) >=
+            if ((measurements.detectionTime - human.humanFilter.get().detectionTime) >=
                 parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
@@ -57,7 +50,7 @@ namespace armarx::navigation::human
             else
             {
                 human.associated = false;
-                human.human.pose = human.human.estimateAt(measurements.detectionTime);
+                human.humanFilter.propagation(measurements.detectionTime);
                 it++;
             }
         }
@@ -76,47 +69,11 @@ namespace armarx::navigation::human
         {
             if (!detectedHuman.associated)
             {
-                //initialize new human for detected human
-                human::Human human{.pose = detectedHuman.pose,
-                                   .linearVelocity = Eigen::Vector2f::Zero(),
-                                   .detectionTime = detectedHuman.detectionTime};
-
-                //initialize new kalman filter for new detected human
-
-                UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
-                    UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
-                //rotation noise at (0,0)
-                Q.block<1, 1>(0, 0) *= rot_noise_std * rot_noise_std;
-                //position noise at (1,1) and (2,2)
-                Q.block<2, 2>(1, 1) *= pos_noise_std * pos_noise_std;
-
-                //observation noise at (0,0), (1,1) and (2,2)
-                UnscentedKalmanFilter<SystemModelT>::ObsCovT R =
-                    UnscentedKalmanFilter<SystemModelT>::ObsCovT::Identity() * obs_noise_std *
-                    obs_noise_std;
-
-                UnscentedKalmanFilter<SystemModelT>::StateCovT P0 =
-                    UnscentedKalmanFilter<SystemModelT>::StateCovT::Identity();
-                P0.block<1, 1>(0, 0) *= initial_rot_state_cov * initial_rot_state_cov;
-                P0.block<2, 2>(1, 1) *= initial_pos_state_cov * initial_pos_state_cov;
-
-                UnscentedKalmanFilter<SystemModelT>::AlphaT alpha =
-                    UnscentedKalmanFilter<SystemModelT>::AlphaT::Ones() * 1e-3;
-
-                //initial position and orientation according to detected human
-                SystemModelT::StateT state0;
-                //initialize with detected human pose position
-                state0.position = human.pose.translation().cast<T>();
-                //initialize with SO2 matrix according to detected human pose rotation
-                state0.orientation = manif::SO2<T>{Eigen::Rotation2Df(human.pose.linear()).angle()};
-
-                UnscentedKalmanFilter<SystemModelT> ukf{Q, R, alpha, state0, P0};
-
                 //add new tracked human to list of tracked humans
-                trackedHumans.push_back(TrackedHuman{.human = human,
-                                                     .ukf = ukf,
-                                                     .trackingId = detectedHuman.trackingId,
-                                                     .associated = true});
+                trackedHumans.push_back(TrackedHuman{
+                    .humanFilter = HumanFilter{detectedHuman.pose, detectedHuman.detectionTime},
+                    .trackingId = detectedHuman.trackingId,
+                    .associated = true});
             }
         }
     }
@@ -149,7 +106,8 @@ namespace armarx::navigation::human
                 posDistances.push_back(
                     {&oldHuman,
                      &newHuman,
-                     (newHuman.pose.translation() - oldHuman.human.pose.translation()).norm()});
+                     (newHuman.pose.translation() - oldHuman.humanFilter.get().pose.translation())
+                         .norm()});
             }
         }
 
@@ -211,50 +169,7 @@ namespace armarx::navigation::human
         trackedHuman->associated = true;
         detectedHuman->associated = true;
 
-        //estimate velocity via exponential smoothing
-
-        float dt =
-            (detectedHuman->detectionTime - trackedHuman->human.detectionTime).toSecondsDouble();
-        Eigen::Vector2f ds =
-            (detectedHuman->pose.translation() - trackedHuman->human.pose.translation());
-        Eigen::Vector2f linVelocity = ds / dt;
-
-        Eigen::Vector2f velocity =
-            parameters.velocityAlpha * linVelocity +
-            (1 - parameters.velocityAlpha) * trackedHuman->human.linearVelocity;
-
-        float angle_det = Eigen::Rotation2Df(detectedHuman->pose.linear()).angle();
-        float angle_track = Eigen::Rotation2Df(trackedHuman->human.pose.linear()).angle();
-        //TODO Check angular velocity! Calculation at turning point may be wrong (jump from +pi to -pi)
-        float angular_velocity = (angle_det - angle_track) / dt;
-
-
-        //estimate pose via ukf
-
-        //initialize with estimated velocity (control variables) from tracked human
-        UnscentedKalmanFilter<SystemModelT>::ControlT control;
-        control.angular_velocity.coeffs() << static_cast<T>(angular_velocity);
-        control.euclidean_velocity << velocity.cast<T>();
-
-        //propagate control input for time diff
-        trackedHuman->ukf.propagation(control, dt);
-
-        //initialize observation with detected human data
-        UnscentedKalmanFilter<SystemModelT>::ObsT observation;
-        observation.segment(0, 1) =
-            Eigen::Matrix<T, 1, 1>{Eigen::Rotation2Df(detectedHuman->pose.linear()).angle()};
-        observation.segment(1, 2) = detectedHuman->pose.translation().cast<T>();
-
-        //update with new observation
-        trackedHuman->ukf.update(observation);
-
-        //use current state as new pose of tracked human
-        UnscentedKalmanFilter<SystemModelT>::StateT state = trackedHuman->ukf.getCurrentState();
-        core::Pose2D filteredPose = core::Pose2D::Identity();
-        filteredPose.translation() = state.position.cast<float>();
-        filteredPose.linear() = Eigen::Rotation2Df(state.orientation.angle()).toRotationMatrix();
-
-        trackedHuman->human = {filteredPose, velocity, detectedHuman->detectionTime};
+        trackedHuman->humanFilter.update(detectedHuman->pose, detectedHuman->detectionTime);
         trackedHuman->trackingId = detectedHuman->trackingId;
     }
 
@@ -263,7 +178,7 @@ namespace armarx::navigation::human
     {
         return trackedHumans |
                ranges::views::transform([](const TrackedHuman& h) -> human::Human
-                                        { return h.human; }) |
+                                        { return h.humanFilter.get(); }) |
                ranges::to_vector;
     }
 
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 099aca7b..3c4cc28f 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -29,6 +29,7 @@
 #include <VisionX/libraries/armem_human/types.h>
 
 #include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/HumanFilter.h>
 #include <armarx/navigation/human/HumanSystemModel.h>
 #include <armarx/navigation/human/types.h>
 
@@ -59,8 +60,7 @@ namespace armarx::navigation::human
 
         struct TrackedHuman
         {
-            human::Human human;
-            UnscentedKalmanFilter<SystemModelT> ukf;
+            HumanFilter humanFilter;
             std::optional<std::string> trackingId = std::nullopt;
             bool associated;
         };
-- 
GitLab


From 718cdbcdbb369eab03e1029ef366bb92faadb03c Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 21 Sep 2022 16:04:08 +0200
Subject: [PATCH 219/324] Extract rotation from human pose keypoints

---
 source/armarx/navigation/human/HumanTracker.cpp | 14 ++++++++++++--
 1 file changed, 12 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index aecbfeda..e82ecf9e 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -30,8 +30,18 @@ namespace armarx::navigation::human
 
         core::Pose2D pose = core::Pose2D::Identity();
         pose.translation() = conv::to2D(centerPos);
-        //TODO: angle
-        pose.linear() = Eigen::Rotation2Df(0).toRotationMatrix();
+        double yaw = 0;
+        if (humanPose.keypoints.find("HEAD") != humanPose.keypoints.end())
+        {
+            yaw = humanPose //from all human pose keypoints
+                      .keypoints
+                      .find("HEAD") //find the keypoint representing the head
+                      ->second
+                      .orientationGlobal //get its global orientation
+                      ->toEigen()
+                      .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis)
+        }
+        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
 
         return {pose, humanPose.humanTrackingId, time, false};
     }
-- 
GitLab


From bf0b081fd6d00356f8e48a36a59af52ad8dde01e Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 21 Sep 2022 17:17:09 +0200
Subject: [PATCH 220/324] Add comments to HumanFilter.cpp

---
 .../armarx/navigation/human/HumanFilter.cpp   | 28 ++++++++++++++++++-
 1 file changed, 27 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index 3c25d4ae..e45d942a 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -3,6 +3,12 @@
 namespace armarx::navigation::human
 {
 
+    /**
+     * @brief HumanFilter::HumanFilter creates a new filter that filters 2D poses (position and
+     * rotation in a two dimensional plane)
+     * @param pose0 the first known pose of the human
+     * @param detectionTime the point of detection
+     */
     HumanFilter::HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime)
     {
         //initialize new human for detected human
@@ -12,7 +18,6 @@ namespace armarx::navigation::human
 
 
         //initialize new kalman filter for new detected human
-
         UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
             UnscentedKalmanFilter<SystemModelT>::PropCovT::Identity();
         Q.block<2, 2>(0, 0) *= params.control_pos_cov * params.control_pos_cov;
@@ -37,6 +42,12 @@ namespace armarx::navigation::human
         ukf = std::make_unique<UnscentedKalmanFilter<SystemModelT>>(Q, R, alpha, state0, P0);
     }
 
+    /**
+     * @brief HumanFilter::propagation propagate the system model to the given point in time. This
+     * means that the human pose is updated according to the filters prediction for the given point
+     * in time
+     * @param detectionTime the point in time for which the pose should be predicted
+     */
     void
     HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
     {
@@ -49,11 +60,18 @@ namespace armarx::navigation::human
         human.pose = fromUkfState(ukf->getCurrentState());
     }
 
+    /**
+     * @brief HumanFilter::update update the filter a new detected pose of the tracked human and
+     * the detection time
+     * @param pose the new detected pose of the human
+     * @param detectionTime the detection time
+     */
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
         double dt = (detectionTime - human.detectionTime).toSecondsDouble();
 
+        //update ukf with new observation
         SystemModelT::ObsT observation = toUkfObs(pose);
         ukf->update(observation);
 
@@ -62,14 +80,22 @@ namespace armarx::navigation::human
         // calculate velocity
         Eigen::Vector2f ds = newPose.translation() - oldPose.translation();
         Eigen::Vector2f linVelocity = ds / dt;
+        // apply exponential smoothing to velocity
+        //TODO try other approaches?
         Eigen::Vector2f newVelocity =
             params.velocityAlpha * linVelocity + (1 - params.velocityAlpha) * human.linearVelocity;
 
+        //update stored information about the human
         human.detectionTime = detectionTime;
         human.pose = newPose;
         human.linearVelocity = newVelocity;
     }
 
+    /**
+     * @brief HumanFilter::get returns the human whose pose is filtered containing the most recent
+     * state
+     * @return the human
+     */
     const Human&
     HumanFilter::get() const
     {
-- 
GitLab


From a4705cb22611fa2aefc1c27ea5b2f7d1d64ea6bb Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 21 Sep 2022 19:44:16 +0200
Subject: [PATCH 221/324] Add comments to HumanTracker.cpp and to header files

---
 source/armarx/navigation/human/HumanFilter.h  |   5 +
 .../armarx/navigation/human/HumanTracker.cpp  | 181 ++++++++++++------
 source/armarx/navigation/human/HumanTracker.h |  18 +-
 3 files changed, 141 insertions(+), 63 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index 14be9eb1..749750d4 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -30,6 +30,11 @@
 namespace armarx::navigation::human
 {
 
+    /**
+     * @brief The HumanFilter class can be used to track and filter the state of a single human. It
+     * hides implementation detail on how the filtering is done. New information about the human can
+     * be fed by using the update method. The human itself can be obtained using the get method.
+     */
     class HumanFilter
     {
 
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index e82ecf9e..dd6ecfc4 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -9,54 +9,28 @@
 
 namespace armarx::navigation::human
 {
-
-    HumanTracker::DetectedHuman
-    convertHumanPoseToPosition(const DateTime& time, const armem::human::HumanPose& humanPose)
-    {
-        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
-        ARMARX_CHECK_NOT_EMPTY(keypoints);
-
-        Eigen::Vector3f centerPos;
-        int size = 0;
-        for (const auto& [_, v] : keypoints)
-        {
-            if (v.positionGlobal.has_value())
-            {
-                centerPos += v.positionGlobal.value().toEigen();
-                size++;
-            }
-        }
-        centerPos /= size;
-
-        core::Pose2D pose = core::Pose2D::Identity();
-        pose.translation() = conv::to2D(centerPos);
-        double yaw = 0;
-        if (humanPose.keypoints.find("HEAD") != humanPose.keypoints.end())
-        {
-            yaw = humanPose //from all human pose keypoints
-                      .keypoints
-                      .find("HEAD") //find the keypoint representing the head
-                      ->second
-                      .orientationGlobal //get its global orientation
-                      ->toEigen()
-                      .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis)
-        }
-        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
-
-        return {pose, humanPose.humanTrackingId, time, false};
-    }
-
+    /**
+     * @brief HumanTracker::update Updates the tracked humans with the measurements. When a
+     * measurement is close enough to an existing tracked human, they are associated, otherwise a
+     * new tracked human is created. Tracked humans that were not associated with a new measurement
+     * for a specified amount of time are removed. New associated measurements for a tracked human
+     * are always filtered to provide a less noisy state.
+     * @param measurements the new measurements of the environment
+     */
     void
     HumanTracker::update(const Measurements& measurements)
     {
+        // iterate over all existing tracked humans
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
         {
             auto& human = *it;
+            // when the tracked human recieved no new measurement for too long, remove it
             if ((measurements.detectionTime - human.humanFilter.get().detectionTime) >=
                 parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
             }
+            // otherwise the tracked human is prepared for association at the current point in time
             else
             {
                 human.associated = false;
@@ -65,19 +39,22 @@ namespace armarx::navigation::human
             }
         }
 
+        // calculate the poses according to the new received measurements
         std::vector<DetectedHuman> newPoses =
             measurements.humanPoses |
             ranges::views::transform(
-                [measurements](const armem::human::HumanPose& humanPose) -> DetectedHuman
-                { return convertHumanPoseToPosition(measurements.detectionTime, humanPose); }) |
+                [measurements, this](const armem::human::HumanPose& humanPose) -> DetectedHuman {
+                    return convertHumanPoseToDetectedHuman(measurements.detectionTime, humanPose);
+                }) |
             ranges::to_vector;
 
+        // associate the new poses from the measurement with the tracked humans
         associateHumans(newPoses);
 
-        // add all not associated humans as new tracked humans
+        // add all not associated poses as new tracked humans
         for (const auto& detectedHuman : newPoses)
         {
-            if (!detectedHuman.associated)
+            if (not detectedHuman.associated)
             {
                 //add new tracked human to list of tracked humans
                 trackedHumans.push_back(TrackedHuman{
@@ -88,6 +65,81 @@ namespace armarx::navigation::human
         }
     }
 
+    /**
+     * @brief HumanTracker::getTrackedHumans Returns all humans that are currently tracked.
+     * @return  the tracked humans
+     */
+    std::vector<human::Human>
+    HumanTracker::getTrackedHumans() const
+    {
+        return trackedHumans |
+               ranges::views::transform([](const TrackedHuman& h) -> human::Human
+                                        { return h.humanFilter.get(); }) |
+               ranges::to_vector;
+    }
+
+    /**
+     * @brief HumanTracker::reset Resets this instance to the same state as if it just would have
+     * been created.
+     */
+    void
+    HumanTracker::reset()
+    {
+        trackedHumans.clear();
+    }
+
+
+    /**
+     * @brief convertHumanPoseToDetectedHuman Calculates all information necessary for a
+     * DetectedHuman from the given HumanPose and returns a new detected human.
+     * @param time The point in time where the detection was made.
+     * @param humanPose The HumanPose that should be converted to a DetectedHuman.
+     * @return A new DetectedHuman according to the HumanPose
+     */
+    HumanTracker::DetectedHuman
+    convertHumanPoseToDetectedHuman(const DateTime& time, const armem::human::HumanPose& humanPose)
+    {
+        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
+        ARMARX_CHECK_NOT_EMPTY(keypoints);
+
+        // calculate the arithmetic mean of all keypoint positions
+        Eigen::Vector3f centerPos;
+        int size = 0;
+        for (const auto& [_, v] : keypoints)
+        {
+            if (v.positionGlobal.has_value())
+            {
+                centerPos += v.positionGlobal.value().toEigen();
+                size++;
+            }
+        }
+        centerPos /= size;
+
+        // calculate the yaw of the head keypoint if it exists
+        double yaw = 0;
+        if (humanPose.keypoints.count("HEAD") > 0)
+        {
+            yaw = humanPose //from all human pose keypoints
+                      .keypoints
+                      .at("HEAD") //find the keypoint representing the head
+                      .orientationGlobal //get its global orientation
+                      ->toEigen()
+                      .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis)
+        }
+
+        // create the new pose with the calculated position and yaw
+        core::Pose2D pose = core::Pose2D::Identity();
+        pose.translation() = conv::to2D(centerPos);
+        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
+
+        return {pose, humanPose.humanTrackingId, time, false};
+    }
+
+
+    /**
+     * @brief The PosDistance struct contains a distance between an old, tracked human and a new,
+     * detected human aswell as references to them.
+     */
     struct PosDistance
     {
         HumanTracker::TrackedHuman* oldHuman;
@@ -95,6 +147,14 @@ namespace armarx::navigation::human
         float distance;
     };
 
+    /**
+     * @brief getSortedDistances Returns all distances sorted by their numeric value between
+     * possible combinations (T, D) where T is an old, tracked human and D is a new, detected human
+     * and T as well as D were not already associated
+     * @param oldHumans the old, tracked humans
+     * @param newHumans the new, detected humans
+     * @return the sorted distances, where the smallest distance is the first entry in the vector
+     */
     std::vector<PosDistance>
     getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
                        std::vector<HumanTracker::DetectedHuman>& newHumans)
@@ -113,6 +173,8 @@ namespace armarx::navigation::human
                 {
                     continue;
                 }
+                // calculate distance between every possible combination of tracked and detected
+                // humans where none of them was associated
                 posDistances.push_back(
                     {&oldHuman,
                      &newHuman,
@@ -121,6 +183,7 @@ namespace armarx::navigation::human
             }
         }
 
+        // sort the distances ascending by their numeric value
         std::sort(posDistances.begin(),
                   posDistances.end(),
                   [](const PosDistance& a, const PosDistance& b) -> bool
@@ -129,10 +192,16 @@ namespace armarx::navigation::human
         return posDistances;
     }
 
+    /**
+     * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
+     * belong together.
+     * @param detectedHumans The detected humans against which the saved list of tracked humans is
+     * matched.
+     */
     void
     HumanTracker::associateHumans(std::vector<DetectedHuman>& detectedHumans)
     {
-        // associate humans by their tracking id
+        // first, associate humans by their tracking id
         for (auto& oldHuman : trackedHumans)
         {
             if (oldHuman.associated || !oldHuman.trackingId)
@@ -145,6 +214,8 @@ namespace armarx::navigation::human
                 {
                     continue;
                 }
+                // check for every possible combination of old and new humans (that were not already
+                // associated and have a tracking id) if their tracking id is the same
                 if (oldHuman.trackingId.value() == newHuman.trackingId.value())
                 {
                     associate(&oldHuman, &newHuman);
@@ -152,8 +223,7 @@ namespace armarx::navigation::human
             }
         }
 
-
-        // associate leftover humans by their distances
+        // second, associate leftover humans by their distances
         const auto sortedDistances = getSortedDistances(trackedHumans, detectedHumans);
 
         for (auto& posDistance : sortedDistances)
@@ -166,10 +236,17 @@ namespace armarx::navigation::human
             {
                 continue;
             }
+            // associate the pair with the currently smallest distance between non-associated humans
             associate(posDistance.oldHuman, posDistance.newHuman);
         }
     }
 
+    /**
+     * @brief HumanTracker::associate Associates the given tracked and detected human. Therefore it
+     * updates all necessary variables of the TrackedHuman
+     * @param trackedHuman the tracked human
+     * @param detectedHuman the detected human
+     */
     void
     HumanTracker::associate(TrackedHuman* trackedHuman, DetectedHuman* detectedHuman)
     {
@@ -183,20 +260,4 @@ namespace armarx::navigation::human
         trackedHuman->trackingId = detectedHuman->trackingId;
     }
 
-    std::vector<human::Human>
-    HumanTracker::getTrackedHumans() const
-    {
-        return trackedHumans |
-               ranges::views::transform([](const TrackedHuman& h) -> human::Human
-                                        { return h.humanFilter.get(); }) |
-               ranges::to_vector;
-    }
-
-
-    void
-    HumanTracker::reset()
-    {
-        trackedHumans.clear();
-    }
-
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 3c4cc28f..311817b4 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -39,6 +39,12 @@ namespace armarx::navigation::human
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
 
+    /**
+     * @brief The HumanTracker class can be used to track and filter multiple humans. It hides
+     * implementation detail on how new detected humans are associated to the old, already tracked
+     * humans. New detected humans can be fed by using the update method. The tracked humans can
+     * be obtained using the getTrackedHumans method.
+     */
     class HumanTracker
     {
     public:
@@ -67,11 +73,14 @@ namespace armarx::navigation::human
 
         struct Parameters
         {
-            // the duration after which tracked humans will be erased if no new measurement for this human is found
+            // the duration after which tracked humans will be erased if no new measurement for
+            // this human is found
             Duration maxTrackingAge = Duration::MilliSeconds(500);
-            // the maximum distance in millimeters of two human measurements to be associated with each other
+            // the maximum distance in millimeters of two human measurements where they are still
+            // associated with each other
             float maxAssociationDistance = 600;
-            // alpha value from interval [0,1] to determine how much the new (and respectively the old) velocity should be weighted
+            // alpha value from interval [0,1] to determine how much the current (and respectively
+            // the old) velocity should be weighted when calculating the new velocity
             float velocityAlpha = 0.7;
         };
 
@@ -84,6 +93,9 @@ namespace armarx::navigation::human
     private:
         void associateHumans(std::vector<DetectedHuman>& detectedHumans);
         void associate(TrackedHuman* tracked, DetectedHuman* detected);
+        HumanTracker::DetectedHuman
+        convertHumanPoseToDetectedHuman(const DateTime& time,
+                                        const armem::human::HumanPose& humanPose);
 
     private:
         std::vector<TrackedHuman> trackedHumans;
-- 
GitLab


From ae6a9eb530c3d1212fa08b96554937eef77e2ae1 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 21 Sep 2022 19:54:53 +0200
Subject: [PATCH 222/324] Move method descriptions from cpp to h files

---
 .../armarx/navigation/human/HumanFilter.cpp   | 23 --------
 source/armarx/navigation/human/HumanFilter.h  | 24 +++++++-
 .../armarx/navigation/human/HumanTracker.cpp  | 56 ++-----------------
 source/armarx/navigation/human/HumanTracker.h | 38 ++++++++++++-
 4 files changed, 62 insertions(+), 79 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index e45d942a..570203b6 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -3,12 +3,6 @@
 namespace armarx::navigation::human
 {
 
-    /**
-     * @brief HumanFilter::HumanFilter creates a new filter that filters 2D poses (position and
-     * rotation in a two dimensional plane)
-     * @param pose0 the first known pose of the human
-     * @param detectionTime the point of detection
-     */
     HumanFilter::HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime)
     {
         //initialize new human for detected human
@@ -42,12 +36,6 @@ namespace armarx::navigation::human
         ukf = std::make_unique<UnscentedKalmanFilter<SystemModelT>>(Q, R, alpha, state0, P0);
     }
 
-    /**
-     * @brief HumanFilter::propagation propagate the system model to the given point in time. This
-     * means that the human pose is updated according to the filters prediction for the given point
-     * in time
-     * @param detectionTime the point in time for which the pose should be predicted
-     */
     void
     HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
     {
@@ -60,12 +48,6 @@ namespace armarx::navigation::human
         human.pose = fromUkfState(ukf->getCurrentState());
     }
 
-    /**
-     * @brief HumanFilter::update update the filter a new detected pose of the tracked human and
-     * the detection time
-     * @param pose the new detected pose of the human
-     * @param detectionTime the detection time
-     */
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
@@ -91,11 +73,6 @@ namespace armarx::navigation::human
         human.linearVelocity = newVelocity;
     }
 
-    /**
-     * @brief HumanFilter::get returns the human whose pose is filtered containing the most recent
-     * state
-     * @return the human
-     */
     const Human&
     HumanFilter::get() const
     {
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index 749750d4..998b491b 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -53,11 +53,33 @@ namespace armarx::navigation::human
             float velocityAlpha = 0.7;
         };
 
+        /**
+         * @brief HumanFilter::HumanFilter creates a new filter that filters 2D poses (position and
+         * rotation in a two dimensional plane)
+         * @param pose0 the first known pose of the human
+         * @param detectionTime the point of detection
+         */
         HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime);
 
+        /**
+         * @brief HumanFilter::propagation propagate the system model to the given point in time. This
+         * means that the human pose is updated according to the filters prediction for the given point
+         * in time
+         * @param detectionTime the point in time for which the pose should be predicted
+         */
         void propagation(const DateTime& detectionTime);
+        /**
+         * @brief HumanFilter::update update the filter a new detected pose of the tracked human and
+         * the detection time
+         * @param pose the new detected pose of the human
+         * @param detectionTime the detection time
+         */
         void update(const core::Pose2D& pose, const DateTime& detectionTime);
-
+        /**
+         * @brief HumanFilter::get returns the human whose pose is filtered containing the most recent
+         * state
+         * @return the human
+         */
         const Human& get() const;
 
     private:
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index dd6ecfc4..c1baf749 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -9,14 +9,6 @@
 
 namespace armarx::navigation::human
 {
-    /**
-     * @brief HumanTracker::update Updates the tracked humans with the measurements. When a
-     * measurement is close enough to an existing tracked human, they are associated, otherwise a
-     * new tracked human is created. Tracked humans that were not associated with a new measurement
-     * for a specified amount of time are removed. New associated measurements for a tracked human
-     * are always filtered to provide a less noisy state.
-     * @param measurements the new measurements of the environment
-     */
     void
     HumanTracker::update(const Measurements& measurements)
     {
@@ -65,10 +57,6 @@ namespace armarx::navigation::human
         }
     }
 
-    /**
-     * @brief HumanTracker::getTrackedHumans Returns all humans that are currently tracked.
-     * @return  the tracked humans
-     */
     std::vector<human::Human>
     HumanTracker::getTrackedHumans() const
     {
@@ -78,10 +66,6 @@ namespace armarx::navigation::human
                ranges::to_vector;
     }
 
-    /**
-     * @brief HumanTracker::reset Resets this instance to the same state as if it just would have
-     * been created.
-     */
     void
     HumanTracker::reset()
     {
@@ -89,13 +73,6 @@ namespace armarx::navigation::human
     }
 
 
-    /**
-     * @brief convertHumanPoseToDetectedHuman Calculates all information necessary for a
-     * DetectedHuman from the given HumanPose and returns a new detected human.
-     * @param time The point in time where the detection was made.
-     * @param humanPose The HumanPose that should be converted to a DetectedHuman.
-     * @return A new DetectedHuman according to the HumanPose
-     */
     HumanTracker::DetectedHuman
     convertHumanPoseToDetectedHuman(const DateTime& time, const armem::human::HumanPose& humanPose)
     {
@@ -135,11 +112,6 @@ namespace armarx::navigation::human
         return {pose, humanPose.humanTrackingId, time, false};
     }
 
-
-    /**
-     * @brief The PosDistance struct contains a distance between an old, tracked human and a new,
-     * detected human aswell as references to them.
-     */
     struct PosDistance
     {
         HumanTracker::TrackedHuman* oldHuman;
@@ -147,14 +119,6 @@ namespace armarx::navigation::human
         float distance;
     };
 
-    /**
-     * @brief getSortedDistances Returns all distances sorted by their numeric value between
-     * possible combinations (T, D) where T is an old, tracked human and D is a new, detected human
-     * and T as well as D were not already associated
-     * @param oldHumans the old, tracked humans
-     * @param newHumans the new, detected humans
-     * @return the sorted distances, where the smallest distance is the first entry in the vector
-     */
     std::vector<PosDistance>
     getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
                        std::vector<HumanTracker::DetectedHuman>& newHumans)
@@ -192,25 +156,19 @@ namespace armarx::navigation::human
         return posDistances;
     }
 
-    /**
-     * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
-     * belong together.
-     * @param detectedHumans The detected humans against which the saved list of tracked humans is
-     * matched.
-     */
     void
     HumanTracker::associateHumans(std::vector<DetectedHuman>& detectedHumans)
     {
         // first, associate humans by their tracking id
         for (auto& oldHuman : trackedHumans)
         {
-            if (oldHuman.associated || !oldHuman.trackingId)
+            if (oldHuman.associated || not oldHuman.trackingId)
             {
                 continue;
             }
             for (auto& newHuman : detectedHumans)
             {
-                if (newHuman.associated || !newHuman.trackingId)
+                if (newHuman.associated || not newHuman.trackingId)
                 {
                     continue;
                 }
@@ -241,17 +199,11 @@ namespace armarx::navigation::human
         }
     }
 
-    /**
-     * @brief HumanTracker::associate Associates the given tracked and detected human. Therefore it
-     * updates all necessary variables of the TrackedHuman
-     * @param trackedHuman the tracked human
-     * @param detectedHuman the detected human
-     */
     void
     HumanTracker::associate(TrackedHuman* trackedHuman, DetectedHuman* detectedHuman)
     {
-        ARMARX_CHECK(!trackedHuman->associated);
-        ARMARX_CHECK(!detectedHuman->associated);
+        ARMARX_CHECK(not trackedHuman->associated);
+        ARMARX_CHECK(not detectedHuman->associated);
 
         trackedHuman->associated = true;
         detectedHuman->associated = true;
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 311817b4..580e6840 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -83,16 +83,48 @@ namespace armarx::navigation::human
             // the old) velocity should be weighted when calculating the new velocity
             float velocityAlpha = 0.7;
         };
-
+        /**
+         * @brief HumanTracker::update Updates the tracked humans with the measurements. When a
+         * measurement is close enough to an existing tracked human, they are associated, otherwise a
+         * new tracked human is created. Tracked humans that were not associated with a new measurement
+         * for a specified amount of time are removed. New associated measurements for a tracked human
+         * are always filtered to provide a less noisy state.
+         * @param measurements the new measurements of the environment
+         */
         void update(const Measurements& measurements);
-
+        /**
+         * @brief HumanTracker::getTrackedHumans Returns all humans that are currently tracked.
+         * @return  the tracked humans
+         */
         std::vector<human::Human> getTrackedHumans() const;
-
+        /**
+         * @brief HumanTracker::reset Resets this instance to the same state as if it just would have
+         * been created.
+         */
         void reset();
 
     private:
+        /**
+         * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
+         * belong together.
+         * @param detectedHumans The detected humans against which the saved list of tracked humans is
+         * matched.
+         */
         void associateHumans(std::vector<DetectedHuman>& detectedHumans);
+        /**
+         * @brief HumanTracker::associate Associates the given tracked and detected human. Therefore it
+         * updates all necessary variables of the TrackedHuman
+         * @param trackedHuman the tracked human
+         * @param detectedHuman the detected human
+         */
         void associate(TrackedHuman* tracked, DetectedHuman* detected);
+        /**
+         * @brief convertHumanPoseToDetectedHuman Calculates all information necessary for a
+         * DetectedHuman from the given HumanPose and returns a new detected human.
+         * @param time The point in time where the detection was made.
+         * @param humanPose The HumanPose that should be converted to a DetectedHuman.
+         * @return A new DetectedHuman according to the HumanPose
+         */
         HumanTracker::DetectedHuman
         convertHumanPoseToDetectedHuman(const DateTime& time,
                                         const armem::human::HumanPose& humanPose);
-- 
GitLab


From 44fbd12ca112e94dc0592971afcfa0eaf64b33e2 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Wed, 21 Sep 2022 21:09:59 +0200
Subject: [PATCH 223/324] Change calculation of orientation

---
 .../armarx/navigation/human/HumanTracker.cpp  | 96 +++++++++++--------
 source/armarx/navigation/human/HumanTracker.h | 10 --
 2 files changed, 56 insertions(+), 50 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index c1baf749..f9149a09 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -9,6 +9,61 @@
 
 namespace armarx::navigation::human
 {
+    HumanTracker::DetectedHuman
+    convertHumanPoseToDetectedHuman(const DateTime& time, const armem::human::HumanPose& humanPose)
+    {
+        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
+        ARMARX_CHECK_NOT_EMPTY(keypoints);
+
+        // calculate the arithmetic mean of all keypoint positions
+        Eigen::Vector3f centerPos;
+        int size = 0;
+        for (const auto& [_, v] : keypoints)
+        {
+            if (v.positionGlobal.has_value())
+            {
+                centerPos += v.positionGlobal.value().toEigen();
+                size++;
+            }
+        }
+        centerPos /= size;
+
+        // calculate the yaw of the head keypoint if it exists
+        double yaw = 0;
+        if (humanPose.keypoints.count("HEAD") > 0)
+        {
+            Eigen::Quaternionf qhead =
+                humanPose.keypoints.at("HEAD").orientationGlobal->toEigenQuaternion();
+            //TODO not quite sure if the quaternion operates this way as it is not further defined
+            // on https://learn.microsoft.com/de-de/azure/kinect-dk/body-joints
+            Eigen::Vector3f vec(0, 1, 0);
+            Eigen::Vector3f rot3 = qhead._transformVector(vec);
+            Eigen::Vector2f rot2(rot3.y(), rot3.z());
+            if (rot2.norm() != 0)
+            {
+                rot2.normalize();
+                // calculate angle between e1 and rot2
+                yaw = atan2(rot2.y(), rot2.x() * rot2.y());
+            }
+            //old version using euler angles:
+            //yaw = humanPose //from all human pose keypoints
+            //          .keypoints
+            //          .at("HEAD") //find the keypoint representing the head
+            //          .orientationGlobal //get its global orientation
+            //          ->toEigen()
+            //          .eulerAngles(2, 1, 0)[2]; //and extract the yaw (rotation around x axis
+            //                                          should be z axis in global coordinates)
+        }
+
+        // create the new pose with the calculated position and yaw
+        core::Pose2D pose = core::Pose2D::Identity();
+        pose.translation() = conv::to2D(centerPos);
+        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
+
+        return {pose, humanPose.humanTrackingId, time, false};
+    }
+
+
     void
     HumanTracker::update(const Measurements& measurements)
     {
@@ -35,7 +90,7 @@ namespace armarx::navigation::human
         std::vector<DetectedHuman> newPoses =
             measurements.humanPoses |
             ranges::views::transform(
-                [measurements, this](const armem::human::HumanPose& humanPose) -> DetectedHuman {
+                [measurements](const armem::human::HumanPose& humanPose) -> DetectedHuman {
                     return convertHumanPoseToDetectedHuman(measurements.detectionTime, humanPose);
                 }) |
             ranges::to_vector;
@@ -73,45 +128,6 @@ namespace armarx::navigation::human
     }
 
 
-    HumanTracker::DetectedHuman
-    convertHumanPoseToDetectedHuman(const DateTime& time, const armem::human::HumanPose& humanPose)
-    {
-        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
-        ARMARX_CHECK_NOT_EMPTY(keypoints);
-
-        // calculate the arithmetic mean of all keypoint positions
-        Eigen::Vector3f centerPos;
-        int size = 0;
-        for (const auto& [_, v] : keypoints)
-        {
-            if (v.positionGlobal.has_value())
-            {
-                centerPos += v.positionGlobal.value().toEigen();
-                size++;
-            }
-        }
-        centerPos /= size;
-
-        // calculate the yaw of the head keypoint if it exists
-        double yaw = 0;
-        if (humanPose.keypoints.count("HEAD") > 0)
-        {
-            yaw = humanPose //from all human pose keypoints
-                      .keypoints
-                      .at("HEAD") //find the keypoint representing the head
-                      .orientationGlobal //get its global orientation
-                      ->toEigen()
-                      .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis)
-        }
-
-        // create the new pose with the calculated position and yaw
-        core::Pose2D pose = core::Pose2D::Identity();
-        pose.translation() = conv::to2D(centerPos);
-        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
-
-        return {pose, humanPose.humanTrackingId, time, false};
-    }
-
     struct PosDistance
     {
         HumanTracker::TrackedHuman* oldHuman;
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 580e6840..ffd0bf2b 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -118,16 +118,6 @@ namespace armarx::navigation::human
          * @param detectedHuman the detected human
          */
         void associate(TrackedHuman* tracked, DetectedHuman* detected);
-        /**
-         * @brief convertHumanPoseToDetectedHuman Calculates all information necessary for a
-         * DetectedHuman from the given HumanPose and returns a new detected human.
-         * @param time The point in time where the detection was made.
-         * @param humanPose The HumanPose that should be converted to a DetectedHuman.
-         * @return A new DetectedHuman according to the HumanPose
-         */
-        HumanTracker::DetectedHuman
-        convertHumanPoseToDetectedHuman(const DateTime& time,
-                                        const armem::human::HumanPose& humanPose);
 
     private:
         std::vector<TrackedHuman> trackedHumans;
-- 
GitLab


From bfa269f6b2b6ea27c2f40c148a99982bc6e668cd Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 11:37:20 +0200
Subject: [PATCH 224/324] Add oldHuman to be able to call propagation multiple
 times between two update calls

---
 source/armarx/navigation/human/HumanFilter.cpp |  8 +++++---
 source/armarx/navigation/human/HumanFilter.h   | 12 ++++++++++--
 2 files changed, 15 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index 570203b6..ba786d13 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -40,18 +40,18 @@ namespace armarx::navigation::human
     HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
     {
         double dt = (detectionTime - human.detectionTime).toSecondsDouble();
-        oldPose = human.pose;
 
         SystemModelT::ControlT control = toUkfControl(human.linearVelocity);
         ukf->propagation(control, dt);
 
         human.pose = fromUkfState(ukf->getCurrentState());
+        human.detectionTime = detectionTime;
     }
 
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
-        double dt = (detectionTime - human.detectionTime).toSecondsDouble();
+        double dt = (detectionTime - oldHuman.detectionTime).toSecondsDouble();
 
         //update ukf with new observation
         SystemModelT::ObsT observation = toUkfObs(pose);
@@ -60,7 +60,7 @@ namespace armarx::navigation::human
         core::Pose2D newPose = fromUkfState(ukf->getCurrentState());
 
         // calculate velocity
-        Eigen::Vector2f ds = newPose.translation() - oldPose.translation();
+        Eigen::Vector2f ds = newPose.translation() - oldHuman.pose.translation();
         Eigen::Vector2f linVelocity = ds / dt;
         // apply exponential smoothing to velocity
         //TODO try other approaches?
@@ -71,6 +71,8 @@ namespace armarx::navigation::human
         human.detectionTime = detectionTime;
         human.pose = newPose;
         human.linearVelocity = newVelocity;
+
+        oldHuman = human;
     }
 
     const Human&
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index 998b491b..ceb13aa1 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -64,7 +64,7 @@ namespace armarx::navigation::human
         /**
          * @brief HumanFilter::propagation propagate the system model to the given point in time. This
          * means that the human pose is updated according to the filters prediction for the given point
-         * in time
+         * in time. Should be called at most once between every two calls of HumanFilter::update.
          * @param detectionTime the point in time for which the pose should be predicted
          */
         void propagation(const DateTime& detectionTime);
@@ -92,7 +92,15 @@ namespace armarx::navigation::human
 
     private:
         Parameters params;
-        core::Pose2D oldPose;
+        /**
+         * @brief oldHuman stores information about the human at the point in time of the last
+         * HumanFilter::update call
+         */
+        Human oldHuman;
+        /**
+         * @brief human stores information about the human at the point in time of the last
+         * HumanFilter::propagation call
+         */
         Human human;
         std::unique_ptr<UnscentedKalmanFilter<SystemModelT>> ukf;
     };
-- 
GitLab


From 50d0594d9deb5b5fea69fe8b340c1f408f73f5d9 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 12:10:47 +0200
Subject: [PATCH 225/324] Fix calculation of humans rotation

---
 .../armarx/navigation/human/HumanTracker.cpp  | 20 +++++++++----------
 1 file changed, 9 insertions(+), 11 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index f9149a09..0d5d85fe 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -32,18 +32,16 @@ namespace armarx::navigation::human
         double yaw = 0;
         if (humanPose.keypoints.count("HEAD") > 0)
         {
-            Eigen::Quaternionf qhead =
-                humanPose.keypoints.at("HEAD").orientationGlobal->toEigenQuaternion();
-            //TODO not quite sure if the quaternion operates this way as it is not further defined
-            // on https://learn.microsoft.com/de-de/azure/kinect-dk/body-joints
-            Eigen::Vector3f vec(0, 1, 0);
+            const armem::human::PoseKeypoint& headKeypoint = humanPose.keypoints.at("HEAD");
+            ARMARX_CHECK(headKeypoint.orientationGlobal.has_value());
+            Eigen::Quaternionf qhead = headKeypoint.orientationGlobal->toEigenQuaternion();
+            Eigen::Vector3f vec(1, 0, 0);
             Eigen::Vector3f rot3 = qhead._transformVector(vec);
-            Eigen::Vector2f rot2(rot3.y(), rot3.z());
+            Eigen::Vector2f rot2(rot3.x(), rot3.y());
             if (rot2.norm() != 0)
             {
-                rot2.normalize();
-                // calculate angle between e1 and rot2
-                yaw = atan2(rot2.y(), rot2.x() * rot2.y());
+                // calculate angle of rot2
+                yaw = atan2(rot2.y(), rot2.x());
             }
             //old version using euler angles:
             //yaw = humanPose //from all human pose keypoints
@@ -51,8 +49,8 @@ namespace armarx::navigation::human
             //          .at("HEAD") //find the keypoint representing the head
             //          .orientationGlobal //get its global orientation
             //          ->toEigen()
-            //          .eulerAngles(2, 1, 0)[2]; //and extract the yaw (rotation around x axis
-            //                                          should be z axis in global coordinates)
+            //          .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis in
+            //                                                                  global coordinates)
         }
 
         // create the new pose with the calculated position and yaw
-- 
GitLab


From cdcf9d01a5fceabe228870226a879d58b711dfb8 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 12:41:54 +0200
Subject: [PATCH 226/324] Make convertHumanPoseToDetectedHuman a class method

---
 .../armarx/navigation/human/HumanTracker.cpp  | 110 +++++++++---------
 source/armarx/navigation/human/HumanTracker.h |  14 ++-
 2 files changed, 69 insertions(+), 55 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 0d5d85fe..4cc4e75b 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -9,59 +9,6 @@
 
 namespace armarx::navigation::human
 {
-    HumanTracker::DetectedHuman
-    convertHumanPoseToDetectedHuman(const DateTime& time, const armem::human::HumanPose& humanPose)
-    {
-        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
-        ARMARX_CHECK_NOT_EMPTY(keypoints);
-
-        // calculate the arithmetic mean of all keypoint positions
-        Eigen::Vector3f centerPos;
-        int size = 0;
-        for (const auto& [_, v] : keypoints)
-        {
-            if (v.positionGlobal.has_value())
-            {
-                centerPos += v.positionGlobal.value().toEigen();
-                size++;
-            }
-        }
-        centerPos /= size;
-
-        // calculate the yaw of the head keypoint if it exists
-        double yaw = 0;
-        if (humanPose.keypoints.count("HEAD") > 0)
-        {
-            const armem::human::PoseKeypoint& headKeypoint = humanPose.keypoints.at("HEAD");
-            ARMARX_CHECK(headKeypoint.orientationGlobal.has_value());
-            Eigen::Quaternionf qhead = headKeypoint.orientationGlobal->toEigenQuaternion();
-            Eigen::Vector3f vec(1, 0, 0);
-            Eigen::Vector3f rot3 = qhead._transformVector(vec);
-            Eigen::Vector2f rot2(rot3.x(), rot3.y());
-            if (rot2.norm() != 0)
-            {
-                // calculate angle of rot2
-                yaw = atan2(rot2.y(), rot2.x());
-            }
-            //old version using euler angles:
-            //yaw = humanPose //from all human pose keypoints
-            //          .keypoints
-            //          .at("HEAD") //find the keypoint representing the head
-            //          .orientationGlobal //get its global orientation
-            //          ->toEigen()
-            //          .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis in
-            //                                                                  global coordinates)
-        }
-
-        // create the new pose with the calculated position and yaw
-        core::Pose2D pose = core::Pose2D::Identity();
-        pose.translation() = conv::to2D(centerPos);
-        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
-
-        return {pose, humanPose.humanTrackingId, time, false};
-    }
-
-
     void
     HumanTracker::update(const Measurements& measurements)
     {
@@ -88,7 +35,7 @@ namespace armarx::navigation::human
         std::vector<DetectedHuman> newPoses =
             measurements.humanPoses |
             ranges::views::transform(
-                [measurements](const armem::human::HumanPose& humanPose) -> DetectedHuman {
+                [measurements, this](const armem::human::HumanPose& humanPose) -> DetectedHuman {
                     return convertHumanPoseToDetectedHuman(measurements.detectionTime, humanPose);
                 }) |
             ranges::to_vector;
@@ -170,6 +117,61 @@ namespace armarx::navigation::human
         return posDistances;
     }
 
+
+    HumanTracker::DetectedHuman
+    HumanTracker::convertHumanPoseToDetectedHuman(const DateTime& time,
+                                                  const armem::human::HumanPose& humanPose)
+    {
+        const std::map<std::string, armem::human::PoseKeypoint>& keypoints = humanPose.keypoints;
+        ARMARX_CHECK_NOT_EMPTY(keypoints);
+
+        // calculate the arithmetic mean of all keypoint positions
+        Eigen::Vector3f centerPos;
+        int size = 0;
+        for (const auto& [_, v] : keypoints)
+        {
+            if (v.positionGlobal.has_value())
+            {
+                centerPos += v.positionGlobal.value().toEigen();
+                size++;
+            }
+        }
+        centerPos /= size;
+
+        // calculate the yaw of the specified keypoint representing the orientation if it exists
+        double yaw = 0;
+        if (humanPose.keypoints.count(parameters.rotationKeypoint) > 0)
+        {
+            const armem::human::PoseKeypoint& refKeypoint =
+                humanPose.keypoints.at(parameters.rotationKeypoint);
+            ARMARX_CHECK(refKeypoint.orientationGlobal.has_value());
+            Eigen::Quaternionf qhead = refKeypoint.orientationGlobal->toEigenQuaternion();
+            Eigen::Vector3f vec(1, 0, 0);
+            Eigen::Vector3f rot3 = qhead._transformVector(vec);
+            Eigen::Vector2f rot2(rot3.x(), rot3.y());
+            if (rot2.norm() != 0)
+            {
+                // calculate angle of rot2
+                yaw = atan2(rot2.y(), rot2.x());
+            }
+            //old version using euler angles:
+            //yaw = humanPose //from all human pose keypoints
+            //          .keypoints
+            //          .at("HEAD") //find the keypoint representing the head
+            //          .orientationGlobal //get its global orientation
+            //          ->toEigen()
+            //          .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis in
+            //                                                                  global coordinates)
+        }
+
+        // create the new pose with the calculated position and yaw
+        core::Pose2D pose = core::Pose2D::Identity();
+        pose.translation() = conv::to2D(centerPos);
+        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
+
+        return {pose, humanPose.humanTrackingId, time, false};
+    }
+
     void
     HumanTracker::associateHumans(std::vector<DetectedHuman>& detectedHumans)
     {
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index ffd0bf2b..f2e3cd8e 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -35,7 +35,7 @@
 
 namespace armarx::navigation::human
 {
-    using T = double; //TODO double or float?
+    using T = double;
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
 
@@ -73,6 +73,8 @@ namespace armarx::navigation::human
 
         struct Parameters
         {
+            // the keypoint which should be used for calculating the rotation of the humans
+            const std::string rotationKeypoint = "HEAD";
             // the duration after which tracked humans will be erased if no new measurement for
             // this human is found
             Duration maxTrackingAge = Duration::MilliSeconds(500);
@@ -104,6 +106,15 @@ namespace armarx::navigation::human
         void reset();
 
     private:
+        /**
+         * @brief convertHumanPoseToDetectedHuman Sets every parameter of a detected human according
+         * to the human pose and returns the new created detected human.
+         * @param time the time of detection
+         * @param humanPose the human pose representing the human
+         * @return the new created detected human
+         */
+        DetectedHuman convertHumanPoseToDetectedHuman(const DateTime& time,
+                                                      const armem::human::HumanPose& humanPose);
         /**
          * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
          * belong together.
@@ -119,6 +130,7 @@ namespace armarx::navigation::human
          */
         void associate(TrackedHuman* tracked, DetectedHuman* detected);
 
+
     private:
         std::vector<TrackedHuman> trackedHumans;
         Parameters parameters;
-- 
GitLab


From a073a12196730a0c3d03c6816d5dd2b67734cf87 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 12:48:24 +0200
Subject: [PATCH 227/324] Make getSortedDistances a class method

---
 .../armarx/navigation/human/HumanTracker.cpp  | 84 +++++++++----------
 source/armarx/navigation/human/HumanTracker.h | 19 +++++
 2 files changed, 57 insertions(+), 46 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 4cc4e75b..2332377e 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -73,51 +73,6 @@ namespace armarx::navigation::human
     }
 
 
-    struct PosDistance
-    {
-        HumanTracker::TrackedHuman* oldHuman;
-        HumanTracker::DetectedHuman* newHuman;
-        float distance;
-    };
-
-    std::vector<PosDistance>
-    getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
-                       std::vector<HumanTracker::DetectedHuman>& newHumans)
-    {
-        std::vector<PosDistance> posDistances;
-
-        for (auto& oldHuman : oldHumans)
-        {
-            if (oldHuman.associated)
-            {
-                continue;
-            }
-            for (auto& newHuman : newHumans)
-            {
-                if (newHuman.associated)
-                {
-                    continue;
-                }
-                // calculate distance between every possible combination of tracked and detected
-                // humans where none of them was associated
-                posDistances.push_back(
-                    {&oldHuman,
-                     &newHuman,
-                     (newHuman.pose.translation() - oldHuman.humanFilter.get().pose.translation())
-                         .norm()});
-            }
-        }
-
-        // sort the distances ascending by their numeric value
-        std::sort(posDistances.begin(),
-                  posDistances.end(),
-                  [](const PosDistance& a, const PosDistance& b) -> bool
-                  { return a.distance < b.distance; });
-
-        return posDistances;
-    }
-
-
     HumanTracker::DetectedHuman
     HumanTracker::convertHumanPoseToDetectedHuman(const DateTime& time,
                                                   const armem::human::HumanPose& humanPose)
@@ -157,7 +112,7 @@ namespace armarx::navigation::human
             //old version using euler angles:
             //yaw = humanPose //from all human pose keypoints
             //          .keypoints
-            //          .at("HEAD") //find the keypoint representing the head
+            //          .at(parameters.rotationKeypoint) //find the keypoint representing the head
             //          .orientationGlobal //get its global orientation
             //          ->toEigen()
             //          .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis in
@@ -172,6 +127,43 @@ namespace armarx::navigation::human
         return {pose, humanPose.humanTrackingId, time, false};
     }
 
+    std::vector<HumanTracker::PosDistance>
+    HumanTracker::getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
+                                     std::vector<HumanTracker::DetectedHuman>& newHumans)
+    {
+        std::vector<PosDistance> posDistances;
+
+        for (auto& oldHuman : oldHumans)
+        {
+            if (oldHuman.associated)
+            {
+                continue;
+            }
+            for (auto& newHuman : newHumans)
+            {
+                if (newHuman.associated)
+                {
+                    continue;
+                }
+                // calculate distance between every possible combination of tracked and detected
+                // humans where none of them was associated
+                posDistances.push_back(
+                    {&oldHuman,
+                     &newHuman,
+                     (newHuman.pose.translation() - oldHuman.humanFilter.get().pose.translation())
+                         .norm()});
+            }
+        }
+
+        // sort the distances ascending by their numeric value
+        std::sort(posDistances.begin(),
+                  posDistances.end(),
+                  [](const PosDistance& a, const PosDistance& b) -> bool
+                  { return a.distance < b.distance; });
+
+        return posDistances;
+    }
+
     void
     HumanTracker::associateHumans(std::vector<DetectedHuman>& detectedHumans)
     {
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index f2e3cd8e..1a83fb65 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -71,6 +71,13 @@ namespace armarx::navigation::human
             bool associated;
         };
 
+        struct PosDistance
+        {
+            HumanTracker::TrackedHuman* oldHuman;
+            HumanTracker::DetectedHuman* newHuman;
+            float distance;
+        };
+
         struct Parameters
         {
             // the keypoint which should be used for calculating the rotation of the humans
@@ -115,6 +122,18 @@ namespace armarx::navigation::human
          */
         DetectedHuman convertHumanPoseToDetectedHuman(const DateTime& time,
                                                       const armem::human::HumanPose& humanPose);
+        /**
+         * @brief getSortedDistances Returns a sorted vector of the distances between every possible
+         * combination (T, D) where T is an old, tracked human and D is a new, detected human and
+         * both of them are not already associated. The smallest distance will be the first entry in
+         * the vector
+         * @param oldHumans the old, tracked humans
+         * @param newHumans the new, detected humans
+         * @return the sorted vector of distances with references to the according humans
+         */
+        std::vector<PosDistance>
+        getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
+                           std::vector<HumanTracker::DetectedHuman>& newHumans);
         /**
          * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
          * belong together.
-- 
GitLab


From f4e5ea12cfe6976f0e78d88b5b24c9ae3bc18a5d Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 17:33:22 +0200
Subject: [PATCH 228/324] Add file for kalman filter tests

---
 source/armarx/navigation/human/CMakeLists.txt | 14 +++++++++++++
 .../human/test/kalman_filter_test.cpp         | 20 +++++++++++++++++++
 2 files changed, 34 insertions(+)
 create mode 100644 source/armarx/navigation/human/test/kalman_filter_test.cpp

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 14deaae1..7ecd7127 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -84,3 +84,17 @@ armarx_add_test(se3_kalman_test
             ukfm
             sciplot::sciplot
 )
+
+
+armarx_add_test(human_test
+    TEST_FILES
+        test/kalman_filter_test.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::core
+            armarx_navigation::teb_human
+
+        PRIVATE
+            range-v3::range-v3
+)
diff --git a/source/armarx/navigation/human/test/kalman_filter_test.cpp b/source/armarx/navigation/human/test/kalman_filter_test.cpp
new file mode 100644
index 00000000..885374fe
--- /dev/null
+++ b/source/armarx/navigation/human/test/kalman_filter_test.cpp
@@ -0,0 +1,20 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Corvin Navarro Ecker ( corvin dot ecker at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
-- 
GitLab


From fc5d357f69845c6f0bbe83c9bda51986c7dd7dd6 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 22 Sep 2022 19:06:55 +0200
Subject: [PATCH 229/324] Fix costmap conversion

Convert armarx costmap from mm to m to teb.
---
 .../local_planner_config/TimedElasticBands/default.json     | 2 +-
 source/armarx/navigation/local_planning/ros_conversions.cpp | 6 ++++--
 2 files changed, 5 insertions(+), 3 deletions(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 34d3506a..4265bf31 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -6,7 +6,7 @@
     "pse": {
       "pse_costum_obstacle_penalties": true,
       "pse_costum_obstacle_penalties_dynamic": true,
-      "weight_costmap": 0.5,
+      "weight_costmap": 1,
       "weight_global_path_position": 0.3,
       "weight_global_path_orientation": 0.3,
       "lrk_use_alternative_approach": false,
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 91736c32..2303b64c 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -185,8 +185,10 @@ namespace armarx::navigation::conv
         teb_local_planner::Costmap::Pose2D teb_origin = costmap.origin();
         teb_origin.translation() /= 1000; // [mm] to[m]
 
-        return teb_local_planner::Costmap{
-            costmap.getGrid(), teb_params, teb_bounds, teb_mask, teb_origin};
+        algorithms::Costmap::Grid teb_grid = costmap.getGrid();
+        teb_grid /= 1000; // [mm] to [m]
+
+        return teb_local_planner::Costmap{teb_grid, teb_params, teb_bounds, teb_mask, teb_origin};
     }
 
 } // namespace armarx::navigation::conv
-- 
GitLab


From da60b8ca1bbdce1c7ce451ce632b0f08851283cf Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 22 Sep 2022 19:15:21 +0200
Subject: [PATCH 230/324] Add penalty model conversions

---
 source/armarx/navigation/human/types.h            |  6 ++++++
 .../local_planning/TebObstacleManager.cpp         |  7 +++----
 .../navigation/local_planning/ros_conversions.cpp | 15 +++++++++++++++
 .../navigation/local_planning/ros_conversions.h   |  9 +++++++--
 4 files changed, 31 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/human/types.h b/source/armarx/navigation/human/types.h
index fe5490d5..0c3e0804 100644
--- a/source/armarx/navigation/human/types.h
+++ b/source/armarx/navigation/human/types.h
@@ -57,6 +57,12 @@ namespace armarx::navigation::human
 
     using HumanGroups = std::vector<HumanGroup>;
 
+    struct LinearPenaltyModel
+    {
+        float minDistance; // [m]
+        float epsilon; // [m]
+    };
+
     struct ExponentialPenaltyModel
     {
         float minDistance; // [m]
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index 8f82f74d..add2038f 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -70,9 +70,7 @@ namespace armarx::navigation::local_planning
 
             const auto& penalty = proxemicZone.penalty;
 
-            obst->setPenaltyModel(boost::make_shared<teb_local_planner::ExponentialPenaltyModel>(
-                teb_local_planner::LinearPenaltyModel(penalty.minDistance, penalty.epsilon),
-                penalty.exponent));
+            obst->setPenaltyModel(conv::toRos(penalty));
 
             obst->setWeight(proxemicZone.weight);
             obst->setHomotopicRelevance(proxemicZone.homotopicRelevance);
@@ -87,7 +85,8 @@ namespace armarx::navigation::local_planning
             // visualize proxemic zone if layer is available
             if (visLayer != nullptr)
             {
-                const Eigen::Vector3f axisLength(proxemicZone.shape.a, proxemicZone.shape.b, 10.f-i);
+                const Eigen::Vector3f axisLength(
+                    proxemicZone.shape.a, proxemicZone.shape.b, 10.f - i);
                 const core::Pose pose3d = conv::to3D(proxemicZone.pose);
 
                 visLayer->add(viz::Ellipsoid("proxemicZone_" + std::to_string(visualizationIndex++))
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 2303b64c..657db4c4 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -191,4 +191,19 @@ namespace armarx::navigation::conv
         return teb_local_planner::Costmap{teb_grid, teb_params, teb_bounds, teb_mask, teb_origin};
     }
 
+    teb_local_planner::PenaltyModelPtr
+    toRos(const human::LinearPenaltyModel& model)
+    {
+        return boost::make_shared<teb_local_planner::LinearPenaltyModel>(
+            teb_local_planner::LinearPenaltyModel(model.minDistance, model.epsilon));
+    }
+
+    teb_local_planner::PenaltyModelPtr
+    toRos(const human::ExponentialPenaltyModel& model)
+    {
+        return boost::make_shared<teb_local_planner::ExponentialPenaltyModel>(
+            teb_local_planner::LinearPenaltyModel(model.minDistance, model.epsilon),
+            model.exponent);
+    }
+
 } // namespace armarx::navigation::conv
diff --git a/source/armarx/navigation/local_planning/ros_conversions.h b/source/armarx/navigation/local_planning/ros_conversions.h
index 05b52e77..083ddcc5 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.h
+++ b/source/armarx/navigation/local_planning/ros_conversions.h
@@ -21,14 +21,15 @@
 
 #pragma once
 
+#include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/human/shapes.h>
 #include <geometry_msgs/Twist.h>
+#include <teb_local_planner/costmap.h>
+#include <teb_local_planner/penalty_models.h>
 #include <teb_local_planner/pose_se2.h>
 #include <teb_local_planner/timed_elastic_band.h>
-#include <teb_local_planner/costmap.h>
-#include <armarx/navigation/algorithms/Costmap.h>
 
 namespace armarx::navigation::conv
 {
@@ -53,4 +54,8 @@ namespace armarx::navigation::conv
 
     teb_local_planner::Costmap toRos(const algorithms::Costmap& costmap);
 
+    teb_local_planner::PenaltyModelPtr toRos(const human::LinearPenaltyModel& model);
+
+    teb_local_planner::PenaltyModelPtr toRos(const human::ExponentialPenaltyModel& model);
+
 } // namespace armarx::navigation::conv
-- 
GitLab


From 2188d923d6e63466058a81289a31ca9eafb70d50 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Thu, 22 Sep 2022 19:16:28 +0200
Subject: [PATCH 231/324] Add costmap with custom penalty to optimization

---
 .../navigation/human/ProxemicZoneCreator.cpp      | 15 ++++++++++-----
 .../local_planning/TebObstacleManager.cpp         |  1 +
 .../local_planning/TimedElasticBands.cpp          | 13 ++++++++++---
 3 files changed, 21 insertions(+), 8 deletions(-)

diff --git a/source/armarx/navigation/human/ProxemicZoneCreator.cpp b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
index 8a6aac53..acd453fa 100644
--- a/source/armarx/navigation/human/ProxemicZoneCreator.cpp
+++ b/source/armarx/navigation/human/ProxemicZoneCreator.cpp
@@ -9,10 +9,13 @@ namespace armarx::navigation::human
     ProxemicZoneCreator::createProxemicZones(const Human& human)
     {
         // intimate zone
-        ProxemicZone intimate{.pose = human.pose,
-                              .shape = {.a = params.intimateRadius, .b = params.intimateRadius},
-                              .penalty = intimatePenalty,
-                              .weight = params.intimateWeight};
+        ProxemicZone intimate{
+            .pose = human.pose,
+            .shape = {.a = params.intimateRadius, .b = params.intimateRadius},
+            .penalty = intimatePenalty,
+            .weight = params.intimateWeight,
+            .homotopicRelevance = true,
+        };
 
         // personal zone
         auto& global_R_human = human.pose.linear();
@@ -38,7 +41,9 @@ namespace armarx::navigation::human
             .pose = pose,
             .shape = {.a = params.personalRadius, .b = movementStretch * params.personalRadius},
             .penalty = personalPenalty,
-            .weight = params.personalWeight};
+            .weight = params.personalWeight,
+            .homotopicRelevance = false,
+        };
 
         return {intimate, personal};
     }
diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index add2038f..e2402e12 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -37,6 +37,7 @@ namespace armarx::navigation::local_planning
         obst->pushBackVertex(max.x(), min.y());
 
         obst->finalizePolygon();
+        obst->setUseForOptimization(false);
         container.push_back(obst);
 
         // visualize bounding box if layer is available
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 7bd970f0..8f86171a 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -1,4 +1,5 @@
 #include "TimedElasticBands.h"
+
 #include <optional>
 
 #include <SimoxUtility/algorithm/apply.hpp>
@@ -68,10 +69,16 @@ namespace armarx::navigation::local_planning
 
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
         hcp_->initialize(
-            cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);       
+            cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);
         //set member teb_costmap
         setTebCostmap();
-        if (teb_costmap) {
+        if (teb_costmap)
+        {
+            // TODO: where to put all the parameters
+            const human::ExponentialPenaltyModel penalty{
+                .minDistance = 0.5, .epsilon = 0, .exponent = 1.2};
+
+            teb_costmap->setPenaltyModel(conv::toRos(penalty));
             hcp_->setCostmap(&teb_costmap.value());
         }
         ros::Time::init(); // we have to init time before we can use the planner
@@ -130,7 +137,7 @@ namespace armarx::navigation::local_planning
             return {};
         }
 
-        if(hcp_->getTrajectoryContainer().empty())
+        if (hcp_->getTrajectoryContainer().empty())
         {
             ARMARX_VERBOSE << "Did not find any trajectory!";
             return std::nullopt;
-- 
GitLab


From 9b8d0be53ba934a8c7928ee3d0116488ad532e4c Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 22 Sep 2022 19:31:14 +0200
Subject: [PATCH 232/324] Write test case for kalman filter

---
 source/armarx/navigation/human/CMakeLists.txt |  2 +-
 .../human/test/kalman_filter_test.cpp         | 92 +++++++++++++++++++
 2 files changed, 93 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 7ecd7127..4cf568f3 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -86,7 +86,7 @@ armarx_add_test(se3_kalman_test
 )
 
 
-armarx_add_test(human_test
+armarx_add_test(kalman_filter_test
     TEST_FILES
         test/kalman_filter_test.cpp
     DEPENDENCIES
diff --git a/source/armarx/navigation/human/test/kalman_filter_test.cpp b/source/armarx/navigation/human/test/kalman_filter_test.cpp
index 885374fe..04cf7c69 100644
--- a/source/armarx/navigation/human/test/kalman_filter_test.cpp
+++ b/source/armarx/navigation/human/test/kalman_filter_test.cpp
@@ -18,3 +18,95 @@
  * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
  *             GNU General Public License
  */
+
+#include <ArmarXCore/core/time/DateTime.h>
+
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/HumanFilter.h>
+#include <armarx/navigation/human/types.h>
+
+// test includes
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
+#define ARMARX_BOOST_TEST
+
+#include <armarx/navigation/Test.h>
+
+using armarx::navigation::core::Pose2D;
+using Eigen::Vector2f;
+
+namespace armarx::navigation::human
+{
+    Pose2D
+    generatePose(double x, double y, double yaw)
+    {
+        Pose2D pose = Pose2D::Identity();
+        pose.translation() = Eigen::Vector2f(x, y);
+        pose.linear() = Eigen::Rotation2Df(yaw).toRotationMatrix();
+
+        return pose;
+    }
+
+    DateTime
+    generateTime(double time)
+    {
+        return DateTime(time);
+    }
+
+    double
+    extractRotation(const Pose2D& pose)
+    {
+        return Eigen::Rotation2Df(pose.linear()).angle();
+    }
+
+
+    bool
+    doublesEqual(const double d1, const double d2, const double relErr)
+    {
+        if (d1 == 0)
+        {
+            return d2 == 0;
+        }
+        return std::abs(d1 - d2) / d1 <= relErr;
+    }
+
+    bool
+    posesEqual(const Pose2D& p1, const Pose2D& p2, const double relErr)
+    {
+        return doublesEqual(p1.translation().x(), p2.translation().x(), relErr) &&
+               doublesEqual(p1.translation().y(), p2.translation().y(), relErr) &&
+               doublesEqual(extractRotation(p1), extractRotation(p2), relErr);
+    }
+
+    bool
+    vectorsEqual(const Vector2f& v1, const Vector2f v2, const double relErr)
+    {
+        return doublesEqual(v1.x(), v2.x(), relErr) && doublesEqual(v1.y(), v2.y(), relErr);
+    }
+
+    bool
+    timesEqual(const DateTime& t1, const DateTime& t2, const double relErr)
+    {
+        return doublesEqual(t1.toMilliSecondsSinceEpoch(), t2.toMilliSecondsSinceEpoch(), relErr);
+    }
+
+    bool
+    humansEqual(const Human& h1, const Human& h2, const double relErr)
+    {
+        return posesEqual(h1.pose, h2.pose, relErr) &&
+               vectorsEqual(h1.linearVelocity, h2.linearVelocity, relErr) &&
+               timesEqual(h1.detectionTime, h2.detectionTime, relErr);
+    }
+
+
+    BOOST_AUTO_TEST_CASE(testInitialization)
+    {
+        HumanFilter filter(generatePose(3, 2, 1), generateTime(4));
+
+        Human human{.pose = generatePose(3, 2, 1),
+                    .linearVelocity = Vector2f::Zero(),
+                    .detectionTime = generateTime(4)};
+
+        BOOST_TEST(humansEqual(filter.get(), human, 0.001),
+                   "filter should not have changed humans initial pose properties");
+    }
+} // namespace armarx::navigation::human
-- 
GitLab


From 84cb65920cff918e75c0af61451318bee2c309c2 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 26 Sep 2022 09:55:47 +0200
Subject: [PATCH 233/324] minor fixes (code style)

---
 .../navigation/local_planning/TimedElasticBands.cpp    | 10 ++++++++--
 1 file changed, 8 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 8f86171a..86f63c95 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -221,10 +221,16 @@ namespace armarx::navigation::local_planning
     void
     TimedElasticBands::setTebCostmap()
     {
-        if (!scene.staticScene)
+        if (not scene.staticScene.has_value())
+        {
             return;
-        if (!scene.staticScene->distanceToObstaclesCostmap)
+        }
+        
+        if (not scene.staticScene->distanceToObstaclesCostmap.has_value())
+        {
             return;
+        }
+
         const algorithms::Costmap& navigationCostmap =
             scene.staticScene->distanceToObstaclesCostmap.value();
         teb_costmap.emplace(conv::toRos(navigationCostmap));
-- 
GitLab


From cf963bf52da7f9c3327b4c233dae9b15ae987373 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 27 Sep 2022 13:32:24 +0200
Subject: [PATCH 234/324] simulating humans using RVO2

---
 CMakeLists.txt                                |   2 +
 .../config/example_client.cfg                 |  18 +-
 .../config/human_simulator.cfg                |  44 ++-
 .../config/navigation_memory.cfg              |   4 +-
 .../components/human_simulator/CMakeLists.txt |   3 +
 .../components/human_simulator/Component.cpp  | 254 +++++++++++++++---
 .../components/human_simulator/Component.h    |  34 ++-
 .../navigation/simulation/SimulatedHuman.cpp  |  63 ++++-
 .../navigation/simulation/SimulatedHuman.h    |  35 ++-
 9 files changed, 386 insertions(+), 71 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 308bddb1..fc6e0627 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -39,6 +39,8 @@ armarx_find_package(PUBLIC VTK QUIET)
 armarx_find_package(PUBLIC SemanticObjectRelations QUIET)
 armarx_find_package(PUBLIC OpenCV QUIET)  # Required as RobotAPI is a legacy project.
 armarx_find_package(PUBLIC range-v3 QUIET)
+armarx_find_package(PUBLIC HRVO QUIET)
+armarx_find_package(PUBLIC RVO QUIET)
 
 # human aware navigation
 armarx_find_package(PUBLIC teb_local_planner QUIET)
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
index c21733bd..ea5576f6 100644
--- a/scenarios/HumanAwareNavigation/config/example_client.cfg
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -194,6 +194,22 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 # ArmarX.example_client.ObjectName = ""
 
 
+# ArmarX.example_client.mem.nav.costmap.CoreSegment:  
+#  Attributes:
+#  - Default:            Costmap
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mem.nav.costmap.CoreSegment = Costmap
+
+
+# ArmarX.example_client.mem.nav.costmap.Memory:  
+#  Attributes:
+#  - Default:            Navigation
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mem.nav.costmap.Memory = Navigation
+
+
 # ArmarX.example_client.mem.robot_state.Memory:  
 #  Attributes:
 #  - Default:            RobotState
@@ -233,7 +249,7 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 #  - Default:            standard
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {complex, point_to_point, standard, update_navigator}
+#  - Possible values: {complex, point_to_point, standard, update_navigator, wander_around}
 # ArmarX.example_client.mode = standard
 
 
diff --git a/scenarios/HumanAwareNavigation/config/human_simulator.cfg b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
index c0a571fa..d7720e7b 100644
--- a/scenarios/HumanAwareNavigation/config/human_simulator.cfg
+++ b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
@@ -157,7 +157,23 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+ArmarX.Verbosity = Verbose
+
+
+# ArmarX.human_simulator.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.human_simulator.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.ArVizTopicName = ArVizTopic
 
 
 # ArmarX.human_simulator.EnableProfiling:  enable profiler which is used for logging performance events
@@ -178,6 +194,14 @@
 # ArmarX.human_simulator.MinimumLoggingLevel = Undefined
 
 
+# ArmarX.human_simulator.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.ObjectMemoryName = ObjectMemory
+
+
 # ArmarX.human_simulator.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
@@ -260,12 +284,28 @@
 # ArmarX.human_simulator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
+# ArmarX.human_simulator.p.human.goalDistanceThreshold:  
+#  Attributes:
+#  - Default:            100
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.p.human.goalDistanceThreshold = 100
+
+
+# ArmarX.human_simulator.p.human.maxLinearVelocity:  
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.human_simulator.p.human.maxLinearVelocity = 200
+
+
 # ArmarX.human_simulator.p.nHumans:  Number of humans to spawn.
 #  Attributes:
 #  - Default:            4
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.human_simulator.p.nHumans = 4
+ArmarX.human_simulator.p.nHumans = 6
 
 
 # ArmarX.human_simulator.p.taskPeriodMs:  
diff --git a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
index a3e73f4f..45901d44 100644
--- a/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigation_memory.cfg
@@ -255,10 +255,10 @@ ArmarX.navigation_memory.MinimumLoggingLevel = Verbose
 
 # ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            2
+#  - Default:            10
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 2
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 10
 
 
 # ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
diff --git a/source/armarx/navigation/components/human_simulator/CMakeLists.txt b/source/armarx/navigation/components/human_simulator/CMakeLists.txt
index 3ea4392a..c5cb14c6 100644
--- a/source/armarx/navigation/components/human_simulator/CMakeLists.txt
+++ b/source/armarx/navigation/components/human_simulator/CMakeLists.txt
@@ -23,4 +23,7 @@ armarx_add_component(human_simulator
          armarx_navigation::dynamic_scene
          armarx_navigation::teb_human
          armarx_navigation::simulation
+
+        # HRVO::HRVO
+        RVO::RVO
 )
diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
index 3410013c..6ce73503 100644
--- a/source/armarx/navigation/components/human_simulator/Component.cpp
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -23,17 +23,28 @@
 
 #include "Component.h"
 
+#include <cstddef>
 #include <cstdlib>
 
+#include <SimoxUtility/color/Color.h>
+#include <VirtualRobot/CollisionDetection/CollisionModel.h>
 #include <VirtualRobot/Random.h>
+#include <VirtualRobot/SceneObjectSet.h>
 
 #include "ArmarXCore/core/logging/Logging.h"
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
+#include "RobotAPI/components/ArViz/Client/Elements.h"
+#include "RobotAPI/components/ArViz/Client/elements/Path.h"
+#include "RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h"
+
 #include "armarx/navigation/algorithms/Costmap.h"
 #include "armarx/navigation/core/basic_types.h"
 #include "armarx/navigation/human/types.h"
 #include "armarx/navigation/simulation/SimulatedHuman.h"
+#include "armarx/navigation/util/util.h"
+#include <RVOSimulator.h>
+#include <Vector2.h>
 
 // Include headers you only need in function definitions in the .cpp.
 
@@ -77,8 +88,9 @@ namespace armarx::navigation::components::human_simulator
         // Add an optionalproperty.
         def->optional(properties.taskPeriodMs, "p.taskPeriodMs", "");
         def->optional(properties.nHumans, "p.nHumans", "Number of humans to spawn.");
-        
-        def->optional(properties.humanParams.goalDistanceThreshold, "p.human.goalDistanceThreshold", "");
+
+        def->optional(
+            properties.humanParams.goalDistanceThreshold, "p.human.goalDistanceThreshold", "");
         def->optional(properties.humanParams.minLinearVelocity, "p.human.maxLinearVelocity", "");
         def->optional(properties.humanParams.maxLinearVelocity, "p.human.maxLinearVelocity", "");
 
@@ -96,40 +108,59 @@ namespace armarx::navigation::components::human_simulator
         // setDebugObserverBatchModeEnabled(true);
     }
 
-
     void
-    Component::onConnectComponent()
+    Component::setPreferredVelocities(RVO::RVOSimulator* simulator,
+                                      const std::vector<RVO::Vector2>& goals)
     {
-        // Do things after connecting to topics and components.
+        /* Set the preferred velocity to be a vector of unit magnitude (speed) in the
+   * direction of the goal. */
+        // #ifdef _OPENMP
+        // #pragma omp parallel for
+        // #endif /* _OPENMP */
 
-        /* (Requies the armarx::DebugObserverComponentPluginUser.)
-        // Use the debug observer to log data over time.
-        // The data can be viewed in the ObserverView and the LivePlotter.
-        // (Before starting any threads, we don't need to lock mutexes.)
+        for (int i = 0; i < static_cast<int>(properties.nHumans); ++i)
         {
-            setDebugObserverDatafield("numBoxes", properties.numBoxes);
-            setDebugObserverDatafield("boxLayerName", properties.boxLayerName);
-            sendDebugObserverBatch();
-        }
-        */
+            // RVO::Vector2 goalVector = goals[i] - simulator->getAgentPosition(i);
 
-        /* (Requires the armarx::ArVizComponentPluginUser.)
-        // Draw boxes in ArViz.
-        // (Before starting any threads, we don't need to lock mutexes.)
-        drawBoxes(properties, arviz);
-        */
+            // if (RVO::absSq(goalVector) > 1.0F)
+            // {
+            //     goalVector = RVO::normalize(goalVector);
+            // }
 
-        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
-        // Setup the remote GUI.
-        {
-            createRemoteGuiTab();
-            RemoteGui_startRunningTask();
-        }
-        */
+            const auto agentPosition = simulator->getAgentPosition(i);
+            auto& simulatedHuman = simulatedHumans.at(i);
+
+            core::Pose2D pose = core::Pose2D::Identity();
+            pose.translation().x() = agentPosition.x() * 1000; // [m] -> [mm]
+            pose.translation().y() = agentPosition.y() * 1000; // [m] -> [mm]
+
+            simulatedHuman.reinitialize(pose);
+
+            const std::vector<core::Position> trajectoryPoints =
+                simulatedHuman.trajectory().positions();
+
+            const std::size_t lookAheadGoalIdx = std::min(trajectoryPoints.size() - 1, 5ul);
+            const auto& intermediateGoal = trajectoryPoints.at(lookAheadGoalIdx);
 
+            const Eigen::Vector2f rvoGoalHelper = intermediateGoal.head<2>() / 1000; // [mm] -> [m]
 
-        ///
+            const RVO::Vector2 rvoGoal(rvoGoalHelper.x(), rvoGoalHelper.y());
 
+            RVO::Vector2 goalVector = rvoGoal - agentPosition;
+
+            if (RVO::absSq(goalVector) > 1.0F)
+            {
+                goalVector = RVO::normalize(goalVector);
+            }
+
+            simulator->setAgentPrefVelocity(i, goalVector);
+        }
+    }
+
+
+    void
+    Component::onConnectComponent()
+    {
         //
         //  Costmaps
         //
@@ -166,18 +197,120 @@ namespace armarx::navigation::components::human_simulator
             };
         }();
 
-        /// create humans
+        /// create simulation environment
+        {
+            ARMARX_INFO << "Creating sim";
 
-        simulatedHumans.clear();
+            simulator.setTimeStep(static_cast<float>(properties.taskPeriodMs) / 1000);
+            simulator.setAgentDefaults(15.0F, 10U, 1.5F, .1F, .4F, .5F);
 
-        for (std::size_t i = 0; i < properties.nHumans; i++)
-        {
-            simulatedHumans.emplace_back(costmap);
+            const objpose::ObjectPoseSeq obstacles =
+                ObjectPoseClientPluginUser::getObjectPosesByProvider(
+                    "R003_grasping_challenge_robot_placement_with_ivt_obstacles");
+
+            const auto objects = armarx::navigation::util::asSceneObjects(obstacles);
+
+
+            ARMARX_VERBOSE << obstacles.size() << " obstacles";
+
+            {
+                auto layer = arviz.layer("obstacles");
+
+
+                for (const auto& obst : objects->getCollisionModels())
+                {
+
+                    ARMARX_INFO << "adding obstacle ...";
+                    const VirtualRobot::BoundingBox bbox = obst->getGlobalBoundingBox();
+
+                    Eigen::Vector2f bbMin = bbox.getMin().head<2>();
+                    Eigen::Vector2f bbMax = bbox.getMax().head<2>();
+
+                    // add some margin to the obstacles
+                    const float margin = 100; // [mm]
+
+                    bbMin.x() -= margin;
+                    bbMin.y() -= margin;
+                    bbMax.x() += margin;
+                    bbMax.y() += margin;
+
+                    ARMARX_VERBOSE << "Bounding box: (" << bbMin.transpose() << "), ("
+                                   << bbMax.transpose() << ")";
+
+                    {
+                        constexpr float zHeight = 3; // [mm]
+
+                        viz::Polygon polygon(std::to_string(layer.size()));
+                        polygon.addPoint(Eigen::Vector3f{bbMin.x(), bbMin.y(), zHeight});
+                        polygon.addPoint(Eigen::Vector3f{bbMax.x(), bbMin.y(), zHeight});
+                        polygon.addPoint(Eigen::Vector3f{bbMax.x(), bbMax.y(), zHeight});
+                        polygon.addPoint(Eigen::Vector3f{bbMin.x(), bbMax.y(), zHeight});
+
+                        polygon.color(simox::Color::black());
+                        polygon.color(simox::Color::black());
+
+                        layer.add(polygon);
+                    }
+
+
+                    const Eigen::Vector2d min = bbMin.cast<double>() / 1000; // [mm] -> [m]
+                    const Eigen::Vector2d max = bbMax.cast<double>() / 1000; // [mm] -> [m]
+
+                    std::vector<RVO::Vector2> obstacle;
+                    obstacle.emplace_back(min.x(), min.y());
+                    obstacle.emplace_back(max.x(), min.y());
+                    obstacle.emplace_back(max.x(), max.y());
+                    obstacle.emplace_back(min.x(), max.y());
+
+                    simulator.addObstacle(obstacle);
+                }
+
+                arviz.commit(layer);
+            }
+
+            simulator.processObstacles();
         }
 
+        /// create humans in simulation
+        {
+            simulatedHumans.clear();
+
+            for (std::size_t i = 0U; i < properties.nHumans; ++i)
+            {
+                armarx::navigation::human::simulation::SimulatedHuman& human =
+                    simulatedHumans.emplace_back(costmap);
 
-        ///
+                const RVO::Vector2 position =
+                    RVO::Vector2(human.human().pose.translation().x() / 1000,
+                                 human.human().pose.translation().y() / 1000);
+                auto goal = human.trajectory().positions().back() / 1000; // [mm] -> [m]
 
+                ARMARX_VERBOSE << "Adding agent";
+                // simulator.addAgent(position, simulator.addGoal(hrvo::Vector2(goal.x(), goal.y())));
+                simulator.addAgent(
+                    position); // , simulator.addGoal(hrvo::Vector2(goal.x(), goal.y())));
+
+                goals.emplace_back(goal.x(), goal.y());
+            }
+        }
+
+        /// load robot and add it to the simulator
+        {
+            robot = virtualRobotReaderPlugin->get().getRobot(properties.robotName);
+            ARMARX_CHECK(
+                virtualRobotReaderPlugin->get().synchronizeRobot(*robot, armarx::Clock::Now()));
+
+            const auto robotPosH = robot->getGlobalPosition();
+            const RVO::Vector2 robotPos(robotPosH.x() / 1000, robotPosH.y() / 1000);
+
+            robotAgentId = simulator.addAgent(robotPos);
+            simulator.setAgentMaxSpeed(robotAgentId,
+                                       0); // we do not allow the robot to be perturbed
+            simulator.setAgentPrefVelocity(robotAgentId, RVO::Vector2(0, 0));
+            simulator.setAgentRadius(robotAgentId, 0.6);
+        }
+
+        /// start task
         task = new PeriodicTask<Component>(
             this, &Component::runPeriodically, properties.taskPeriodMs, false, "runningTask");
         task->start();
@@ -213,25 +346,58 @@ namespace armarx::navigation::components::human_simulator
     void
     Component::runPeriodically()
     {
-        // obtain data from perception
-
         const DateTime timestamp = Clock::Now();
 
-        //
-        // Robot
-        //
+        setPreferredVelocities(&simulator, goals);
 
-        // ARMARX_CHECK(virtualRobotReaderPlugin->get().synchronizeRobot(*robot, timestamp));
-        // const core::Pose global_T_robot(robot->getGlobalPose());
+        // TODO(fabian.reister): check how much the agents interact => this can be an evaluation criterion
 
-        // ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
+        // update robot
+        {
+            ARMARX_CHECK(
+                virtualRobotReaderPlugin->get().synchronizeRobot(*robot, armarx::Clock::Now()));
 
+            const auto robotPosH = robot->getGlobalPosition();
+            const RVO::Vector2 robotPos(robotPosH.x() / 1000, robotPosH.y() / 1000);
 
-        human::Humans humans;
+            simulator.setAgentPosition(robotAgentId, robotPos);
+        }
+
+        simulator.doStep();
+
+        // visualize paths
+        {
+            auto layer = arviz.layer("trajectories");
+            for (const auto& simulatedHuman : simulatedHumans)
+            {
+                viz::Path path(std::to_string(layer.size()));
+
+                for (const auto& pt : simulatedHuman.trajectory().points())
+                {
+                    path.addPoint(pt.waypoint.pose.translation());
+                }
 
-        for (auto& simulatedHuman : simulatedHumans)
+                // unique and distinct color for this human
+                path.colorGlasbeyLUT(layer.size());
+
+                layer.add(path);
+            }
+
+            arviz.commit(layer);
+        }
+
+
+        human::Humans humans;
+        for (std::size_t i = 0; i < properties.nHumans; i++)
         {
-            humans.push_back(simulatedHuman.update());
+            const auto pos = simulator.getAgentPosition(i);
+
+            human::Human human;
+            human.pose.setIdentity();
+            human.pose.translation().x() = pos.x() * 1000; // [m] -> [mm]
+            human.pose.translation().y() = pos.y() * 1000; // [m] -> [mm]
+
+            humans.push_back(human);
         }
 
         ARMARX_VERBOSE << "Updating humans.";
diff --git a/source/armarx/navigation/components/human_simulator/Component.h b/source/armarx/navigation/components/human_simulator/Component.h
index 52e7aadf..7235893d 100644
--- a/source/armarx/navigation/components/human_simulator/Component.h
+++ b/source/armarx/navigation/components/human_simulator/Component.h
@@ -26,33 +26,38 @@
 
 // #include <mutex>
 
+#include <string>
+#include <VirtualRobot/VirtualRobot.h>
 #include "ArmarXCore/core/services/tasks/PeriodicTask.h"
 #include <ArmarXCore/core/Component.h>
-#include "RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h"
 
+#include "RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h"
+#include "RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h"
 #include "RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h"
 
 // #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h>
 
 // #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
 
-// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
+#include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
-#include "armarx/navigation/simulation/SimulatedHuman.h"
 #include "armarx/navigation/memory/client/costmap/Reader.h"
 #include "armarx/navigation/memory/client/human/Writer.h"
+#include "armarx/navigation/simulation/SimulatedHuman.h"
+// #include <Simulator.h>
+#include "RVO.h"
 #include <armarx/navigation/components/human_simulator/ComponentInterface.h>
 
-
 namespace armarx::navigation::components::human_simulator
 {
 
     class Component :
         virtual public armarx::Component,
-        virtual public armarx::navigation::components::human_simulator::ComponentInterface
-    // , virtual public armarx::DebugObserverComponentPluginUser
-    // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
-    // , virtual public armarx::ArVizComponentPluginUser
+        virtual public armarx::navigation::components::human_simulator::ComponentInterface,
+        virtual public armarx::ObjectPoseClientPluginUser,
+        // , virtual public armarx::DebugObserverComponentPluginUser
+        // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
+        virtual public armarx::ArVizComponentPluginUser
     {
     public:
         Component();
@@ -106,6 +111,8 @@ namespace armarx::navigation::components::human_simulator
 
         void runPeriodically();
 
+        void setPreferredVelocities(RVO::RVOSimulator* simulator,
+                                    const std::vector<RVO::Vector2>& goals);
 
 
     private:
@@ -114,7 +121,6 @@ namespace armarx::navigation::components::human_simulator
         PeriodicTask<Component>::pointer_type task;
 
 
-
         // Private member variables go here.
 
 
@@ -127,6 +133,8 @@ namespace armarx::navigation::components::human_simulator
             std::size_t nHumans = 4;
 
             human::simulation::SimulatedHumanParams humanParams;
+
+            std::string robotName = "Armar6";
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
@@ -157,6 +165,9 @@ namespace armarx::navigation::components::human_simulator
         template <typename T>
         using ReaderWriterPlugin = armem::client::plugins::ReaderWriterPlugin<T>;
 
+        VirtualRobot::RobotPtr robot;
+
+        std::size_t robotAgentId;
 
         ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin =
             nullptr;
@@ -166,10 +177,13 @@ namespace armarx::navigation::components::human_simulator
 
         ReaderWriterPlugin<memory::client::human::Writer>* humanWriterPlugin = nullptr;
 
-    
+
         std::vector<human::simulation::SimulatedHuman> simulatedHumans;
 
+        // hrvo::Simulator simulator;
+        RVO::RVOSimulator simulator;
 
+        std::vector<RVO::Vector2> goals;
     };
 
 } // namespace armarx::navigation::components::human_simulator
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index 0a4d735d..857ad242 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -29,6 +29,7 @@
 #include "armarx/navigation/algorithms/util.h"
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/StaticScene.h"
+#include "armarx/navigation/core/basic_types.h"
 #include "armarx/navigation/core/types.h"
 #include "armarx/navigation/global_planning/SPFA.h"
 #include "armarx/navigation/human/types.h"
@@ -53,10 +54,7 @@ namespace armarx::navigation::human::simulation
 
                 step();
 
-                const Eigen::Vector2f goal =
-                    conv::to2D(globalTrajectory_.points().back().waypoint.pose.translation());
-
-                if ((goal - human_.pose.translation()).norm() < params_.goalDistanceThreshold)
+                if (goalReached())
                 {
                     ARMARX_INFO << "Human reached goal";
                     state_ = State::GoalReached;
@@ -75,6 +73,31 @@ namespace armarx::navigation::human::simulation
         return human_;
     }
 
+    bool
+    SimulatedHuman::goalReached() const
+    {
+        const Eigen::Vector2f goal =
+            conv::to2D(globalTrajectory_.points().back().waypoint.pose.translation());
+
+        return ((goal - human_.pose.translation()).norm() < params_.goalDistanceThreshold);
+    }
+
+    void
+    SimulatedHuman::reinitialize(const core::Pose2D& pose)
+    {
+        human_.pose = pose;
+
+        if(goalReached())
+        {
+            ARMARX_VERBOSE << "Goal reached";
+            state_ = State::Idle;
+        }
+
+        initialize();
+        update();
+
+    }
+
     void
     SimulatedHuman::initialize()
     {
@@ -88,14 +111,34 @@ namespace armarx::navigation::human::simulation
 
         global_planning::SPFA planner(params, scene);
 
-        const auto start = human_.pose;
+        const core::Pose2D start = human_.pose;
 
-        while (true)
+        if (state_ == State::Idle) // human reached goal and needs a new one
         {
-            const auto sampledPose = algorithms::sampleValidPositionInMap(distanceField_);
-            ARMARX_CHECK(sampledPose.has_value());
-            const auto& goal = sampledPose.value();
+            while (true)
+            {
+                const auto sampledPose = algorithms::sampleValidPositionInMap(distanceField_);
+                ARMARX_CHECK(sampledPose.has_value());
+                const core::Pose2D& goal = sampledPose.value();
+
+
+                const auto plan = planner.plan(conv::to3D(start), conv::to3D(goal));
+
+                // check if plan could be created. otherwise try another goal
+                if (plan.has_value())
+                {
+                    globalTrajectory_ = plan->trajectory;
 
+                    human_ = human::Human{.pose = start,
+                                          .linearVelocity = Eigen::Vector2f::Zero(),
+                                          .detectionTime = Clock::Now()};
+                    return;
+                }
+            }
+        }
+        else if (state_ == State::Walking) // human is walking and replans to existing goal
+        {
+            const auto goal = conv::to2D(globalTrajectory_.poses().back());
             const auto plan = planner.plan(conv::to3D(start), conv::to3D(goal));
 
             // check if plan could be created. otherwise try another goal
@@ -148,5 +191,7 @@ namespace armarx::navigation::human::simulation
         const auto sampledPose = algorithms::sampleValidPositionInMap(distanceField_);
         ARMARX_CHECK(sampledPose.has_value());
         human_.pose = sampledPose.value();
+
+        update(); // should bring the robot into walking state
     }
 } // namespace armarx::navigation::human::simulation
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.h b/source/armarx/navigation/simulation/SimulatedHuman.h
index fa4ed6a8..b1bdc556 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.h
+++ b/source/armarx/navigation/simulation/SimulatedHuman.h
@@ -31,10 +31,10 @@ namespace armarx::navigation::human::simulation
 
     struct SimulatedHumanParams
     {
-        float goalDistanceThreshold = 100;
+        float goalDistanceThreshold = 100; // [mm]
 
-        float minLinearVelocity = 100;
-        float maxLinearVelocity = 200;
+        float minLinearVelocity = 100; // [mm/s]
+        float maxLinearVelocity = 200; // [mm/s]
     };
 
     class SimulatedHuman
@@ -46,6 +46,34 @@ namespace armarx::navigation::human::simulation
 
         Human update();
 
+
+        human::Human&
+        human()
+        {
+            return human_;
+        }
+
+        core::GlobalTrajectory&
+        trajectory()
+        {
+            return globalTrajectory_;
+        }
+
+        const core::GlobalTrajectory&
+        trajectory() const
+        {
+            return globalTrajectory_;
+        }
+
+        bool goalReached() const;
+
+        /**
+         * @brief resets the human to the given pose and replans the global optimal trajectory
+         * 
+         * @param pose 
+         */
+        void reinitialize(const core::Pose2D& pose);
+
     protected:
         void initialize();
 
@@ -58,6 +86,7 @@ namespace armarx::navigation::human::simulation
             GoalReached
         };
 
+
     private:
         const algorithms::Costmap distanceField_;
 
-- 
GitLab


From 8e5faf80a2498729d285e0ead3cce5bbb507de38 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 28 Sep 2022 10:09:15 +0200
Subject: [PATCH 235/324] making spfa algorithms accessible via aron and spfa
 params struct

---
 .../navigation/algorithms/CMakeLists.txt      |  1 +
 .../ShortestPathFasterAlgorithmParams.xml     | 23 ++++++++++++++++
 .../algorithms/aron_conversions.cpp           | 26 +++++++++++++++++--
 .../navigation/algorithms/aron_conversions.h  | 10 +++++++
 .../armarx/navigation/global_planning/SPFA.h  |  3 +++
 .../global_planning/aron/SPFAParams.xml       |  5 ++++
 .../global_planning/aron_conversions.cpp      |  4 +++
 .../navigation/simulation/SimulatedHuman.cpp  |  2 ++
 8 files changed, 72 insertions(+), 2 deletions(-)
 create mode 100644 source/armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.xml

diff --git a/source/armarx/navigation/algorithms/CMakeLists.txt b/source/armarx/navigation/algorithms/CMakeLists.txt
index 23422ec5..abdba073 100644
--- a/source/armarx/navigation/algorithms/CMakeLists.txt
+++ b/source/armarx/navigation/algorithms/CMakeLists.txt
@@ -1,6 +1,7 @@
 armarx_add_aron_library(algorithms_aron
     ARON_FILES
         aron/Costmap.xml
+        aron/ShortestPathFasterAlgorithmParams.xml
 )
 
 armarx_add_library(algorithms
diff --git a/source/armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.xml b/source/armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.xml
new file mode 100644
index 00000000..91f0b6a6
--- /dev/null
+++ b/source/armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.xml
@@ -0,0 +1,23 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <AronIncludes>
+    </AronIncludes>
+
+    <GenerateTypes>
+        <Object name='armarx::navigation::algorithms::arondto::ShortestPathFasterAlgorithmParams'>
+             <ObjectChild key='obstacleDistanceCosts'>
+                <bool />
+            </ObjectChild>
+            <ObjectChild key='obstacleMaxDistance'>
+                <float />
+            </ObjectChild>
+            <ObjectChild key='obstacleDistanceWeight'>
+                <float />
+            </ObjectChild>
+            <ObjectChild key='obstacleCostExponent'>
+                <float />
+            </ObjectChild>
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
diff --git a/source/armarx/navigation/algorithms/aron_conversions.cpp b/source/armarx/navigation/algorithms/aron_conversions.cpp
index 031170ef..6580d25a 100644
--- a/source/armarx/navigation/algorithms/aron_conversions.cpp
+++ b/source/armarx/navigation/algorithms/aron_conversions.cpp
@@ -2,10 +2,11 @@
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/util/util.h>
-#include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
+#include <RobotAPI/libraries/core/FramedPose.h>
 
 #include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.aron.generated.h>
 #include <armarx/navigation/conversions/eigen.h>
 
 
@@ -70,7 +71,7 @@ namespace armarx::navigation::algorithms
         ARMARX_DEBUG << "Converting grid";
         const auto gridNavigator =
             aron::data::NDArray::DynamicCast(entityInstance.data()->getElement("grid"));
-       
+
         ARMARX_CHECK_NOT_NULL(gridNavigator);
 
         Costmap::Grid grid =
@@ -95,5 +96,26 @@ namespace armarx::navigation::algorithms
         return {grid, parameters, sceneBounds, mask};
     }
 
+    void
+    toAron(arondto::ShortestPathFasterAlgorithmParams& dto,
+           const spfa::ShortestPathFasterAlgorithm::Parameters& bo)
+    {
+        dto.obstacleDistanceCosts = bo.obstacleDistanceCosts;
+        dto.obstacleMaxDistance = bo.obstacleMaxDistance;
+        dto.obstacleDistanceWeight = bo.obstacleDistanceWeight;
+        dto.obstacleCostExponent = bo.obstacleCostExponent;
+    }
+
+
+    void
+    fromAron(const arondto::ShortestPathFasterAlgorithmParams& dto,
+             spfa::ShortestPathFasterAlgorithm::Parameters& bo)
+    {
+        bo.obstacleDistanceCosts = dto.obstacleDistanceCosts;
+        bo.obstacleMaxDistance = dto.obstacleMaxDistance;
+        bo.obstacleDistanceWeight = dto.obstacleDistanceWeight;
+        bo.obstacleCostExponent = dto.obstacleCostExponent;
+    }
+
 
 } // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/algorithms/aron_conversions.h b/source/armarx/navigation/algorithms/aron_conversions.h
index 4c91b833..531412d2 100644
--- a/source/armarx/navigation/algorithms/aron_conversions.h
+++ b/source/armarx/navigation/algorithms/aron_conversions.h
@@ -22,6 +22,7 @@
 #pragma once
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
 
@@ -43,5 +44,14 @@ namespace armarx::navigation::algorithms
     // Costmap does not provide a default c'tor
     Costmap fromAron(const armem::wm::EntityInstance& entityInstance);
 
+    namespace arondto
+    {
+        class ShortestPathFasterAlgorithmParams;
+    }
+
+    void toAron(arondto::ShortestPathFasterAlgorithmParams& dto, const spfa::ShortestPathFasterAlgorithm::Parameters& bo);
+    
+    void fromAron(const arondto::ShortestPathFasterAlgorithmParams& dto, spfa::ShortestPathFasterAlgorithm::Parameters& bo);
+
 
 } // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/global_planning/SPFA.h b/source/armarx/navigation/global_planning/SPFA.h
index c0900376..2246f92b 100644
--- a/source/armarx/navigation/global_planning/SPFA.h
+++ b/source/armarx/navigation/global_planning/SPFA.h
@@ -24,6 +24,8 @@
 
 #include <VirtualRobot/MathTools.h>
 #include "GlobalPlanner.h"
+#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
+#include "armarx/navigation/global_planning/core.h"
 #include <armarx/navigation/core/types.h>
 
 namespace armarx::navigation::global_planning
@@ -45,6 +47,7 @@ namespace armarx::navigation::global_planning
 
         float resampleDistance{-1};
 
+        algorithms::spfa::ShortestPathFasterAlgorithm::Parameters algo;
 
 
         Algorithms algorithm() const override;
diff --git a/source/armarx/navigation/global_planning/aron/SPFAParams.xml b/source/armarx/navigation/global_planning/aron/SPFAParams.xml
index 63b61b6f..c1b2869f 100644
--- a/source/armarx/navigation/global_planning/aron/SPFAParams.xml
+++ b/source/armarx/navigation/global_planning/aron/SPFAParams.xml
@@ -2,6 +2,7 @@
 <AronTypeDefinition>
     <AronIncludes>
         <Include include="armarx/navigation/global_planning/aron/GlobalPlannerParams.xml" />
+        <Include include="armarx/navigation/algorithms/aron/ShortestPathFasterAlgorithmParams.xml" />
     </AronIncludes>
 
     <GenerateTypes>
@@ -15,6 +16,10 @@
                 <float />
             </ObjectChild>
 
+            <ObjectChild key='algo'>
+                <armarx::navigation::algorithms::arondto::ShortestPathFasterAlgorithmParams/>
+            </ObjectChild>
+
         </Object>
 
 
diff --git a/source/armarx/navigation/global_planning/aron_conversions.cpp b/source/armarx/navigation/global_planning/aron_conversions.cpp
index 358efefc..ef57566f 100644
--- a/source/armarx/navigation/global_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/global_planning/aron_conversions.cpp
@@ -4,6 +4,7 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
 
+#include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/global_planning/AStar.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/global_planning/Point2Point.h>
@@ -69,6 +70,7 @@ namespace armarx::navigation::global_planning::aron_conv
 
         aron::toAron(dto.linearVelocity, bo.linearVelocity);
         aron::toAron(dto.resampleDistance, bo.resampleDistance);
+        algorithms::toAron(dto.algo, bo.algo);
     }
 
     void
@@ -79,6 +81,8 @@ namespace armarx::navigation::global_planning::aron_conv
 
         aron::fromAron(dto.linearVelocity, bo.linearVelocity);
         aron::fromAron(dto.resampleDistance, bo.resampleDistance);
+
+        algorithms::fromAron(dto.algo, bo.algo);
     }
 
 } // namespace armarx::navigation::global_planning::aron_conv
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index 857ad242..f008cccd 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -26,6 +26,7 @@
 #include "ArmarXCore/core/logging/Logging.h"
 
 #include "armarx/navigation/algorithms/Costmap.h"
+#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
 #include "armarx/navigation/algorithms/util.h"
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/StaticScene.h"
@@ -103,6 +104,7 @@ namespace armarx::navigation::human::simulation
     {
         global_planning::SPFA::Params params;
         params.linearVelocity = this->params_.maxLinearVelocity;
+        params.algo.obstacleDistanceWeight = 1.1F;
 
         core::Scene scene;
 
-- 
GitLab


From 3a6e01b93a8fa01ce3b8ab864677f7b82019ad84 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 28 Sep 2022 10:16:16 +0200
Subject: [PATCH 236/324] navigator: exposing additional params

---
 .../navigation/components/navigator/Component.cpp  | 14 ++++++--------
 .../navigation/components/navigator/Component.h    |  2 ++
 2 files changed, 8 insertions(+), 8 deletions(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 3509d2f3..d1d6abb4 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -170,14 +170,7 @@ namespace armarx::navigation::components::navigator
                 .humanReader = &humanReaderPlugin->get(),
                 .objectPoseClient = ObjectPoseClientPluginUser::getClient()};
 
-            const std::string robotName = getControlComponentPlugin()
-                                              .getRobotUnitPlugin()
-                                              .getRobotUnit()
-                                              ->getKinematicUnit()
-                                              ->getRobotName();
-
-            const server::scene_provider::SceneProvider::Config cfg{.robotName = robotName};
-            sceneProvider.emplace(srv, cfg);
+            sceneProvider.emplace(srv, params.sceneCfg);
         }
 
         initializeScene();
@@ -491,6 +484,11 @@ namespace armarx::navigation::components::navigator
                       "If the executor is disabled, the navigator will only plan the trajectory "
                       "but won't execute it.");
 
+        def->required(params.sceneCfg.robotName, "p.scene.robotName");
+        def->optional(params.sceneCfg.staticCostmapProviderName, "p.scene.staticCostmapProviderName");
+        def->optional(params.sceneCfg.staticCostmapName, "p.scene.staticCostmapName");
+        def->optional(params.sceneCfg.humanProviderName, "p.scene.humanProviderName");
+
         return def;
     }
 
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index 5e552d7f..e601f796 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -223,6 +223,8 @@ namespace armarx::navigation::components::navigator
         {
             float occupiedGridThreshold{0.55F};
             bool disableExecutor{false};
+
+            server::scene_provider::SceneProvider::Config sceneCfg;
         };
 
         Parameters params;
-- 
GitLab


From 66e0811b5610013187b191681e4b282059443e62 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 14:39:09 +0200
Subject: [PATCH 237/324] reducing verbosity

---
 source/armarx/navigation/algorithms/Costmap.cpp |  8 ++------
 .../navigation/algorithms/CostmapBuilder.cpp    | 17 +++++++++--------
 .../algorithms/astar/AStarPlanner.cpp           |  6 +++---
 .../navigation/algorithms/persistence.cpp       |  2 +-
 source/armarx/navigation/core/Trajectory.cpp    |  4 ++--
 .../armarx/navigation/global_planning/SPFA.cpp  |  4 ++--
 .../optimization/OrientationOptimizer.cpp       | 10 +++++-----
 .../local_planning/TimedElasticBands.cpp        |  3 +++
 8 files changed, 27 insertions(+), 27 deletions(-)

diff --git a/source/armarx/navigation/algorithms/Costmap.cpp b/source/armarx/navigation/algorithms/Costmap.cpp
index 0a6c5a32..5644c818 100644
--- a/source/armarx/navigation/algorithms/Costmap.cpp
+++ b/source/armarx/navigation/algorithms/Costmap.cpp
@@ -197,13 +197,11 @@ namespace armarx::navigation::algorithms
     bool
     Costmap::add(const Costmap& other, const float weight)
     {
-        ARMARX_INFO << "1";
         // ensure that both grid and mask are the same size
         ARMARX_TRACE;
 
         validateSizes();
         other.validateSizes();
-        ARMARX_INFO << "1";
 
         const auto startIdx = toVertex(other.sceneBounds.min);
 
@@ -213,7 +211,6 @@ namespace armarx::navigation::algorithms
         // In this case, only add the part to this costmap that is possible.
         const int rows = std::min(other.grid.rows(), grid.rows() - startIdx.index.x());
         const int cols = std::min(other.grid.cols(), grid.cols() - startIdx.index.y());
-        ARMARX_INFO << "1";
 
         ARMARX_VERBOSE << "Adding other grid to region (" << startIdx.index.x() << ", "
                        << startIdx.index.y() << "), "
@@ -221,7 +218,6 @@ namespace armarx::navigation::algorithms
                        << ")";
 
         ARMARX_TRACE;
-        ARMARX_INFO << "1";
 
         // add the costs of the other mask to this one by a weighting factor
         grid.block(startIdx.index.x(), startIdx.index.y(), rows, cols).array() +=
@@ -369,7 +365,7 @@ namespace armarx::navigation::algorithms
     std::optional<float>
     Costmap::value(const Position& position) const
     {
-        ARMARX_INFO << "value ...";
+        ARMARX_DEBUG << "value ...";
 
         const auto v = toVertex(position);
         return value(v.index);
@@ -384,7 +380,7 @@ namespace armarx::navigation::algorithms
         const std::vector<float> costmapWeights(weights.begin(), weights.end() - 1);
         ARMARX_CHECK_EQUAL(costmapWeights.size(), costmaps.size());
 
-        ARMARX_INFO << "Merging into with weights " << weights;
+        ARMARX_VERBOSE << "Merging into with weights " << weights;
 
         Costmap mergedCostmap = *this;
 
diff --git a/source/armarx/navigation/algorithms/CostmapBuilder.cpp b/source/armarx/navigation/algorithms/CostmapBuilder.cpp
index 6321398e..3bd21a56 100644
--- a/source/armarx/navigation/algorithms/CostmapBuilder.cpp
+++ b/source/armarx/navigation/algorithms/CostmapBuilder.cpp
@@ -61,13 +61,13 @@ namespace armarx::navigation::algorithms
         const auto sceneBounds = computeSceneBounds(obstacles);
         const auto grid = createUniformGrid(sceneBounds, parameters);
 
-        ARMARX_INFO << "Creating grid";
+        ARMARX_VERBOSE << "Creating grid";
         Costmap costmap(grid, parameters, sceneBounds);
 
-        ARMARX_INFO << "Filling grid with size (" << costmap.getGrid().rows() << "/"
-                    << costmap.getGrid().cols() << ")";
+        ARMARX_VERBOSE << "Filling grid with size (" << costmap.getGrid().rows() << "/"
+                       << costmap.getGrid().cols() << ")";
         fillGridCosts(costmap);
-        ARMARX_INFO << "Filled grid";
+        ARMARX_VERBOSE << "Filled grid";
 
         initializeMask(costmap);
 
@@ -79,7 +79,8 @@ namespace armarx::navigation::algorithms
     {
         costmap.mask = costmap.grid.array() > 0.F;
 
-        ARMARX_INFO << "Initializing mask: Fraction of valid elements: " << costmap.mask->cast<float>().sum() / costmap.mask->size();
+        ARMARX_VERBOSE << "Initializing mask: Fraction of valid elements: "
+                       << costmap.mask->cast<float>().sum() / costmap.mask->size();
     }
 
     Eigen::MatrixXf
@@ -88,15 +89,15 @@ namespace armarx::navigation::algorithms
     {
         ARMARX_TRACE;
 
-        ARMARX_INFO << "Scene bounds are " << sceneBounds.min << " and " << sceneBounds.max;
+        ARMARX_VERBOSE << "Scene bounds are " << sceneBounds.min << " and " << sceneBounds.max;
 
         //+1 for explicit rounding up
         size_t c_x = (sceneBounds.max.x() - sceneBounds.min.x()) / parameters.cellSize + 1;
         size_t c_y = (sceneBounds.max.y() - sceneBounds.min.y()) / parameters.cellSize + 1;
 
-        ARMARX_INFO << "Grid size: " << c_x << ", " << c_y;
+        ARMARX_VERBOSE << "Grid size: " << c_x << ", " << c_y;
 
-        ARMARX_INFO << "Resetting grid";
+        ARMARX_VERBOSE << "Resetting grid";
         Eigen::MatrixXf grid(c_x, c_y);
         grid.setZero();
 
diff --git a/source/armarx/navigation/algorithms/astar/AStarPlanner.cpp b/source/armarx/navigation/algorithms/astar/AStarPlanner.cpp
index 5d3c7ad0..9ce4afe6 100644
--- a/source/armarx/navigation/algorithms/astar/AStarPlanner.cpp
+++ b/source/armarx/navigation/algorithms/astar/AStarPlanner.cpp
@@ -63,7 +63,7 @@ namespace armarx::navigation::algorithm::astar
         const size_t cols = costmap.getGrid().cols();
 
         // create the grid with the correct size
-        ARMARX_INFO << "Creating grid";
+        ARMARX_VERBOSE << "Creating grid";
         for (size_t r = 0; r < rows; r++)
         {
             grid.push_back(std::vector<NodePtr>(cols));
@@ -81,7 +81,7 @@ namespace armarx::navigation::algorithm::astar
             }
         }
 
-        ARMARX_INFO << "Creating graph";
+        ARMARX_VERBOSE << "Creating graph";
 
         // Init successors
         for (size_t r = 0; r < rows; r++)
@@ -118,7 +118,7 @@ namespace armarx::navigation::algorithm::astar
             }
         }
 
-        ARMARX_INFO << "Done.";
+        ARMARX_VERBOSE << "Done.";
     }
 
     bool
diff --git a/source/armarx/navigation/algorithms/persistence.cpp b/source/armarx/navigation/algorithms/persistence.cpp
index a7c0e965..efcef663 100644
--- a/source/armarx/navigation/algorithms/persistence.cpp
+++ b/source/armarx/navigation/algorithms/persistence.cpp
@@ -105,7 +105,7 @@ namespace armarx::navigation::algorithms
 
         if (not std::filesystem::exists(directory))
         {
-            ARMARX_INFO << "Creating directory `" << directory.string() << "`";
+            ARMARX_VERBOSE << "Creating directory `" << directory.string() << "`";
             std::filesystem::create_directories(directory);
         }
 
diff --git a/source/armarx/navigation/core/Trajectory.cpp b/source/armarx/navigation/core/Trajectory.cpp
index fc5c9b0b..2265c682 100644
--- a/source/armarx/navigation/core/Trajectory.cpp
+++ b/source/armarx/navigation/core/Trajectory.cpp
@@ -695,7 +695,7 @@ namespace armarx::navigation::core
         {
             const float posDiff =
                 (pts.at(i).waypoint.pose.translation() - referencePosition).norm();
-            ARMARX_INFO << VAROUT(posDiff);
+            // ARMARX_INFO << VAROUT(posDiff);
             return posDiff <= radius;
         };
 
@@ -730,7 +730,7 @@ namespace armarx::navigation::core
             }
         }
 
-        ARMARX_INFO << indices.size() << " points in range";
+        ARMARX_DEBUG << indices.size() << " points in range";
 
         return indices;
     }
diff --git a/source/armarx/navigation/global_planning/SPFA.cpp b/source/armarx/navigation/global_planning/SPFA.cpp
index 62b42068..9f309e54 100644
--- a/source/armarx/navigation/global_planning/SPFA.cpp
+++ b/source/armarx/navigation/global_planning/SPFA.cpp
@@ -119,8 +119,8 @@ namespace armarx::navigation::global_planning
         }
         const auto timeEnd = IceUtil::Time::now();
 
-        ARMARX_IMPORTANT << "A* planning took " << (timeEnd - timeStart).toMilliSeconds() << " ms";
-        ARMARX_IMPORTANT << "Path contains " << plan.path.size() << " points";
+        ARMARX_VERBOSE << "A* planning took " << (timeEnd - timeStart).toMilliSeconds() << " ms";
+        ARMARX_VERBOSE << "Path contains " << plan.path.size() << " points";
 
         if (plan.path.size() < 2) // failure
         {
diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
index d7ac3128..94a42162 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
@@ -72,7 +72,7 @@ namespace armarx::navigation::global_planning::optimization
             orientations.at(i) = std::atan2(vCombined.y(), vCombined.x());
         }
 
-        ARMARX_INFO << "orientations before: " << orientations;
+        ARMARX_VERBOSE << "orientations before: " << orientations;
 
         // const float yawStart = orientations.front();
         // const float yawEnd = orientations.back();
@@ -83,7 +83,7 @@ namespace armarx::navigation::global_planning::optimization
 
         ceres::Problem problem;
 
-        ARMARX_INFO << orientations.size() - 2 << " orientations to optimize";
+        ARMARX_VERBOSE << orientations.size() - 2 << " orientations to optimize";
 
         // TODO https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/slam/pose_graph_2d/pose_graph_2d.cc
         //     ceres::LocalParameterization* angle_local_parameterization =
@@ -199,7 +199,7 @@ namespace armarx::navigation::global_planning::optimization
         ceres::Solver::Summary summary;
         Solve(options, &problem, &summary);
 
-        std::cout << summary.FullReport() << "\n";
+        ARMARX_VERBOSE << summary.FullReport() << "\n";
         // std::cout << summary.BriefReport() << "\n";
 
         const auto clampInPlace = [](auto& val)
@@ -207,8 +207,8 @@ namespace armarx::navigation::global_planning::optimization
 
         std::for_each(orientations.begin(), orientations.end(), clampInPlace);
 
-        ARMARX_INFO << "orientations after: " << orientations;
-        ARMARX_INFO << "Optimization: " << summary.iterations.size() << " iterations";
+        ARMARX_VERBOSE << "orientations after: " << orientations;
+        ARMARX_VERBOSE << "Optimization: " << summary.iterations.size() << " iterations";
 
         if (not summary.IsSolutionUsable())
         {
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 86f63c95..16f873a3 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -67,6 +67,8 @@ namespace armarx::navigation::local_planning
         auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(
             params.cfg.robot_footprint_radius);
 
+        ARMARX_VERBOSE << "Robot footprint is " << params.cfg.robot_footprint_radius << "m";
+
         hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
         hcp_->initialize(
             cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);
@@ -74,6 +76,7 @@ namespace armarx::navigation::local_planning
         setTebCostmap();
         if (teb_costmap)
         {
+            ARMARX_VERBOSE << "Costmap available.";
             // TODO: where to put all the parameters
             const human::ExponentialPenaltyModel penalty{
                 .minDistance = 0.5, .epsilon = 0, .exponent = 1.2};
-- 
GitLab


From 7bc679d8e8e15abfcd45bfefad752af98d60fefe Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 14:39:39 +0200
Subject: [PATCH 238/324] fix: using obstacles in optimization

---
 source/armarx/navigation/local_planning/TebObstacleManager.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
index e2402e12..e16fffd3 100644
--- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp
+++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp
@@ -37,7 +37,7 @@ namespace armarx::navigation::local_planning
         obst->pushBackVertex(max.x(), min.y());
 
         obst->finalizePolygon();
-        obst->setUseForOptimization(false);
+        obst->setUseForOptimization(true);
         container.push_back(obst);
 
         // visualize bounding box if layer is available
-- 
GitLab


From 1a4eaa40d7c49be583eec1fd215854a7558e2fa2 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 15:04:53 +0200
Subject: [PATCH 239/324] reduced verbosity

---
 .../armarx/navigation/algorithms/astar/Planner2D.cpp  |  3 ++-
 source/armarx/navigation/global_planning/AStar.cpp    |  8 ++++----
 source/armarx/navigation/global_planning/SPFA.cpp     | 11 ++++++-----
 .../optimization/OrientationOptimizer.cpp             |  2 +-
 4 files changed, 13 insertions(+), 11 deletions(-)

diff --git a/source/armarx/navigation/algorithms/astar/Planner2D.cpp b/source/armarx/navigation/algorithms/astar/Planner2D.cpp
index 05e3e9be..73f1219a 100644
--- a/source/armarx/navigation/algorithms/astar/Planner2D.cpp
+++ b/source/armarx/navigation/algorithms/astar/Planner2D.cpp
@@ -4,6 +4,7 @@
 #include <cmath>
 
 #include <VirtualRobot/CollisionDetection/CollisionModel.h>
+#include "ArmarXCore/core/logging/Logging.h"
 
 namespace armarx::navigation::algorithm::astar
 {
@@ -71,7 +72,7 @@ namespace armarx::navigation::algorithm::astar
     {
         if (!hasParameter(s))
         {
-            std::cout << "Warning, parameter " << s << " not set, returning 0" << std::endl;
+            ARMARX_WARNING << "Parameter " << s << " not set, returning 0";
             return 0.0f;
         }
         return parameters[s];
diff --git a/source/armarx/navigation/global_planning/AStar.cpp b/source/armarx/navigation/global_planning/AStar.cpp
index 6765a908..276f1f3a 100644
--- a/source/armarx/navigation/global_planning/AStar.cpp
+++ b/source/armarx/navigation/global_planning/AStar.cpp
@@ -235,8 +235,8 @@ namespace armarx::navigation::global_planning
         smoothPlan.pop_back();
 
         ARMARX_TRACE;
-        auto trajectory =
-            core::GlobalTrajectory::FromPath(start, conv::to3D(smoothPlan), goal, params.linearVelocity);
+        auto trajectory = core::GlobalTrajectory::FromPath(
+            start, conv::to3D(smoothPlan), goal, params.linearVelocity);
 
         // TODO(fabian.reister): resampling of trajectory
 
@@ -262,8 +262,8 @@ namespace armarx::navigation::global_planning
             }
         }
 
-        ARMARX_IMPORTANT << "Resampled trajectory contains " << resampledTrajectory->points().size()
-                         << " points";
+        ARMARX_VERBOSE << "Resampled trajectory contains " << resampledTrajectory->points().size()
+                       << " points";
 
         resampledTrajectory->setMaxVelocity(params.linearVelocity);
 
diff --git a/source/armarx/navigation/global_planning/SPFA.cpp b/source/armarx/navigation/global_planning/SPFA.cpp
index 9f309e54..17b1aaae 100644
--- a/source/armarx/navigation/global_planning/SPFA.cpp
+++ b/source/armarx/navigation/global_planning/SPFA.cpp
@@ -94,8 +94,8 @@ namespace armarx::navigation::global_planning
 
         ARMARX_CHECK(scene.staticScene.has_value());
         ARMARX_CHECK(scene.staticScene->distanceToObstaclesCostmap.has_value());
-        algorithms::spfa::ShortestPathFasterAlgorithm planner(*scene.staticScene->distanceToObstaclesCostmap,
-                                                              spfaParams);
+        algorithms::spfa::ShortestPathFasterAlgorithm planner(
+            *scene.staticScene->distanceToObstaclesCostmap, spfaParams);
 
         const Eigen::Vector2f goalPos = conv::to2D(goal.translation());
 
@@ -158,7 +158,8 @@ namespace armarx::navigation::global_planning
         // smoothPlan.pop_back();
 
         ARMARX_TRACE;
-        auto trajectory = core::GlobalTrajectory::FromPath(start, wpts, goal, params.linearVelocity);
+        auto trajectory =
+            core::GlobalTrajectory::FromPath(start, wpts, goal, params.linearVelocity);
 
         // TODO(fabian.reister): resampling of trajectory
 
@@ -183,8 +184,8 @@ namespace armarx::navigation::global_planning
             resampledTrajectory = trajectory;
         }
 
-        ARMARX_IMPORTANT << "Resampled trajectory contains " << resampledTrajectory->points().size()
-                         << " points";
+        ARMARX_VERBOSE << "Resampled trajectory contains " << resampledTrajectory->points().size()
+                       << " points";
 
         resampledTrajectory->setMaxVelocity(params.linearVelocity);
 
diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
index 94a42162..206bc90b 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.cpp
@@ -192,7 +192,7 @@ namespace armarx::navigation::global_planning::optimization
         // Run the solver!
         ceres::Solver::Options options;
         options.linear_solver_type = ceres::DENSE_QR;
-        options.minimizer_progress_to_stdout = true;
+        options.minimizer_progress_to_stdout = false;
         options.max_num_iterations = 100;
         options.function_tolerance = 0.01;
 
-- 
GitLab


From ea37a68695f3dc12fb4062fdb0045dbed8da086f Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 15:05:05 +0200
Subject: [PATCH 240/324] human sim: adding param

---
 .../navigation/components/human_simulator/Component.cpp       | 4 +++-
 .../armarx/navigation/components/human_simulator/Component.h  | 2 ++
 2 files changed, 5 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
index 6ce73503..fe429dbe 100644
--- a/source/armarx/navigation/components/human_simulator/Component.cpp
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -93,6 +93,8 @@ namespace armarx::navigation::components::human_simulator
             properties.humanParams.goalDistanceThreshold, "p.human.goalDistanceThreshold", "");
         def->optional(properties.humanParams.minLinearVelocity, "p.human.maxLinearVelocity", "");
         def->optional(properties.humanParams.maxLinearVelocity, "p.human.maxLinearVelocity", "");
+        
+        def->optional(properties.objectPoseProviderName, "p.objectPoseProviderName", "");
 
         return def;
     }
@@ -206,7 +208,7 @@ namespace armarx::navigation::components::human_simulator
 
             const objpose::ObjectPoseSeq obstacles =
                 ObjectPoseClientPluginUser::getObjectPosesByProvider(
-                    "R003_grasping_challenge_robot_placement_with_ivt_obstacles");
+                    properties.objectPoseProviderName);
 
             const auto objects = armarx::navigation::util::asSceneObjects(obstacles);
 
diff --git a/source/armarx/navigation/components/human_simulator/Component.h b/source/armarx/navigation/components/human_simulator/Component.h
index 7235893d..e0f004aa 100644
--- a/source/armarx/navigation/components/human_simulator/Component.h
+++ b/source/armarx/navigation/components/human_simulator/Component.h
@@ -135,6 +135,8 @@ namespace armarx::navigation::components::human_simulator
             human::simulation::SimulatedHumanParams humanParams;
 
             std::string robotName = "Armar6";
+
+            std::string objectPoseProviderName = "R003_grasping_challenge";
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
-- 
GitLab


From 4950ace9029bff754dd4fdec211c9b214dcdbd3d Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 15:05:51 +0200
Subject: [PATCH 241/324] using new param

---
 scenarios/HumanAwareNavigation/config/human_simulator.cfg | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/config/human_simulator.cfg b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
index d7720e7b..af906f63 100644
--- a/scenarios/HumanAwareNavigation/config/human_simulator.cfg
+++ b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
@@ -157,7 +157,7 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+# ArmarX.Verbosity = Info
 
 
 # ArmarX.human_simulator.ArVizStorageName:  Name of the ArViz storage
@@ -305,7 +305,7 @@ ArmarX.Verbosity = Verbose
 #  - Default:            4
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.human_simulator.p.nHumans = 6
+ArmarX.human_simulator.p.nHumans = 3
 
 
 # ArmarX.human_simulator.p.taskPeriodMs:  
-- 
GitLab


From d225c61ef034484f52c6b22814c83b3598cf716b Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 4 Oct 2022 15:06:17 +0200
Subject: [PATCH 242/324] human aware navigation scenario update

---
 .../HumanAwareNavigation.scx                  |  2 +-
 .../config/example_client.cfg                 |  2 +-
 .../HumanAwareNavigation/config/navigator.cfg | 33 ++++++++++++++++++-
 3 files changed, 34 insertions(+), 3 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
index 942bdb1b..ea96507f 100644
--- a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -6,7 +6,7 @@
 	<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="navigator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="navigation_memory" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
+	<application name="example_client" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
index ea5576f6..5b947d42 100644
--- a/scenarios/HumanAwareNavigation/config/example_client.cfg
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -250,7 +250,7 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {complex, point_to_point, standard, update_navigator, wander_around}
-# ArmarX.example_client.mode = standard
+ArmarX.example_client.mode = wander_around
 
 
 # ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
diff --git a/scenarios/HumanAwareNavigation/config/navigator.cfg b/scenarios/HumanAwareNavigation/config/navigator.cfg
index e55d723f..48abd636 100644
--- a/scenarios/HumanAwareNavigation/config/navigator.cfg
+++ b/scenarios/HumanAwareNavigation/config/navigator.cfg
@@ -157,7 +157,7 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+# ArmarX.Verbosity = Info
 
 
 # ArmarX.navigator.ArVizStorageName:  Name of the ArViz storage
@@ -404,3 +404,34 @@ ArmarX.navigator.RobotUnitName = Armar6Unit
 ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
 
 
+# ArmarX.navigator.p.scene.humanProviderName:  
+#  Attributes:
+#  - Default:            dynamic_scene_provider
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.navigator.p.scene.humanProviderName = human_simulator
+
+
+# ArmarX.navigator.p.scene.robotName:  
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.navigator.p.scene.robotName = Armar6
+
+
+# ArmarX.navigator.p.scene.staticCostmapName:  
+#  Attributes:
+#  - Default:            distance_to_obstacles
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.p.scene.staticCostmapName = distance_to_obstacles
+
+
+# ArmarX.navigator.p.scene.staticCostmapProviderName:  
+#  Attributes:
+#  - Default:            distance_to_obstacle_costmap_provider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.p.scene.staticCostmapProviderName = distance_to_obstacle_costmap_provider
+
+
-- 
GitLab


From 23bc5a4238af3cd88208e6e7620d54506b02e28b Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 6 Oct 2022 18:30:59 +0200
Subject: [PATCH 243/324] removing build .gitkeep (not needed)

---
 build/.gitkeep | 1 -
 1 file changed, 1 deletion(-)
 delete mode 100644 build/.gitkeep

diff --git a/build/.gitkeep b/build/.gitkeep
deleted file mode 100644
index c9f1420c..00000000
--- a/build/.gitkeep
+++ /dev/null
@@ -1 +0,0 @@
-# This file is tracked to keep empty directories in Git
-- 
GitLab


From 66d739fa9dd47f3c107903ea436d9ee65f41b766 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 6 Oct 2022 18:31:55 +0200
Subject: [PATCH 244/324] navigation memory: property to disable transparent
 humans

---
 .../navigation/components/navigation_memory/Component.cpp | 2 +-
 .../navigation/components/navigation_memory/Component.h   | 2 ++
 .../navigation/components/navigation_memory/Visu.cpp      | 8 ++++----
 .../armarx/navigation/components/navigation_memory/Visu.h | 2 +-
 4 files changed, 8 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Component.cpp b/source/armarx/navigation/components/navigation_memory/Component.cpp
index 13f1fe8c..d774a623 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Component.cpp
@@ -475,7 +475,7 @@ namespace armarx::navigation::components::navigation_memory
             visu.drawCostmaps(layers, p.visuCostmaps);
 
             // Humans
-            visu.drawHumans(layers, p.visuHumans);
+            visu.drawHumans(layers, p.visuHumans, p.visuTransparent);
 
             arviz.commit(layers);
 
diff --git a/source/armarx/navigation/components/navigation_memory/Component.h b/source/armarx/navigation/components/navigation_memory/Component.h
index b1bbf3ea..930215ae 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -100,6 +100,8 @@ namespace armarx::navigation::components::navigation_memory
                 bool visuGraphEdges = true;
                 bool visuCostmaps = true;
                 bool visuHumans = true;
+
+                bool visuTransparent = false;
                 
                 float visuFrequency = 10;
             };
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 2b5e1aa0..02838557 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -177,7 +177,7 @@ namespace armarx::navigation::memory
         }
 
         void
-        visualize(const human::Humans& humans, viz::Layer& layer)
+        visualize(const human::Humans& humans, viz::Layer& layer, const bool visuTransparent)
         {
 
             const Eigen::Translation3f human_T_mmm(Eigen::Vector3f{0,0, 1000});
@@ -199,7 +199,7 @@ namespace armarx::navigation::memory
                 mmm.file("RobotAPI", "RobotAPI/robots/MMM/mmm.xml");
                 mmm.pose(conv::to3D(human.pose) * human_T_mmm);
                 mmm.scale(1.7); // 1.7m 
-                mmm.overrideColor(viz::Color::orange(255, 100));
+                mmm.overrideColor(viz::Color::orange(255, visuTransparent? 100: 255));
                 layer.add(mmm);
 
             }
@@ -248,7 +248,7 @@ namespace armarx::navigation::memory
     }
 
     void
-    Visu::drawHumans(std::vector<viz::Layer>& layers, bool enabled)
+    Visu::drawHumans(std::vector<viz::Layer>& layers, const bool enabled, const bool visuTransparent)
     {
         if (not enabled)
         {
@@ -283,7 +283,7 @@ namespace armarx::navigation::memory
         for (const auto& [providerName, humans] : namedProviderHumans)
         {
             viz::Layer& layer = layers.emplace_back(arviz.layer("humans_" + providerName));
-            visualize(humans, layer);
+            visualize(humans, layer, visuTransparent);
         }
     }
 
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.h b/source/armarx/navigation/components/navigation_memory/Visu.h
index 71c057df..d965fecc 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.h
+++ b/source/armarx/navigation/components/navigation_memory/Visu.h
@@ -55,7 +55,7 @@ namespace armarx::navigation::memory
         void drawLocations(std::vector<viz::Layer>& layers, bool enabled);
         void drawGraphs(std::vector<viz::Layer>& layers, bool enabled);
         void drawCostmaps(std::vector<viz::Layer>& layers, bool enabled);
-        void drawHumans(std::vector<viz::Layer>& layers, bool enabled);
+        void drawHumans(std::vector<viz::Layer>& layers, bool enabled, bool visuTransparent);
 
 
         viz::ScopedClient arviz;
-- 
GitLab


From d60279161499b3e48b158975d6a06b781fd2dec1 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 17:40:10 +0200
Subject: [PATCH 245/324] Add new method for lasersensor measurement tracking
 in header.

---
 .../dynamic_scene_provider/Component.cpp      |  2 +-
 .../armarx/navigation/human/HumanTracker.cpp  |  2 +-
 source/armarx/navigation/human/HumanTracker.h | 25 ++++++++++++++++---
 3 files changed, 24 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 29c23bbf..185d5568 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -351,7 +351,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << "Running human tracker";
 
-        humanTracker.update(human::HumanTracker::Measurements{
+        humanTracker.update(human::HumanTracker::CameraMeasurement{
             .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
 
 
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 2332377e..c879af3a 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -10,7 +10,7 @@
 namespace armarx::navigation::human
 {
     void
-    HumanTracker::update(const Measurements& measurements)
+    HumanTracker::update(const CameraMeasurement& measurements)
     {
         // iterate over all existing tracked humans
         for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 1a83fb65..d5c92f1c 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -24,6 +24,7 @@
 
 #include <ArmarXCore/core/time.h>
 
+#include <RobotAPI/libraries/armem_vision/types.h>
 #include <RobotAPI/libraries/ukfm/UnscentedKalmanFilter.h>
 
 #include <VisionX/libraries/armem_human/types.h>
@@ -50,12 +51,18 @@ namespace armarx::navigation::human
     public:
         HumanTracker() = default;
 
-        struct Measurements
+        struct CameraMeasurement
         {
             DateTime detectionTime;
             std::vector<armem::human::HumanPose> humanPoses;
         };
 
+        struct LaserMeasurement
+        {
+            DateTime detectionTime;
+            std::vector<armem::vision::LaserScannerFeature> clusters;
+        };
+
         struct DetectedHuman
         {
             core::Pose2D pose;
@@ -93,14 +100,26 @@ namespace armarx::navigation::human
             float velocityAlpha = 0.7;
         };
         /**
-         * @brief HumanTracker::update Updates the tracked humans with the measurements. When a
+         * @brief HumanTracker::update Updates the tracked humans with the human measurements from a camera. When a
          * measurement is close enough to an existing tracked human, they are associated, otherwise a
          * new tracked human is created. Tracked humans that were not associated with a new measurement
          * for a specified amount of time are removed. New associated measurements for a tracked human
          * are always filtered to provide a less noisy state.
          * @param measurements the new measurements of the environment
          */
-        void update(const Measurements& measurements);
+        void update(const CameraMeasurement& measurements);
+        /**
+         * @brief HumanTracker::update Updates the tracked humans with the measurements from a lasersensor.
+         * When a measurement is close enough to an existing tracked human, they are associated,
+         * otherwise the measurement is not used for human tracking but returned in the list of unused
+         * measurements. Tracked humans that were not associated with a new measurement for a
+         * specified amount of time are removed. New associated measurements for a tracked human
+         * are always filtered to provide a less noisy state.
+         * @param measurements
+         * @return
+         */
+        std::vector<armem::vision::LaserScannerFeature>
+        update(const LaserMeasurement& measurements);
         /**
          * @brief HumanTracker::getTrackedHumans Returns all humans that are currently tracked.
          * @return  the tracked humans
-- 
GitLab


From 8dc47d9b811288263ed655b3869f8030dea7fd59 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 18:18:44 +0200
Subject: [PATCH 246/324] Implement basic version of getClusterSize

---
 .../armarx/navigation/human/HumanTracker.cpp   | 18 ++++++++++++++++++
 source/armarx/navigation/human/HumanTracker.h  |  7 +++++++
 2 files changed, 25 insertions(+)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index c879af3a..df05c557 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -220,4 +220,22 @@ namespace armarx::navigation::human
         trackedHuman->trackingId = detectedHuman->trackingId;
     }
 
+    float
+    HumanTracker::getClusterSize(armem::vision::LaserScannerFeature cluster)
+    {
+        float maxSize = 0;
+        for (auto it1 = cluster.points.begin(); it1 != cluster.points.end();)
+        {
+            auto& point1 = *it1;
+            for (auto it2 = it1 + 1; it2 != cluster.points.end();)
+            {
+                auto& point2 = *it2;
+                float xdiff = point2.x() - point1.x();
+                float ydiff = point2.y() - point1.y();
+                maxSize = std::max(maxSize, std::sqrt(xdiff * xdiff + ydiff * ydiff));
+            }
+        }
+        return maxSize;
+    }
+
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index d5c92f1c..2d0ee981 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -167,6 +167,13 @@ namespace armarx::navigation::human
          * @param detectedHuman the detected human
          */
         void associate(TrackedHuman* tracked, DetectedHuman* detected);
+        /**
+         * @brief getClusterSize Returns the size of the given cluster. That is for now the maximum
+         * distance between two points.
+         * @param cluster The cluster whose size is measured
+         * @return the size
+         */
+        float getClusterSize(armem::vision::LaserScannerFeature cluster);
 
 
     private:
-- 
GitLab


From 26182499c65f3dbb4c9ae04115b92159fcab168c Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 19:15:29 +0200
Subject: [PATCH 247/324] Implement getSortedDistances for distance between
 humans and clusters

---
 .../armarx/navigation/human/HumanTracker.cpp  | 48 ++++++++++++++++---
 source/armarx/navigation/human/HumanTracker.h | 34 ++++++++++---
 2 files changed, 68 insertions(+), 14 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index df05c557..0a21dd29 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -127,11 +127,11 @@ namespace armarx::navigation::human
         return {pose, humanPose.humanTrackingId, time, false};
     }
 
-    std::vector<HumanTracker::PosDistance>
+    std::vector<HumanTracker::PosHumanDistance>
     HumanTracker::getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
                                      std::vector<HumanTracker::DetectedHuman>& newHumans)
     {
-        std::vector<PosDistance> posDistances;
+        std::vector<PosHumanDistance> posDistances;
 
         for (auto& oldHuman : oldHumans)
         {
@@ -158,7 +158,42 @@ namespace armarx::navigation::human
         // sort the distances ascending by their numeric value
         std::sort(posDistances.begin(),
                   posDistances.end(),
-                  [](const PosDistance& a, const PosDistance& b) -> bool
+                  [](const PosHumanDistance& a, const PosHumanDistance& b) -> bool
+                  { return a.distance < b.distance; });
+
+        return posDistances;
+    }
+
+    std::vector<HumanTracker::PosLaserDistance>
+    HumanTracker::getSortedDistances(std::vector<TrackedHuman>& oldHumans,
+                                     std::vector<Cluster>& newClusters)
+    {
+        std::vector<PosLaserDistance> posDistances;
+
+        for (auto& newCluster : newClusters)
+        {
+            //calculate center of cluster
+            Eigen::Vector2f clusterCenter;
+            for (auto& point : newCluster.points)
+            {
+                clusterCenter += point;
+            }
+            clusterCenter /= newCluster.points.size();
+
+            for (auto& oldHuman : oldHumans)
+            {
+                // calculate distance between every possible combination of tracked human and cluster
+                posDistances.push_back(
+                    {&oldHuman,
+                     &newCluster,
+                     (clusterCenter - oldHuman.humanFilter.get().pose.translation()).norm()});
+            }
+        }
+
+        // sort the distances ascending by their numeric value
+        std::sort(posDistances.begin(),
+                  posDistances.end(),
+                  [](const PosHumanDistance& a, const PosHumanDistance& b) -> bool
                   { return a.distance < b.distance; });
 
         return posDistances;
@@ -221,7 +256,7 @@ namespace armarx::navigation::human
     }
 
     float
-    HumanTracker::getClusterSize(armem::vision::LaserScannerFeature cluster)
+    HumanTracker::getClusterSize(Cluster cluster)
     {
         float maxSize = 0;
         for (auto it1 = cluster.points.begin(); it1 != cluster.points.end();)
@@ -230,9 +265,8 @@ namespace armarx::navigation::human
             for (auto it2 = it1 + 1; it2 != cluster.points.end();)
             {
                 auto& point2 = *it2;
-                float xdiff = point2.x() - point1.x();
-                float ydiff = point2.y() - point1.y();
-                maxSize = std::max(maxSize, std::sqrt(xdiff * xdiff + ydiff * ydiff));
+                //TODO does subtraction work for vectors like this?
+                maxSize = std::max(maxSize, (point2 - point1).norm());
             }
         }
         return maxSize;
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 2d0ee981..8e543425 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -39,6 +39,7 @@ namespace armarx::navigation::human
     using T = double;
     using Vector = Eigen::Matrix<T, 2, 1>;
     using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
+    using Cluster = armem::vision::LaserScannerFeature;
 
     /**
      * @brief The HumanTracker class can be used to track and filter multiple humans. It hides
@@ -60,7 +61,7 @@ namespace armarx::navigation::human
         struct LaserMeasurement
         {
             DateTime detectionTime;
-            std::vector<armem::vision::LaserScannerFeature> clusters;
+            std::vector<Cluster> clusters;
         };
 
         struct DetectedHuman
@@ -78,13 +79,20 @@ namespace armarx::navigation::human
             bool associated;
         };
 
-        struct PosDistance
+        struct PosHumanDistance
         {
             HumanTracker::TrackedHuman* oldHuman;
             HumanTracker::DetectedHuman* newHuman;
             float distance;
         };
 
+        struct PosLaserDistance
+        {
+            HumanTracker::TrackedHuman* oldHuman;
+            Cluster* newCluster;
+            float distance;
+        };
+
         struct Parameters
         {
             // the keypoint which should be used for calculating the rotation of the humans
@@ -95,6 +103,8 @@ namespace armarx::navigation::human
             // the maximum distance in millimeters of two human measurements where they are still
             // associated with each other
             float maxAssociationDistance = 600;
+            // the maximum size (aka length) in millimeters a footprint can have
+            float maxFootprintSize = 350;
             // alpha value from interval [0,1] to determine how much the current (and respectively
             // the old) velocity should be weighted when calculating the new velocity
             float velocityAlpha = 0.7;
@@ -118,8 +128,7 @@ namespace armarx::navigation::human
          * @param measurements
          * @return
          */
-        std::vector<armem::vision::LaserScannerFeature>
-        update(const LaserMeasurement& measurements);
+        std::vector<Cluster> update(const LaserMeasurement& measurements);
         /**
          * @brief HumanTracker::getTrackedHumans Returns all humans that are currently tracked.
          * @return  the tracked humans
@@ -145,14 +154,25 @@ namespace armarx::navigation::human
          * @brief getSortedDistances Returns a sorted vector of the distances between every possible
          * combination (T, D) where T is an old, tracked human and D is a new, detected human and
          * both of them are not already associated. The smallest distance will be the first entry in
-         * the vector
+         * the vector.
          * @param oldHumans the old, tracked humans
          * @param newHumans the new, detected humans
          * @return the sorted vector of distances with references to the according humans
          */
-        std::vector<PosDistance>
+        std::vector<PosHumanDistance>
         getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
                            std::vector<HumanTracker::DetectedHuman>& newHumans);
+        /**
+         * @brief getSortedDistances Returns a sorted vector of the distances between every possible
+         * combination (T, C) where T is an old, tracked human and C is a new, detected cluster.
+         * The smallest distance will be the first entry in the vector.
+         * @param oldHumans
+         * @param newClusters
+         * @return
+         */
+        std::vector<PosLaserDistance>
+        getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
+                           std::vector<Cluster>& newClusters);
         /**
          * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
          * belong together.
@@ -173,7 +193,7 @@ namespace armarx::navigation::human
          * @param cluster The cluster whose size is measured
          * @return the size
          */
-        float getClusterSize(armem::vision::LaserScannerFeature cluster);
+        float getClusterSize(Cluster cluster);
 
 
     private:
-- 
GitLab


From 05615bb86860da2b98871df2025cfe164303deac Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 19:38:28 +0200
Subject: [PATCH 248/324] Extract preparation of trackedHumans for association
 in extra method

---
 .../armarx/navigation/human/HumanTracker.cpp  | 58 +++++++++----------
 source/armarx/navigation/human/HumanTracker.h | 16 ++++-
 2 files changed, 42 insertions(+), 32 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 0a21dd29..5d019240 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -12,24 +12,7 @@ namespace armarx::navigation::human
     void
     HumanTracker::update(const CameraMeasurement& measurements)
     {
-        // iterate over all existing tracked humans
-        for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
-        {
-            auto& human = *it;
-            // when the tracked human recieved no new measurement for too long, remove it
-            if ((measurements.detectionTime - human.humanFilter.get().detectionTime) >=
-                parameters.maxTrackingAge)
-            {
-                it = trackedHumans.erase(it);
-            }
-            // otherwise the tracked human is prepared for association at the current point in time
-            else
-            {
-                human.associated = false;
-                human.humanFilter.propagation(measurements.detectionTime);
-                it++;
-            }
-        }
+        prepareTrackedHumans(measurements.detectionTime);
 
         // calculate the poses according to the new received measurements
         std::vector<DetectedHuman> newPoses =
@@ -166,27 +149,19 @@ namespace armarx::navigation::human
 
     std::vector<HumanTracker::PosLaserDistance>
     HumanTracker::getSortedDistances(std::vector<TrackedHuman>& oldHumans,
-                                     std::vector<Cluster>& newClusters)
+                                     std::vector<AdvancedCluster>& newClusters)
     {
         std::vector<PosLaserDistance> posDistances;
 
-        for (auto& newCluster : newClusters)
+        for (auto& oldHuman : oldHumans)
         {
-            //calculate center of cluster
-            Eigen::Vector2f clusterCenter;
-            for (auto& point : newCluster.points)
-            {
-                clusterCenter += point;
-            }
-            clusterCenter /= newCluster.points.size();
-
-            for (auto& oldHuman : oldHumans)
+            for (auto& newCluster : newClusters)
             {
                 // calculate distance between every possible combination of tracked human and cluster
                 posDistances.push_back(
                     {&oldHuman,
                      &newCluster,
-                     (clusterCenter - oldHuman.humanFilter.get().pose.translation()).norm()});
+                     (newCluster.center - oldHuman.humanFilter.get().pose.translation()).norm()});
             }
         }
 
@@ -272,4 +247,27 @@ namespace armarx::navigation::human
         return maxSize;
     }
 
+    void
+    HumanTracker::prepareTrackedHumans(DateTime time)
+    {
+        // iterate over all existing tracked humans
+        for (auto it = trackedHumans.begin(); it != trackedHumans.end();)
+        {
+            auto& human = *it;
+            // when the tracked human recieved no new measurement for too long, remove it
+            if ((time - human.humanFilter.get().detectionTime) >= parameters.maxTrackingAge)
+            {
+                it = trackedHumans.erase(it);
+            }
+            // otherwise the tracked human is prepared for association at the current point in time
+            else
+            {
+                human.associatedClusters = 0;
+                human.associated = false;
+                human.humanFilter.propagation(time);
+                it++;
+            }
+        }
+    }
+
 } // namespace armarx::navigation::human
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 8e543425..5cdc5a7f 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -76,6 +76,14 @@ namespace armarx::navigation::human
         {
             HumanFilter humanFilter;
             std::optional<std::string> trackingId = std::nullopt;
+            int associatedClusters;
+            bool associated;
+        };
+
+        struct AdvancedCluster
+        {
+            Eigen::Vector2f center;
+            Cluster cluster;
             bool associated;
         };
 
@@ -89,7 +97,7 @@ namespace armarx::navigation::human
         struct PosLaserDistance
         {
             HumanTracker::TrackedHuman* oldHuman;
-            Cluster* newCluster;
+            AdvancedCluster* newCluster;
             float distance;
         };
 
@@ -172,7 +180,7 @@ namespace armarx::navigation::human
          */
         std::vector<PosLaserDistance>
         getSortedDistances(std::vector<HumanTracker::TrackedHuman>& oldHumans,
-                           std::vector<Cluster>& newClusters);
+                           std::vector<AdvancedCluster>& newClusters);
         /**
          * @brief HumanTracker::associateHumans Associates those tracked and detected humans that
          * belong together.
@@ -194,6 +202,10 @@ namespace armarx::navigation::human
          * @return the size
          */
         float getClusterSize(Cluster cluster);
+        /**
+         * @brief prepareTrackedHumans
+         */
+        void prepareTrackedHumans(DateTime time);
 
 
     private:
-- 
GitLab


From 112051bed992b13eae848125943c00daf8a4ef68 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 20:51:18 +0200
Subject: [PATCH 249/324] Implement update method for lasersensor measurement

---
 .../armarx/navigation/human/HumanTracker.cpp  | 125 +++++++++++++++++-
 source/armarx/navigation/human/HumanTracker.h |  18 +--
 2 files changed, 134 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 5d019240..df8d2258 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -35,11 +35,134 @@ namespace armarx::navigation::human
                 trackedHumans.push_back(TrackedHuman{
                     .humanFilter = HumanFilter{detectedHuman.pose, detectedHuman.detectionTime},
                     .trackingId = detectedHuman.trackingId,
+                    .associatedCluster = nullptr,
                     .associated = true});
             }
         }
     }
 
+    std::vector<Cluster>
+    HumanTracker::update(const LaserMeasurement& measurements)
+    {
+        // TODO do we receive cluster with correct threshold / expected size / as accurate as that
+        // they distinguish multiple footprints?
+
+        prepareTrackedHumans(measurements.detectionTime);
+
+        // only look at the clusters that have a size reasonable enough to contain at most two
+        // footprints
+        std::vector<AdvancedCluster> potentialFootprints;
+        std::vector<Cluster> unusedClusters;
+        for (auto it = measurements.clusters.begin(); it != measurements.clusters.end();)
+        {
+            auto& cluster = *it;
+
+            if (getClusterSize(cluster) <= 2 * parameters.maxFootprintSize)
+            {
+                //calculate center of cluster
+                Eigen::Vector2f clusterCenter;
+                for (auto& point : cluster.points)
+                {
+                    clusterCenter += point;
+                }
+                clusterCenter /= cluster.points.size();
+
+                potentialFootprints.push_back(AdvancedCluster{
+                    .center = clusterCenter, .cluster = cluster, .associated = false});
+            }
+            else
+            {
+                unusedClusters.push_back(cluster);
+            }
+        }
+
+
+        // associate humans and clusters by their distances
+        const auto sortedDistances = getSortedDistances(trackedHumans, potentialFootprints);
+
+        for (auto& posDistance : sortedDistances)
+        {
+            if (posDistance.distance > parameters.maxAssociationDistance)
+            {
+                break;
+            }
+            if (posDistance.oldHuman->associated || posDistance.newCluster->associated)
+            {
+                continue;
+            }
+            // no footprint was found before, so associate first footprint
+            if (!posDistance.oldHuman->associatedCluster)
+            {
+                posDistance.oldHuman->associatedCluster = posDistance.newCluster;
+                posDistance.newCluster->associated = true;
+            }
+            // found both footprints, so associate both footprints and update human with new pose
+            else
+            {
+                //calculate center of the points of both footprints combined
+                auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster.points;
+                auto& footprint2 = posDistance.newCluster->cluster.points;
+
+                Eigen::Vector2f centerPos;
+                for (auto& point : footprint1)
+                {
+                    centerPos += point;
+                }
+                for (auto& point : footprint2)
+                {
+                    centerPos += point;
+                }
+                centerPos /= (footprint1.size() + footprint2.size());
+
+                //create pose with orientation from old human
+                core::Pose2D pose = core::Pose2D::Identity();
+                pose.translation() = conv::to2D(centerPos);
+                pose.linear() = posDistance.oldHuman->humanFilter.get().pose.linear();
+
+
+                posDistance.oldHuman->humanFilter.update(pose, measurements.detectionTime);
+
+                posDistance.oldHuman->associatedCluster = nullptr;
+                posDistance.oldHuman->associated = true;
+                posDistance.newCluster->associated = true;
+            }
+        }
+
+        //associate humans where only one footprint was found
+        for (auto& human : trackedHumans)
+        {
+            if (human.associated)
+            {
+                continue;
+            }
+
+            if (human.associatedCluster)
+            {
+                auto& footprint = human.associatedCluster;
+                //create pose with orientation from old human
+                core::Pose2D pose = core::Pose2D::Identity();
+                pose.translation() = conv::to2D(footprint->center);
+                pose.linear() = human.humanFilter.get().pose.linear();
+
+                human.humanFilter.update(pose, measurements.detectionTime);
+
+                human.associatedCluster = nullptr;
+                human.associated = true;
+            }
+        }
+
+        // add unused clusters to return list
+        for (auto& cluster : potentialFootprints)
+        {
+            if (!cluster.associated)
+            {
+                unusedClusters.push_back(cluster.cluster);
+            }
+        }
+
+        return unusedClusters;
+    }
+
     std::vector<human::Human>
     HumanTracker::getTrackedHumans() const
     {
@@ -262,7 +385,7 @@ namespace armarx::navigation::human
             // otherwise the tracked human is prepared for association at the current point in time
             else
             {
-                human.associatedClusters = 0;
+                human.associatedCluster = nullptr;
                 human.associated = false;
                 human.humanFilter.propagation(time);
                 it++;
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 5cdc5a7f..ab1ac283 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -72,18 +72,18 @@ namespace armarx::navigation::human
             bool associated;
         };
 
-        struct TrackedHuman
+        struct AdvancedCluster
         {
-            HumanFilter humanFilter;
-            std::optional<std::string> trackingId = std::nullopt;
-            int associatedClusters;
+            Eigen::Vector2f center;
+            Cluster cluster;
             bool associated;
         };
 
-        struct AdvancedCluster
+        struct TrackedHuman
         {
-            Eigen::Vector2f center;
-            Cluster cluster;
+            HumanFilter humanFilter;
+            std::optional<std::string> trackingId = std::nullopt;
+            AdvancedCluster* associatedCluster;
             bool associated;
         };
 
@@ -203,7 +203,9 @@ namespace armarx::navigation::human
          */
         float getClusterSize(Cluster cluster);
         /**
-         * @brief prepareTrackedHumans
+         * @brief prepareTrackedHumans Deletes all tracked humans that received no update for too
+         * long. All remaining tracked humans are prepared for association with the given point in
+         * time.
          */
         void prepareTrackedHumans(DateTime time);
 
-- 
GitLab


From c843c3d0a0d052dd442776ef55280026baf1b71e Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 24 Oct 2022 21:01:17 +0200
Subject: [PATCH 250/324] Fix errors

---
 source/armarx/navigation/human/HumanTracker.cpp | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index df8d2258..b67d489b 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -116,7 +116,7 @@ namespace armarx::navigation::human
 
                 //create pose with orientation from old human
                 core::Pose2D pose = core::Pose2D::Identity();
-                pose.translation() = conv::to2D(centerPos);
+                pose.translation() = centerPos;
                 pose.linear() = posDistance.oldHuman->humanFilter.get().pose.linear();
 
 
@@ -141,7 +141,7 @@ namespace armarx::navigation::human
                 auto& footprint = human.associatedCluster;
                 //create pose with orientation from old human
                 core::Pose2D pose = core::Pose2D::Identity();
-                pose.translation() = conv::to2D(footprint->center);
+                pose.translation() = footprint->center;
                 pose.linear() = human.humanFilter.get().pose.linear();
 
                 human.humanFilter.update(pose, measurements.detectionTime);
@@ -291,7 +291,7 @@ namespace armarx::navigation::human
         // sort the distances ascending by their numeric value
         std::sort(posDistances.begin(),
                   posDistances.end(),
-                  [](const PosHumanDistance& a, const PosHumanDistance& b) -> bool
+                  [](const PosLaserDistance& a, const PosLaserDistance& b) -> bool
                   { return a.distance < b.distance; });
 
         return posDistances;
-- 
GitLab


From 3ba10c63becfe6a9a0b02d664c273b922b0055b8 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Thu, 27 Oct 2022 13:25:20 +0200
Subject: [PATCH 251/324] Test

---
 test | 0
 1 file changed, 0 insertions(+), 0 deletions(-)
 create mode 100644 test

diff --git a/test b/test
new file mode 100644
index 00000000..e69de29b
-- 
GitLab


From f73b71868cea69f04c264d3cdc2716cf36002b76 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Thu, 27 Oct 2022 15:10:26 +0200
Subject: [PATCH 252/324] Create human tracker test

---
 source/armarx/navigation/human/CMakeLists.txt | 13 +++++++++++++
 1 file changed, 13 insertions(+)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 4cf568f3..eb57ec12 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -98,3 +98,16 @@ armarx_add_test(kalman_filter_test
         PRIVATE
             range-v3::range-v3
 )
+
+armarx_add_test(human_tracker_test
+    TEST_FILES
+        test/human_tracker_test.cpp
+    DEPENDENCIES
+        PUBLIC
+            ArmarXCore
+            armarx_navigation::core
+            armarx_navigation::teb_human
+
+        PRIVATE
+            range-v3::range-v3
+)
-- 
GitLab


From 1aeb4baaace915f8c0abe36d6bccecc07f69ddf7 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 27 Oct 2022 15:12:13 +0200
Subject: [PATCH 253/324] Clean up project

---
 source/armarx/navigation/human/HumanTracker.cpp | 3 ++-
 source/armarx/navigation/human/HumanTracker.h   | 4 +---
 2 files changed, 3 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index b67d489b..689600e2 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -103,6 +103,7 @@ namespace armarx::navigation::human
                 auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster.points;
                 auto& footprint2 = posDistance.newCluster->cluster.points;
 
+                //TODO more efficient by just calculating mean between two circle centers for example
                 Eigen::Vector2f centerPos;
                 for (auto& point : footprint1)
                 {
@@ -356,6 +357,7 @@ namespace armarx::navigation::human
     float
     HumanTracker::getClusterSize(Cluster cluster)
     {
+        //TODO more effictient by using radius of circle saved in cluster for example
         float maxSize = 0;
         for (auto it1 = cluster.points.begin(); it1 != cluster.points.end();)
         {
@@ -363,7 +365,6 @@ namespace armarx::navigation::human
             for (auto it2 = it1 + 1; it2 != cluster.points.end();)
             {
                 auto& point2 = *it2;
-                //TODO does subtraction work for vectors like this?
                 maxSize = std::max(maxSize, (point2 - point1).norm());
             }
         }
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index ab1ac283..b31ae524 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -36,11 +36,9 @@
 
 namespace armarx::navigation::human
 {
-    using T = double;
-    using Vector = Eigen::Matrix<T, 2, 1>;
-    using SystemModelT = kalman_filter::SystemModelSO2xR2<T>;
     using Cluster = armem::vision::LaserScannerFeature;
 
+
     /**
      * @brief The HumanTracker class can be used to track and filter multiple humans. It hides
      * implementation detail on how new detected humans are associated to the old, already tracked
-- 
GitLab


From 609ed1d468420f26a84b5cc804047f153d6b8e06 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 27 Oct 2022 15:13:11 +0200
Subject: [PATCH 254/324] Feed lasersensor results from reader to humanTracker

---
 .../dynamic_scene_provider/Component.cpp      | 19 ++++++++++++++++++-
 1 file changed, 18 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 185d5568..4a177243 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -349,11 +349,28 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         // here ends: data fetching
 
-        ARMARX_INFO << "Running human tracker";
+        ARMARX_INFO << "Running human tracker with camera measurements";
 
         humanTracker.update(human::HumanTracker::CameraMeasurement{
             .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
 
+        ARMARX_INFO << "Running human tracker with lasersensor measurements";
+
+        //TODO why is result a vector of LSFs and not a vector of LSF?
+        std::vector<armem::vision::LaserScannerFeature> flattened;
+        for (auto const& fs : laserFeaturesResult.features)
+        {
+            flattened.insert(flattened.end(), fs.features.begin(), fs.features.end());
+        }
+        std::vector<armem::vision::LaserScannerFeature> clusters =
+            humanTracker.update(human::HumanTracker::LaserMeasurement{.detectionTime = timestamp,
+                                                                      .clusters = flattened});
+
+        ARMARX_INFO << "Human tracking done";
+
+
+        //TODO use clusters for obstacle creation
+
 
         humanWriterPlugin->get().store(humanTracker.getTrackedHumans(), getName(), timestamp);
     }
-- 
GitLab


From 482aee62149a70d1538cf23de64dc2c48502d2c4 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Thu, 27 Oct 2022 15:17:31 +0200
Subject: [PATCH 255/324] Add human tracker test (this, for real)

---
 .../human/test/human_tracker_test.cpp         | 96 +++++++++++++++++++
 1 file changed, 96 insertions(+)
 create mode 100644 source/armarx/navigation/human/test/human_tracker_test.cpp

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
new file mode 100644
index 00000000..641c8f5f
--- /dev/null
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -0,0 +1,96 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Timo Weberruß ( timo dot weberruss at student dot kit dot edu )
+ * @date       2022
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include <ArmarXCore/core/time/DateTime.h>
+#include <ArmarXCore/core/time/Duration.h>
+#include <ArmarXCore/interface/core/BasicVectorTypes.h>
+
+#include <VisionX/libraries/armem_human/types.h>
+
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/HumanFilter.h>
+#include <armarx/navigation/human/HumanTracker.h>
+#include <armarx/navigation/human/types.h>
+
+// test includes
+#define BOOST_TEST_MODULE Navigation::ArmarXLibraries::human
+#define ARMARX_BOOST_TEST
+
+#include <armarx/navigation/Test.h>
+
+using armarx::armem::human::HumanPose;
+using armarx::armem::human::PoseKeypoint;
+using armarx::navigation::core::Pose2D;
+using CamMm = armarx::navigation::human::HumanTracker::CameraMeasurement;
+using LaserMm = armarx::navigation::human::HumanTracker::LaserMeasurement;
+using Eigen::Vector2f;
+
+namespace armarx::navigation::human
+{
+    Eigen::Quaternionf
+    quatFromEuler(float roll, float pitch, float yaw)
+    {
+        return Eigen::AngleAxisf(roll, Eigen::Vector3f::UnitX()) *
+               Eigen::AngleAxisf(pitch, Eigen::Vector3f::UnitY()) *
+               Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ());
+    }
+
+    BOOST_AUTO_TEST_CASE(testLaserTracking)
+    {
+        HumanTracker tracker = HumanTracker();
+
+        Eigen::Vector3f initialPosition(0, 0, 2);
+        Eigen::Quaternionf orientation = quatFromEuler(0, 0, M_PI_2);
+
+        std::int64_t timestepMs = 100;
+        Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
+        int cameraSteps = 10;
+
+        Eigen::Vector3f posDelta = movementSpeedMetPerSec * (timestepMs / 1000);
+
+        std::vector<CamMm> camMeasurements = std::vector<CamMm>();
+        for (int i = 0; i < cameraSteps; i++)
+        {
+            DateTime t = DateTime(Duration::MilliSeconds(i * timestepMs));
+
+            Eigen::Vector3f newPos = initialPosition + i * posDelta;
+            FramedPosition headPosition = FramedPosition(newPos, "", "");
+            FramedOrientation headOrientation = FramedOrientation(orientation, "", "");
+            PoseKeypoint head = {.label = "HEAD",
+                                 .confidence = 0.95,
+                                 .positionGlobal = headPosition,
+                                 .orientationGlobal = headOrientation};
+            HumanPose pose = {"posemodelid", {{"HEAD", head}}};
+            std::vector<armem::human::HumanPose> humanPoses = {pose};
+            CamMm camMm = {t, humanPoses};
+
+            tracker.update(camMm);
+        }
+
+        // TODO: now add a lasersensor measurement roughly at the next human pose
+
+        DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
+
+        std::vector<Cluster> clusters = std::vector<Cluster>();
+        LaserMm laserMm;
+        tracker.update(laserMm);
+    }
+} // namespace armarx::navigation::human
-- 
GitLab


From 7224a74cb0dd02e12bc46a72d4506d6c28c8c94b Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 27 Oct 2022 15:35:39 +0200
Subject: [PATCH 256/324] Use ellipsoids saved in clusters instead of iterating
 over points

---
 .../armarx/navigation/human/HumanTracker.cpp  | 41 ++++---------------
 1 file changed, 8 insertions(+), 33 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 689600e2..db56cbe6 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -59,13 +59,7 @@ namespace armarx::navigation::human
 
             if (getClusterSize(cluster) <= 2 * parameters.maxFootprintSize)
             {
-                //calculate center of cluster
-                Eigen::Vector2f clusterCenter;
-                for (auto& point : cluster.points)
-                {
-                    clusterCenter += point;
-                }
-                clusterCenter /= cluster.points.size();
+                Eigen::Vector2f clusterCenter = cluster.ellipsoid.pose.translation();
 
                 potentialFootprints.push_back(AdvancedCluster{
                     .center = clusterCenter, .cluster = cluster, .associated = false});
@@ -99,21 +93,13 @@ namespace armarx::navigation::human
             // found both footprints, so associate both footprints and update human with new pose
             else
             {
-                //calculate center of the points of both footprints combined
-                auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster.points;
-                auto& footprint2 = posDistance.newCluster->cluster.points;
+                //calculate center between both footprints
+                auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster;
+                auto& footprint2 = posDistance.newCluster->cluster;
 
-                //TODO more efficient by just calculating mean between two circle centers for example
-                Eigen::Vector2f centerPos;
-                for (auto& point : footprint1)
-                {
-                    centerPos += point;
-                }
-                for (auto& point : footprint2)
-                {
-                    centerPos += point;
-                }
-                centerPos /= (footprint1.size() + footprint2.size());
+                Eigen::Vector2f centerPos = (footprint1.ellipsoid.pose.translation() +
+                                             footprint2.ellipsoid.pose.translation()) /
+                                            2;
 
                 //create pose with orientation from old human
                 core::Pose2D pose = core::Pose2D::Identity();
@@ -357,18 +343,7 @@ namespace armarx::navigation::human
     float
     HumanTracker::getClusterSize(Cluster cluster)
     {
-        //TODO more effictient by using radius of circle saved in cluster for example
-        float maxSize = 0;
-        for (auto it1 = cluster.points.begin(); it1 != cluster.points.end();)
-        {
-            auto& point1 = *it1;
-            for (auto it2 = it1 + 1; it2 != cluster.points.end();)
-            {
-                auto& point2 = *it2;
-                maxSize = std::max(maxSize, (point2 - point1).norm());
-            }
-        }
-        return maxSize;
+        return std::max(cluster.ellipsoid.radii.x(), cluster.ellipsoid.radii.y());
     }
 
     void
-- 
GitLab


From 71f79526ae19f6da1ecc543a029cf0b9a5b99939 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Thu, 27 Oct 2022 15:37:21 +0200
Subject: [PATCH 257/324] Remove unnecessary comment

---
 source/armarx/navigation/human/HumanTracker.cpp | 8 --------
 1 file changed, 8 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index db56cbe6..ea22b062 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -202,14 +202,6 @@ namespace armarx::navigation::human
                 // calculate angle of rot2
                 yaw = atan2(rot2.y(), rot2.x());
             }
-            //old version using euler angles:
-            //yaw = humanPose //from all human pose keypoints
-            //          .keypoints
-            //          .at(parameters.rotationKeypoint) //find the keypoint representing the head
-            //          .orientationGlobal //get its global orientation
-            //          ->toEigen()
-            //          .eulerAngles(2, 1, 0)[0]; //and extract the yaw (rotation around z axis in
-            //                                                                  global coordinates)
         }
 
         // create the new pose with the calculated position and yaw
-- 
GitLab


From 6242f7ab995eeb2606de7923d8c54ac4f4144f5e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Thu, 27 Oct 2022 15:38:12 +0200
Subject: [PATCH 258/324] Save WIP state of human tracker test

---
 .../human/test/human_tracker_test.cpp         | 26 ++++++++++++++++---
 1 file changed, 22 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 641c8f5f..29d64823 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -58,13 +58,15 @@ namespace armarx::navigation::human
         HumanTracker tracker = HumanTracker();
 
         Eigen::Vector3f initialPosition(0, 0, 2);
-        Eigen::Quaternionf orientation = quatFromEuler(0, 0, M_PI_2);
+        float orientation = M_PI_2;
+        Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
 
         std::int64_t timestepMs = 100;
         Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
         int cameraSteps = 10;
 
-        Eigen::Vector3f posDelta = movementSpeedMetPerSec * (timestepMs / 1000);
+        Eigen::Vector3f posDelta =
+            movementSpeedMetPerSec * (static_cast<float>(timestepMs) / 1000.0);
 
         std::vector<CamMm> camMeasurements = std::vector<CamMm>();
         for (int i = 0; i < cameraSteps; i++)
@@ -73,7 +75,7 @@ namespace armarx::navigation::human
 
             Eigen::Vector3f newPos = initialPosition + i * posDelta;
             FramedPosition headPosition = FramedPosition(newPos, "", "");
-            FramedOrientation headOrientation = FramedOrientation(orientation, "", "");
+            FramedOrientation headOrientation = FramedOrientation(orientationQuat, "", "");
             PoseKeypoint head = {.label = "HEAD",
                                  .confidence = 0.95,
                                  .positionGlobal = headPosition,
@@ -85,10 +87,26 @@ namespace armarx::navigation::human
             tracker.update(camMm);
         }
 
-        // TODO: now add a lasersensor measurement roughly at the next human pose
 
         DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
 
+        using Point = Eigen::Vector2f;
+
+        std::vector<Point> relOffsets = {Point(0.01, 0.003),
+                                         Point(-0.02, 0.007),
+                                         Point(-0.01, -0.01),
+                                         Point(0.015, 0.009),
+                                         Point(0.002, 0.001)};
+
+        Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
+        //Eigen::Vector3f leftFootPos = laserPos
+
+        std::vector<Point> leftFootPoints = std::vector<Point>();
+        for (Point& offset : relOffsets)
+        {
+            //leftFootPoints.emplace_back();
+        }
+
         std::vector<Cluster> clusters = std::vector<Cluster>();
         LaserMm laserMm;
         tracker.update(laserMm);
-- 
GitLab


From b66799a97ab7afb8385c4699a50e5c8b5f74ed49 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Fri, 4 Nov 2022 12:36:14 +0100
Subject: [PATCH 259/324] Complete test case basic code

---
 .../human/test/human_tracker_test.cpp         | 43 ++++++++++++++++---
 1 file changed, 38 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 29d64823..734243ac 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -42,6 +42,7 @@ using armarx::navigation::core::Pose2D;
 using CamMm = armarx::navigation::human::HumanTracker::CameraMeasurement;
 using LaserMm = armarx::navigation::human::HumanTracker::LaserMeasurement;
 using Eigen::Vector2f;
+using Ellipsoid = armarx::armem::vision::Ellipsoid;
 
 namespace armarx::navigation::human
 {
@@ -53,10 +54,12 @@ namespace armarx::navigation::human
                Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ());
     }
 
-    BOOST_AUTO_TEST_CASE(testLaserTracking)
+    BOOST_AUTO_TEST_CASE(testLaserTrackingTwoFeetCluster)
     {
         HumanTracker tracker = HumanTracker();
 
+        // PARAMETERS
+
         Eigen::Vector3f initialPosition(0, 0, 2);
         float orientation = M_PI_2;
         Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
@@ -65,6 +68,9 @@ namespace armarx::navigation::human
         Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
         int cameraSteps = 10;
 
+
+        // CAMERA MEASUREMENTS
+
         Eigen::Vector3f posDelta =
             movementSpeedMetPerSec * (static_cast<float>(timestepMs) / 1000.0);
 
@@ -87,6 +93,7 @@ namespace armarx::navigation::human
             tracker.update(camMm);
         }
 
+        // LASER MEASUREMENT
 
         DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
 
@@ -99,16 +106,42 @@ namespace armarx::navigation::human
                                          Point(0.002, 0.001)};
 
         Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
-        //Eigen::Vector3f leftFootPos = laserPos
+        Eigen::Vector3f leftFootPos = laserPos + Point(0, 0.1);
+        Eigen::Vector3f rightFootPos = laserPos + Point(0, -0.1);
 
         std::vector<Point> leftFootPoints = std::vector<Point>();
+        std::vector<Point> rightFootPoints = std::vector<Point>();
         for (Point& offset : relOffsets)
         {
-            //leftFootPoints.emplace_back();
+            leftFootPoints.emplace_back(leftFootPos + offset);
+            rightFootPoints.emplace_back(rightFootPos + offset);
         }
 
-        std::vector<Cluster> clusters = std::vector<Cluster>();
-        LaserMm laserMm;
+        using Pose = Eigen::Isometry3f;
+        Pose leftFootPose = Pose::Identity();
+        leftFootPose.translation() = leftFootPos;
+        leftFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
+
+        Pose rightFootPose = Pose::Identity();
+        rightFootPose.translation() = rightFootPos;
+        rightFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
+
+        Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
+        Ellipsoid rightFootEllipse = {.pose = rightFootPose, .radii = Point(0.05, 0.04)};
+
+        Cluster leftFootCluster = {.ellipsoid = leftFootEllipse, .points = leftFootPoints};
+        Cluster rightFootCluster = {.ellipsoid = rightFootEllipse, .points = rightFootPoints};
+
+        std::vector<Cluster> clusters = std::vector<Cluster>{leftFootCluster, rightFootCluster};
+
+        LaserMm laserMm = {.detectionTime = tLaser, .clusters = clusters};
         tracker.update(laserMm);
+
+        std::vector<Human> humans = tracker.getTrackedHumans();
+        BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
+        Human h = humans.at(0);
+        BOOST_CHECK_CLOSE(h.pose.translation().x(), 1.0, 0.05);
+        BOOST_CHECK(h.pose.translation().y() < 0.05);
+        BOOST_CHECK_CLOSE(h.linearVelocity.x(), 1.0, 0.2);
     }
 } // namespace armarx::navigation::human
-- 
GitLab


From 23e4942a59753a4b64571f9ee63459987bfa00b7 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Fri, 4 Nov 2022 12:39:57 +0100
Subject: [PATCH 260/324] Make everything const that isn't at 3 on the tree

---
 .../human/test/human_tracker_test.cpp         | 77 ++++++++++---------
 1 file changed, 39 insertions(+), 38 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 734243ac..25e24fa3 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -60,58 +60,58 @@ namespace armarx::navigation::human
 
         // PARAMETERS
 
-        Eigen::Vector3f initialPosition(0, 0, 2);
-        float orientation = M_PI_2;
-        Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
+        const Eigen::Vector3f initialPosition(0, 0, 2);
+        const float orientation = M_PI_2;
+        const Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
 
-        std::int64_t timestepMs = 100;
-        Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
-        int cameraSteps = 10;
+        const std::int64_t timestepMs = 100;
+        const Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
+        const int cameraSteps = 10;
 
 
         // CAMERA MEASUREMENTS
 
-        Eigen::Vector3f posDelta =
+        const Eigen::Vector3f posDelta =
             movementSpeedMetPerSec * (static_cast<float>(timestepMs) / 1000.0);
 
-        std::vector<CamMm> camMeasurements = std::vector<CamMm>();
+        const std::vector<CamMm> camMeasurements = std::vector<CamMm>();
         for (int i = 0; i < cameraSteps; i++)
         {
-            DateTime t = DateTime(Duration::MilliSeconds(i * timestepMs));
-
-            Eigen::Vector3f newPos = initialPosition + i * posDelta;
-            FramedPosition headPosition = FramedPosition(newPos, "", "");
-            FramedOrientation headOrientation = FramedOrientation(orientationQuat, "", "");
-            PoseKeypoint head = {.label = "HEAD",
-                                 .confidence = 0.95,
-                                 .positionGlobal = headPosition,
-                                 .orientationGlobal = headOrientation};
-            HumanPose pose = {"posemodelid", {{"HEAD", head}}};
-            std::vector<armem::human::HumanPose> humanPoses = {pose};
-            CamMm camMm = {t, humanPoses};
+            const DateTime t = DateTime(Duration::MilliSeconds(i * timestepMs));
+
+            const Eigen::Vector3f newPos = initialPosition + i * posDelta;
+            const FramedPosition headPosition = FramedPosition(newPos, "", "");
+            const FramedOrientation headOrientation = FramedOrientation(orientationQuat, "", "");
+            const PoseKeypoint head = {.label = "HEAD",
+                                       .confidence = 0.95,
+                                       .positionGlobal = headPosition,
+                                       .orientationGlobal = headOrientation};
+            const HumanPose pose = {"posemodelid", {{"HEAD", head}}};
+            const std::vector<armem::human::HumanPose> humanPoses = {pose};
+            const CamMm camMm = {t, humanPoses};
 
             tracker.update(camMm);
         }
 
         // LASER MEASUREMENT
 
-        DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
+        const DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
 
         using Point = Eigen::Vector2f;
 
-        std::vector<Point> relOffsets = {Point(0.01, 0.003),
-                                         Point(-0.02, 0.007),
-                                         Point(-0.01, -0.01),
-                                         Point(0.015, 0.009),
-                                         Point(0.002, 0.001)};
+        const std::vector<Point> relOffsets = {Point(0.01, 0.003),
+                                               Point(-0.02, 0.007),
+                                               Point(-0.01, -0.01),
+                                               Point(0.015, 0.009),
+                                               Point(0.002, 0.001)};
 
-        Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
-        Eigen::Vector3f leftFootPos = laserPos + Point(0, 0.1);
-        Eigen::Vector3f rightFootPos = laserPos + Point(0, -0.1);
+        const Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
+        const Eigen::Vector3f leftFootPos = laserPos + Point(0, 0.1);
+        const Eigen::Vector3f rightFootPos = laserPos + Point(0, -0.1);
 
         std::vector<Point> leftFootPoints = std::vector<Point>();
         std::vector<Point> rightFootPoints = std::vector<Point>();
-        for (Point& offset : relOffsets)
+        for (const Point& offset : relOffsets)
         {
             leftFootPoints.emplace_back(leftFootPos + offset);
             rightFootPoints.emplace_back(rightFootPos + offset);
@@ -126,20 +126,21 @@ namespace armarx::navigation::human
         rightFootPose.translation() = rightFootPos;
         rightFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
 
-        Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
-        Ellipsoid rightFootEllipse = {.pose = rightFootPose, .radii = Point(0.05, 0.04)};
+        const Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
+        const Ellipsoid rightFootEllipse = {.pose = rightFootPose, .radii = Point(0.05, 0.04)};
 
-        Cluster leftFootCluster = {.ellipsoid = leftFootEllipse, .points = leftFootPoints};
-        Cluster rightFootCluster = {.ellipsoid = rightFootEllipse, .points = rightFootPoints};
+        const Cluster leftFootCluster = {.ellipsoid = leftFootEllipse, .points = leftFootPoints};
+        const Cluster rightFootCluster = {.ellipsoid = rightFootEllipse, .points = rightFootPoints};
 
-        std::vector<Cluster> clusters = std::vector<Cluster>{leftFootCluster, rightFootCluster};
+        const std::vector<Cluster> clusters =
+            std::vector<Cluster>{leftFootCluster, rightFootCluster};
 
-        LaserMm laserMm = {.detectionTime = tLaser, .clusters = clusters};
+        const LaserMm laserMm = {.detectionTime = tLaser, .clusters = clusters};
         tracker.update(laserMm);
 
-        std::vector<Human> humans = tracker.getTrackedHumans();
+        const std::vector<Human> humans = tracker.getTrackedHumans();
         BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
-        Human h = humans.at(0);
+        const Human h = humans.at(0);
         BOOST_CHECK_CLOSE(h.pose.translation().x(), 1.0, 0.05);
         BOOST_CHECK(h.pose.translation().y() < 0.05);
         BOOST_CHECK_CLOSE(h.linearVelocity.x(), 1.0, 0.2);
-- 
GitLab


From 8c0e1770607ebadc3902f16156d03aa42fa2dd8c Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 4 Nov 2022 14:21:52 +0100
Subject: [PATCH 261/324] stack result reader + storing it in memory

---
 .../armarx/navigation/memory/CMakeLists.txt   |   2 +
 .../memory/client/stack_result/Reader.cpp     | 120 ++++++++++++++++++
 .../memory/client/stack_result/Reader.h       | 104 +++++++++++++++
 .../memory/client/stack_result/Writer.cpp     |   5 +-
 source/armarx/navigation/memory/constants.h   |   3 +
 .../event_publishing/MemoryPublisher.cpp      |   2 +-
 6 files changed, 233 insertions(+), 3 deletions(-)
 create mode 100644 source/armarx/navigation/memory/client/stack_result/Reader.cpp
 create mode 100644 source/armarx/navigation/memory/client/stack_result/Reader.h

diff --git a/source/armarx/navigation/memory/CMakeLists.txt b/source/armarx/navigation/memory/CMakeLists.txt
index eba21c61..267142f9 100644
--- a/source/armarx/navigation/memory/CMakeLists.txt
+++ b/source/armarx/navigation/memory/CMakeLists.txt
@@ -2,6 +2,7 @@ armarx_add_library(memory
     SOURCES
         #./memory.cpp
         client/stack_result/Writer.cpp
+        client/stack_result/Reader.cpp
         client/parameterization/Reader.cpp
         client/parameterization/Writer.cpp
         client/graph/Reader.cpp
@@ -14,6 +15,7 @@ armarx_add_library(memory
     HEADERS
         memory.h
         client/stack_result/Writer.h
+        client/stack_result/Reader.h
         client/parameterization/Reader.h
         client/parameterization/Writer.h
         client/graph/Reader.h
diff --git a/source/armarx/navigation/memory/client/stack_result/Reader.cpp b/source/armarx/navigation/memory/client/stack_result/Reader.cpp
new file mode 100644
index 00000000..f95e1997
--- /dev/null
+++ b/source/armarx/navigation/memory/client/stack_result/Reader.cpp
@@ -0,0 +1,120 @@
+#include "Reader.h"
+#include "RobotAPI/libraries/armem/client/query/Builder.h"
+
+#include <armarx/navigation/core/aron/Trajectory.aron.generated.h>
+#include <armarx/navigation/core/aron_conversions.h>
+#include <armarx/navigation/memory/constants.h>
+
+namespace armarx::navigation::memory::client::stack_result
+{
+    armarx::navigation::memory::client::stack_result::Reader::LocalPlannerResult
+    Reader::queryLocalPlannerResult(const Query& query)
+    {
+        const auto qb = buildLocalPlannerResultQuery(query);
+        const auto& providerName = query.clientID;
+
+        ARMARX_DEBUG << "[MappingDataReader] query ... ";
+
+        const armem::client::QueryResult qResult = memoryReader().query(qb.buildQueryInput());
+        ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
+
+        if (not qResult.success)
+        {
+            ARMARX_WARNING << "Failed to query data from memory: " << qResult.errorMessage;
+            return {.trajectory = {},
+                    .status = LocalPlannerResult::Status::Error,
+                    .errorMessage = qResult.errorMessage};
+        }
+
+        const auto coreSegment = qResult.memory.getCoreSegment(properties().coreSegmentName);
+
+        if (not coreSegment.hasProviderSegment(providerName))
+        {
+            ARMARX_DEBUG << "Provider segment `" << providerName << "` does not exist (yet).";
+            return {.trajectory = {}, .status = LocalPlannerResult::Status::NoData};
+        }
+
+        const armem::wm::ProviderSegment& providerSegment =
+            coreSegment.getProviderSegment(providerName);
+
+        if (providerSegment.empty())
+        {
+            ARMARX_DEBUG << "No entities.";
+            return {.trajectory = {},
+                    .status = LocalPlannerResult::Status::NoData,
+                    .errorMessage = "No entities"};
+        }
+
+        try
+        {
+            return LocalPlannerResult{.trajectory = asLocalPlannerResult(providerSegment),
+                                      .status = LocalPlannerResult::Status::Success};
+        }
+        catch (...)
+        {
+            return LocalPlannerResult{.trajectory = {},
+                                      .status = LocalPlannerResult::Status::Error,
+                                      .errorMessage = GetHandledExceptionString()};
+        }
+    }
+
+
+    std::string
+    Reader::propertyPrefix() const
+    {
+        return "mem.nav.stack_result.";
+    }
+
+    Reader::Properties
+    Reader::defaultProperties() const
+    {
+        return Properties{.memoryName = memory::constants::NavigationMemoryName,
+                          .coreSegmentName = memory::constants::LocalPlannerResultCoreSegment};
+    }
+
+    armarx::navigation::core::LocalTrajectory
+    Reader::asLocalPlannerResult(const armem::wm::ProviderSegment& providerSegment)
+    {
+        navigation::human::HumanGroups humans;
+
+        ARMARX_CHECK(not providerSegment.empty()) << "No entities";
+        ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
+
+        const armem::wm::EntityInstance* entityInstance = nullptr;
+
+        providerSegment.forEachEntity(
+            [&entityInstance](const armem::wm::Entity& entity)
+            {
+                const auto& entitySnapshot = entity.getLatestSnapshot();
+                ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
+
+                entityInstance = &entitySnapshot.getInstance(0);
+            });
+
+        ARMARX_CHECK_NOT_NULL(entityInstance);
+
+        const auto dto =
+            navigation::core::arondto::LocalTrajectory::FromAron(entityInstance->data());
+
+        armarx::navigation::core::LocalTrajectory localTrajectory;
+        fromAron(dto, localTrajectory);
+
+        return localTrajectory;
+    }
+    
+    armarx::armem::client::query::Builder Reader::buildLocalPlannerResultQuery(const Query& query) const
+    {
+        armarx::armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties().coreSegmentName)
+        .providerSegments().withName(query.clientID)
+        .entities().withName("trajectory")
+        .snapshots().beforeOrAtTime(query.timestamp);
+        // clang-format on
+
+        return qb;
+    }
+
+} // namespace armarx::navigation::memory::client::stack_result
diff --git a/source/armarx/navigation/memory/client/stack_result/Reader.h b/source/armarx/navigation/memory/client/stack_result/Reader.h
new file mode 100644
index 00000000..756d6f0b
--- /dev/null
+++ b/source/armarx/navigation/memory/client/stack_result/Reader.h
@@ -0,0 +1,104 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "ArmarXCore/core/time/DateTime.h"
+
+#include <RobotAPI/libraries/armem/client/util/SimpleReaderBase.h>
+
+#include "armarx/navigation/core/Trajectory.h"
+#include "armarx/navigation/local_planning/LocalPlanner.h"
+
+namespace armarx::navigation::memory::client::stack_result
+{
+
+    class Reader : virtual public armem::client::util::SimpleReaderBase
+    {
+    public:
+        using armem::client::util::SimpleReaderBase::SimpleReaderBase;
+
+        struct Query
+        {
+            DateTime timestamp;
+            std::string clientID;
+        };
+
+
+        struct LocalPlannerResult
+        {
+            armarx::navigation::core::LocalTrajectory trajectory;
+
+            enum Status
+            {
+                Success,
+                NoData,
+                Error
+            } status;
+
+            std::string errorMessage = "";
+
+            operator bool() const noexcept
+            {
+                return status == Status::Success;
+            }
+        };
+
+        struct GlobalPlannerResult
+        {
+            armarx::navigation::core::GlobalTrajectory trajectory;
+
+            enum Status
+            {
+                Success,
+                NoData,
+                Error
+            } status;
+
+            std::string errorMessage = "";
+
+            operator bool() const noexcept
+            {
+                return status == Status::Success;
+            }
+        };
+
+        GlobalPlannerResult queryGlobalPlannerResult(const Query& query);
+        LocalPlannerResult queryLocalPlannerResult(const Query& query);
+
+        std::string propertyPrefix() const override;
+        Properties defaultProperties() const override;
+
+    protected:
+    private:
+        armarx::navigation::core::LocalTrajectory
+        asLocalPlannerResult(const armem::wm::ProviderSegment& providerSegment);
+
+        armarx::navigation::core::GlobalTrajectory
+        asGlobalPlannerResult(const armem::wm::ProviderSegment& providerSegment);
+
+        armarx::armem::client::query::Builder
+        buildLocalPlannerResultQuery(const Query& query) const;
+
+        armarx::armem::client::query::Builder
+        buildGlobalPlannerResultQuery(const Query& query) const;
+    };
+} // namespace armarx::navigation::memory::client::stack_result
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.cpp b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
index 4ecb1efd..1fbdf8e1 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.cpp
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.cpp
@@ -8,6 +8,7 @@
 #include <armarx/navigation/core/aron/Trajectory.aron.generated.h>
 #include <armarx/navigation/core/aron/Twist.aron.generated.h>
 #include <armarx/navigation/core/aron_conversions.h>
+#include <armarx/navigation/memory/constants.h>
 
 namespace armarx::navigation::memory::client::stack_result
 {
@@ -68,7 +69,7 @@ namespace armarx::navigation::memory::client::stack_result
         armem::EntityUpdate update;
         update.entityID = armem::MemoryID()
                               .withMemoryName(properties().memoryName)
-                              .withCoreSegmentName("Results_GlobalPlanner")
+                              .withCoreSegmentName(constants::GlobalPlannerResultCoreSegment)
                               .withProviderSegmentName(clientID)
                               .withEntityName("trajectory")
                               .withTimestamp(timestamp);
@@ -98,7 +99,7 @@ namespace armarx::navigation::memory::client::stack_result
         armem::EntityUpdate update;
         update.entityID = armem::MemoryID()
                               .withMemoryName(properties().memoryName)
-                              .withCoreSegmentName("Results_LocalPlanner")
+                              .withCoreSegmentName(constants::LocalPlannerResultCoreSegment)
                               .withProviderSegmentName(clientID)
                               .withEntityName("trajectory")
                               .withTimestamp(timestamp);
diff --git a/source/armarx/navigation/memory/constants.h b/source/armarx/navigation/memory/constants.h
index 2b3364a8..f0932218 100644
--- a/source/armarx/navigation/memory/constants.h
+++ b/source/armarx/navigation/memory/constants.h
@@ -34,4 +34,7 @@ namespace armarx::navigation::memory::constants
     inline const std::string CostmapCoreSegmentName = "Costmap";
     inline const std::string HumanCoreSegmentName = "Human";
 
+    inline const std::string GlobalPlannerResultCoreSegment = "Results_GlobalPlanner";
+    inline const std::string LocalPlannerResultCoreSegment = "Results_LocalPlanner";
+
 } // namespace armarx::navigation::memory::constants
diff --git a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
index 0ea9699c..6c74049d 100644
--- a/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
+++ b/source/armarx/navigation/server/event_publishing/MemoryPublisher.cpp
@@ -54,7 +54,7 @@ namespace armarx::navigation::server
     void
     MemoryPublisher::localTrajectoryUpdated(const local_planning::LocalPlannerResult& res)
     {
-        // resultWriter->store(res, clientId);
+        resultWriter->store(res, clientId);
     }
 
     // void
-- 
GitLab


From c7bed5cbd01bf2436ed098845aea2bcfea8514d2 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Mon, 7 Nov 2022 12:47:15 +0100
Subject: [PATCH 262/324] Fix bugs

---
 .../armarx/navigation/human/HumanTracker.cpp  | 17 +++++++------
 .../human/test/human_tracker_test.cpp         | 25 +++++++++++--------
 2 files changed, 24 insertions(+), 18 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index ea22b062..4cde5d0d 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -7,6 +7,7 @@
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
 
+
 namespace armarx::navigation::human
 {
     void
@@ -53,13 +54,13 @@ namespace armarx::navigation::human
         // footprints
         std::vector<AdvancedCluster> potentialFootprints;
         std::vector<Cluster> unusedClusters;
-        for (auto it = measurements.clusters.begin(); it != measurements.clusters.end();)
+        for (const auto& cluster : measurements.clusters)
         {
-            auto& cluster = *it;
 
             if (getClusterSize(cluster) <= 2 * parameters.maxFootprintSize)
             {
-                Eigen::Vector2f clusterCenter = cluster.ellipsoid.pose.translation();
+                // TODO: Why is the ellipse translation() here 3D? Can we just use the first 2 entries?
+                Eigen::Vector2f clusterCenter = cluster.ellipsoid.pose.translation().segment(0, 2);
 
                 potentialFootprints.push_back(AdvancedCluster{
                     .center = clusterCenter, .cluster = cluster, .associated = false});
@@ -70,7 +71,6 @@ namespace armarx::navigation::human
             }
         }
 
-
         // associate humans and clusters by their distances
         const auto sortedDistances = getSortedDistances(trackedHumans, potentialFootprints);
 
@@ -97,9 +97,11 @@ namespace armarx::navigation::human
                 auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster;
                 auto& footprint2 = posDistance.newCluster->cluster;
 
-                Eigen::Vector2f centerPos = (footprint1.ellipsoid.pose.translation() +
-                                             footprint2.ellipsoid.pose.translation()) /
-                                            2;
+                // TODO: Why is the ellipse translation() here 3D? Can we just use the first 2 entries?
+                Eigen::Vector2f centerPos =
+                    (footprint1.ellipsoid.pose.translation().segment(0, 2) +
+                     footprint2.ellipsoid.pose.translation().segment(0, 2)) /
+                    2;
 
                 //create pose with orientation from old human
                 core::Pose2D pose = core::Pose2D::Identity();
@@ -146,7 +148,6 @@ namespace armarx::navigation::human
                 unusedClusters.push_back(cluster.cluster);
             }
         }
-
         return unusedClusters;
     }
 
diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 25e24fa3..19449812 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -19,6 +19,8 @@
  *             GNU General Public License
  */
 
+#include <iostream>
+
 #include <ArmarXCore/core/time/DateTime.h>
 #include <ArmarXCore/core/time/Duration.h>
 #include <ArmarXCore/interface/core/BasicVectorTypes.h>
@@ -68,7 +70,6 @@ namespace armarx::navigation::human
         const Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
         const int cameraSteps = 10;
 
-
         // CAMERA MEASUREMENTS
 
         const Eigen::Vector3f posDelta =
@@ -106,25 +107,27 @@ namespace armarx::navigation::human
                                                Point(0.002, 0.001)};
 
         const Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
-        const Eigen::Vector3f leftFootPos = laserPos + Point(0, 0.1);
-        const Eigen::Vector3f rightFootPos = laserPos + Point(0, -0.1);
+        const Eigen::Vector3f leftFootPos = laserPos + Eigen::Vector3f(0, 0.1, 0);
+        const Eigen::Vector3f rightFootPos = laserPos + Eigen::Vector3f(0, -0.1, 0);
 
         std::vector<Point> leftFootPoints = std::vector<Point>();
         std::vector<Point> rightFootPoints = std::vector<Point>();
+        int i = 0;
         for (const Point& offset : relOffsets)
         {
-            leftFootPoints.emplace_back(leftFootPos + offset);
-            rightFootPoints.emplace_back(rightFootPos + offset);
+            leftFootPoints.emplace_back(leftFootPos.segment(0, 2) + offset);
+            rightFootPoints.emplace_back(rightFootPos.segment(0, 2) + offset);
+            i++;
         }
 
         using Pose = Eigen::Isometry3f;
         Pose leftFootPose = Pose::Identity();
         leftFootPose.translation() = leftFootPos;
-        leftFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
+        //        leftFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
 
         Pose rightFootPose = Pose::Identity();
         rightFootPose.translation() = rightFootPos;
-        rightFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
+        //        rightFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
 
         const Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
         const Ellipsoid rightFootEllipse = {.pose = rightFootPose, .radii = Point(0.05, 0.04)};
@@ -136,13 +139,15 @@ namespace armarx::navigation::human
             std::vector<Cluster>{leftFootCluster, rightFootCluster};
 
         const LaserMm laserMm = {.detectionTime = tLaser, .clusters = clusters};
+
         tracker.update(laserMm);
 
         const std::vector<Human> humans = tracker.getTrackedHumans();
         BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
         const Human h = humans.at(0);
-        BOOST_CHECK_CLOSE(h.pose.translation().x(), 1.0, 0.05);
-        BOOST_CHECK(h.pose.translation().y() < 0.05);
-        BOOST_CHECK_CLOSE(h.linearVelocity.x(), 1.0, 0.2);
+        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.05);
+        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.05);
+        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMetPerSec.x() < 0.05);
+        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMetPerSec.y() < 0.05);
     }
 } // namespace armarx::navigation::human
-- 
GitLab


From 23b0fdd9be34bf4d08a63697f5af62cdc8730561 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 7 Nov 2022 16:23:06 +0100
Subject: [PATCH 263/324] Implement new cluster center function as ellipsoids
 are 3d objects

---
 source/armarx/navigation/human/HumanTracker.cpp | 12 ++++++++++++
 source/armarx/navigation/human/HumanTracker.h   |  7 +++++++
 2 files changed, 19 insertions(+)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 4cde5d0d..1c29cf40 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -339,6 +339,18 @@ namespace armarx::navigation::human
         return std::max(cluster.ellipsoid.radii.x(), cluster.ellipsoid.radii.y());
     }
 
+    Eigen::Vector2f
+    HumanTracker::getClusterCenter(Cluster cluster)
+    {
+        Eigen::Vector2f center;
+        for (auto& point : cluster.points)
+        {
+            center += point;
+        }
+        center /= cluster.points.size();
+        return center;
+    }
+
     void
     HumanTracker::prepareTrackedHumans(DateTime time)
     {
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index b31ae524..ab360521 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -200,6 +200,13 @@ namespace armarx::navigation::human
          * @return the size
          */
         float getClusterSize(Cluster cluster);
+        /**
+         * @brief HumanTracker::getClusterCenter Returns the center of the given cluster. That is
+         * calculated as the mean of all points.
+         * @param cluster The cluster whose center is calculated
+         * @return the center
+         */
+        Eigen::Vector2f HumanTracker::getClusterCenter(Cluster cluster);
         /**
          * @brief prepareTrackedHumans Deletes all tracked humans that received no update for too
          * long. All remaining tracked humans are prepared for association with the given point in
-- 
GitLab


From 163e91cf13030b5c83e4680a8f6269a5656a943c Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 7 Nov 2022 16:44:54 +0100
Subject: [PATCH 264/324] Use new implemented features, remove todos

---
 .../armarx/navigation/human/HumanTracker.cpp  | 21 +++++--------------
 1 file changed, 5 insertions(+), 16 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 1c29cf40..506bb660 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -45,8 +45,6 @@ namespace armarx::navigation::human
     std::vector<Cluster>
     HumanTracker::update(const LaserMeasurement& measurements)
     {
-        // TODO do we receive cluster with correct threshold / expected size / as accurate as that
-        // they distinguish multiple footprints?
 
         prepareTrackedHumans(measurements.detectionTime);
 
@@ -56,14 +54,10 @@ namespace armarx::navigation::human
         std::vector<Cluster> unusedClusters;
         for (const auto& cluster : measurements.clusters)
         {
-
             if (getClusterSize(cluster) <= 2 * parameters.maxFootprintSize)
             {
-                // TODO: Why is the ellipse translation() here 3D? Can we just use the first 2 entries?
-                Eigen::Vector2f clusterCenter = cluster.ellipsoid.pose.translation().segment(0, 2);
-
                 potentialFootprints.push_back(AdvancedCluster{
-                    .center = clusterCenter, .cluster = cluster, .associated = false});
+                    .center = getClusterCenter(cluster), .cluster = cluster, .associated = false});
             }
             else
             {
@@ -97,15 +91,10 @@ namespace armarx::navigation::human
                 auto& footprint1 = posDistance.oldHuman->associatedCluster->cluster;
                 auto& footprint2 = posDistance.newCluster->cluster;
 
-                // TODO: Why is the ellipse translation() here 3D? Can we just use the first 2 entries?
-                Eigen::Vector2f centerPos =
-                    (footprint1.ellipsoid.pose.translation().segment(0, 2) +
-                     footprint2.ellipsoid.pose.translation().segment(0, 2)) /
-                    2;
-
                 //create pose with orientation from old human
                 core::Pose2D pose = core::Pose2D::Identity();
-                pose.translation() = centerPos;
+                pose.translation() =
+                    (getClusterCenter(footprint1) + getClusterCenter(footprint2)) / 2;
                 pose.linear() = posDistance.oldHuman->humanFilter.get().pose.linear();
 
 
@@ -336,14 +325,14 @@ namespace armarx::navigation::human
     float
     HumanTracker::getClusterSize(Cluster cluster)
     {
-        return std::max(cluster.ellipsoid.radii.x(), cluster.ellipsoid.radii.y());
+        return 2 * cluster.circle.radius;
     }
 
     Eigen::Vector2f
     HumanTracker::getClusterCenter(Cluster cluster)
     {
         Eigen::Vector2f center;
-        for (auto& point : cluster.points)
+        for (auto& point : cluster.convexHull)
         {
             center += point;
         }
-- 
GitLab


From 78587f3021d7ed25cae705ef0fc233ae4d142524 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 7 Nov 2022 16:50:35 +0100
Subject: [PATCH 265/324] Fix copy paste bug

---
 source/armarx/navigation/human/HumanTracker.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index ab360521..59ea9f32 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -206,7 +206,7 @@ namespace armarx::navigation::human
          * @param cluster The cluster whose center is calculated
          * @return the center
          */
-        Eigen::Vector2f HumanTracker::getClusterCenter(Cluster cluster);
+        Eigen::Vector2f getClusterCenter(Cluster cluster);
         /**
          * @brief prepareTrackedHumans Deletes all tracked humans that received no update for too
          * long. All remaining tracked humans are prepared for association with the given point in
-- 
GitLab


From 0a60b3043c20bde822d153ffe1b7eddc4b3f7ef4 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Mon, 7 Nov 2022 17:12:12 +0100
Subject: [PATCH 266/324] Restructure human tracker test

---
 .../human/test/human_tracker_test.cpp         | 115 ++++++++++++------
 1 file changed, 80 insertions(+), 35 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 19449812..f7497fba 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -45,6 +45,7 @@ using CamMm = armarx::navigation::human::HumanTracker::CameraMeasurement;
 using LaserMm = armarx::navigation::human::HumanTracker::LaserMeasurement;
 using Eigen::Vector2f;
 using Ellipsoid = armarx::armem::vision::Ellipsoid;
+using Circle = armarx::armem::vision::Circle;
 
 namespace armarx::navigation::human
 {
@@ -56,48 +57,50 @@ namespace armarx::navigation::human
                Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ());
     }
 
-    BOOST_AUTO_TEST_CASE(testLaserTrackingTwoFeetCluster)
+    /**
+     * @brief generateCamMeasurements generates a series of linear camera measurements of a moving
+     * human's head. It will start at startPosition and linearly move to endPosition over the course of
+     * the given timespan, giving a vector with the given amount of steps inbetween.
+     *
+     * @param startPosition the 3D position of the human head at the first measurement
+     * @param endPosition the 3D position of the human head at the last measurement
+     * @param timespanMs the timespan in milliseconds over which the simulated human will move from start to end
+     * @param steps how many measurements will be made (incl. start and end measurement)
+     * @return a vector of <steps> measurements spread equally with regard to position and timespan
+     */
+    std::vector<CamMm>
+    generateCamMeasurements(const Eigen::Vector3f& startPosition,
+                            const Eigen::Vector3f& endPosition,
+                            const Eigen::Quaternionf& orientation,
+                            const int timespanMs,
+                            const int steps)
     {
-        HumanTracker tracker = HumanTracker();
-
-        // PARAMETERS
-
-        const Eigen::Vector3f initialPosition(0, 0, 2);
-        const float orientation = M_PI_2;
-        const Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
-
-        const std::int64_t timestepMs = 100;
-        const Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
-        const int cameraSteps = 10;
+        const double timestepMs = static_cast<double>(timespanMs) / steps;
+        const Eigen::Vector3f posDelta = (endPosition - startPosition) / steps;
 
-        // CAMERA MEASUREMENTS
-
-        const Eigen::Vector3f posDelta =
-            movementSpeedMetPerSec * (static_cast<float>(timestepMs) / 1000.0);
-
-        const std::vector<CamMm> camMeasurements = std::vector<CamMm>();
-        for (int i = 0; i < cameraSteps; i++)
+        std::vector<CamMm> measurements = std::vector<CamMm>();
+        for (int i = 0; i <= steps; i++)
         {
             const DateTime t = DateTime(Duration::MilliSeconds(i * timestepMs));
 
-            const Eigen::Vector3f newPos = initialPosition + i * posDelta;
+            const Eigen::Vector3f newPos = startPosition + i * posDelta;
             const FramedPosition headPosition = FramedPosition(newPos, "", "");
-            const FramedOrientation headOrientation = FramedOrientation(orientationQuat, "", "");
+            const FramedOrientation headOrientation = FramedOrientation(orientation, "", "");
             const PoseKeypoint head = {.label = "HEAD",
                                        .confidence = 0.95,
                                        .positionGlobal = headPosition,
                                        .orientationGlobal = headOrientation};
-            const HumanPose pose = {"posemodelid", {{"HEAD", head}}};
+            const HumanPose pose = {"posemodelid", {{"DONT_USE_ME", {}}, {"HEAD", head}}};
             const std::vector<armem::human::HumanPose> humanPoses = {pose};
             const CamMm camMm = {t, humanPoses};
-
-            tracker.update(camMm);
+            measurements.emplace_back(camMm);
         }
+        return measurements;
+    }
 
-        // LASER MEASUREMENT
-
-        const DateTime tLaser = DateTime(Duration::MilliSeconds(cameraSteps * timestepMs));
-
+    LaserMm
+    generateLaserMeasurement(const Eigen::Vector2f& pos, const DateTime& tLaser)
+    {
         using Point = Eigen::Vector2f;
 
         const std::vector<Point> relOffsets = {Point(0.01, 0.003),
@@ -106,17 +109,16 @@ namespace armarx::navigation::human
                                                Point(0.015, 0.009),
                                                Point(0.002, 0.001)};
 
-        const Eigen::Vector3f laserPos = initialPosition + cameraSteps * posDelta;
-        const Eigen::Vector3f leftFootPos = laserPos + Eigen::Vector3f(0, 0.1, 0);
-        const Eigen::Vector3f rightFootPos = laserPos + Eigen::Vector3f(0, -0.1, 0);
+        const Eigen::Vector2f leftFootPos = pos + Eigen::Vector3f(0, 0.1);
+        const Eigen::Vector2f rightFootPos = pos + Eigen::Vector3f(0, -0.1);
 
         std::vector<Point> leftFootPoints = std::vector<Point>();
         std::vector<Point> rightFootPoints = std::vector<Point>();
         int i = 0;
         for (const Point& offset : relOffsets)
         {
-            leftFootPoints.emplace_back(leftFootPos.segment(0, 2) + offset);
-            rightFootPoints.emplace_back(rightFootPos.segment(0, 2) + offset);
+            leftFootPoints.emplace_back(leftFootPos + offset);
+            rightFootPoints.emplace_back(rightFootPos + offset);
             i++;
         }
 
@@ -132,13 +134,56 @@ namespace armarx::navigation::human
         const Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
         const Ellipsoid rightFootEllipse = {.pose = rightFootPose, .radii = Point(0.05, 0.04)};
 
-        const Cluster leftFootCluster = {.ellipsoid = leftFootEllipse, .points = leftFootPoints};
-        const Cluster rightFootCluster = {.ellipsoid = rightFootEllipse, .points = rightFootPoints};
+        const Circle leftFootCircle = {.center = leftFootPos, .radius = 0.1};
+        const Circle rightFootCircle = {.center = rightFootPos, .radius = 0.1};
+
+        const Cluster leftFootCluster = {
+            .circle = leftFootCircle, .ellipsoid = leftFootEllipse, .points = leftFootPoints};
+        const Cluster rightFootCluster = {
+            .circle = rightFootCircle, .ellipsoid = rightFootEllipse, .points = rightFootPoints};
 
         const std::vector<Cluster> clusters =
             std::vector<Cluster>{leftFootCluster, rightFootCluster};
 
         const LaserMm laserMm = {.detectionTime = tLaser, .clusters = clusters};
+        return laserMm;
+    }
+
+    BOOST_AUTO_TEST_CASE(testLaserTrackingTwoFeetCluster)
+    {
+        HumanTracker tracker = HumanTracker();
+
+        // PARAMETERS
+
+        const Eigen::Vector2f initialPosition(0, 0, 2);
+        const float orientation = M_PI_2;
+        const Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
+
+        const std::int64_t timestepMs = 100;
+        const Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
+        const int cameraSteps = 10;
+
+        // CONVERSIONS
+        const float timespanMs = timestepMs * cameraSteps;
+        const Eigen::Vector2f endPosition =
+            initialPosition + movementSpeedMetPerSec * timespanMs / 1000;
+        const Eigen::Vector3f posDelta = (endPosition - initialPosition) / cameraSteps;
+
+        // CAMERA MEASUREMENTS
+
+        const std::vector<CamMm> camMeasurements = generateCamMeasurements(
+            initialPosition, endPosition, orientationQuat, timespanMs, cameraSteps);
+
+        for (const CamMm& measurement : camMeasurements)
+        {
+            tracker.update(measurement);
+        }
+
+        // LASER MEASUREMENT
+
+        const DateTime tLaser = DateTime(Duration::MilliSeconds(timespanMs + timestepMs));
+        Eigen::Vector2f laserPos = (endPosition + posDelta).segment(0, 2);
+        const LaserMm laserMm = generateLaserMeasurement(laserPos, tLaser);
 
         tracker.update(laserMm);
 
-- 
GitLab


From f6b42ec8c4fe58f8477acae32d2f4c1ae4bfe66b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Mon, 7 Nov 2022 17:17:33 +0100
Subject: [PATCH 267/324] Fix dimension mismatches

---
 .../navigation/human/test/human_tracker_test.cpp    | 13 +++++++------
 1 file changed, 7 insertions(+), 6 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index f7497fba..3d2e8037 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -109,8 +109,8 @@ namespace armarx::navigation::human
                                                Point(0.015, 0.009),
                                                Point(0.002, 0.001)};
 
-        const Eigen::Vector2f leftFootPos = pos + Eigen::Vector3f(0, 0.1);
-        const Eigen::Vector2f rightFootPos = pos + Eigen::Vector3f(0, -0.1);
+        const Eigen::Vector2f leftFootPos = pos + Eigen::Vector2f(0, 0.1);
+        const Eigen::Vector2f rightFootPos = pos + Eigen::Vector2f(0, -0.1);
 
         std::vector<Point> leftFootPoints = std::vector<Point>();
         std::vector<Point> rightFootPoints = std::vector<Point>();
@@ -124,11 +124,12 @@ namespace armarx::navigation::human
 
         using Pose = Eigen::Isometry3f;
         Pose leftFootPose = Pose::Identity();
-        leftFootPose.translation() = leftFootPos;
+        leftFootPose.translation() = Eigen::Vector3f(leftFootPos.x(), leftFootPos.y(), 0);
         //        leftFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
 
         Pose rightFootPose = Pose::Identity();
-        rightFootPose.translation() = rightFootPos;
+        rightFootPose.translation() = Eigen::Vector3f(rightFootPos.x(), rightFootPos.y(), 0);
+        ;
         //        rightFootPose.linear() = Eigen::Rotation2Df(orientation).toRotationMatrix();
 
         const Ellipsoid leftFootEllipse = {.pose = leftFootPose, .radii = Point(0.05, 0.04)};
@@ -155,7 +156,7 @@ namespace armarx::navigation::human
 
         // PARAMETERS
 
-        const Eigen::Vector2f initialPosition(0, 0, 2);
+        const Eigen::Vector3f initialPosition(0, 0, 2);
         const float orientation = M_PI_2;
         const Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
 
@@ -165,7 +166,7 @@ namespace armarx::navigation::human
 
         // CONVERSIONS
         const float timespanMs = timestepMs * cameraSteps;
-        const Eigen::Vector2f endPosition =
+        const Eigen::Vector3f endPosition =
             initialPosition + movementSpeedMetPerSec * timespanMs / 1000;
         const Eigen::Vector3f posDelta = (endPosition - initialPosition) / cameraSteps;
 
-- 
GitLab


From e508e128dc61efc775720afd9a24dd4afd97918f Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 7 Nov 2022 17:35:24 +0100
Subject: [PATCH 268/324] Change calculation of cluster center to calculate
 centroid

---
 .../armarx/navigation/human/HumanTracker.cpp  | 20 +++++++++++++++----
 1 file changed, 16 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 506bb660..1a1fa43f 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -1,5 +1,9 @@
 #include "HumanTracker.h"
 
+#include <boost/geometry.hpp>
+#include <boost/geometry/geometries/point_xy.hpp>
+#include <boost/geometry/geometries/polygon.hpp>
+
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
 #include "armarx/navigation/human/types.h"
@@ -331,13 +335,21 @@ namespace armarx::navigation::human
     Eigen::Vector2f
     HumanTracker::getClusterCenter(Cluster cluster)
     {
-        Eigen::Vector2f center;
+        typedef boost::geometry::model::d2::point_xy<double> boost_point;
+        typedef boost::geometry::model::polygon<boost_point> boost_polygon;
+
+        std::vector<boost_point> points;
         for (auto& point : cluster.convexHull)
         {
-            center += point;
+            points.push_back(boost_point(point.x(), point.y()));
         }
-        center /= cluster.points.size();
-        return center;
+        boost_polygon poly;
+        boost::geometry::assign_points(poly, points);
+
+        boost_point p;
+        boost::geometry::centroid(poly, p);
+
+        return Eigen::Vector2f{p.x(), p.y()};
     }
 
     void
-- 
GitLab


From 41fd3a3465698987bbb2f6232e80371a129be301 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 7 Nov 2022 18:00:06 +0100
Subject: [PATCH 269/324] Fix bugs

---
 source/armarx/navigation/human/HumanTracker.cpp | 4 ++++
 1 file changed, 4 insertions(+)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 1a1fa43f..076bc2f1 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -338,11 +338,15 @@ namespace armarx::navigation::human
         typedef boost::geometry::model::d2::point_xy<double> boost_point;
         typedef boost::geometry::model::polygon<boost_point> boost_polygon;
 
+        ARMARX_CHECK(!cluster.convexHull.empty());
         std::vector<boost_point> points;
         for (auto& point : cluster.convexHull)
         {
             points.push_back(boost_point(point.x(), point.y()));
         }
+        //make polygon enclosed
+        points.push_back(
+            boost_point(cluster.convexHull.front().x(), cluster.convexHull.front().y()));
         boost_polygon poly;
         boost::geometry::assign_points(poly, points);
 
-- 
GitLab


From 195e827f68398609ddef70ae09d99dcb88b2cfff Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 10 Nov 2022 19:13:42 +0100
Subject: [PATCH 270/324] build fix

---
 .../navigation/statecharts/NavigationGroup/NavigateTo.cpp    | 5 ++---
 1 file changed, 2 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
index 0db4ea9c..a4a3b8fe 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
@@ -29,6 +29,7 @@
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
@@ -37,8 +38,6 @@
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
 
 
 
@@ -67,7 +66,7 @@ namespace armarx::navigation::statecharts::navigation_group
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::AStarParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
         client::IceNavigator iceNavigator(getNavigator());
-- 
GitLab


From 74fadcd0425442fb3e584257180f9edf207f3d40 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Fri, 11 Nov 2022 11:35:26 +0100
Subject: [PATCH 271/324] Add convex hull to test clusters

---
 .../human/test/human_tracker_test.cpp         | 26 ++++++++++++-------
 1 file changed, 17 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 3d2e8037..3864f98d 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -103,11 +103,9 @@ namespace armarx::navigation::human
     {
         using Point = Eigen::Vector2f;
 
-        const std::vector<Point> relOffsets = {Point(0.01, 0.003),
-                                               Point(-0.02, 0.007),
-                                               Point(-0.01, -0.01),
-                                               Point(0.015, 0.009),
-                                               Point(0.002, 0.001)};
+        // These are convex
+        const std::vector<Point> relOffsets = {
+            Point(0.01, 0.003), Point(-0.02, 0.007), Point(-0.01, -0.01), Point(0.015, 0.009)};
 
         const Eigen::Vector2f leftFootPos = pos + Eigen::Vector2f(0, 0.1);
         const Eigen::Vector2f rightFootPos = pos + Eigen::Vector2f(0, -0.1);
@@ -121,6 +119,12 @@ namespace armarx::navigation::human
             rightFootPoints.emplace_back(rightFootPos + offset);
             i++;
         }
+        std::vector<Point> leftFootHull = std::vector<Point>(leftFootPoints);
+        std::vector<Point> rightFootHull = std::vector<Point>(rightFootPoints);
+
+        // Add one more non-convex point to the cluster points
+        leftFootPoints.emplace_back(leftFootPos + Point(0.002, 0.001));
+        rightFootPoints.emplace_back(rightFootPos + Point(0.002, 0.003));
 
         using Pose = Eigen::Isometry3f;
         Pose leftFootPose = Pose::Identity();
@@ -138,10 +142,14 @@ namespace armarx::navigation::human
         const Circle leftFootCircle = {.center = leftFootPos, .radius = 0.1};
         const Circle rightFootCircle = {.center = rightFootPos, .radius = 0.1};
 
-        const Cluster leftFootCluster = {
-            .circle = leftFootCircle, .ellipsoid = leftFootEllipse, .points = leftFootPoints};
-        const Cluster rightFootCluster = {
-            .circle = rightFootCircle, .ellipsoid = rightFootEllipse, .points = rightFootPoints};
+        const Cluster leftFootCluster = {.convexHull = leftFootHull,
+                                         .circle = leftFootCircle,
+                                         .ellipsoid = leftFootEllipse,
+                                         .points = leftFootPoints};
+        const Cluster rightFootCluster = {.convexHull = rightFootHull,
+                                          .circle = rightFootCircle,
+                                          .ellipsoid = rightFootEllipse,
+                                          .points = rightFootPoints};
 
         const std::vector<Cluster> clusters =
             std::vector<Cluster>{leftFootCluster, rightFootCluster};
-- 
GitLab


From 3366a428847844c8ee0c93c25fee330c22748a51 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Fri, 11 Nov 2022 12:39:59 +0100
Subject: [PATCH 272/324] Use millimeters in test instead of meters

Because HumanTracker uses millimeters as well
---
 .../navigation/human/test/human_tracker_test.cpp   | 14 +++++++-------
 1 file changed, 7 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 3864f98d..8afb1a61 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -164,18 +164,18 @@ namespace armarx::navigation::human
 
         // PARAMETERS
 
-        const Eigen::Vector3f initialPosition(0, 0, 2);
+        const Eigen::Vector3f initialPosition = Eigen::Vector3f(0, 0, 2) * 1000;
         const float orientation = M_PI_2;
         const Eigen::Quaternionf orientationQuat = quatFromEuler(0, 0, orientation);
 
         const std::int64_t timestepMs = 100;
-        const Eigen::Vector3f movementSpeedMetPerSec(1, 0, 0);
+        const Eigen::Vector3f movementSpeedMmPerSec = Eigen::Vector3f(1, 0, 0) * 1000;
         const int cameraSteps = 10;
 
         // CONVERSIONS
         const float timespanMs = timestepMs * cameraSteps;
         const Eigen::Vector3f endPosition =
-            initialPosition + movementSpeedMetPerSec * timespanMs / 1000;
+            initialPosition + movementSpeedMmPerSec * timespanMs / 1000;
         const Eigen::Vector3f posDelta = (endPosition - initialPosition) / cameraSteps;
 
         // CAMERA MEASUREMENTS
@@ -199,9 +199,9 @@ namespace armarx::navigation::human
         const std::vector<Human> humans = tracker.getTrackedHumans();
         BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
         const Human h = humans.at(0);
-        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.05);
-        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.05);
-        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMetPerSec.x() < 0.05);
-        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMetPerSec.y() < 0.05);
+        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.05 * 1000);
+        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.05 * 1000);
+        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.05 * 1000);
+        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.05 * 1000);
     }
 } // namespace armarx::navigation::human
-- 
GitLab


From 8ae3db70e4cc707a3c25a29db21eceb1694e9d9c Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Mon, 14 Nov 2022 12:34:32 +0100
Subject: [PATCH 273/324] Add debug prints and change sensitivity

---
 .../human/test/human_tracker_test.cpp           | 17 +++++++++++++----
 1 file changed, 13 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 8afb1a61..64d61891 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -21,6 +21,7 @@
 
 #include <iostream>
 
+#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/time/DateTime.h>
 #include <ArmarXCore/core/time/Duration.h>
 #include <ArmarXCore/interface/core/BasicVectorTypes.h>
@@ -183,9 +184,16 @@ namespace armarx::navigation::human
         const std::vector<CamMm> camMeasurements = generateCamMeasurements(
             initialPosition, endPosition, orientationQuat, timespanMs, cameraSteps);
 
+        int i = 0;
         for (const CamMm& measurement : camMeasurements)
         {
+            const Eigen::Vector3f mPos = initialPosition + i * posDelta;
+            ARMARX_INFO << "Measurement at position " << mPos.x() << ", " << mPos.y() << ", "
+                        << mPos.z();
             tracker.update(measurement);
+            const Eigen::Vector2f tPos = tracker.getTrackedHumans().at(0).pose.translation();
+            ARMARX_INFO << "tracker now thinks human is at " << tPos.x() << ", " << tPos.y();
+            i++;
         }
 
         // LASER MEASUREMENT
@@ -199,9 +207,10 @@ namespace armarx::navigation::human
         const std::vector<Human> humans = tracker.getTrackedHumans();
         BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
         const Human h = humans.at(0);
-        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.05 * 1000);
-        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.05 * 1000);
-        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.05 * 1000);
-        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.05 * 1000);
+        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.1 * 1000);
+        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.1 * 1000);
+        ARMARX_INFO << "velocity: " << h.linearVelocity.x() << ", " << h.linearVelocity.y();
+        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.1 * 1000);
+        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.1 * 1000);
     }
 } // namespace armarx::navigation::human
-- 
GitLab


From ac2d88bc97ed6504ec04da38c1e93713ee6b4799 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 14 Nov 2022 14:43:12 +0100
Subject: [PATCH 274/324] Fix all compiler warnings

---
 .../human/test/human_tracker_test.cpp         | 32 ++++++++++++-------
 .../human/test/so2kalmanFilterTest.cpp        |  1 -
 2 files changed, 20 insertions(+), 13 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 64d61891..05a32b18 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -84,13 +84,17 @@ namespace armarx::navigation::human
         {
             const DateTime t = DateTime(Duration::MilliSeconds(i * timestepMs));
 
+            const Eigen::Vector3f dummyPos = Eigen::Vector3f::Zero();
+            const FramedPosition cameraDummyPos = FramedPosition(dummyPos, "", "");
+
             const Eigen::Vector3f newPos = startPosition + i * posDelta;
             const FramedPosition headPosition = FramedPosition(newPos, "", "");
             const FramedOrientation headOrientation = FramedOrientation(orientation, "", "");
-            const PoseKeypoint head = {.label = "HEAD",
-                                       .confidence = 0.95,
-                                       .positionGlobal = headPosition,
-                                       .orientationGlobal = headOrientation};
+            const PoseKeypoint head = PoseKeypoint{.label = "HEAD",
+                                                   .confidence = 0.95,
+                                                   .positionCamera = cameraDummyPos,
+                                                   .positionGlobal = headPosition,
+                                                   .orientationGlobal = headOrientation};
             const HumanPose pose = {"posemodelid", {{"DONT_USE_ME", {}}, {"HEAD", head}}};
             const std::vector<armem::human::HumanPose> humanPoses = {pose};
             const CamMm camMm = {t, humanPoses};
@@ -143,14 +147,18 @@ namespace armarx::navigation::human
         const Circle leftFootCircle = {.center = leftFootPos, .radius = 0.1};
         const Circle rightFootCircle = {.center = rightFootPos, .radius = 0.1};
 
-        const Cluster leftFootCluster = {.convexHull = leftFootHull,
-                                         .circle = leftFootCircle,
-                                         .ellipsoid = leftFootEllipse,
-                                         .points = leftFootPoints};
-        const Cluster rightFootCluster = {.convexHull = rightFootHull,
-                                          .circle = rightFootCircle,
-                                          .ellipsoid = rightFootEllipse,
-                                          .points = rightFootPoints};
+        const Cluster leftFootCluster = {
+            .convexHull = leftFootHull,
+            .circle = leftFootCircle,
+            .ellipsoid = leftFootEllipse,
+            .chain = leftFootPoints, //don't use me, probably initialized wrong
+            .points = leftFootPoints};
+        const Cluster rightFootCluster = {
+            .convexHull = rightFootHull,
+            .circle = rightFootCircle,
+            .ellipsoid = rightFootEllipse,
+            .chain = rightFootPoints, //don't use me, probably initialized wrong
+            .points = rightFootPoints};
 
         const std::vector<Cluster> clusters =
             std::vector<Cluster>{leftFootCluster, rightFootCluster};
diff --git a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
index 48529d44..0ae9fc51 100644
--- a/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
+++ b/source/armarx/navigation/human/test/so2kalmanFilterTest.cpp
@@ -71,7 +71,6 @@ namespace armarx::navigation::human
         {
             const T t = dt * i;
             const T angle = t * c;
-            const T last_angle = dt * (i - 1) * c;
 
             const Vector last_pos = states.at(i - 1).position;
             //const Vector pos(angle, std::cos(angle));
-- 
GitLab


From 8a8a0446aa967e93749dc82f944937e56e0ced4c Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Mon, 14 Nov 2022 15:01:14 +0100
Subject: [PATCH 275/324] Add final position debug print

---
 source/armarx/navigation/human/test/human_tracker_test.cpp | 1 +
 1 file changed, 1 insertion(+)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 05a32b18..3e6fc3e6 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -217,6 +217,7 @@ namespace armarx::navigation::human
         const Human h = humans.at(0);
         BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.1 * 1000);
         BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.1 * 1000);
+        ARMARX_INFO << "position: " << h.pose.translation().x() << ", " << h.pose.translation().y();
         ARMARX_INFO << "velocity: " << h.linearVelocity.x() << ", " << h.linearVelocity.y();
         BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.1 * 1000);
         BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.1 * 1000);
-- 
GitLab


From c9e76faed3d83ba1d57c6bea8a4f9a9dd484292e Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 14 Nov 2022 15:17:36 +0100
Subject: [PATCH 276/324] Fix initialization of Pose2D

---
 source/armarx/navigation/human/HumanFilter.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index ba786d13..50ba6b27 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -94,7 +94,7 @@ namespace armarx::navigation::human
     core::Pose2D
     HumanFilter::fromUkfState(const SystemModelT::StateT& pose)
     {
-        core::Pose2D pose2d;
+        core::Pose2D pose2d = core::Pose2D::Identity();
         // [m] to [mm]
         pose2d.translation().x() = pose.pose.x() * 1000;
         pose2d.translation().y() = pose.pose.y() * 1000;
-- 
GitLab


From fd4df794a0401ab97d30fdaefbc0e77c1c55f988 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 14 Nov 2022 16:21:34 +0100
Subject: [PATCH 277/324] Add some debug comments

---
 .../human/test/human_tracker_test.cpp         | 24 +++++++++++++------
 1 file changed, 17 insertions(+), 7 deletions(-)

diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index 3e6fc3e6..e9fc5a51 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -192,16 +192,26 @@ namespace armarx::navigation::human
         const std::vector<CamMm> camMeasurements = generateCamMeasurements(
             initialPosition, endPosition, orientationQuat, timespanMs, cameraSteps);
 
-        int i = 0;
+        //int i = 0;
         for (const CamMm& measurement : camMeasurements)
         {
-            const Eigen::Vector3f mPos = initialPosition + i * posDelta;
-            ARMARX_INFO << "Measurement at position " << mPos.x() << ", " << mPos.y() << ", "
-                        << mPos.z();
+            //ARMARX_INFO << "bla";
+            //const Eigen::Vector3f mPos = initialPosition + i * posDelta;
+            //ARMARX_INFO << "Measurement at position " << mPos.x() << ", " << mPos.y() << ", "
+            //<< mPos.z();
             tracker.update(measurement);
-            const Eigen::Vector2f tPos = tracker.getTrackedHumans().at(0).pose.translation();
-            ARMARX_INFO << "tracker now thinks human is at " << tPos.x() << ", " << tPos.y();
-            i++;
+            //const Eigen::Vector2f tPos = tracker.getTrackedHumans().at(0).pose.translation();
+            //ARMARX_INFO << "tracker now thinks human is at " << tPos.x() << ", " << tPos.y();
+            //i++;
+        }
+
+        ARMARX_INFO << "state after loop:";
+        for (auto& h : tracker.getTrackedHumans())
+        {
+            BOOST_TEST_MESSAGE("-----------");
+            BOOST_TEST_MESSAGE("time: " << h.detectionTime);
+            BOOST_TEST_MESSAGE("pose:\n" << h.pose.matrix());
+            BOOST_TEST_MESSAGE("vel:\n" << h.linearVelocity);
         }
 
         // LASER MEASUREMENT
-- 
GitLab


From 6d5eaf7c32c3409126ed17ff73b5b8195dce5c71 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 14 Nov 2022 17:28:56 +0100
Subject: [PATCH 278/324] Debug HumanFilter

---
 source/armarx/navigation/human/HumanFilter.cpp | 10 +++++++++-
 source/armarx/navigation/human/HumanFilter.h   |  8 ++++----
 2 files changed, 13 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index 50ba6b27..124a415d 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -9,7 +9,7 @@ namespace armarx::navigation::human
         human.pose = pose0;
         human.linearVelocity = Eigen::Vector2f::Zero();
         human.detectionTime = detectionTime;
-
+        oldHuman = human;
 
         //initialize new kalman filter for new detected human
         UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
@@ -39,6 +39,8 @@ namespace armarx::navigation::human
     void
     HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
     {
+        //return;
+
         double dt = (detectionTime - human.detectionTime).toSecondsDouble();
 
         SystemModelT::ControlT control = toUkfControl(human.linearVelocity);
@@ -51,6 +53,12 @@ namespace armarx::navigation::human
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
+        /*human.detectionTime = detectionTime;
+        human.linearVelocity = (pose.translation() - human.pose.translation()) /
+                               (detectionTime - oldHuman.detectionTime).toSecondsDouble();
+        human.pose = pose;
+        return;*/
+
         double dt = (detectionTime - oldHuman.detectionTime).toSecondsDouble();
 
         //update ukf with new observation
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index ceb13aa1..9a9b03f6 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -91,18 +91,18 @@ namespace armarx::navigation::human
         SystemModelT::ObsT toUkfObs(const core::Pose2D& pose);
 
     private:
-        Parameters params;
+        Parameters params{};
         /**
          * @brief oldHuman stores information about the human at the point in time of the last
          * HumanFilter::update call
          */
-        Human oldHuman;
+        Human oldHuman{};
         /**
          * @brief human stores information about the human at the point in time of the last
          * HumanFilter::propagation call
          */
-        Human human;
-        std::unique_ptr<UnscentedKalmanFilter<SystemModelT>> ukf;
+        Human human{};
+        std::unique_ptr<UnscentedKalmanFilter<SystemModelT>> ukf = nullptr;
     };
 
 } // namespace armarx::navigation::human
-- 
GitLab


From 534e3666304caf09555ef733d14de6750e638956 Mon Sep 17 00:00:00 2001
From: Corvin-N <corvin@navarro.de>
Date: Mon, 14 Nov 2022 19:25:28 +0100
Subject: [PATCH 279/324] Fix HumanTracking and clean up human_tracker_test

Fix implementation of tracking and association and get
human_tracker_test working.
Increase steps of test and reduce error tolerance.
---
 .../armarx/navigation/human/HumanFilter.cpp   |  8 ----
 .../armarx/navigation/human/HumanTracker.cpp  |  2 +-
 .../human/test/human_tracker_test.cpp         | 45 +++++++++----------
 3 files changed, 21 insertions(+), 34 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index 124a415d..b31edcfd 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -39,8 +39,6 @@ namespace armarx::navigation::human
     void
     HumanFilter::propagation(const armarx::core::time::DateTime& detectionTime)
     {
-        //return;
-
         double dt = (detectionTime - human.detectionTime).toSecondsDouble();
 
         SystemModelT::ControlT control = toUkfControl(human.linearVelocity);
@@ -53,12 +51,6 @@ namespace armarx::navigation::human
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
-        /*human.detectionTime = detectionTime;
-        human.linearVelocity = (pose.translation() - human.pose.translation()) /
-                               (detectionTime - oldHuman.detectionTime).toSecondsDouble();
-        human.pose = pose;
-        return;*/
-
         double dt = (detectionTime - oldHuman.detectionTime).toSecondsDouble();
 
         //update ukf with new observation
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 076bc2f1..e4bf473a 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -168,7 +168,7 @@ namespace armarx::navigation::human
         ARMARX_CHECK_NOT_EMPTY(keypoints);
 
         // calculate the arithmetic mean of all keypoint positions
-        Eigen::Vector3f centerPos;
+        Eigen::Vector3f centerPos = Eigen::Vector3f::Zero();
         int size = 0;
         for (const auto& [_, v] : keypoints)
         {
diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index e9fc5a51..f653299e 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -21,7 +21,6 @@
 
 #include <iostream>
 
-#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/time/DateTime.h>
 #include <ArmarXCore/core/time/Duration.h>
 #include <ArmarXCore/interface/core/BasicVectorTypes.h>
@@ -95,7 +94,7 @@ namespace armarx::navigation::human
                                                    .positionCamera = cameraDummyPos,
                                                    .positionGlobal = headPosition,
                                                    .orientationGlobal = headOrientation};
-            const HumanPose pose = {"posemodelid", {{"DONT_USE_ME", {}}, {"HEAD", head}}};
+            const HumanPose pose = {.poseModelId = "posemodelid", .keypoints = {{"HEAD", head}}};
             const std::vector<armem::human::HumanPose> humanPoses = {pose};
             const CamMm camMm = {t, humanPoses};
             measurements.emplace_back(camMm);
@@ -179,7 +178,7 @@ namespace armarx::navigation::human
 
         const std::int64_t timestepMs = 100;
         const Eigen::Vector3f movementSpeedMmPerSec = Eigen::Vector3f(1, 0, 0) * 1000;
-        const int cameraSteps = 10;
+        const int cameraSteps = 100;
 
         // CONVERSIONS
         const float timespanMs = timestepMs * cameraSteps;
@@ -192,26 +191,20 @@ namespace armarx::navigation::human
         const std::vector<CamMm> camMeasurements = generateCamMeasurements(
             initialPosition, endPosition, orientationQuat, timespanMs, cameraSteps);
 
-        //int i = 0;
         for (const CamMm& measurement : camMeasurements)
         {
-            //ARMARX_INFO << "bla";
-            //const Eigen::Vector3f mPos = initialPosition + i * posDelta;
-            //ARMARX_INFO << "Measurement at position " << mPos.x() << ", " << mPos.y() << ", "
-            //<< mPos.z();
             tracker.update(measurement);
-            //const Eigen::Vector2f tPos = tracker.getTrackedHumans().at(0).pose.translation();
-            //ARMARX_INFO << "tracker now thinks human is at " << tPos.x() << ", " << tPos.y();
-            //i++;
-        }
 
-        ARMARX_INFO << "state after loop:";
-        for (auto& h : tracker.getTrackedHumans())
-        {
-            BOOST_TEST_MESSAGE("-----------");
-            BOOST_TEST_MESSAGE("time: " << h.detectionTime);
-            BOOST_TEST_MESSAGE("pose:\n" << h.pose.matrix());
-            BOOST_TEST_MESSAGE("vel:\n" << h.linearVelocity);
+            int i = 0;
+            for (const auto& trackedHuman : tracker.getTrackedHumans())
+            {
+                const Eigen::Vector2f tPos = trackedHuman.pose.translation();
+                BOOST_TEST_MESSAGE("tracker now thinks human "
+                                   << i << " is at x=(" << tPos.x() << "," << tPos.y()
+                                   << ") moving with v=(" << trackedHuman.linearVelocity.x() << ","
+                                   << trackedHuman.linearVelocity.y() << ")");
+                i++;
+            }
         }
 
         // LASER MEASUREMENT
@@ -225,11 +218,13 @@ namespace armarx::navigation::human
         const std::vector<Human> humans = tracker.getTrackedHumans();
         BOOST_CHECK_EQUAL(humans.size(), 1); // should have detected the one human through laser
         const Human h = humans.at(0);
-        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.1 * 1000);
-        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.1 * 1000);
-        ARMARX_INFO << "position: " << h.pose.translation().x() << ", " << h.pose.translation().y();
-        ARMARX_INFO << "velocity: " << h.linearVelocity.x() << ", " << h.linearVelocity.y();
-        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.1 * 1000);
-        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.1 * 1000);
+        BOOST_CHECK(h.pose.translation().x() - laserPos.x() < 0.05 * 1000);
+        BOOST_CHECK(h.pose.translation().y() - laserPos.y() < 0.05 * 1000);
+        BOOST_TEST_MESSAGE("final position: x=(" << h.pose.translation().x() << ","
+                                                 << h.pose.translation().y() << ")");
+        BOOST_TEST_MESSAGE("final velocity: v=(" << h.linearVelocity.x() << ","
+                                                 << h.linearVelocity.y() << ")");
+        BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.05 * 1000);
+        BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.05 * 1000);
     }
 } // namespace armarx::navigation::human
-- 
GitLab


From a41c0b8cb81fc7771fb97d05640a75a72241631d Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 21 Nov 2022 19:04:06 +0100
Subject: [PATCH 280/324] Add SimpleVirtualRobot for AzureKinectOnTripod

---
 .../config/SimpleVirtualRobot.cfg             | 255 ++++++++++++++++++
 1 file changed, 255 insertions(+)
 create mode 100644 scenarios/HumanAwareNavigation/config/SimpleVirtualRobot.cfg

diff --git a/scenarios/HumanAwareNavigation/config/SimpleVirtualRobot.cfg b/scenarios/HumanAwareNavigation/config/SimpleVirtualRobot.cfg
new file mode 100644
index 00000000..25864f55
--- /dev/null
+++ b/scenarios/HumanAwareNavigation/config/SimpleVirtualRobot.cfg
@@ -0,0 +1,255 @@
+# ==================================================================
+# SimpleVirtualRobot properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.SimpleVirtualRobot.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimpleVirtualRobot.EnableProfiling = false
+
+
+# ArmarX.SimpleVirtualRobot.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.SimpleVirtualRobot.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.SimpleVirtualRobot.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimpleVirtualRobot.ObjectName = ""
+
+
+# ArmarX.SimpleVirtualRobot.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimpleVirtualRobot.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.SimpleVirtualRobot.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimpleVirtualRobot.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.SimpleVirtualRobot.p.oneShot:  If true, commit once after connecting, then stop.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimpleVirtualRobot.p.oneShot = true
+
+
+# ArmarX.SimpleVirtualRobot.p.robot.jointValues:  Specify a certain joint configuration.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.SimpleVirtualRobot.p.robot.jointValues = { "tripod_joint_x":5000, "tripod_joint_y":0, "tripod_joint_rotation": -1.57, "mount_joint_height":250, "mount_joint_pitch":1.85}
+
+
+# ArmarX.SimpleVirtualRobot.p.robot.name:  Optional override for the robot name. If not set, the default name from the robot model is used.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.SimpleVirtualRobot.p.robot.name = "AzureKinectCamera"
+
+
+# ArmarX.SimpleVirtualRobot.p.robot.package:  Package of the Simox robot XML.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.SimpleVirtualRobot.p.robot.package = "PriorKnowledgeData"
+
+
+# ArmarX.SimpleVirtualRobot.p.robot.path:  Local path of the Simox robot XML.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+ArmarX.SimpleVirtualRobot.p.robot.path = "robots/AzureKinectOnTripod/AzureKinectOnTripod.xml"
+
+
+# ArmarX.SimpleVirtualRobot.p.updateFrequency:  Memory update frequency (write).
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimpleVirtualRobot.p.updateFrequency = 10
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
-- 
GitLab


From e06e5238985f7f75d427f1d283b1797e4cd3ab06 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 21 Nov 2022 19:07:12 +0100
Subject: [PATCH 281/324] Fix Head kexpoint name

---
 source/armarx/navigation/human/HumanTracker.cpp | 6 +++---
 source/armarx/navigation/human/HumanTracker.h   | 2 +-
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index e4bf473a..71d964d1 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -182,10 +182,10 @@ namespace armarx::navigation::human
 
         // calculate the yaw of the specified keypoint representing the orientation if it exists
         double yaw = 0;
-        if (humanPose.keypoints.count(parameters.rotationKeypoint) > 0)
+        auto head = humanPose.keypoints.find(parameters.rotationKeypoint);
+        if (head != humanPose.keypoints.end())
         {
-            const armem::human::PoseKeypoint& refKeypoint =
-                humanPose.keypoints.at(parameters.rotationKeypoint);
+            const armem::human::PoseKeypoint& refKeypoint = head->second;
             ARMARX_CHECK(refKeypoint.orientationGlobal.has_value());
             Eigen::Quaternionf qhead = refKeypoint.orientationGlobal->toEigenQuaternion();
             Eigen::Vector3f vec(1, 0, 0);
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 59ea9f32..9176f62b 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -102,7 +102,7 @@ namespace armarx::navigation::human
         struct Parameters
         {
             // the keypoint which should be used for calculating the rotation of the humans
-            const std::string rotationKeypoint = "HEAD";
+            const std::string rotationKeypoint = "Head";
             // the duration after which tracked humans will be erased if no new measurement for
             // this human is found
             Duration maxTrackingAge = Duration::MilliSeconds(500);
-- 
GitLab


From 300081bfae25ad99cd0ed2ea9cd706ee559f683b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Wed, 23 Nov 2022 12:14:30 +0100
Subject: [PATCH 282/324] Add test case for deletion of old humans

---
 .../dynamic_scene_provider/Component.cpp        |  6 +++++-
 .../human/test/human_tracker_test.cpp           | 17 +++++++++++++++++
 2 files changed, 22 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 4a177243..80f27318 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -354,6 +354,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         humanTracker.update(human::HumanTracker::CameraMeasurement{
             .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
 
+
         ARMARX_INFO << "Running human tracker with lasersensor measurements";
 
         //TODO why is result a vector of LSFs and not a vector of LSF?
@@ -371,8 +372,11 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         //TODO use clusters for obstacle creation
 
+        std::vector<human::Human> humans = humanTracker.getTrackedHumans();
+
+        ARMARX_INFO << "Detected " << humans.size() << " humans";
 
-        humanWriterPlugin->get().store(humanTracker.getTrackedHumans(), getName(), timestamp);
+        humanWriterPlugin->get().store(humans, getName(), timestamp);
     }
 
 
diff --git a/source/armarx/navigation/human/test/human_tracker_test.cpp b/source/armarx/navigation/human/test/human_tracker_test.cpp
index f653299e..32202149 100644
--- a/source/armarx/navigation/human/test/human_tracker_test.cpp
+++ b/source/armarx/navigation/human/test/human_tracker_test.cpp
@@ -227,4 +227,21 @@ namespace armarx::navigation::human
         BOOST_CHECK(h.linearVelocity.x() - movementSpeedMmPerSec.x() < 0.05 * 1000);
         BOOST_CHECK(h.linearVelocity.y() - movementSpeedMmPerSec.y() < 0.05 * 1000);
     }
+
+
+    BOOST_AUTO_TEST_CASE(testRemoveOldHumans)
+    {
+        HumanTracker tracker = HumanTracker();
+        auto zero = Eigen::Vector3f(0.f, 0.f, 0.f);
+        auto measurements =
+            generateCamMeasurements(zero, zero, Eigen::Quaternionf::Identity(), 0, 1);
+        tracker.update(measurements.at(0));
+
+        BOOST_CHECK_EQUAL(tracker.getTrackedHumans().size(), 1);
+
+        CamMm late = {.detectionTime = DateTime(Duration::MilliSeconds(1000))};
+        tracker.update(late);
+
+        BOOST_CHECK_EQUAL(tracker.getTrackedHumans().size(), 0);
+    }
 } // namespace armarx::navigation::human
-- 
GitLab


From 10f81aa6917f5ff6e26289afa8f903d71181528b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 28 Nov 2022 16:00:24 +0100
Subject: [PATCH 283/324] Set proper configuration for pose detection

---
 .../components/dynamic_scene_provider/Component.cpp  |  2 +-
 .../components/dynamic_scene_provider/Component.h    |  2 +-
 .../navigation/components/navigation_memory/Visu.cpp | 12 ++++++++++--
 3 files changed, 12 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 80f27318..4f72fc40 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -217,7 +217,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         const armem::human::client::Reader::Result humanPoseResult =
             humanPoseReaderPlugin->get().query(humanPoseQuery);
-        ARMARX_CHECK_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Success)
+        ARMARX_CHECK_NOT_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Error)
             << humanPoseResult.errorMessage;
 
         ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index 7d58e1bd..aec652dd 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -153,7 +153,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
                 float occupiedThreshold = 0.55;
             } occupancyGrid;
 
-            std::string humanPoseProvider = "OpenNIPointCloudProvider";
+            std::string humanPoseProvider = "AzureKinectPointCloudProvider";
         };
         Properties properties;
         /* Use a mutex if you access variables from different threads
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 2b5e1aa0..e0d9a99d 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -180,7 +180,7 @@ namespace armarx::navigation::memory
         visualize(const human::Humans& humans, viz::Layer& layer)
         {
 
-            const Eigen::Translation3f human_T_mmm(Eigen::Vector3f{0,0, 1000});
+            const Eigen::Translation3f human_T_mmm(Eigen::Vector3f{0, 0, 1000});
 
             ARMARX_INFO << "Visualizing " << humans.size() << " humans";
             for (const auto& human : humans)
@@ -198,10 +198,18 @@ namespace armarx::navigation::memory
                 viz::Robot mmm(std::to_string(layer.size()));
                 mmm.file("RobotAPI", "RobotAPI/robots/MMM/mmm.xml");
                 mmm.pose(conv::to3D(human.pose) * human_T_mmm);
-                mmm.scale(1.7); // 1.7m 
+                mmm.scale(1.7); // 1.7m
                 mmm.overrideColor(viz::Color::orange(255, 100));
                 layer.add(mmm);
 
+
+                core::Pose pose3d = conv::to3D(human.pose);
+                pose3d.translation() += Eigen::Vector3f{0, 0, 1000};
+                auto arrow = viz::Arrow(std::to_string(layer.size()))
+                                 .pose(pose3d)
+                                 .length(200)
+                                 .color(simox::Color::red());
+                layer.add(arrow);
             }
         }
 
-- 
GitLab


From 89b7528a811b6c88ebb5d5e074172f8b8bf42573 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 28 Nov 2022 16:16:19 +0100
Subject: [PATCH 284/324] Add SimpleVirtualRobot to HumanAwareNavigation
 scenario

---
 scenarios/HumanAwareNavigation/HumanAwareNavigation.scx | 1 +
 1 file changed, 1 insertion(+)

diff --git a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
index 942bdb1b..ef910fb5 100644
--- a/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
+++ b/scenarios/HumanAwareNavigation/HumanAwareNavigation.scx
@@ -14,5 +14,6 @@
 	<application name="HumanMemoryApp" instance="" package="VisionX" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="human_simulator" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="SimpleVirtualRobot" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
 
-- 
GitLab


From 1eed433e9de52b03bfaa80e30b628d369cd76d6e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 29 Nov 2022 13:57:43 +0100
Subject: [PATCH 285/324] better dealing with teb as optional dependency

---
 .../components/example_client/Component.cpp   |   2 +-
 .../components/navigation_memory/Component.h  |  17 +-
 .../components/navigator/RemoteGui.cpp        |   2 +-
 .../factories/LocalPlannerFactory.cpp         |   7 +
 .../LocationGraphEditor/WidgetController.cpp  |   3 +-
 .../navigation/local_planning/CMakeLists.txt  |  40 ++++-
 .../local_planning/TimedElasticBands.cpp      |  25 +--
 .../TimedElasticBandsParams.cpp               |  29 ++++
 .../local_planning/TimedElasticBandsParams.h  |  44 ++++++
 .../local_planning/aron_conversions.cpp       | 134 +---------------
 .../local_planning/aron_conversions.h         |   4 -
 .../local_planning/aron_conversions_teb.cpp   | 146 ++++++++++++++++++
 .../local_planning/aron_conversions_teb.h     |  19 +++
 13 files changed, 292 insertions(+), 180 deletions(-)
 create mode 100644 source/armarx/navigation/local_planning/TimedElasticBandsParams.cpp
 create mode 100644 source/armarx/navigation/local_planning/TimedElasticBandsParams.h
 create mode 100644 source/armarx/navigation/local_planning/aron_conversions_teb.cpp
 create mode 100644 source/armarx/navigation/local_planning/aron_conversions_teb.h

diff --git a/examples/components/example_client/Component.cpp b/examples/components/example_client/Component.cpp
index 11261fa1..1110c342 100644
--- a/examples/components/example_client/Component.cpp
+++ b/examples/components/example_client/Component.cpp
@@ -37,7 +37,7 @@
 #include "armarx/navigation/conversions/eigen.h"
 #include "armarx/navigation/core/types.h"
 #include "armarx/navigation/global_planning/SPFA.h"
-#include "armarx/navigation/local_planning/TimedElasticBands.h"
+#include "armarx/navigation/local_planning/TimedElasticBandsParams.h"
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
diff --git a/source/armarx/navigation/components/navigation_memory/Component.h b/source/armarx/navigation/components/navigation_memory/Component.h
index 3361f180..b1b1a1b6 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -22,20 +22,19 @@
 
 #pragma once
 
+#include <mutex>
+
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/services/tasks/TaskUtil.h>
-
 #include <ArmarXCore/interface/core/PackagePath.h>
+
 #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
 
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 #include <RobotAPI/libraries/armem/server/plugins.h>
 #include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h>
-// #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h>
 
-#include <mutex>
-
-#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h>
+#include <armarx/navigation/components/navigation_memory/ComponentInterface.h>
 
 
 namespace armarx::navigation::components::navigation_memory
@@ -65,8 +64,8 @@ namespace armarx::navigation::components::navigation_memory
         std::string getDefaultName() const override;
 
         static std::string GetDefaultName();
-        bool storeLocationGraph(const armarx::data::PackagePath& packagePath, const Ice::Current& current) override; 
-
+        bool storeLocationGraph(const armarx::data::PackagePath& packagePath,
+                                const Ice::Current& current) override;
 
 
     protected:
@@ -108,7 +107,7 @@ namespace armarx::navigation::components::navigation_memory
                 bool visuHumans = true;
 
                 bool visuTransparent = false;
-                
+
                 float visuFrequency = 10;
             };
             LocationGraph locationGraph;
@@ -142,4 +141,4 @@ namespace armarx::navigation::components::navigation_memory
         Tasks tasks;
     };
 
-}  // namespace armarx::navigation::components::navigation_memory
+} // namespace armarx::navigation::components::navigation_memory
diff --git a/source/armarx/navigation/components/navigator/RemoteGui.cpp b/source/armarx/navigation/components/navigator/RemoteGui.cpp
index c63a52c4..f1dafca6 100644
--- a/source/armarx/navigation/components/navigator/RemoteGui.cpp
+++ b/source/armarx/navigation/components/navigator/RemoteGui.cpp
@@ -16,7 +16,7 @@
 #include <ArmarXGui/libraries/RemoteGui/WidgetProxy.h>
 
 #include "Component.h"
-#include "armarx/navigation/local_planning/TimedElasticBands.h"
+#include "armarx/navigation/local_planning/TimedElasticBandsParams.h"
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/factories/NavigationStackFactory.h>
diff --git a/source/armarx/navigation/factories/LocalPlannerFactory.cpp b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
index 1dcb347b..967d693b 100644
--- a/source/armarx/navigation/factories/LocalPlannerFactory.cpp
+++ b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
@@ -5,8 +5,12 @@
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 #include <RobotAPI/libraries/aron/core/data/variant/primitive/String.h>
 
+#include "armarx/navigation/local_planning/core.h"
 #include <armarx/navigation/core/constants.h>
+
+#ifdef TIMED_ELASTIC_BANDS_ENABLED
 #include <armarx/navigation/local_planning/TimedElasticBands.h>
+#endif
 
 namespace armarx::navigation::fac
 {
@@ -33,8 +37,11 @@ namespace armarx::navigation::fac
         switch (algo)
         {
             case local_planning::Algorithms::TimedElasticBands:
+                #ifdef TIMED_ELASTIC_BANDS_ENABLED
                 localPlanner = std::make_shared<local_planning::TimedElasticBands>(
                     local_planning::TimedElasticBandsParams::FromAron(algoParams), ctx);
+                #endif
+
                 break;
         }
 
diff --git a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp
index b59ac4cf..c0f9df03 100644
--- a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp
+++ b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp
@@ -41,13 +41,12 @@
 #include "widgets/graph_scene/Scene.h"
 #include "widgets/graph_scene/Widget.h"
 #include "widgets/utils.h"
-#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
 #include <armarx/navigation/graph/constants.h>
 #include <armarx/navigation/gui-plugins/LocationGraphEditor/ui_LocationGraphEditorWidget.h>
 #include <armarx/navigation/location/constants.h>
-#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h>
+#include <armarx/navigation/components/navigation_memory/ComponentInterface.h>
 
 // Qt headers
 #include <QDialog>
diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 4b5d36b1..27607e3f 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -3,7 +3,8 @@ armarx_add_aron_library(local_planning_aron
         aron/TimedElasticBands.xml
 )
 
-armarx_add_library(local_planning
+
+armarx_add_library(local_planning_core
     DEPENDENCIES_PUBLIC
         ArmarXCoreInterfaces
         ArmarXCore
@@ -12,6 +13,26 @@ armarx_add_library(local_planning
         armarx_navigation::conversions
         armarx_navigation::algorithms
         armarx_navigation::local_planning_aron
+    DEPENDENCIES_PRIVATE
+        range-v3::range-v3
+    SOURCES
+        LocalPlanner.cpp
+        aron_conversions.cpp
+        TimedElasticBandsParams.cpp
+    HEADERS
+        LocalPlanner.h
+        TimedElasticBandsParams.h
+        core.h
+        aron_conversions.h
+    OBJECT
+)
+
+armarx_add_library(local_planning_teb
+    DEPENDENCIES_PUBLIC
+        ArmarXCoreInterfaces
+        ArmarXCore
+        ArViz
+        armarx_navigation::local_planning_core
         armarx_navigation::teb_human
         teb_extension::obstacles
     DEPENDENCIES_PRIVATE
@@ -19,16 +40,23 @@ armarx_add_library(local_planning
     DEPENDENCIES_LEGACY
         teb_local_planner
     SOURCES 
-        LocalPlanner.cpp
         TimedElasticBands.cpp
         TebObstacleManager.cpp
         ros_conversions.cpp
-        aron_conversions.cpp
+        aron_conversions_teb.cpp
     HEADERS
-        LocalPlanner.h
         TimedElasticBands.h
         TebObstacleManager.h
         ros_conversions.h
-        core.h
-        aron_conversions.h
+        aron_conversions_teb.h
+    OBJECT
+)
+
+armarx_add_library(local_planning
+    DEPENDENCIES_PUBLIC
+        armarx_navigation::local_planning_core
+    #DEPENDENCIES_PUBLIC_OPTIONAL
+    #    armarx_navigation::local_planning_teb
+    DEPENDENCIES_PRIVATE
+        range-v3::range-v3
 )
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 16f873a3..50572732 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -26,30 +26,7 @@
 namespace armarx::navigation::local_planning
 {
 
-    // TimedElasticBandsParams
-
-    Algorithms
-    TimedElasticBandsParams::algorithm() const
-    {
-        return Algorithms::TimedElasticBands;
-    }
-
-    aron::data::DictPtr
-    TimedElasticBandsParams::toAron() const
-    {
-        return cfg.toAron();
-    }
-
-    TimedElasticBandsParams
-    TimedElasticBandsParams::FromAron(const aron::data::DictPtr& dict)
-    {
-        ARMARX_CHECK_NOT_NULL(dict);
-
-        TimedElasticBandsParams bo;
-        bo.cfg.fromAron(dict);
-
-        return bo;
-    }
+   
 
 
     // TimedElasticBands
diff --git a/source/armarx/navigation/local_planning/TimedElasticBandsParams.cpp b/source/armarx/navigation/local_planning/TimedElasticBandsParams.cpp
new file mode 100644
index 00000000..c7229835
--- /dev/null
+++ b/source/armarx/navigation/local_planning/TimedElasticBandsParams.cpp
@@ -0,0 +1,29 @@
+#include "TimedElasticBandsParams.h"
+
+namespace armarx::navigation::local_planning
+{
+   // TimedElasticBandsParams
+
+    Algorithms
+    TimedElasticBandsParams::algorithm() const
+    {
+        return Algorithms::TimedElasticBands;
+    }
+
+    aron::data::DictPtr
+    TimedElasticBandsParams::toAron() const
+    {
+        return cfg.toAron();
+    }
+
+    TimedElasticBandsParams
+    TimedElasticBandsParams::FromAron(const aron::data::DictPtr& dict)
+    {
+        ARMARX_CHECK_NOT_NULL(dict);
+
+        TimedElasticBandsParams bo;
+        bo.cfg.fromAron(dict);
+
+        return bo;
+    }
+}
diff --git a/source/armarx/navigation/local_planning/TimedElasticBandsParams.h b/source/armarx/navigation/local_planning/TimedElasticBandsParams.h
new file mode 100644
index 00000000..9cd9a29e
--- /dev/null
+++ b/source/armarx/navigation/local_planning/TimedElasticBandsParams.h
@@ -0,0 +1,44 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @author     Christian R. G. Dreher ( c dot dreher at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+
+#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+#include <armarx/navigation/local_planning/core.h>
+
+namespace armarx::navigation::local_planning
+{
+
+    struct TimedElasticBandsParams : public LocalPlannerParams
+    {
+        arondto::TimedElasticBandsParams cfg;
+
+        Algorithms algorithm() const override;
+        aron::data::DictPtr toAron() const override;
+        static TimedElasticBandsParams FromAron(const aron::data::DictPtr& dict);
+    };
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 928c543e..1d147c2e 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -3,9 +3,7 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
-
-#include <armarx/navigation/local_planning/TimedElasticBands.h>
-#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+#include "armarx/navigation/local_planning/TimedElasticBandsParams.h"
 
 namespace armarx::navigation::local_planning
 {
@@ -23,135 +21,5 @@ namespace armarx::navigation::local_planning
         bo.cfg = dto;
     }
 
-    void
-    toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo)
-    {
-        bo.pse.pse_costum_obstacle_penalties = dto.teb_config.pse.pse_costum_obstacle_penalties;
-        bo.pse.pse_costum_obstacle_penalties_dynamic =
-            dto.teb_config.pse.pse_costum_obstacle_penalties_dynamic;
-        bo.pse.weight_costmap = dto.teb_config.pse.weight_costmap;
-        bo.pse.weight_global_path_position = dto.teb_config.pse.weight_global_path_position;
-        bo.pse.weight_global_path_orientation = dto.teb_config.pse.weight_global_path_orientation;
-        bo.pse.lrk_use_alternative_approach = dto.teb_config.pse.lrk_use_alternative_approach;
-        bo.pse.lrk_enable_collision_check = dto.teb_config.pse.lrk_enable_collision_check;
-        bo.pse.hybrid_homotopy_calculation = dto.teb_config.pse.hybrid_homotopy_calculation;
-        bo.pse.robot_diff_circumscribed_inscribed_radius =
-            dto.teb_config.pse.robot_diff_circumscribed_inscribed_radius;
-
-        // Trajectory
-        bo.trajectory.teb_autosize = bo.trajectory.teb_autosize;
-        bo.trajectory.dt_ref = dto.teb_config.trajectory.dt_ref;
-        bo.trajectory.dt_hysteresis = dto.teb_config.trajectory.dt_hysteresis;
-        bo.trajectory.min_samples = dto.teb_config.trajectory.min_samples;
-        bo.trajectory.max_samples = dto.teb_config.trajectory.max_samples;
-        bo.trajectory.global_plan_overwrite_orientation =
-            dto.teb_config.trajectory.global_plan_overwrite_orientation;
-        bo.trajectory.allow_init_with_backwards_motion =
-            dto.teb_config.trajectory.allow_init_with_backwards_motion;
-        bo.trajectory.exact_arc_length = dto.teb_config.trajectory.exact_arc_length;
-        bo.trajectory.force_reinit_new_goal_dist =
-            dto.teb_config.trajectory.force_reinit_new_goal_dist;
-        bo.trajectory.force_reinit_new_goal_angular =
-            dto.teb_config.trajectory.force_reinit_new_goal_angular;
-        bo.trajectory.feasibility_check_no_poses =
-            dto.teb_config.trajectory.feasibility_check_no_poses;
-        bo.trajectory.feasibility_check_lookahead_distance =
-            dto.teb_config.trajectory.feasibility_check_lookahead_distance;
-        bo.trajectory.min_resolution_collision_check_angular =
-            dto.teb_config.trajectory.min_resolution_collision_check_angular;
-
-        // Robot
-        bo.robot.max_vel_x = dto.teb_config.robot.max_vel_x;
-        bo.robot.max_vel_x_backwards = dto.teb_config.robot.max_vel_x_backwards;
-        bo.robot.max_vel_y = dto.teb_config.robot.max_vel_y;
-        bo.robot.max_vel_trans = dto.teb_config.robot.max_vel_trans;
-        bo.robot.max_vel_theta = dto.teb_config.robot.max_vel_theta;
-        bo.robot.acc_lim_x = dto.teb_config.robot.acc_lim_x;
-        bo.robot.acc_lim_y = dto.teb_config.robot.acc_lim_y;
-        bo.robot.acc_lim_theta = dto.teb_config.robot.acc_lim_theta;
-        bo.robot.min_turning_radius = dto.teb_config.robot.min_turning_radius;
-
-        // GoalTolerance
-        bo.goal_tolerance.xy_goal_tolerance = dto.teb_config.goal_tolerance.xy_goal_tolerance;
-
-        // Obstacles
-        bo.obstacles.min_obstacle_dist = dto.teb_config.obstacles.min_obstacle_dist;
-        bo.obstacles.inflation_dist = dto.teb_config.obstacles.inflation_dist;
-        bo.obstacles.dynamic_obstacle_inflation_dist =
-            dto.teb_config.obstacles.dynamic_obstacle_inflation_dist;
-        bo.obstacles.include_dynamic_obstacles = dto.teb_config.obstacles.include_dynamic_obstacles;
-        bo.obstacles.obstacle_association_force_inclusion_factor =
-            dto.teb_config.obstacles.obstacle_association_force_inclusion_factor;
-        bo.obstacles.obstacle_association_cutoff_factor =
-            dto.teb_config.obstacles.obstacle_association_cutoff_factor;
-        bo.obstacles.obstacle_proximity_ratio_max_vel =
-            dto.teb_config.obstacles.obstacle_proximity_ratio_max_vel;
-        bo.obstacles.obstacle_proximity_lower_bound =
-            dto.teb_config.obstacles.obstacle_proximity_lower_bound;
-        bo.obstacles.obstacle_proximity_upper_bound =
-            dto.teb_config.obstacles.obstacle_proximity_upper_bound;
-
-        // Optimization
-        bo.optim.no_inner_iterations = dto.teb_config.optim.no_inner_iterations;
-        bo.optim.no_outer_iterations = dto.teb_config.optim.no_outer_iterations;
-        bo.optim.optimization_activate = dto.teb_config.optim.optimization_activate;
-        bo.optim.optimization_verbose = dto.teb_config.optim.optimization_verbose;
-        bo.optim.penalty_epsilon = dto.teb_config.optim.penalty_epsilon;
-        bo.optim.weight_max_vel_x = dto.teb_config.optim.weight_max_vel_x;
-        bo.optim.weight_max_vel_y = dto.teb_config.optim.weight_max_vel_y;
-        bo.optim.weight_max_vel_theta = dto.teb_config.optim.weight_max_vel_theta;
-        bo.optim.weight_acc_lim_x = dto.teb_config.optim.weight_acc_lim_x;
-        bo.optim.weight_acc_lim_y = dto.teb_config.optim.weight_acc_lim_y;
-        bo.optim.weight_acc_lim_theta = dto.teb_config.optim.weight_acc_lim_theta;
-        bo.optim.weight_kinematics_nh = dto.teb_config.optim.weight_kinematics_nh;
-        bo.optim.weight_kinematics_forward_drive =
-            dto.teb_config.optim.weight_kinematics_forward_drive;
-        bo.optim.weight_kinematics_turning_radius =
-            dto.teb_config.optim.weight_kinematics_turning_radius;
-        bo.optim.weight_optimaltime = dto.teb_config.optim.weight_optimaltime;
-        bo.optim.weight_shortest_path = dto.teb_config.optim.weight_shortest_path;
-        bo.optim.weight_obstacle = dto.teb_config.optim.weight_obstacle;
-        bo.optim.weight_inflation = dto.teb_config.optim.weight_inflation;
-        bo.optim.weight_dynamic_obstacle = dto.teb_config.optim.weight_dynamic_obstacle;
-        bo.optim.weight_dynamic_obstacle_inflation =
-            dto.teb_config.optim.weight_dynamic_obstacle_inflation;
-        bo.optim.weight_velocity_obstacle_ratio =
-            dto.teb_config.optim.weight_velocity_obstacle_ratio;
-        bo.optim.weight_viapoint = dto.teb_config.optim.weight_viapoint;
-        bo.optim.weight_prefer_rotdir = dto.teb_config.optim.weight_prefer_rotdir;
-        bo.optim.weight_adapt_factor = dto.teb_config.optim.weight_adapt_factor;
-        bo.optim.obstacle_cost_exponent = dto.teb_config.optim.obstacle_cost_exponent;
-
-        // Homotopy Class Planner
-        bo.hcp.enable_multithreading = dto.teb_config.hcp.enable_multithreading;
-        bo.hcp.simple_exploration = dto.teb_config.hcp.simple_exploration;
-        bo.hcp.max_number_classes = dto.teb_config.hcp.max_number_classes;
-        bo.hcp.max_number_plans_in_current_class =
-            dto.teb_config.hcp.max_number_plans_in_current_class;
-        bo.hcp.selection_cost_hysteresis = dto.teb_config.hcp.selection_cost_hysteresis;
-        bo.hcp.selection_obst_cost_scale = dto.teb_config.hcp.selection_obst_cost_scale;
-        bo.hcp.selection_viapoint_cost_scale = dto.teb_config.hcp.selection_viapoint_cost_scale;
-        bo.hcp.selection_alternative_time_cost = dto.teb_config.hcp.selection_alternative_time_cost;
-        bo.hcp.selection_dropping_probability = dto.teb_config.hcp.selection_dropping_probability;
-        bo.hcp.switching_blocking_period = dto.teb_config.hcp.switching_blocking_period;
-
-        bo.hcp.obstacle_heading_threshold = dto.teb_config.hcp.obstacle_heading_threshold;
-        bo.hcp.roadmap_graph_no_samples = dto.teb_config.hcp.roadmap_graph_no_samples;
-        bo.hcp.roadmap_graph_area_width = dto.teb_config.hcp.roadmap_graph_area_width;
-        bo.hcp.roadmap_graph_area_length_scale = dto.teb_config.hcp.roadmap_graph_area_length_scale;
-        bo.hcp.h_signature_prescaler = dto.teb_config.hcp.h_signature_prescaler;
-        bo.hcp.h_signature_threshold = dto.teb_config.hcp.h_signature_threshold;
-
-        bo.hcp.viapoints_all_candidates = dto.teb_config.hcp.viapoints_all_candidates;
-
-        bo.hcp.delete_detours_backwards = dto.teb_config.hcp.delete_detours_backwards;
-        bo.hcp.detours_orientation_tolerance = dto.teb_config.hcp.detours_orientation_tolerance;
-        bo.hcp.length_start_orientation_vector = dto.teb_config.hcp.length_start_orientation_vector;
-        bo.hcp.max_ratio_detours_duration_best_duration =
-            dto.teb_config.hcp.max_ratio_detours_duration_best_duration;
-
-        bo.checkParameters();
-    }
-
 
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron_conversions.h b/source/armarx/navigation/local_planning/aron_conversions.h
index 22eb26d1..1b7d2382 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.h
+++ b/source/armarx/navigation/local_planning/aron_conversions.h
@@ -1,7 +1,5 @@
 #pragma once
 
-#include <teb_local_planner/teb_config.h>
-
 namespace armarx::navigation::local_planning
 {
     // struct LocalPlannerParams;
@@ -21,6 +19,4 @@ namespace armarx::navigation::local_planning
     void toAron(arondto::TimedElasticBandsParams& dto, const TimedElasticBandsParams& bo);
     void fromAron(const arondto::TimedElasticBandsParams& dto, TimedElasticBandsParams& bo);
 
-    void toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo);
-
 } // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron_conversions_teb.cpp b/source/armarx/navigation/local_planning/aron_conversions_teb.cpp
new file mode 100644
index 00000000..d859dd98
--- /dev/null
+++ b/source/armarx/navigation/local_planning/aron_conversions_teb.cpp
@@ -0,0 +1,146 @@
+#include "aron_conversions.h"
+
+#include <teb_local_planner/teb_config.h>
+
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
+
+#include <armarx/navigation/local_planning/TimedElasticBands.h>
+#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+
+namespace armarx::navigation::local_planning
+{
+
+    void
+    toTebCfg(const arondto::TimedElasticBandsParams& dto, ::teb_local_planner::TebConfig& bo)
+    {
+        bo.pse.pse_costum_obstacle_penalties = dto.teb_config.pse.pse_costum_obstacle_penalties;
+        bo.pse.pse_costum_obstacle_penalties_dynamic =
+            dto.teb_config.pse.pse_costum_obstacle_penalties_dynamic;
+        bo.pse.weight_costmap = dto.teb_config.pse.weight_costmap;
+        bo.pse.weight_global_path_position = dto.teb_config.pse.weight_global_path_position;
+        bo.pse.weight_global_path_orientation = dto.teb_config.pse.weight_global_path_orientation;
+        bo.pse.lrk_use_alternative_approach = dto.teb_config.pse.lrk_use_alternative_approach;
+        bo.pse.lrk_enable_collision_check = dto.teb_config.pse.lrk_enable_collision_check;
+        bo.pse.hybrid_homotopy_calculation = dto.teb_config.pse.hybrid_homotopy_calculation;
+        bo.pse.robot_diff_circumscribed_inscribed_radius =
+            dto.teb_config.pse.robot_diff_circumscribed_inscribed_radius;
+
+        // Trajectory
+        bo.trajectory.teb_autosize = bo.trajectory.teb_autosize;
+        bo.trajectory.dt_ref = dto.teb_config.trajectory.dt_ref;
+        bo.trajectory.dt_hysteresis = dto.teb_config.trajectory.dt_hysteresis;
+        bo.trajectory.min_samples = dto.teb_config.trajectory.min_samples;
+        bo.trajectory.max_samples = dto.teb_config.trajectory.max_samples;
+        bo.trajectory.global_plan_overwrite_orientation =
+            dto.teb_config.trajectory.global_plan_overwrite_orientation;
+        bo.trajectory.allow_init_with_backwards_motion =
+            dto.teb_config.trajectory.allow_init_with_backwards_motion;
+        bo.trajectory.exact_arc_length = dto.teb_config.trajectory.exact_arc_length;
+        bo.trajectory.force_reinit_new_goal_dist =
+            dto.teb_config.trajectory.force_reinit_new_goal_dist;
+        bo.trajectory.force_reinit_new_goal_angular =
+            dto.teb_config.trajectory.force_reinit_new_goal_angular;
+        bo.trajectory.feasibility_check_no_poses =
+            dto.teb_config.trajectory.feasibility_check_no_poses;
+        bo.trajectory.feasibility_check_lookahead_distance =
+            dto.teb_config.trajectory.feasibility_check_lookahead_distance;
+        bo.trajectory.min_resolution_collision_check_angular =
+            dto.teb_config.trajectory.min_resolution_collision_check_angular;
+
+        // Robot
+        bo.robot.max_vel_x = dto.teb_config.robot.max_vel_x;
+        bo.robot.max_vel_x_backwards = dto.teb_config.robot.max_vel_x_backwards;
+        bo.robot.max_vel_y = dto.teb_config.robot.max_vel_y;
+        bo.robot.max_vel_trans = dto.teb_config.robot.max_vel_trans;
+        bo.robot.max_vel_theta = dto.teb_config.robot.max_vel_theta;
+        bo.robot.acc_lim_x = dto.teb_config.robot.acc_lim_x;
+        bo.robot.acc_lim_y = dto.teb_config.robot.acc_lim_y;
+        bo.robot.acc_lim_theta = dto.teb_config.robot.acc_lim_theta;
+        bo.robot.min_turning_radius = dto.teb_config.robot.min_turning_radius;
+
+        // GoalTolerance
+        bo.goal_tolerance.xy_goal_tolerance = dto.teb_config.goal_tolerance.xy_goal_tolerance;
+
+        // Obstacles
+        bo.obstacles.min_obstacle_dist = dto.teb_config.obstacles.min_obstacle_dist;
+        bo.obstacles.inflation_dist = dto.teb_config.obstacles.inflation_dist;
+        bo.obstacles.dynamic_obstacle_inflation_dist =
+            dto.teb_config.obstacles.dynamic_obstacle_inflation_dist;
+        bo.obstacles.include_dynamic_obstacles = dto.teb_config.obstacles.include_dynamic_obstacles;
+        bo.obstacles.obstacle_association_force_inclusion_factor =
+            dto.teb_config.obstacles.obstacle_association_force_inclusion_factor;
+        bo.obstacles.obstacle_association_cutoff_factor =
+            dto.teb_config.obstacles.obstacle_association_cutoff_factor;
+        bo.obstacles.obstacle_proximity_ratio_max_vel =
+            dto.teb_config.obstacles.obstacle_proximity_ratio_max_vel;
+        bo.obstacles.obstacle_proximity_lower_bound =
+            dto.teb_config.obstacles.obstacle_proximity_lower_bound;
+        bo.obstacles.obstacle_proximity_upper_bound =
+            dto.teb_config.obstacles.obstacle_proximity_upper_bound;
+
+        // Optimization
+        bo.optim.no_inner_iterations = dto.teb_config.optim.no_inner_iterations;
+        bo.optim.no_outer_iterations = dto.teb_config.optim.no_outer_iterations;
+        bo.optim.optimization_activate = dto.teb_config.optim.optimization_activate;
+        bo.optim.optimization_verbose = dto.teb_config.optim.optimization_verbose;
+        bo.optim.penalty_epsilon = dto.teb_config.optim.penalty_epsilon;
+        bo.optim.weight_max_vel_x = dto.teb_config.optim.weight_max_vel_x;
+        bo.optim.weight_max_vel_y = dto.teb_config.optim.weight_max_vel_y;
+        bo.optim.weight_max_vel_theta = dto.teb_config.optim.weight_max_vel_theta;
+        bo.optim.weight_acc_lim_x = dto.teb_config.optim.weight_acc_lim_x;
+        bo.optim.weight_acc_lim_y = dto.teb_config.optim.weight_acc_lim_y;
+        bo.optim.weight_acc_lim_theta = dto.teb_config.optim.weight_acc_lim_theta;
+        bo.optim.weight_kinematics_nh = dto.teb_config.optim.weight_kinematics_nh;
+        bo.optim.weight_kinematics_forward_drive =
+            dto.teb_config.optim.weight_kinematics_forward_drive;
+        bo.optim.weight_kinematics_turning_radius =
+            dto.teb_config.optim.weight_kinematics_turning_radius;
+        bo.optim.weight_optimaltime = dto.teb_config.optim.weight_optimaltime;
+        bo.optim.weight_shortest_path = dto.teb_config.optim.weight_shortest_path;
+        bo.optim.weight_obstacle = dto.teb_config.optim.weight_obstacle;
+        bo.optim.weight_inflation = dto.teb_config.optim.weight_inflation;
+        bo.optim.weight_dynamic_obstacle = dto.teb_config.optim.weight_dynamic_obstacle;
+        bo.optim.weight_dynamic_obstacle_inflation =
+            dto.teb_config.optim.weight_dynamic_obstacle_inflation;
+        bo.optim.weight_velocity_obstacle_ratio =
+            dto.teb_config.optim.weight_velocity_obstacle_ratio;
+        bo.optim.weight_viapoint = dto.teb_config.optim.weight_viapoint;
+        bo.optim.weight_prefer_rotdir = dto.teb_config.optim.weight_prefer_rotdir;
+        bo.optim.weight_adapt_factor = dto.teb_config.optim.weight_adapt_factor;
+        bo.optim.obstacle_cost_exponent = dto.teb_config.optim.obstacle_cost_exponent;
+
+        // Homotopy Class Planner
+        bo.hcp.enable_multithreading = dto.teb_config.hcp.enable_multithreading;
+        bo.hcp.simple_exploration = dto.teb_config.hcp.simple_exploration;
+        bo.hcp.max_number_classes = dto.teb_config.hcp.max_number_classes;
+        bo.hcp.max_number_plans_in_current_class =
+            dto.teb_config.hcp.max_number_plans_in_current_class;
+        bo.hcp.selection_cost_hysteresis = dto.teb_config.hcp.selection_cost_hysteresis;
+        bo.hcp.selection_obst_cost_scale = dto.teb_config.hcp.selection_obst_cost_scale;
+        bo.hcp.selection_viapoint_cost_scale = dto.teb_config.hcp.selection_viapoint_cost_scale;
+        bo.hcp.selection_alternative_time_cost = dto.teb_config.hcp.selection_alternative_time_cost;
+        bo.hcp.selection_dropping_probability = dto.teb_config.hcp.selection_dropping_probability;
+        bo.hcp.switching_blocking_period = dto.teb_config.hcp.switching_blocking_period;
+
+        bo.hcp.obstacle_heading_threshold = dto.teb_config.hcp.obstacle_heading_threshold;
+        bo.hcp.roadmap_graph_no_samples = dto.teb_config.hcp.roadmap_graph_no_samples;
+        bo.hcp.roadmap_graph_area_width = dto.teb_config.hcp.roadmap_graph_area_width;
+        bo.hcp.roadmap_graph_area_length_scale = dto.teb_config.hcp.roadmap_graph_area_length_scale;
+        bo.hcp.h_signature_prescaler = dto.teb_config.hcp.h_signature_prescaler;
+        bo.hcp.h_signature_threshold = dto.teb_config.hcp.h_signature_threshold;
+
+        bo.hcp.viapoints_all_candidates = dto.teb_config.hcp.viapoints_all_candidates;
+
+        bo.hcp.delete_detours_backwards = dto.teb_config.hcp.delete_detours_backwards;
+        bo.hcp.detours_orientation_tolerance = dto.teb_config.hcp.detours_orientation_tolerance;
+        bo.hcp.length_start_orientation_vector = dto.teb_config.hcp.length_start_orientation_vector;
+        bo.hcp.max_ratio_detours_duration_best_duration =
+            dto.teb_config.hcp.max_ratio_detours_duration_best_duration;
+
+        bo.checkParameters();
+    }
+
+
+} // namespace armarx::navigation::local_planning
diff --git a/source/armarx/navigation/local_planning/aron_conversions_teb.h b/source/armarx/navigation/local_planning/aron_conversions_teb.h
new file mode 100644
index 00000000..49120453
--- /dev/null
+++ b/source/armarx/navigation/local_planning/aron_conversions_teb.h
@@ -0,0 +1,19 @@
+#pragma once
+
+namespace teb_local_planner
+{
+    class TebConfig;
+}
+
+namespace armarx::navigation::local_planning::arondto
+{
+    struct TimedElasticBandsParams;
+
+} // namespace armarx::navigation::local_planning::arondto
+
+
+namespace armarx::navigation::local_planning
+{
+    void toTebCfg(const arondto::TimedElasticBandsParams& dto, teb_local_planner::TebConfig& bo);
+
+} // namespace armarx::navigation::local_planning
-- 
GitLab


From 910fa6f13dc632db195d664f8712ea9e0f0171bc Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Timo=20Weberru=C3=9F?= <timo.weberruss@student.kit.edu>
Date: Tue, 29 Nov 2022 18:54:19 +0100
Subject: [PATCH 286/324] Fix missing aaro_conversions_teb include

---
 .../armarx/navigation/local_planning/TimedElasticBands.cpp   | 5 ++---
 1 file changed, 2 insertions(+), 3 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 50572732..faac2b82 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -21,13 +21,12 @@
 #include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
 // #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
+#include <armarx/navigation/local_planning/aron_conversions_teb.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 
 namespace armarx::navigation::local_planning
 {
 
-   
-
 
     // TimedElasticBands
 
@@ -205,7 +204,7 @@ namespace armarx::navigation::local_planning
         {
             return;
         }
-        
+
         if (not scene.staticScene->distanceToObstaclesCostmap.has_value())
         {
             return;
-- 
GitLab


From e4b5fe5dd7fe1d0afbe92d343fd70c9d47c2bf72 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Sat, 3 Dec 2022 15:45:15 +0100
Subject: [PATCH 287/324] adding missing include

---
 source/armarx/navigation/local_planning/TimedElasticBands.cpp | 4 +---
 1 file changed, 1 insertion(+), 3 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index 50572732..02013bcb 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -18,6 +18,7 @@
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
 #include <armarx/navigation/local_planning/aron_conversions.h>
+#include <armarx/navigation/local_planning/aron_conversions_teb.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/local_planning/ros_conversions.h>
 // #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
@@ -26,9 +27,6 @@
 namespace armarx::navigation::local_planning
 {
 
-   
-
-
     // TimedElasticBands
 
     TimedElasticBands::TimedElasticBands(const Params& i_params, const core::Scene& ctx) :
-- 
GitLab


From 6976443b1906daeaac10d06bd4c5ddff16ee37bd Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 13:28:43 +0100
Subject: [PATCH 288/324] Fix NullPointer when LocalPlanner is null

---
 source/armarx/navigation/components/navigator/Component.cpp | 5 ++++-
 1 file changed, 4 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index d1d6abb4..c8ff0582 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -251,7 +251,10 @@ namespace armarx::navigation::components::navigator
             fac::NavigationStackFactory::create(stackConfig, sceneProvider->scene());
 
         // set visualization of LocalPlanner
-        stack.localPlanner->setVisualization(getArvizClient());
+        if (stack.localPlanner)
+        {
+            stack.localPlanner->setVisualization(getArvizClient());
+        }
 
         memoryIntrospectors.emplace_back(
             std::make_unique<server::MemoryIntrospector>(resultsWriterPlugin->get(), callerId));
-- 
GitLab


From e9f13c096f2d3a6ade2ed765227961750d0442a5 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 15:40:20 +0100
Subject: [PATCH 289/324] Add teb planner to cmake

---
 source/armarx/navigation/local_planning/CMakeLists.txt | 4 +++-
 1 file changed, 3 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index 27607e3f..ff91b53a 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -52,11 +52,13 @@ armarx_add_library(local_planning_teb
     OBJECT
 )
 
+target_compile_definitions(local_planning_teb PUBLIC TIMED_ELASTIC_BANDS_ENABLED=1)
+
 armarx_add_library(local_planning
     DEPENDENCIES_PUBLIC
         armarx_navigation::local_planning_core
     #DEPENDENCIES_PUBLIC_OPTIONAL
-    #    armarx_navigation::local_planning_teb
+        armarx_navigation::local_planning_teb
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
 )
-- 
GitLab


From 7f8b5b61f901633dcc4a9780e36efbc0e882c3aa Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 19:30:55 +0100
Subject: [PATCH 290/324] Add timing to dynamic scene provider

---
 .../dynamic_scene_provider/Component.cpp      | 64 ++++++++++++++++++-
 1 file changed, 62 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 4f72fc40..deec2b8b 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -29,6 +29,7 @@
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 #include <ArmarXCore/core/time/Clock.h>
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
+#include <ArmarXCore/util/time.h>
 
 #include <RobotAPI/libraries/ArmarXObjects/forward_declarations.h>
 
@@ -191,23 +192,34 @@ namespace armarx::navigation::components::dynamic_scene_provider
     void
     Component::runPeriodically()
     {
+        TIMING_START(FULL_DYNAMIC_SCENE_PROVIDER);
+
         // obtain data from perception
 
         const DateTime timestamp = Clock::Now();
 
+
         //
         // Robot
         //
 
+        TIMING_START(READ_ROBOT_FROM_MEMORY);
+
         ARMARX_CHECK(virtualRobotReaderPlugin->get().synchronizeRobot(*robot, timestamp));
         const core::Pose global_T_robot(robot->getGlobalPose());
 
         ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
 
+        TIMING_END_COMMENT_STREAM(
+            READ_ROBOT_FROM_MEMORY, "Timer: reading robot from memory", ARMARX_VERBOSE);
+
+
         //
         // Human
         //
 
+        TIMING_START(READ_HUMANS_FROM_MEMORY);
+
         ARMARX_INFO << "Querying humans";
 
         const armem::human::client::Reader::Query humanPoseQuery{
@@ -222,12 +234,18 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
 
+        TIMING_END_COMMENT_STREAM(
+            READ_HUMANS_FROM_MEMORY, "Timer: reading humans from memory", ARMARX_VERBOSE);
+
+
         //
         // Laser scanner features
         //
 
-        ARMARX_INFO << "Querying laser scanner features";
+        /*
+        TIMING_START(READ_LASERSCANNER_FROM_MEMORY);
 
+        ARMARX_INFO << "Querying laser scanner features";
         const armem::vision::laser_scanner_features::client::Reader::Query laserFeaturesQuery{
             .providerName = properties.laserScannerFeatures.providerName,
             .name = properties.laserScannerFeatures.name,
@@ -241,10 +259,16 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         ARMARX_INFO << laserFeaturesResult.features.size() << " clusters/features";
 
+        TIMING_END_COMMENT_STREAM(
+            READ_LASERSCANNER_FROM_MEMORY, "Timer: reading laserscanner from memory", ARMARX_VERBOSE);
+        */
+
+
+        /* we don't need this at the moment
+
         //
         //  Objects in the scene (both static and dynamic)
         //
-
         ARMARX_INFO << "Querying object poses";
 
         const objpose::ObjectPoseSeq objectPoses = ObjectPoseClientPluginUser::getObjectPoses();
@@ -349,14 +373,32 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         // here ends: data fetching
 
+        */
+
+
+        // process data from perception and write information back to memory
+
+        //
+        // Human tracking
+        //
+
+        TIMING_START(RUNNING_HUMAN_TRACKER_WITH_CAMERA);
+
         ARMARX_INFO << "Running human tracker with camera measurements";
 
         humanTracker.update(human::HumanTracker::CameraMeasurement{
             .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
 
+        TIMING_END_COMMENT_STREAM(RUNNING_HUMAN_TRACKER_WITH_CAMERA,
+                                  "Timer: running human tracker with camera",
+                                  ARMARX_VERBOSE);
+
 
+        /*
         ARMARX_INFO << "Running human tracker with lasersensor measurements";
 
+        TIMING_START(RUNNING_HUMAN_TRACKER_WITH_LASERSCANNER);
+
         //TODO why is result a vector of LSFs and not a vector of LSF?
         std::vector<armem::vision::LaserScannerFeature> flattened;
         for (auto const& fs : laserFeaturesResult.features)
@@ -367,9 +409,20 @@ namespace armarx::navigation::components::dynamic_scene_provider
             humanTracker.update(human::HumanTracker::LaserMeasurement{.detectionTime = timestamp,
                                                                       .clusters = flattened});
 
+        TIMING_END_COMMENT_STREAM(RUNNING_HUMAN_TRACKER_WITH_LASERSCANNER,
+                                  "Timer: running human tracker with laserscanner",
+                                  ARMARX_VERBOSE);
+        */
+
         ARMARX_INFO << "Human tracking done";
 
 
+        //
+        // Write dynamic scene back to memory
+        //
+
+        TIMING_START(WRITE_BACK_HUMANS);
+
         //TODO use clusters for obstacle creation
 
         std::vector<human::Human> humans = humanTracker.getTrackedHumans();
@@ -377,6 +430,13 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ARMARX_INFO << "Detected " << humans.size() << " humans";
 
         humanWriterPlugin->get().store(humans, getName(), timestamp);
+
+        TIMING_END_COMMENT_STREAM(
+            WRITE_BACK_HUMANS, "Timer: write humans to memory", ARMARX_VERBOSE);
+
+
+        TIMING_END_COMMENT_STREAM(
+            FULL_DYNAMIC_SCENE_PROVIDER, "Timer: complete dynamic scene provider", ARMARX_VERBOSE);
     }
 
 
-- 
GitLab


From 54b88934d1af066df72fec5a35195a128a680ade Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 19:31:14 +0100
Subject: [PATCH 291/324] Fix leftover visualization of humans

---
 source/armarx/navigation/components/navigation_memory/Visu.cpp | 1 +
 1 file changed, 1 insertion(+)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 2169aa43..37490d91 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -276,6 +276,7 @@ namespace armarx::navigation::memory
                 humanSegment.forEachEntity(
                     [&](const wm::Entity& entity)
                     {
+                        namedProviderHumans[entity.id().providerSegmentName];
                         entity.getLatestSnapshot().forEachInstance(
                             [&namedProviderHumans](
                                 const armarx::armem::wm::EntityInstance& instance)
-- 
GitLab


From 89eda28f670762f1fa3025d882a1e2275ea255f1 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 19:36:11 +0100
Subject: [PATCH 292/324] Remove orientation from KalmanFilter, fix
 lastDetectionTime

The current implementation of the KamanFilter does not work with
non-zero orientations.
The detection time to remove humans after a period of not detecting them
wasn't working properly.
---
 .../armarx/navigation/human/HumanFilter.cpp   | 19 +++++++++++++------
 source/armarx/navigation/human/HumanFilter.h  |  4 +++-
 .../armarx/navigation/human/HumanTracker.cpp  |  4 +++-
 source/armarx/navigation/human/HumanTracker.h |  2 +-
 4 files changed, 20 insertions(+), 9 deletions(-)

diff --git a/source/armarx/navigation/human/HumanFilter.cpp b/source/armarx/navigation/human/HumanFilter.cpp
index b31edcfd..baf14d07 100644
--- a/source/armarx/navigation/human/HumanFilter.cpp
+++ b/source/armarx/navigation/human/HumanFilter.cpp
@@ -9,7 +9,7 @@ namespace armarx::navigation::human
         human.pose = pose0;
         human.linearVelocity = Eigen::Vector2f::Zero();
         human.detectionTime = detectionTime;
-        oldHuman = human;
+        lastDetectedHuman = human;
 
         //initialize new kalman filter for new detected human
         UnscentedKalmanFilter<SystemModelT>::PropCovT Q =
@@ -51,16 +51,17 @@ namespace armarx::navigation::human
     void
     HumanFilter::update(const core::Pose2D& pose, const DateTime& detectionTime)
     {
-        double dt = (detectionTime - oldHuman.detectionTime).toSecondsDouble();
+        double dt = (detectionTime - lastDetectedHuman.detectionTime).toSecondsDouble();
 
         //update ukf with new observation
         SystemModelT::ObsT observation = toUkfObs(pose);
         ukf->update(observation);
 
         core::Pose2D newPose = fromUkfState(ukf->getCurrentState());
+        newPose.linear() = pose.linear();
 
         // calculate velocity
-        Eigen::Vector2f ds = newPose.translation() - oldHuman.pose.translation();
+        Eigen::Vector2f ds = newPose.translation() - lastDetectedHuman.pose.translation();
         Eigen::Vector2f linVelocity = ds / dt;
         // apply exponential smoothing to velocity
         //TODO try other approaches?
@@ -72,7 +73,7 @@ namespace armarx::navigation::human
         human.pose = newPose;
         human.linearVelocity = newVelocity;
 
-        oldHuman = human;
+        lastDetectedHuman = human;
     }
 
     const Human&
@@ -81,6 +82,12 @@ namespace armarx::navigation::human
         return human;
     }
 
+    Duration
+    HumanFilter::detectionAge(const DateTime& currentTime) const
+    {
+        return (currentTime - lastDetectedHuman.detectionTime);
+    }
+
 
     HumanFilter::SystemModelT::StateT
     HumanFilter::toUkfState(const core::Pose2D& pose)
@@ -88,7 +95,7 @@ namespace armarx::navigation::human
         // [mm] to [m]
         return {{pose.translation().x() / 1000,
                  pose.translation().y() / 1000,
-                 Eigen::Rotation2Df(pose.linear()).angle()}};
+                 0 /*Eigen::Rotation2Df(pose.linear()).angle()*/}};
     }
 
     core::Pose2D
@@ -98,7 +105,7 @@ namespace armarx::navigation::human
         // [m] to [mm]
         pose2d.translation().x() = pose.pose.x() * 1000;
         pose2d.translation().y() = pose.pose.y() * 1000;
-        pose2d.linear() = Eigen::Rotation2Df(pose.pose.angle()).toRotationMatrix();
+        pose2d.linear() = Eigen::Rotation2Df(0 /*pose.pose.angle()*/).toRotationMatrix();
 
         return pose2d;
     }
diff --git a/source/armarx/navigation/human/HumanFilter.h b/source/armarx/navigation/human/HumanFilter.h
index 9a9b03f6..aaed6eec 100644
--- a/source/armarx/navigation/human/HumanFilter.h
+++ b/source/armarx/navigation/human/HumanFilter.h
@@ -82,6 +82,8 @@ namespace armarx::navigation::human
          */
         const Human& get() const;
 
+        Duration detectionAge(const DateTime& currentTime) const;
+
     private:
         using SystemModelT = kalman_filter::SystemModelSE2<double>;
 
@@ -96,7 +98,7 @@ namespace armarx::navigation::human
          * @brief oldHuman stores information about the human at the point in time of the last
          * HumanFilter::update call
          */
-        Human oldHuman{};
+        Human lastDetectedHuman{};
         /**
          * @brief human stores information about the human at the point in time of the last
          * HumanFilter::propagation call
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index 71d964d1..d9841e38 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -14,6 +14,7 @@
 
 namespace armarx::navigation::human
 {
+
     void
     HumanTracker::update(const CameraMeasurement& measurements)
     {
@@ -319,6 +320,7 @@ namespace armarx::navigation::human
         ARMARX_CHECK(not trackedHuman->associated);
         ARMARX_CHECK(not detectedHuman->associated);
 
+
         trackedHuman->associated = true;
         detectedHuman->associated = true;
 
@@ -364,7 +366,7 @@ namespace armarx::navigation::human
         {
             auto& human = *it;
             // when the tracked human recieved no new measurement for too long, remove it
-            if ((time - human.humanFilter.get().detectionTime) >= parameters.maxTrackingAge)
+            if (human.humanFilter.detectionAge(time) >= parameters.maxTrackingAge)
             {
                 it = trackedHumans.erase(it);
             }
diff --git a/source/armarx/navigation/human/HumanTracker.h b/source/armarx/navigation/human/HumanTracker.h
index 9176f62b..1f27aed7 100644
--- a/source/armarx/navigation/human/HumanTracker.h
+++ b/source/armarx/navigation/human/HumanTracker.h
@@ -105,7 +105,7 @@ namespace armarx::navigation::human
             const std::string rotationKeypoint = "Head";
             // the duration after which tracked humans will be erased if no new measurement for
             // this human is found
-            Duration maxTrackingAge = Duration::MilliSeconds(500);
+            Duration maxTrackingAge = Duration::MilliSeconds(1000);
             // the maximum distance in millimeters of two human measurements where they are still
             // associated with each other
             float maxAssociationDistance = 600;
-- 
GitLab


From 5924a7ef7c2eda4b38a6cfc012d92a4df30db3bd Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 19:43:03 +0100
Subject: [PATCH 293/324] Set goal tolerance of teb to 0

---
 .../local_planner_config/TimedElasticBands/default.json         | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
index 4265bf31..67fe56d7 100644
--- a/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
+++ b/data/armarx_navigation/local_planner_config/TimedElasticBands/default.json
@@ -44,7 +44,7 @@
     },
 
     "goal_tolerance": {
-      "xy_goal_tolerance": 0.2
+      "xy_goal_tolerance": 0.0
     },
 
     "obstacles": {
-- 
GitLab


From 9bce5d14843ea6c41b4de50c8ff0d0fd3cfa0e42 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 19:52:40 +0100
Subject: [PATCH 294/324] Remove kalman test docs

---
 .../navigation/human/test/findings/Notice.md  |  18 ------------------
 ...l-start_0-mod_100-low_error-dirty_hack.pdf | Bin 67584 -> 0 bytes
 ...native_model-start_0-mod_100-low_error.pdf | Bin 60874 -> 0 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 67438 -> 0 bytes
 ...ative_model-start_0-mod_101-high_error.pdf | Bin 67428 -> 0 bytes
 ...native_model-start_0-mod_101-low_error.pdf | Bin 67336 -> 0 bytes
 ...2-start_0-mod_100-low_error-dirty_hack.pdf | Bin 67677 -> 0 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 67596 -> 0 bytes
 ...tive_model2-start_0-mod_101-high_error.pdf | Bin 67633 -> 0 bytes
 ...ative_model2-start_0-mod_101-low_error.pdf | Bin 67431 -> 0 bytes
 .../start_0-mod_10-low_error-dirty_hack.pdf   | Bin 79390 -> 0 bytes
 .../findings/start_0-mod_10-low_error.pdf     | Bin 76832 -> 0 bytes
 .../start_0-mod_100-low_error-dirty_hack.pdf  | Bin 67390 -> 0 bytes
 .../findings/start_0-mod_100-low_error.pdf    | Bin 60704 -> 0 bytes
 ...start_0-mod_101-high_error-high_offset.pdf | Bin 67661 -> 0 bytes
 .../findings/start_0-mod_101-high_error.pdf   | Bin 67660 -> 0 bytes
 .../findings/start_0-mod_101-low_error.pdf    | Bin 67362 -> 0 bytes
 .../findings/start_0-mod_11-low_error.pdf     | Bin 75469 -> 0 bytes
 .../findings/start_01-mod_10-low_error.pdf    | Bin 76717 -> 0 bytes
 .../findings/start_01-mod_100-low_error.pdf   | Bin 67290 -> 0 bytes
 .../findings/start_pi_2-mod_10-low_error.pdf  | Bin 76444 -> 0 bytes
 ...start_pi_2-mod_10-low_error_dirty-hack.pdf | Bin 79465 -> 0 bytes
 .../findings/start_pi_2-mod_100-low_error.pdf | Bin 67483 -> 0 bytes
 23 files changed, 18 deletions(-)
 delete mode 100644 source/armarx/navigation/human/test/findings/Notice.md
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf
 delete mode 100644 source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf

diff --git a/source/armarx/navigation/human/test/findings/Notice.md b/source/armarx/navigation/human/test/findings/Notice.md
deleted file mode 100644
index 61048442..00000000
--- a/source/armarx/navigation/human/test/findings/Notice.md
+++ /dev/null
@@ -1,18 +0,0 @@
-# Different configurations of the kalman filter test:
-
-- start_* is the start angle of the simulated trajectory
-- mod_* is the modulo value used to define how often the kalman filter is updated
-- error is the noise added to the measurements
-  - low: 0.01
-  - high: 0.1
-- offset is the initial position offset:
-  - blank: 0.1
-  - high: 0.5 (1 for the alternative models)
-- dirty hack: skip orientations close to pi
-
-Alternative models use different calculations for retract and inverseRetract
-
-- normal: lplus(tan), 2.lminus(1), 1-2
-- alternative_model: rplus(tan), 1.lminus(2), 2-1
-- alternative_model2: rplus(tan), 1.lminus(2), 1-2
-
diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error-dirty_hack.pdf
deleted file mode 100644
index dcb8673c9ff6ed9fbb63c7d22740bb65ddfac5b2..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67584
zcmV)RK(oIkP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_TXj*B}x%7
zZNO;2fCt@uXNCtx8{I(T<e=<<?YH+9xz?g~-tU~On}tGEePSN%kSI!`__Jsq=j(s|
zX0QKa?L0sJ>(Ap~j`K$w=W~Dj`v3p)fBg9O|Ht|9-~aE!KK`HA|Nbwp|NS4w|MtJX
z{^0!hKMy-U{@0Ix`LOuO{J*cCbN_Ll_A$o!qrd+D&kyfE?$?iz@cHpyKK|43Ww+jc
z^w(d%y0ssVKO$teuSWWR{r8Xm@b}}+$=x5V{b+v9HeTK54{zhT?c?u1kAMH){&xOt
zef01D?f7?pvmfJs`uqPl{^!4c$AB*fYV*g~W*5!x=jPAzWBOg4Ncc^+yZyMfPoe#r
zPILUYN85UV@SARa2iL`Z68<^%KR@oPdw+d(*pKJ>g8hHaeDCdto%`%S_|5EW{IKWQ
zx`FV0x0m?6i!uqn>2@1M8QnnmO}FVOSh)b%{6p#Q^ZGHqkpA=EBK_U3cTpzcH*@Rf
zn<%6Gn@-l>MVW-}yR~Ohl(QQNzv*_r4!2>o03`fVOYoXkv&-(+SMUDg{OcX?asK%N
zwAtT9nS|fW&gZ)*lkl5vuO0m+$|U@zo3;In%;xu9>=_iSWIqZ2><$>W_m^ndYpc$$
z*#B?Y0e0PQqKx)$W;g9!lu7tax7YuF6J-*9)2-bUWpo4KH{HxAT37-Q{%{AF`H%M3
zhtS8r;SPBGU6RrMes0(GF2`tp-)Ww^6i4ef_e}rgp6~yPv$0Lc6ONr(;`C2T{cCq#
zUkLrbN$GjsrT6()$nK^Gl3?E*RId%Ocvam*c-`>->^U%A<Mi>mFFwZW8uhOfkw0R|
zYrl_em}q`Gx7ShDUks~GB7ED;Ugzfe=jvCK?>oNaVD0y<qbT2Z^pVPUbrj_fmcjg`
z1<u!L@O-}xf3ONR+b?2Pl<%i_J--NAQNHi^%(sPS``b?KrLw#)eNn#e_&P`5*S;u!
zuoCTcM)c>mJL1o7#`e+y-^Hyc-%oPBKM{X^6y^Jlcj%8>KN7z0_PmtU^KCUm`L<&>
ze_MOD|6nD$oj>N?$K&6v#2=}Mz1uIsR+R6j_j>HT3tLgX@A!ILzOQ^yzVG;Y61}f{
zQNHi^-0v$d!k?_g^ZHgQE8nigpIx1=H|D#r73JG0t~af}9l}NVzN0_UVZVAw`M%?v
z!Mv@bDBpLy``#&9f3ObzI)Ux?d*Y9j#^?D((2DZy)RtlAP0&R6zFY6Vta?$t@A&HQ
zzUoE!zT@ky|Gw%)`4iP?yl%t!+dc7Ty3<Qd{YB7<@*B~9*F)cR%+HTsfB0WB<(Tf@
z*2LF4C+FGj*G|jX|2pOWZ_Rf*#@mncZuh!SUn*dk8vot@E56t{?z_FdI$yfNxjz5e
zRxjTEwV=K>Pg|NuzQCe2!IEY9i?_i=TV7Ed51B=IiS-ereC&brqNK_J%Im*gl(&}Q
zRT-4^CV5d_GJE_&Y6FDz)VR+0@i#&ZcTJ<sC%S%q96QPNsik!-N?P!Wf){lVUjMWR
zHOUy)BGn{c!t<hB@r8FvO?#~N_TO`Tixc#Cc+nzKl(F%php{D3a8MTSUX&MGj-BEg
zV|u*sJO-4MHiA&B3IZ)#!6^$)^&ez{IqW?8bW&RJ$%0R9<I{^hN07v)SIde=(IS5g
zwxkme)}X{>Vm}=ut=YT|2y&$;<Vt>^jaxj(XWXKUp&yE69k;k(xnkpzd|NKTi((p4
zEWw!Tqx_-Z_>1HkQE>c4F^wqLIfi&+$-Xg?M<B(BT>P=%+oF(1XYRPs#iQH-iy|JK
z$+pqNqZ2%8;?W5nHEyUAEXq|lK#BpGB<BQ+OiWt_iPwQ9mYrbG`GY_E8u}3g(};sT
z&W*V!Oa8pJW&ZJ^n8v&Q>!s%3Td&~Gi-K-f3dN$J+x5WEctJ|9JiQm8Ke_c@q;+!O
zwUC71jZZEF9%o^%9Q@(ngip3!b97n@7a`d2qF_5ON_?2cvqgznJJ)0>Ag}Koi_|#U
z5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?E?GoFZ+4i;`2cSjr;^(ZoVtHzs*<
zNv<19i`9R%V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P(E3%K
zVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wppEeZu?
z=C130pqT^jTbCSo-@4?uwc%fs#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi9YG0J
z>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgpd<yzaWUFwm1U6kq-
z>}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8%*)I8
z04ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1w;a*A
zbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5oi9qm
z5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2i)3?}X+)5$P#3z_R;pQ+-!
zNN6P&`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpEUWELjbhdfptEmYcNy^XK)-68^
z59^B%4II7m!emb#@~Jn!ICehlkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT5z9cF&`
zl!`ZT{+<$wi39h%w2>#y*Hcn4^ITYz>K4*<QYu!+!{Y9lQgI|{vG<fzK$Bk-NX3hi
zljLvY1WPIgF3?jt;Y=Y~6tW*qowIAza4?=-Yp{%mt8I8<O~)ju(9e9$E&^A;qeW(R
zFjHs8>|8|y_j`Oq+T!f^hHeiyju(YI>CwV_X6AYJ`Wx+(JhDvTD~mFsO@^dA^P4R>
z7S33bqD4*^J|V3UULSid$(6+?LIMvEdU%ZWG?=LuEsH$aal(mQLUO{-JT<?Z_i{9I
zera$i*Yl#Z5d;cJ?wc27wZ@Zro;`XvjMznsfH{slUl#>)91ob(ImZF@bCK}F@z3Dn
zdQC-##<d$a*rZp*xH0yoGi%&n6#pPcuJdH%`Mf9`>xBh2jrGcBn?2Gr$A#fT)5H^P
zwK?7lxUgGVNIu$vLc7AqQ+<)Z+ZSbx<3-8V>%Sx^Bk%r2;mAh5;O&;E<csb_(P1$h
z-E@VF+>VRF&w7g1i-hJ{@_S$}4#$rU?!^JG`aLLsBX_&q@wo$}VE)Yq#mM*jix91b
z-_SWRu(@uX6Qglpdiv*^(O{EFLXJ+)i-A3L^LaV2rS8xH4v<1v@HkIO{BVha;fG5U
zPW*66!jYt0LyE$Q6+HRvQ|`6TutsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+wAT{=
zJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bi;}I^f9VP0kn>Bz
z;`pgWg0$c%YnKc~J~1{uNPQr>M0bskoSc<?&j-e)gT%ucwFo1d@!z=?3SeoH15a((
zpo=CY$0k#fJI1ElN0Be4S1uwQ?9%h)Mai+r$mAV-ldj_Z)zZ1*E#4H1GSD8;YHa3;
zo@j-5LRDK7$UStkBS|5iQwpu;XlzQM#hZFjD5WPtbZ)6xo|@<)QFd@uOsO+HuSqMb
zW6!H#)+@KKf0rQj8^J*#Nc}=<pp`?{#e#RR&90lUPmEnRMTgi--4s1{v<)4l9Wzez
zTmBHHJhY+kq_iQcYI{JL8zn|GA_Vpbg5ghc%^GGnCR(wAuVb438f!RoyS6KBdxn!d
zNiQA_r<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7w*gLy
zw{3uv+CF%2+K}Sb9BgaUI~uka27~M6b>8NE(>i#jS0Emri$Xs2c;qY!<gvZBQkeo9
z?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>D5(2h0thYz_1P0JsxVLsce42UiD
zD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNI86&91T+Fx&;h7(I<}t
z3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn&q2`ANm(>P1r>g?*)<qd;
z$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%Eh7DcT
zPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+kyh(`VtFL&=Y!Reu%DC+>8R%o_0dl>LoUiV
zdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)val#v
zs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe=^93+
zS9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV7&|qk
zMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixlvw}XtkUl
zE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5A^ZJ-
zU7*w6cq~%N`Kd1%mh2R#pp3~h{h~yRJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}t1Lns
z7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@ghMOTK+@`LgPMN?O;>mZPf7!HCe<L
zCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSRo0NpR
zgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SAo9o-B
zdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{5~9Nd
z4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk=r3jv
z<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4g@UHp
zPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8Y(8am{qx%{&K!l4G0s
zmN6Pg`ox88a>{hr#LaXn!T`P~9Nf^iFu0V6!;A*|MMAG=K^o-P>4;GY3PuNMu$xwu
z4!g4%^_fLsw}Cc0VQFbbHssD7K^j58_Mc6iumx!twi~VW_m{?M*nW0tuy}Nsj^D`F
zh&FyQJ>h1lHudqS2YlI!6la57l){0l!|228<5o9}m6lh#B$%|dn$GNzx}))tu?TVG
z8S*_AA&yBr9TuO)WGBpl7E&agt~UFC+apa;LBSNLI?!qMqC^9NftZ&?!I^{C^ox?M
z*MAMNe(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p@w-SV
zk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZA*IB*
zkNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vo^7KgP9mhi0Jc%I+O&
zA#IuVJ?rE^=lV&1R@PV-6S(ZU6CLNg=~i^(QPsr;!;0ymbeNtEw#@F_%$;J~xt--!
z>z&(Kw`u2g?$NrzUEQsSVhKvJqQj&dq#R6#|HI&|>m84MYh*=-es9wFJ6w^A1YY2k
zWXO(O?T~Joj(X=Iy;BCp$1|(*l%^-ScOKHZ*Lw%I_z3U4fm=;G2QlVB!YuH>Gv-+L
zd~2AT)ScEvP>v*lhw%p|q?3^@i<0cyDAB?iw1*N(=jI|MJBxBFLlLXeVC#9KEQ{Ns
z<T^oFH+j^18W-Q%$tWo=Z7Mes@uHmuMWe}LQ4HTEWhA4d@z8h(%8{gGRC;WCbFqqT
zG78JzxC?hmSbfZ-O0_0N6s6^0AR$o1-YMyTG$~+EY&MELoK$W?+R`=xb4G(vwCyO3
zG;&|gy$3BdMYy#_)D~cNsd1c_c!}YkQ>-fr$41Tn9O51r1K<C~&(k%)qJVihzD^CT
z2;?P}`s|t$DXj!A<>PD=Je*bV?QfDtW6B#vf|vX}tppEDKWoFK)StEAurbbaYc(2E
zw7C{VLPgTH--36GLQds2UKDVOgjCp$JPKBmhgY5+jmDFWGIe(4k<%i}4u{eK!uw&?
zp0OWhpztgUv04NkWj%eD4dxP^n++~|9Il}7I&e%0j$TrZAn`iLPqn%YFojmPf#(lX
z*`ed0JrD)mD(yLS`g0LZF_4RJih<zyo%+p@SKMmqp3K3}^r4%x(fDEXBDI_9YloSr
z-PnV?kr$!kA_uc>>aV=o+s$2>-pFGS`q=e>7iH5I+C8LYfKfDcQ15sVsFvioTs^>~
zd(&nxFlsZ7);xFRXi>tMA_b};Z=#f}2KPD@u^<?<E^@@kc^6AeYGHOdr4(|;r?f)O
z_>@+d=EFuKhV;=!8-|qDc0K9^LC7fM)Oy>6c->Nq+eKA}MwoUX_=D<oyQt_;0e?|G
zprGf-sQ9D~->#_+Sl?@Y)H7hEuki14H8VJMe@(3H6}|(oeizT=iB`+^3zqNV@=hHQ
z7uR@lCY_zIShP~;;nXg!@Wfo88P)5n(MZ7;T2R;t6Qb%mwK6BgVrpslGUW{FWs1d_
ze5LT&xhUBOPM$U&b;1m0y-Ww%e3xPZ^H!fYc8<uAVJ9rWywnW~F!@l)79J_L20Ia^
zq6hsVp$8d02YYd}RETbjcBl*P#FZt3J~$+&s}Bdu6Z+O*dv<!z=(MNcw3{$t(pG{j
znzE)ai>53tOrn8RCdX#jEVSK3HVq9v7@Vma2Zzf!Ohl1ela|s`yrh8}W~NB3$sQcu
zpn;plsznLqn<lN#NUdQv@DBd}vWzVXzXidBv;TmN4Wtgk92iJDg-mq~5dme+Yp_!s
zW%6q@Rmd*bXsVFykU2VKUPO-0`k|awN(AkbnVv(dCVm4FAv@<v&p{_H9^Cvgm<A;c
z$4z5t?8TwreFWR=k)-UUn{&Xjt$UJ@Rx$&(Vd^w8EF^MxU~uMYo$7{j1W7z)lx7l-
z4A)1HMwzyomuVZkpd|wa@|K1S8PJ;}CZw$FjZsofSBpcDleNAvBuW<jm9BHs3jo3O
zscr-9Ha5>eW6YDh3z5}x$^&tLL_Y>UUcL{0ynG-0c6mQWa>_SnNuzlKuf3$C??b1y
z)AylM+8aGq7a5MDL;jt{I3+oORua!OHb2oK<XT@09*jhvlddKv`N$WAB%ktDG0TVk
ztVr<*o1a`>i<I2g+1c^-lJ9IK@#F%~z1BKTW4Yj3hml){W52+Ddh!}v)r*q1A}uEE
zp+EXX+I)kN;}bqp`VSW+J(YAauEd^elpC_8Q~B6jm5Y@AcpYCI@i<7L3BuSsqK)R0
z^qS_-=sh=niN13kOP#)RJzU`br4RSW1RywZ`7H!T%MaYpKYhhPNa2t-c@Z#6Y49Dw
zA*Xa?1jTT4$n+C#YOX#W3cXZk_+isO-Wc5_|9PX)MNak?MK1W23Y4-hFMVqap`atb
zF~F<qplDDo6cNzU<Z^651Cbsy_P_#W2W8;FYDIj&)KC$=mB9-KNXdOhH#8hX6#>y`
zfay~Mh6_En_>q(pDJWGqkSiR6sX-O8v2uKJI0)-#jR%FoJ{qp4iVTU&pmUENVb)It
zoJ7)3Mqp^OHHJ?}?P!_gnSm{<mElc{d}%P__$fVJu~pI^6k8>2!EkdpTN%V-`qdk%
zyyAA6-CJBwgQA*oKdY4=(3>49GlGW>kPs@QAIYUx5Ymf)0HsLyiJ%|Yh#Ma&=Gqo`
z{#4Xc!xO3^qZWlBR}k8K^c@JXN{Rxo8eYH^qSf%Ut}w2KH#|bU4v_LQdMm*;p_s83
z0pVmVjX4!<){Mu3>j7hUY$|GP<@jXKlO7|qzbX1HGK1o#@Jo}U#6aXv=oyN$YlydE
zB;INxnvXBA6ZRs7^esv*j|BdNMyjYlW(y&5Fn<Wz2g3^&VV)I#xY`}jh8!IfR7Ei!
zD>EpfLYWL3$wON(BvOYeUXrOp6;m0hL$Qe!blFZugh~}Y84)VI_k<Cj@tqAO#>4Ql
ziU#Eb5u>9J(v>Nc5uvgc(damoXWSUhHDuRW;am!6MQ%~WytXt!Dk?Uzi*kOlgPbr^
zDZF-3GO*M&KWHzC(2bm<IMEfv%cP@<^o^t=zZDC-+R3;j?<=9`9t<QtKw<RpK%240
z$&<(`8hga@qGV_-1oco_kqLUhXq8la^vb)*&~mE&k#`fJ+0gS3CEg$!JN}5F<*x5D
zv^+<Q8Ai1C%6bWnw!*;|DUN%_i$@|%g_Ez;m$3z$M{-Pz>ZZqQk#gvo%+08BDuRoW
zBj=NOQ92^$VY*+W5JJIqFsG&h?jxrrV*XFGGTt9A*F{KqLOlOUmwE6PH)fnFoe}~T
zVQeV_M)P06kt|Y7@iGk`N4OFc7A2;rB!)$aoq8z+(|{O*bcmq9lEjP&Cg(7nVztMX
zZDF(=DkH-fAf>bo1I9|Fb{J4iD*eM0GNl|51I9-sk|2F&OExitQC$;_!7P;ngybDH
zAg1zEzKa2_qH<ykSQN;cIY7#l)yBG^O)CG!Xrok$PGtSW#}tQW7c+bKyfDUIDIv%J
zsZdEn{7K{#9Z8AbLDtb~XJ(ZI3%~`Hyu`s*g41CcpQRKiGC_$`1^|J|tujCcRQ^?P
zchAtWO#iPeE@Qk_<b4@UpiB!}g!p@9jx7ok&L9ko-BJo#NK*_1y22t1WU$$V<cG?7
zGlp>~Gj36GwzozOwN*)XmbvD~mZQf_hD5%kY>9qM0Ag}r?B(_0OdmWzik!+?8`#N|
zhiEXGR<5EU7d&$r<48G}>j(l;9W^W_YU&i9h$2>A<)U1pvMvot-j$fSC^>xIiOeOc
z1kXju;k(Y3$%M^;R%TW5_FI&(rJ2Tgoqx{_H5p;}z=r*zZ0W2<yRA}Q7loO#5F1)@
zD|gnAwq5D9M&qthaMz8Le3BeYIKiL0W{8+(FcOEq5`h<`jV)8yXcAU7u}v6tkaC=q
zNYbVjW=hgNwTMj8HZ5XopvZeZ(2jI}<wl#bv~@u!OPe}Y+}fv7u#cqVm$bE~BPCpW
zTY1_v+*#yl>pGZtZdc0qB4s+bi!+(2J@DU|rCp-JEbXBy5GHKusGm|*lmTyP)UF))
zMacQ#062ma*a_z)Rwfvg67m-zc`2o10!TuM{YOAqp9uvp@FzLLTQX)b!$<4~Zj%58
z79~&{h(WLj3EFUq`@mlkmVr$oMx5+KzzBtiT0{Xhx%^i<J}n>mq9j^H)2ad8h_2zK
z$^za<4qHR`V8T1BR(_fA4~sH3fC$T^?*j-DtGQS$_n{%uuuv$LMw;KG;nk1_4kU{M
zq=c%V^~46Sg9M2|)mEq(Hi#NA83G#$vELi|hQU1`gbqWxc!79W1~nGW#}UeR{LEdQ
zhRg-o&ap`Q99MFJIhu<Q*H<BvyhwsB`3#*u*dTZl%RtFOKrtkj1104EX~?FM?HGw%
z6i8bvK$b-arU<m<Snrdjpz8H{N#vQPE_sB>BVd`Pz9GoOlP9p*WZbtw*dE`yCGd=I
z-4f=-w_XYICbRo`g(dRLP&Ws&hPrtUac-SL3<`uN-gg^LkHODUSUy2HZNvMCcVi6j
z;-l2yj49xt_1??@mP7!{qLoAdyyt-_)ds<Po~=_t<vd%bgl6JpGH{d%9O;O+@$+m5
zN(R3VL6#O_!(d{nXW=vjB~EmKIq_NEWY#r=yA~+aqKpkTYPEx(y)&#VNHJbVD^R3-
z>yaQ*bv`tJNaeth-CqD$1|)z&$bu0f0kjOb00ppRh`0p^*8$QfpsqA^Jog6XMdOF?
zz6=O;1qpTp$#3F@;g53gH+$iD7y6hXy0_5DY@B31jh$h!SsxS5Sy22I5Sk$(xS-Mu
z&NaZP9U#TD0Jvs@KzVf*;F^%ZlGY?4yB$GFh&U;o<1Bc%Ws!;*2|>=Bn0Sm<S(HH5
zA`l%7TLo5U4lE+!*@ZDIzALo>fPO~-<1JFoak6#VhN}k?TS4zFLQYwM?dC+q)AIWc
z`WLpm_y!H#29INb2g2TWY!HKC6pSxDTen=rXX}=bh+1g}q$Cj!4PPxxMA{z<H8Ch-
zM^-dIMF4*B0BNy;HaVst7l@-_$_4beD2W)^8M&BUqyaeYPg&CpuGNB_G=z;ena(WW
z6ORqQ(g0FX7?(jgcN|QEixyy+q!3Q?03lf;-Oho*SH>|Ig#q3PN^s^Tj@Y8)MD-%v
zD368{+?uE4GfxyEj>Zp76u^-AXQPlm!1NQWDUI8V+Q1J56N!&n1gY{FX-|w*gUlBU
zD=5bX)k?#9p}7X-+!0@kGAKEDr5=SG8>9_emTlPqeF~43l0(YH`NhhWX>g+yqY{kv
z-WWy7#;C-ny^B#vcs51_K5cDG5pE4P?0kj)OFu<H1P5jDjv&H2q1X~mw?ZQ(Dbb1z
zsSkx_TokWK3KIEXQ;H8tSro3aD0i<<Duj@&fj~Tc?w%WWNZGithJ5Q4E{fnbH2M49
zB#D%bV~dCPvvCXrfSPeFo^xXe2%8wJ1$}H615juPqhvg`i9rzBHqj8Ur)_dT%Du~N
zM#S2?;6Am_Mzm^|jR><X!HHw*aeCvmqn>}*W6!q7Vq-r07K{D-jGb3W+V@$M%-OeD
z923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY&x6R|Hy{?uHPO=h+V9^=~VDyAESg
z>M#zG>SZ6niM=Aj>oi`A*-zU}<29QVb6%%$EZrj2ZMD9#qS@=VT0hy#*nyj<m%+o4
zF0)8=UEMLFv0YbpjA(4v)g2=m+jaHih~{?PpE07j-R>46y0+Urd30^J`!X9Z3R!f6
zA@_EfCqwS-GG9Ym`3YU>M;zpfG&P`Lh@G3p(yex5YBiDdpy35CHUkCpqi(i!3ucsw
zVvVHC6TnsJic^PHb_D67(rEGNy7A&1>59&#0@#)0MFnvcH<6N%=YB^7GZoFQ$YUy_
zU2()zSUaPDkB?MpgHl><&U(J9#@*@(dPYlnbaJehIU@DIuJBf>=!?Q<*NHjadPb$9
ze=HK;Q77ieE;&P)GV!433iafpqqj3{C;77IiqYiLr7QfB&zr8uO1^-46PhQVNsILM
zl<G|fF<x6;;f;KeElPAc^3AqVgQ`y~kzx?}^y^J)pD)AST+b*=%gG{DubhLcSHm3S
zs=za~BghZ$*q+vh{hb?0Q|gm5nCde!^J?tR>Ao2s;Ku8l^`T)AuB}@x!e)GkR@o5Z
z^hm?QK~nJhc{d{TH_Jmv%bVpPBnFm;vR8DO9$?bwZ-$510Gr_<nY$Su93sD2AM&Q`
zL<*r5rf;@~Jb3$NdsusS<p9E!4s%cMed}}OpH!C|U6~&o!}Bs3<{M>^*ll2VdWOP`
z)q9yI2gX-da~i~yHTfx{S!7nKTMTh---^}km!4Z=X1?aR8}E9r(;yC;Nc%i#@XN8>
zTc>dZq534Vo~=`i<k|Wpv-I2<S7fM?-+8xpFKLJ~Y!TEU2jY^3^;+w0TaU04F@ZKo
zYaHIHOEAPs6mVf~)(BjWUc!*fSQH94F2gcO;Ptl>g}IS%vw7)huuU%#_g^w`r6aT3
z15WU8$UDiYp&zi4N18JahbK5O)guJMrEtRz-~HNpr0Rf_>rYwqnU(!1tA8)k1v~@2
zOc&uh=z%p!UqXKT+4|(i<-dlPqWdq7j1JS#@d;-~P}nK&{yubFgvX>0dQalBLmI*a
zs#YIzUc)cLKWO-<G`w`}^fF-Jy^Li21Ei4kL3>p`pu1v*=x6FfvH@RI$H^3aB^;uP
z5u#VC56MP6ycaY9JwiA!5e_8B*&=YoJn#<67Z;LTCJ%V$0GjYA2OfYG4v=z&GGD<H
z*ehxX-oifUZ%j_=(1@q~5ft)%;6pk!@YwHz_egp+`_MIl=YJmxiKd6NPig$=MD3_N
zN-rz1E<WXj1t3Q3Aoyw*iHylJb5Xz;97ttEfm^uGCK2O{V9MhK2Xmhtt^AH`+B5!5
zqJpDl_L?9R?=q=`ADor0=_e0xlEEK|LuHnrAT+Q~Js#kZ?~}0*aN74dH9sh+Q^wA8
z{r4&Z#PEPVb;Tfr05C0|h-B&&frX%iKFb-3$b~+2iloV-Pog0*Bw|r87#Kkog|R40
z^HL}kf-Z<|^U27JM8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}pehm#z$y
zV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZm?V5D
z_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gKz%BjsI&Gn1CIJttBk0;e$_HV
z{{JDisb3X8gG*DfO=%)X@T)zFs^5A^Ak?bgx*!ma)o&>f_o)htpA6tS0-MVe(-rK#
zW#K_6SikwGM6?)Dz&;gUbp%w{Nm9tdt&<=k(^i{7XZh5)B^-!sTNK8rAp9**%rHLO
zSNA|Gr%W3V!t54-(QX|l#jPtO;`IV^jnQr)?6*z@1pM_|HX&FB0p_*`4ifS0Q_+Qs
zLf+w`xoIUrkYc~{R|m&NKRF^Ddzl0y7LrJHpA7XPnBAx1DFg8iZ>x;C3=+qWJEJ1B
zFt`55kAk4EMG^n80m_nyAkjr(xFqaB50zHLnl3^<L=leKWmrVW>cR`81jP+dfn4{K
z0E2r-?2#aZm^F^+G9qFk0dANRLg4L!NGwY5s6V<k5Goevj1MU}e%$~F1zsqRIYmSZ
z9}C#>B4u^*GOr=**iY>(geH518zE3?fpC)Lh;R<1P7FGYB!u&<DCvOwbW$cLld<>t
z$PAoNMQvv{B_tqfI{-)DBD=lfj2QmyvdSSwJWxy-*}dNCtKIb%*AVb&#NPL4BKSSe
z2|uro3S(b5s*V4g%;ZL5H2k8#CCykWmqm{u^{${KM&0{a`3D0$sQhAt?>jI@6yqNN
zvYg)l4<5}hE||caO?^I-37nxzNH*}W3NjfX0Be<=5G*j|@1D4L2z^^=4{pkB!`v2p
zF4r*U=CT|j$KnviZY5&4Dg7W+Qcp;ZNaXOs%|NP$TccPq8^jB|0tQYmU<#y_c%e*S
z+-@q3$NUrr8U#{UqJ5DNd{cs}wL~t)XHnR~3ts^_G+uZL7?T%P0+MkSk}^|XkQD9$
zIxx@Ly!enOhlZx-_{`Mw9G{srz1&+)`~cvX1rjuJb|73bYOdrZw@VYuWQRq;dLkui
zQNW@LlTqpovZ@w}HGc+4+=RMTZdUvee&@!Fl=_MEF0Vv+{Fj@q7v_>J61pMRY~gvM
z8}iY-64o1JA)~YMhcaZ)E2|t9PQr_SDnrgIg&e5n0ZNXu0I7Cf8RG$sp6KSeR*14%
zluX7;iE<@>9}Ol>R~Q$Q1-;U?kx;lOm8KY9ax`Lc-YS6-tJf-l63eHcF6Kjet1QY`
z>m!ilF(ce3O{X_9Ef=M2*_c7#a35mWGuboOsZuI&-L#2Tu90#okumC(L)|0j+F_+-
z(&=hr=txX;S#FWN8le5mlg&-uRN;v^uwFUS$dmQTnMN+HH*SQ^b-x&gz~HJ?Re*`I
z9aCf;CNg`Y5CJ~rm?bQL2Qq{g;bOvYuA&eokY(&!mh{L;DNnNl+ugUM=m~LFQuM@{
z2_2$eQFnoy%45Jg4T;RF_AN^~&jH`Eq+_n$h5G>8CQCdVpGx!gEloO~&`}x!-ST?#
zuKn1djdW;t47pkarqQoQ%W5-;9wO4?2awdhikU;k99fL6U^-;Sv*7us66n2>rjcat
zN}6_@3%#=8kgV^WPZcKgFA7ltI@n1M=K=*-t^85o>3bzn16IHVBF+db?*+<`dc1cf
z(K!?<??Mv-(1BNKbvo{y+12oadoN&ysV+?52IzwKUx67`6%c+LdPFZ^h8w*q6*WL0
z7Ga>pF8nrbg3iR$$h~B(kxvF`9Z`^kxFHk{rL4lu=Cbk=_F_@qurcz7h-6~wMr;g-
zh)x;6aJZZU#OgR)nE1f+SOfs8bac{fi(E-(s(1QqP>CgRLmX1YV+hU`uiWo+rFaj%
zz(cYMy+Gmza*|!S;XpxI1dd~>*FZZzqRd$&J$k2UnxHIEQU<>Q#h^cEWe=TMa1MBX
zv_Ln<CMX=(`CTEH#G3I=OD6GX7KICh>K$G==`g?tC1obTZ=#S6L<ZnEu24<@=o~=;
zSdXa}(Rxh1@-J{+R4zL#-9f>flZI`t>~@&3S^MXc&_Sy{5L(ee`pR?;jmQ!JCt``A
zPvRH3(-KRJBX_AZKtYO1MYyVA26ly>0$?d9knhA`ViBZIK{PFjWjGyioSY6KLOn$x
zCHyen6t2@2W=pS_R>Ddx5|NG`b<1rK;8d&00pqH0!B|`<GUKiTIgF`M6e^bqrc9QJ
z`V^R!yMQi$w-pp(kfr9gNHG>vLv=Z{i0tK+^bho}MM;-A0K&Xb001H8@`4d(%suqI
zgdt;btWTnp9ZAAxoIMCbhReZq?!%-R6nrN2t-}@XOPDox-3HecEntp8QSict!){MV
zf@Bl6yYB#TDSCPsr8RRAIDrRJmAA+7Dd;&@q%q;?TxDzsVHcE~6pV`w$KOFDJTLSE
zVCA{ul?kZl!b7;Zw0fD{z;t4{v`=C8xih{p@%^I48s>R(ZS|gmmG5x*9T^1ZP7FCf
z4Z7?8x`%4HeG013GcfJ|iCyw1CRR$f8z2(BKpOy~=nTU?gth2SD@s}wy>K0n#Obc5
z<;{((JMl)?^{QC+DP%}5D2O|Ev2M(pyI3z&z)iZB_6|%+ciyXjt@Of^Nc*6>E?QIq
zaaU9w0Wn=JTY_dfQ78bb>8?k?)3ab-jy7R957qGd6j-Mha0LK8-zgo#1?*;?(Fdyo
zehN+0T?Qv0j(S000G0Hea_2^72rltXT~23WqP|m-f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E&I5OpG@-G682@PI7?K9>0)oe0zKpw(Z`|`Mks9I^+2Z
zL)V2CLY&=q3OPl9TqmaxQ%*czcVY+<^Y@)X#sD#QiV=A|5MS7p#6S$<cgmF?zrnp*
z(;@}tY<HDipy}+5!lg_}TCmD*EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NcG0$UI_bJ2&D^BKxpXfL?m1kfB)L#Lzx=%G9(7t4-Btr@RRtZ7!>Qd=T?{lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3ja<SJm!v%f|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR4#ex=JNrL|3T|EVY2*vO($6KJv(-bwdDAtm;rI3oAdAO4GfR
zoaBrzlb^IAmX;{hiRC9sy<&-q(!e@ZqEgdP>Y`LRR>P3C$LKB8y#<9zBOXgEyis~&
zmgb<M$;ut2igp?^q^?E*kQ^JC@Te2E<T#~yf)Rsyk1AFTV6&Bqjd~?6WH6RADOH_i
zPo&K=WXoL+JqB&nivU4eLCH?N9v1jguZP8GSxv_EPT(Y5?*y#oh~egc;jdLEWB>rG
zUP-J!qlXj=)YMxG;aK$?W1X9z93Zd{2Y;~-R%B4W?OGA)x1CUZtjtqSOjhrycPK0T
z)LWHhfcTg_R4Aw(ycvL{H?ab+>fOu$ta@9cg3<B8C;6w!9M!Wu3nA6Jp0$$d?az8j
z9(GaIU`okTU4Yruivx7^;s9N}VD@7TC|NLABC4z$tRt015SE!LBMC}TrGW+lje1qE
zwt&KJ5Z?@_qREDZv0&6WKw=+^?PeDa?N%o;lV<IQ5Em%pRdy&=`YK};%Yl_a3t?Af
z^Fr9wZWv?bv9g|_I$0UmSimd|a4c{J16@`x%X6L?(4BS)+4)#Yjg~+ZTPsr`La;V-
zBI~u4$&p3f(j>{EZ)LG$VYoDE=D;8ailt_SIhsaUgRYFHtWziZ>XDV~$^gq^cV(qz
zLA<i$X34xV^`fZWZVyK3z0GKxL0M&1X8FD{J+s6g%+m)*X;#*aL^}qp+$<(ohHw@f
zq^bNsNkUi3J<ArBy`7~E%O;QNhh?@$fy9HxeULiL{rona960iCdN^F)ria7%P()G3
z%^R_bK9;wFMIp<h!LpI%^+0LKL!J?qpDe!#OH`I`g=H+u|AIo7n~w(7Fw2j_f|=#&
zVTe_^gR<;q`HK!#<t(ofOLwN%iKRWuE5(qi@>?OM>X2`XMMTT{g*v0<AY&=ga-y+X
zDLiclNV#Y_3?KU_Z`}%vN>=W5Q|YeD4gDC|uY>N%gJUbCifdylriyDrE=d-8J<4s#
zYOv+nWW`u{KT%Uw?om~pg$wlnsgKRg%JQ}4iCxug>8kxy^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9i73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<wt4xnALV{JOD~y8CWf5p`e5jgr5OTLV<Es>%vC3ap@CK@5Bf#TB
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g+=<PlIYk=_`#Nn4^f#%-$3eS@W)0hotQsEX2zgYDcSIUV3u2=@#M<2K<L
z$Rjl4Hlb_s+|8&`Zw%R-oZ(c|DrX3&f(l$+Bm}N<me&^f>RI9e(Xk*5#?KxgBoB0+
zGjL0RxN&Qq#%NtoZcvbO%?rB1e&ZG&duT9kdc+Se3UW;mV|;*=L9mSP4D}@##TTd3
zw8(g7D#Q$VPTf1Bsi!(k#Deoy<x`=;tK)$Y!PGFB<Rc|X+SGjy<X&&572&Q}Z|{ut
zW<dCQ?PXe$BF5uc8N=hNn(tGEo%2D<z;wFkGjja^WuAL<JD=bc0ncYU!sJ28aQ0J+
z=aIXtXnU9yDj?szGh#nm3fRY-9TDLb`A=g?<p$6wqx1n<a5BAsMxV?+I6#R+6J;pS
z1XWoK?n5egw3sWwfe#LBYV<?t5*$6GM>!X?6jove?2kt!Z_tdHxgCz&&dU8*_EjW@
zWD7iVU3st-R+0$~%aw*g8+N6t(0b0N)RCmI<-owtQE4*t!&EMfJ2P}lUwSw}o$p>L
zIuuf-=m5OZ7v2G~ejKTx$O}3^ieFIjkOSqa5{x|Ujmk=L#7;47$p@lL;t`$m0Y+S9
zIyrOtFTVaAIsD3)a)wt`T9pF?PkC3)?E8!FbZ5T3a<zOg`)t%SGyP1*>|pv?{-|SY
z5{=<GHfat6Nko-=wn&*bCh1^)yHePEFxyPG{upFd)4T_|>8M#L=S;72rjsiL&zU`b
z35L>v$W^&~ixMKmbUz;edYMv82a<1)Ab2Dx_ROr+M^c(H4V@|BQvv~rXLjNdq)h$P
ztqjv@<vBW1U1_LGN~Sr|+~Z?Uo%F$+OdTK0>{bfqqC^Vj;NT$amD=f(8JM)YFG?F*
zis&NbXwxpT+L=o!D~K~od+I`EmbTJW9R}P=XI+$JOh;?%*|5&6Y^BUPYSvd;txsgJ
zDHqo#5Vb2~*TV)}IlYcgFzeT06Rxyie~oC%8+PSeOMz3qHPVkA>DGF&Oys#Khxu?A
zkt@;Jm0~SjY~o%~`m_hvY0}SjZW?A`yArH*4k*D|w+5EClD!ut)K4aayK<~c5}0FM
zqJSi87awpNjZGFN^3_WgkTW+*7NFiR58h$ZrrYI6QgX0uy^?{_Oy>1L(ZG&YzP?XX
za;&U=N5Edk*r8Dg6TkuPR=5F<9oh+wvq*Pg4>)tM1y8Uj3HKm<14lupM}HB*7*Ie6
zp65qlB{)p&g{R>2+3*$|5rP0^I6%rT&+39N<5|iiZFw6VwI&1*aRe!0CLkBrxdBW#
zGqwdn;d!V6r~-s|zZaT?<0vk~3uj`tyjFe@>47o<55Q6A8V(%$Lf~*jFbbq&5t0kG
zbxJO%#D&9iAT*FgNIpnAy>QmZr{X}(>rNCJzW@RuToOlYWMP*$^T-8nvM4bgLZIXi
zB|gi&b&CNBN@Y=kKSEn^q@N3sW&IG+DT&z<lpK+64rZjw;vbafE_j&yp&ZfJx+P-F
z*t!Ky%h<k^h%q$0AAY$IZPp(^i5BXOU&Pyy%>jiy3Or{~QsL+l4Jg}!;8~O$UE6xa
z=vwv3!I|tq@$XV9F91<=2?fD+WFNQ)wsUTsQrKxuUX-zc7dbSo0ytWfYZL^M!`HLH
zBrQ?`LFqwq;aC;cl0(ZYJSInGK5V>4Qi7Q>={mH<0)KLpFCjS8YUhAuo^_`53*vfF
z5)5jnQ*c)}ReoI?j+I}4951jdhjXeBu@)tvxBAvC$KSVJDGWm2TBMu++#HLL;9G?7
zT9jaU+xq1A>GgF245-GcU-yP4=7{et#4(4XtWe1oC6G&^`s`{YHkuw3hzKs|GmnQu
z0;4&x3J9Eb1Syfx>KMqI!s-+t;+<X-7vb$_y-CP}V?%rMix79R*dP>HfN?>1o()rO
zQQ9Ev+yP3gkJSZH5O)-nz!w6(U9^S~0uPkbXsni<0C%<Qz_+VKC%&B)o%nXDZnsFW
zi-hdwH(-i{{O9mN7CK;1{N5o1JuBlB%-|yA(w<wd<iyF=8jPR}7iCF?vYdmkh9XGB
zMTw19Ha-GGoU}sRIf4yr(GloffQ(KQ34t~SC5EF-e;a`xbAq^7%Nz$kYe7gl;>QbS
za#0prPQk%Cu_=UC>3E?RrlrGQTez2=_!UCNJc1Czk*0^Ye_?Do$_f<@rvvsvP@RjA
z7)Jv11Ze~PbOgZ{FsQ@wuqXrV#1?&uUu}aLWs7_QYP{e|7bUSr>32x*jiX>sN!p-M
z9VU^2PxY*uQ~;|YsCe(9B>1du=^Lo`1amEdoM7;U0~9tFvH@3CI-Dqa<KGQfv*WF0
z8f=^rg<lKOhH>ja87UmxqFC`NUgU+ROHyI(I(+wq%ezy$hP%*cSr_h&BF+RDtuTUj
z%FvfWT<)82Tt&LJxrYP^wRor0L_?}rVCpD}w4=Lk$jRBFY4pE*{HJ5>^YitquPI(_
zyvVQ9?YwS(9j+h$`9FUA%ZGiOum8#a`(J+^HH!1&r%r`NO&>5%t$ZDbrmK2l&N|VF
zc?dW1Kv`SF`=Ah5lgk}SnVBjlKKUfHa__9<wD_S)eOF0cCShY6SN%l0vR3jP4T83<
z2?+Ca?GGo0jetfA+A3k-1RTf<_j+hgDv%CkPNe2m{`Qsamf>njZp)%l3gSJaMY^7f
z9dKXngqT_`0cM$F%^6$`+>Wp(;l{e;{Jd~u`Mur3abcxOm$KsHzMH>f#QU>=5zZgi
zY0tDTL<MC;aIL<J3!mRhd1>WP8+o`cD5Ot1+4pjnj9aLR$30=(jd-k`^_s13oTTt%
zCT1*|HDwkyl(MW0T%fVo7+lgbtIiP=jg>r%WksvX#n>nplpXXj*aq+`6qQ@);|v}+
zm575P-d=^pC!<f5!~Il*J^V_0fI1@(rzDKA8Mnd`=s|;%_w3ToB9FLVdJSe;WA}Rc
zT~fy$ohyGK4d*{d!+fKB*^y#2)e)4tecKW0I2R;4zRTa2L(M;H>PX7{ZO0XgDQW(h
zMuJVczvvWO;Jn!hTf)EXg!B)~V;FT^bJzTJ2X3s_o9gGb&H9%e5b(jR_fv;eZN@J;
zRxw?6B<1?9V}IJ)*8Uj+`o7t}=*Tm{)RC0y+l~piiKF8u16XyGe9<Y-n+zoRS?7;`
z*Qq^khtkimdAuJ}f89~1*{P1C%<nozVjT~?SGUIEyokK`q7zTb6P?(e-*g)HcAEao
z+8f*H`q!QE2u3)_PaVnq+fG~2`E`W-42+TYllzN~Jm4EUigJI~(GZ)q?tz~PbfsJ2
zufL>=qeTa{zFa4Raff%y&#ZR(cH4Z>@h;6OJL;PHmKjyE&Tzb`_@XYezwWrz6=X+H
zR3h)MJ0hp3PU1k{e!DEc7%K17rjDe1dlF|w9$dXY1?`QS_{(p_-!ybV^Zu^O{dS`#
zC*SY*FFBbu=Sv-_9Q5xOeQX*7g{27J$%-d@W_FY2(ZB2V+;7@Q?tpjw<jY;ah?%aP
zkbz(4w;h=)2yG{K_`Ck|<qmg*ccLRH-M;NOo;PjkXW~7)=~rKzU{J#lG4pd%%>3Jq
zPv5mQoXtDso70)uR_qAMu<tr{201|){2Au+clGd#+lN}@P)AVYCHvx%>~G5E&&=U?
zQ$N4x2rac=>PWry+nv#$@utlF%uwAo_4bR7)PgAhMY+D~=uE3c*7MJd_}VC6cBGbl
zsv{}$+m1drUHoUnZ|u7H7o8r!{GwB~@AG?2w(na0&v@Ctsr_Gc!{eZ<8wk(0-RO+L
z6XIu?Hh=S|(A&e<QIu=z_<DMr>*@M>u-aVajn{t+w^fz>U;A>cM+j{}cuPcO_iD*e
zm0?Z?QAk7ykP;fia+d_wN&PA)rr%i>rb}LiBG8tFyYwns7Afa8+OT(BXSI$1fuUhA
zm#odQE|XH$Wfb(B_cqD2(9OFhITFT3gUj~N(82~duZ;;wnMBQU6lN!=&O4>}5;jPM
zrXXgFa6QL6sW`LDIa9GoMJP^%6?OKqC8Gdo#hr-KHr|BEcDCY8w8)lFap|0+oo?E0
z6pRU)_yU{YJU46UT6yF?9z_|<os-RSJiC3=v(Vo!_R(=~X2V$6ac}m~A^fS$bX##I
zwD^u|vyMjG%!|b4ndJ@Njn88@K8Lw*$XG=i_7K9YOy6U(J_oDEW_^xU8R&z#qYTgB
zd>ehY&@b)|+MZD$dzAG#>#&ZpJ);)usOVj&>O?oABchGkoCe0(FYb)Sppip9k3}kf
zMsUV!gQD2B*9Jv-R<9_4JDcVEq18gZpP01&>iQunT~Z<dXF!<0sesURAo-p6c5+q4
zycre}F_F#Z)+1)^Dk((omQ2MrtGCMC`;XQ^jm~R^p_W&n)f${{4z6=A*UHiLZHnRF
zQ_<HNT-*AD-M4L>?AdF}((i}*vzVmH)6#X=l&MRHV^z6@PqMkp<<~>*pSyE&eMSkg
z=?<-uyN*1`D$7f!Y7_Vz%(+$E*O6~o6@cl`RgvHqVXGkwpYX928m8m8DH$}p&5KK_
zSL}F{W<BF{R-@SQ0YZ*_Y#nm!bUe4QRaB<Sylnv>cY0Z~D)Z6+g73<X^a~|iRoWTO
z{I&&upk8bG8R*TALs5B*2prfdO*6QlZ6P38dleBNN5&|`FP~ed<a339pgdtkfS{(K
zVn7r?(b}{13eHv(NLEjm>*-?k^gRS5BH9}B02u<(<cVOINEHodC`sEwKr)KssOsYp
zq!QzsTelqF+`5gda$dnOF~BVxAWr$JmL4HAo@LjoR}Qe^#q!@+n*9JNI9TywDMD4`
zooZ(lf=8TC){2J?aj}Ma+q%U`po;T;v4na>jIo5eRUi#iJ5{%jc&PZHbL*BPlDGMS
zcGN0l3`&hXTd(xGJzK9BkV!P4aM)b}1;?blMT{*D*<HP2IJO6j#fojAB7ppE6)S=}
z+$vtIMXRFVVmnr9TSjLu@NLCa;bN^kHpJisX1999<}=3MB@=w>k>`T>=H?1PF-I#t
ztGEJ$6bAaZI^<t4jsq%nv$l204_BxVDvVdq$h({C$QaM~nF=Yse|4RrEbyW*))F2K
z<Uqy`<w<rT&;Svst6hB@MmvV!qG0r?V__l$G`tWDWKDp3#oxw~RfGs)Yn$@B5P!Rn
z^|^=>=g+C7hx-1aL<{H2sYRX{JknJ1AR>r!Xwu;kW*ij-FxY_^DZ>EK$}CL~lqg+*
z>kzT&t#Y#_j)zkUVA!!&u>`JAicywR$aZ+1Tjg#|PfHiZjtAc<Egv!6i&8<~!L_rv
zhKJ3m>jA;zi$W(H_V*djIYgh^^N1m+y|_r^NbY5OlzD)tczYC8ob#{>M49=|iVrq?
zNb!P*u#cJ>Xy<S0UO*7N!Icm)YtiIfatpjDXoU^?DVfL(VNc0KoP~!yB@(HM+2e0{
z3PE5XLa16+d2I;Ax2IR$$Ai&V%E<$kP*WUF)F5FB#SMm3MhbG67l}C(HzrUSDd}f=
z6hela532wbq=g(&C*|C8M^-HrNF?%07KKSEIevvEAx*{ZElDYlWvg^Iq`O$9ydfuM
zQItdzBU`m#7T{Y@qD5{F{6;0D(6LboDY<bM1<XW=9jgpBWC~a%upu*OQ8*UI?<mx4
zU=5>$&%?Z>?53AOrV6|WXoMH-W@hrhCc0JaCGw@>Cv+qrsfv}1KACrAx3mMKW*MHp
z!6|H;n;{PQtF`)uU#->8%gpY|QVKT76!0D=G4g=1i%A7YSg=cP1eC2sttw`#g&<tI
z8PexLKT;C1jlGImy)Oz{5s_;bUks=aY*(c)rj*%LDU3NLmh?)>;^8%=d*k1km`6_+
zO+5hgvkPxYAdJ~1t&ydv?V<sZz;<>?K?sC8tF$zr&#`z~QerW$IwSB1wn|HbO_X)o
zk`kNc>S*QY7-#B?fVwJ&abR$j#5iJbmBN^A=1bWrKsB>VXi;=LED|T+7@H&qd8byn
zZNM5^lnw(N-p-chLeE<Z_4q!S{~83g4S&GV_f_Ulmcz`jW%0mIq~J!e!G|fh!TQQ@
zLng0HAsx~oV^hi}Qi7v4;vglaH!raunPHoK5kXcq^;YqWG&7YWB#M>EzK9eJn*bIf
zu9QvJU#OtvCvcdoEQCm?uu4zsD0;~{pPvHFK`mKOf)7JmDsd$vngYKQyL6QHobO1~
z<NXZ3L=2sYT5ye}A3Ji{*E~jr0o_}O-XJOV@zApy1v*dyIVg<t(Ee#iHM26j0bzjk
zmp>Dj02C7?qx8hQ1`XVXwoJzAqj+_;qly0x2AF1K;6S~{0ARvu-AQr$(T493v)1;(
zTa9smN0LGaE9VR0{5A^T0SbyM&&N`SXC?L{Nil85w#wHVLJ*^^!t$Sqim}EowAe+7
ztINs+2rv^9PHG@<JV`0kju^i%Mgd)Ne9&>9q!2@(dIoaInQa1hEbD^_dDAlsz+6B-
zp6|OLad<fP1c2!%$z)|qMA0Vml5b=N7;z{a)t^idla7c46NKc85-nn<bZE!|esrV?
zED9&x!98Ri0D#0~YczzVy6b^x*uer|TxcUEtVJM>nCszz8e1m+re_tdHMY1v3}LOV
zmk0oft&-Rb7qjamIUle#d4FQd%c<>nBAN<V6D!2LP<w9h)uc6KB7s$!+j&PT7XpyW
z<^}3=VfhNv2M4iL(i{Aq)_KDu$dFYM9BRBR3Ma@IuSbcacs5$kAB}U_DkJWM-dILZ
z2J|QjD57LT^!trwa9U7&L}s$C6B<}fR(4U~Jy};lO5#SDAn=GSWnHP1c=1_f%)Q=s
zt3|vm7>5^$fLjl~EiAj|!M8KE8gYW1xirMqvR>Gw400lD9iDe46Ke+qx)nxULXVh|
z?hZnaEK(tc#m_Pg?=OOPAFh~UzaPE{!kP<kGwXsgeYl7Mzk9fdz`g^DnswE+>ycq#
zofizD*GvZBfG-I~a+7t`o;1|8`aB5gW`%SINPLrxII!V7e}|lcMk1^6(UEmvg?ERn
z1Ct>+km{ZcYUIaohjd<8M_`zo`9lQO!#<a}xub}Hb-{n$*yo)XMF(L^tOM>7xe2R{
ziQTw2y3jpQTl7UiYsD~IV-ie9eD9(F*A36SMHy(vUTVVZyl1q8jfnf9@zx7q!!`E8
z!@E;L3jPk2UKb@0Fp?CkYeM;kqumr%)ZvGIQP2vmDK)ZZBF7OV&L>ok0>pzq(+Us|
zZboZFu|{6fA^_g1!`Ej`pquc7S({oi<SjG-PQ$%qZ3>VTo+4{IsAe))P|&DdY|0Pl
z2nDl*$~!>HZbH?(@(*GP@ReB8DFio&5jXEec&Yya&Fk=8tQc8-bfSmOCAb|-Kzbb>
zg~Md%?{FBHQb0SL0gFOtQOJW3lrL8&A&WYC2{<`3krx3#uN|Fq%%Cv$qU2w+Fea`x
z*#PSR@%TETI82GAz#(}N(8#}Ug*S`G3KLN~a@ws4Z}U3Ui+{l`IgW#|R@NGkc^~y5
zH1ES+(ZV$$2L{kbjxDcZ!ba5!)A&*^Vj5rg4lNlSs0v4ra)A)gWpadc#Ce!fWjhST
zD~gz~%W3R6BCuGQAKC5X5Qln!SwOZ}lz}$85E^s3I&pwqoye_Ua!dfrEM6P}Z{C^V
z*w@93u5R@y_ChWg(WI^M6+*=67X_{CQV7pHb_(DbE@@M$aaYa@Ib-USQ-YRRIadL0
z0=66=<e8`plJOL$@@JP-b+z%|@%Qpn0si|)QVx~YQPV9!W2gx!bwJSM;OYZ8+-5?6
zMs|TIGnzo>CSXXynJfz7$FqQi*@IU0(Cso9rmuP%0Ax2)=?s9jo83~WhDVd5?drn8
zc6AXLe75kBhKIAM<ODEFO!$<<r8iSK31-{LVb}9@dt|6Rz686UsXPRd*Nmu^i_kJW
zA6uP<JyW5*faDL(0B_o1Mlc#G2<&e{!c5@*Xy=DnFUL%Pv48+G)!glArn4&P0GqaD
zMF*TFCS7}xQlzS+1J_*_YCauJm4CZ)=_eodofbB^F1vH>0ZdC{nhEIIJz7=H0n1p`
z8@jrndIPM?Rs|fm(p9b@SNbKU6U|(&s@`C^U{$*TDuh+>2B;8L_dH^8%~ZYt1w>7L
z*G0)61`9ejHJ&9$AdKV^Ktbr-(#(-u6vKe42FR7a3(?3xlOsvVDm<u+(4`%5CMK+a
zjyRK`V7xP1kWv7Ho6t@PHe!}P>DUZXO@KABDBxxHRBZ)F&{3rJos!%YJUD>17e$GQ
z5j0^Y6{m*+DVKEzK=w|7%~L?E9S;IC;R|;Z^)(<Q{9_7aV3fpQ^o~NZlo2vvt)o>l
z5lUh#REh8wF!{?n?TT-dI3I$PGsy6iop6JBdKV%<C32H;k$_Qh>?9rx(7#$93)M1=
z7Bbg(Fvy|9N<?N-*%}XqqTpZ<a5~CNlM*$U@CV7L=3-P)$f*?ER>@c*q(}*k9q}da
z6vLW9wrP&sC?_veshC-4>YdQRZ)^ct{N5-zsjOAS11Qu~Gp#cJ`qaokIUg+!zIxvO
zFtYO&`!Rf)i{2>bI~&f)8>~n}BT9Ax^7W1IzDTEwy;NsT*DSEqXV)x>GIr@ebbu&F
zRz@p1i$7|bXHh6-IXvSUv5B)!(teuwK+35tjBSHraNE{e_9E-lLRe0&_9siu?UY-*
zjBU=sbvy|URky3Nfd%mDIEf;8+kq2h^zdoq;uAogvqpk@%`htVaXx1QWj{I^fNJ07
z=wg4B3-tFHxwy~qck&;YWl@@tGr|nIR)8~TT7jbE3Piop$9UVT;wXv-n6PTvbLzrD
zuK9E7!by+<Ak)T0fh_R*(e;v&2*`;=0HnZu>rNVIvkUGCB2Lux(rzBAs%?K?x`M#0
zd+G`zpus(L2Z38R57PWLl_?duzK8B|FyaP!dEMp#TY=lW<J-RJ2n|^brA9PF_=oC|
zBWqx96)kO2mLOFbhhADw16<3ZWPPD_mxe_y{GwsCyEH6F1C2DHq_qqfPTdboxOhsc
zg6Wmo73-H?RIXIN^tz?q_9_!g^%hHi-BNEc>FZKAOd2kEXuJnV?3NoPfniH;Zr7Aj
zj5*Rw6UukH2G>v(NiSZP)aV;cGz<`I7qw`C900NHsK>*L^ueb^ySVPEBzke(RV4Ik
zdexxb_SMvj(`o9(>HPYHY8O{tVNdNcW_)u-r+RUjPW6IhPQIA(I6aay@Rr1&C*Mp6
z!D{nXFN}HK>Vz2hHo1-YifxnIm@i#s+!!N3nQ&9j<D(&}uins$GCt~=9qBfB!Q;S~
zLwzvf*m?1w$AE|WfXSN?hT~<5I7jQUEZ}x-n-PW_?XukrwAl$#0T2~gJ&qu;6E^a%
z;2#W7lRZT^GBQUk%1B!n2TW54D~pdueIV1Ygk&~Aqb;NfLb5S<OqDd4Nw1>f<5nlI
za$unwV#y-gCOR>2q%q`66+KqM4LgCAW1<h%c>u@DR4JqZM>&j>_?dxDVAB||AgNq9
zgST4O-WiU(evZY}iDT*N#L;y0;ZQnGQo#c>Mr+A{yC?&OV2*}nG2Oibc|c_?ZVa80
zMY$zFcNv}Apfz51Bnk_LWtsyz*$XR0i;1k@&1s$|7!l&0n(7lUm4~Kw=JJ#wo_X)q
zSa2I&ds9^X(VPZ)Rnul<lRN`23S9@$n(6^A5CA?r4jBK87CuYQjH+2XJu@m+P5Vi!
zQq&IPyiR_nab5?%(;lnC-a9*GzFK4aQNbrUjq^Ikoo9hg?Tk5Uw?5q{^f$OoXU#2c
zQ#xq<YfiK2t%as|JTy8qnp&8d(HzpDgO<TW%I0XD((!PXoz5GYPg_rq9A?;wjzV*6
zL(w_w^u8mz=SasMx*-lu^{$xX6COfzyXb0+*4({}2T18=)NuzlwxK-NO6a-a_5?HG
z$d=dh2on6T@dqv+EH*4{G4ii6?Z<k<XF5Wax=t>5hRc=PPzB9;M=QOr!V=5sX4bnl
zVy90ZZ<S7uz78cCX5^V}G4pg=x2!>SY>w^L>F<|Pk2SHbqXvOnT_+7JEQfVz+DJ0D
zPK(xGz*hk&wgLr^B!pmsm?9+DSWB-l#7pJ&TBAHkgT?-07{k(Pa$A~e{WWZ5>-1GN
z8fQAquZ84tp%vB;C7ZRza1T|IZw2Xt;WBhU${Y$-AJ$c=y;Xn*IobvM!dZ3&pOB#d
z42<{_OrbHfgv*U9*i_uIHH7wPKQf@q<!xg2j|mi-**~VNz{Y?wM=K+8a<Il25QXhD
z+II>M%oy5}|IV-;sR+if9s!*q=cgiynDbLnM-94mMkTFQezogY;nFr0iEWA!(~BNY
zln9T)&mvAt_cm<L$09+b6cwh2tD?eafo*uOnyURaM1>uujM9duyQyF?vwuuwj~i?|
zruxYZCal9$mbobuOiwOrjCX@LTE^6oJFvj|RXnG7=%zF1qN?TH6#S)&O~GHWVn<Rk
z_zU-#osdikeHM~36{ydAA#*(!SoPkV&w~b3Src|cJ8?ibop<eI45;=%;+P#l0^}l8
z)&aF0IYdPANlFI2o*LejQJA=GvPzUGt9lU_smZYc4su9&rjZZ<`NyXcjZE<W4dw4_
z;5q>^?P}*KgSt>QI$CMN5=>9z9L3;i>}x=-tq9i!=tWaOgO+y1;WfofP8hlzPK38g
zzG+n)lJAp2t#ZXIQqGWv`Wuj8<P_nb+0H;!ZU=i%7stljNI4&>dMn!}=S)S(fH`Y}
z@7Blw3bU<%2Nr2WyW>w%ubWMOfRkADI*dlRsSpVR7_3cR-z!BXyU{pijJcYw0Wu2Q
z=_ZUkn)oALn+BxUMVX>73Oq#<nKTh84yBfvG!agYc6Pd=g?+>_EQ^rg^t{{bX0XMi
zOV+Y#lud5?7a`;2lP~wBfcle!<bi4zFH#1aYXNSo(qs_jN~%d7@S=-UoHHq86moIw
z5^&|slm;d%8j8u<g;)$@=+<Ru<qR()7nILHCLrAb^Jgl9gyV(<|7z6IjP}B-i4Ax>
zTzsY4%~S@73$2Kk97D#~uZu?H$oYxkd$uAg1S8L#dAUXooMO9N!*9w^;qakBUPEgL
ztK&7qdm50h5;s$}40&(NmdVjr{5P16Xrb$3sFMK>!GscI06Q=hk22tun+i-BqsuN?
z!H`^J7h@PKZI>)$WsEhu_>VbV!c`dY1MK33LKHH)s8sRSIid}pSCR%4{ljivAch40
z#f!g0YXxY&sb-kbK6*>#Cp%2l$bx0jt&1&J%3=IBv*w%(po8P)32n5W-dc35V{8vh
zkePEZ0uvGNSQHZSSExQS(P?dH!WfU-@E9lFO;Kv@V2aZ^RJa&0!`wPRmc3P|)rMsC
zILg37hBDlbn25t!0NHji6ZO>WnvxbF(Yd3KIFh;QxX7NSRmYM3G%`2ueqIPkNf+_c
z^?8dw;HPoEKaN&rs=9c<#8Rh)7Aa6cA|sets!IYDzw9BbFY`#LE*?BzBgr*?hK62M
zV>DC%d)=JTVj?LGBgmCHf`kc07Wry}leiA-LB2k-rxpQ6)65pH1loxoEh`YD4M_EI
zDMbsCretwOcv&TjpPJnjtz0RD_qCJOQ$vBVMd9QEsp2$x@fIOJ!+*}~ZR%++O0*!W
zN)y*9Uuoi<yckHM=KI|CoNzF7L@WQE8R5?G7z0XFQ@H{|kY76s{hLYQgVP5(1d5a%
zNy=>P5(mJAoh1&5>UCadWEOu(1MaFtqBL}-@uQWK(-xmSHFk^~Xj13REE*=FE!`h1
z1KfkE%rY@800%Jg#BgHe+C%EwBC!`yK~J$B=t^diJAf&ff&Edtt(g>nNpuID36ls9
zI>q%Nfp8aqyJ_b2rAOTc-)s2NnxwUD0xkc7D$oS_l41}H<>{K-*M>y)CKvLe1cyzv
z%@!#kHGJ!qpLcN!&`376k0qo=oH>i>XEe|O+3rn#MayjWhB&p=OgIhQAmN=jnxgEe
zmN)p^Y!J%-+PWkUZuKFOtZ>Kq0BDMrj7P%r$S46y{E%)E1c9~;3*`^RcobSnwADqa
zZZRS`b5>F$aaUlBHMmS@j7du3uGrQsp=zXUhF7Jb5cA?Va_bu-vlk(dYWmhCN7L&=
z(Zb&&Krw7m=n;BblkdTRmDc1}Sd>JB8C$1FYiKH5Z$MOQs&>C9$*Z|_%hAp1m3BBX
ze1K2VDe@87WSX}ux0zr;_|CxaZer3Iviw`Sw{FS0d+QdwE0Gu&9j>9V4uhs!2vBcL
z$tO%!ZAe%#MCCTwu!C~8GR1zP;zWamI^NpxqqcPkK6Yu2a91q~wreK09)g|@QW%xl
z1!sHL!7zaQ({(T;9&tlp;iqf`O{U;QN%$$>IuR-hwJ17~vZTNy#z9jC8Ix+8^3Dt;
zUYm-yE!##@aW@;SaK6|DP(jLhgMFlRHgfQKp28W|`psYiChoS*k0kG(txNKrao`63
zU6X+|C~?cXR1a8p8Z!_LLD9`kVvJ%uUI##K{G)lD00}|lZR?e|a&7CCz;bQtl)!R)
zBf&xySaWO-V9^c!Y{K5T<b_awPAkq|my*cQ=-B`t<nqd)MW-FwsV}%Rj6saMOY9^B
zpWY3FAa~c+3oO64Zi#z$SGQ>80yuH+WOjfnv?cPxLDEPxL+~;SVz!|j4&;cY+-q7Q
z8#s1+B2}7B+-!%G4JNV}ilsE>iPOT_R29?`Qt=29HUY}M4En7N(d|t}JsMBjaI^?Y
z$p@t;1|=8?+iR2gE)ut&#JU6@5is9qy)#D;Wm6qiOFlQ1YNeI84c+Ykb!H^MrxL=C
z3>HX2NYA*$+#86WrtxNbXtc>$l^A4Fd1DD%11?7!df~%ey(o`{+Y-dIrxVanb7qmI
zhMN?AIT$_ld_a-YMJetk)|U$V(qi5OuD}HM2pqxi0H`%}Wjo*|7=Q99V|<(1vZ%?^
zrcUdPa_eI&v7}9&)=6k{h&NC}%C-o{eVaP0HwvFh@D{YRE>=s-0dC>c9u`Ggcu_Kt
zs8}<ieQ~U@*kwB0D8;FS<Sm_zBw>pLW%2GhH@+mriZ3A|2)sIWQrq~jq(+s$Md;fk
zLuM}ek&YsbZ5AO)0FJ5lwJl1B)^%-*k{5p2lh{qDKSl9vfbsD%206kYs)841anFsZ
zLAZXr@#d~=O3F<~t~grO8&RH($7^BkXPakGV7ocCB~}HrqS!7tA5}-K+LD{WifuK;
z5I$9GlgO&7TTx`AO}Rf*8%`TRwd1sXo_$-c9ro<I5(FJt*r(67D@iEM#CCu7Z5gM;
zGk0E*RJ@AAMb-C09#oxA#}O;|)sdwte>&F$z^1cLl>&7(KF@ZzFGnDY4f2FlH9{W3
zRk4r<byYRwS&q_&Jl@Av9FccMR{_PM)IQCNMwJ*3-A4WF+ig{)8*!mkbw^x!TLnnm
zi-+n&*5%nxFLtg`Rc%Q_%XOpM*;t>FN{IQ*DwcKaSCLDo23sLast+udd6bG#6*Z}b
zsOqL6S*{9mQkhZl&h)(|r=CsgNNzow))8e%&P|J|8lq6Oj;+ur^)VD9U6fHJOgFvn
z%o3*1qJc49g-_wo?Si?aLRl46p>=LWS5q%VS=NJuu@`Txih3}_LHVunuYta^7J>GV
z)R4D=F2v{Qn@I%qN^O>&z16C<0dUYNXbXpP<ifnG=8IC@LLQV&36=kdN->Q}e{w-<
z4gIt;hF5Qi$j#APBC_49)-RtaSqqq+?XEm!K6Rp=u<x&--cm60y_5xs^~#DFDdv>#
zuHM@A$_jBtxF~)oYadsqn2<t0`3CHY>okODc9}a4;yLxr;L)RX@jV+-xY;^TdVDi=
zAb+QCwhq)DZ)N@JG2FRz3U0T#^$8(sSH0ajxJ?5XN|6fzV!iWwyEh9&j`o&0A+Gnx
zZ+o*R^!9A_gdFR$*%MIg`^{|8`?;GfVz7$gqxGZeiZ4pAw#&kbhsL5%Qy6IhkEFtf
zc9*u5IH#$mZ}yI4ePk~_d7=Z^QN`35KF~Ll$G`yl_N8EFryF%l>_8QFw}E=(o6RHZ
zk(bFMP3ToZJ`7~h=CuXv%9R?bKI^R5>>YW$_dd7JB=_K>KWNNb6!t=~@m^aWrNz5;
z{sms$Tc_{|c7>bK`nVEl)hl^bGI3!zGP|P^!_l3ENm+Z!ODJ%u`?>Xs@puUZ?q}bG
z0ynbT)-CwsZR-{T@)8SNr(S^>`3&q{mM~nE-nU-)7iGAPQ$yB}1D5OVE;Dq9jqld+
zkZTnV2<v#vfF3zy5iA0|3AmYjZk>`7Iwj`G5;xT;5_Y@GBswkf&&&T1^6J#-Cawp+
zs{=lKGwdrI67l7`dd2vwFesk7ee6D!tTLNiIOx{sV|S^99F20R#G)xAimsYI%BRx8
z0@+9TRB-yM?giaKedwNt=cp^@N%1*-(A+(H03*-^n3{bbQsCge>SZCpBfO81UNaop
zL%wqqB^qOMf#nRPssqfUv&P5~q$QR^+aF;<z2cehj_-pZI`I7Up^Kk!L%l2}s4COT
zW`anfK5!+#2MO2<Q1VNHVP&vUSIHJbj!hqrT&e-SQSQ|E$}ImYg7y29))yYuKIMOn
z4&^4p2{=uxyrM-_6xl+3%1MT^ZkCe_m6oRL;IKFl!6c;g!iVsTg9)OSbp^>xgkeca
ztWSk=O+0q{EMdu4gDU$NGN<}1alsKaOJ4GXnnDsZm@^jMOrtkHq)yPF1~8pI^(eSb
z;o5v=guq%#g5M-5nI%67EFuKaNlG$HHkb=fuP&HWLrJGT*~-CI01Xa-sfz*;RQ)RT
z0hqFc68dBamC%Ng65~@<DaK26;`@IJ;I>z|)fI|X1zTOvnJz3hkaU5rl!SHMTnuw0
z8gCaWZv;`r;FwCYqFrL%m$dr}?*4x1JjXxwOHTG{;-__mUl98(&Iy51{gPe>c&mOf
z9GqcM{VkR$=e372<(+fYQpEfDeyjGp*5NIbDL%#Gjf7$jxGx4>Es4Erp&+n#Efn5}
zxAroI&`}6!9j2&N({Ju)l;24RvuuX|+&cEN(oVmn;@`li@3-FWfG+E|tl}6~ub3&M
z(gp^bBG}?N*cnQNicVdjR5{FEwzC*!fWIleE+?%zQHBayiv%eFhFiZSBp7)B&nY}G
zN2jz{12i1*>plZAyx$7n%=?5Uy4$fJ6}pMU<^`h1;XB4w0i009D*y{IV!h0GoE#zi
zJ_UKcC>6n(yp!JysCtXS@yBKGu*&#qUr88f#x?pVb`z(6+5K*4wvVom8y33$R0JpX
zNd<NRAHJ745FF@&$43ZSqAOB}unnGy;>^w1%R+d=GV@3W$sGA3NMuDSlMfU2?Ku-K
zQqjF@DIbVo@T0Saz+o_i_9y=pvd*}#2dD8PB@=l53-}UjdysJ0Rqntrr~b&hia9L`
zL;*2uy)1()Qm{x2jn1nz;7378ZhHkvJ$bn-%B{bNWm`C=9Aq9Bekv&vhC)YdR0DYF
z!dGQ`BmgVY`py=Rtqh6(ha&c8Zg5xqkcLq&3UdiidTAldp8BJl;>}!wR6zrm7VVrL
z^QTYN<W!hb1c1fgJQ|;4I!ea_GOWwa#^NG=Dh#@vBXD++6OsrcRnK-2*4zlro0Q;#
zio75w><EZo&M}S3i-I|(qUwl@TJ0FWDNXoH-NQ4Y=>RDvplGQG6nm1wq={RA#hIuP
z<ELbx9Ly1@$Cb>H6Hxl@nL3pd!{dA~dZBNCg>JnD2LUS(41|w)!C9c}jSJ^!QLd3#
z&u6A@m<1X%^I!~oqHQRG$3_#X^rwQyyigkqDNkOg3@GK}1-f88;jHnYo}6OpD^Nq+
zWIJjA{BTnO8)oJOSpbL)S3p$*=9F9Z7;!v%!3-EB>edVgKCKK@Ov4K>fJhNu@BlzL
zbAbT>&%rD6KfxKi68&NG^i1qOK#H$d9zR0CyfN7a_y?{Stp>0IZvsqjmQ9W~btqRV
zJ>UXe0b30~0WRoC#DE=HwKsnUMowqUR!~9|E2$lc^xh=(4YB)9(9VX0cdra}gm`&V
z790M}D<QpkK-)9V842b@yH83^Q^}ry%Xiv8S@g`2M1CY`WKnB;7|YEB@is9KiG0Ia
zx1lLsshWBt%m`Aey-iK=!dR5;jl5}B#y3E^ys5xbgQe3OA481j^2Xb(3UdR?BlDYA
zGuPy3$Y^#MTC2~!{ciM9^0qqRCdicMBMTKICy?Omvd6Y=QSE^F(}p$D#Q^l>MPZH}
zOr<V^ErY{cu*M7y^DR*u7gvrle<*KxXN|u_h)H$<TqJU~Z>iciR{E)&a2zW#{5IqY
zd)JN9N3`&j)G8N&U%}hSyXiY=Kk=?BCXJ^qLouVpSdJnofl}m(mTM^59aSvAahxJb
z*Txajo4$l2q|1=FNbB1j{~fz=OV-8}q-u_=gy~%=c!48-1cev^ke99<ix@H&g!!T*
zD+S-=7Ohm98*uTx>(+9dFqOd#q(-k4ZfBkNf=@!0tp`T?YGoHeBV}Du?@C)m{_LU<
zC84KY;<AJ@q|Cd{0)&)#*I58Fsz)`>sJ$9Jrf#yZp}L|4QNcARg$$7kwgE$+4?l~b
z(naETp|WJYH!P@8<Q+4<u*^C)U_y1`LMDmb$n86Kj8K65Q7?Y^!7^VuRMUs*l_fqX
z9Mm%hWkcu9plsm0q5sfj>u-bNL1h#!J+D-A_~$%=AXh6p$QT$wY0-r@_2|(ktQ7XZ
zzv|D4mEu{M1|x9&Jx7ps7WXq+LxpZWGZ1b4HGK?6gQ?XOZ`sC-R{r|b-}CEJe~$rN
zS#1Y`KXQ3JGuu(*#ucjB23on8<K|y$75I8lEN2@}w20LLebft6=g~(9_;Y3pQZ-L>
zX=vr2OOb{xK1vkjC}z{R_>-;1MG&E`ZkQY@iZ2Qvnf&cnT^$f5*`})p0hva$3XF+e
z1jZEd;L>j<UmVWZ#x}WZ((_>;cGn?0Gm6DoAvxm9;<Wd!0blAx_^4aGI9}+3s(-?e
zviKp6@zEcFdC0nQ*GY_IEtjXL!JK(SMXOwfEB!I<I-p@P^@0+Bfz(|`HtLne4`GnY
z92$QDTr^zgF1R0*Ty<5CX<_nokMxXo;fbJnGYtuMF0WNX{wNB2B_UJ|m8>~hR>O4{
zj0bW99j>m`W*^RGvJ2;ev_xmMoJENXNA9t9abN14ba8JA-R`=hlo|CIlxg-tNq~LR
zRl28L*%G!LJ3xR~?AlfSXMyIW1WkY#;vg=Vg)~dLY6vyhM%@e8?&hjfcfGmjx{y$4
zJ}CHft~rf<N4vS|0yMh0>O#A_bJcZ^-CcdagBy<mR+mdsuDt9cH<w=T#~UjzSfm?4
z{;pE(i<IlAHzrJf?$oZ^%@bKy<eguQA0oCPce3!5Zti4(tK8hl`R}-A{TApE@<LgR
zFDc1&y=ak6@2p7Qkb}>PegQTLW0S(m8!U|OdIvwy%87V^S}m*;xK<BEI*Sw#pBN69
z^YBF0o8jRhOpo2MNE73M?4a(byYBU8kU65@p@#8JJXck|3#7M6O|grVOY9nGk8EKR
z(gx@Z(~e-m=Y86@xW{SV;@;elV!=RQraod{qCcbfY;mTar?>|^C;dV2sh?KN6h*uY
zK6P3K-zaIn5L!u3ER3Ci$CO%Q`|sok8GR7?w@8bU3}ARO@Pgk7$q>~JI4AG;B3;>f
z^3&W!Md2=b2usX8^59L;Pwo-=mI%)LPI=Vp1BlL;WQz-@qk6*j?Z%UHr(9znelvYL
zDMxQS7R3mF1in+qJ@6BTk)7$SbIczFh+QoT4%V}c_g2XbApP6;Rd4`qw+R<*A#W7O
z4NQm~$!(hyBfG5x9m#DQ;npt9Q{u>&ui8-z`PwPZFZ+-oU$s|zgKc>u^;7#0%t9fj
zonqRFc|i8g$4Gr2@BQujfH31>(ow}~Z*Rv>;>vf;oL}mgcwSt+_d36mpWQX_d_?r_
znm8n}yAB{yu>Vxsq7N|wV%OodcV!~=&g<?*i&q_?{IBg!iwXm{oADm$eY^ND{JQvn
zde3`LRiE;Gr#tq@nh0mxF5*s;1j;2wBo{7btfKQORIMlvr*CNm-A^eKV6K}KkUR<8
zq)LF3c!3<Hq;#4a{6g!2a>U{hycnxq1}{dXhqBa#E1|5r>yI#NANretHZ{VYv4h>G
z6g<vyO2xyRE-7>n2HFdJ>U^QWz_TC*w`kSB$Q@eMFJMQa65Jh+ZWk0-R5Zyprt?UP
z$M!^o)}mk;5upVY{QyaNd@fr;in^<81;T&pHPDBt6JP^+W~{}NA`8OcMT8j+uA?eW
z46Y+9PK?egOZ6m%f7H{b4_6P)hl|Q5R3G^gB5J;j1gh9KxXLOHIJn4+|LUXOoG>2u
zQIAfn(Wpl!#((|tdR&y)d!4zGebk$iQ>Zs5r*N|u7la#DkxC4|a#y*648QV#yX%uL
zQo5x3<cm}l11E|x#0x!nGx;J_`L1c|HqcJNq@OOzIiU}kKJ#rtLu;Q+oiNzRqx%16
z?QM20%aQG{`F@HV-aF_re}atQ)PN<x9vG6^Bf}F3x(1Bufn*4_-`<B2Yprv#)b(Xm
z_C*2RA0rPpe>OKG7+kS}rTcr{jU?PEz2o+g!K%Y8f~ieT=C><lf)L~FYMCI=fIp@>
zMw?YBp*Fu>rG(o2dK*gR=~Ggu4UQqXt&n`|!>z>xWhRVlCNN8nq7py>%a!ggyk}sy
zn5y~L!bPDPx<}8#l>H&k!jvUJ&jNjW%-!~O|4lj;;31rFE5L{NK*UOezhNEr26s&v
zSv{S11X5x?>070Oa$XWBS(Dq_Pl__Uq*!4Hh_mT5Ljkd}DWy@#*2`g=Fsn8`9J+*A
zT?x9e;c}NYaD2{k9ZwJ{+0^D=nd8#|jrRkf^A%z50DF_o?@|`R(~VCLU@e>PjD-is
z+;{#|Af@b`J~djF>ScfzEB){_g1`x9mXRIu;^#kh`StO!$8T=~h`@T^7+ic+UB<nW
zs|Ifal(8^)BakUj1GfR%Cu72`Kk4xx+{%Q&C)_HpNzk;Z8V1bE0MJ|hn&2tk;9#z!
zE(Em60fA)V+a<h;cRVwA*wr=A1asB<s%V0_>V2OygNs8s2#e(ILBjK21*o!jmQ=ur
z?42bwxHgnyFRBC=`vh>vCjJrc?42DICtqbpE#Oq$%b{2fHPI|zQQ%q*<D(Ztbj^vA
zsyjl|0a{@ky+!a}y)PRlq9$=835l<dOUr~r;nI?p!{PO`PD_A9y>Cb7vAR4(JFxDC
zEd7K0z$OCiD>}HA<(SHBe<w*r7^S^)q@D$P^qnU4Y}}yA(oJSa8!}?)3K_Zk9ITb0
zRN@nHmG;huT5*+EP%jBfWhn6)kW;2Gp=TBtD(}j%+JU$-5wJ``sD=`79U>ZNG(8h(
zbxh>*lMa=4hEc+-2B9)Wn3b6CpDS7gJ;;g4B+&pPRHrkMbUhfQ>YZ|fmy6{o)I+O>
z6e^-#tRYy_m>iUFF;fJXfmaLQisxIUy{^7?^&Wahc`6OjnWjt%Mif=K9v-CV&eq=v
z!ntJL3Buvj?%(AH&$8yJPWDP>VaOY0Vi_X(%=$s8U`e5ga-1g>r)R`Oz4L>I5I7y9
zCM2r<op31UIq8bN2mUY<`x_i&y%l<>9@%Sq$&4yiELw$6LPtTP^+qHiL3|;WYWN7{
zG%-LS5B-zaCsu<iM+tR^{xW6dVaj_`W*;j$<foun=&==a3;na|Kh1vwx0NY7lp&VW
z-g%o01kR>dQ3J`dF^Ly(T$X9b40(34&uDl9F{PE>Yn=>@5BrE<afU=SCN?nZTqm9T
zuyrn$g5VjVJxx4gTo7*@A3<7tTff%A^7R1-yh||wgP2%s8eIz?3;eDab`Iz(Yp{(C
zd|1}%3fSo9Q_wJxR#$?)A&YJ<UVP7kkWMZBQJ_w({Q-0)OV!!NjopNtYV>IkR&^!y
z28o<XT03rQ_v6JI9E59by0p1rTH6{Ajw+2eP272Nqga$|AXI?|CyL72(ukH|teEhE
zS2eBm%BsO_>uxk-XORPh!>RG`O9gcIM|@?-h;bzx0Ei#nm|LUQv1u_wW4^(=1_G_S
zqjQu|29aX&UrJv(;8$2ER5ZWJsF{c7D58W?VU@drhSC%#Bu!K5>5?p|@?X<l2XGpy
zlt%tFG~T}{G&C_d_i$0a;q5ffEc0;C505$t5U-hm2QCdJNfNX#=s8bnS5hl)g2!5*
zb{-vxdN;V_ZW*HlM(7Qk2ND9<`UjHr0lx>*;f>J0f&|kG#!o=Q8|we?O#O}r;5qzC
zu*l)adj}Tqv_He82LT^YbONCQF9AvnWvEH8N&CD?H9S#S(~B}guiEB2(!wZVpanZ`
z2xd^;RfD^5hN<_aI1s!vc&=s`JHHqQf>OpNh72aS-DXH<z<D=A_7PlwGloV0bQ2F+
zzsmbKLz)5?%rj&JAr5qgmK_OPW^^qXEa_-kGOm~&&X+5whmC>yV@A{421kb<wU*&S
zj%}X28Gbldh<9@#-Fc5QJ=8QJa9z7Pi75QN&MHO%jL1((atXWZO=aA!D5Q<N6z-ZW
z#2k@|+KN)5LbUL*z&G{|+OndDa4j~_IyhahMoxxG>1KdfO_wP`Y6aIGT}*E27C|G3
zg9Rw#j*!F%u3dXEB#y=hDGr<`VJptN=|jq4A(q2sT$92;wB<$`0WlyMi37Z8KPVCa
zZ}?}%^l^-ch!gjcF}8ne+gbQnHeFW6!2KN>BjWaVaEv?saab&iaiva&mBDR0x85^?
z>G%7kZp2-_U#ctak}C?huPa*kN%f5$aRU}?ia^U2Lr3jBO^6DuMYt3>ic)n|y9Kz*
zu7qzVz_B3)Fk1{8l_FjUHQGZ%MA)c|$OXce{XQQp#*IoPA&`AjBY^^KZfzCtDNhog
zJt?Y*BFTp_a(y?HD(YK{1FW-iNhNK@=_&JqF;IQMeQ69-U%XW`2C6S!!5M;spLfW!
zDa5=yi>45B9cC~|@8D_!S`Go&4@A`#u6(Y5vEG~;Xf6eNUkQV~0TnU4#<}VtrOgyj
zZVD(jO$}qpc}}-I8P_eH0=njRyt{$<?Hv<u0P9WU4Y72dPx4ciprX2EyuqJ7MOJ8g
zeT45Dyz9I^DoMqZiU#0{YDkSUhi}?sv+Pwg1`JKTf}&73yic%=ph4Za8-vPqgKU5a
zPF?L9KKiMDued$kj9yVTO~1|+RMXl&_>-;P@h2O;Xv1bR?Y$TrJPXnbpe3KWV>8?`
z+*?WN!|j+G)0mv(67O0?b&-3>4qbg_33h`Zk5)V9%qt;doVsp%3|s9KsM9vdH3orm
zhO3Mzi0YLTyGB<v>_MjEB?#naVbmXp$oIkJjo@H0rW(W9=X<|6q95T2V1q_V39#%&
zxbv#R0LJ7^cuA6#CEmY>war_JD_M2rt}4|LUN9H~;CX{!;Ooy@ee?{8R;Ln>8A8@4
zvz8gs08BacucT;M7Twy$$oXmSTKT5rn7@+hj(s#m4x5U;NXdQU@~N96a(Qa6z_rhu
zgG~)m?7Zt>vc^ZHm6#1xsmbaeb*gt-5V$&;85{CYlD*S<K!S!TC$urDpIHX2?43#f
z@{^LBzHvS(<?P9MY_OZ=h>xa<{|RfN9&|r8xq{8#j7nJNZdqbGWK`O!Ax@?Jt^!V_
z%~C#6YQl?8X?^^@xSv*a3f9%Ij|$mM?Fl3x7z_+CP!UX}Bz-LfSYXO*dL=crG8hZJ
zJKv62<bIiQy*kq3Boqr1xw8NLqfYg|zv~orRr{y{o-lb)U{YTZ)C*F|OeN|yq;j5e
zs~QaRE8&3<`AVkZ3$LUo(CVJka1%I13vaOaCnFu76cq!Sd_`nu=<f{y4uiMn6Dd|E
zGhNq%a$tRbRI7n$M}Yq5?;Qaase(tJ6rEz3<686Lw==CAP@ZIRcf;M~R5JQ2xfXYy
z9~H=L#}(k>w&UvrM+%d@Tit-pcetz}n@zT)N`bafDUyhf?;oTpN?>3PSnd_^{li-B
zGDsXp&ffLnpwSetYz{Ek>`gB&&!q~4&hl+t9!j!WG+Cr%z9^6615vU*zPA*zKFTFR
zGK|J&6u+a+D}MXcbSA|W@Wp9z_DT6DW5eH!kC@0(tIupYgMxCS$!+fBfYf2d$pLAa
zOHx4EFW8L90I6eWp5$knnp#pq%J6hjLPD85CCUy<n~)LmtxoEk(d4**3xQx;NQysG
z76v&&)R&sv_MTix@SA8v1wT~;pQ-FjI5V!KCKpMZh&TRT0`g1)KMH}%B}x8LojSl(
zQt;>R%b44M{Xq;hL??u^{$A46<0bI+XPK)MtSH2Qmt^N4wN1PwELri?zNbZ0wwjln
zLmnUVLJ1aKg*haTt{V2D+U1cG$-WXE|C{oATJ97k%3iZV33t>eJ(Adb^*AMOFDKkv
zBV-dug3t9nsECU3@u7qfm)UZo5jf(vgaa(g?inI*p=g9`vZ%4$I169j33x>M58wXX
z)4$#S{_Fqwtpi-Pxcf1EbGc&w>wo_CFV9_V?bWH@{{O4`|M=JERet^VmnhDk^=)1E
z@pwJ2fBWm-p8w%r{?h)^UTyvLU!MQ{pZ@yK-Ta^a>wo*t|NMXa^?!c;r@uaTMpwjm
zJ#+W7+kN=!z_Yi1`}hC$+kbi0yAQAb{ZD^;I*wy2xn=&Q1X~MSGk0izu(!!*{#9@P
z>3{u?|Mx%t_5Z3~1|BtitXKQ5FS~izReXQ1o0Yagy&Uko{6sH7f%io(|F{3;->8>%
zr_$~e&NKRc{o(C3tNrhGl2#3S$#dOjFaP^Wqt=BgftvE`N<gEmWHb8PH<fYG@F(Wu
z-m|o?*Vw=L=e7Rnzy12_w>vXhW{1nH@B8Lne=O_W_uriwgWBRKZG0}fuRHvApI2`D
z1^4djfo11Y@H_LyYB)^YepEMfy81Kg{bf;G+jm*so2b9PnEvwGD7BjY{P^;6`8_)1
zR{CmehKn~<GTp>|S*<cmzH0@v|Cg1(8u+fYxsQHX4SSBJ{~d?%XQuyUP58W^#q_rO
z?@a&CPrl)-{2rYS&tHxXl+o{M%Bl5LwFLcqE@cXSPz~f~?`mRc`?A_Le1~ul+n?U;
zwfe88{&%+0zqEg3^-tVuy~m~)!!O5H)D`bqq_X(35`ZJ`T0)Y1RqYyfSjtGjboR$m
z{@rS@Wc30l_;af4CGUO{ZeH7@{rxZCTl@JJFu<z$9-U}5zZ{+I@0T(KKd1(W(7T!t
zh+kH_N6?Q-ef)5bym>USuxk1#__JTYOaD$^#c=j})Blfr0myW#!720Ym!qpIqK{g;
z|AD34%ZvR{&Fl{><qq%LyPBYyUsgj}#`h~wp2na00{V4s{QXVn+drTKkhxWZQzqB1
z#s;^ID!KoGWqgw~zN_r^V?{rIqvz)z*c&T4@xATr_j3BvtN!|Pe`nGELq^Z}e)XO|
zuy#M}KnnU-8x^h@-_<1Gee0i?k$c;2>!mNgt(O|L-!nvhYD&`a_3kE$UykjR!}ncD
zf-kFexb5Ec-jc5?!fF3eQIfAK;<D|dq9i}@8v3O{+OOT<eElAN;w^OC41e@glCOsd
zU)o1SNxrU_==6_jD1TXLz%Bf)_Lh8I5itZG6(#wJH!%|U{lhQf=QJa834ZidlCKB3
zzds`W?b}=Ob;WXnebl4i>uTUu{ir9&mlZ23&AS@QKk+6qB~Q$C?5j8NQzl|w6n?kZ
z-jc6}hY0MCijsU?5ya~s6(#w)V)Wm<`M2cjiYLB*^Ah~bySP5mGFHBP7eA*u`})md
zdrQ6?q9G*z)00BU*A>AP@u_+#`MM%dTOSoA`MP4v&q`VPiT9BAFF*b!e#&SB4Em#&
zl6*O|RYb4vdJ=qH4P1jC^(6VaBC=+ERFvfFiU7fURFvdrOs9(}+dup!e$IBf&e87|
z+FSC2rTx7f`n`?$>$l%N_;)wDd=<UFw~zFxN$}^)o7YU0yQ^pRso!z9*w1X`?C7kU
zth<%x-H;?d8etLHe$*qg?bp@n`u3w5?{mMb*3SOEH3)uGjUG<Ch4$&;{PQoN#rnPD
z&tK+0@DdtOS0BUM=WBh6ir_@}sJKWo@pVPS_<vMX)c@BN0nYiTD7eno6%qUOeisS`
z`^lGafgr#0GR8mhGFrzWTO(}!t7A4Q9wZ@9JqmtM4M?GPHKi!|vfA!&RI}RdUpcB-
z4b(Aw3rAEkKlKvMr7QitOOT&`2M6G|_uzz<`*Lujad4<M+Q;aAw;EzP-_@Fb<;_C1
zI0a5qH41)EO>W?N1MxFn;LD6&W@Y><dx6<Y<Ry9!PKk=X9Nd~8Ro48`&y!#FT>*5n
zUsf6Wqe6o7zWg~H#hB|4Kk=WR=^Nnsujp+=5B>0B41=QJ>w$R`Li=4U$QATuHSfP^
z&HEo|4fy?cH39m+tOgb#&OggP`3C$lZvD<1_y=};pS(`v;O3XtX{?55-FG!5YyGks
zqSxQmlx+B`Y8woesz$*NssUWcH^A~wzJYzQO~13-`~wEi-t#wu+h1P9u^KW1zpJhG
zF}mNa_FI#8{~?Qa1A_amCQR;^)xf-{H_*;UV}Je)TsY?Md;|Z`IpD)HL&=v1CZOCt
zD!wH@aVosP-8!K6{;%w{>Z7n<A6@+r{lJ&|-PEA?Gmh#T$g^>4^`$51XEw3{1oTH&
zKSV$Dkp5-?e29L=5qx8-{?JH&YPlj2(C2!6i@tX3AuI7`)wk$poO_pavHy{g?w|21
zwT3&=w`1uo`hhQFf9G@f+qbvmXPjr3!|V@@Gk(f{R#?=}-o8aYaD~Nh7sH3>r*8G^
zmo<O93;m3_M+eepXWyb9c+Y>UNq)0w|N8B}d-@+4caHflcl7rjzQ!6cezAJlza94f
zcSrqk4ZnXmF`~~`?F-+RQu?R=SJU$qEcM=Y|3AO0R|3HCR4aEegu_n+40AXkZonD`
zLfE5zi_l`=cEjmU0i9YX?IuXv!-*b8BFS)4_(adpr%=2*ZW6*PG$jfm7S51@N-G&o
zsCf*GDTw%vfk6?+924DQge$lQ!Wp+xP~>phDuIa7aB@>c1(aUFs$$QHVoXyMmOLD;
zvjma`IQO0`@0=?JM1r_2ocwpOvVi6mrnZ8uku>ub5mtv2NjRAAKrJ6m;=5QiBw|jG
zV>09cA!9^1$sCYFGMw=ZAb7ii@<J6DJQQ*dzPBr2za0I5!?O6_!WmnK{F0%NeDJ}A
zlTajr{bEce@af@1)<@*zGJGNebBmCysKphoP~HfPEE_l&6;V8KYE+E1s3eprKm*_o
zNlDJkX?P(_)|^1$a3a`GLzftG1Ni<GAb|HY^oi6#r=wr33b#+2XpK{S2{8&BWPcB3
z5=QFE5XAu4>8=31t^%5?O*}F$@d49Rh<gC6b+Lhv0=>&Eqq#cvZyr`p0o{Wkw<*an
zMEza;=Q$1zo!E#red&eR3<LrxO>Cv-15hZ$VsH%oV>rTjdspzl>K_A#4zhoTcn^>R
z;0n-e0ZU^upaD>i*d(&d#Gz5q*iV)7J#PfAA(3coMme9Ih5WZ&9YXx-sgB1s@@XAM
ze+oRBp)#=<=6)Pak)7u_+T!PWz=jr^&?Qje1yXmPs29R$H}K+xP>6`>xdLpabwL}O
zpDP%KVwbn)983_SrO)}LevSv88eD8;k8Mywn{iB6QmrC9vgfFj>AFG9?8b?@qKO}&
zLbj@8>ToJw37?3$YU&0OZ^lxJ-3DE=j+!oIv#1U`Lbk4?KJ+U|K8jd}ZPiW|qHgGI
zzDl8HDt<TK8RbDU6~%4wK$NRvDSd2%23mnq_Dq@V;pw=N+8}!6On6en&KkUju9<=w
zT1<`H>Zu*$g&ta-DX78x7fX568}!iHY8IMkDf@aWRkXw)-Vv#nB1}PjaxV!=xvZA*
zKqq@(=mMrQlfxCUnbO{|=&b9_v&1GGV_6!VV>p#kxj}b{ed0>8=M4SqAXB>%wgLSG
z8t$h=H5OAt&|u3@x(}Ti8}!#=hV>#Sd{V-Op}|CP(ZO37YifX{$CmOdBYN{GZ}BbW
zcea$08MKD623tNDpVAK_Ic~gpF|KH(pf;vkuKqIsx+C~B7NX&MWyZY#vOrD0W%RYk
z4xbd&R&hnuJ!Py$y4(<*Mn~jpET*~cRRAkV2T5QoYz)Pqm}P7>9eQmkr+Xjheq-4C
z73FN(VKZgFTmg0hz}Z9DEPA&pVSrZi6=LJ)pj!-NYq;gRx|9o{gRn7_{h%Y-IZWh~
z9nlXV?0!d(bRbbd2U}!_!=r<RF_>cDNm2EmHt_3I_9`h~I^wkhc>r!XKMs-p_g-w#
zLDK);Q(+;kRR;lMDDhQ?+a#DRt0O5&m^jBeBG5xv=_{#OGfi!vYo-|pbj}z(-;200
z#DRYWHMz#t59Zc115j=T)_^BPx%|a&e<dr+*dxGj8ceg+!R{Dhq3@Ym_s-Nrsa^)n
z*$x_j5Py6h9eo>oXh+xHpCOXvh7FW%x0JRWiE~2~B^{|^LiF%`PzPF9!_a}IFSUpc
zt^m6VXlTRu&$ZZ;A@GW7fK5$9C0bL{GfUXZ1`cFNFW(0kM(>>!M^iRVhy$gA*&!vE
z<x+`aj=zH1{^n8N>#P&=pj3Bbp?07SNu1L2i7<JeTdd_dLtTeToS|l+5@)DYsKm)q
zem5e7zmk0aWM1h=jB^DX9Q5OKHC!L!6Uw)FMGMu~^2P{hHg{z84KccR@K`<}O7|<e
zACLIkJ8}!hT<SCQ9!Xp}IHqHYzOy6M?-lVUD@$w!if=NY>q_c9FSQJAyqKn@q4~%J
za|JafZ3xId9MgW`FE*-7uF_LuBn@Z>!%9pV*d3tVP{P@cOg>ivqV7I%Y!lsjuf)9}
zzV(hfuMppQN8a85-})`**Arq_?_gCA1<7^%Tg<MO1}3<xsgYCMWh$f1D_SVm49omR
z$AkHXJBV;%67}%(;+v1z)H1J?p=iNuA0n>l69=>*Yr0%(Pm1sr&)U>OZ0T2WP>l~N
zm&TQ#f2lvBmcau_PVkVCjf?@I#L*oobwiMvj+DAFl#H#<okg}>ILa$Q%Vn=#0pAJK
z<X{DiP<DAyBZU}rIua~j2_9N%I+TICBRTF%Qk}Y8kTs2MC6xHPW9td=q<3sjA)fSJ
zd)R|({a*W9D8YC~e%nwI@(w1cD`Cq}k7F^rRG(0fLsoX;3}VQ}M*fe$SP$N}sbSDj
z#E{jEv?C$9_A8mFhE2<$GKciCA%WHv)wW=%5_OZ<!Ot2ZV(-ZQ8cD?7k@q<&Ia-bn
zbgfr}XO=b;A5e$R4yCN`(CY!Z<*PP8FLp)vx{=*AMA+Vu$~8nI)REcdN{YOygT*XF
zEp#O-%WQmNjQYG`0fq27omSEn)u2}X&5l6F^`nkJ$90;+AaT6{?la(Zi+=dbLWLal
zqdcF{kLIAfqtTUeu9qztT}CxBONBV!JCaugxQjY6UfnWVdVMw_y7!LEo>#&VLI-x)
z*|5PwjPBj&h7`F`PrE%tZPdZ%dL`J_k+v=nSKh7ul`041uF+{R1K}NFLb{Tg*`=;Q
zb#+m3_Bxha3ERc7twYh`C=;Sj>NxIP$>2}2ThZw;?s;emF(2J>uB9%^d*NIs#-(0q
zv7$4<`W4gwWK|<kR`jU{_v*jCU7Q@RB%LW&1ohYHYtCDz9KzI~p#I3I)RW3Fx(x4y
zoX(N-^Bvre(T5s_?(0JXg7Om))0K?EH^Il9c;W0Wt@8zEra0<5vU<NHDAl@<dA{t)
zB3s3MLYHlhwBONXnkT_*h`+vrWH!3;qFhl8uzpZ_vdidRP?I8p>hPXi37@*)>lUSb
zhZp80$<j+jHW}s%DzZtX!>5xHsOJSG*^b)9X;O^$y+~=VfUV*-qE!ViWgkrny<ApT
zP@B@a-KeTik)pouNJAdYxs?`;YKVKPgGKgAumylcHUwF`l6*~V>%q7Ui?-Q~RDj~E
z>Y#bO5)Qs*FPiM_-LeG2whq47Xtb?&!*tQDd?nd^eDFI}U86y~VgFqTwg}L^UP=9=
z6j`Ht`3iDzG?~9(bd5IUeAwmmZ&QyQn6-(=LW{Mju|bP9<!S41K!>>WdpfA2$%NiG
z-8I<9yLOXX=3{Hexe~mt4Mo>vFoTXYM48o*ZT(8>%T3>WR6>>qg8ZtQOkHpwN0Uc-
zLzRhYt8b{XCi=cB$_bW1yrIe(ozj4PUI9D20aHA3K<rX)SH#vmOZeQtnd)Th>R?R0
z0zTFA!1)G0cHF{T2|lJ>7Ofvy$HkNCht$&@T&a&A8OR_@^+N+0T&aF!Amc*GQQ`iZ
zGrLB|Wz-e1)!GoQgv}ldP(EwicwI@QC%uvjffSk871RJPg?{%^hkoR?_ELvef`&<d
zdPQhC`A=^d?RvfLlr;XL1}8fkETw*y7J_$lSAJ>l)m<6QASJyLK4+lI3ng?;iZ|&-
z{m4Z2fzHW92D_*$#=hgy)sIPI;9}O3`K;Hitsg1oy4X!g?JPbq7<s0XBJ@cK8#eS^
zc6M=qrUV~6?xkHRBD%u~=;BN3b-8^7thLY`*~q@I0_kb?g;&ybNb#LTYylw1^drYJ
zF7dB~?d+Ufxt$%i4bDsy9Z&&3vZ}#h>7b1202kacTlN}G(?$;_Ne>#<;EnW<pV<SL
zWSPXpS>d6S-5u}>54oB_o9F=}xd;(mxhguy4n1Th7nk9aB2L3W_hcs*3t>vI8%4_!
z+66h_m6SOMo<9%yqN9}Cm7ry??|I15u7F?%AmN&WNY`*hIiRTbdCT}Zk>lZFwb9uq
zC^tI_&#5a5Mz2JEDZwWn1D%uMjD!<cQd?YwIr%$JMn{?o4_VGp>)e$&<4UUk`ha6%
z1aF`9O$wL-wq0u0nOx%vYK$_jqZFkFjq9i5AFl{san*Mv;poWUaV2cZYE-nO1GnW@
z!lo7mHBq|1mz9iJ^^gx6Q}2n`c_69I%1n-pz7CYKpR$ticCUmz-(01#lmkjrL`_#x
zt5mjfc$V0zW0hjs9m}ApUC+VEe~kt1VkqqR06av(*aOPYrJIq*&|N<2s1kbx_2)8r
z1N`nU5sJASg`c{TiZ!6sTU&>Fyqf??igJMW1O4anQCB*|D?r1i%oKNh{HLMwWimf0
z$!T?YrBBZi_I;36x^j$MNzSa0SN(uQ-IY?LW50J{sjg&YnO%WyQ<9M@DQ1`j=InlE
zme{e0uE0J%6CIK78S3gv*tJ;)7I!(HOYOPK^?b-cLreQW*9lg2B{dw-$ac_-UIE*-
zU+SrBnLIZ#y^*HT3B`JnQmK~LRJB#TlTt-;Cl|Qt(p*&c=!;G!jOw49(Fgj^VQeQi
zhPzDdvoZZr%m+EeT{%)Zc)H#(FC8f#-Q}DvgY62~vcsfwc&B0Zxu91ars0(g{-jo6
zSJSs|jjXmEJa6u@&aVxdWqiEI8F?jaCGZ9sP0F&Teaq}V(3nDCT}gI!%Xtm6{7U#>
z(Dq(YK6$j3h3flgP?(#x`2bt53yF0lxm35{Ay<^!fD*%8$z2Saw)qw0Vqm72(aOAW
znEJ0Zbw#-rcHjp!LRZTpOQ=84Ra)5tX(*qU2*vEeR-d34_g1H%7zMc+I2QWev`Gif
zjxP~P_n}LDf>PY{R1femUkMuq6Sr^L+yf-ezL#1yOzT3aX4KSBsl>!<Rlic@WvZI{
zclCmw?3Gk6U@DIysJ>-3h@=R<r)F?t3Go}gl3GGT58jx?!3UQ=;_*!{^nlaCmGEXD
zb*As3=2NK&nl&nU=1bBwKpX;h*K_L-xVs)3SR=Hj2Rt?oAH`FmTEb-t5BPm<`CVzF
z5_@wnee^>=11S`J(GfksSndn<@~FI<E`ZiRYDQn>h91nt>5Go&E2=O%I-&>iJ^G>}
zdi0)Qcx)DmZ3P`6SCm6qfp)rr`PfVy@>Zx79P(CZgdL~6MFV?)BkD?O-x=k1ObN$W
zMwcUl&nV~RlL9tAFd}}ueP#i>4l;!L+G-aHa_#pJp&{2+!#Mn{jfP7-E`8n|>XAu-
zMmMPYwbeHCqw)j|(Dh#l$D9gMd4p~_m&?+rdcaNXYq6<?F)g*UFaXnY7Y1PTGmlC+
za3$C~I+Um~4vh{ax{OUhVJ;cnBR&2uOxM7jfG^tI1NR2Lrdoo^TvIK<%js*fsZyEB
zV>FO~))UfoOSKe+8iu}HL&~B<W3Hi=10x!0Iq+5n8xD-IcKw_x94c2=tx}SLbzMRA
zj<)syhqEvKd#S@k+j@*vr5YYG2>YUo`buhL(nWnG^<JA)1}?W=B9wBfjc)3J?5R#b
z*FeT&SBj;P$vK{su;n^+xJo&T0(=cz0$vFQI}nPiScEa40?kzmD$tx=fx0tS!?i>l
z_f$`bsxP#p2W~!Hd6~wrS81yqC_LM2$8fe#;--Q7)GJ}rj4q}zekD1kt%l2De%uzH
zyfA{L2dAn86l@Hf@)V*xa8-RJ&^=?LD>S69gn`a{3gVpEGbl!*A^i*_qPZeY3N)ih
zQ6qItN*aH&vdoqp?jD<H8mB#Fk-CyvP*c+a<tf<LDA<4(H{=6Jy~Tm&!a1sBQv+0g
zPT<!S+-G$4^{{VU-G%D3{tK&A-}IeM=uLwWeFdW)3n#_^aKnv$?<=WQNWb@$RQG9F
zUr7x>e(y1>3R{Niw8oZkBs4m`uO#36JZib)BsPzlhIdB*urZ+pr!40=5MnONdCn}U
zYfyX2f^{X?n@J;iLg~#=_n`D9E2Ot``n!!<h11nDoCzm=*aILVS1zqVAkr0~W%y(S
z-nx<+kE4`RJ-1q3S)wMJ3uBQwo=|{O);17bK4m;l90v=wRS!yCHrGd`)Maz2XV7JH
zp_J=w%5<L8V}xjp8m3SBs|SE=KIyL>0K54#HJn@I6>y&iX6_}*64aOwTUSz}p%IRl
zMW0g*$1nK;r`pBYZ^|milJY659Lvt9tm#QjCdAgTmL*g%Tro`gs;{K_0$=sWM8wY3
zUV@rw+1vQ|TyU*{5A;gdE_B)KQakmb`)q0(XFGCt51>G=022eGr~}e9taF4i+ihft
z?ZR2gL}XWxZ*a&Qw^E3A6MIlTsKQ6qm4h;sT|xF#SgtF{t^yqRlqmZ;LM=fZ4jANS
z`8QjEG90qTjoMIHt}CkX$Qnn!V;{1{t+e5gF%F&f_<%Kz1jw!oX;+dffrzgw$b~Ru
zkf)~fv85@H6#0tS^3GB{0CyO|fRPdWN(O(D8`W6v2h_KtJZmKSbV0lZ%!@1GgON%0
zityyrmP2MXfapF<(*|`pWOxJ7?gjFy5kg-MS>9Iqa>($uzzd<_ZMX~>CKpDfA8{pm
z8?et@$gly>z7J_;gT_qU*H{J5_96RtK^YF&$4KAlO#3!qz+M4%ja9nvwGy(8{53t<
z17Qw6=*b?)gM1}ywdch0+kXbK9=}BS&jS<I^w3cgCR-ZzybJ3!Dj4K7IOU8R2pDmq
zxkkmE+%ony<U76+jtzGTz204&gj_JKfy0vb;4`7kdZ;JRW<c-XcZa0N-a{?dQ`stx
zbV6<o#P(b|7_<Yl@s+TlI?*Xj-4)buT+KiY3hp&<$bG!aI7X0@cNxdavxLtYQBqgJ
zhu|Wi4vY^()#0V7f|_HlyDP~4%6MK-azJy9h2z8(ux;o$rNUqaA6I_7k**2vvbh($
zo(1Q6Aj$>SVPYd>&6PlJR8*UHQ#&}}b(0qZd6QiLuTlP)E5P>;7mh3Q-hiLyN*2ns
z&vaST={|Cyxdsv^d#8JQAV}~^&=4{+dmlt54v@Dw2&zVf8QvnsxS<;f=Nd==eFbc~
z!^P6O+QxaX%QW9r;sD_;?Xb!bBI%5L`n9q@WY1(zSN>xcWNRStwRc(68``j3U-vWG
zFI6Yzo3Wwlgvc65x9#odsnB#v?>9EE+1}`<t~gb1a#bU(w>K%~T{^&p$-0u;|MvD&
z!%gdr7B)P&-lTW;zNPvLJWjHcH`JJLS_1*U-ee~uCio>m>GnWQXe3AX!e2cQRTpFz
z@A?5B7?{G1Qca&+&>L54SHwAnW)ebcRN%BXd7wc%`I4ZN%b@}=ABa{8YG0_kh*uef
zTn9pD4P@iJ68*lWN~SLI)w|LY4#yoplT#YGcfHB_t=zlyAZ#UhJ>yL-Y24sAQyLE3
z@mvAhhVE)Z(~ip`Z!)4QV&8?~8i@J#MiUvd09Sw*oZ&Nz91+fR!gyUty)PNao>vI1
zYd8on@+SKj7j52XA3HAAn^Y-M+g`~+IXmBo?;Xfwdqr#+YOpo6ZJ-#FQyaNzcOks$
zK`V>c6p)p6ANaJrPG<Yah^`#8DPhCVi&w;!Q{il(zy>Z@_mL4@>=paKhDOHMeS(OU
zfdsEx0I%WxD#<=}M_*+i<2HCB^W&)d;wJ^{zJrI226Ejw@8j=ADvgJ-0S#PK@AGz8
zgA-&QIjq4NvJdR$Bo*00bPceMY!coMhlhVF!Q}A!MER<5dB2t5W*|%GJ~E<_4s)Nk
zqOIhXDZ+-4c`9%DU8%Yv>le8oucYoI2XZOyBSjm%UYKlMfFQ1f4RyRk`JKVJvXA`E
zAYIu^Z#iOMcBOn{U{DjK8qd(~b)g_BV7mj|mkk}Ix3@4~BgnT08~904eGU4;!?MIG
zh6N@Ma~NI;|9z3b?}4BuR#q}lIa}DR0p!j;@;Vp1Cnb~baMfHlHM}s_4W*ptkf9x=
z9X8Qj$cp)-ge~tZvDGp)UlNq^vk>&_CgaT462f*MKj)Qjf=YL8G2~v!LM?0s;pka?
zR!@m?-h-BPQWDCj#?!8ZeXSOENHeonThOj6sv*cp9jO+#vWO0h?n=<`!63K%B2oL=
z4w>Rnd*78{6S=G{S!UDaPTT=I`x$t1TL7>D8kZfgv<u$1LpC%ZfIDPGA2?aIuw4U4
z!X0v518ukic6FwA-65;`l>Xdd+E`C%&>iwzpN;|OYd@txcgU_jquzd*)lW(4^~0_P
z-`5VguJMWPkfDtvwp&=QCv)Fs4`n5vi4M|Au6=2T>|bnMSHgJ!w(W{or`ncl`at^y
zUDKzYiERgn*d4-m48Uf0$S)0K?GD+|*q*llTLWA8uFS+aQya4>Pjsn)?Q%pzQ*4)Y
z4Rr7($m_{0B-tOAVm<YdY?obpN};*n8V3r^>56`C_T*gmPD>f-l($e?1IX)_1f}YW
ze9;GX_jWm>0rB20XLLSN2KK2l{uXHKN~-t%pjd3D@;jeXgV}21U@$bgC+wXKl-E<D
zTt7~mc>-d;1>2gSdf85+d4lO>!{&KPWT;ltGGQF<{LW|Dj@#*tzJlr=ENkT1ep14g
zq2AooGE|(?9X&G`;g;EKA*f!G2gMp7P4tO)hV7FL*9W$Js@+*jZqg}oCG}RP+JTl7
z&}-rpuzjd0!-T^ke=?1Emf3sgL7})Z^?9p0d@l5$cRd#{*X^BSC^hI^Lx36thKpI(
zx6>k@I412nYdjFuvg~U6r3t;M-Hnyd*zCqa;5R;bpxfSl;ZHW|u;DTw_da@VsY}7S
zCXSj{0*ApB<pB1<bL*ekPiR6RwldxQ?b;4Kl$vmddJ9dsgAdJBx<h@19^9e#14USX
ztp}o9rrXsx6ybI?UdR02&Oq@_{;P<W`lRg6e#&Zkd#e)ODT2RJgzo_%VkxR6^-Khk
zr3{O;mr<1>%vjHN_>$=D_WCPDp1bkv_45?56G-&kWR_jgtd0{6Fw?)10<JCiXnLdJ
zHQ~rf2_HT%99drz)G#T+k?zW}@5-8fCDnJCWjD2H^*w?OPINtjM$AO+u$1vftBP0x
z@Q$SjYXB~^6v3xB;b(ivTs<%jP|F}gGE0Ib*h@dBXg!eBQV~3VBD6C_?1N#o$cmfr
zGQLE*vX}@^O&M!0_LRq|S+TE~?t>lO?AFpJ*f%@2Fjt%1TI%U$w{SBtyH^QD%<PU;
zEM)$K4>(0^-}%~2Gv!#sX}~=t3D%p3KRT?3_JeQ1G~B>&=X;)lW1DI(I65BEZtipR
zYN(@!y%M%(mJ>fk?}}KTJa|pScBiO%IvUqvSHDJMzj$jgakG#jC~e$6qzEkzRDxS`
zj?QWCY_4<GwNK!h<BCwk*l>$dvKm`c<AVcf8r$HPrX67*18QSP%au*M8rSCzVt^E}
z=0vB2$iJeEihNLZO19mV)P#GepN4)4mVZUn&o?gr%IYl$n14lhI@>qw3C?1zLst~t
z#Kl|6YWu<ETuRvfs)Z=H{sh&-6``1i(^r{ivk4xW6yeFc`nT2L&Hin587`TWVZ*4a
z%_~}ZxU-Xs4|nuY2I25pRVib?9qZJWI^i4&??WaSI8wwu)PqbN2&_{Xh9kHnWEhU%
zl8|LMu&1XCn-T7&Q^Xz|jE2@9C{0p=4}V~VrYwInTNTjfNk#lN^(GauK>b&QPU_lY
zPAX!+`jNIf%joo^8h+b^lWN$9^v$Fm7Pg<M2~)&AlpYqi{|Yv%Ej}n%i(NpG%?}Qj
zC%`L0C*^3JlM0u3{VTbxzwNq7UAm7tL|vMO-BXfUl>+R~Nli+?{*??on_V(Y_YUoz
z?|f6T0t@_-6869_7UA|MxQ|jaFii`SOQe2^@<}rL=Hl?A@F(@}cBzL+-MU?mqH0ah
z{+w553bH@JPLm?e2oL}%!<2Y+N1yz3c4woAuJF#}iZIpd-8<?_A@}EmzT8XA2Zx}~
zeNtU+yvD$~5_o^kQ$=jZU;s-ITRQlRa2fWLtlpU67w9tGs}rcT6yec@Y%2-u4#3}1
zhCRcmTon#5jmlNw0Mn>k_pAqHjiJ`5SQ!d1jfz#F09S;?In;RPhNWnLE32UnHQu>6
z>p9f5TZciUF?&*m4h*hUogEU~m;yFGIMA-v2bIm1MPRdv*!gU7usSvvHTLGI(4dXC
z+_aNv)0<)orcoU$xL_L9v4RVxQ5)y&^#jo=0mnvdjQE1d^y^LW1=FaGE5M*0M1`yn
zgK1F63Nx5s)kzVCx3H<y-F-c3vzxO1t(3B22Ce|zl<{wy9i{Pa(6&ofy*bvc;sP=c
zLr&e=dN`Hs+V4(L+afez8Xm(rp{iXv8(450n_!-q3_F=;kIe_?66XLroJgGm40@K4
z0CTmZm@VJyT-2Zf^v^{NN<{x$(2a|p)mfaQPsuQctFv*L>BWDO5<a|h5+@(tspJLY
zzcNfB!3<Y~Ih0;!5nIi|U24kk?7<Z>^k^JeYj##C#zj+nQ7<mh#!Q4QbS#5q_fMjX
zCTMI^#EuvzuxTPpeUojzluA*y`GQVdyhXW^`d$;ef76C!a8qwW?`JBJoGd%)0d=Gu
z^`La5@cXlt(UY<)Z@fN}?Y?jtHJR><8q;LDgRJIBndw=MiX7R-I1~;r@nu~RiWr9T
zc4{JICuQ}`uhOkb9yk|us{#b(qJFIi0Y0fd6?3&u{c4V44OaI3qHaZyz>}i-;1wk>
z7uBu81g@x7jOie-@QZBwK8PyUbO^v6`4Z_6u&85A+I>^U7H;x^thz2^epAOPsNjmw
zb=vcrD%MPHm`xpvxPrM+1>4D{l2us2+|;rRD|k{?o3#Q9=H?mJXz_0-S%ntNO(k2Q
z1@}SpO)0ow7B^2y*n`2L=@_u7Rc-K^d2XIxO)gy~9BL-xeM4y~s9<jDOcQbB+*Fzf
zE4Tu@J(=sf^rOjG-_(z$`<l7wK2jjT+^dS5l*K8BCl{t(3MNjuo7$0~1anh6Dwbdt
z4}WipC79syPZ1`Z3Utco-#m&=nd%$bamrHP)Q)A5K9JRWVF1Cbd<H3CpB$4rWxemf
z+|Kt-0Kad_uorErNJSFNT^dq>1QUmg6yf}^c@~{A`Zx7x#uCg;EvjIGxuHeh0R?l@
zb3AGHZ~Bd=EPtmiRY<{1e|!q)eSy<HW$3pzc2Xa{H+E7tJ5G%|YiJI2t5AdKRJT*c
zzIVP98T(FkJ5Amfr@mFd!E_YaI!~h+ZZMrL<Eit2OCwJm2%IWeF$dG3k`;6?ohMjD
z9n2)(sYjuRfyw?y-jx*92IE#G_MfVHiY9tGb@d!5)@P)+gy~e%3{02~Ej@+0noc#X
z*o5hH0#DiXPE9>!);l%zJ3L`}scMBMOy_Zy@d?v;npJ?p^j$^3qbEF0DZ|d`RKi0h
zyHg1dnCxB(RuKo!l~n6PwzyNn4%*^Q{i>LQ>C~?kbnv7k*QX*6rc=c#^k6zw>>wax
z7M;gS;-ns(;QS~VX7^xr5o<7=3RS@dGcz@%fVvaOoKnW-4o4?LKd3y1EcBrEtoXfr
zSmaOSyALW$1r^MovK%nkqZ~s+275rsq-^jv!AjV&g10z|E0{r5slb8>a+wsd1A{XT
z1s_zNiY%Bx<;l>3E5V6$$ax?4M5@Sw89b2=of3j4(xJ~k5c2$z$+QoiHiy3D;APAh
zA2rcWIr9VY5-DTfsZSY;Fk@AT-KIJnETWHH$|k5x6^}53+Ef7vGoVdJSKEt=vQygx
zeZ)hbd{F0(jv`j6&J<B6Rz@y7DZvWR@ge9l9y&e*Z*+#v55XIq(dt1^z+DG}paSkX
z8Uz)vf*xj2|5nt)16lRFvsOM?$A_Tu?K(dMl`kV7o|M%<y3P+l4XoIQ8PLFrf4Gub
zBRvr!GkCMxT|J<VW<<mc-v1~fVxCgS-BG~T*L4m!RK}ft{sTqZW#1nvTE#oeql0ai
zjen?V74a|+6)i&^=0S=5LyURKFhPgPRzVN*@P1ZN4-?ElDPji(Pko)ofWyn5F1LOm
z9aB<2xr(&YZa>tceaap_)T4-4m<LL-%UOS@BfG5hLmk=QR{Eim?4;niqRE;Ig2j3q
zKJROaBZ7~@)XLyLS4%2P;Z@|M!Hho}-#PBm?*ctI&30M#hl;ezwm;O8UF!BwOZLX?
z;80C=8Rdu0pC+sP@S;U=3s+PfZEqyT3G}r=cOU3U1uk4kb(Db%6Nu-OP;DJ*P6aQ_
zL*3crus@|cn?B~l(`ln~-WpG*ieIpX!)c>^Z;gl3#t-$1>g^S}gwG28tcGKa_b&}t
zXluNEX|4u&`_eKkleN;YZL6`4SJjBovPKQ7$OvoHuq39rGOF0N***@V3XiZx1)K2^
zw^&P+0TNHjFxsUK3@p{Q)PY$=j-C1yX{Pc)Jkhp=pI||l#>!irW@?JpI?aeHw#Iv%
z#(O+#xY%j5|E*CeH`8FLlrs+Fu}1CNrkYzQ;_XoVD(u1<Rj}eN9&1#=ioCE!72GC@
zwb+NoO7+XY3u~L!hC(l_QT?`|4p0Rv_QD$Pf!a{}o7P6-c4Cd_h}Kn;=m<qvScB44
zjD<C)|5QO1)~IzEWnqm9wl#INlx*WBV=bt#6jx!5T2_G-hA;alu)+|!bk1RGVAnh6
zXs*g6IEbyVVy(_Ho6p)up%vDv7bo|k2a@~aqd*G7u6Yi9^i~<Ljv^%t#NG$n>Qkco
zN)AFL40PeQ%(m;joI_LIKp1os8SxlY#yMMUU9EBy7hzC52XPUG__=fFu(u8^dd^nc
z6JsKl$BK9TC_2Kx-+s=*b0-F{cy(*tvRHcy^zk{So*8<=qq~9V=O{43IxvZckr7s`
z_P5NQElloI*B0h>YEl+DJ9!~#NQ!k7D`9<Si7nS2co-*PFprMnB&-9Kc+ODM8>7^B
zTxQl$u!JEH^_;;6JKo`-4l{85oKugu-RSCOpkrNK4fL$@iNTK1PB)mS=kOWXsit0*
zYCVdaFl1`D66!Fdb2z7|<%6!%YPZY@aTGXVl{Vr^P)f__D00G(Q|ko%{f4AkCur4M
zCe=y-HV)7NJtt_>8`5Z<2tB8^tP}L^TPDsrik~nf&N`tyriRQ}FA+-BIeptWdL712
zSe?v{!Y6DXdB9QpgyE2P6hC1&37((>-*8+!0^Zq}uhOQIz{bRIHd`(y@`<gcXO3^H
z-HGvSsUn<bkAQoIp!^d{)eN1ZIc_<^rH-wduA@*1LsFO%#?IB#u7I5@jdu_zVVN5%
zi`*~9!fc!RwlUkLws%eURLgaVb1JX%RsYDJbA-7wq{cc3l(^-Z>!|^Hme?$=T22f#
z;}{Pw><mtx6VjjX1f8HoZs{yK<?(nRsGfB7Ezp;azSY07Uv;x`Lh5%=u_<uEkOAvN
zQ@c=Yikq+^?l=mYxPpuaI#G^zLr$zCyq$sm;{?3$2It#R7=<N)$nnD)fGf!LrL^LP
zL{i7~Ial_n<A;weH{$`5^?irso;=DOZg6290q+d-D@TDA26~qB4zw_2%{mOUuuPhD
zTn0UIW*ub^H)PE^3bn9F1*uRAL*A^TPz$THSx3<pSC9+SY2DA#G{;^0JUq!KVR;5$
z^HKPPP0JD+HH=SY{Y>K7!%XCctY}97Jww*5mn2K2JY8lvob>0NZQPJf>j-jZaQ7cY
zVHnbBo%+`2OK~a$!zS20kIP60DbZ2-aYHVxBcz>8XimjoSf$f?j-oIO>_aa}mK^V3
zs%fv`$y~?X$??fML7Q2uzv|l(+|H0)>oBsyDtFdVWQA4ktS3e66cnXGD-6lAjzTL8
zxw8%<D=crQj`w%BpeMa+LJsCw#<;aCVIx3F#lx_PE6ArEryKo>vj4KUkxT0+Zo<GV
zc9dJ(a98*o1Vva8lpV!I7!qNfO&_{}4(Kq2xD^}F*#ff|t}_p!A`D5ej=~}gcc4dM
z5r%uxgG;o#GvsCJQEqX=ed`f8&XCgcY?#(a`gzN2s1k}?2^%tuNZQw+7B`J;L$a*1
zWjPyc-9xmTCArVpGMjCockAOR`9bcb{zC2T^`0x}J){%2%9VA5lr!YYI-BOTLFw(K
zrg6eM+tfDn-Zr)ES;AHgIKdHe&VWNWn@OJxV1=_~fES$MY}wx+Ks?G;ZXf_UTS=d+
z7=X@}`E7wA$pp8+m}r6n%yE>W{He~#*hbc^vt?}~?bg{t?Lb@Zp>~kI=xmzg#T|K+
z$=r~2>m**zkaO#7qUQ}cw+_ieN>poCmU|}MI$L%-l5QO)LpK0%j(~EHA*0q&!gH&P
zT4&4TMn<hG!Ip%CS}zGocd;vvxh?3tC3_k$q$}Y=Yl_c0dg#PaY#kKu`&*$YfW9N5
z&5+Uh3b3;j`_L8OV%Crh>#RU2r%Z4+1H<c4nsO`X*AbG<7F5?+`=eGaoJCW4?JRI?
zINAxIW<al<B{m;RblX`=&)k@_rDtN!mWBuQq^#tx*9RRX2%8m6?^#Q2mr-#RO=l!}
zKT1VzD~AWWx#ssUgSY`yc!XUu01wZCxm(0Ow@6DH%syAdUK~u>)Vv<_OX?BHtj>~u
z+g>Z|EV{N0EAXuHY#Y|-S#)e0(p{ZJ6uNC{Euq@1AfIQ+jNUlOE!fClq&`b_awf$(
zi#Jt<6j*1;B;F%S*pL8)Jxlg5;Iaql#BJlc{|Mt|0N$QOd$_Q<x6GbH$JtS{&~kR(
za|Si11mlJzSw{dj%OqL1%%-8`3^wy)*j$etH4eRJp~j*4l&aivA5Q`H$BnS<W1+Tk
zAs(a2ycdQb6L~L;Kqhi3s$*||H*#wolRXTDcg)|<t^Uf{4ZV31!)B>eZ_i{71E_vX
zCNa?L$7B*Cuhy}xhIieC9%e7M?ODK%0+Rce1f^UDw$!TU*y!DU45r3Wx^n|q{|MP;
zK>Z(+5sZ9U$M{*l9#lnEf$}ohyU39BlAx5|j`EWmY_{hRg=Uo<>z1)~ARP8eu-79)
z)-n30ts*OqO?g2;L3A>Uxgndv5g_eKYAiIAksa%pJky?wN?vJLvBzXL!_qy%uNgv9
zjuMg^lVKg<&@4k-j`fd9wb0~xMy$*+8pbbk|Ij$jBIa3EF=&L2$tp&W_A$Ak5yyQc
zR1p>JbEdq|2nRotUTCDpI?7ybh#5K)wzb3kai+Y`_mq@nwhXT*6P24oDGI@62(&*l
z-kn?Mi*zX>w9b^J>>HhNJqU_0qdu;=o$0a8l<DkHgHxt6(qkPV&<yFZ&XnoQBk!5=
zQ`fQhOgXA?ay}D|Y8<VPQk5Hy-)C-a^Ejhl3ERF;kg;6>cqv&ZSMT-Zk_G5YTGHi~
zI8!z<@@E~T95=W!jzDJyj)*JaIU4!1&ZOr$S{Bezq|Z82W;3E1k5Z6ZWgL1^gk1y)
zw9b^>TnV(!l-V3O<4u~)0oUl9ay-DFbd<^5K+|yqK{KRoI?76JNTPKnOZQUbOc}Uv
zmz^mS7um566OJ34Y)7CmgA?v~iBP<wk!KoSyffvQ1|`awP3=PS6|r><(9n6A$zfOv
z4W*pNAxCt%E{_tH8}niv0n7|^GDoS#4YAFK*fFcbR%gh`jKo%Fyq(Metu+FrTsuQw
zDj0LF1P?81_X^k(fWFR<ml=WGXUNN(xvh?pjT_>_kI-R;bZ=*DUT_7DYC~S-sFT`|
zTRCu2QxbARKCA;k**)LEGk=EM%5dKwp~DQR@6M1h90${h(0~$E7v*d|xF8s`m@CEA
zQ4(>(4aEU0%y@}$2C?6Un~pQ&Y{qTK8FDtC+Y@=3ahY<)<XnLs;S8DH;7~XNrZ;F7
z&XA|MXc*2=ic|wx!x=KYkp=MxRc1(>btTvvK>l+j8)rrE|6I|+PijCiw$H2*W(kUL
z$k49bSx<`C4m9DA#~S${&ww>vnX``4kQ*{*9RbG-sk6?I&l;(-&X9qQ+*xPHNYC6^
zx4bLPz;JhXkj&hWOzQ|oW=N)W22Jz>T{&c<7pKr`j9o_h!PP{UMPB)~j(}x`d|Ri>
zBuBoj=XCn9^NRH-eYxQh_6RX%xTZZ_K5N|NUJ17@P~n|U1H8EMPM6afxwMXwnj4a7
z9iqja6y*Z%a#|yu*6DIugNNvJS?M4mI-LnuuVkVYo6lQ~gqT_7&N@tUZb+SVy3A{&
z&U($$wXauuX~9na^FmInBQV%PPOK}b&1C^EaFF%oDN((!g&)+c(g(djH*}P|d^OzC
z3l_Fot<Ec9(;YKrDAjCDJ+(?+jn>&OvyHE!%e)VxiM+t5dHP@l9P;{5d$<tjLqmms
z>?phV6$Pp_%$dDPUF|^8_0Dz-6Da5M0uJW%uBM^>lwy1p7wHi!Y&9J6iqhq^qOPPy
z&@_j6>{E{Mg;ZHbu(8!}q-#eV-uV97VUKYc(2kyq%K%`(R%P5i?R-2oKgXuH%Y{@~
zryWfcZrWR@ZKz1$z*c6;IxV=zTtN<@1)9cTuZ7x%&TOHng3fHArVB)NgcDmpnw{o&
zE_|8I^<21Zl$Cse0_Zf|7_FR<)3*8#720S=FTm`sWT9N$r5(KruJ@!UzuHv<!>7@V
zUf>`;ji&ShPw{E=TQ4NnI!%7-h3r}fxyo0s3bnT^<kmWEv03QPw$v_C`JQHK7%H@x
z8ZH&8gy#zo$U_X+OET~wwW(Urh5~b~*SCAxR268$Hq~Do3)_SqTgZxal)Ze_esF}_
zTF8ra+E6o4egMxsC8`%Y)E2Z~8=RX|eoAn@u$3K^%BRt~8eUmqqqvZ7T`k~7Uf`|;
zbnkg*GGCxPKf-9O%yxBJ`>0e4j^5^lY*#NymatYsdCOPnk`NMWfrcl}Q7dKGUJ2Vt
z+c%C7+E;RCHt^8;)<SvB7xG%gfhoR_*D6k^;Y<h;C)95F%CJ2k>s1KKwLqmGN;ken
z%My;+Ycw=U=ko&JP8>L&S6VA^XiqN~G;wH9KMOWbDBbviT@=D(E!a+Rh`(NGU%doN
zO@o*x&SKkjHjA^=dM%Mqit>fb1#xJXuTdrLtYhGH8J{}vwxmoe8&;gMw-*f8IHpI|
zHx$Rz`})q}Om%;vv-)NcY7vJ9_Nr75Pl~E3%fH!7X~Qeww3Rvx<s)CngcV20niftD
zafVv98qiR~hSfLF?!x+`Z~Iv|#)Pt(FC2B^=rhhpnK-n#7nphCbhV88^H3i1g@aZQ
z;I%40R-E=xse0GcUq}C1aR4l2#|ojh79xq_G(OgUsi(5Dr3)iyDL)GlN)bm*mx>GJ
zF<(ft5(03oN{<zB)HJSuA`aWGk2K<__56+_LUUDmJVM$Vfn5<Ip<l?56-s2jkRvOC
z-s)8;u_9;(FJ#0D5b8c9%EcHkgclqTA;{K(lj0@G(*5yP69~DFps#v?NGD>e*?WQt
z<u$+Mns03bv!m}j2M1S7#8Nw>hO*Skz))mkBYRc=;FW_b%@#^gz7Vb$!fUO{s}y1C
z%f$2>1HTvCSuaukz^X4Yn9CcMlG-@nFuMY_f~cn}!hVE+&xom(>#3afItN51Ctrvu
zjTl7AE#$(Apy`c-R}n+at{R+dab(L1<|}_vlpl-$UJK63h_2^s^i`Ji^enOG&SfCG
zdOAAX^;oFGpbL8;KUPHJ2ud4<yx0qV-3V!Fq{xbp@r@K&5%gmJhj0Jxxr?^FYQBEu
zW4)@jUt069`8xLe`+xiGzkKW8+Uvji-~aTt2Y9eRAmQJ>K_!JS4ZXj*x;Q7jyjG#8
z=w3;kUXvhSMF%}V$fEB67x|%?cXN>6=euBSqmBWO?{|X2Odr19sk)HBVTuZ$>1^N%
z8n_Vgcj$@8yN?)*T9G&_M5dFi?9JuGpx!s6VVal{-XZA>lAj7%3KDn?#=oAeunPh}
zdf|bIf5jO@6my0Pp0ni?)0J-dqoKV&JmaT4Lp)aEL>1bRu}cV_U2DbGYyI16jo3Wn
zb%KBOx%IRAkCw{%exc+*xlU@5Kh{aj4A#kOnIy^X=NgIMtP!3UKG#Ui1J;NGw)4E#
zi0JL#YvjB2@!jg^T60(&Po^5E)qvH(!0eC3@n#>x;!wD`*2dEP(RYhueZMr`ky!7w
zLBMn^4Z=7b_ZQ+7e6I~51h_O5K!MopGlg9^oi4uTb9wlOfyd=h3#OLG>*)4cAFox>
z_uWHYe=O_W_a9jv2ty91Re&JmATSjCkU?DNx46F+4;yyb(7a<44t=G_br6DkBC0rq
z_C!o^IPb&|Q5=GLBBD5i^h7*y2<chj#3`s_;!81w(_03;70$~rsI?Hv6Phms^bDXC
zLqN|`ptp=Bp^6Fo1U@>1`vinKF6{I91~&R|Zg7dg4$*Ui4K;)dMci>X&+bt_2LTPD
zjzfS@#2rVjw+bZ=fjtpO9Kw1AP&Of~C(!62s3+oxBaxmNK^%g42DC6?p3gS~6o<IB
z5l$TB+Wr=f7f+j_%(@Wsc7S~{5*rFMe>jiz1@{jELo+(~RjNO$H}uE_ZWM!H&oXgC
zI8Io>SAez;mKZGp#6pBO+BArl2!cIN%fD;1h_(p9JQ0o&&Qp6v1>Yi$bl5gy!v%M6
zwiF1oP8zX!Ku54iZ0hR+)`{5ENr>VN;5$#92#MVMhQtFQ<R%Vev7N}63bl#N+h_#i
z1c01~)Cu7@k@zG8<2*bZ3dVU}r$Zq)4-S62JYzV$hVYzqz71Iy4}yF{c+L!V3ZOEP
zctGmylxHk9H`TN8+vomW&&ClN?t&2Z5>Z~U%S_3zu-H5-BXBH=yyq!NHO8|tf^lQ>
zsEo8dvFo6G>Ik-ZR6e+Hh|Qxiaty@gNx2*;A+#mp;;vv-F~8A0h%3v;x?9Er4|>hh
zZ%43fY#wcUgAyPHvgfC>d9dwB6A+sR+YbL#?79T%sf|PU$c}*6*o;%|h=+~c)DIl1
z77euyN86RK<vLjb2KSUC*V{VmD|Y^M^x)Ulzd{ei-Y<}3Z+L;RWF3RfKUScWt-5O9
z47I3`I=q}$0=Hd9JnR*57O;aaXJ6~79g~P1d^t+Fv&Y(M7H6on)hrHCi%O|i&}yu$
zMr)^kLRia=0M(ZSrCc&=sh!;0*HSCk+}C;!4!gTxl`m5(OKie1mZj0*h_x0<rB0Wr
zmD<jQu<Q+|sby*dr>SLXr%qE(EK@`9FfK#sK9v5fj$4HwRI}sSA(p}sIzm~mhz-LD
zxuzN}1+u1^g$4mw^C?lSfWfv7M#M93M=)#XwA67;6GUS^DOxFjO^$qpv8djzqz2Jx
z)kB%QE&GmK<FV+E?iCaJaY{r??3G~P2#LKC_OGfxv8XCL;$#E8yMHw`JFpO%&Kp<<
zjr<%Pw{KU(W(P*t)GWN0$x_%63mbMc15`71)Gf;rCk<Xm3sr#^(t=$pT~nNb4<z}*
zjMqvXL>E`W2gAc?t_PQe76rn8N|MtkR>6+w*AS^-NAPPHRcU`6?ZR9wBeFF>7MPO!
z`b8DkE3h@Jlxgp&u}nujXe`s^PzSGm*iwz0W?Sk+VBVHG5}3Ee0FVx1l@J+VM{H}D
zTn8238b<Bf5#Jgh0_+vt`lNu3L%WF!up_!PNClXZ``9VR2V9Hy<eFmy%pgSY*9(ad
z1~66!4^9|e%~w)=8@z<<2xbi{P1_O58pivg4zxws;B!+Anp7<hb0IRo4p2vk46p<F
z5k_!F2RbB-psrp4u1{E3+c+Z`bv6%&A_we<Zw+f|9J;cY0c)~m7O_KskUz-z*MX`D
zQT}xVuZAf9`arIQm~s*n&C?Zd0MMY~0PF~Py%ID9{W(P=az)wSS?!dgf=xhs&QRxZ
z01|~@FWl3UA~p*RN&>-NA+RyY0(1qr6lRs+lYBD=b^xqCoF)S*RXER%_}7>~k9CB<
z#uWWPM+9sX&hz?W@^7wLXjFkbJ1}Ke!gihG+iDo6CV@QV;@MhW(6az}cF>|lfjl3G
zYKU8nL(9&s##7S@=h=}!KHx~{1Me}W_Lhp9O$i@chnti%{wBMteS|@>A?#;InCz7-
zl&ibiNDw6(1b+4ml8y3}KM>@~7WT6vY&L}b><F8UIn^=_X%lp!y+D;A<Yx!&GKl=_
zfM&*|^Q(iYKLq^j6I5X_wId<4Hm3Zw2(67tpJd0cV`_V0m~2cL0@aZaLbRi=A%tiL
zkTr-9?ZCRm?C<%SSgrMpm#!5)w1dJigb(fDcnsk~JDDJ3>XZNu|Crou@X}-QUi(Vw
z4Wt=>RT2dleIUA{6JoR@bT)=|8idZq;JtQ7<ZFx|8lWTeH3qMxdxgG+K%^ZXSqyCz
z_!48Vl;2Mb9TPw#8p4cru#JWwqrG;Pl(3=567JkPwx*W|rJUKJW5R?o9<&oCbg|&0
zeHM302tV2ZZGTBn%Fku+8oOh|k0FEJ;LxZ`*9W3%**>aO(>P=I3IGVfLOWsv0yn_-
z8$uvK2pHNCY7hd3UP<*(c0lsvUcdPL8!p7bj}A)u3fO(<$1zc=Nhd<2BNR4Dk3JAp
zFQoBdQlzBGU!G+)1BE$w>r#HGq0bS9ONa@uBQ`cf1lX<A=a5;B2$m-X|Gj#zFVI$&
z_(bT&(KPF&<wirHHi<5UjbPX4hwm-Dn$eG*P$$d~sb5FDPxK@E89_nOWt1auD7p-D
zd#SlDqa5L`(P@;EVmnCam!e!|qVwypt3zyly=?F3GTe<PMKbkuFyM!X`g-!;N7tu_
zkgVv^!d4|M_=Da`-y*g($mG`%+8SLSUxl`&B+;C`B3q;HcPsTxi0ZH7njl2<*Ad+s
z;`!?f30i_Ye?8;oZjm>9&~Y6q8L@XEj=zrByy!xjbg=G+DE@kp*+<t`j`L!4DQTQu
z130UvL^a(~uo;pVeSTD`?n%8O1~$O?*BS2`eQIV(opotb#JonAHbuIC=u)N&7lhH@
zx1Z2wU;ymP@^8)yeD|HEJ;Gw6iy)|HFldPS@0P3cGUOMuSJ#&fCrjV}e|JClVWR8v
zT{}yxva#l*H{scdPQAI1x;Mo5*DLJy<K7N|vC*U{5f>XxR(d(AqFfsfBssZFx)VOI
zmjtEke3M<iB1>!o0T)-qMxel&zGg(vhS>W$qGzM=+s*tR(L}%B;S!7{cN!vNUy@te
z?e&+wQUt|D<5$WACeienA}ltVbmWFIYx1O3RBVWwuOnH?6HOl~0%fD|tAwL9+EP=g
zx|)1x8}8Dk+ntW!*=RDA5i1`}suZ!XA&R|T!LV15;XEY?)Z%lX=$bSsywB0(HG_xx
zN(y(}(}Nvi-Rp31U&%tb`l~}XLSe6jEyMbbHq~@#x;E4@4vJ*l>)=6%rY{$1hOVRz
z{9wF~rq6fRGubZGp;-2=q{gR@_udgaDZrM2;Mr*Unh`u3tz*d0nWE+EML`kmZ8alW
zHk!`hh?b2e_d23wuY@f@X|{$_#`Y|5bkLcN-#_AIqv@2sOQ-qKhOps*y&^W8UzeYw
zcI#y5VCU;dh~-DN^sevRk2pp8K3T-qjR0CdI&mX_)(=nIb>Zcr=IeFg|D*`}1_EUL
z@W!{-#aT-5VDP8-p?f`v@cjs=-NA$JBJ1mjk-ZY)8G4r3ZpXZBKC^S$c>mPvPVpr`
zp{7jUba2po03;Ao`;z1*iG*-|?4!!cGJ8>~%t^S{ed0yP>s@s9w_j6FsgKjo)N^L_
zbZQbOdaL6qqGKOFa&;p-){ksw<lTEoP`VEtYS%E!N|Sj-k?&kbRRqxbA=;}Wg4U00
zY0tBqlb*OFGy6;E$;z3PF^$`EKQg9qz3$4b+kHP-WV0I!R32``+q#JQdIsG3;lI}C
zbPwDSZR>|V?uw&zG4OTZ5?ma79ngg<p%WGG1`j#45lZV!q}x5Rz>(BJ(8a;m9j<E^
z2VY0H?Ui6x0%FOPQ@0oWy(^<`2l@Tu%&6Oe_iz#S^+JSP0UNJf!Ie<ABc9g7b+>|m
zS`Rq63Qgx?*y}(Ic}Q6Ul;<Sb>w!Gh9`a#<oy`M2tYmKUkVOq{Hy6cT2j#to=tX+m
z2gsZT>d=)bw*#5zNQ&D5U378sb%ftu37Z)hj;v>d-@20Gb_CD5IQBZz)w(j-_R4bW
zA!`{7_AW}j4gz}zrCzV-Sr2iHbdUpHQEepX))law>bi%_XAI9lv-gx}rGPCjOs~H0
zSO9_1U`7gJ4|&6*LdIRxd>yD;4{2TCa$N~<JD|QUs=Xf0Mc?%9Jo_h=iXdAT)m}%U
zW(U(=M~JP5@EE;fY+b~99Wl1<Qlf~lb(anW)un@L?<rA!#SSeR_0L=~P>=*zb$q%m
zgjKKa`!zt<EjBg*7a3o#J;DXN>exoEB%h0&#$8d3y+GzpBEF7jTX&*8`srE1OT~`p
zf?4(2HJ=pW8Kn(f{$_;Ix}a1Yp|mb2RR=oXeZTt#tw=akPmupD5@uMd&s`p8L<+bd
zRZo9uC>NxvBW~7x@tIJO{su3WimZ($LnqwHv(<sabU~szkg=Yas9wan?$WQ|m3LvD
z`oSH#3-#11FvJCW>Ife3ggte{mbh?F9T?6lp@Ic-u)A)SGw{`2>J>JRd;M#j_1vX8
zPa)-;2&tYus18EUxV|s&$2*}<J;P63=%-G5(1m}xqCg!EJkTX+#RDzlL`C+BWqo{0
zDZ==4;-or)SzSP>jxZ+|RO(7{WpDYWMr&CFXc@s(PO`j#a8?(VY7}es6_~M3*{Pz-
z8?gOd5UYV;FBit@N~*ukrf{Y1+tpS_e@jh{R)4b<s3w7|26)AN%QrQ^K7LWRY#91V
z;Hy!mD&Mqz2M%7om4<5IaOO%<J8*(?<)|Gv<vBU`MjiuQ7_D2b^^gf_2O<Dn`Dq6@
z<9+jE9SEXzC8r%Y*Lo7{J&@Fh=#?HgAG_%C1|npAo8DV$FXDio6y$fk?c*`kLHkzt
z<y@A^Iy)*#)0K2~ki*}Vb9R8?-Ia27ART}!<LrP-!ZYFQK)9^$!TXGXz*A?+*@4(p
zSH{_q(W|a>vjg$1zUyD3jz6wEvIEW;7p2{3CreziP)Yj@;D%00f5!t!y^E%9986+U
zM-C>jX#x(qCM`RVr^1yRc9a{-l^J%x)8z|a{D3penHcs-QBExq!wy8fy7Iz~UKQ}c
zAne-7j5ipX?TZ?8fZP2_*tLP4=wt2!UE%3<bnMEm<gWu^uD<X!_nCjQW3?K5>1#%i
ztFQOh+@ZRZ8g?M=)s-1`RNSktt#)y|Lsr;lz#Z$#3_B3@>f+rSh<f#<k2k|!U0GpA
zQNlkds_`HOK#Y0=p{~xPu%mp^zD#Vrb98LYvp*c$wr%sowr!o*)`@Lfb7I?0PHfxG
ziS1vWFYbHSy6^l^GhJ0(Rl9r7UNfKSuFeTb)G1C!<Z8jM^a8!K*Em`M#%yDC{3}V=
z&Zwe+T<s_VyP}gl^<6Sw+6g@}$KGF}FGbT$6{v4tnvS=3cxQr^S8(+j`45mbq=xb;
z@Fk=H-~}5h@#9^oiVKr`8^|Dpb^0$AKdeEH-5&5<6zv{SK4jmB`}ks3HL)Np3+@Hh
z#VE>aT%|liXm`MZ0z+yyaHcz^%r;hx0fO%WXk7zCZg;?n7Nx?rAXi9KslDoVp`P#x
zNECxM{3e9WGTBB@4SR;ru7DZMn(J6dK*uZHg3t*!^Iv$TE-vavh!sP;A7$=SeOUWL
zIE$F=Wst%qo4Q@J_R(1tX5RH9KMM{=dO4AB&!tIu9azssdpRAP&ziS?S2*WlJwsd?
z=)w7bCe&4<)q_eM;Nf{GMBL(I<IjWYUfIbka<og79{1wcXO#*<Fk~8#yc2bpXHrn{
z9Yx@WN4d^k!yip|kTk>np>*m_D5ztw>i&*V;hO@{bM7`k_8aFc_<$<aG1zr0eN(G$
zU|D}sLN5l;?3-x2bKpyAOx$fjw92Fyd(+ne9n)jv^CR(|d%^U|C|`Rb*(JGlZ(%*0
ziF+kOXinxRI3SvhlYJaPy;kHsKK}^^$7lF_&W&UWrwJV~4xp93Y_wmXmXw>OApYMl
ziiDf&nQFqbo>D#v?iAnD=rku1-FcGT39$coO7ac!u{j&DvImJ9oKYjc2!7ZZnZ|ay
z|LbeAtwBH&zuCHih4gMOMEaH<Qw^}k?0&x|JlH&sqrOQs9TOT#q%u);fTC8Oy;_{2
z7G}6L5!uA?l1fE~&PNyrc&N3kN0Y9sFX#$AW~lYfwk}q6!lEw&JDj<B^OIoWl|4fj
zzJ<z8Cj=Mdw{a!3Ylh@yRwTXi$X>kg>IX}!4m(n?cbs%H%uDNd?OEXW_Q3M~65$4z
z1y}M#KP^zyl9@7HXOlfF?b2$xW1wPjutVOGBa|_X((2>LTU^viYapakVOMx-t$vSd
zrRPfC6QkDIC+cw`0s6c~SeVOGR2o7LMa*PtAl9>_PJ;nE$ik_<k5iR1Je_3Na`s-V
zGhwS30Gh9IaBOmD&fHNbZ<LVvDwD2u_?A5y&@yc0gJ7aF2SOe!I8Q8rO^d3ZSym7Z
z?#cde$Ouj^)tlkzr+zzD`;{~olP)IQCLQ9s)&Z!aUi?l)!2LPH^`d{^1F@M+YxEPb
ztuB-u=BpLZ;YCC@j-dbB%;}2qJUZhaP$7oD#A<qOu);s#<^57_*HP%KSNi&Klyg&G
zr5wtEDNHe!xBStMg4P;r+H{U|`?j2!PvKXB8A!Tl%cRn(MH~IoQrzIfD+@p`169mU
z!eJ9nY5Uw0#A~9|?9r4S@QKmMTPth)r|Bm_r#kEOwL@;UK?Cp+jMGa*AL?=a4D6L4
zHAFK!mPb<pCiEcw(wGCHmh5(1_VFo~!O`bjoy4M}-E;IcR+Z&P-qE|-=gdG!8UER6
z)CSi6L+ww-C5U7UK+R7&7`p$F@qJ#9DKRP1j&2%+wwK$0vJw)I-BfLI)_=6^DzCTl
z-q9VemgTp7@QKCc#H)1yA%CdRyJStb<*Ka5zCpX&W?2+@;>1eKGQq1*4uyBueZR5x
z*>PG2G}yXw0ilb`;MSqE6-m33jx}7pPv=80jZVCTkCT5c+TmD{1Li>r`d9bf9hBH(
zD@D|nNd78v=6Yzg;+(F-@%ik>xO!>cQ%gcrGE}aq7brApCt}k^9aTg+-bm+;Z|QEw
zpZfy!0_(vlPLAw%z!EN$jf+s>(9rDapJYy&m*6NWdm@1lchAQ7fjx4eGM@ED22M1Y
zG@6Z6@>qxxhQRXb{H<D5U5HqIDV=~2;4?_f2`i$fFxa2$G<@N(X6*4o2aaZH_}891
zN#zKwVqH@3{jO(K1h2}<gSwk(ko4p`izx@@R2$zENQ~2woVy<)<n?=R@qpYb+SI}K
zx)H7x=u-Bbgl-fLIJ8F2vP~DOj>KvNFih{HoX%Yi<V@?{^UFh3U!w9$>6p~Jt&nLP
z$<Tce3wW}Ln~5AAj)(l)!dThb{r;buPOkD2JMerfE?`?+#Z6-Ij}F=MEcRzq9PS!R
z3&1Sy_CG-O&jv$|aJFjOT|mThiKkUdTfXz#irNDOyUDZn()F9v?7Lig&_=H0O-mli
zf5eh#eNV45$WMSEDZ5~m*c~zsg;n)NZ8eY8^U}r3O@`40y$N;k-GP8q;lmznc$&TR
z0%48V<EO_mW?i@>pLI{lb{`m8Sd#Qd&zE&ZN`Q?Y=}+c?nBN)#d~sY6+fve9{GW|z
zSx<X?kN9~q_okc)kxk(gW&fgDZ8QvqT900VPF_4H{Ux2e2)|vGXkW({Nj`I{Ax=~^
z@%Zo{Z9Ao({u_ph&vaYtfy&SB(9#)_iu0?xi&{g!NS82crIdC=qb($+9q?EDm#yb=
zcZRRa4$CJ@t*)cdSE6ZIES*l9B;@l<3zR~2VX>}!!O0>3P6sKrbIbG>hhgkmzm%TT
zWVD^Tv7ud|Fk>z8c<3^e$Dlma0+5d}EEqeCQC*7hJxuu(i*;1PIYMnk>aN)xt(0;+
z{q-CW?Fh!NQ)v)2ix5z)dT_(`VD819Smj5#>Kx4z+#WzL{X<Hv84Am(7i6%x4pRv-
zuZ(8$h-VvW#<gJLxGGYyQhF{u*gVkRW9ixrVE8p4CO&c;HP~%zuDxa?S<oL&SwO|#
zy9{A_@8RO7FM3Nb9>AJ)q`#k4`RxzgD9x~AomHlVpwrv3;ymS$ye_!G@^*sx5TSMZ
zALPcBya$y1J~qHb)d&3Q@+1x)wn#O)tU!1HxTU4Q&#M>=Ry($r@vu<#K4H-(Dv=hj
zQ0%o%ZX?hxJVQW~NFFFH{)!s)<<Xm;F83Ng*`G1oM-D;dhwz<V{F@v#hUO^2+c0EB
za5P~X%Yb<{`jz2*Qg{zAcnr(e`!(Qa)a>%hAfV{oM<T_$_v!H#sQiy0;3~luv3(y_
zCf$06ozI@KKSDUk{zzHf<8Pq$qO_;fxcEPqk{X->osX(d%?04iX3ezGuAOvU`dX82
z+iz8aqEiwr_Fnb?XL&*RH|T)5?|Y;^uN6!QmmGkGP@pYxIqd5pR|x4qgRuh<ZS@Pn
z`$xAhDSr7`Ys@!j*{MD~Y1}*gWDdHZ@ms)%AnF4F&qOyyO(rTZ6;d4BK3;R3YMYjA
z&vV%#PDor{jH?;XE3rvaupM0mhxZg>SDZ!g5Nf(pn!GWs=R=83@pn4MF7fBSQDKii
zLO@n+f^+0Q;9NAcwi&gg6v@9QUZxgddk~tY4ib4nl1st&yCP1dk;yvZ0nn}PaPS}K
znK{rC-d3|*H^C{XX#s1(d1+{68nxtC)PgB<t6)dB5&O{uwQ&}Q3&C;hBFUumIpDdp
zuLZs{SZB<e%YL3qFY1DWTBCO^z+9{QsH>ycmsG4|7cZwzIl=FT6bA&jdEs5r2NCm$
zTA6upGN0(?0CGVZ1%R}+bRgvaI(D|uc{UB(D5DkJgz7dlQ=wbG()6k$%e9aVJJPs;
zUQ~7hvDw%+hr_cm#aeP>xk-ui$-*}>n2b5C0BlYdi~%W8IAj57b_VKhkBNRoF!!4Z
zv$FxQ+B&ro3s7pPl3c=zU>Gdbr>>&rqSUoz0r^fd8soKT1WuDIHZ5U48W<`L$@-o(
zfkT|e*AlDL>ES@^Qx^OR>`GhDw^#~~i$Rj1TgcynB!Z_((HDYXu<Y~idt%{8n~$t=
z0R4Hp=X5=RxlGSjw5|*|a320{rm93jcj2XiCbpK-TI3>obDo{MIeKGGL^&-U5`yIL
zJoK)lTlcoJry`v%9rH352Qv{EnTNzH$hD=}lM-M9>khg9*jNrB1%Mz}4X2DwmCL~^
zTsPxkqn(@pfycJoDc?e^NanE52iXjG?k6~Uz?ZWX9_CAT`Zw^fO5KiT8hVbmiyw*#
zRLRq;w2>AlCrP_z#zRn~k(xM0$uaEBN1Hpz=z=pew+)0di;8oTG>;p9+#cD&D)QnO
ztKVGZGuQiIcA6FUgRsi}Obh7z2+t>5S+`GE>1%=GX-dnUiFi!k6}m^pXUDDABuLh(
zuyM>avq4@cENS1}eV_+awC`f<hWF+edoDVN()AcK`<wl&awM8#W8KigQ_`Qsu4a!7
zr)k6s7lUDYwC^j4>8c3VN!4JbwtionRU$b5PA8HA))44fOV_})%Bigs2j1RE`<Fi?
ze6p>Q<Xz7KR#FcwLgbpkwa~GDF7eQajN8cIVCflU*eW5YW&G4h9uRKM2$=i`*X)Tk
zs+(+hUoea@%L`aK4A1X3^ffEE;O(Nvn(oD`+*EW7dPtIjkPg>bC^{}wZa->hW|`E5
z{ryl^EhynAI^$$yx)-sS!a_y<8|I!)0xbReKNE7@pkT!tYjI$e{6IN4?&cyx-z#@w
zsm_|Z4kc}d_^x<uPHWN%imGUH3NndfbX!R+xj6q2>WOOX$!OSZoSWMxnklXaYh3gh
z5@89`Iu3g>v{?)dOg;V6FNwi9TyxFOK(4nHHSzSEew%@coMiOR$`b!WRE>EkR^u}$
zU+jDy4=59<&P0-5%g#z3bgZpLc*xd5aQN*mY^0(5Lm9}TW;t5MrFf_C-J}wtnw)!Q
zNR_xoYIVo(6RQ$n4ovaPageLFhQV_Kzhs<(#|C~yIVHmxbs!gn$s14nEH3Lc4FP{J
zbZ8e7*`^?%tT-ho>|JF}j^W}Beh|+l_b$UWdW;aU7cT@qEW`fgUo;OAHHdVLo8TT^
zZ#&Ke2lf#jo=I{qWN3N~G}L=1MsV?4c`nEnS-CXBVJl+kpoc>O#`hvcMX~$l2+TMk
zFB3IfV!i}=@IJm}AIH5241aIX$a6FcH6jcHff6N(-ZhE|Rw4-n`p<32Hpsnl5loD4
z;YXSd1^3Rbf`{n|Hzmq=*;ckB+)uST(UlvfR9<3rgu5eAO|J=isYh+h5nkfvfhs#0
zdCoEOt(_-NQJaL=$IAkUQ*Oz`mVmsmau<TBbW{ai!)@piz1l1263+xbp};lEAztKW
z*vDOcZ_$M$sP%`>^;;1hUdR5jA4l-nOcD#kCmCQnJa8GL*6;9WdtG7NvugU^UY8k0
z1QG^n(3F4y)|h9!b;(orI*9`n=SW3qT^WCW$TaC|a!wvj!B=x>v_Nf=9b6L8wwe{k
zslmbJME91whd)=1@$XbckS|hohdiDK8^6xts;K5GIg6lZpDRtI8fkK*$dg_2SW2xe
zk{Ydo?QL0Dxd%F?)y+T;m6kh7ju@Uq445i+#exl}9)aMThii6|Mj$vYHO^i13)<>1
zFY(4}RX^wi@{GWoi2j@{($@)<zTR2nNzke+TSCn|G_cQ^`RmnV^-Vp|t?=V%oz%`n
zbv<`=oMsBcaSO=`xJlri_!V)70r3j@%Kl;nsLmf+7}s7DW+4K++e?6%Hqgfid*`on
z#BO&W){m<yTElRR5P}R-L?lD(sZSmj69ykjWqf*QO;7uTR4^nRLgd`<FHJX1YgYj2
zTX_Be&>qc37d)W)&UFLhFxrJ4HOSj^S(>?3A~mQxCR55z1j1<9@)i+LZM}=N@<DLr
zjVr3l<!~vE^CQ%W9_M!ffi|n4wX<lYwh5oC8tFm%M2OJDLxWv(Ov{!kd4HAlDAu*k
z50+HB$}$Z2&Knt}-J1GxZB|K;9y3b04L5q6AY6-O3KIuV`kxxO5m%pBFp-jb+FTF{
zExO*(vvqdiovu-em||4*z@?7>d*rgN6P*n>Zy^@+u(#Wk`h{$}Hx86`xvWT`0}lO5
zJEd6nc~)KA4ZJKj924X0kzv26DXs*KuhauB;54I1r|glMZ6`<vvIQeRcX12^2dcy%
z_)nyHx%D6+Sxo8*c$+w}zIJj&>k%xR4Z?XpKN+Xzv7l`TW_*Ts4jBrMUwjcKPCG49
zqG^yl_)}SwUhr7<u{(z%r8pN6&^~E3AF25`Ebo*z_*0K*a(0b!EeuH~@&L6gNu!i>
zQTMh3oy(1y<T@Xc&Qf(-lwCRNKVbb)wyrWvh@&l5Nl=W-KI5dJI&+0Vb=^Gj+2Qf7
zrs>K_Cv>4|SsU_EMy^rH^pj_&$}&T}WL8OLixkZ3E`K>AR@D=J5dM;XqXgE`t>B1Q
zzTIizW*G%Q@)lSSO!ax8ku@|OR`rOLXz!_SCT7cU0k6>xkoj}Uy^UTt=!{9(*kzWZ
zN^UIuMtvG_I%yf@b24FZ&75;mDuJ$M$r4Iwd>fX#LspUzZVlJ4r3e++sNjI!8~)m+
z0PdWHAE3C&y02)4+V;S3FQTKB*%s3QI~O<jhZdi9wNg@~xQ=;A=RfX|E6qdq?ujX#
zGv);Xs#C0x3r3f%V1elS)pfuuSegltUEHzNqoC-g)OAEHx>#zPl(ZG#Y><oY(qE;K
zt!(D}i8klh2QY}+Z$e_}1zoyDC1ap^V<^F+o@8JG&7+oO;5i{G%t_F@;T%(~EVV%}
z>RJ+7hQ8@3gQ4TT&lavOwG=-4CT3sjX|^A7wAiIplz%oS0j4QdSLQt}a+~EEBZ<?#
zZ7&JY@wmY+=>0u9uqbzBlCY*fxTWP4{@~ev@TXG%l~E%Gw#XLNM4q=){)BrR_(}*>
z;}`*&8`aHFgKFdbdq?dop5nHP^|d?oex{ni7>-(SwariyBmwN#CwRzcP&1e|*mJAT
zDOdh<C}C2d*1+Lapk;U-P1cv-H!1g381yQ1DKlE9OqP9<%nV#L$%iwj0u=!?$KlVG
z&E-d~*TQA(si`|T%4##6KyK=C*3WWVBm|e>E!}EDYIHy5Ef#mSTCBz(3>%!hAX?f@
zExVR)iL3%k76bFC>(ybmVAXQ=!LLHB=KHj+jZ4qS7(JL(*^^96Q5v|Qa*nM&E!b8d
zc}8H3E!7&wh;r52b+mvK@+6=!HqO-Xp1_~lnojoHrmMvAj)2)rMoQ>-8!W5|e_YV;
zfWYY!p#S}g9Q+2=8V`Au^o-R9l3y_lrIW~~*7$`OXy^I(CA2`#0|W)I>jM@fJ33Pf
z1SjUqBiE%Ko7HK2L+rQP{oICiY`JEbfi-NAB`ERU?bf<NZKi@0?<?@f%uPbydiN|)
zk(d?n2{Z5#hmY}xdcb}4*>l}Z0ATL9Vy|p_5$mVjC=*$6$tNo6o#Y>aYwFz>Zo?|I
zx~PW`>9$6C5c^=HNxSS&@f<$&j~DNajl!1Pk@dkcWJOAmli1WrPzu{HvqST7!C*o$
zZtP>|qj>bS2(j*jDC*LEW&Ca{^XO+H<n$nh34%M#?bG)k@Ved!fr=`oY(3)(!rY>|
z5eiE4G)r7V;gV5vp3V5}fV@Itp?QBQMM&Chbq(S{--&fC>_RUljjAV;fDk39)~f5V
zi|np+GRyiTd_{^k&q|{CEASc}S((V(OSJS|7eQEo46jkBfD$DZO7kfUjiaR)Cjb)h
zS86vD!4oe)Pi#hI{KnK;#_9M9${oFr_Sdw7hQwTg-3M6#uCboj_0Wz}CwEjj4X=AE
zvWVF+!<A%x460Hr*?2czD=M?1hp@_^;^~EIBCjW8e~7-kN6561s0KyQuk7)~t6-Ug
z?9}fnr3edKD2*zae+wYd5Z)1$$9cFmNOd#0aF$OLc06#~#OONB-!jK8EezzGI@_Xq
zr{0}{J0qD=*yV}zDtEANX?`=1=8SQ$k8+6+0m{f5Do8SU905V)-Mq7eYHK8R2BKn0
zsO4(D9%e9+3~X+*5|}tTeaUz~|6<f-hv1;0Ip?zhN`+z1Fdrf9)?0$jj$I<rX?ROE
zQfmb`qK9D6v;AzLLxn%t)GeqEj*Wqj@dFx+k&pQ}5r9E`YI5>HBma2wOT<TL4th*W
zEY?{Z^8&2@kc=3_o@m!$z}A!|Ucdj%GM@dehFWDjoBsr1P^sDP^mop9wq_VvjuxYj
zFUax_N+W6aFnwG6k9j-l4OT#~4YZ8>NCbJZy_+%}+WL%UP!Z1A@I^Ogn6X~l5B7bG
zUStm1R015Hy`P(aq%{He(|DjZa?Rh4l1SqZQg~#8DCI$_JE=sjUJB_5nfdfa7m#de
zZ9QW2&UFU?9IS=)U0{p0xvG0|xtqEzKxKFg!Un;mFx?T?s6I5Qy_l48I)G4ZD&>{+
zM?|m=`Wa0yy+Oz|5J5HA<`lse@HOf5EZ_=Z1tPrJQezZ3<Y<~_eFm`)s9Q*Ab!TRg
zt)Adqb`O^GPI0W3d#~_OzMItSpII3ovT~DzgK;n+i{GXE2365i1XRhG+i>0RGPV+v
z#zJ_}IM?r1*zfWBVz@Xw7cP!?Q~ZR$S8I0`B38BB1z@iEE)Tg9wn)yvMlv%gp-|Cb
zLNB1u(UXo1(vEN3W$lt$b|$J%>3H2^bOaXzj3TqT$cNt%!Kd7CDgRtThRcQi8qV;e
zVrf3^5|rg*bcsK+LG~w>axtF6{5}_To#KOX!ItaAMKld&wx0(e^9QU@`&U2+&|>k<
zf&&h&ibrHevZ9Oau&+!!?^2SLWeK-Fu=N`XF)bEWteP3<Vlfh?QmHU=Ym2ELhVvs&
zARe4g!9i<bB=v-tYB^F_Wl$Z>wVk&gl~$E8l%S9gx(HHattvB<OkXiNNy26#A9&a`
z3NxOGgU;XZJ1h~82+eq%{y-!Z3Z&+B)_l_w=AeByCm9^S1a@tjcC!!)L`*yvvjWYn
zSbue9u(WV-bde)^1`kqfBgXJpo_-!kx(FmUnJGmw;>vv|ZgIcN&O9;-{*!%Su-aIx
zLShh2fp<RU;5ax_oFEKlhB*_LCeRtHgC5Yb(25PP@?C`of7KugW@B~moaK#UDMRUi
zGRDF8vuG`JCkN-jN|?45Ze#V3&h;NA>LEVsc*JHk`Sw`@o5TleN2713PBzYpIHB)r
zc#UBRcD7m)hU=wc7>bIhECb3R9!B`TNc)I5TcEbcnV~YFWY8nwFYzrP5jg~e%8W<$
zE<$ps2Em9G!%>&qv2X32pT~nif_O<3!F^ZpgknUxZF1`pL~?CnuSba`I3&UkfhZ?Z
z0Id11${a-bfDmslmJljK{4IGQh?VnjWx~G_Nk6CtLC%Q~VIUx%E)~VyEFlWob)?B^
zW0_QmOE?4$%827QuKZ=V8oA&508v((yX+V)7S63HA@8d{^rnTkY!IFr^S|L5QS+@4
z=Sk#pnuFpaqFi|H@|RiKgQ6pRxN2fXc8Np4+jy9Y$%V<Rw9rq@X}9QVsJz$}HR2wQ
zD<IjICT@UM$i^BTaup!U29Qf=G}<fs+Q1E>9bz10FBK~<a+dBpYxYh7>o}4#$xI>A
zZJkRdS|GUlO(ld;TOiMz`FX}ZFl+MhiED)Gy6_t(h{M<v&W_H*^LccYL<qUPZfVBq
z&_s_f8cf>48A?zkz$)X1Gffhpxhr3w1JJulb%~B6o-TrLc@a}K<Y_eUnP5Y*H}NVA
zS|3L=&0B&ih(Pp0U~3gLD;xq?`?W)UEa3%Ifgo7(BbAdL)E<GxOVMa4kU_tca|5(P
zvKR4u4t4tHgG3lz$mn?J7ySjY2C{euDb5{U5WE^*dV^}|jaDH=^<<#>HACJv@v!in
zJe_CyB>K<6XEQLJRPLA+BDMS@Zxx+Ii(n`<<L+K54swoaW&2;I%hGFkVlqgLGI|FZ
zIT^y`O{^`kfJAv}Y=xSe+&V$m|Lk`hfe!ZVYGaCLqsf4KjfqVnTkc3Y9rUijX~aV)
zVC2WQWPG35rn|!jt7^@-EwzXSK6+zE7F&@q{o(wY%cY+aoIQc3pwfRDd5Jn@MjWa+
z%)1*Omr?SKk1;u?zqK3`0;Mo$pbZxjOCp`GXaqwUfBfa?Z$gmGuke{>$ZJkICUpLQ
zL%rNzb)7k#a8^Lan8Ts6nkJJFt%zsMFtNvQqHqRlgi#)Rjj%+&CGEfysuGShjZIhA
z3G|GE)G(??zaHTm#P;^=o`+Ey;@NTnr#8XA>gq4fgdd3<+2MDz#=8~0Lj};B7#?}}
zU_{<t<ikO=rg?T-!Oown49~aJRyzUP7GsCsg)-SCAnVg0b-YN=3Nmmk3a_q_1pOhF
zRY9_c7(ioQxYII9FDnD`6c_OUxt1MzhGRpIxv`F#a$%mFRFj9v2_DF1!dd0IhE7W8
zN(3R7MMXarC;q8!Ajmy0j_o35v_?g#H|r`&1<MInyxQh403@$r@WLqrJeLvvqnYYW
zG?WKKE#%Yz_MKEG(8<~Rdu!&oWW9Lp{LLqaZ0akBZYJDAh=?rerCoD!$1gc&jNLN8
zs5<1iG~3_bj@Pa8bWqD^a*UIB3UR+JDRXA40MHdTp`J2KM>kX4+QtuuP-f_ItoKMu
zqNprEa}=5J*o~aCrdy1IGO-jE;w}{y=>?t>xN>)>5`8*z&rz%{S-B-#u}Qz7v-&Pk
z<&OAr)9s<7reG^AjE9`FGbGN(AhK<Q&wp6NQS=TO`Ru4&qyQEY!efr#W=*?mxTxt6
z4S`lrFhCWyEm*dM9?|5WVyq)AL@hQ<MCZxTE_tfCfV=V2h-ZUmJdIG~h~Qs?4B;Fk
zzQdph!XDHv2;a(`&?)fWioI4Vh~J9MDzbnt+eoG^YzYdWLYrF`5<-JHy~rnmc?t8}
z@s;t9TN;?!#u5zgZY9TR51+x3yCb-%0#I`lkoK#w;m4Z=S6Hm&Lo%UuHWL6%3`O|a
zD#bESz5^LYek>`}R+iScfLcK5>mVu$goNAjIp7i->p-^5CZK)(tk7YfM8-dlEcc8>
z(gJSQ8Sb(QzgTj-!%3ldY0Hc$A3lgZUoXvkZrzJ1k3gj8q&FH}aa+pR63qSUsbrQ&
z%5NFZyo}t>Hkf%1<&2|t$4@a7sOgN4xktRD3n`%-&c2MSNLzm73$f518*aj^)MT|s
zny;>^brxQVelX|?wh+0N_XtwH^bw?QCyI`3$GBo03D+_}PCOX84*Qe|7`V8$gR0+k
zi^ml!N|_O|Lkoj%!PLE_B)kNlEz2o0)jf-PZzkPPS6u_ek0k^?TB8*!gGKHsft3pH
zYz`7;71duyra4a~O7X7IE`qbWrk(8`V5AVWTi^YGYTR=1M*${EJ?u?R^_^6^x%43*
z7hQ9^j~b_`bm8DJTw9gKEw<^qq^%5bwEHu$7_=J4#})vpke4eIP?=^^a#CL^qwktb
zt_I`?_vO1uVyLTS1#GBGZ08=_7b!g6p2wuAR2&%^r@>_55k{z)T-Fbq%$OJ~rZnru
z1rW<nfCR!AS6y8Zpy~I3#I|SprVUDH+yU-PxFJwByy-E*aLpecM`GCJoD8Sfa-H+1
zjG|iWN%dTVn(N4dv@m*7JmHBVE)Dnt7m<n6yv;lJXueIn;UU7o4fvhH0ku044$|sW
zAqbDhg1XnS)EJSlTS7$m|4<fuIM`o^5nd(*RMxx}<-f1%#KTN1lS7Sxyp5|ahPfYj
zzHjUeR7+b4k4i<X>tDhK;82#lOAV4G-LQa#rn82O0)UodRe}FDK0?<w)k%~o;IeL^
zdSImDR#If{;q5mEH~HlbHXTVqITQP=B_q_syJt?%y#0tOXdUs?462VowA1L@KNo4J
z6roEi-1K9o*|;pf^HS5e?E+ojmi8ISH0tLO2*pBnr%YczZ=e}H1nianJ$n1{8RUb;
zwSLC{gJvYbmeCJ7F~lpwF@tD=?h5SEMN_4Ol+1E7kVAT*a>B(>7zq0%6bZYq`S;ZP
z19f?rhajP*k%Dz2m#TYK{)d4(e{{VzE32Wm%UD4z8P#_D)T7AvGfNL6Mw?aoJ{Vwc
z_Xvp=(v^Oc1Uvf}z7xsZt>55VeUgoXzt@GN8Uxqwa)+K_W=CzL%H?MyG^@xV8xgW{
z4{<W@saI<9lFw!~p8x0`q=KZo|A^L#l;|e!*sLk?KhRm2R#+jyw`xqAE~F_NYW>=y
z*g5kUZWshzM&`ASm}=R7nMTR6AI2>pM`*n(n4eMmgCLuvYHb`j0yMItC6PGpG~j(q
z&a?fCqg>{|9{+7q$4R+OPZvgPi*;lSCG83WZ&3`cg`Cx|A3}!JFaoohlx7L!@cZfY
zyRy`qcM2FIV)vDsN)r%rj?Hr}S?YVxc8@}>E3uJ5{<;;r!X|Uy#rJ!eF5$`TM?wb%
z_b$)Y482mn>yJjAz2I}GoF)wSw@nsEc?%w4bNZVBSG*It*(W<Gb*s{R7j#WnG8Vqy
zpLC87Zoy;PfT(k*l%^4k<r_E0h;nzC*t*W%#r4UlZPm?uYmJVgoX$a<WyjX$RBPlR
z=nWKi`)QGO^0Td2=T7jk)>w%GnP^9iX^r190W-Y%sSJ)!ZoxC!G7w<G7W5G8SK;bS
zqVUVevsMw<)%$<`f-vh2|6XhIK$*F@ccXU_yLWbJ7lr+{-aZJk+(*=i*8Ba_lR6cK
z)QO$|%%zi2ze4#fA~hL4fpS1*!yZ3u*m`uaaX;9TUVqRvTe#*Aq|w*y>9WR0<Ja5p
z*SqRnX@~lCKQ2jMpU^{G&&Pd-^>nOL+TGn(Ps7*6@wxo=*N2gB`7q__=YpG+t#9?~
z=^bHp&&wv_VVD!<<BR)pkMGmV+u2=*z~^bp_Sf67U+d@PUDL5~&-(4>Nh$N#XM5b6
zz}>vS*GI`$_uWO!@z>`tVRd9hdS=1q*LB$*15{w;CMQj{k<k|Q`=-Fhkze=MyFuAW
ze~V4?uQbhHbY=`K-mtIaa=7nMMV8}HyKz+Q*a1V{VqXu0e&k}loTXQxjTWvOeiKeD
zwjY382m^;x>en(vs`eb(eMYzd1K;g8cfZ$<D*@XSc9_85`LUbjPlTISLfqYz&is<`
zV_UyiXtpYR{Az!_Zl6yJWG)F+wMKXAkmRLkY|4M3)7RPdTCP`JPWdq^8C*6I>gGJE
zne|jt8DC#8jGMD27Zw{#r!Otb@aM*KPpivU^qA7N`gvzn70SJt(y}>in~!HfKL{77
zTo3c?UKdX>x(9v)%2QpxdY9$C18pxO+OaTV^G+XanS=4I%7}*`_~s!`%`jp=Abt6Y
z+vw+Y&y3F_x()H$e@L4*8q8sP2t6qe2v7KG3;-F`-iBZWZ~q)HyH2uwZAlI-)lp~`
z3ir!`j}80_UM#QzJ<NPeTcP~nK?qjaR^qhx?xDloiQ!q_bgSG^^K)Q!JxR{o@v5Hw
zhq!Wc(Xy0%1F;9Nw;^?UpMi<XhUZx&t=#hMq1JVoPbVbCyJOzisL+$`VSAS;H-VMC
z-!I+TJU9%2&mwZ)P27FT0cgjU$Kzw$>@}RLPJyMlx5WK%laF~utaH?3-SUNnzU7Wc
zxp?6ptAjfq9P5<=w6;t3)bR3Q3eDZ!MQmV7W^b$?eFQ5;6Z^D$*Rbk75Usv6l=?X>
zDFeX!NmWy6YrgEb`pg2W_lmE2%>k&`X1F{6&n(*`W)N@xQ^d#Kh>6>j#Uo5CLC_o2
zyfOH<)UiI?_wQriWiGliFODg$o++Z-{lC6BfBzJIS#iWultPLEuImU^p0EuvKzl3*
zuWdBR%C6x0!OMdv_em}Nx{O-%rcxi|{wldQPJBs7R*)I^srn*!Rhi}pSmKZgD0b;l
z;+8;eFJBGE(V50D;}WPDh}v7Pj7UBwJ|O$%7xUiR`>4nXu<1IMz3}K0&aP(?V5oeJ
zhWq{_45MoOB_lTsX?50m;H~r|cHdl_OWbGREPWf`l{@URtvdaX;I+4Qptde?-<*rT
zRnMqpAWB$z%1?axn5Iz>m+p<98&NaH4|pPdnvOp(k9xck_*h-OQ|amcM4X-l4}>wZ
zGj(=xGBdLM=aap$6%0EO6VX5KL_|dF++3W@|K+p(hyUZpKO#mk4;Kj)7b6!lqJJ~~
z;TbV~H;5QTgov1l7)^}6DL?-|%KxT};`Vkf|4aKPJrg|>5y!V#<^L#s>-{GPmj7`^
z#Hi}&U`E8KXk>0iL{7x~FXxIzPG;Y>nE%_CQO?ZN(n#3egGlF_#q=FGHxV-n6BCi%
zztly(9e?XP6S4hI2MH&8SBL)<%)g!di~CQP?-!%Ww`(UOJ7<S~oSAt3mn}u);^b=f
z-<HU?mZ+JVrHPrcgz!Ji|6HrGnX|pClZlx#(Ldv+4D<h88s~TWpYi=?q-4$P%v~&q
zxc(<BaZ4K)GbbWOahvav6*V)lH~p8V|0psOak6o9{A24sQ|6I<q3P{`Ce~bYrn1Pl
z$;UU(mjO+dL57-03|$i(3<R8vESeid1dO^-D`YI13=4IOq@^!I<R5B2bB#kz6j;w(
zk3?{Oc8emS?hd^*j*f}0=t5erkH$%n;_U^((DCH_)wTW6z0R(tS5wVX^O~a~LPab}
z8U+>KTUdr#;`jW%B!FsMMJ$RVVEI@H<VnY$7GEkZTuPPkd9r}b_fvs*FwD08X_oRR
z#phB#EABx9nwe4Im#J~xF1}A_{K;`$&9UiUre@lrm0yJG)JY{%nQx{=%vkH3wR-P^
zjZ&!4+_Q1<ZjU%gCGy$4IVoeTwI3MGp!0b?rd|ezHJY|h%)~w{36c?|hUA?v-}UWn
zMn-=T-6AgZVM<4v;@MmLm7fS53LToDq8){y(2^pLW}6OfJ)#8&JNkZ2COPpG6sGGZ
zV@S(5!k+`Jk}ylBd+y2}%uke(87SAGEjx*6YlqM!DL@(Rzi=ljQXSv|8Bv717>5L_
zNdW#rCQ7<C7<n}DGJYY+BRnuz{Md>XHD&v`Sv!iwPtlVPx_Je`nFQlauJwa5-F6ot
z5CN5OMq;aIAhY7JHbcZJj4fwf<nIUnpfMpbhb`o&a>P*l<AjY4OM^x;<I6yUc}TD4
zx;A5-aUpH4EEIWz<{ujNeUpJmPMcJ0<#aj@by_v(i+5E}fmvDZKAYl!ir;sk8s2vV
z!rGHdEnb)#fc3^x@zspsngTcmgYH?2Uv86V!;{vjl$<0;=XRMnVm|tb3k4=t@*o^u
zNB1Y`8$#;*f$6CZY3~ejY+`KTHI#T+KR&C54ZNQ=m&JS1ho>))&o}HGFUET!?Lh<D
zFEb#UZMfs-kYAEVoC<rg4JdgmB@#uHoK{5or<!sXFVuQ?fxnNvejIs#*U97HTV}C@
z9A)8K)gl;AR&EG4OFTeuqpn)3ccuMow)+Su-#bDS2+vYI{4LtW71Wmd)8tI3VZgYU
z3Vr;K>?>W4L|*aqT79=nv<a*hvg5p3K|rL4GX35XogV4nMg7L0t)_g?3S(NqY3BT#
ztF3=Q1;y-(({q)KfK@wON%5E<p54)s+&T&yS{*5g@g_zEy?uvW)Z4RTg<ka}(pqSW
z^&!AvmLDz2uP8lM=S4loZ;=5Op3+5+VuQHCP}KSYZeEhZDY{_oV@=YelSe-bK+lPR
zeGVTd9uJkn>za0HC*hkoD!V0rccyP%NxPIIt!xpAW(b^nDX9{q9hti)%g)or(*~-}
zm?+|0D4RO!ZO!+PJGCWVO}m_9xhW#dMixReDExygEIHo9pGOkc2F?}UHLUUnOJ;29
zP(Kw%WL(lP%|0GtIii)xL){dJMu2y+ny^ga=$c9O@P^ou&#>;Yt~<6?8N+-U_jojm
zM#dYs>+kMat<!QBjZ?L$uIjE!t8>0{z@inOvLsAflv^>kh4BaVq`GBu<FA8I^Cbah
z5=LIBdp>bWMYekP+-f}K%wcg3dw)vFgN^$?&OC^&W%B_AZ>{9CEDiqDk5Q~NO0{GW
zXBblpbZWmJWtP#x0NMy)EP^UnW(c>u44dUr2&<ktIhUPbp&D6kMq+5R+Xb53fR#{=
z$)ESu6IM^C(jUXkRqMy>Lyek8^E_7Wb(d?JkNJr;DHaW<^ES;aGTy25v-*bXs}yEA
z&Eo4~21Y$Uc~kJUHSer@xir}MFnl&jhR#lB5+E1ly?ReXoC`3o3hq^%A7o9aHijX~
z2JYjP1czop%76$&ebMu~hswZTsZ27N(-_z|=HbWmwTo17udp#=)JZ{I^QA{={t%Ak
zp+^m$=HBhqa{1(T6X*U=n78DiwQ5_r<)}gzDKt`UOcxqgf~=A&4Prz}LSvyjNGysm
zW&TY(n1|$^4xg6A_&eB+?WdWtPUTAvIRc8XD_1zEnZ?7I9#SNU6$x`0H91W&j&e!G
zx>^&G&AU`{qUodScvE|-bvTXOv4^?NaTs)fkqv*H<j)b>bC^08&C7DNIGW7p@vUR#
ztT@h}yVX#{!?;r`7R`RD3y)M07;|=LyW?T7=5IC*QFf36C}D1^x3>i%z6gv_XGdWl
z1QnN)sW|G5HKr)X$P;T}=_zq<V#tiAxVJ&ly<&%l4AxEJabDIrp=Z};q~wro)8;`M
zcI#Un8*!Z41Z>eC^FH=34tG?v>$l?TM3E^6c$kTE36~YVM;S3Si%SSTA7w4u1y{2J
zbJeL4>n%N6<da{-?^dIQ=e6s_Mi6tgNS4=$Tr7Oa!al0>u9Z988dL%Yg%WFow+lQP
zZ~H!p1II)I<Z<5d0w9IM32z)sT{ijyE~Frr1^1sf^ZNrgSHlKz#~)IDYX)am=Y+!@
zRM@d_O;H>%vcKmGExRopt#;v(Ga0EtKD&G*oqIzKTwtX|lVNmLboVO-xDFQvlD7PG
zH;_s!yzWX=%TnB`OMe_BQbhaRsm2k!@wgUrm5Kj85xkkbk$ZcxZSc%o^@_;r8Njr;
zkB_nKCK}3tXXc-O1fO(&4b;&w$-p5drB)U`1D_S%?FW|@I|pA2n?k1@lyVfNE4h1y
zQlhO6pBAOZ7dElP!&fFJKv^GjyFsb~AeyXU&)yg%+o${$(|#{>r-DG>-aIRK>|VTF
zYn5Xj+{fP7qUJTeijs(|ueTF@zcpK^@x0YO3IGI)LGOYIa*JjEW(1hv+~k}zDUO!$
zH*&V#-nP3kuD2bw@z+cXh-m9fPxy6B7l<f}Zyx6@8>JFZ<x<5)UNPh6Xm;Y36_{$D
zlXHc5DUj!dy<*Fc7R5=)I+P{?Vx(kcvGPx$BPJxIEwS%XU&q!6>sJa4tD1P|h2~NB
z(QXB^2a32l@ga&<%>e~BELMbhIwa`Z`m8-&M{O~B)ip>{$&y+#1)+t?+E|%q%kS;m
ztMD;^sI5P%8W$B0i*Gy+K+yT_QuA~7@=DlSa0VqOjlqqB_kv!^(pF{a<!L-J@NqFS
ziDcIG2=Yw5;C4*J5XQs^?{xZdlag0?pHcTAr%`jug<<nGB`p$AnL@s{<_owvlBlKA
zw3OS}KBha+Q>U}23JjGvZQedws{^>Ngxj8X0z-t}fP;fU@(RLL+_ks&VLz(X>DMb6
znelO0csVCmuL7I#fP({0XD1kOL_&0z5*yw6i^X7$FQp)k^w<?MqioEJc)FbHnCe9u
zt-p@XO<M~JmqKiHn?Qm5bwXdMLgGH${2BLx#;V+buxR3&j_vER4aIibb=y}JsF<^#
z)!|X^x_2te)45#;6`6hv4B?0tl$pl!4mc(o)Crn*=ZcvFdn_7sT1SS=Q)E%j9KC(y
zK)2RvN6DiIg^{Pt#DK3C%BO)#2VS^MxfoCz`szFBWT|peZRvf>Sbb%MtpR4u_BceB
z=oEsKpEAzR%9h}a?l$opy!>fCETy_B`$XcqI2O|0lKVM_^3n=RNl(en$+E|MSj2Ev
zQApW{BFI@2glb3Er&DURkph%yw1-pDD>U|M2)*{ns1Cv}?$3g4Fb1_1?=mkGKGR<m
z?$p@<?cxcuWGNI%v@iD^a~xyZdqnC!%ZVQh0?W!2la|<XK2l!a`@OTO73Jx$4+|6T
z<0ZC6NOF(ZAxmI*aEqIy2Kh6P8%rI}N4&_QV_FmEnYzu|*~*Jv^>_vG>r1{@gB`7F
zP7EYL6b=a0O97zv1co+=2M&n&BQbAI-+9u?s&)@rtgX$iwsCAHsKmX>;|U_LOdY9m
zaSV}wOn`v(pq*i&)Xo;d4cwSY#ygohwTJWj!-G-e*AsDG3(_K~uAM;3uiZ39<bS`)
zuO|po=D3iENCJCCPY}~apvdti#Wu3u7m}WSOufZ8HU{&H<%OCp)cSJD1=_e+k2Wt)
z0BcFA9)vp|%eTnx^c~44ZfAGt1Y6G5h10bVZB2^)l@qa_i+Kh#Dzn$IA)!BF8@YD<
zMTA_UtVz*$b1Rg1`wit`@{SK$OxPJwo^6*G*0W8u(2Udq91`1VL<$SCe>kE>l4#>D
zB4Xv(KR6f>utz2iLt2vgF^~eFzwU5t8L3N1+U*Pbv~~}F`m+dKQhd<G`Y@>y=61<j
z>$o0!Jly$mFfk9Fr*!O$B>SWL=(l}fpUGwe&6r=4<8t;X>v4(81|igY-BCstM;?0V
zZ=;ctJR8`ep}`>`Zvlu<GN<wh%qn>Cm5$VeT2Wa!KxR)4v{UC~KI8Py+k$mnVV%z9
z=OrCvKb*GXO^bKtgMEWps~+q=Ih-+^@u3^XvH8E2{JeIa(fv?SMs;+tZ{`WBw<>k4
z`#)dO;^)%I>tyy)pWTx-9Wlxo!^Jb_lkVHIJ{z#mGG<s#FOHBsB1Utc8`5O_9NjMG
z;a@b$+-F3X_l9!$ypLv@e2eXHcuI_Wds#Odsy{!Ec}s?)dPLu~xzE~2_DobHe^HT3
zQ;3%(1^+&*74Ry-c1v~DJU761aZ~(YhF1C|DIE<9cp<e<BjpGA-O^LRd{9N|+NfV1
z=A}M-ZrW+NL?#(>@?^)$N7e=3P2TG3Y7>Q-SPv*FM_+HL>6KkX&XVYKUfOIqx>2CQ
zToyp5-^0Nd+ZVS9?fzcvax;>EX~07_Ss`~y)s1W*ph?yJIc~l;J_3%=<qFmkP$}H4
zF7_-<fo*C?wL;J)oiYHeH;~%|U7_M`+U#EJa{H$IZijB4;?d+n`NwQce&%tFL!`x)
zeXc&>9f2aSIY~;0(j-d2xOx;{dFDcNGuIy`QN3!l&3Q6YkN3|MxwX`J9%E!v)ba%q
zr~MWhXGLhGUc2eXE4j?FG$l<MW6g$cd#96b{?A$5tDdhRK&D_=(&2H9KA*v_MEUF{
z(^0yKLik<(m9H@_=p^wyUf`M&L0wZ~%OaB#QJ%EV#Ofq@X-p7&(2M~70F5M`#^$xJ
zw0I_8e~jJdK%IRhuH3i%X9WSYr&dAQQ;c?am1lLHh*SJmgxK+~J(=Fb-yveCgyKbT
zCS1a6Ur}8@1ePjw?DvNW(78X#hS8~WzGg68CG<$`=pH0D1Ki`k{62?8oF(b|8ltxB
z5LboWjVi!8%ncPZ%ZbNFR92j$mxw1^{&edd@Nh@5rX}&L3_#(F*Vm=R-|3QYS`e(p
zSsy4fPX5v1Fd|+3^$1j9me=4l7d2`6P#Hd1xO$C3IP7jT6@r=w>FZ8XR)je!>x9+q
zZ^JcqX~y7$d}f5$7TCe0+Y_6dM8iU8c{68eTEJ%D1>`M%<E0#7i4(j0J0(}_3}L?L
z0MC;koh{hr_i=m;&n><djOUy%SeQ*2*r`B>_2T|hiYW!@JKkb=JdX*Xa-26G9`$|!
ztpKLf@=fw2rDvhE_)|66K11`M+pI~WlD<O!0o^;^&)zT>Y?+@Ot4PXQ6u?v@hplc!
zA2GVZ$HZ4|nf5gdlSX1Lh%bTY)QJ0Qls2&r(;su7BTCTRk)E+OBnrN#EL0-W7qcG9
zHE<@_&wSPSbb{5;84%p2FiS^CzJ;MKAu!6Zv|`UG-Zxj*<Me+~58AT%X?-QmcJ&kG
zrB~RK*$HIVK?zh%rvw3oGQE|lfg({ABERoIuh7U`FK!hk{ma10M@y|t^z)mWTvhqK
zssgPpYeMsXXM!gQyp;7Rw7X&R(+DVTvYc$`R3Ol_W4;X?m@L{EaXuopbF%!j*PaY|
z#?@BEPiNz<ozu<OFfV$M%&R5~^q&h}lY_?m!?^L$O&$>&4xh&-aC>y|G>Mog(F(Hw
zJIH@yYal9ZRvs?Vi^M5lfpbCAy7=`(2|?c|+AbRD$$J~o80iy!Wt*O6l2iNpfMLRS
zwP=X~OB}%&adjAH6wVVYW3=ml>0Gw>22l!LKTV-Q+DUti+<w31QCo*e!;oRP^K41~
z$v8Lm#e@vbvT;@wXEqfZKqhf97H)aVN(Q1O4O*`p{NfGP=rb{rg*qLKdOigYmGV2j
zW-GXrIji_1&pWsSYlJjs)KpXg&Ts^_nJrx*a)`4c1tUb;4{7Egqz8QWjjmM-c)M*!
z2bdG=T?47xvCn{Z#|x=j-xKjmySEAExf}#1Yll(py2zjLwRaKty3K#OerN2E`CS@Z
zcPJulxVK1w^|^@RnGKX5`MS<OO6%I3(MJ^+6U^r%;7b?iIIh<Z>KUlSuNG*E9q#BD
zLvX;5>#c<AmwIpB-cB6I7Up%XzW`KejX$d^^n0{_JD3M2tUN4N+r%E_hXV;tEG!qr
z&J)NM#&xRyHnfLIuRS;(x`Sx15iCLq#0xQS6J*@AHZUY2+HH`;&JKy&4yVwse5M5$
zNa4SnLMx0rF)*db*X{mRz&#kXHCX!2eHGq8?~BGO9m4}p5Jqv3`a%E$%fL+#eT-U}
zUU@`S=#`tqsH>5{G~H`s=3qzZR*+`cmFC6K7U-3;VEQbR=TzerUCY}^W<|?>Seze>
zhAJU_oY19AhNQn5>p(av-EZJ6Yq!A9GYu~?NqwsP*$+c}CXqE8!czn=4-P{V35=(~
zceQ{kG+g&9z$?!nXcHz=o&;B6a?(7FLJ-F5Ogx#B0fo{*wG)8`(3<Uodotj3b%u5R
zVjvhWP)(mseITDQz_1v-tbdpUriYIqcP)YMz$RS#@F*vicBp|HG7W#C{#XTL%`|NH
zw*>i=>qV8iZuO^L0^&D=`$1uN3*v!>OAbPStVm~==pP0y`xjJ9j;Rki1cU&ENncQ?
zdk8j@$RG&vx5;ym7L$Ch=7#5Appm;iEUR1Qi(O#GXabBs60lfB10NvbpA!e9;O`T`
z$RMHnBM!g=p_x9KXmBx{&x)v_SWKF|zUWM)AeZP&if3bx9DV+z4$}@$&?k&LmmNRe
z?HD%}rzfv&1$(+7t}v}!MGQb+p+?YWI?~df>;m=q<hI6P`J7$0=7aI@y~qTcfweYW
zbIJ2N5HhfNrrC%@!tC_awkCtCX<SAFr*Z;2ota&vpRVPFB%cJet>Q~ILCb_ruogTe
zIKf;ck>ly|gK!h$r^yh(B8lsuQQ|{_jl(&6<52El!>t2XfRTb?uz)Y33h<@NbNnsd
zsdylKKsrGHU>**E68<5b+MvC<K$pf2&`jC08%R5Yt5X&;;1(36Ab4Dp#DX`0x^Qri
z*xLSxwU}Ulp3$OeK{+B23wnC}N4kr5zg^<5b+Gqw%FiC)<hV?(|BGw?1G4@X*Jfj4
z`7hGU{eR(D=6@jMe__&$|9^Pw|At@n636X=n2^MtJ|ne?qr$^LrO1O-i*PY~OB)G+
z9^*;SO|a{Cu6Xw&l*?e#2cEYo62cBPesJ395_=*xSUQFnxp3^T7z7EO+_3PZ92!bA
zY<2Ig%jRf6XRO<5Ia+NnRg?!F1R<oc+thm3JI5iy0425<GDly6bksQ0Rz045Aj+Sp
zORDJw{R!C9=lNQbgOXyq!j(DRZ@(CQEP3AeAxzN2iak1kfw_$hm(!77KGzs(g=G~o
z^~pPqXnYEJw+XIxm|AElEvCj3B^&Ze<$Lgp_#==TU0#bco0X7|RE3xyIxjp*#FS=X
zx+srT<|u(xW;gMLNwiqlcQ#F_My!Tg<z8&z32>G1&F>QL3^h;1W}D6@mvD|v^_hIp
z?#%4cJ}T+Q^yr}Omfm{tl{mrysiOSEa%AjGnBD!@zG*Pm@c9LtO;(Kff9LF9Gx48E
z`#vY+zjMa?5AgqA4E^88{Xe+{Q8Q-~Crbwxd#8VZ_<yAv<c(~<a|d#=+G<*2w4!EK
zM(VCA-;n<Q$i<CpEp0rBsQxV?`bS3nZ=sEm`8RgY@;{ow|IRMZGc*0ay3VerZ5Rr}
z_x%;VK@?3C+ez$%yRLvhn*@RluDvu(EkRN_sWk1^?>%<Y#<awW6u&wCI3Lc<Q>l`(
z%T!4wbdi8EByvX?9(wa`%Xw43SB(2{^R6UJQOMkPX@AtelyHT1xG<ah%GPU;3{2yt
zm%jRVWqBA+o%^9f9-<s8$%r6~i2@;%<7kBGwtsq$Pkw<}P^7&2-E@_QF<(W-x~^ZW
zjT-{+)9m^}1^^R>oB4!<6LZ@DTG*y$S8ukNH=P{>zw(=1;-`Y3G>ITDPPaty-FuZN
z_SFq^gtw<>AT`rOvO-hY@T~L0x(el`6RM@tO(n#Ou#Ol;2Ro?`b8wcz`3yBd`ytjt
z^a%=X51#;$+TV>OlEdg*Gfv!b8589S)%n9NDNY2!p7$7QOVDe?lEj#kJ-K$dEkTc_
zrLnGMVkWW~T%4}^esg^VAP2Q}X0x_sH)~ye5lVdl`q$gGxgnT0y}6cLN}kJ{i!4ox
zZ(N>pelcG3KmrFiw=k&vw)QFZF6_|UfqMOQ)oQ|-NGE)MF{CBQ*op;BsUn9zbg^d8
zI4_XoNCVuXBt{xKl%z<5ox)ZlO{pwJ)MJe&M`Kl%Q%%QqSxyBJYf7e{_o9^4D1+Ee
z^J6<L@E4bRyWSa`Zs)n+i~Uzotmq^0+_p$M#XKCahh~M``nm`t(74`5S7|Bq<m~MB
H@ow@TfvY3y

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_100-low_error.pdf
deleted file mode 100644
index 8727bb0cf9a7c758407d3542771e16dd6ff4ca7c..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 60874
zcmV)aK&rnbP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58fy-km8yRsG7pT8oT_cd-Z?XW#P
zyGVdUsZ;_^wGfReiih-+yYU`Ez`w8Mh%rWZ<vn}lK6!W`xZC5Tr$1LX9F7=K-p<GW
z{cCyrf2E%1+kgIX{Nr)H*M8pf?eqWs`+xKHFaDqN?Z5uFqrCl($N&4ckN@`%$AA1!
zk3Try{=cJ~Z~y1pKfV?JWc>e+&slpPXMOAae7Cc_{dlwbesz^U-u}bezx!#6|MXwq
z{^f7Sj84wCa=(wun$1Ubd$-!JS>As8ar}$F|LghJ)#h)1fBfaI?eBj3hvQ%U_G%bE
z?WK+P8NIakao+->n?J2qje|oq0AEx)?==-!E6T4cwR=3qk(E&XqSCBr$^RF{Z_a(2
z{r$Rrf9~!3bKl1OJg_K#F|gkKkFyqlFRHcrUY@D}_@Y{!pIQU(MYYn|T1-F6-<|(5
z-|J8Ie*F{kf0j>!1MqrqHs^b3GpiB!qT2QN-=}H-zNj|Jr`7;`QLSBU%~ycsZ?1qn
zgxC1VFQ9yX1?=&^<?+8cH~?P^uActCSq;D!)z0fvYXDwXtG7M3M&OHT^KnS@l>aRM
zp%r+H>nvB9kAF>jKYxD(-p=o@Kpo?~_f3!!_+oI6)98Gv2H=Zoc7JLOz!%l(_|zJJ
zFRGRLo<~5GzB~I50oH$C0=@l-{r@D9zm~@3aSm<gMHIiNa%~%T6~6fMKHpp0I|bm2
zYOTHBE#*DS-<<985LWk3_WGZY_r=Pm!2$SUaOL9QPz}Hr)z0>*H2|-x-RJwfH*t^h
z>q^)4Zg&cM6u&w94>{F-veo~DvNP;?Tqu8~FLGSe7q@}^{KR~peV6i4{z@{v+g=If
zFV>0;`K;etGk<)`*Z2989sg&v`@Dk?sGIWei@mhR;riI~<uU)`v4wx427ITRZTc){
zHwBbe%IT<nY-cqAFRNYMZ#G#?z{_egj;O3A;AORP#*HZJCGw3$xbJuSdJ(?!16|_m
zd>UXPuSfXU7~946QIEjuYLCO=sTRtwD?QGk`c#X+>uT4&O``OT$uDC*eyCs0{&&u%
zb%;MtB7xTfd+djGm~8cgysTJ@`G3xeiM+1((7EoX787}0v7I5jv!al1tVMmu^Xu!i
z_>NXqd-L;U>#2~}LmY7f+$surU2zsa2DgerURS)k-{-c9LS9z1^Zqo(M80)4Jao`$
z{cf*T<9j!h#~J)A<`a26M4b3rMIo;%_Ve?xDdcs<$Izb-vP522yyhp_o5*)o<7)5K
zzFduO-B|AO>GVwG<q+H2Ax}e0<aNbze>y-Dd0o+LujHlI720@~!2-Uq2FtK^f4v6Z
zIV;*YpH5DeUk`5WiKkiwURRsDjEK_93LVC?tdz*>ijTYX^HG+_H|D>WN2_1Y|93Q{
zUhhw5XCkkMxc0>J5QV(1*vBU^pUCTq*ZE1zC-S=DY@d#@M82~ckK3euy&8Ywj-yN1
z^Ofi0?ej=}rQhD?zpmatc2SAW)>+@%@LSsFe*dr4?d>dl=tJ{yfIkGzLyG4m`Y-=e
z!z*W>v%akx)jiJDd>fDdbN&7ZaTe6;rUgO>&AAW6OJPNe(ts7)E;m#h4)G7dc2U>e
z$FHjkSqjHOvKo<sMy~bO>q9+@k5a>Z+>x^ca+W8=wuY7+?(!S<@r;CFWC4ErzHIwU
zAa(o98u~(3Z;mHq`_8)6KalM^Ku*m>_o)np3m+mB23|+JoF9&|sWZ)|lRqjTYpQ6u
zG1y}kqWL2*G{NRGdcOBh<&u+SKB4C}0!PLTd(=W6qJ05V!v^3D#Tbj*d2hAEauu*<
z^8pl1LLhT%=kebThq9&O2IaYp$@l65$<0SZ`^HPPA6tpd#`U6(OU)+2%`jrCj!T=@
zk;5T28`|GO*lav<I&zjz2=~0}01w^%%F?oqXUnvgXUjq~0^gVq#P`HAlr7T|pDp_~
z978Kjq{rX@Ie;z2Vm9p?bM$xqci(c4vS|Po6V<hMN9?)>k`2ceYud~kq5)K&sHT-4
z*i%i7vz(2`mTKH}1KX#?&e|c{)<5=-W!qlT3V4aj-XZ-S5ZAq9yBM48*cztE7s8T{
zwuS%<$ag~J%&W|)@7M<^jye{d;^=V52Uj)uiJTfhta{PpcVFd_O^2*`AVb}cbuRDy
zQ<+oWvB)LoAXc>G)b|h@r)Ium1y9X<B0~d+H9fuC2OuBQxvfAf;i>%}4RQJ#e&T1A
z9s}&Res{4G7lKJ>v0x8?3lLj#AzXmwYxDq&tJv^vb!+}(`!0m@&&RHmdo5O^yVyHE
zK|@36Uhevg{}g*ly*M{(*sy#%#4lqZIT33K`n3(*C%mVq3kAm!jXdOXzqX<Kg!dG6
z%}X41{JIvxVH;+6#N-3=?hP%!VUCA}Z868GYVc_=M9%@J#iz0N3{#xK&wTb$Ju%Fl
zB%MKS^%Qo7+3Om0C=d%VeW%8UbKvV=$AWU?F`-Qh9u|j%<iKM-o0h@6^cZ!_RmJqB
za#S&UsT@_zUemDSk+R2X9f9y=b?Q4Yd&a4#dW{|WOzcK`=U?>0i`kdhdXj(@b7wkt
zE9TBn@_E|?V8uqP*^QXC6oD0!lp?TtiHlMAyH4>}Fl|-+D44dQ)hIDZMT-$P%ws`A
z--$^o+J^<Rlv-TDEEO$C{5Stlb|_}5XnPb))wy*jrs~{!gk6=oUBUF6TaRK_rC2PO
zuoR2Yh<}KC<ir%E26)C4wOe~6dg6#a6m!&W^(gwbkggB;9JO0LTAHYr^%?&iK9EOu
z4nRIb?cVz1^U>zkpS6A3+`8ktr-i&c0D0qc>yA%HOObg-DLyh{ybHnHj2kzUHrW|y
z!L?oN%u<8B?TfvEVqE1Ovk?C!FR1H7-OHxW#8g~ce|%@OYwM4p@e_h!+!*=T`r|vJ
zjjca16(jrOC3a=vhtr07GqDGxQ9>zS2zxUzaA}mGrmqimZsrAf+g-hxK5$(O$Hc(<
z)}I)7mxengM&7sn#K0wcVI6lQe(VDm+tzgGjOj(30|S@RCb^4SfFmdWX32*JwKFaS
zhXbas#2Be};+C+0qL0KN8%nXqO`10@4GX&XjToQAFm4eG;a|k)D2I;+6h%xC?lDbz
zC~g`H;gZD_1eT)!u!dDDhRZ~&nkBy&w5k=u#h^(v4`}_ZN;?`OezlU$0~&mjbRN*o
z8%r_3qV=No-Keb&Xx2^2>VS6LpseEhvdWwnsKBjA>Wq#7NG{_}v!0bWGf-*UxpgN7
zaLW2Hpq#c-`v=Nt!!3M38GV$wf1qr(lbRduK?~u^LA7irOK^SSuio`TlYkx#TD;v_
zG^m4ekFvNZEr6>Ab<pmuZ)-fqg0Q)p|97q!^g6p)@+KszM<{ScQGG1LrK3r=#qDY#
z?3n9oHr21#;tOHFe3u^%aXT40Kex{LVi=q8g|HOevFjay<~^WRS<3EEqAVphG$xZe
zjBDCLR`-s8q7o(z8j@Y=8x$hDP>P<W(5@ll7sLfD=&o!51KNxYbtSYJ8=9#2VH^uW
zU!bU1O7c)t7Q)>RJ;hRxLo2Z^ooy6Mc*=4=->u`{@rjhSCpKW?kN0#V%>p>tvEdiO
z*~Y1Dbab+QV;UrYJI`sO1dfZ`Dr1NpXR<X8vEP^mSpsmiTL_2PaRwX3a=+szLvPIm
zM2{hranoC6oTZ(|t4T6<9Is~Fybt7x?_z)8>i0lUiq2M@7;vI<NMDW4N>0aJ&;fll
zdK-R=#{y1#nB9dj*JS3zb#Wo=ZJdcF!QC&M8pdLDS4IZh9UakEqqowsd)O7tRqF#t
zbQiL`U;c0Q6z7{svg0bb5cYK7xVECc;y5!_S#3(n<6^lGY}*dwlslqCw}zLvA8`bk
z1UfE=waUQI!}d`npL>t9XF(i(`~g=ACW#7@DlUtw%;DomsCS4$KxZ_}@%y<@C9iu^
z*Z4b#L!i<gaTqR;3u5<i->;KD16=T{gm}l@y-J98*yJ4|;JuRq?l(#=pRD4OUnSJz
zO6dUigt2!hMbBi<?GWl!Mve}dUN82(vS*U=xMnVd-FFGT$|yz8q_Fq6!`3TjA6M2Y
zJ4mnU9pz9_?>PSj6PK0|Ts#-VArv_+a|0Fco(_kOdt}Aoa5z-sZ#w=Wx~IdUN3-0u
zxCvGs6mbDP9N~aY^^6-TE}#ztCI6Y%t{*;xe$8{E<F;05ed)NX)vo0@qZDnl8w&`#
zbG!YQxXM@zTtgk{tkb<*StZs_&ri68I)bg$Aj?%H7EgwoHnDg*(r^V`NDQS-ZY^CY
z8m>T9SBeJFU2&&?hvF(XwG>m-q&~NaNs__GyV|%k4N|)5($PXnR~>ncQo8EQYyS3B
zWe&oH)RB{wYWxXCh-*hRS*LLMbcp3M{)Fp;7Yez+8m^xUfzsP>iKsdhar>-Qr((mE
zq3QyI+h?s+@(Z`m1#wik6I7j*xPLAL!@{MYR_;MwKOI8z6zuh#l?uMXg@gWIWtM{5
zx+4%2xPUH*BW>yqw<krpEcXp2-^$PW&Zt$EtOo79>b`^vs3RCR1-DM!25rY7w9SYJ
znY$WAHxA+k18SA|tHE4aOYT@xe@v~jKOA^fe>iYT>wG!D#q$BN<R8(QjceyZIB*ys
zt88d-?K~X9ibLnFGO9HSXI<WK^;`&Ng4V$*1)vpmh}*rWL)-;L9fEX$@?7&V7MD+l
z(4kWu;tv3(xO$@G6I1k9+fG=TimrwYGPy|kXt1aiK6f-o<RWFHh1z{M6rI6kb0L@u
zTsIv-*?;9l7fReU7h=#`4U)LX3K&<*1yp{f;4|1I7Jb94#O*T1h~I`m#umM*n46i3
zE~2<PIuc7_p&XY<wGJ1@g<uv8x^R)2W010Ca*G(83Cff_v`f9=JV5;|Qhf{tpQ0<R
z!QxY<1cgD?mdUAsq%BgAaAR}?U4*PHQ)Yh~F&X&JG5^w-;%2x2&J`X~i&QAy`W6&h
z#^Qyt=;6p<XDQOD3`UirrzC^?ELYAIL}<}%+F&p#Qnd^sv|O4iXu~D7FI*xQgt@{a
zT9G<tO+)8gH4eQ%X~LDU7Aa^3qedB;Fv!Ouqbu%%j&ytoBC<$j!~Jg|m_rE2A}!9K
z&K8<#4>LUd6y5r9<68)Sh%iYMsCowRS7gw&8dvQibq|*}N6<frzbAx4$DC676{&;<
zb3&0h0XH;9(Bq<!b5cXzuMb7h!{Io;&_s*0$Or;(0KLcC0+GX^m~fezaU)v@CY*9k
z77K%Up>$1nz12D<yi(4|L|rNAc7$y;=phwyO<F3hVUENwaO-j;`dp{lN+eXuLS+_r
ztf~lT!<EXBScE#+IM$%z>R(ddtrTV*rP$TdcX1hdMq-ZTy21O8Ll_ip?M3gK^?E8%
zh*4>-VT3MCW>nl_00Cjk5HA(lVUb>qd&)v6UJ%p?$dRtrJIZJr@~3vSt(9~aiK55X
zN;xJIRPAay5w^^QY&^GUrm7TU8!#|+T-k=Ev&^Pxyv7~CAxs4Hz72uiS9BSGhW|iN
zimQQ&-Gex|?zosgAvOMl8v(jq$wv+7<PKp{D7tjLs1#j061&cC97iB*9UG>yaqf<)
z#)%ZQtsiz#<J>~HXcw9DYEk2fu<_VI{vkBaJyq0v^zT&TEXNN`PKov8k9vpLG`HEQ
zrV~NS++`<AKI7$9L)dgs>7Eg`6PvEwYNm$sW4YN3c3rujN>i;s+CXJ`Mxco5@>Zt4
zDxhHPu_?=?FDHT%$52FHQK}Jzja^x;rxKpKiY|h2WFDWO_@bOaA4k$&>iH2&V9y#*
zK0-7vBsM67;S&%OB-?D^Z<NUKfTD;QG=4Jy)xZQ+{fU6^)hT+LE2ny!NX^)FJ3~{>
zlA-66p(hneec>GMPtBfPf04*j-_I5%n<qqdVn$9_88-y4OPa>h-Z{+&%J#fCXH}I%
z5UP(AJ!@9NbIl3&liU_($?pico;KTA-anV)N*<f@#B~lO>NMKfCsmjo*?u2~1BE{;
z%q#U3{?O`u>%)m$`>*#{$PTQs;b-O|U;%7M0NV+%QE%P4cIeur(E>h~*-i+sg|H!9
z2p7brLK4>d(vUU;qPwHaQ-kGxY!Z0^Y&ntgB<mM)KFRue!v>p2#Dbm=jfJr7f$1FY
z{ZpBZ$39&M8^1aMo|c%*o`<Cn9hR|A8IPC8?n3&fGTXi}cb#H40SJlaMc%GhqDpdN
z;x?TG)6}FFLX}*QL95~}#MP>4(``x#kW@<I;91Coc7uIrQcAh$OpSAwnc5EISWw+H
zwgpfp<(9IiQdPqpWt`7V8>p(`M5L2qW@_rBn1+gn9;vbq=&4lHGPXvcLdtzmq>$pg
zS&;N_OhQr1+zCZ$As4<#CB;)iy>-<>iMJ{)b%><B%xezU83wGpjVy?ls#wK&f4b%@
z<oTMjka(!p?Px*!{b`kX%fYhEyis9IX5Of9ek};s94^zOy24xELU^UZy3D*%g&OJz
z`izyCd8fiM%;%CWSX`8O;T+^;cOftxphT+yetz@PT^?&NFPRN+1y~U623UhRWH!JW
z3|S30<3m=1g&YC(w=@#0GOzMngCVm)e74JIz!i|KXlTB>3?`iKE~^3OyKCeZzwF&g
z3(A5DddwN_8aQXTY2cjU_<0^_(^=4F_VF?eQ`pwC$u7kirTn@OTC(VqWS2q*E$ve1
zAO+Z^8KeNa=-##<8m2gjv=v>NLz7{Ob7*gAe_Ih{IG-<0V3kFVvsK@BL*FWM*qke9
zl-O2P7Ew+duT@hMMfo)~QM^^TzJCPLVaMb|l{AQ=ZzT<)H@{q9$aFv2fM^iqL{WfE
zP1GriC@1QaMbz&S0nzr0zc74-Q+3ih%(*(%8_d;3w-ec+7j%Uw8?$rWSOeO!7qS_<
zS231AulNh1H6Al@QOwb>UN4HdFukwx#AkeB4u|+SfO)tm<Y?w!2;T-Seuqy3aM)T9
zyMw7<z@VNTDkA{>S)wvbPtO+hqSvI}HW*)s2M{3f_IPq`U?bNvN=4Mzk#8-P@n3q6
zsf^#!qfKQXmL7I0LZ*&<{b4+#9*8Q#oAiiO8K<O&rplP3xbYu=qC-&y=B8RS7krE?
znhI!jdKRk}POp4Bs|>oSMUw%CL_NYWxRTFwm4Pu~)rj6T^@rnb>JN8CQ-3&cXngUs
z$PckU+yo8%sVGHXs(u{wBB>fUY(@DJS{VaUs|F5-K|QH1gm1MRIO8|)GRt7ke7mg|
zUn8pqZt4#foR5*Z*jENs=q<T2ghCI_mGKdJlxEN<9<KQzy=C95#<%Rs=Ho$9_os^w
zlE!G4$^ZtuwbzTjBD&~Y<$ZgvXIyE%=r6?I0`%%%89N}qfCsWU4lwLAeG3qF3ipEp
z$bd%z7mltW($wkPFGq(;=l*bohzQq$&kQw1KMd?o#HPyYg0ZRTm~m9P<;#1+k?=A>
ziJmGL68-JvA`;=N;b)>sbX38JMtlOYXiUsgII67j6<#RtXk#R6y1FouRo*ZRWQE5J
z5xA;MYy-N#yW35rqr2R47~h(%JB)9YdruuuMdblh>Bue*A&+-`qX!XVUFBosNR=DX
z0fb&g*lzSwmp9XjL1pK-HWbi`Y+wv*`c5$hHvOw=_@P&+U-UYsm)7A>O+PLM#HODY
z17gz`3<0rk@)xV&QXc+d970#`ID}5`Hk9PHhH~_5>IXAAUEA1uN^faE^c{x>U8V21
zoa_#U%%&$^rK>od^(wu^<<A!}wCVEaF|;?l5%H6UZ@4@MJ&3l2Ln3FN^8D5a4Dm(s
zQmk|dhaY2wL%19rJ<=9Fi~M=pyL=@N00v)34ggj@`CL}IX-f-0q-?lt##Vr~E7#72
z)ZP2jBWJ_m6r~extegbKn90Mm$_HB~HGQy)=Ah8y6m#GbI{jR$+^uy4%iUT>u)MA5
zQ;XPI_}o59$L5jiLACeXoOT&zn~uE<vrXq;N8B_72jL2jZk?j?>aOZ3B)I&LJ@6Kv
z#Y>Pw-c^gz=IQKVxcA(gp&jv0%F@_xy79`Ah|pX*Ua#`*nC)@7`0T|$FnpCd3<7o2
z2i%dfZhqnqWb-5UAYFL1hZJShZn~p;)b4$6F6)lqtB^X~Ev0gNXB=<%#vep_-Tdb(
zy}6@Zx>(C#As1_%8{uMoY;OFF*iBb|M(t)efFlS-z!)z^6hzPHcdcVWe%Cq}I;6Lv
z7Z}uw5C?uJdVHZ21J<oPB6<}?!GK=ISpbRsdSzd>U=5G?z2_Fs;fVK@@p=_x=Lifr
z2zg7a!T=Ta48{sYpD-vmLsY8!d`E-|yVez<lHEguN_Oupqh%_+!0GY?$Q!y*x*~*!
zJ%jGfcpXF$zhz91BM}+IenFL2WDui@GkU0Y#R_HD;wq*fBnBEskW!_OxPq7%b*w<A
zN~iINg*pHs(CM9j62X+Zx^-y(?Ns03YQxB^3{KAQEl0eqqMeT$K`UDaBg77}Jc5a1
z6p-B=CyxTo9KnY#{>i|1`9rJ<szWhGAZZ=W<_e9gbT@Ch^K{%F!q@QtRQE8vN(XcW
z>M`&+gZXN&TeP1?J^R70h(L$@kMy3@<2-9AjdAB_DU1tDY>m<w79WK#GE!O*j+Gwk
zP1g{FPS@5B6k~mK>!1sJlk_c$@Z>xd#cI~@Xg{`SPKUfvT_*a;_)absPDSxeR}l6c
z8CuG?>kL1wbbVKdDkHHG$4bOanhJJZP~GEU8Je9Dvz6}gt#2KQVGpUx4R<2N=Q4gf
zV|W?AopHXkg}n;S*he7ody}cQ;h<GOF+;pF=y)NFUOw|fG5Txk5W|<VLv@dW_CWAE
zzC$xsWAyU1btpzJ2~Nj+MP)NsT#?%m#2rg7(`Ae6nL@y8V@R_!a72`682Q0}@;}8N
z?cwN^{{4zruk`R&R682Q`1F~&hsU$089-kd1fU>$4seUaU$YRiAz9rR=PXgpXaR-&
zb2c|_0H5+T9U>6mA|%OxBWK-+2)K3|Tfu^YZ{ys06hsJ;&kgS!qDJ68+4vKDGkK57
z)}tUokP)mweGyrMc4aa;JfMy8fg3qlAsq4ENJKNJp;z7Dg3&Q4DEvp`-IHOe;m#@=
z3;x!~bP-|q@s+8s#B3Q#B-hBEkX<9BU>l)nh>@c*P6Cu2lnP1e;m8>ux%el+79szw
z2c$FoL*gg-MO;LA*JSc(Jy}U^{*7B1x>R3=UWn|(krv;X`c6!nWN@QJRLm+4y(Rey
z<!th^xGeS#N&+*2qo+v*0$XG-3jnLj)MsM$#y0YpJ*dbo(PR2jw)VFquHk8t+%|sV
z-19B@Z*T@3Z(zwG<ek&gRRisij3A61=_ytljN4-D;R%?uK7L5{`0~();=>$vG79mX
zu_dJtwjLD4o)QxrLvtH>?8QmGxE;!&#}v<P<T1tfHu9KaSRnjEZy;duKOpUpG}}hn
zA(<N*S%>)I(F_+j(Ln(MUlbIUq?4))j~OWzp`^y`_#m{pKT<A2Zxy-Kj!b>1Cq-81
zWkI<n69kklQEgR5-iVEBNAwpyL{WMz$jP`$&O$J6$+`gjFR8<JL=q4#X(Az`BAG;G
z4`d@UV+pNRvZ<x;t7KDqE@|?s$ki&p5sQ@`MJ;SWVr|<1&OB6fk-j<7rc78L#|BCN
zWatqY=BRro3Eht9FOIk5u_H%Da@{>4H~)sjdZ$JZSNW0Ru8LSM+YZvTuC{%V<@b;P
zj10JO(B!!zV{1B=eQawGt3LE*xj|fZ7|+C9_=Io>Z^?f6C^^HT|Fejck!>czomNEC
zNYPWo$;juf4Pu+{0v;*n5~1vg8xLqBk0%5Rk1NoaTjNBy>%bZ%_R3?2rbZE4YHp1O
zqC0)VWr}o~0FE~jZpQ6YjGS9JTZt`pZ><E$=$TiDA_mc-xgx@5e9K+u))0}abBMkP
zMOB(e*}l8>;gu3gKvVa^t4Oq|l@W7S**@$$^GXqwNbZub5M6cu_L|^JVhFd$t8QB&
z5X<k7Q})=3+*9!P7B6igsT#o`d!=f`>nVDHtEm`rcO)C~t$OvXp+H9N`MA+uW2@zW
ztYVBCyz)*3WWw&-g6x1kB>9mkpG>wqZTpizo(8>K7Z<cuTZ5W?pOyJEXds#wpUSBS
z@`T2|JTqlal=2tvi#f;h@*d$_weOQaa(4mA5BctzyXXk-zB#uat8de}i3$QK7}jo|
zbNes=nnwAXnY&mBWD^4Z)0_9!V<P!m^ts#x1CdXH;6Aqz2!R7}$dmirey<(Qft!4~
zcd<Yuf2;AbaF^}J>Vodx<${aHdlw8up5*SGk0%?XpYz(O_bw+K*u{iz)VuB@B($9`
zYc}s)a1cqE<eT;0L`i5g_by9(v);xd@7}bTa9@=o;2ZU}=R@?6*XwrD-n%kGB$X)N
zsCV0s^gG>kH>mEa!kxlNK(_1q?{0aTK?AvWRffo|5%`9?`=&(2_UhSo1lr&Ivleyt
zO>H8wX>301U3UpH>%A*4v46&<HpO-sTVuXGcGU&I$oYzuA6r|o^4D`|(~)A;Q^MF0
zMe5h#w%(uA=KI<%2eGQxb}fljz2s{oXl~a7U$@jtVE4Y~`_pyd-n5d0@*WbaHn;0Q
ztlGU@2f88$P>#L2U&vz7_6u1o+I}I671}Oj5%F_>zL0r5gzhgy^5U`n+7Wfx-6cG(
zLVaGV;;|RJ^hRukuAysm3wgeVu4oSZc;c?=kZ#WFUx)ztgz%pHSe8|cVIRCoGtead
zX7${3KX2Yuc}w~I+@n|2S)cF)Jzw(|lDF^Sovqt7f86omyy!0%=Y>3*9aelzQFmf`
zZ5#CT?%FnJfBug!odtCN&s^z_sg%JVh7~&-OWrXWm=2g?7Lo=g^N#HXrkKawz!dYi
z8<<?eEGR8Z@!==?k_RpobvNd6H!#Iqc0E_Yn6;p^FkL-DqV%1Zxy`;56Q|f^+ScrJ
zcb+yp#462wF>PbF?zM?9ER?+y;BE}aCvK#5FJ>tP*uX5MWocl?L5R^bxd2Z8z${%`
zUt*S0lnqQtin8I#<U%%s>lxp9Hn^_%v+Pbxlipa{#rU)s<Aooq9#~=eT?i-t!c?WM
zbz!n*s*@KsRVrH-rYrAY7p5!a-G%A8_a4Rc@LG0Za_+4^v4te<F3c8%-9bydl@ov9
z6I0HuD?TxW&!{l?d#E3Ni8J(u1$6*EGeys+cwAV>#XnhFrpP-6?;=*9lExc`l{7`g
z#4n`s6Wxp14WExv)C=FB3&?Kx_)E!dT=9|YMofT8KKPpQcw+dK-H0=40qn?);q!VE
zt7r;XJn$A}MVj1=(WjUUMcay@6oXF@36@_|6dj(<EF<FZN@EOMiw8K%5Hvj6SjLXw
z(Z-5x9f<+E*u)c#WqcMM3@szA;!Wpph!3S_j5nQBP7HW|ER6y0kEQO4Z)JZj?P&h_
zxpW1^@=f`~BJZ!IKJG3H5?*Gl?60LU@O&&SUdk8c69`{Q3x_G45N}780X29#vXTxj
z1v^^~FNMRD%*AVxG42H~-j*RPcw90Cu*ADLqLBHb9b>#$^6{m^OO4Xg<Gp1tNv|AV
zy1Ud^M%ne@C}0^G0%rmbuBH>fd(^qpl^{kZ=^HK!iqQt*<I{5~JRdAVHu#|!)0DeJ
zY}IsdF{~Qh6XA4WioH1KnX$soKlH3+8AAbw4-<zFokA=lB)U=7q*n`)_hv){98j#J
zTZ>@;>D6K}O%}loco4IUWWa-%DQ+QrWh}!M@IYn}qd+$vA5?}UI8`Hv0a!*u>2fpB
z(1d$y`2Q>d0<IhMw2Ur*4-r@k77!KEP00nRF=zk}YEF(IZ>QSDmhhn$Hp>73ys&|G
zVfUf3boYm&73doR@aa$2e)ww{{P>UM&SmMu-=PcD^l*VLRMW#HRG;+N?{HnSbkN7U
zoXPhd&vKT&_wZm_$g`K5Cz0&>PIOn7@qUR~<KvC4be696c(=3K+^&pAJ4?@c@S<8x
z;SEJ2J?r88XYixPhhhNfVtB>YNFPIJ5^|dd)vIl8^WcNEbejidEcr}6`1oh(Cl6Oe
zr$ssWCoT~zedFPe>9j3Ex|i8uoR&33>WwuRJPgO_{4#V>#zD9Fh@Y5V`V6`Qt8MPy
z@Nl)w-y5e>`g<3r%V8r0jYty06*o9`=)l{>%kv?RU)#L0<1k34?22iX`^N~1CfgjW
zA(iDj4Vk<-PuKWr`c6asK6y{Sk<;iSUeZ?2>||+;#H3sXv9_p^KJsDB>6GB%yR;YE
zoUcQDvCaG1A59m)8Nv13PTf)P)CO{=4?e3cZm4uZ_dT;YV7rjqysr@xZSt*d_^6~8
z9?=|;gTK$cQRfU-e9&FdIp4Rm$s@!c)fQ_O`-bbGNxUH@!02*)=v~b=59@*6(7_t=
zYjd#<`DKbz8kAo~-PGeAoCmD43j2})710+%$>pqNJQ89sEWNG~r(x-Jjn_9v(9jiq
zGszvizAcC=eZ9w@u=}_KnPg<7RB&Q7H8f*{l9PChvvkcykc*{jHiBR*-LnV0s!aab
zc%XCcx0AIxzLQ}){=2fahwXqsj$u0!U*V{tUBw^8k4ol+c&c*%ZQNYMJ^YAdcY(w-
z?cqnUhSHkxpyxb#{B`3lU=p;5mm>Y%hhnN0!Wc2=`quSpL~NF&LpkENoc!-(wSf;Y
z{xS4;IG7(FdiS&RFuzJr3dZ(EteGQdr^H-Q`@RaNN+w#5X(M&vhh7DP*ziM9aF!0}
zh?4^w;sGe8iV8Xc?#Q9|p_n}KEPm)EaUmLE#oFl{LIj|t>pG$YN$U8aNJ4`*`=M|{
zOLuleBszlTDWI>XxJFA4_e<hg2O8odNlp2o7)nd0cf?te(DEaLG0A%Qp@>ZjH+V#J
zTDrmGb<>f?zlmLxaZZRGbp}qf4Lvq}<q?Bw=_`*o)!^~;*`gSiZRhIh4+q}W9}c{$
zKNB9^$bjci=ZDxI4jhW9spKEYIBz)KlB+bJ=uJj?5A;U26hstT`r`B1mb9n=4Sa}U
z$mq)+&Wz7+Dk!^e1>#+o`g85k)Rr#%*QM@ow?nbCJ9j$_RBaFKCO>Q-zKhe%AK~F-
zl?}vqgURzBapu-Cv>V2xmXX~M)GZ^s5x{SZ4nWwuWpn@n;~hbFAe=K^00H*a$mq`~
zd}|rl?aFD>`y~STNy!_?5`C?p5GPoZsxr?gMK3@fK;GXEG7MPbwG12t77x7#p!f?i
zB0&B&`ALB6z!;tYIs|KSew}#hCQb2&h!x0X{2}rMQw#(68La7s2M&jWoX8&{da$M^
z43I&PN%=#B5f+gTAd~?2GC3xE8l*;nl)^F^!krSV@zw~R1Z#Q;nL!9f+UF0lVFZG%
znTVo4#HO*3j&e+ZXwOK>LB8n^F?W!U`a|p<)~K0*0L0*xc6^8>gv8b#ViK{YD=OGV
zNQeC)MiOg=l8;XpSa6z<Q9BUdj(S@L5ejLzKSY*tSmU)9ZWorZ9bjD{pZAA|SuCSH
zK;8lt@B>gxgozd=HiFbb5XF#6{6kbS#u$-9d^4sX5htXvCQT8XHDE0VGST4;@q;WQ
zOTdpq`tv|y#v4j8+tMvT!~+U-lI+BsOWmBI$TnTo;Td8IP?<BR+R=M>(mq2m-!jaC
zc*vUc(@8-nTkQlVtTEJOPBr{YghV3wk2jJfJtH;xPaO%)BqXH&fHR3Ts=9C`u_jd)
zR8C~IUseQomn1|=C~HYib#ehjPjzAuI!eCfr67Zx>KXCr-`S~R%O^Wk;g(N!D%{?m
zkXQqHB;1sKGH8H<3mE{&!G+ezLq_2zRs4=pa*V}~ZAap|(z<BJ*zhy!m^Hm8-cT){
z5H`$pyzPxS4nE{?@{H8zJV?hV?4;}8c+P)@*fN*Z)H0Wq(k>DFf|!@#gKj6!Kr}y4
ziZSa70jCq&0-oS>Vof&-IGtFAK*8zc8S$3m@&QV{*mb&(IHjI7UPs`A@&vGD?hfRo
zv!)x%J=FAu+|fO5kD;a$iKZ!6@1e%IXNFquD09?Nrl^x$Etn6FPY_#9GQ|F=%!bKi
zcd23RGQ31K`P$u6ttY}^W2;TIjQ|*TO<~rM_>1c^z;?LtZncw$M#-IbtEEKZ!`yc_
zTS_2Wx`JPnV(UUFh9YkGGZeJF9AZLw-p-SUQ9^|uC0Q=~MxK%QaO_DtA#5&QtLQg^
z{4B{~`ULQ+u}?vTn!rK2RBNKvhdakJf=c&%OIFq$Y1A>r;(ziNyCY~kde`5dOZ@Ym
zw6mSSThh>4Q#yfjs;h}a9gxhH$T0Ve*!}dCLY;I+>QmEr<2|0Cy7j-b{onc^hK>hR
zA%_@(w@ECWUrfNB*QWHW6i4kME8Z5kjI1K0W3z$ndFUGeuBUw!oXXqQ19RQBIm@Nt
zB*KrvW1bI(+rAGzxb4?cruvo$zWgSh=|jbP`=x@T`WY|^2~6Ova|FCOq{B|RLCWk6
zsplqp@T&I=gu#Upjm+Io09y$uNCxm{gmQb3$i3*yz;2B<yA;c0BY#HvChw0AJ=CSV
z=R+M239_SSxvFKdk>fSu31QRNptY*$M0jdo%aTj$8Dituq~MO%5sP=Zr!w2-KCSki
z2l)pX?6<R?&v4I(G=$SVulVqmx&|NKo)MfQDDAon9@vgg(1b#Xtyr5hQzEcuNtr?p
zfnDQbqJd{*)7zM=AT>MWGXQV^VcXnRLv3>x4JpNmP$}-2OhMWy%50o_WU%oB*mi7@
zV<m$~rI}B6&j=gl_PEq8w!@XWDVP6}Zkh;nQ!YQQ1{mN}%O?josh4u)c^B&_@gBy7
zro7607?b-w^I^<Sw;?71$x9S+h3J~abRxKi9e{LKLzy=*E?M5hHU!r>#M3k532%;k
z=*!C`-}UkW%6GlIq$2;yev`#B-ZQ|)W7#a4#rhbnP?^cXiY~)gBrCd)Vo8khuAxM`
z1D1r3czOHhBVL*anEd7$sk^0tIdl%$BKRUFd&L_w@uW?I*?Q9M!IVCZ8~_Ts%n7%&
zxuD0EHW&2IWbiR&JTi?P^J_A?aE{wsT7>vcmPVs^Cff~5d=(436LTn~U5YPYX}jX1
z7wlWi#Uzs#W|Pv6O#XP(N?RI}L($%LeCP?wGSj$q+5Y&MD{O<DOR7jpXlrA)3^KV@
zS`YE?B>N(tnbH6m&rC2;9soECoJn5GRDv0n^TunLQsSDfWy;rQm&~x7w@Y?d%o~kR
zO5lfAo+AyseAG!RFyC}&C*~VYT9T0t4aR2XLo<AZGd15gi#4BO(x$zTu!(ESO<sSL
zf7iSl@h>ceGWi+A;HgQXQinjY550qg^&WpS@EJ}C1));=83iF83gRt-&lLWdMnRZ~
z{my)(i0(8B!c6RU@+eYfKPrEG{$SF+d?Mk9^BIN7|BiTP;gs?rCXnz*$i#lIQf1cn
z#%IwR4;$PjmTBM{A4ZjGxba<7iTxTMM(=oh<4+-9srZA+r!4*k^SO(^WIc%;`nl)3
z8O`GPxJF?Uk8c!K`8Wshc5E+rl#_bqlXT6eKnm%6E<~QoV|!ENfq-X6oh$h;$+IaR
zFL|Wlfs+|N*&ptKrv7l?P5r?ygOM4={|=`JW$J5mZc$=B##HEGmkLlm{>o;VFT_;P
z@)?;HM?N%Dq0Faf>Y#Y8J^-;l*!%Qu(e07333?i*+E0mi1k~^{&ynKVs)u-9it@3Z
zS2Dimr|E~{dHoF^Ms;6eL;zd|a1T!30$jj%_k+0E%RzzGgmhs*s@?Q*U^ZTOLBwQ*
z;{*o?0W4Pv=KM`}3+4q*mkeYMKHlKC0f>GhT*@iGk*3DvH*&Mq%@6U{ddqKwqq^lc
z!aaM-Z-hVAo3qtX+}&Q7m^nRT3?A>MjLEovn;s!n_Gc4SBC|u&JBR6`(|?CKrqjm<
zd8ju(Am*t~Um@nQPJbdKynaicBj&_D(lN>4B8Aa_ku05?kaau#pO~2&9#RLO^rHGu
zdhc|!VhZqd#$ujuIcyzDCT`-=G$b4kw=V-9T)KrByv5}?X5kyY`IcGuhRgfRI)%7$
zJJAswE^O8*!K+jUI(dtIlxf@3T@I<;)1!{r->I%2A4m|-G?X7oAurE8qf57(`<RG6
z9RN)Z-0%@Z%KP*pTmZfOIFa--WZ&qZLYD!fTeV5Y=)1$Cb$X{roq!v)+$OC{FrQjw
z3T7z}oq}08fazH6E}Ry$MY!o5K*G;gdVxDpO9PM-wKRYZAq_{<RethBUBEyUuHKc-
ztkxk@<?gzWDv#I$NI0`Hm#sXOXMU4DvYd5#Bf~TIFnJ^ED5E#BPBJhL$pzRzJd|F-
z3vqt|c@i5~hG4)5AR5w9(nB|uzp{aN2p-Ko$Z@78bchQO=B977!6R8Rb>Pi_4%SCN
z_q};x8z_R(Rog)DD{pQa<t?4PZ4|ooOOVQKSvP&K45w$gfr&W1&leJ+G!x5@Licl&
z=sFJ(NndA4NpK{?P5uBBzUR6qgJ>un?iWJudHiAq^w6*m9)TD<@K1ebcmFqV4`qaa
z$&Wfy@6nN3LJo{X3`AJv=&vr412T@$3^t5YE*VE}>P*rOF6#`PuyCf%gzTU#Lj1)6
zC^`%Q2JdPGaTvX;8ROvqnqgO3#CUL)pvG2RwFcDK%$YtE$HJ~P*hDfz`hZ@W>Cgw`
zSlBn{xk`Nwf^tOA9DrhbpDeA>WDawBb!QH9dUa=h^1(osOi&K8q>Kt$NJK~Jl0r}K
z%r-tc<M>#NNH5(s=;+N5CL3LWP}!Ln!i3dlbOl0DG7JSmu`3YFnag`XFqbJc67J!d
zz8j?X8Qx_eVagCN3x{z9i5*6d@l3ltpkHT_?GeV@%%2UarVLnf<c@$eFJ5|I@)8C}
znM!|h#mqV4;|pc{Fwi??;GNOITsf!*Od^?ZdR&Ul<L<s-p3D@|V1UYKL4zB*0t#&~
z)K;qWxS;<jD$&Md*kY6vgUCr@T&+}Ox~XT{H5&}AO>xfXT4g*QjINb6cSLw?(<9=5
z?w?tQ>B^o7g9ig_Q+(q#5UG9#AK5ZX?_fYJEuSL_>;{8rk==ISsNC|<4#wBgG&vYe
zD^(TgHX@qV=ntP+Iv2Io@uqlOFZ)c_tsgPgs(!>sQ$#bEwjxl+5pT6_{XjtRDqWAO
zheD5yuJjB}UI1i_v`esMF~)h7Ys4>`K7uf6%mqE|izp=)gh*<X`dbEKuW~H&ncawy
zpIa}&l!1Wn1t5rg>jwkL)epvz7kveR<k2fQDkwJH=)BMHbq7{Y6ya`Q`C<(Gv4DuK
zm!$~2Ul~j9$UV1sdjl0%#^n2lBD#KV-HG^m8F?-!BVqtBh6acwz(3>^4Rh-d$p^AS
zBp<-9n9&2GEU>HYoCXFKvgAEjNKB4&Q^psFKVc!&xi|D;&xnIl>gokso2VKb@$Shy
za=F%XGEmMKl5k4aUeJTU8sX(OH(m(~LbRlwIE+CH&P!q7M-y>HAl?tYM_#s3Ul`*V
z&Q6D>1;q~1d*6kdp?EfoK@Z~MSO|DPcr#=mgcv;>@!m;-UM3<C&OfYzpbx=^`o=I~
z44x1R$wFe{8cW_?sk@hf-omzVlRl-h>|L{M&?HaELC5~GlnU)FIa!Rs7~*YNNX(_)
zP#B^i{uf7FFo+~(K|Yy!0AU!1sAe4T4zrz@$D%vt6<jna1@TaHQVM3-)Y+It-MTM6
zoS(XOU*x7aw^93^lv2u25mER!;##SAevHv0A_H0onSXNBL^x{rM<?^pf`Wxf0uNlk
zcM3dYbr8wXj_^Rdf>ZcTi3iqU@hLgd>&CfcO!)?0rsEkJ>U0n@!D4+mE3){XRyi1#
zWM;lPsn}AKfq_|MQwGk#B&1r1vtp$%6Ts^)Q`_As%s>czU)v-DVd<V5v6fxqAoW%h
zH)bwlZatBAEhH95w%84!&de-*q6%~5zBf9t9pTI(+uz-D856=83NG$DMHTqEMS->>
zT1HTOi%e}HJKb8AO&ty@t(Gl=ZmVrg$5J<ze9+SCHe_h7VwKZ2xj{MUzRog5CQ#J*
zSa-|P&VlDp59Yj!y(e*=7FtNQ>(V|s`3NO(pIz5m68l9-FRV-r31-0K31PEfi@zzj
zvdkR@hWR@M*9F!`aTz*v-)~8HxFcNRNS1b=YN?7;@c<IL>)curqW=1Z6M^H7(16ZN
znjnJQ%ckD>1|*wg0-L_&$={}))KnhooNq}HTkeRy8lq;-Z2-PWXNnpm6`0rdWg^*M
z*Kd=t6VOKMxe%u)9ou&RG|g2ol#01Hp}u{_H|vyAlR(i@f}}J{$6K<T8WW<<wskj<
z)Dq@Kry8XylMi#Of{-=K+#CPl?cW_sqdy=0cx<7o_Q!V~_m%USZC&mD{l9tp$G7r!
zKK^g~|Nr^NvAz<Vrg7%|NQo-GXKJmP`oPA@O0k)!k4U_B^AXkmoVF=L;#?_#g&Cst
z!#<fZ*k}OqwO?P!{M#3^)@9f}7!m6eq03p{kb;QBXOT=HIXkbQye2&v`Db^Q;}DBn
zy@NSZTysZ5G!iAj0r?v;X7p2B>D+w5=)}xW4cbHsy`0l&iY`!m^HUIRK9G@ZB`sY|
zL^f3J$?m2-9O8&wiT%_1oV7jnO|yHYAb;F2&vK9Q)9o|3eIEb&BTv?C`+$yBOF-jf
zZKs^jm<h^sfhCQ*tf_eK$du;G)p>0hy4sguC@vY6hF@}KN>^&zWNiSkWfETW_O|Dr
zQYw(-c-=_TALY`KdUH~+LlyLkN8Fntj6;kmMUJvGK^GeKltW;~ZLH;!L<?EaE?QRC
ziv7--^v`QD%M<d`idamXct759dF^#Yds_2V@&2?6eo~Q}#Z-~V{jwr#Slm-TbWzA%
z_LCNwsp?imZqNR*;y9o7><<|~wTpjN5t|*J6+gD^Z!atM^XVt?!ynzAe<VMth~HAZ
zRFS_fds)%${U`TB9v=D){(d$7Qo{lN$M)0hud3DS>G%9Y&(`@1|4BC~2uu};+%GE@
zlf3xh#{85XKdG<;%&7{)yY`|20+lF&elW%*Wzz4r6Tv(cp(sDz1dLbJJfL@zZ$CoY
ze3E!SsYt<StSIDuS@9}Q^7F@ArgpC{Cx(Kz+^X2LNnTY{eo;y@XTN!p*gvVr9I=-w
zQq;ecW|1&1jHExDzN^Z)?<W<SGEn}&@nJ73C<#r)4^*kybjbXqA_M?vB!6tDQ-4`8
z+$eEm{di+WBOYNtX$|LGWhIp7i%NwlEpZtBc${qI)A9I|ia14~>i^izReM$O9#4nu
zquyCR9lyU{kB4+YJptFtYPOx^UTHtrf7ZizNk*0NzWX%%{%j~xDMaaGRJDIn8GgSa
zH4Dh{ADgbxUsfdZ7Zi}SaQ7#b<R=xOxq!Lu$EM5JtBTkCq~QE`oBfl<^Sjlg7d2J`
zVCPote8117$v*VgGS&^~@sHk0xyCOmvebrf8H<bTl}`;suDq~$W}hoBq@D)w8rvWE
zmHHanUj(9?CDQ)VB=-zaqek+;OI~#wl5M%6AWXT(6J%R8&$43KI?AR&#*dO#=_8@K
zeZ_UQtLA42sC-6#mF>Gs!jgmXd*>z3hz+5^WP<rA|Lq?<@-}^yv@`^8ZgvrumDjl$
zFo;A8hpzV5x!Ev?=*xa`UAqm&k+Iug{4z4`Pqv70?>3D)Qt)I;L^dl&TZ!AoW|kSD
zAhUEvvY^d&0_2lbW~A%Y2BmqTlP&G3oc0ahsDmZ9@YZo{)-B(qW4mAamK=(r-H>c`
zwRdC^CmFcLwVAy9*vYpp0OPY|ZRBIurTa(P+K4=v^~TuEdO+w;`8$_c*pkPS;TVW4
znPEWTk$mhB{^TvQbgc`U@6?g+U5VsdKv<MU+f4MnFGoIjC6aFezUkW57680|)2u(z
zXbjW;u+NVHN{*&G=1Bi7SUWPw+K%MYLl>iDlw(&J3Fh^lF${kYrMf*s#3quk!Mn*w
z!!hz~kGj3TK$FRaW5?8O%44bPHsv0=oGI}1_%lj29t)cy3TYk3{?6q>#`E(XpOAd!
zij~`+xk9Au?_5{p0`%yfkG%7a{h2FPYJcVuqVL4og~<;eij_L?2R*VM>Jz>QJzuz(
z^)X+#aLi=#MLr@bJL4PP88d++-Xgaok9@B@G7}^pHI**%jSruhQgS_vX2waroCYr~
zADKf<p4%I)&v;kqEN_|XGTv~>nH%M>H}{lhNL12Op27UsukBgaXSSy}V^)-&0?iYr
zD90xsr85yIAFeZ5C?B^$T+BhngpX|^Vt(l=MN5qmm-6|2(JDvjWKva4#G5jq8W;-m
zy1@tkh43$8Ubi<gm;-vsx5%f{^NkESczQ}V<mu_#8yWKZ^tSm^#O&rPndeRKsRkjp
zkTTL9be_nxwREt^)V6TKAoq6wF_V@v5l=qKple`{WR6|>e`FTk2lA#Qz4RzS9$)&`
z#N-)EXCwwr_m(S+*>bk|WLgbfDbm#Q_YUh{Pg#d#Ts>u-r|;@1=#UjGVhq@~n6?yk
zNI<5%$`;C()933uF>Udu2cR>)Q}msfCw$|LME|RV#BP1_befS8H=og9^yum7<g=7A
z5V`F7=I9htk`AZP_Z|>SZ<!sN9$LuG0Kjc{_tpzPby^BQCT_p8Ss!{!rzYlY54$*1
zwks0}ozaj4<3s*xwaK4pAZ7b}a(ZKSjt{!U9Zcx)A=f!30Rghg_;(Ce!Vs=`wOv%O
zMy77xoB(fRYG=7k<w^OFn_wl;$g$iAGaWp=3~P{k3}$DSng=(<s;3fKfj7pC!Sw7<
z^WYGf8ScYpvWiGzFg5$wy5W+m2D<}vVkYVNko#s$4u-+J?CCj*yURwFFs3pQeYhiO
z3^qMSanDG4f`MyA(hm&2dM4w*z=a^G1K|By^To&+m}@>d!G#tnr4B;gdU}qAnw|0a
z@Ybyvj6a|<BPi0{@2|I-LG&P%t_qo#(L9|;;VRJRJUTeUbn=Irg5uf-d>=BB9Ujg#
zqSR?3jF@zKNyjp#)BlL^DX<C5+cksB;eXAXbw0lFRx?r@*MORl;qdcj>b^ky_n995
zoxex<mEx{YGl<)-3N<6R2UKOoYvcNW6p!>MuTiJ+Phy{@%RltjhK{|}wtM@#GcuEQ
z2E-SR^!LB|_T)j={n~bKe~;ErtLfjo_XTpo&U!O2f*<1CT7HO=3vH_D<~^V)Wmt6N
zfv#k^HQ2SPr8flMjX|jUDEq(J6KFIUwv5|HwTuV|e$kpS%An@28G`I#C)Fglk@qk|
zi*X%U2!tw>44YeDd`sHg`f{S3jK}fcm~9~eMQ=`=mCzhAPIy3dFe<pnP*52Yd^i+!
z_y+|wvgPPqy8q)S&$!*V(HstKflA&x$?-U_Ge~#D*}f2N7#z<wQeycTZL*~y)58N{
z$%m6-`-~Et7LX62np9aNm#7&giyKch-PJozPNTn91c6mcSAGPFEoiDz%nBp3dOQ=E
z)KuJUDg#yzMXfD}F?TqsO!60bHXaB{-j$3@1-oe7!c%cBZQ-dni1apSxCAYPad}sK
zSJ9j}bGBeqoH@!KV7L|4Efy6=3}R8Q(3ebhL<9|1lZeI@X(1V^7`@HlQ)E-Biarfz
zG-X&YT$&ugcX57f(Wp2-OgzNa;mK!g#wS-QGOkdL=&R9N3Gv>!`7`zu0MkG$zfY<P
zJ#{(1MV`Xqu|=N3z+r{19<i|{rhE6&#ZXqg5yy`yG6K~t5EZ9>HR{6%cl9T=rl8qp
ze+-1t`gc$s=m!nVox)h(wcq(}jm|L65;w|vE25LH$5O2kUtG8NR9poWpX#!<N`^Cv
z*`bpS)%Y9EG-PX)HjewyLfE?yq(`k1>j=cI8S4tcxy8D=+^iDxxDPF)Gu*qzU$DQB
zq*Zbrxy%;A{^BZx@Yo|D|D|pLvbgG0Nq!_>t5u@k?@3<9jTqtbwaVWvZc6kZ2p~Fm
zDds-9C)-DZ%hiI&l0bg~u|eGGT`~%=cO*&(o6=*-FBGG1$@>rzx9U8>b*d^<*Jp``
z$zjM4SZh)~g#4{!e1P<=N%;WbTa)o&az}~u0T+X+n*#_N98p6tO@1aJEn}@+YANnm
z4xu4D0#w>uaK&0ca#-{z!@dmq$6EVNVX=x_9EjGcgY0q1l7EKy5Nl1UhoR^Br0E#=
z1|5<hMl&iI*Q}#vSTa24YE8liI9Av6XoKX;Xk`$I_=l2^Wa2{{6>Qg4PSIeis~Nux
zViW%m1`Ex(%Kig}l$rs}U{R?N(2UDgt)@dB)NKpmI77^4jB}&EqK;Z;SgX}?XF~2~
z%yUqqIe=opH#ou;B{XXM(eY{&H?39XLc&T}bq+_K=8TVKZs(w3JOFt&bT-SWQ)lx^
zS6yj{V!CSuPzSHq5y(l0zJX69t57t;^{nbhk_x2*(!sCzTIuL!BJe8rR3;RcPYSuc
zYG$J&gVBPf8jD@1YZ)`OSK9lT6du9ZM?eGL;ogOLt;#M2VkWu7f<UWQ8p;mxJJk%~
zZbjYUUOv^GXCkSpsP2PoQ?*Kgz_sgvpcH-4Qv<GCH6y<p>|(Vl<giiTZzNl><ey2l
z9Eq6#5!X?xln-!9IfAm`GvpnEeAm?w)KHF)=`IE!)-m?viFK?hBO@uE7D8G(T6v0Y
zjzM@<Gsql7Of`edZF)(}YvHx594q8lsu_e1dNxO5Il$mn>6r`Hp-NZcLu^U4NTC5Y
zk|VJoxMI}|Tn7=7yx<P;9yx^mKxWI)i$q6s%>oi1LMb*w(JPG&FL9b+1Sxv5!JVoW
zJwltSxg|Z8aiwwy{eToMdet#VVdM@ai{L72rs!8DRmxzID6)ToIjCk_J(z+PqM5>L
zRfgJw7|0Ryuz88IWE?h15!g`lB<}a8TBLV@%%^5tK5k13!Iq*2<ds_r3UU#_iP7Iu
z+8ORg3*pp3D3%L^ZMY8AjPJ*Fs1_M$LB&%u;@{|)FO#joGf^5Gt~QRKe~@;`3SdPe
z=j4@$Laf0P0A3xI;Q3l)MX>a1<mAFckjZqNYA1m7oX2Ob&mQDSnHrNjq)Sy8*o$lr
zf9rT|XO#32*1&ixBtp82(ldX#)JG|%C>erbP=7)SA|R+O)~J#+vN27`1q}C7kpaW{
zy#sOeQ&@%J%2AW`09TGJVgvV!nmh=V5iU;<8t*7FfP>V(uC^ALz$*n`J{8tWO=Abj
zOE}4YDfmSGOSu=oA&#D!Bn+<Vdl_S-&`b8;!7!Bs!bd5I8!97LI!dwbEX8jyxq#vS
zP+Be^Zud#^5IXoX5X+ua!13R)f*=8WLf9~uw5j1lV!tI>aD(ejvPsmYmWjY{Tfnqd
zL%H0FvAyyc0bD&*S;U>I=Zwy9-A(Oqk?pBexwoXnhobomuxV_9s)hxy-9o}-sC>zV
z0S(a+%nM#+lO3ZLw(ag9A0*;&h#RA*^+aNGH<ZvaO7Y5G<YH4P@^%EC<0O*CMg9rF
zU-0Jx6KFDbK;dyDW)AAjGlG^76bbF6itfWzl~u%cf)?_Ouw`tpGP#O7goYRiHq}rf
z@fQ#(W$L?pM=Mi9iq54oJInkivn^csXqKV-=~`7TeU!-1JYip!fzM=_vp~HRM+Bfi
z-nJN}LXlx8g)~sf$C1}CNCiMZ;>WI=S#0=cAbws|47r%knq(>%rz7ZS&A$=Czv0Fx
zPY5YYRvG)?j5*rNh7m-Kvvck@q;N>l@Y(Q@Eb}Ai{t07bNs8$c_uQO_)AGYY&R+KU
zJgaJP($5;pjDKTWc&TVhWXu`&-X4Xv#Hu#ZS@gS2<Y_;iMY|>u?Q!Ov!B3~7$Zs-^
z@YH5ZL_f*UZJ5j^A<!7)Z<I6!&&dAcS6-cGh~4!yC1t@AKxyV{8teopA8(ljC}kHD
z1wA8@W_NV%N@;d02N9Y=9Oj(@A(0MY%*;nwT5TRF$(cWCN5-c!f;pI;k+}NmXo*}-
z&t<gCz|(ttI-tN=fMYF&M;(M2<-k~wha(vao{_#Cu?Le}<*5t?gJ+=R>He1aw4RZ8
zMT1H}{(`*>g#lC7qyTXTHnt0gck&mcvceo<&j<(2J!n#ct{#cJOllA|p{4ePd9i2h
z%P9=d_T*HBa>5N)r4n&7)lZ5aQ?!L*=wt<M6D^siu1e=lgvvfQP$<3JE4+wxMM&R;
z`Zo7Uk+zSWQFP1TJ}7D!?~Kl3fR+t&P^9g1E1bG%aN$oj&IsxIRO=mof!hE^cuL#n
z%AcR^8Au9<>q!iJ-f9{Pjr4-L)Gz~K-h+bX0A*z{MB@y_zNzkGVUY|mFJNRoh%1|7
zx3d_lu9S3OJ=mg+k+?Chir_)OP4WOzaF2~en^C}m%}aO74LP5ix!_N-wL_t%uU>38
zKf_BcmVFN0h4IcyCWQrI-9e>L!O!REI5B9f^Bfv9g1bSk@Rql1&-95=bDbl&l55;$
z0l*rQqDE|jOhcMB0Z&zm?s5sKTU;o?%0N$v6+%ht3TLy)y28n%OjGLa*<@V_)={T*
zfO&-z47sLU-m|531^qQyS31ft8z`CgG+9?TbtdZyr_N-^;q;lTE1W;m&^diD*~?z#
z2)@JVt31T`2Q;K{&(}1ho&0PKOCM*irWuWUp2AECz$awc)YKGN5V`Xx%)%IWc#2|t
zg_A`+N*Tc?MVT^!&r>!;P`xr`a@sFFR1qKIY@Hf9XY16^!H?pQ?53pDNK5NNXvD?j
zT$FB^Bm4%70h~tbb<2c{$+|+iWq$Bm23*Y5b<1##Thj_-ORF@)*kHN_a>Z9;!!Z0!
zwr}L)j;>)27<N{Y^MX&HCrkc(^*K3sO{&+*_$rz2nPFTO{>q>xamX_2j;{pBOU`Eu
zPQ%5{yz?`B!@&L^eUP3k4rW)+ca2H{B=O)@axdw5gh77!hH@~<FP>d0*`!3cTNxCj
zx0}kaAHDA&?fl^orh;#tMN`rB+{6umdu3Hta0JO5`6g8v@KTipoWU$&9%g`{-oG+v
zTYllcL#e^A6tNyx#+T^Pj)97`R^FW}<3&WMTp1ps7sAR|5RfoeMtbm-@rdZg9)H5k
zZt4%m1*xjn%*v39iYw-!C`deu;*X*~#uDCU$u2@)7Ny+2a6i@iEP^C!Reo(oHRy>q
z!X~R&uNgLpSK<Q@o{5K=W@k9YC}G`jbJcToy}*`IbtyuaWxRPum}S0*S4ITr)x6UE
zzv^mo(Thd*4!ZX1g}#Dg)Zg`4##g8=&|P2N01U=VkAZse6;rDGb*ejB!Bg-093xEm
z@?l`eX8Ji)_|uD@-GeXbfq|VF?(*`lV8kXJFc7YpE*dqw;g5iB)`_{H9y|DsDJ7L2
z?^QY}T;7lHC_zl;TY8)@q_b9KF9wmY99QZ{Hx-iHjPQPeXh2kFI?N!d(*b<+lFJO{
ze;@^4I_6ZmnOEs!gEIQk{8L6t-3q7ja3taoD5j-d1r;^jkt*1$t4RMN&a>8w500XZ
zVCsNMk8n9gRXTuIsYHV^I!c|t=Bb{Ab2oDsFzC}Ax$w~rXE1IRnEC3=u2B?Ec8!u)
z8p)swiu4aUXV)90_&H12KoDp;yw%a@B&To2jNIxg#p|7YqlBemKxgiHYuey)A|(Lq
z^wslGARzSEDV9b$3bJqMDahXa4KdT;yMUY$5e4c1zEjyWyGy@p9n}a6T?kBm9vJGa
z>u?^G?w;J0^u*>tEJtj`pjUZf>)e$iwvJsoVke0i{jPb&F0bow8D)oyTtaVsHe5oJ
z#){6_I&+!tp;~2+qXyTS^g=pZ5o%hks<V*9k^JQ#<lU|8Zn$Ar^_GM!IyMn{T8&0h
zXLX70>ZFvvHV;a7*QTwV(Wq4^a%wto)8bj>z%ARQ9JqN9b{E{HW3b=igyClBc!^aS
zAV#oOr3!MyzpIn3$A8Bu*ZKH?97POgttPuyhXKKKrgf;?N{v)EA8=YX<pj>p#>Um@
zMJI4sg%I*umDj0u1PY|1dzJgP4w`<!yPk6ZS*{dU6?`A?z&`-N1z!^ZGXs)qIh~GD
zZ&eXm>0C)~ZXGQ2=hh)2Uu`%gRC#LauH7NqSL{OcY<Pj6gn7Xv=n?OVAPOK?#BXrT
z8Mb2-_Q=FjmHCY%VpZAUs{FZiC+&<Yx4E?*vgB6lkoQW9=Yg=^LtYH&*DX$A2F5b3
z#mi?@VcUKLDEFU-#d_~_%L`ZV2yNkfhb2R)2^l$CmA=rC)e>_aibRjQ7QQk_t+;XQ
zefqDQwTur+W=B8Z6pQ3xw!Lg2Oc8inn}j$5Z!-YO5&te@@ez(&n=VhtOT|Ddgy(Ld
zSSvcWGX16p=iX1jT#VPvh%W@}RwV~@o+oca7b1AH9~oR$!>L`FOc~{y@o669>n-W7
z126Yhbw5McZ&iL)@_0t99D{%}maZa;n8NK47mSd+n}4%M?NxfkE3S`m!V3Lkm@uLP
z4?-)R5dUUOV$l~ElE_Ia3`yk9p&OBs6+3iBt?WsRFeNRFKrJQh$sy{lfaGr(eTg9C
z+ETW{38|%QJ-LiBo`<`AlOeq0>Y`xLO8<KWlsba8CHTW7zm2Uou~B99?TjxT*_|!)
zb;TVc#1GQAF_>6pSi0;p#ugFJ8HLM;=i07=MQ>C3dy7zF3TOE9XB=>C8DGr52=0h>
zZQZEx5%q$>#MzA)D@(D&Q)Z>cXktohh5<Ag85={4=R5xbk<{$QWGpH*bA}2u$!>-U
z#HMKzf#XGAh|%8^IEc&UECBI2ztxS}-!inkGOmEp=ZM>mVDs!o1ks;S(*F4HSz{1A
z_65TZdWz_FWfXnqA0du@=sS#~pZX31=_kx^4XQ+!7>;lS#rv;va59vwJLDD+;qLW`
zTmU<Yk|qF>3uJeK-a?YMT_m)q*`2rKLRcF+=0=L~M)*p~;3o=LvBG+fsRqXn2FC$_
zm@H$-dnPH{23|Bs2vHeMA-)K57fZoKTGZs6;Ex*zCc73hXIoc%=A_Uv0;9KW8e--e
zi5eX8wQbux#2#zep|_;ts0iAis`8QYD~UZE@|ly$%D|4!cgxmE4`TWZIa=`}!Zlkw
zBrad2*hLu}DkzaZh0{+zlrCWjDW3c(q)F_uj4)E9k8R8#tdYXX;1LnJ@Cczc?8sYk
z!tl@mZ_EKG_8f&|mN{Z5gk3_iC5a7e&<IND6aPJCQ7UbNjiBoxhCwSmg=8aNjow)z
zj-^k{0gSog?C}%&jt_GRk}{~A8X}>}0gy3>3r~Wel!eee`wgcgDhx?jR6&rv?v&i{
zO?*dL;*fFmTM#!o6w)C>11Jr6BL;FtBi!ux4X%rJ6rHcBXw6|38PYYOE!B}iE)m|i
zK@;q@1ogPf+7RWS(MlO-;?07C`wp4<ODe6-vX7{4qb73kPe`pbHH2W&vaM~BI&;1g
z$vKY$Y}hvEv1qonE`)O~`_n4n1#`4K^b^9Cs-i^Woa2>qq!3F4K|QsF!Y*pH4d9%^
z>tm!CgHAtswjCG7k%A1yeh|S?m9Im(;D%(={SAb39OO>kx|OGfNItw%LnHzoM~A$-
zW9uA|ra_VtZ)lLQCL<e<19qf_xN2PaFKq+dD@69UBgxJ`$t=hw@pduvyp5|?9kSdC
zVMDQ?n>Lsb76)knQqBqBw!oEU<V*1eWy7)PDd>pE5{sLoI2-{4J7hK%%btQRk*V40
zZ^<!<GI)og9Au)pSZ@d$4l2=eYlVn^H7>F)7Oqs_5-D1Npb{-xQ$#=?0V0xkX~Lg)
zxo+Pjm1usKNUnZ7oLn_O6YQe4e`igwSW0&!zq9`O5ZNh_dbQl3dWFmq7aCVa)FrFM
zl?n*#sh1vjgrxd_c<pQKf8%P%HCgmols|<K+HC$d-9RFRE*1r5z{&Lyz)34O^WiJ<
zgft!+h4#hSw(k&$pL>C-K<}Do1h2A%X3M!HO$dPM*FyT1nkCDs5PFExyA+y7l>(;F
zggUS7D@1bsLM$ucOd<Woq-IoTon_*h9q1b65*TwbR7(h(@r9d|13O}xI^PfT-aZ=p
zVeaeg+h|e{2vHKC0zGRX>TbkO-=`Y8m1>Cp=J#-Wz8Mml2$h$k(B!SGM?1pJfonQ)
zC+%f!RXPtN1rw1iOH%=*ijp{OK(_2V^{&*Hcc^I$zEhP^YDd(zZ`8Z;`kIh!t@}<@
zcB>sR&0ya$WE}}))4o-eX{+#QLfN<yX)HxfskXK2+w^W*yS^)x7HmgiOTnT0NILWz
zX;M%4#okDhdh#bNfWPSQ5_eDiI8SfnQ9Wt++JKk>WX#Llj~l>N{iM(2k$0SIky|ng
z9Q}DlI6;j3L?%`yt2~|{{F=`Afq2f#n04g#^E{a`>u{4_2u{F+cwH+<5}0W^ccio2
z!5-iA7coG-J1nTR`0&(c0^z&ELi(0?v>=Bel9L{Q##y%vraLm!<5*-^t_sp4da_jP
z^$04klb?tcymP{Z<fO+M-rF=_74L1*W91~l&OK!;OOP~(bU@D81CXy8^U^xd=9ap4
zAvH4Ma<Y+AmKkx69pPLf%WNr{Yh;-%l4&Qh%of_F{6mqxx2eazAj<e#5aHp7KI5~m
z%)yRCK3*2r)GO=o258Ja`K4;Ak(1W58y^7fNOzpG;8U;AnV83_89+u_g{v&2oJjV}
zDL|51#V|Q?NAhOQL5=yBd_(Tg!xR+aP_J7WX-B-n4W*dsra3^Sf`~yl0L9cc{LGM}
zR*?V&xlT<^{R_DwEjG*`3yI0>+qh#gyLLM=*UDMGAk%85`hI-Kwq)StMCw}kraRK6
z;=F*|x00R(QazFN(72JhRsqK4WO}io9goztaJ*jSn7u)p<bq=QhSnRYY2E$VOLt^}
z=a?;K>f)w@1;a|pIb^DpOL9S;TPrE)kg2w$plfj}G<g?)%7Ar;j5ZO@FpY<NtnQH6
zR+TFFj`Z_#szT6>$))N>I(j)!AyCKUKXqRR1ADy`KL>h7-68KytUpLnY9I=_eV(jp
z%8}O8$UKBtB9jZ$ja>E4W#myuCZ?nN!ibeF6@f|yucioOVj#7bW4xDIi{WaHueg<%
zyDNFSRA>=7Wpq?R@>dfD6@sl6fdB5BRHRln64cX23HfAA4oNq%)4M;CM|UxTedRwx
zUix~g`55V)&0kRi|2al_XX`Q4@Q!xij@G2Jcv!wG4n9(Gj@`&cPgXLd+yy-Vv>6{8
zsLgI9q8EkQ9lbO<6-Ck)J5ycqn~53qEpLvhGqovt4pCL2<B&8XP{JKleJl@{^UdfV
zBsIs%uEKbePYO*^*-2Ru-<{MI`2$H4kv|YL5tD1Jv<%VlNz1UhsW?{`YsIETr1uY$
z2GL(^I)mkz1HHg(JO6yk%HPM2<`}Ad)&s<Ns8e6Gh&tn~@i;%k_OYGj*77KhLAK9F
zvAlVB79U2A$AVAf(HFyMnim|ia^2A}8@@X{{$e=$p%i<uZ)b4~C(kA30O~X%>)aFp
zrp`?fWa^Z30!^KVHntNo#EXqQFJe^tF%=`vV=BfpG*dY2Z0O$1)6T|rYDRZ;RQ+wn
zL^yaa1g={pXacNBy@7+b$+@9`(#o24S~XE%c?k*;JR1s}xlNu8C49M!jtvE#+Scew
zU7WrPc{&dOzNh5MP~fO-tz|#Z*S7V=x0%1UtREnpwXI3}K^7#ij|C9j)z+)grpdG6
zC~(lWmI*15(Otd`#T~Rwo(-!UL+I)r)3vw$&bF^E61D(h06lvb1CV|MjR1si2cQ_j
zQ13d1puGt1Y?G_QLM9Nrgcj%l)`k|Qqy0;t9%w&z+CcLR?kb@lkYz6b->^+)raG_(
zq$a_g+UV49I5hBO?qMi7@@pt?s5bQ_b}Q|Hr7jJo>2?T@XoCwwsZcmX4_{oFutp<x
z0jHxS$$WwPtm)ajz+2YzYF^+P3mVM;e46lZegw4UNe|}*j<D8sLxCf#bsZt_gf-B9
zu6c^1&h(aEz`APwmR_tnk0>T2j=4bMi+JQXGI3eKBZnz3O2H#Xun0%lJEmMJ1ytpr
zEB1*R7YU7{6uWZJv!UQ+gH*{tR?kOKSKKAh^axnsN*`>?QC_1TI{op?LCWSpd>fAf
zb*O-Ep3KjIuy^b)RJKvoUsu!ek+6V1-;^n*M7BS&R|gQispu{=F})g=2y8e4LPJa?
zN6Q-mCKkZnxl-k6e+phfK-7Hz@_ythLu=BbV!6&J#rP5GVR~UK5e{;QMm(TcFewlS
zEHOPg7Ce?XXZg*)iEENlBo&0UEcSE!V6NgN%rvrIID*f{k7X!7Tft+B>8)}h(HY!+
zk;=pLc3F@k1jOu1wj+O<>Fu)M!Nn1L7rKX@GYe9nm@-Zsg&CuVuE-vkWJ*(2kfX(h
z4vBcAaX>AFeP~Euxh&Z2F#sqG%9gc|8sFdoKs^|W=Pn4>BHMl-1K;70aKes(QfwF9
zx-Y!@n;u0A5(^<UKmf6CrQqOwh$#kuxax=0Vg=D|%u*0YOw`aeLwfEZ%Oqm$kPjh7
z+0`8`9FE4J6D?9(nX;o51phHN!x2#Y35VIy9p3vRD;RS?1TgUtj&dAtkw?M{=!Q<a
zYp@#}ASJHeU9N#%KxAFG@#__LA?OB&OA#EUC4FTly$~kE<QoBbCv-X@;~aB%1QLJ2
zf#NhAQzoYi@;6S@ze&T5DCwqqJOZhk!j&eHC^hmP&rl(on2`~&-72SdhW^<^r#wSM
zwR$n;4_Q!~IGLxZBQfXG)Df2jGj?+m)ANL*L{rGqZ0bntC&aNgw;&+Qy@_5Lk?^hR
zVI9%(O%YLe7i=^%;8n0GAPOP*O_qn*LjpF%NFlO+0kOSiS4S}R5Drb|iP_bU*j_W_
zKvM|S9O?+hKGc!eZZo!Qa|^~qqJbtd@EQBHDZ~m~2u)@Vyi7J)Ip*d6hC>|~7n;JY
zf|H@i1_IKC1|vw&I(QL-j-O7GRb*b6Yg*c86foe4T}R9NoLKCet|TC+XbRoJ>t=IH
z%8bd)#HvAo;Q$6aLxeU3a?O~nMq|s2gTE=R3rrjiM6cp8t))3;#()=s{Sf18qOhMa
zq^3Zy`;0=EYw(oN6c&a@&?e4&e+O-f3A;~?6egWhBgL%*6eulhJO!iVO9CE6o8rYl
zw9-WEA6zVlBVh(A7$r5syI_>E3l)r#s^T35=d)g=*iSGUfo7)3YP48rq8L45np|p;
zH(~@DElYRkVoezh@CMpsX}V3r#5@^RQ@qM}18s)Ck1_HZar>RQ8J|7y_}LV;cDE>m
zWdKi~O?E51d^X0k;oY+-wF90#o9tS53o}DgK8U-iO*~aLj5{=1@E$dV!38r?GkO1l
zJgFJ=Tc=lQGK+zKDFN7t+VwK?IR9!g=X2PSyzFB!$kqfPTxaIcfGph+Uymuuv#wSI
zcq@@P2_Hlujte=BMD~?uAU-B?@qsQ1xcEgL85Wl$AOY~Jpk=)Bt55SsZ;Um4<!$}n
zfBLVF8=zlNI;bbeqzw{~fBG+Pe}61tbUwQE`F|g^|K)GT^ac3qbd~UYd}&FC`uJXX
z`|Zc^FaG|o=U>+<{r30AfBegDe^=V|mw)>2|K;!g({KOw_*cIjOV%LK^eFc@*T>s<
z{GaQ06HOO5lJ>b2ksrFsMVYy)f2p?-{P&`_fBC=u-~aY^zx_k>a^h2V)&6MjA<|b?
z?DZ7)d)=%!)7VWosehxFZZ~_`%m4fT_}A)XTT{7mbvL^g(bD;TosU^9zn`=lJY?+T
z;_F_&*u9s3Tgh#6s^Vwu7Zry8NkauM!H?z-%)?SM?$>+kU;kb2fBEkpA8%_$w7vdV
z9`o?j;P6`AciZd!{_f}Ech@^}!bj9^S0KqBn1Dq!b3Jy$V^ggFhu_}|e{I?df4r9n
z8C@H}<!)CD=__&DLB)~P#Le-t+UYZ$wN3=*ycF%XUz1b`<*(0!XsPlzxc=bg%eimM
z0q^?#xwr4neGA{#92k9FUk<E?7N4~`@BA;T!I?R$DT?xCwK_kwR_Cv@27WzFzxejP
zH~)`gss3c|*FQ1;;a;*0?kvABIKv%5)l43cFRQ_xk<~6fNW82DLupo%<@9AWSkSow
zvZ#M=1w0|rPksUA`zv6`%9evunzomN0~b|R6FJq(YH&@<YVuWkRgDgbs+Jy#FROvL
zj4QzMA5&Kzb;?y1z2Q<He}4tu&hM{4g}p5YCj;Ee!FA){j1ha==zdxaiA=JZ-M`Wr
z-kY*o9lz3=JAG;XOZ~&jV$S~ZU;2Fs^!6wA|C2=iS{j#S(%CA^{z3yom22C$tMJ92
z!^1qQblR6*R>LzX=ep?G^jouCR_yIh_WGZY_k3B)!HIL`<={Z=nAODf__EsBKDBnX
zUuX>`6V<wDU3pdM3X>?O|DuKTTeJU=Q|%{P{ZA-6cnH$C^f2^VU*x!`FKz?-`HAW3
z`*vXB;{RGQxpiU_OfZGKTq`!@vwm;Q{P8Vc-{((u{GZY8^A19wZpy>2-bU9g{n5?G
z{Ex>L{)rm!oo*tmKf5WQyi!g_Si-WJfS1*R7jmm6;AJ($nPfEqFRRgKC+j8hjYU}Q
zbYCyRcYdG+X&knW3VA)kaP8ab5qMqAJ#)5ND8H^0p;%ij0<WuG`!<QvHzwab1-_pB
z@0?8~g1fd(5_mnZJ6-^`dO}`StngXSiiy0g2tvZGqL9}W!9KKA6!ML=@C?{ruf=z?
zGBP`DJr(kLh<HxjDhhdBamJ&-R#C|7iZGXN6@|R4$S{=cXb|$Pv*DqGPV0AjwHn{M
zp@1WHH>BCG$a%U%ZWV>Rt_UKct)h_E6-WDYkR|fE;x#|X-bB8$8drO-_T_4P>&9}I
zPp4-hFNfI9{^|To<aI@mcW)Jiysl`rSMt*93c*9O)gkbWHCTqV`|CCM&RNmi?{4cR
z%C84^wda#l!0T#rml08VS)s#tmX#8DT@j%|TSXz?nE$>4%D$fe?`TRLw6I%Gg}feO
zxLfZPg}koV$0sqL$m@#N`AN(t^1322E^HNrd}lQlz5my%@h9#$x`aJnc|P7gkL0Uc
z{-^gE0pB#4KI;Foyx5fT`N>AeS0fA`{H-1d)?Ziq^k_riEAz*vXBz@vReOH8Vfnj@
zaQ^c=-INo~x!dr@{qm$|#n10ILcTO7)z2;d(i6@@VVa*?{G~^naw5(%*Fu4x-&~B9
z&g6gN-ANrqu+cWcv;4x_%KiBz=l-Raocr@j&izX-IX6hHvYJ?~URDELpv+8-zKq{m
zgnMbUKaom*!jgS|e#s&5#o#`_<lMjXl5?Ne^Me3^*VQJHo2eRsFRFcd$(eudC1?Kg
zyyVQ!FFEs<UUFu)t%}Ery!>;gNzMvjO@3LWj;(^HV0iiGPp>xf&%D~qf1X#H3vsj>
z6oD^{^zhKlYP0{sgTRH@gsgUzUuo_0OV0I6FF6+|6ZMqP+GeN!!z*yDmz<xhz@L!#
z7rZ-jaB}y2IXDE?XEjCIzpQq)PpzHp7g`(l`TP(;;EQVTzvl|D{LK{@O9B7icn4xH
z!6=x66UE@m!GX0otM&629$Lm{m3RD-#ydWHDUDz9QX1#Y)?x+Ddu!~EufTfS`N?nK
zPu&APKkht`*AE$S0o*Dk@{OzA3QY;iUn&2aO@9T6c($%?(3ckfy;>B%W%Gah$VWWR
zy&T{BcLZ4l?Z?*D4f?{^Y@av427Sk({<whLzckWsZPzn`7xw*{&=>aDxNq!L6Z(#Q
zbVVAMUm5B6j(HA*3|n_M=vOR|drcwVu|cj37{4^m`JHhhRqx*0gkD>hko9A$x<TKu
zFRffL_O%rHj=Dz!(%#vGUhmw$IY~YV?T@#=`TDPn+sFLZHTuQA6=R*VzPDKH&%^#-
zYt-9Y&3M0OoyFD*@7%mR{_;OHJ+B<|m$mtS{PbLz$jj-+%GwO`f}IGNLFc6ytWbpJ
zg`lnYTQIfF@NZlQ!lNSCX8{PQ3b&nkDF`jXcN{qJ7c1&(0cbH^)fRvN#exb5sPfpD
zc_|{VVoZ~C6v*Q`FGc+sy0wKcMz<8?=z%-)qOLNLZ+#)?Rzw@lE23aQB04Wd&VoX8
zUND`xL;WftN)@q%^XeIjIK5M(EScR43ivDdbA%Zh{+Ll@9YX*eGss9+8AIwZB>HzD
zKyb<eGLfZuUJSQJisX5bT?R3I^J27k#PqE)YFwCnQ@<`uJ`9!~)#pWY>%#KZjLD0B
z)r{jqzZhRMC+3zRODm4gi-;_om|KKRA&_rI95^BYV`K=)i%~J|E0SfeGTOT_23}Pn
zLhlHK5q2^CjM+ns-MkpphZwtgomu5Z71B%=bmWY}>cpUP(jAR20AW|bEinfJCU0==
zEd*`Gh!%i0qfi(k=X+`(JkEENxSoSq^l*gna$&7tRBG^w&cWL$!sX^*sGN5f_q5{;
z7MnT9=hgh*3S^7Eke39ZZ&Q)pclhAVhz>`%9L*>AVDyLFJ9k`wrwG39h##ASEGjps
zho)lU5$iU^CGN3qQ)J_Ks-I*dzvI_BN8h65d|APHe#b9<j*aNeP(xI3-fhy8VtjM(
zhY8-c30ef_Rhwd70E^m`TON4R9EiyJAWCyY{9@55OZGD_p^Fo1$AGjOWW-an_xFUQ
zia%RWmMs9$ls9^<sKFcCqefN>@QzI}^gGYk914ECF|Z_!#Bnvmz#D9#heKqqdK5(U
z3o6ZpJTqoZ5}|+{YYxTZk`Ze`V#M+l68|uWCudJyPaI4A7OhK=Mo#5&AeYtb$sJl@
zyt~;_2))_GqI}w8bjmA1#>J`J6Ld|R%1=SY!iDf7pk|tVqPRMi6o(DnNE*b3euyeD
zDuCavoH&kpFfHOV>PcvY)2JsCEzYB!Y_&a3dgUKkNOU}DZ{v44`#{NeOi#MW;UnqE
ztrh3<?8y!mXZY;NAcjM#CtcZv&b9ndoKrn1&u~yFKTH9M?d;;T0*&oN#<(M(=ySs#
ztdAx|C{C(Qa;+0bRZpr>1f4I44dcM-Ngo#{meTDMcm{=8xPYy8GJ9J<vF4<x0b}j#
zBDN`~m(XZAvE<^)34YqcAv9Y~AD?KHz*sxG*scqX!A^d^66aiGM>>E+-$g4_aMUTu
zQUUku?4r8`_w0<UWozn7lsFokb{#+bf&))xtcAp;J=HE^pcll3<Iqzkssg&%$!t{x
zY_n4dtrk+FPEdh>B6cdPRw*q?m{=T!%FMM8?<{$*O60$tP5dCBf1Qm=ZUOu2O!_Uv
za!o}PEhLr@$;lSby~H`edDq0IQgGrmu|=2hC=KzMl{juEvaXe&Z1plf8Yf;O?M(3#
zjkIb7NsMPwufe`DTW5_pv6Rqm0lsIFDy~Fy>|{cpfPB*=<y@JVHIg3|oLWlDw~&~$
zAU`?+^51mR@3{EU)kLCH;$WD}DOhTp9kYqZtFF^!jnaRib+t*Zv5Hfx>33CeYPE_|
z%&^$6YT=xTG%Iq}J3@*!oLWl$xYz-sSEB2x-iKo<hvY(HX8GS^R!=pJGfbH(3zEvu
zc53FUd6DdKxNfx*CB9GblX3e}-cDx*be%}4J)Oa?M=f?Vt}PD)rFiC=`YO&eBWFrk
zTgZ|*4riK@nUZyHA<4SuJy)94Qla=gAQZjpNpOcV%`S2R;@)MK8pa_P!~h4N7@bl*
zcp&z)owm<^n6^{<`SRKzHx@X1X0lO&KX01SPJn`ECZ}ca=}b#H!i%#n?o3eROcT=~
zPCiRAL>zoZwnRVrtc%tiWH!^1gAs?HB~K&nX(lc&(9z5wi#P)Dg-nu2oP9_}yvngL
zl+^<aG7DkTcd*_~r9m$CIR27F6_hVCnN|(=H!-~yaNtf$iq4=vnMoLn=dNj=IRYp6
zI11=TrdU9ZMFBWPB2vH}GA;QFah8e7q=4;XiVvlb&trl>rQn%X{3`_{wv&`C#SG&q
zYC2A`<cTSIPR6l{T+`D;J!rVNiK(aPc^N<O!=crgD%BV(K1CN)uq!6%hKk{?R;3-A
zC(N7TJSv9cOKvj@nW)5;hL_k%aDB}hjL?Dj<W{NE`1Q=n8ZjCXd&Mts0c`ZbJ(Cn!
z1-Y9SfFHEsPFAH3N8)7%FmE{I>Y&A-KzzmHJg7mY2*C?-E>CfW7vx-C2*-c3bJCCv
z2V51?oqG$+DsDW(<qV^VrJW&S4?w<|D$^yFh9j^_rH=H;3qZR#Ll!4Sl;Ss8b<Vcp
zrI0x|wPuxK>?xwAo(c<+Q_U(imV(S!4+y2`rMNed18i36#c?XHGJ9R)rnn%si&L>m
zH%7j+g+Rg}HQPcUE*>ZUtVJ3*NP8EAmT|MIqQ*q#yIGZ;0W`e}AuVYT^)7@h!&F(N
zD~GzX0JPMwv7{|iYg$nJN&G##j<d2z4F+@WLhwx-mE{&IGnjH`x%tg-6d^-cX*ev)
zt-j;5EVLjW1=&1jk@gJD(h*F*pO!`XGxCuxq@(P%kp-}A9G^vWdf>=i2#1a1Q(>f~
z!OFZKR>M*F|1<VBx!UABbLKo(Q7d?n`lYl2k8Ll()BXm%|4H8xuZTS51`MNs!V#Z4
zlaf+WP*jL4HjuB?zRGm%K)&Mmh}ix|l8X-MeAkx|fegS$l9Miz2Cpx#0x5QvaxXkr
zbO&Z}9PAGCm0{hRP6w#j>zuNZ><~%xh^l^*J??1UcU!fJBW#jJcYS#(NTYis+GLaM
zb`=K}CEe}%vS?g2j$q1G^GH;=nj6PeWNWi$Jpxq@*JWvxvLf}<L2uWuYG7ZfR-M@Q
zWhfzW?Q#+mGS@D)nl}*`@R(^(*!Zt6Ps-@G#1e@oVHI2G>1}vYL_e~ND-PXD=GY@q
zGN?gK-ak*JbGRs)UBQj=libn|2EVK|WR6{5RvVl$S3;250S>;~dcndkht5bW{L<`<
z44Jhu4bLE9@p_Hf<cVEQ<uky_FWb+}61%>9Km!NoyOfyhe!DO4P+mD)uZ(aQRqM48
zp2^IPAS?bT?bs19vq=-SOj%Smuk|`)DM`1E#7Vb~P4e0X$02wmU+S(qAYV^*9E<C9
ztky}Czav6<`X|?GtDJDpOF5?s(VdsGQWX-q9tn|@InaCMpDr^WklsQIZIj=?%}d#|
zic+^8iNYU)u`dSrObC5#S`%J*y*95W2>RM-eMDJR2P>XH=u52n+3w$}H~9H}F_Rlh
z!)p_r@W|`^0x^T2uTAus0Q!F6oU@wG5vAhJ0CPHt%)q){!#z=r*K4z#z``ptG(3oM
zPRZiVV}<qFfz83gdhNjGWMYvh>xQug5#PVzzH=1Hg?)qduGb!HLi5J92Rq|`KUXB>
zaZ4-!WGy|Cs>t0*s<g8@k9Htc5<>jeKenegF}GveoSq4OLDlc;W7|8Ov9q5mYW~gn
z$JjEbGhB9TThnu+_d2K}AuaZ_eVWm+uZZ@MM>O^q$M|5{DJv-OOVzQ+pDWt8Q!?su
zZj@qwahglE=8Nu}OZ$<0F|Dtubwr98opxkw8_zcub!?l?#G;Pf|2(sJMvhd@RO3sj
z$FXZ<&b>U7jV~o%9@}0?PVPL|eXc~B#hm>Djpy_6<p+#@OH!KZV>c&=h|XA&l^r7J
z+RTogpVUS+5u<~X%G>*c@9Jq6gU@O!n*h=AC0vZb=qU~&K4^jM>X^5ru*s7a*rtxj
z7qUk>h@cye`=OA}M-mDoecNO+J0@+y%8sBxuh$4j3P<$sFwaNw1&98<cG(z@bnqUD
zT9_WxBT>Za#LOc})#=iTWotYZ>}MO=k*>2?Hnbsf#ImUk*CQ6D_GOC1`T|*R>K0xk
zVpBPLs$)|*d#YD1T|sESQ$AyN$y5Cl$Sg-hN5N)^WlJ1BODqQzhtP5)3*cXc7T7$`
zOtV)qC^sHrX@Hh;h~avsUI#)fPjr|mNAf+D6_j1Q+OJ@XnUJAJBC{0gN-T%Ohr1HX
zPVLqBZryLCf4gI(uSN&k^5!3pgw-IQKLQq^tjCqq99FB-dp5P#eIoz5gMG<5UW1`x
zuQn8vpX8x<es6y@0jG~dEt{ybF}&iI^uow}{vk(YF+0o7Y7*tfva@;tV$0TaGE|O0
z-q>WI91*4a@x#XQ9qRF=EM_uX3B9s&FvO;GYhe~tAqI4WY~Gx?5$n$zZtul%wV3}$
zL~pQ0MA$vO0k!b_yGu=kX&D8kN`#DKm?{xAj-jd?3F{+Nl_Qb8oP?Dysj3j+IYOo|
zbd(6&!aGZPDg2x;i>hSG+bhvqFA|2WU;;fy*bLqvVGKF?3H2OKUtKmp2%qYdZ{=+T
z!(WMzCHxc!ED<(^x9)Y=Jq?yd$UOcbZJ1(Jc2^5AjiI@mvJ?Z2Vc+!DbrRdp$#jWm
zb{@fX2~)KSah;Du$_KTzHH@7S@j0x2hD?M_;SKPGZDDMm2uxuT8HSUZm&<2)QbK2g
za=!jjptMBTVZDL5u){jD3qDsg5R6-5HGugNA?uk8ff4psU#+hX?#SvFP6%H};}_;_
z6=*8qMDzusO2E8&QZ%mMd+1hW+FOkk9f}NEvAtu;TV3Bg0Sr^FDhB+K<Wf?x@{c4{
z)yy~-Qy%L|db#I_Pz8WZr&T9&T+Br&8x&StZhJyFQ(?G-a%NQaF=2vMg{u-y4N~8h
zr8g^z)Afk-2<UZllvHwhhO?SfwtC@YDD?%pGK0#4X!BU7BY`d_W;v2Got?|2a_{FS
zp_FFrbi#W$Fd-UNg#vQ~lTIABB&CDe_cJ0YTkJ3mtFm_wXY8pYZ;shqt;y%jDfy%*
zD^mZwC~HzxwYUXUE5FE*sA`d0fN)-;Bg)!pnpRvNNAeE+=8mjl#i5Z^q<Jy2inW7{
zvsgR$XqHyJtd~en!h;|`;j8y<+VJ|lo1v1Ham}0Sr>NSJ)**(>-dX^}f!TWmw{qrS
zRdOoFNUOJA!b%KNm@ABx7;-^Z7%MU4f<BU4{jsbWI80jBgXj#wv8<Y%-&m+lLnnq@
z&=p7Ek$^cBPvH?sd8Lu^L01wY#|Xa&1QdO%mQ2DMLso9Zff{4Fe!$z9|Iss98_#c?
zvPY6<W3}{KVwHin5@Wb(z}pzs3%reCy*(X@Va`^?X?!G7-Rbh776ET#So_Eh@4~W*
z2m6Smovq){#<~{pY&6$-Qo|-^K~2I+jOGf0XrsA;AlhiEAb_USZO;|u;A{Ngyi-o-
zQ_lXbt{ZqZs`aj0f~i;wdp2dMJA!PDZ0sY+)>KM)#k5!}Te?xKl?~h|ZX1v|WOg4(
zexUcyQ@7j0jH_C6i{?ubN04=q3%YXP^pjA!7gx7Co+GOexvEy6t#4}q+Pa+3m9wxT
zIf|bY<%^{^t&H#kw>9QtRj4vYf?l%AhBFP;q{<wD^s<}l%WCpdhG|-r^qNmN7C<Fn
zWjMQHy)pZvhx-j!GzqJcJTrR8rBX?j8GX7Dz+#_jM51D!Rt+k4Oz`K5vJo=DD<`<o
zr?mr(&RALRYljsNkY9-~D+kHpT$z=_=79B8NppS5(wqCo?)0z~E=@R(XC=4wch|XQ
z^2$(x(8_Uoh#2-<Q8uxoI_}?kC2-me<d9~r<kfG|*VAQOSMpQ^c~on%Xiibh!4uk>
zyAd$$PWxA((L|Sfx<aD~CxWe)NOQ{4%x<$+G=o7$Al>=OTq9~CX)pg#G3({&P6DJO
z$&8@&k~^ZyD_zMwbR<-QR725aM_1@EN0RS-Dm;?tc%^GHO`^*!U17&WlUusNj)}Id
zoNEqYepn?zPdFxZg*<a4sA418wsqZ&WV5fjLdgkJ#wyvEquG!q8*{X5^$-49Sf@63
zE!>shUlR~Rh6xk7D!iqigwpNDW>0k`hjO&(=7N1~T6JPyGgLRA5Aw>BqP%cF`N5sT
z&Bpgn9?ga~JeV+{t2Qnsgws4%$Y-G}(6s@2&J<ngi)c2S>98l7c+*ETc}%?m^xdS@
zwVfAuK0>}blB4yxlI-SYwZL9$Rtxkw=XOoD%n?9quh3<}l&;!<z9!onYD_fS-<KK_
zPOnrOgokjJrpn+AQ@SccKAc+WNU{yGwR>XY6OMI#M7PGatULJVyj!&ckj~XrNe~p7
z?dw65jgb9)7lUwqu?le}V0BekGvPF5wUYuXoC~c&oe3vUtGVWcv)0#+3$zN)Va`M~
zOQb@b3G%{Kh%@0ta+QSFQEj8MsD`rFJy&$wXm(h=OLI6wUS;tPXVt5$@KG_*lLh=-
zfixwCnhaLq&V+Lc)((U^5#f<s&p|kOVI^U8)Iim^f2)PLaSidsD)gGDVXS~)6LnfK
z7+P)RCjdvak)L^|ujG1gYX?D1J3ErBnJx4lx5QclE#^q{g!Y?N)_G6#t2VsJ_#CE#
zRcxZD-7g0G(kgin<wxv#@ddxy-TRBdV)H!{Jzq(#QolCl52P6Ht3s$%Y{{t2Z%v52
z9I<+tEm5oXJTP01gvAPG%TIDk32Ie-?1~{BW^ElwZh5LL>bwsTwfLoATFrlE*H`7r
zK9cOM*G?O9Q-^6>M>1|%igAS2Yj3kPiL(7t_K9L~)zMEO|H{v9+SQG)d(@TXA0KVS
z7V_w<gvB;8Td^q14F}$et!B1#Vcu2EUElKseW~mWj|AQ9?27Gbg0mfol!JLCbVORm
zyhSEAgqA3>nBlWTvB{i#mMGIN6)c*nRR^$GY%%9X{0P({V6oU}9)iUpqj`Xe#SlC|
zMW|YJ<Qt?GTr8i(JOIXGiy7ui6kE&#U^G*!CKu)i&Om=satC9<WX2bA%2EzcmhLu#
zltrfXQ?J)0%=W4fUyg*OX1=#H@^30{i+Scie!|qQnl7X$HjgKeSZp9qAd!Gn6-vt~
z%j<)$Dn#X~m*jGaQUf3sxv(oFmm}feu#$WHh@=`wEEwC#gbDMzDomItMT#q~$x^Hv
zKrF9ySK4Tc90y_)TjY6p^SL4xBJy{KqvBMEEMb~gO(ILYwxl7lJn?Q<8i0FcT;oQK
z*H}BpEwQZNhdmOlRrqR;NQ%I-*PiW}2y`UqNjK6FaFAI^fc+EQAAn}BJ=>Yv`UuoO
zc7Lyp^h`?qq=<gOUHaO>7TLwDtqR%Yoqrxmcj;?~H~E`?5=wWJy|%J(>xT(i71w{H
zd-*}Mcubn|2U3Fb^c|G4V{N79b@1nkLcdXXEU8VzbE1<fe$3k`WzBu!RK<09?abyf
ze3)%jN$4K0ec7aRKa#w@aU@r>?dbscUR%^;bUzY0fYYWB-|D%dtfKwd$(ea=VT&{K
z%EA_9=CwCl2VwCVt3{c4ZFEDMd2Mrx67$NO79-|;#g(jw67ynBbF_ELdgVpV*M>7E
zhI89;&J5~LieCNb4E?$7-6q(>+?dW83}S9u&X8f|-i8R+Fmv0z9fP1}p3U%MjzqfW
zElDpI5{_sfIA7|Nr8(!#k*L=u!Paa_=Rxt@W`-O|HqoXu8FJ>ftsFrEWGlz{XPdyW
zR5u&J9GD*o4^TJTz?{2J1-`9$FhBD)|AS=RirCo=^JQ*3y9tCcw@v8`mU1OJ&$<Me
zBarURx0f*u(O_=7y4U+FiE4e)lhHyW_<Cuf&2306a~pgiwM^5$j%3`js<sMMv737(
z+RZKFc@@5p5g97XPeSQflylq94Grc<RJTfR+s~b$gXgZ+n=8mOx7PsD<^Cj;vSaPp
zJ~`!YSy~#6DPQ{<t?_J!S91dX>9Ot*fGiSg+>)v>)cf{o6P@KJq4axT*~W$<G)2y;
zBy*q3%<4)y_qpuUUWsf+BE@%X9)Z;6@cl_B-DXbHw<?61BSCX+^^QPoi(8V?1jM<P
z?$1;hG}DBx%3pKY&d$8Wa~V!aygs33Jt-PI^}Q!+X9xCLR8Qvk%70c}H$A_M$@I=#
zw#DhexonHWwVBJtcz%gzE*s;pZRV0K4%cRy-&Nt-Oj5a3m^P;@tMXE9jsVRNYv!`;
z4Y6jL^Hq0l0O$Jr)g)J+3*$R^i*wm!4YhHa%vGU3&SjVNCd>F-wzc8b%!R#unKg6S
zV-2%rIxlsFSu@w?v4&bRonO1M63k_jJQs^2kmkmCsCXfu)*OM96ZcW{u_IVK!$NbC
zpa063)|<`dG+nH+9v%trNIYCNn^|>_L{$S0moG0@cr$aoeld8s<jCIh7F4mc|7O^W
zovfMXiliDqG;ORxr8yFoK~U^Sq?vp6M}+DmHy(l1Um%=e_=Y%rB&<P{@M!EseZ2*T
zDD#t0BAlt}1@<{zT}|uZNf8YM{KBqo?2w;?((UP(u2pu$k!YK+!M>0o-ro0?a>D;g
z^x~wHJt(JkyC&IlCE3djy38~etPyd1M)y;ooLF2fW4W9%j)R7EIzuk&h6VeRP`Z64
zuXV!)J`&#9)Md>z0n(zmeZX4CYu)bUhf|hXU@gq9ZZKqKRH^EWk!npn8&s{RGe*p=
zZZBA9YFB&DBSkMARJQn~gUaTVycvdm%WBASK7y=k`QAuR%UyjWS^3vJN6@q*LUlr)
zX<Q9v&5ZXy`axFxwQ8_0URk~kUd@cxx_{_5xAo@0oo0eHSTsj6C||@r0_nNC!s(O(
z4HC_fNJ|>L(@e0I8{9d~9%*cX=Ui?gfH@bs0mr$lX=jO#A#|K!HK5}RHz?7uyt{fl
zB|IJx#S_f(-M*;Wl6jM|{2mZ*u7t4w_2!BgVsLM+NYm)@Z>|LOI54h={wnG7{E0jy
zN>RPv?^Q(=*NMatW##>aOQG&2%Qpx$SCo9wmY$&$sq*z!)a>|%f9Z;(E)nmFG#5+a
z;!n1$Fah$4=)Vh)SD@}oguEi^ln{9(szS@=Ee`>FZ9h?1TjxV0yZ%8&rNSLER4E-N
zv?SDA3Bv_K%@uK6)1cH`*+7t=%O+PVlOl~ve7q?>xT)IU;ar)t&FpfST#fs(S2PeT
zJ#_mdUqsv3KQ%7mUWsZDG_AX_=^(nIkuM6hL(KYyYx^f^uG8Whh#S;!kY5q!7!6L%
zl~Jj!&(d6}t=_G!)mG=$@8fONR2!&<1OJMsMSZhK&FiZ!uN>+h5j`%8s&P>86Uoh~
z{M=UrIwno$N`UDG3FpePeUNajgsBaw<|lex%c^QQ{95A@eac?_tm{d=tg2ow#ak!#
z%1?^&JJ`ZHS?KaJ*u=Vt>2A%#QyoIi6=`v~l$<M({>E4gJ(DBRHdf<E>WT<+(KxtD
z8GYV!D8{n>&IgV~F+Xm|srj@z)DX@;j$~w6eKu6VaGi%L85FNA`73M7)gaVd5ig$9
zZ@R{lar&8ImCfdrsRC2Yn6AK7Q?&PLHBNC@KQ}n8j0yzf;j`EXT60CJK`<U-xB@JA
zSH?<2*pHv6`^lwx>M)~KimKywrEJdCty;;RtHM$<?vIE{<rb^egqSO^E)7#{vsx3J
znyKHK;56h)ZH+r(DSP#^kpgPaUNtVaT1UVq&{nIpl114?tuQI0T76M#y)ZPv=4Z@7
zZ%9$@4_iyzjMr5ZZhqEV6K=|UYXZ&iJ-F6{n!%>4HBd9O@oKO=Zbm0nllbayT5)>S
zT`cBy4H_RomR%E&n$h2yfOKv)PK}5{nL&yw^xNLgwu8}gMbaktolBd{2J_}8vvJl0
zq*I3%t<5a5cr^j(3@@Jqa=J45DRFd$>nI$ZL6I6xFEC9gI;V9DMxC9eHDJ_N02*|k
zD*|WW0JlI$zx!Mf>p&CO-irXO32A*3pxvZXz6Q{e;Pa$Rs+K;sXM7X%n%CdpdtH%U
zmf!D+)DS_h`Tea4dT00Rg}l?7z6MwI$WFN**mXjU)&;v$^n=y~yVKjgF4)c6=?^l-
zt#^JM-1YT=2L0!VZn0?4R-<4SGVAt0>q2H<A!wKWa|JXWzRwlm`D;C&$v@RB9j+V^
z&C;fz1Ie?v0fe8tGBrVvJZ<lHLGrY{-v!CKF>oaL4PQ4xh&*36L#RA$N_3&}^e#ax
zpDR-xKxJPpXz+Zlh$?hO$k?t!XMN{>LF)<2LzaFQD*Il*5oIO07|=S1I~>9Mh){03
zzE5fQg3*PzBm8n9?x7dtt0GG*{;+wjNc|ze9o`*u0q$^|$3_&%D^mr6&gBk4>x<bp
zrWGz)Hw`#_sde5WK-In}_Vl0-S9btfXKy;Xm-a3+9lCSZhR}4R|FjKZ>9AoxUe%y$
zZ6B}tS7f6$1g5?$a76U4JgqGsYTh6X!Ktqg91-2A?ZD9Hb$B~4*t`y3&TB)v*I~pT
zf?;19I3hlb4f`R41x$y))U^LbFxe|oH3g@>3ebk&^s=1vuB@l$^bnfz8e!=WdFhDw
z1h4MYwIMJa-X4qu)A3q;SJOP9hrsmSA;`=lw}yRN8ynf~jlj@GwtFKmw2$rEi|`Nv
z`{qC!lg9A<g|>b9-3hn4DDYfK*4lRk+7RaU<%S4yeSe@0L2jM|v;p4saMOghT^oTR
zxb+Q#HUzglzNQItea)Z^-XrCUaodApjt^fjXoI`RSB7@&kbTLZ4R*-gy9L5oUy*cg
zt-;+^LPo{D5{)FmwC@_UA(+-(gErqRY3nwH!QH!nDGc^af;NT0zDm%hAedD>McEb+
zC)yMQbDN+|fpGVBVhV$M_nJ3_!oGRXW}>h!9vlJRO?!-4^wqxgWojqfy)~FXuP+U>
zsm-wO4YVob?F3|RGdH>2X8#nVcANcEklKsiElBO<tCTjnTr+4BK<#!0PXTK824Xs6
z>bHT&3z<LB>naR&C))*L>tBIhp18|RgWuGdfGTMZ+Z3WU8~9U*s!IcH9;|H34fW=<
z8NFwqyNSqjL?Z=yv5>MYzgSySUoB`;;Mwf3or2Hi2|t0)<~_lLRCQ&%elbj%ZT^{W
z&Oft9+tkkmn$3YFTL?Apb%B<fu3yO(dI&OoXP|{3v*lX)q%6m9v*8}X%x1$qc#4@H
zg3LB3V*UH-K?^}>vt1v;&}O?nz);^lXxir<8D+kojrPbbYqQB70#x5GXdystpUECA
z%W6|oBW$mSFt#;{w4qve%M*nw%Q+w5t8W~%5Wf1-K?`B5FCDb#ZmFI7A&hO6;(fEN
z_z=G87D5YcUt1A7p@ksVHxpV2b(^jI0Ck(~f)MKF<%9<r<3pA`&Y&w%g9W<Hrab{6
zu1GF|NaXeXgBAi_-#};~;MEm`7Q)@SzZMF3xrA^8w=uqi&_c-TTL>)#z4i0|hp@NW
z{~v<hs$D^>EU~79ke7Q1PYZ!>wevr;{q^01M$V)wQV%ROH++5*f?r=yXrY~LwaFjy
zDf@mwTW=O+Y%d|J?-#TsWaWav5#*$-J`GraXf>JYi1M4)VP(S6>H~o#9QD<NwgjV<
zfOd`eF;_xYE#au{C$uFTtv(W1x7ZacqAmHHE5N>lv(?*%rJZWE^}n=J%?k$)vXK&&
zr6pXg?a!<DP}&kKL1_Ip0IREey<)7cdU^w}oIl*h0SgqZzC7Gup<Edn<yEfUI4ogp
zRgu;edl*(iZS_uqQ=Kc~#quiqdP7^<nAXqp&uLW3=+2OSd;XUY_g-RXE74YW7@jN1
z-YvHGi7a(R>Jh<hvEzRUZp-KRU*K)=4q$1wTJ%tkw_?x#l1G_@15e7by}lmN7C(`8
z`H#z@m>;ni`<J}Oy7h1*G{VOI2C0kf`Yog`w(a*Te|-tc)Y!)T7E0?fMB61xQY4Tr
z(-64jCoZ<^w}9HWA=(yD`#wb50CnDn(7SSc>Ow@@+Uxp8MB8#X7oP-dA$l<rtL=pJ
z;vK*ir2A$>gQ55nc?Yls;fhg^GMdP`u)$~Fb7))mTx`m3;qyJSeGpM~pBHSwGglzm
zPJk{xE!YC+(!7<}g6QJof-QtD-V<ygw699E4MOKp_JfGA!g;|S`c^(K*n<X}7qSJ}
zd6u4U5@!3#MBBpNVvBzZe0|-aZJ;(UH#~@_mCp>eu(q%X*aF((O~4k=mRHUSy+yi&
zw66~gwxHIxB-&*)UjdZ7wuQ7W_Q4j;`j$l7f>~XYXj{H$68JnRyRG%ri6hBszTS9j
zZE|0E8BTgqs%f@#f3=78^@sj~wXe<$`YWjQ1&IC%YTuxrdPXF@lI*G@p;|$aDoyJW
z%)+&KQkI{<H!1o{QOe~@e%X%nSFU8;qj;{2rcHj5qw*cr&YstoEBdPq?yIfG(_bOB
zFH`ha+t;_did}WmzTt?dlsRDi74*J359qI;_uiZ6FR=SIS5v6_wy%?fyRY^a{T1%M
z%{37AzRgun=vAbplrS(GMTTW{1%%Eo8;t%6o$1vlW%>Q9)oXYBRyS7uX5YE!1Va9a
z%opmfU|kn4j$~w64H0DfQpFKbb#E5>E6jd%GSFXPwk}`v7sP&Fccu{gbxgnh3buU-
zqrZaf_jM(N+P<36-~G?#TE^|Dv<r?1_35TQ0;x}6-`vXRFs!z(W%QS`$-T9g=y%Eb
z3D_c>@@d2NrHjtJuFai`Uh;4CRVh?VCkCAm;@g)gIy9=i!!Iq=Es_P(lR~w9-J-*w
z+B;m;{Q7%q@6bVpy|s0CI`FZ5F{2Y%efwTU&+zM4GAJ*ek@EK3qBJ+!sB?o3;_f~C
zNT+t#{{7<i-aa$v+;iN!yCR9GN5YB#W9mp)w;)U%Ngi|_N#iNiX3)PnFX&h<N1|>R
z*}+XDk&dCXb;qJ}vvm88MZeUjy{lh4X@aMD;Y9d|^ia^@Svo&2Zr?&@ar+iZi`%!Z
zQkn3b^a?)-rR=lURao?y?o#xEmv`^iig%9l*LpVtU3-9z8Ncs!ijJYbm!kyr-$r0B
z+4`NG!d^1<JKKqEHeV;M&|b3Hd&T3pmmxN{FWaQNBWOIO_hbhi36*6V^z0=serK=r
zlibqz%X1O})LvNh9rn{EF6kK$u%EUsSairw+czwF@}Kq!E3LFplk(|Mowlx1bcjyd
zS1S6YIc?vk=&+oQM2d)twaxD9wciqRzjj(Q+{R9mhV*u-?>ml1bnEYFTRZh1R+A{X
z*RZNVgSwYvHvM~b=^D31-7OrnD6RL7cVVw?&CsIu>Q<fW%l4Ivo~)?7nj1M88%>HQ
zjkKq}6W?L4>Zjt?P8NA5KE(D_iH?tEb5){~m*|vLm4#;6*&UM8Ud8XtLA_V;dzZdr
z;l=sS>I7hI8IK`6UCFE8oXR^F)DheXztSY{?WNm1xnUn|=M(R(+!8Z2eTB~z=@C#%
z7an@LCbu(&cifjdJageD9SQuJBdYn7-kaRW9ZT;8k3t^#Be}h%#Np2sWdm$sw{}a?
zoaWk&&|A}_+fFUsTkZh&CE@kU7uw1a-iZdZ&6(@)hxWbU(4h`(-*9+3Zu9Lc4jsSx
zj^Ta<h+??;0Fmi(_eHm3hgA<cHmf%2)b6GORMD+@=9YUqhj_p2qiwofhgr1mHHppv
z#SR<Dd5E#Y?z0Z3X#1W-=kR0uRzxS^-uAtS-WJtul<szUn?H9%cQ)#l#1V{Jlos&K
zmn1qzK|8AV01c1}Tg5Prw%Kz%&y#i(s|Mq^OYvMu4!&aTpk5Sf2l<?Iy!ZE(n4ul(
zcI%!*heUJ)yp<SU+iA%==W5$mC3?pF+Ia%>Ai4GR-H1+B$vtKEl6Z1E8+j)?<%UxC
z^qvK20r`AWqC+9tzA14eci7Hly=1Z5%1YjoX0*+&>l}k_E=qJ5Mtd%+1_<Yp52Zse
z+H+ZVqlLz5(tB<*^m^~qFTSn<+onw4o}uWD;Cm`7Xv3Fd=sl;p3S^tMe2I&<r&fx~
zEZWnSFU+DnhZPTY6?0g1{^Op*s)07rmG>kcZPV;J$M#2pZ-AryBa!ZzP3%@3G{`13
zu?shxyC+3i8Qa3pg|^vpJ=sD>z;Xgt=tyn_pDW5QC3~3=K-<a5vjMh^`=&0{Y6t+k
zXSJe>ZnL@{HvL<rCH+I&`N@wY8<b}00RE<!^G9-9BUgEc{<4+6yhD-MBFO!k2Q_F<
zqi8aNwn=RrUeKO$l6R;-KMAF4G>q+<fPTYfGeJhTvy*oiMMuI~k-<vyMN-{vNov`U
zjZNuJ=wT}xM$t}A$di)Wx?w9j`9yoz$c8Mm$D(v6f|+n#VTO)K??{X~61`;Hl4=cR
zI;HuMWL>|hOvdm%rZoYYLl*Q%$Q(AH2aq`&QM1Ds+Rkd;2e>(GLPI0k!)Ekl5$$0k
zdQ3G^Rx}i%J%*J7txk2`ArNh|=z3C!_Hc}#4q<4IZe5YBk_}B)Zzn_Vgd^Ti>Q4EN
zFWbk^8~3n*Ovd`HROcNQ&>nJsce36;M>G)J$~M;?;2h082XKyN)d1(0?7TDXw`p_z
zH!t?Ek<Gl>10$Q6wTFD(M{*k|m-i7&9%1%RKyuiKo`B@g?4G9%c5C+u1di7g0Rl-<
z-eKf!GvGRGpFLo~KRwAld%Ug)0NCZz?ofSp-)=t;=p^NRa$9Me64zOVcbDl6v3d7x
zUBA6wU)ICkudlC-Z2ruT>l3hZrt%J<XPeg6FB+Zlt;ur*x4XNY)_~fPP&u&8iOD;J
z^L+_yeR2nTcYCZS*w&{j2ex&)t7l?cx5Ikoa`0^BFYgnyGj;7qvPF~9o!#Be>Przi
zW!bpc6x%t^J9MDk?WiVL(C#+32^O@wkEc4+pWSV6V@@53UIhMiyR9+HeiBM&usgkZ
z=c2?G53O@0c6XcP+_>1?{%WpeJiFUUPZrVcHqs#x?VAL>!ynovvUS))`x<!<l5C&N
z^vEZqmF=Q)r*{nKZCYCos4TnNA}0~Wkz@-a_lwSqegs)n+uH$R_Rm2bKxVgpI@mCF
z+2p_d$nLhs*{^ITNAJ-zOl^?E6FL&91~t3g(#aCq%@#T&q34Luj3?Ad)H{KQHl(-?
zJ!m&u>6an2o5KZl_IkV7NWW@jjk9^&CdhR*n7d()la*z+^}Qh1D<@6w@O`d?-Ul+9
zJ=LMDW(!_?5wqD*4f$s`JF4OSY_sAz+@IY{Ywv8-ceA~od->gLu9F65H~iEj%Gu7L
z{`9<;w?(n*arc(wLhlfDwmESfZ^mx&Qm4D)_w~A~0rol3dB<<E&3EhYc#cFb=0fBV
z<(t=g|D7Iy!?T-R)azvs*et*PoZY@1`C`x5WO3sZ+RYy7ya>9RO>n|;Y;oOwi#nO0
zwo{uQNe&j3ZYSDHjpJ-Ld#M$PWGiWT&l|Seth1iiaF2vi_L<$(<hR=G{n`i4HM^--
zza?n}=b9~WSU5ikrCeaD4eoSE?rM7*r{%7mja+ozPG8=+3;k>{#rm4}-}M9lS8Xff
zs67(Z42-Le;nVT=?z$-5ntApSfM-|vr12r|YWsST(0o@L*wAuzwUK?9Iolb|JG`82
zj#-C;v+LCI4h3gdThvLwIRYtS2k5-$9SY8dV)mpc@+qlWG|CqB0vD?cYVP)L=Rtq^
zO^&zCB<rNl+tps_1rk<!rQzi4YI}N<yLDGt)Jf9WPKDk%|JabtItL`DjA~9%jznuQ
zM=eK$?tLDy$<0yCR>t%WJ!e;&+{w;)u1G(bJR`-0_SnMaNNHD3?wx2^eM`L)y6cFf
z3b?Eo*_>5vr%3O+Wr;4~RC`xDw&C9FYR5KND0j7En@p9v;@3`k&aTe7+M(xc(bGEQ
zoL%kOhMTkNYt^0hqyz0q(d0*ZO*Y8u1mu}rY-J~RW}AlAH-x8M?D2*<vy05`dmg%-
z-Mn*Rx{GaUPF0UY4sXt0k4WzY*@`^gJE!UqsNEnN3C^DsWgBdq@5HuZr#CVEc9AJg
z*uU)*=uf|=)cdl{dU9U2GMRT6FT2=&hVb%}P`VvkY%dSa<9CsZdvIvKO#~a9?C&BA
zdfWhvr;Kl9kXH96;-9k@<>5Y(>_nN|;|1x8rtWz2Ce$w7it&Y(PAO~O{MIZ*Dov2P
zsmaF+)pMJ-HQt88ss|F_N_7PQxKdpKK(5$NJ)oOx<tD$9te5QK@%})r6e|YgN|9oi
zFS``02KGv^YW$zhS3Z&hv(5P$a9f^TUcDLTW_kVMy8(1U^8u@8o7^?tc}rN{1Fq11
zx9blSzFS&A!gpH>KnRQL8JV^Fl&vM#ig&yAfZ@B{ZEW`5W!0pv+oo`hOL;lv+4Yk<
z^4>Iy2XvSHE~^F{Uwf$sWS9Le>rQlhwU-`nUG^K+yl7-7ob#aW+o{b5?c3&ijoT;t
zoqi3__sR@@1`N3)8vG<{EIW9>wA<o#4QMT|+}5K&|J|?r)<eXWS8nSgxnKX4+j<Za
zXuoMukCMNKNjyY;d583-Q|1VyxZL)2Yh?%MH0IBMxwuUX8)B%u%~b=%Ub(EtZzk`z
z`3a%eE2{Sq<-lyJ9FXOt<Re#yZPwNhujQ>?0!3_jt9AA4+-gmL)?1~i)3u=Nb4A&t
z$`7(R#hS-0sd4P)-eMgb;%~FLh6pT5QGO-a{hrXtV0qs^&*boWWu^|I`}{<=6#uNf
zU8}Szm(!CE_|D6`t5LY^ctp~gV0I+Zd%^4oSQd#fzj$lTw6&MmCIhO>5;beUlsN)v
zK9hRwWwq%cV|5S<W|^8bpt!6ZuGgj-GM`6%sfx_!Be^TX+VW5zQPu?y^|;2#+A^n4
zdESnbJw32!mSPm9DC;W+^}sY*ds_Lmp4J{#okL=!iF1Y)?3lHOwHMlHkcJ$yOxPMV
zOHy3*5xZJcX@L<q&CV;yU$m@RcU>D*bNK4PWsGGa)*wT~k+8^+LgGmBz5V{JdXnzv
zh*a6m7;M&@0J%)n8rb}6S1Z0Pd)BU2-1+zw#e+{@t$Z*Dt91{)eATU*LC%h~i<M8N
zP4SB+RmK<|cQ5uU6R_pElB~_^`UUlQsb5eVS-u0R%i6DAd*ctREid(e>ax~$<r1>i
z+U}WzwdJhkBlE62SH#-FR`*DxJSW~-Tgr209)Yyq$-9=bKMn3@E$22LB$HWYgdIuN
z&~OXo<w&$XwA<t(p@R4gj)V&0S2&WaAYpoz_*>5v-NCow{^0yte(OQHpS9$-9;5_X
zYg+5Ux0Nx09|YOq+BY9bR({@6V!~R(YHGG*SPQp@mXn$fSTk#RMsovlE!)hHVwPE0
zBO~xUYjxM9Q5X572R^Ewgwm~xjc8n4Yw1G8zzw!mvzkt~Hdn6GtIdk@tx`%f=XG<K
z512H|jI9BaW-XcH5NX!3J)S(8wW`={1M19j>hl40W|_t{a4)W9<2rMIU5Q^5x2UQE
zf+lGlN!GXcwLyJfw}7CPYsvg>iGj=3H=fwF4A*#T*RuWHfWhT}n*Z~k|Nfjo`~DvN
z{VeMEJ^KT#H&$=Iz0m*oZ~y$i|CE2;-+%f4|Mg$b(%eWx;J^MMRQj4u_)Xf2<&(C8
zpJzFVTIqDrs#=T7$honc$)ZI4Cmd$I<lKwpq#Ex{7ocPi|4*jhd^4G5c3mYe*q?lG
zgl~v?(<BhmC$#0Lf!XjUN<8e~X>wj;x1oreRabn%L0XzFXiwiB;spCf!r(GX==w*~
zZ9Z;2+NHvFHZO>9Hk!Ney+10|HH;nU?hm;`r$Mmm#&<wLLY>{_A0LstJ>SMD%{ecO
zBwSh>*K`h`K7O;J{{~KPyO#O;Bi^!S`9F@I$R7Il_{q`oXZ&0(43;}q?pI={Ja?=l
z&S<PKax_+)*M+g-fXE&y$5MFyjuZ!Q_elA&craSLGiJElR0cRQzv1GzFbtPznAC__
z-QgZRU`lm_F^?EC!Zl*1x%?V5QOwGEmB+Emu3*T7^F!p2S+o2ZF3!5-;WEEdJq?$S
z7te6HS824974tQ0t2DD2@;l^!`EBZcBjz_w$~;TW?~l<-iTQswU<gKe1a~wnpx6}E
z1rSF%30D3VXCl!pSE#>Ooma>`uo!I)$ISx2OkiE*PU;nM4y^RStVrJg@i|X1J0fFv
zo-#TsZCd(70NU~r0^Tk0Qj?~<Lfd<Y%qz6JPpb2CB_qps%?+J{LzrHou3kd*DdpHA
ze*KCePa-kyj|83L7SK1Su_he`#R|6YD{=N&p)Gv!$yaE^z&Kx_BQr?p%luR#*{*0Z
z`-pbC%s<Vke#%rM=v!^yvFlc_d%w*6=a#7!;CYFsBu7}GojkF6SBQH?INueXsq5|@
zLz8(edQy=c7Q4x~@7oLxZP?T3J!NnVyZA_G(xwG++Huulg)VCBm%f)pkf#50C4Oe{
zOxB8221k&<vDq@ln}t)W>F}&vG+82$ausEnKT6_`HMN40*<(%Z-S-&{Q#eHg>z^PC
zw?!t7?(~f=(MES#Yp2XLi+v5cBS2lQ;75RhG%c1XqGT~xW{4_t%9@;<?SB8Jx}6GY
zvEA$zr#AGP&7v44SCZA7dSO;l+xg8#acVce*(sVhx*>Xf1{FK)BS7uAtG71t|33sJ
zpUpbK8V^M>KdXZ?Zg!AUGZ)vwGKUoJ!<tOxoyUD^ifNAj;wLx-HkURyK&Ryhj$B4t
z$t8VKGHw}#>@6L-akG)UK^jRov>c{!uN<5{;NFWbt5skxMyECs=?}UBn!sl9Mq=FH
z!!pD4-u+vSxJb&T<%o-9by`!Ce6z9q0x*{MrQVg&t+f30N061qUte&)9YJb6k~DOt
zrv4FSL$s?XZ$5%${Q__f&sa!}wdRX0TF9TZ9E-8!P0!^>j7P9}NNPYe;xIlbs`->u
z0c?)KSa5bO1z{|>NS8^f&(Hq7#T@^I{A6ngp$qqC*Vxv>26Zg!Ar8+{<i;a8O)^il
zyg(*l8_S#Src;(`Fmu?0e?)iaj%D2!H_c`}<-6{UkYcv14(j-8A$v|UQ;+1<PI!I<
zSvvvxZ}UL?CiR`yBV)>G!Lz@H_9_MM|B>jm;H6El@{*DEhz5f56-_xUTr^*b+gM(_
zutP{*GHb%hSbo`2;3N#w!nw$D%*Mhc`epuT$&2>OaTcG#ZTutpp2`6PeE+rwcWXfV
z%FAfc#4UyRLTkv+UT(;NH3ZOws07~*gS?D?wygi!gxm%a@Zj%n5+jGab%ivMN22P1
zl7wwMlcoT5<Mm@;ox?4bJUd(ttXMc+T;i2JKM{B*Vrj{w1k3x&LQaBp11%Qv5iEyU
zJd#{p9A~j`=DEx%Ev4U*dJaq!!}JJlYx?%G$GPgFaUfz}R-2e;f@vY7$Lh;!1cHvX
zctrOT_3&f!mQ+tXrCs}&LP(RPY{x0es@V}ic$9T1rzJzDEE7%(;Z>I6CH}T4nAwh(
zSV%{^953-m?$~#@#3RY~N-cob=R+|YCrmFK=r2V{ES&kTKCCxUkhIcwNPv2MSWkBH
za@@p1wu9xciG^GTtK+bLj%3`jY7hGLZXXZu=U|9Ok`)%4rBqlnODxnQxiyx*ufV)m
zCZQflHbHLtQrX{i2T&;_RbE|g`%=r@O-nNv*sBz?$ukMHR5_q}y6g*tl)EQKaiW_T
zrlkUIU0#JkxTYh?HKMj#P^CaJlS_{z>!IlCN0KA*^-G0hL`y8`_E@Hu76?Pj^wI*M
zXm!v13Y4|&6&h;NYTL?jz&5*4NM*1fm=<ywED=n9gY5K)0xp*1VlB9$1+vz1D8&My
zYblbVe1XqTLNP04Jk5;hf1QOe)Q&_wi<7iXxy1@xw<F?nB}6sPQwVcMqQS;yuQ5-b
zE6RSeJCg`*%dWC=qr9!=xk@0o)ihTtbo$jiS;=a@+OTrquo-u2!eJX$o$K<iue#p6
z`5rp-F73Ugk$+Qpk<iM`FR%!Xf7;i8zUFD#z&_JQk0k4Apl)DaYbZ(z%_&O}(AVtG
zg$25rCuw7cXpZTTTzBhg2J}{MNs8GdHfAZ&5>Hu*0ng@q2!+6l%QV%Ju^Cr0Qd5N^
zkzT-(gPA8q*#eH*O8a49^VDr%Ve`~&fMH|iW)#ck3YZTKIBc)qnN{=5ZEO+ic4fiG
z>Wm15F>*xG%`UMTxi5M7l%<+|VrB9^h2Ws8ZY%#`YF$<grq<;)gQ?Zvttq(b@=Mqd
z)<x-5!$1uq{76(W(61_*Q6Zx0G8eVr!T(7potaXN(=0fvPS<O(jMiz*d4^c06@!Il
zrj{hm9|@)G)1kw{au>!UkQ$(|+V{-zy39%~9ZX|!J=3rQY9^GHo<E=-9R#a7T`OE{
zSoh$f+$g>25Pv9VHQM(+s=<`)iDo8+7M#zk3O1i3%8Cj%d!?G5ke%%tq|nma{hP_y
zA<rzIA`~u@9ElVIdDS~%41#5vXz83cnkHJXD;6}-g5|MlvGP1|ti`H1ajd@YQAh!>
z%o8oxN~;=PxxllkrfAw=3!CSDK5))F(L&7YRRGS;k(XJbM{);~SfWR8*3ja~*V)e%
zPr%N8&Q#JPxih0IYbMC?Dhg;^uz{C|qlM7o%f!)=;m21As{$R1vyT1VN}FtQ=RL8X
zWco31t#~Tt*5C-ZH(c009Fh8hO`RB}g&oKdsDkimE~B&zh=Z%>u)B~IU=`0r&bO91
zrsZDCTg7LHT-;klccaSy{fbRy_GPQ&Q4`2#ifPHqfy)fjGRRN7inqFK_g3+Q9spNq
zehlC$p0b0x@<+td!A5tL_UA>L$5dfX<t`(&<UV<o>LrW4^b#Spu-{&0q#jAuw^}h9
zL3XR>Gmd_X(hB;ON-3M?IX&0~ij7)ESL^KF$_uN@WYjW1x?*?M0O*RXYWx(>DmJT0
z1+c_VEo0t-x(paAwwJluyFNZ@;R5h7AGL5vc<FGs<SpVqhmN>&7If62yU5Ey1q)d^
zmSPGPGI^}m(|%llbUeXAevp;i(+AQ0=&z^vNCbQ}!?}IEUeEA!ge~(*pMtmSh%^S-
z`uT{r;B{LLHdye?tv96V-Zorjo*u!SRj*ft0R}qO;E`kt4A4{CLq{4sqT4916I`KR
zqN5(c{nF;69!b&$awk368amEkndO$G6(-K>HR49`Um~8KVxFA5UJ)ix`sNQ3NX;=V
zgdA9}r$0dn))#uP;8<RcJXi>Cux{YNGJiPgpo0Z3^)gAdOl}!2GgS+|?d6Drg#+s4
zfP-b`-tqNfF}Y>9ZoI)l*#BkXYRS0&OTh-qyoLOWN_mdYp-L71I`!E(%_+rtJ)=3s
zSg&U^Cmkz;1U`sz&}l~BNE^!`0t>M?mI<nbWLV1-)u+t3MJD}BR18J_JA!+jZw6|~
zbD%K)v`lyx;n;tLz$Ib!Xvs9NSCa4DI&N13b2*3|Ujq{XW6Nut=W5}|eudaAk&*rW
zDFpZrNA@d9jT@!|6oSHpIj7~OXbTfg3t8O4as7_u5(f6fi;>yju0Wbfw#b{}D746%
zVoob#`~0|Y#2MSZ=YO*_2*LA*<HM2ZmAv}Rc&?!671V!F%C0v&N2N8!XAXK}`}C>g
zS#WIK04W*0=twAK#XTXT-;&-4lQg!mJ33#>6DbDYOEZb2hOrI1M0a{(8+SQQk6qmZ
zFg%>`w-8GzcD`i({wg|vECiwo<@zlocnqidEu?`AXZkJViVW_X9TPY6Nrs~b7IIF8
z^Zb?w8l*`Id*KMAD)RGrmPYXTY;F^*E1dJU5Kcdw^0x%(<YH;=5=}pr=PnsKV*$o-
z@h_YJ_y}$TmM=#aNFT9$vIH+Aoc*^XcjQV?eH6r!0sa)2C$X6S<ctp|{w*Yy4=4UD
zB%hDvMPg;l<8Z9O0`(=9AiThJiN%@#)g?^1DG&)m7d}%|cu1-WO)_BLpmO2F!3E}2
zEKZ}IE6P@J90kiI99OU;%_W>SxWIFX<pZh(X(F68xR4b$oHqDKvQ->Vt#<!b3mc=u
zHauLJaJt|Ee>9vfxWF-u)vdSDo^CU1H9iymG$Q(k6AB+mR?V)lHEv17Gw7(Xe1NqE
zwbKC>#F%i_;F83cSYA6|#>DdNkped+oH4l2@!_PwN0Q%F=UVq$h4TeJ1p@L<#6M?i
ziWNt)=J=pNR~PF{SM2jq>k3gWgSdo+K$zj!ge7BThFPzLK_BY_d}hWK@qHE_!|MXn
znFxEvk~<SjxF;pIHfDnrR)~NOR&oi6@VdY<6Q+cf&9>l*azv4%Jj@C!tYBeUSh?)_
zFe|LUzdw>3sBmz?#IOPhClu7MK*9+JH7v=*i7%#MfoXF@dggw{u+0uugo79sZX!f@
z%I`#0Gs+6r8IFYS&y|NG;rnwfBFri)n+yFRURlX7xM5~lfp-((Wgv++SHi#pTqAsC
zw1B>0hFSTcb2uVmfu9p1oE7*vVZvG2IAA06gB%LB7LuP6CY%)rI^lSTg*g020yDp4
zXyPM5@t}b=?lE%W22Cvc2hk>|l}*y7Fh#9E$qC0tEO2td@evE8oVYZ#lJ|uozHL4x
zUYMv>FajgIWMC+UBP15A$@n59mTPc^<0BSK(uhhazlzt4tJG`8UTU4~jScXI&$l7p
zgaRLyOScJg(+Yf>2;VL%FmB?~(+YH(aD>AO+a^R%t4X*C6V&R<)x|JHtwOm8bJS|?
zIKoj5D-q5^Otd4oT{f43_#Dx=0=*XabO^%=GbU!ZHWk$lnp9t)aB3n~_GO{m!1cFn
z3nvDy?CZk83+u~1F&w_IvOf%G20oI>WALGgsUM0~Sl@)cC(J54qT8Ql#<SrKX92G4
znZuC=D`ES8l855$-EPGoovC0I+Dn)Vb|m=)a(X=}O4XeoWLGv<1e|kV!ip;*OcASZ
zJh!NC298}qScUQu4nkOy@)Bl<)#T)-MB{+Hp(6-ZE)<7IUKKx2nB-N7NFQ*#o)k5n
zQXhb8CVEwFMaR^?-`c&N4x62;GVs>I2GXpribE_+`>I^m4%5Es<<7+PJgkss!mO_f
zS0=>qs!(OZd3I}3WkRH{=SuDubY#K`S0+sSI+FX%O!KPTeGjp`o=TkhaQMM`Gogf8
zUA2H~WBI+{nn_(pa*xTwyslc<Hj39(lV1}KT3F%N#7G>jFl=Ik*ya^?Z#Y?Rg<%uU
z)mzIC)l3YlFl<603v0oN6lR817&ZYjtirJgC+)2S#1BU-tOUf5q>p9gKsNKoYDr)-
zeXQa-57Wmg&h>yj_EbFbF@{ymEYVABNJqC8&~9|AAtO;Z3vh*)6Y$AuQgdQ-HxaxW
zpl~g~-SEYS3N<I3|F=TT38(+9mzonMrBzNlf|!Q2a8vLTtot|1RbjI#e%cXa>zaFj
zz3P`3xRO*VOk_Kf+rH|0fSRVURql8Mw6*6-vNhGZE|8j%Rym;xQ_?EOSm8{<wX*Y6
z*ux{p3M;<Kkz{>+`>G~RnzL33(I3NMnQCP-Y93qVa4sAlv2uPFqOsL`z;}wd&OMbg
zz_>KF${Asp##RY86K1hhE>MM8Y_%qhFU(}Cuz8|;{UIM)biLyaYxCA>ZMWpcfxUfM
zNwOirS%d36d<~P>Dsg;58H1lI%JyWf*m0WWb|hy?IyrD9n_ZabRx6IJaBASnQFEB+
zR$=nQCA!u7%ITH?+sSf!QgR2eS#Fi%>@dsiNbZ<0%dI9GC`5C6uH+7i8&|OsmOo5$
ztDNA68Edu1EwMIM4mZPewF(<3L|3ax^a<0|Dny?!U9Cd&iQc{VLG%gp)ha}v5M8Za
zo==#qR^j;^iT?c_m4?Y`wdNb87SI+Ctr9ydoYc2A0Jl5+PQC1raJt?Kza-2%t8h?)
zT)j03Dq-eXO*YP{ndd8XoG|sQLdOYH&nkiW1Lj#JEPr&T?5s(%xgr_~6(`I+tCy@3
zZCf>)Mo49~Y0LOsw#&eDN5D6Pj&mdo4A?l~K!%lsuTM1F2PB0J#W$?2-vVC{%FdBU
zF?+_gwEwB(o{eUE0k%~*1Y#wue>52f4J^&ex_PBA!L)gv5<M^+@~}d%36s<+1e+jK
zVQqQ!BFsLk4cs&Ttirbm@y{v|6r&ln3CaHi5e<)E@QmsL?wNj8Nn#w$)3F`B=6qMW
zG2ow7Iy%fhtN9&{K<@<A9MJHoP-wzrvI>PJ6t1u`w!+M@BguX;fGV1Pm_1er+ZnLO
zYR2@8CWl#tnHjB05s1|sl%WzoG)x|=q{I%B$LgJk(L6z!s-Z}T&lTl}5y*Bxsu^UH
zq7%(?7K%=ob5^_jr%hMCDvX>k$E<eUWfi2dK7}b|^)6viosy?^kje25kK}#?6UvU{
zHo=s#+JUR2lsze_`DQf=xT>4d9d-_xSP70BW|SRC8eG-L+Q%(PD{xhp+6P)yUHz(%
zqJNUC6;M^fY7?reah6E?VWL_k(te1j_FPfTr&y+lG8`tVRRR&mC8||0Hq1+_Km2{d
z(Gn{F9S)aR0r4;?t%CGXr<JhE#O0~gB=bb|J{&SnC{$vF$`f^1G5A-V)92oJzLoWj
z=YA2;!4oT-{c!Naiun}8O}U)}>NynRk=*+AKTl=-48DWSsqT2!p~Fp6+A92>fYMek
zyC)p@u)^*M#}ufrdm>qH52F0e4ibQs8)CiHw1dN>w<E}}%sMiNM;vCp)eP|;=Dk%y
z{D*mOb%3T0k65w(pD<^wLhlKOHmtd^i0U<fy+>5zHiVudNjD38o-nDc!siK*+Un@H
zASD1}@d}X}t>=oQ_$>2b&Rb=(7I5Aw`?)aZt+MBf%X!P1fs<yv)x2dCCcRbIJYkC4
zk>n-!B~Dp|t`j9(J2s4FtJT~>NAZkimmTGs(QLy*p%81v+Yd)VJc8TZ=Dbw`@P|2X
zM{>6XM<nHdXR(iM<V(~w>>EXaJAyltinDB2d>U~%aFv^EVG3MLFG!dHS8<(08G7l~
zSG0i*Hz!PBtMk1js!449aCpRuGboDbEESJY6nVTWUZp6V(yf^tayX{K{I@z`WrhiG
z6>?6P|8^vI%A5aIFI^|heybCxJ(&ixn60zlZUVfbzg6;ogz0ZJDLo<f+jAv3;`HxX
zc`;uq0s2Giwj&s~_$OAx-MD<gB1oGOrm`JLR?S{J_&6aZTTMDnWT3?dNsdR1bbP7d
zNQ;$ww_(0p<!Wx=0=z98H|&Y@0;vv!GJ#Z+-Hzmba>#BqBm6&CAjKf211r|_Cx^o-
z9>J}>11naX&`%Iqu|njD*Y@{}Eb+B~Ovg~HT-lD-+|??w&l}c*NB6~B2iNDdG0wH{
z5Yeqpl5>WsZgqm1rn*&J{Ncchm9YQez>9U_H3$MPR)YSAnQoO+ig3il3L(fuwJJi;
z7dEkq6D0OpO}5W#$C}tauP1u|iRQ08RRkat*s2&nuY7An>5o@tdnFh_ymqZAN`IKg
zRx@8#n8sFv?V~~|9zk}Wy=8HCk8e(Ah&qagSUEBa=d`Vys|64LQ0>)ebqzu<hoc`>
zBIbt~YV}6U5A)MbIlD~%n%(u<R3?5!yf(o(a17JaYMx1k*=bcQo*Nsn#!#3cd$D5P
z5@Coga_Q|k*5>xC;#hZXd%-hI$TTOdauz%t)9^@6x6EyC6j|`*w%Ht^dU>ZC>xP?=
z=KSdtZLKCV=L)2GIYx~POQ<>1(GqKtbG|q>6>`pBN$&F}r<hNQ%B`@y<(%SAg-@*a
zlz%#WVuc4V9X_$fRvYatU+*oUcqzz^jA!C(O@~FS8Hwu%(yF=KhpC8%6>`LMg4zms
zW)ktRCPQO7;$dAxYMTzRQwdNu9r3Vc472Hghm|mAlYobHHTtaCVY3>2W}|pD`pi@A
z@K=6iZ?56NOu`w~g-3llp5YPId?qL6ItAQOgoc^UO<Uo>Oy{Ppm)kS9tz6hYb9?g(
zLuhUrzR-xK;~G8{uF-UU+9SCY^KLjJ>Rky{olFE<zl(TM)3FUJ)R-@5Q(bXOOiEZU
zQy~j0w3oTI&9~&e%w@|KYS(lY+X@qAI%HwZ@cEMv`3I?qpFfv3!2IJ}+5q$TTn0&0
z%#{!9f1bI#`CaK$I}&NlZQOJa#0rsSItXHgNONC=+MNyb<`*i>yfF|fjK1kOh!qyi
zREMW1qhr}lzBHQYoVJxAF>lnv3L$Yi>S0aN;&Vkb2WI13p0P=XoXcBVD3f#9Fy6U8
z`?YUS%(`|fs#I0;{LYW*D2WvY&0O6}9~7GDz=@S<HXS&zG7;wuoLG}SGo7inZW29B
zrK+vaXQl%uR_HU+ffFl1^QQwRRu-FQI(lLyZ2lLl>`1bWUJUM%HO)<{ENb)Prq#^N
zeMS0)okrT#290Kln^u!VGeu5&t|SL~<=?ZBK1<(&M*8Gx4@S8mf6wO@rFAk|<aL8-
zGnermWcW!a<uv~A9;WnM#(M(uPv^-!lG_*`n{V)!bS+PcvO(7bIREH8x)lgM5`8~_
zHS7{kD1WX<bq82OkDM_cUR|&lrW5T}h&MAn?g}aFXV_AJ>psJl0^$8<*is;l^G`x4
zF*Rf<G;E<G$wyi;YmOi>uO;9ACz*bzFhm19Z<kp!L%y&Evu1|i`bh5QiRt&|j&H`$
znMxyg&5WV<CIE*Ph$HAcl-+P7lV`a5-ttz&jA7-VYjnLAaE<O4UvP~C{&p?u(@{+i
zq|to@lYZ)ScH@z8|5oD$8td1%flm3t+l{h5qxzMgYgE0GJ`<j|mn7OVs@n#(IxlX^
zYdACHz-rKJj$}~2^D&&fqrGv9HUB*kG2Z{Em;*rbsIkkN@#=|1e>rL<0rThFt_5&7
z9boYV59f9dD6r?$oNI6XK$^kCxuqFMoZFhWF`sQ_dqKecA3c+cu3uY(fqHF8bkl~o
z6(Y4w6UrO0@@)hBB;^nMw;~8!dS_u#b3DOTis74H;@aIbo4l1G_|Da#6+vD=Fla@P
zryX!B6?E2Xg?R$`1}$cq2i^*C))K;72Fw2typ?7wR!utHHrxe*D(`-eC@VMA4+&L5
z^i$5d>0brK(#uiSbm-$&1XJCL!Kv=<7fcD#8xFW95xf<lQnR9&V2uuelHj`)p;8kC
ztlfC~A9^?9?SJ6iig2k>65>iJfu5#9AGZ>MT<H}`i4WR}K&o0XyTs+dW{uP`3Dm75
zzOsbFhncHL=`!L<tAK13s|Cm$E4d{f=ELa*A7(mKa)S@^Oa(@6c%G*tBR2x|f5?0!
zS$TQKT77Sc6M|M>V=-;2udz7wRDqk|x>dl<aZ*|px^3$zfUi!l8-D*8%c_d8H@Eh!
zCIWhOs6xPWm$fSV6XC5@;oq`mzTFW?b)`*4>?#EG0#Su-hV075a+*ipY6GFahlJ3o
zaWg_^jR}#P82%ut`4*OpDp(xWBUl{PM6eo;NuLyDWFQY;h2nR9$)-^Jy;90pO)@i&
z<lJxVvNDe#Lj%dmJdzB5<N-{SiPc{}r69#l9@%PS7$0gD4iBW7g~9_-%E%_$Nbevw
z9*Eo(c8bWR5d7^MnuN}PT=ArcFh0^u{EYSuO(I8$Nzpj6U1n4KhGzb|^lajxEVpnI
z55)tqkrTtDh}M)7!>ou#&>9aq1>0}76BTP;!G2mRiuChjk*YA_8o@K1@bO3#K}c0A
z4j_b&{D|Ujq@M;s#*uy+44Gx7MS~!-AX>Df$2@=H{Ip9)_`>`&I1H<G>rr?bIdWT4
zA#S9fhjQ<KL;bW2(eGG4SCEyJN2&2|3ib1(D64Dpvnfmz=I14Me35<{WSB3~Ps>_n
zI3T7k{FpD)PlF)yMfz#UkNJZAH25)(qWv5}2H^SPWDkcBs`^Qe1jooeA#9SXksZb5
zf0H#@Q^=`e#rJZt(^fWx_E*}<=Zf+h$&_swHPO_J2E}HXnbF|bEN7)`jdQ{;AW(y3
z<A6Y|tv}I#T3duCv9-(eS|53%F$b5)8;wc&MFVOIeq+nj!Ed&Vy+%YTlQ&w%`C4^T
z$j~n~M1Sj)B9><{QRd40lUv&qz53ay?G>^7utXja#lu7V6}>3K)VU(s2v_HdRD;CR
zD`I`=Y(=h2H8_xZ1=62G;fN@%tn_RBHH)}B8gP=bm!F(k9|@(bun*Z9yqqhF?DEUQ
zxdK(KQIpqeGen##Vrs+0`H7aX0WQv!<>HiFoGVZj6IHKB{gbeIMV#)oq*h)LQ@js4
z_6@x}m$NI;+ebFWj{hT}HD26d%=|>t&rMZ<<+?`}v<^d(`N_Nz!;-loDijPWAE6!5
z)N|MEd?ZVcsY0Q?^n%=%x^lS37k$~k4qs}CS84b$S2Pf;>?N<$oqxZ&PUE&3=am~$
z%}?Z|yDLG!>xCG~%oSCVOuYI`UWs8^|3qGjp<`bW6;IN3intBipmtx`ZH%5_YLB9d
zYcU>0_4bX^BjdB!YmoGr6iI(!#Cc7IKXXMx84;?Qr&V}Vjl$vv*Bphf)m4px*ZX#u
zH&@1T0$=}%)WW9rXmK87e%lVKctkO-gr#DT`pv1%+931W_G&!HS4t+$Cq<_zd&^UB
z={BdRh9&TBzw@+U?`6I0W{*gU6Lj~sCn4E3e{)KV!2sFc2O8PsSEetd>?FJVd3z3!
z?FE?N#8;$F#LB-iS~mG=`}=D1ezpC5waHi8UW1c~^Q27A1!H;NRd<{x*4NF8A^JIF
zpxIoJX3b)VF0Z+8ZH|cI9iHp!?8U0V(aZgUn-TOmZpO~;{+u^s)7{Hv^4N6kN?T)W
z`qd{kZN6Eg=i%sF5t^oemXoRTqAAe)oHJ9Pxnw%e1Vd+;Is&RQ<-2ZNXgjj|ll!L^
z<0&v)T8s&cekH8(lk`eg2KW$P{feX=6#cw7Q%JhJ8qcONrL&kL$}#2Rm^Kq!SGPKW
z>*u;jQVwro`JY0`&p|W0D%$)qKyrCOo?ye3>0LwpZ4d4gmO4q*5m9-$YUbU9UV*A0
zEL|+ebFhXjdvUp&c}1!Kbh0Z`4JM<~UYjXYw%cY3lzr2`Db>=I=|>EU;wnTIrC!ke
zxou{svA+I)WCO{oAJN*^>V@44_wfXii4gFlDBIx}0S!9N73t-IX-5fYQ$QV?9oFOr
zYL{U8^XE*#w8I26ZWjMUPE^;R_FS1NuygEuUY#j?ms=-<?y>CfOt1JARsE>xDQXZe
zr`t{u6y@Vbv?zFjw%s#ud*;UaO481BXrCiUmVqZcM*=f5O+1K_XJG4#!-dO|pq!iu
zdX(dd>D-YmNJl=mXL_{DlHglLgPMVP6%C4nt*bm&ncGR%k0fi~-9@;Cof@*i@|nA-
zV~6MsgnVqo9hgq~*oaFYmPCW%Gq)|IJb?OG5-qrVIsc?|n)I8|HzxgN?7fb&xjhka
zt<C+JMkWafW6cpV#EK(ih&4y({aPuKkj)}9e!jG2qWrv+d?+&X@0@7tKQBpFwUL=P
z8h=hom_*-6N$m7iJF@(dq<eQ$5(`3_<?OWq6ms?&k=OhDJxk$yc7A9q`p?q8`_v?r
z!2Ma_y&$RjKJr9kv75_oE*8j-E73T!POd~-L_(fU5!qI<B3S-OMfmX|8ZP?zAvbRP
zxu&~JB%;J^2t?n>iwHypZZU{H++JYq{9s!Qq7Su`LG)oZ@o_kLA=J)2d0{CN#mM-*
zx({BYxYIu4H~%K;#FL`P(-{_w)bWQu(J&iKpJ>TF`i@rC(10~;Lq7V_sx@dtQM{Rk
zv2t1Il#^uZ>>+K5U2eDg;%Zj0+nv}=QM9wZ!JVQwd&m(a#X0_?A7tgcspga~%9j^z
zK_s>pb>&Iw$763ylS@&jEXumxoByhJZd2BE%t$bu!V(XE>Xdl{%Z3^0EooR$bU(ap
zMdc`7=3#S1@y43<D2f<$jcvgtuHP~Qb;cJop(tH?i%INK41=|JlTC=UOIyc3n!KUQ
zQAckvk)6p7Q7DSQL$P*B^Dg*eL=<nq6>Fz>2TtI)D2gx9cDp5MA+&OQzBN)n9tn!S
z1clPmvikO;K?{oFbYl%(P<(DQXhBiDi34Dx2wrxF@9q}rGKk)gL)4qMt*anL76sNR
zc8~7C5cLjRk#&kT;BYXb_|OCzXE^3+yM|1pPwhc4VYhz|C9OAW66UR|ZXw<}lYO)I
zjL&lhpC?{J$L0#<yR0X~Wxu6lm&<Jn=_l+{gYy%gOYMe~jMp$i3df)1mf#v*@;Pna
zW|n6a`upBet^)n#c85J_op_mX9cd2|nCIE94pArUA?pxzNHU4!-a+oSQ1e#w{bn7q
zcJ$^t5$CZtO7{Y{#`+QDJ>;tS++QwS_+YO?y$K)e^;h@rD<!T`50&%2f)DnN$oHs+
zUYfB4<Uj5NY>i&5SV5(_ig~B|wWbUz<)gs<cHgU>^wzkQI~LT_aacy%{wBbW&iQ&W
zZ@&A{T>)@>gx50&&hzJjbXOD{-;eIEE)OrgSa*k)t41!<?~-)KdmBF4>-Q4HcSE{!
z7sL0VJ4BvP^5PWz>ppac$@ATZ?h1wD`_NsHa5%|(y29T0;O<BkKT*4ZAs^iJq6@^>
zIlU0`!UuPqMMpQJJIm5{L%OqceK({#%NsYOZ!1f=mz$**81g}0=VU^6raQEp@6L2D
zg)86PYKkvS(?Z3;@!4Ki92_6y_2Rq24OO}+-2CE}rR-}iReiUtJJ+tbW&I$^`d8~|
z|GH(}liu^)vhL7(e9O8Q!Z3tS?K<?H@0N9k-SgeD?icF6Th_hkTE4eIT~TgyOxG3T
z#<#4GB-`{_6E~YU%X?CkZSov0d12URc}I|~dfm?X?|auz$94*z=XGqWKe>3X^>xZ>
zC1ACe+c}9dL4e_o2^V`=H3+ts+MNKlmlbo3F*7SZh!lfZx&bgpA?{FpVu#zEFOlN)
z#UMuWatLCnz96=zTdWAm@=Eri0Liv2k0>j5HZHxse*y=07&>3z;0{A4HfCn8iU#1w
z!Cf(Iwtf)fPvGFL_%#k3+^gasJ8<w3)qF~d6$n`##UuGb37^uxLkag<pFgpLdsPtR
z=GG|)vRsXwq#ZYM@Ro#bmw&KltQp4*?us?zxWPyA#SQMYXWZbVD|IrBIBsw!8Oawn
zxO2z*iyPcYU*fpIzad`}{2Vv<2#6beONxrDE04V@Eb=SGgFCAZBYZ^TPZZ$}|K>=f
zW&CeZgga?oh!FfBQix!^D6a@RNbnK-2@-rI@vj)cPm2B>B=|`F6(slw2og*S*uxPc
zxL2+!enEme%$+YtaEH0`1qtp+-1%YzcMjv9SVCT+CdBd_hRUO;!5t>g7d5!o{WoH8
zhqrU%0iz~k9*gAFt3n=6D^bwn1nS-t&e*8j6wX+buFhim1q1F)0gesJ4I;jx0ryt^
zL<8<HeQxaE>@>JOUo_wj*N14p52DMD$Q0<!*-w|>dbttP%fE;|4xZOrhLrkprXI;9
zr_7hqrAv(Mx3(`2YKN{fHihdL`4XD;_GKsKfy_H<6HGjuq0L6e$RJnggXr>b9M-Nk
zqWCMU-4R?qiR0RJa+DnjY}DSAz%;C$1g7DBCyKuU*LCr1hK#wVC(&k1_n0!6PJhoY
z_o!+Ei)QHii$gQUpNAF?sWPOl8N;LR%TKDFSTM6jSB-CCH^-nm<*XjIS|k09gU}sG
z_OJcTT`ZbmW34&Osm49oZipz?#jF`}NI$*5w@7okvYgshV=J*7FRu45hv}evNBbH&
z9_sx|VVWq}$zW<TtbZ9yscZi-n92lX19g*{qMKCTqo6zg1|!*_Eyb7XonW)e0p^Y<
z$DFM)ay71@Gojv{6;*0;pZI)<Qai!7oE5bb`{qlFdL&8J+*U>Uo4&s`eu+?70eb(F
z7Pa>;5vp4GWkN->65e#%dfll{SrQ0q_9a8@{Y!=_RXM7kFF$JUbzKEmR88BKl$K6`
zr9rwDkdp3BC6`*d8ziI=q(iz9M3C+l>F)0CZul2{eZTjMf6ujtoqL{{IrBWv9Im}@
zm_z=pXRdxMdE9E>Nl6{@UE=G^<q)FFX|Bq?fBm&`;YFCU!)bojg-m)<Z0SO(fZ9hz
zngDaf8r9$xemw;aeoWkGv;#|C=7=q2vb_er=wo`K2>pw_tPXgCK_+Tn=V1PN*V;_)
zD&iD=UfbEu>1%Y}{`=V<cbXDepoGUX_fh$&3s;iv8e_Hh`HLXD5<Z>*<&zzWw;Cn<
zVUywB<(obWxw|HELDS_QFGFPgbQ;cDcBe1woHhCDIU>$)gR8@b+#z4}t!*AY;0kZ^
zVA5^uJXZCV(`18Z*Qd$OEbI9oTSPMHwo4A*?X7TrJW9}#9}t)+S>j(d9h<Pg$VsJ;
za+xqyokWh-<U28O=H_z-JKMP;Sb6;PmE`N#je?wzqamo-1?BNn=Cs75=@2yMYtkRc
zV^{pg?skNTQ@8UI$-(a_uWWf6lJ^;uQ@cuT&)+%F0cYuQUZW(36KzznqBeZ1P?oUm
z%;isdzgA`4{3=!HIxudDW?r6cJafyE=JSr3hvjDCP9lwlFcDU9`g{J=RMVze#N3<y
zm8Mkro!D~D(RaAvpI0a@N(*|93~QSXCog^uy3eNXV&(Na1HYt+CXcoW9gnroc3msK
zAiz1zCA=SflYf(Bn;xKh4z!Qoo3?J`@x1KEbCRCMBz8Ctk??MoOTvnac#~BA!yds3
zJh<bsc3`K6IpDV@pSI0|1m2W{Uq5Bd2Q!rLMr)I#$=9S%7=WbV2NjfycuT_fw`=8&
z4){x7u{B&ez>SRCgct`uTlT>Hy3NsL0_UGX5!C@t238nsX>Ym)zZm4M;qtJ&6c*lz
zLg|reB3h6haBMv!^V8oD+9#QHhpgtKid4iegCx!f{U7Z-rbs!2##?pmKNPfIw93-X
z8@Af*Mp{GmhGNe7^xXvA(RGm<YG@hZoOq*;WC2k)g$FZlY)-Y4Jxc#ZA}h|sdWU_S
z2M^fkcn;J#m?xj)y~Izm&`LeH?&BZk-(!#-=_9$o5lWgCX(Fd(_dp>|CRM6Z5$poG
z$4k^w(ZP`i%?k^;AM^8Nb_abA0y|<8I)WX?it_K@C>4ND*@UQr_>&gj6?_>~XQTQN
z1=$3cQNpQ`N0g6zoVeztGo?`3v`7LpFGn)}p0;#SzXPQ*vOyNY_m=`*h%NSA&7zcP
zjI(57t4KN3qul9@b0IByeN4R3A1oau{6nMIH}6UEqc4c;EIeP_h6C324lFc?#Rm>%
z8uWw*=n8v%MyxwAFPE#@Wdw;s2M(MWTZbVjufVtO3?uq(U={@WL}|s?8NibzBUFXj
zncF0%oj6e0Z1q!R(|T#4zZZaqP`%oA)+;vq33-%k-x6PexM#pwGm%89aNdB=34wcd
zEw^bw%OJA7d3pnxRB9D*qPX{RmYU6p)^}Dm56#AwSG_OFNbPv(E<OeB=WBJ@!7u2u
zr3SBkDXI)Q93@}R?&UYZmVd$-4N)wW^WCABk!3aI(dx@XqXT=F8o0ALT#Ue6o_?Ml
zLmVpYx7_(GZ=O6gh6fU^>Xu7wP}Rcg;B|?N@HrkNUT-Wr^HWKbA7tF<WIe8F@1D+k
z?KH(RYiID9A@!TK5?$T5Qzne~fu^;5G!bxe-kja0Re9!38+`*YZJu7l5|FHLReY`&
zyl9c8{2<oR$wl%^PbJmeKC9YHj`;Z&u(Y6kYuZAwr*ZdW0WE(Ax3oa7WEc3YU^QVr
zkJIUj&x5DQAZVzZm@-dfYue=X`CZ|xX#POZB6=!h+W{zjWESGFS&ofQFFcab#_b$!
z$}`jCv2*r4R#JzX`}q%ez*TR5rkYjuvmNl9LjH<n0OW41hjw`64#Zw<>b=*Jo=Tx^
zy%LJmn-C}6#PT2@)O=sX6zWnFmz=vMHM~)9hgd&){?3iOg836^>%Q(H_F;V}`F&{r
z80cb+pKM{QtZQl`XEW43t8LBgBoCc`w1&c=ACCL=W#Nlc(5-VqnabJztWF)p7|&u4
zudq&YR^X(`lwZA&s<Y>%rz$7|cnF{Q{tE^PWu()|$k10kxRQhuvI)NaF`VehDwxvg
z6L)mZA)M$-A|AJZHAY|pw>@8(R@h-+#KNA15eb1194lcO{mQH8e)yGDVhk~z&EYrb
zi9JSBT!?ed#nS`V2hL^F0|ZBn*rMTZH70JsC*{>vfekDb#3bJx3QXzw^fwoVon2c7
z=5xL!3e!pFOdz(q>J`BgONMK3(|a$t29yuDvFj?T4b&easjW8=mFVMK&M&oFmySR*
z@|!i^5!chhl#hPL<-}DsEI+H<c30Pbb_4C+qmP1ZQn|yQ{`q#|`Q;k0;=EO@uCa5n
z?T0Sb<Z~?R<Z6M$xY@b$)(J0myL9YayL=vj5sRbG&M-Se;91lI%AP7BsUG(Sd>6mo
za4p9RyKV7w5Z95nXWl$O?_$BkJ<MexYpg7}<AQhH@{=jaDx8AxZMaL1@;CJq1dFm;
zAMdm2Aee_?Fa?@&qF{O}m+rD*O@GER*N%VS=nF=anCnUm?vx28?y)bkK)D>#Sq><Y
z=NPut6boTQlrFb94h<h<;Bf|;_Wk;x$js;y`)SQEj<~+(qi#fX^$iWOvIpk@Ls=Af
zgOp(1Np!>#H;2{y-Q_$UlnVDywu`IShjgq=hP*V3W<hJ>WGaxoWj*S1wTGYo$olro
z4n}v_`DP@lFU#*NWfkp<*sRbBeAD4Rz>b2hWtMeCe8hjWXbSJ{`Ep71$`8~m!$Y;A
zhF+H1Tn^YA?7>#&uo|fTtt6~3#6X#`C_h|tzt<;I%hNKF>=^|6M4Z-dSZ7MVCGDGA
zT9{NPT~d&Ut|DnxA`(|XwxNvW&b_0jKgh7lw$1biIx?hu`<_>L?s0Nv{7l@seW>0$
zAflU0Yu7K@iE)T=h$Pf1KR+vh5eOH$HiZ50;a+-TH6}VNE+ii@QU~jlQh994FGos<
z&%+>)Td2<?^hR|$2U!}OHkO=kxU2&)7k?VjxvOjbr+!eFIZYa@+bY&+AEI(E7%46E
z;<KSVx<xEUM+$zJN~kZtp+}f6KTTIYvsQ4&0seWF60H-J$*Vfy!Z}1xO#oX^%2;9+
zcC8B_&s16o^2{bxg`^ragq2VvsFyQ0{_C(HF}e{}#$bBs;c^OX*=$2WT#<tc(vKJ}
z?utw~u&Vb6z^<<Q&exo^Ahps@)La2$Wce?eBlYc8YnIGkS?S-I2(*WOu+0&ULWHgS
zZkFxDi!%r;O+|9iUVD@pL8PrHLlnpY0<AR0eg>|$1)6^lNzVK{9XtJook(4f$kb$1
z35laTbGU~;JENm;U1L)6Yo1<l6mVo9Pe+1q27Q4R*ftbsQ==wR!sH#yC+#?dCynFd
z@m**9XSdT(vAJz~5?F(9?)%2Hs2@?C^6F96&q(3Im&~q(KY{y{!&7;CG=#GidX*@n
zg3Q6KvODPsgn6I&Cf~r)3h}|xP&M0k2s<igRqI9u(?YhrE*7p(fiWb<la`Z<*#hH<
zwo<D*#t_maYYxhx%O-DunPZ{TM>fpxM2V<KyOO>tsJ%z?QjWKwkCn@$T?DF)0IB#B
zID+_Hzb;a9n$Wp%wjj4f#7JmXavO!p>rOe$do_MHwEU)v5ocHIgdixLwt+5mrDPz+
zRj@44?Z7Bf<YK_jCB)}?VvdH9@2oAMTS%6mXPF<U-T4Xn%3+TV_nM(T1pn<<Lm$*J
zEi|aG8WKHAY()A&_uMbOrvX{_2JL4oad&LqNhbm9j{^5R$%M@|D19}uo+?~h`OK&H
zswS7wZ#}PV0=+$wP8=Q@d#h&{D^0Bn@xetuJR5lU<rn7`8C_%!_8bN8ogL~p1s3?;
z-`n5bZU=4GkE%9FmlXrK2xXCE%;tmcur|}1(;o+FM%?djJ6Da+<qZ2wP&`slwPgUR
z+e}8T^s#J4R~z|*k8^1cg<-{}y<+sWoegHpcIN|E<tgtdSt;^qn;raz850H*hxNSg
zB*otoDC)tF<SGk0U85)PRc$b&qm94q0!wXHymd!oc?T^#N~E&1`mL*fGAO9_d*9ng
zN8Ch3an45x&$QTOzQJ)^;doAxYw~ypKa&R+_jy`Oc6@HP6Ui}H%s}0AmoQPD%Z{RI
zHmDwJZ(R$QH0fDm=X50_O!`+}1G#fm<u85DRmYbZ<Vg)R<$&X@6+e5?t8$JSxX>3q
zs0qSXw)o?A#(t;54%v)bDpqWRj&P(QL2imz_sg$^8M)+xH!wc*(cbNRBWmOFCccLV
zM(Lzr`vYeN+N<ojW#?E>i4uIYfD<Mg>X@YPxdF!H+&dBc5kU^kvxKui^i+6ccOXfd
zVxdB1#^CcfMfq+JSdFdIDN^xMIb!EcipcVjw4C2`Zj3b^e72q+qj@D!t9k>u$W)Ju
zNgzv3kP_<F=`9*DfnnC$NtD6O+|$JmZal@lIM>cewq)AmDK%(i0iGy=O>s+B&s5il
zg-^z-psL(s+9PbPTX`maHr={Tir4*^N=x58#c|NlYs^;M*J+5-$Jk~j47+9tWTEV}
zVKEsbZHtU4YBg%i;hM{GywjTA6CtEsZy)^xU#xjdaZ(6e<`~}5<etJO3X|dpWKq>L
zWtre1YK49|>`%9hs#!FFJMJSuI@S_j?Fp`|U3rFWPHRk~ZJU4)gj9q|EkiTUw6`9`
zrR}(aI<Xx^!m?XOanFR}J2LhRCO^U~gPX~@2}WZcW+os2oBcI<o7E5$QAg9GzJ~CW
zI!!m&vn!$d(N2aP_u=NJxdb7S*-Ck4>nhZ7s4SBu;mh93<t||pCFd%`N(xk}xmSJy
z>CcF_eR6VNTh~dBh>YSi^?Nk|M--KVxbWOfDTpI0a&~YWLUNXUa!4{!i0g^XXz6s_
zccOA$Mml%|9Fg-(QrMH57i?BV1=>r$H!cfu&Vh->-7Tr9*2tvj<QLl09<-zg2OoS*
zUF*oYXK6NX1fHASybzT^XGAi#Hga&ZHwIZfeX=nyN8$vq0G@sV002&Qb{4KbIQw5X
zAKz0IvzV)+go-1`(HQU>c)~y|kOF{NL<qnNU^WCn&H@5Y#=p<Z;x^Wf|FAY;WMO0h
z03qEf|78TR`|Bdu{vHg#tm<ZK3}99SfsFxF0M=iFD}wBeA$_s_Y0E5UY-9!!ws8e$
zK_C_YCl3#Rm5qf3p!3UI1Trwh-T}bzcLND~8z<X;T+Hu5exXlIATMSW$k6s6YX{q>
z!3^F0z)}E5dne;RB@u{~sIjw|p|P@r@DupgT$PO-Y@F;3jU50_ep5#J*VMQm<tP6>
zc}mvU8te$!k@xS*5;wDSG`0sYi(5iGD{5?LWAtmJzYJLcTx>kRr@sCQnQO|vriUl?
zc%vZLYqM{!Z_m)AoakhVk|>($1qmV|BCM)9`np;eW~9EM-;ZG01pUZ-Z2xHVH!#pj
z?G|x9_zd9~WKianfMBxm_$5Y-cZEI%L{aWama_6U$*7t$x22B@gZG{XeQE5Q@4W^O
z4^yaO(X*nAVS~MIip-2jzs=w93WvQwh{}^s=bBU?3F)Pv%pxUIjg9B$vlz&5V@EtT
zNZoV0Dh<dL>uEuc*X!WvW+zEfUpbm{!o2m4u&QPM-dd{jR!TC*_k4|@e1j>mvh4wB
z;yI}Cs&slZAH#kw=saAL`7@`L5P=rmVCzk_=4Ar^gW@#HdWq&9ju=9^5T)`fb4|Ju
z5px_&tcvo(;5*{V<6KM%0*Tp~=a|{w8o%+gx5;wAgqRr6QKYV;&$=m%(GJ)&yKBo+
z#KsOej3}GI6@w0Fv?#?9*$2{46#By?&#2=iOLg#aahzzOm4y+$uI87n0Tkd?zrehN
zZDIZ3Q|!+jkgsY!8LUvnT0hFoTP(zkKe<F(<1Niz>e9@a^L;-)d;hJ;!kcKj%>DQa
z1{d9pnh+Iizf?sOudMG}sCm1TsbSOsYZz?lMby%i`!Y8}O_4G*L-qSEyws!0H?TUe
z^aa_$*aaLIW&M^m(VvZ|H+&c<U)lfI9;K-xS@In?9h&*vsO4{ZjDbx+rBydrZtoS4
z6J56SY$bf?)tEn$w`kWcLIIJHURN`jS!2UQJq6<ko=^+c{_ZN5=aQ7-I!CsHwg_d}
z3SxQIyP}t3$GTQr9_wUW;<o``@n*smn2DArMVm|&8AH<JS^D*&yCgBf^L1ay?9J0q
z(WIGx*EdjhMiVy9u%q33r3b90dKyRw0!tRj1ke*mxCP3W=HJ?o*euk#Jmy*PrlntP
ztgh1_3Fcma0g<+j^Q28ku%A%+3JV^l^K?#od+=y3r#CMjtB$+*anm`!WS4g3M_3}~
ziFW=FjvZVJOH3)p`1x@|T%xNyEh<tJMJ_9;Bmv4kr6Z%d#o*+DNLx6ux9XyLLD);t
zaR04F)G|rHF*Ei9oYfIQS95Mvk(4FG%?t(~uNtO$Oam}*`wcW1F8irY*JuoS3^#A$
zV?wvqS$ho=Zk=Q1OQ{Q)eSXHp$iOd(KdPaG%9_TVId5Ls-#A`WkTz-`$EYCVR?5|i
z@@F4J;A-sd?rx5ri-7sLOuYJoqiCL+=-iw~xWspaH2a_5v7QLxSgBI9X1KumCt|NC
z&{5{hU>cD|!WI%)trBX(bx}~Yk_GHb@XnT;PU3F7;F;Nk#)}Dsr%B?YiL@fm{O}2f
zc_?Th+mLs6=k4`Y-Y{|gZpb=ToT<h*txf6~xl}6x&l)w^t^4H+?f7Qs^K>p?&z5L+
z=4b7i8Efr<oJOiqTQIm*PDHw!JWnXvU8}ajq<7-m)ok54Z(*p#;(MB6rMS(H>UNka
z^!-0w(EHIs?3Kt~!G#7g<$T;4#T~2;?Y5+&r)H|7=2kA1DwNVrDzNacNy+<I^D=K<
zs3>AIb318%%*o1ML<2SJRQf7cMbMI)*jX;lcS^f2mnhz!qvE;N6t<&`Y`l)<I?1X;
zhZag^UmqX)VIW1e4t~|{w)<!AVftRSD0;SK;9EF}oQYl#cl1l1PpmWZGq9biPK7{~
zuZ|23mbNvVA4Iq2ig}$hn0Mk(OpbJuBrc~6Q&@|!qh({L1W!*nv<eA_qR)*yLMi4y
zADkrnNul*evAv}x&0627y&(I<2Tr3OZAgVRQ$!MugmY6wdnGiB;1uheU>N2QMsJE6
z>9NH>LfHkr_AKL*`fORR(5R4{qfmzT8d>MsgpM)J#597N)D9>4qZM)rvbLI0Wu3B~
zS&6+W&sS~cFUe<e7w^E|zRH)BAKD$*aV8!nZ}wTAl5yA`<nUVyq>Na`naB`PTYB2J
z8?GXkVRd|`ID@)ri6S^;DkRoXYN2+t_V1LO@(RklXA;%faWp!Tx6Wc`!AdlE&z+44
zrxN|edPTBdmDBvaqg*Lnp;<W{1xJ9A2}SeD$ays6L0w#9+hudJ-`UuUG_R>UdiWm}
zvZql*H+2Ow#=MKQ>fY-b%6<gtev5FXC;B31a7m|9p=?E>^J9a~p)!BkejlzXl|P^F
z>$g$oVT~!~DS6`{+!0SgmH{=n2q@;uLRNRevt=kwolD-p5kCCB=XAB^X=&T|FfJ!b
zJDU7kw3IPsnW_kvnN3JadNJd|{EMu!r9MnfmU%>R{1x(Mwhf2en_JFCnykXo%5)Ek
z4@IJU(z}Dfek)4^H+8OeD010mMK!zHld~04Vevm9yRV>q6DM|b$v_j3KvC+N%20_1
zM&;w9eu#jr?KiC-a)Y9BtmLPUd1sJ%B4a=yq#6`Hr5L!eL>ADBkVTE|N2vV4;EPbD
z?0j*dm=BAA*sIU)r=4nZci9AW7VVNQD;>Qe(eZn6v0{wi`OAvYRf43!G47hfM%owh
z)x#lCqoK(fvk_IP736(QcftD@n2cF4v<CTjcmo&jt_Y@)e^Q5SSFf*cY-B#y5Jx#`
z6{wy*G0~u)U(kA;ddgz5FV>gz;Z_X&1p)4vuXKylx^#Z6dUg=MoO6)*=@u3xQSGRO
zuZHg6!q$PrtQ;5N&!*{x>V_IO|Ib$L<lo)|2IRb?i5>|$uyQ}?mJ_rwC%m4)vT2rC
z%zvJ%qcd7%<6SQQ?oMZGd}Lcgzgn#QWe$jLWQnX4KPo09p%AA^ZSEFnz2DiLws3mh
zNN@M!xiqjOJS=9eSgDC6k_5Gr0$G;Xe|3M{wgoj0HG=*la>sjg7phM$Xxg`J&1zg+
z84mM}rr5^3W-Qr~2jWdUz@3F+4vOXrKWr&U_QaCzaqmpP7*q_>0gU^W71bn(Zg;KQ
zq<pW6LsvPzonjSoNbzcn19@|w=QX)`4rMfM-*2H84kNr)zFXdMxV^A0cYSpzFgQ4e
zjSQ^q&P&ro-|q=DEdh0W7)Um3J^#k4fEW{nKR~u#w3TIh!H}DE%RnrR7p%6D=qjN)
z65!cjiiy{epB3^ckCh|-Q!&=%M=OK+n)Hd`=g0E|6URcaHmQ3;?>vnpSqPK%nJRgD
z>L<prZ?!q>>JLN9daDw7Sud)=#yY4$Ey!Q=R;Skc?mLcqS456|?2#l)Y&1K^*qC$V
zg{ktFGU<t!n(p?>nY9XbKWCOO3P{z}D=>LknL3om4xdbe8546nWb#7VSF}7|D9}%b
zk14X%-}1ebXv~is{7}uk7p;<>h;E}oC6=5Ri7qHSx{8&UpgQzwqu@wgj5E22XUM2n
zE`0LLUo&8i$im?jP~lLiAYP%OQt!?F=DJQbf{5q)>8qQvTX<)l<~Q6bZEm1L@n~T)
zCEIv~(`|v<XB?qk?t-^0PKiKSQj^L19}&Y;YBJ-a6l{D13uj$pS7ZJh-tP?Tr32J6
zHKyoaS|evtNlh3L?=3x}scG>s4ffSMD&^*+qOfwEQ5cEOW0cWKz?H6##tlH{2y*xE
z9K-sIE`Zo0#gz`rKIG>Bzn-<(mV{WJudc>lV|O*2I_V{N-es8Ena8MiJCwGRw)uFL
zJo4W1YGG{b!-u6rQSc42n$`skRpaLv71zO<J0E(t(G#nZpO-%(#4B1kelTGT3Pu6D
z#}F6Sw7*8@&jHhc{x@Cw*1I)e%?t&Gp=RsIWzA0t)br`+O5sb;Vi;U*E)izHsy+Ub
z-A2ZhmotlEcAwG@JXd-OR5bMEHX}OT9+S!CcjKbc9C@*^d&1wcC7QF>_Ti|+^CX6`
z(|KZ6+9CSf3CHmmm!TFI)ENikdp}U!eNS#fYquRWg^~F<=uX)~IgU%0d!jn4PnYnb
zY@TYqTVjS<>V?c{&b4PiMX1IsP&(NvT}qcgwYaAg{hKW+2NjaCn;wr&w{b0>#()yr
ze)TFMNOcgg^#OogPH+b@7GN$f@#VZDsC`#ZHQA=__O*<3L2<#?CHB$(MV!nLPyLTa
z20cHU>%}!M$ReAhWlIXi!!oB%byb)Vf2+apBiN>{Y;iTezA)!nC!2Rr=FkOoZy2X1
zgeo&dH5%8kH(8T=<ZkX~!H3pBGk(lcKK3x&a3<on)dxl<+_5P>1v<vcUK%jPI?Upe
zE~r%#o<!vVTV`+ENdbdW*g`1;{1S708SP6#X@ei#2%6iB&CR&C_w%TyPph3R4kQxy
zsoLt0NdWYegmPI;>Ad*N??_W$Q^6X@a2m+S;crHF$Libr%f7^M#te-WY3fQ9@6sLj
zXtc3vS<pHc>y)?xu#y3NAi@Y<n^!2t8L38YMt(rWka_{mySK<TQE_!wKV1tDN;lz;
zGGfkZB4I%YC+?CjOlVBRq@BK2+2{p?6s~ebcwfd^Xs%|HsxTFMlGpt(PEs)Jv<U<~
z*K<D}%EZ%qP0MI0eL&HKskfj(*>u;NzcRQi!a;5_<>FH$)HLCLElo~fWW<6Vpq<;5
zdG$bcd2>}s$IF(z*S#%ZQ#P2p(oGU^S^Q&47CD$<tpdN!jud5*0bCan;<LWhy|p!g
zL*q#$yOSDLOloKN?1O)W$^1a-?!^8Koimf3LfxaQe3AFgH1WzzrNzp-`K@#Mc$=y3
zo*nMnsWUx2GyOPml`;3>y}FM}ev=8DHy)&41st|VKJOSh&dja%ZW@sDtHb}e(P)=X
z<bY~EhFwLri_XnSmd_d8g1%9?DRPv3y?eMic=qDFIcciCe)gu>*MF<A0<yod_F+WJ
zL&M>%_f=+1=i7HO)k9WSfyK?8NADAwKHi@+f8OrUCQD(-QEIc#Id|!7o~B>9jlR8^
zyng>N5dTUff<A@!p`hPE<t@#GH^+tT+m7t{N5RL{OrD&Oj6?F3u^2{2yb0-2H?%7M
z9PzSfK3_%&Q)J!sTf<o<`+$_TsJI-s9fC|lDPR?*eW1+RD@MSrZ8+afrkm?1nI-gW
z=Yg@@9{Yqee7XHZPv~2o{=kGQqb6h(k_L)e3_&bOEPjceZlSA}Wy>t}emvbgrUCBu
z7%re1FXRGhCnMI8mCW*PWwTO8=Bk&Q-*Rvlr>7P})!mT_cqKI=N7vl+M@-AY)5M$J
zb#WQNVN1$jye!LA&Uxf69uGaWkm8}Z;}{Q)yfGkBj_}~eA6U&06eRX4$w*+NhRcx`
z4_1q|#gj3p-@=$-vH_6UBYB}XEK$@&Q<ctJauggyJ;RPM*RG#PqDW9~Kn+~%nAjQd
zRF~cD-Yn8|L!b2OTtT>;qnZEsGA_D3aibUhgd?oj|5eV|PB_K49?f{)Q#&|gM0>d|
z%PunZ(u%}As_-1au}E`my1o*=L~lR#>hBRzo8~taXQ*ZYypn`;#tBLj@!4bO_HUwi
zU_zq3yt0Lm!syHp7T7x;tw9ElUXRM>M4`>TYh2v8H_3JNr}^JCb*Eb1qoRN3{QhR7
zQ*i9s?$K-YB>#%2PJG_({kT$xi~j5nI?W36sj&U*1BA=B$-tv$4?nTFuJQ+uN`UG#
zs5(}B92J6y6d7l4Mu|>$g$3>APdKHv?6y_F)Y|pOjTfLzS8%2~?pJl1eOCL}Nd}Cd
z@8rerr|crikKAts(`YM(l(+flmK)p5kn;#-No6dKu*W{CmbI^`%eGHlAE4pOpxJXx
z_s(>`bmODjB(aY?rz*de$iXOKq|s#LAzP2CwmXpEt|lB!+P$6gEkHrs2@1=AZjlz;
zm2&N;X+Wh*{eXxu0fZd|!9qys4+65c=smU#_ip|T)sc7%yr-;;ZvcJO4`0z7aNyu_
zm_Pe|p&`3z)R*#g%ayz<qc(f{{gxMsnB+?9SyTT93(li(tR`GrwHEK^OY}5%mGH%|
zOTFXOr_6BL#lFnu8I3RxBT(MBN7srq9MA$-M`pO%4J=W5MZU<~M{T0qk5cf0i%{uC
zEuGL0luO#Ucf&B=Uwq4<1?=0s8GYG<mM)<Mek_wR`Hot-9FNLm>@#tn*K2x7w;UQQ
zS3?V+A2s<bBA9;jjbS{#%khbKb!A4DN8qj+S?lyXlBax$V=LNH0@uK}#0b@ld6eg)
zhs4dW6zStf&7lG7TJDnv6XY7>19SWF%2&izpJ4V;+~<%P$+`Uj;6d^17PdhbCLCH9
zYY4D}2YnIWGMIX_llIKJ682)O{yOd1Sp6~%<xL#g6yuUHR6XpTqe!X`F*DEgCkEGU
zMCSN62toel`t?3mTKk^KkVl(OmGLCm(E0XP!Y{r=t%PsLXg!5a`)YTz2|LEEk0n2&
z3PZ%jef?8)YRMnWtAAf7;@RlqG%n^jPo`NNrY4BBG%lt{Y%~bFWCmq1iLzt?S48ma
zYgGSuwaECZR1G)%IJCGa#kbHnv<0Ehia3_R(CQ3a*GN#ka<0-XY)~?Au=U<`Mu?9E
zK2$PG-I$u%OY0wDzDu?ULm{WIETWxqxC*z-q0t`tbn@!UKaWLBWLy%2<%>s%KuR?G
zw8T!+MgeWY;2Tt`{A!5|iV8Xp*;TQnB2#e=>cv#1WXnBt9ujRz)^QtJVpi+>sNuUN
zhC~K^%mY3%SZr4iIp@_6+L}q2%dqgJON6e;WosxbFQX$wXfLA{SE$wR;1r)yLlglZ
z^v@qWSNJgEyh}__E)y+Z2x~-IBnt#dr=cj&TK880wE8tZv(`?hvwXI@j7(l%iL41W
zma1Xvby)hKMBvsC@!6)@gB)9ywEbROys`c?;DFjS3{vDX;ssb_43xv7jFGX6Y<@=T
z8UnrXj(fq9(TsFomSN-WbIIs?#=)iV;!P5fvI;ccxw9nVn{=On+ZsTINSO~MRHII0
zuqSn0s~$8WF?s~UkAycVFrKtR={{3v!30plnjyI8YS4{}%8jt1D>+@JM@UBq!RSjr
zp{${(Ps~3(GeoSBZlP-dMXaGgIlr`ufYtFa@p;t}*lr1p{i2Ji<$FvfoGX-;5MYN$
zd*{X2Gjbo`aCDr)XwxGe$w{+ZOY{4c2ecVaMVtR7lb@K)KV&i+ko^z6%k$qHDC-k%
z`-=!>{$C{MKRHjG=w54o78J3|Yb56Uj~FFTd6>e5c|^GHzf_Pu3(1tE67_w1bXmDN
zthxj389isA(-Fed?_ijZn&r~Gh0BFcZNXREJ8t1m(%D@|3CF&@Uxnn&?;<Z|WPRz>
zUR&CpRfv@J;<YwcbNg~P1HS<6v*3jWA;D=3G`$4%s+q42g525j0Cgu+_~+)ABej#(
z;=v!Tr|@5=SKUii33hBAppSf)r;OG`DJ~w};^oaMT&W2($2Sj{xZ{;!FFo^nIA|zT
z78&8r%PQQ%PJ}#UF@-h1jn08Q1wFsi)o=lCAhEZzMKyS^4ZNa#vpLrsn?`lX;IN!h
zgU*zwAfo@Og87Dgi%P3|+J1ObXz^ncn8_dc!u;5LAS{}Ir`(in!YDchNpEJ~`Rc}X
z;Iek>>m^6@5q=wkD^g6yt%u!5LyaphD7en-mj4dduOR#tF9`SlCtR#gMEf7k`ZrVl
z#N~?`I~dxV**e<TKM~)*=zV#R6@;socqc0(Do-zJYz|U)Qh`wDf7gqHtjsLk0JOiW
z08e#vzbh?4U<g;v_P3?*Z#JKim4%H3z{mk)1F&-OutQjVcDBD*eJMwfrJ13SHQ3S^
z!1Ak|kb~iqEWpFY{j2zNeNSaZHg?WmfC$J|(%1}a3Q-Oq-TZ=79F48i0o=daKNTeZ
z6rN@X$wXr|z!PKtPX_-<viNUr{O-=l!10${p$gFmo;>vn6$UvN{}Mm`KhK!iJ2;A%
zg6#h|Ko;~@nU(Fg;PLP72K)-h@5Lf!4G{^<tib?g4Kr&YYX`GGz^{=t%#0jO9U!U*
zJL}Ud{`bKSWcjNe$PNVj=Nlr?K+r$u|J?&bap8K>jeZ|M&Oe{Ixc@aO5RzP6>`$5W
zzYie$lR5(#hxJeE-*#+V|LTJUzyX;$CnO`DuIEWvdD40y2;}`s>VZf$Hfq*pPr3=<
z=_d2fu>E%uKWR$8b5q95=*de@vXk=PqLI^+#Pkp4hV`GSl%l<jk&_`rtD!Xnnc3R_
zSeaNknIKc7HFb2fea#G!zaS{s9%O53X6V3VV-KeLo#-MEt<BNQ##;1AI-?bR&BnsU
z#=_0U&BDsb#>qy{!bZcwLif)>|E0VAk-|hkkj%FM{|fN0Df}gb{YztVwKq0FVgayn
zAhG=Y0zksT&IvF9{KkMRY+R7}JiP$ce_@b%$m;q}jDrnw3IApXDLe(~-!O<)2oc@>
z1LNU-3etbradAQ-@$VQ9D+}Z|#eZT?$?_i<C;NYo!3nuH{JR~Hg`FLeH2>BX$il%1
zNw7bdqdf?+w(WnZa4Kf*#!tR_x``><*g%5*<n!OlOUl{=65FT1|4JnXN07baFYf|b
PI3e076_uERIMV+Cz3Z>_

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error-high_offset.pdf
deleted file mode 100644
index 934d6ddc327f7f50022048264af1854d8fdccbdd..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67438
zcmV)xK$E{EP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-%+#yN?|<uTOD?&Y-W05~Zq|
z8VC#o$iQ~bf(!x&Hel>K=wy)O+h>bhYf<~YchBqJYc#t1iT7xiL{SpOKa2KtzW?W+
z?EQbNo#)qo{dxS$asFuIeD1Gb|Nnpfk6-`(|2V(?`~Q8|*Z=eW-~Z+PzyIU--~RXa
zADmzR=V9m9|N8YWUlu=^|M&fK?mzC+zQ#Cz^!NY&`Q`n`{r)i$USI#^>pva8?biE`
z{{HKCxAx=lM}+M5yOI81|NZMf{PS_=<nFK5el$O48}IJ(hqrOv_Vv#{kAMH){^|Uu
z_0fO+Z^ys;C;Kt}r+@w*$N&7#-!b5~1GV{MY_p5z_jB{-`7!;jP9*$Ax4Zqgwojq`
z7oFz#agVn30^u*Z`5jyr`$_o6*#G>vukQW*)nPxL>o@HG`^@*=e%QIs4urp$osA#%
zJX<#qzVG%HzfVyn;V-(~Mo~sL5dNau^c1XIfNcIv>F@LUF@7Wc=f6ezyI-H8Ou}Ex
zt)CyFjP_r2vi>Q`Bz)hkJ(HrG-AMS0Zuk3e8&(TI!auYG?|C)5?0$ds?mx~y-vM9e
z-(P?>`==<A@E5c5`6<dI{6)9-j{Xp368@r_wf&6D=J#Ff85FE!KMDWn4j8xhw`kdW
ztIprC|KG9$?7BZh8STHA-Ly|pCgCr-z5oA*D3kCP-P%o2MmG@tqMI2-3rhgP-`oLa
z{-gc*A@uccxC0*llw`EOpWAhP$}!sCcbexe#nJkUd#3+#&-Z`D+1MuJ3CGSXar%d)
z{=GY|-w6G`N$Gh$rT6()$nK^Gl3?E*RPPP3cvam*c;E2<=s7Un<Mi>qFTTe68ui~P
zB7ch|@BKcuVWRo%+}=l7e>1E)iSTVVd!L)@pQ~R{zVG;!gSFqcj-q_u(MKxZ)lrnc
zu?*&KEpWb1gXjBo_#3NWv;87wMfrY;*Yk^@73KSm&-_?;w!iJv-YU!I(ii3Xj_-5y
zbM1@rH&&v(&xro~<&OA!H)DJ2fS=-4l<y}wKc9#{zl!pG$2;`Ltse>BcYEH->iMx6
zqI}!2n}4i5+kayvx}87f-N)nKt;F9_5qq~^gsmvwPw)NM`xLgKeBbf?xcprCqI}=+
z{UrKa`J#N^@wq=&UWC817SH=zsjPgv7Ju*Re7`Y2g{>&xPI0|y{o@cW%J&`pi4ObK
zOUm~h=M3g;9Yy)R<K6d8(fS+f;O`UI{(4XREv4~!ei5{yd^@#e*!d7N5x(!%`!B0r
zl<zyfJAAHsQNHi^e(Qg(dQtw4>NMWB;rz=z@%MD6x0?EkpcUmWMEg?@{nRmEU%&qF
zzh=rY-G5pWU+<ipXS?4!EocAhl>fgq-|ZN0KhC?|>q332fMsg@cmJ>WV&}N;_WtU8
z>k8-k{CiuydHd&r`rbTkX(IUoi`E27mgO(r1{ZC4MR7c27UeD0N09Qd2hy98DhDX<
z|9VqCT839;P}ZB|O?k`g@e8R95Y|)UI^)Mb2sPX_jW(a?`uaL{lIv4T>spkw;1vZg
z>L9%TX%T9YF|I|bNxp^WO}XL=pOl*RSnch<=lT{W=<)EPMWiTW<4X@?OP=7MEZ)5-
zZ?+se#W%+Ec;R^rC@F0Op;#3JTDF2y7M$uo$OLoPdGzU|wBnNmpW4Q!H+zmCiBIpA
z6_27t{updYCmyUpiOIx%I!Icxc^?quN>Rv_{6HJGc#zMyMHxds6w5kpalvxM#wGc-
zT!J^nG@@97G1o`=L&5Pk$u*+j_?u!HQLu9i@y3#UV<eA2iV?Z^W5KsYA&<`7aifbz
zxdRqOJUWwYqlrf+c+|wB6Fh3%P$yWFt8jo612Rd@2^N`{whR*Q15GSD!JzX8fA&4}
zBM7Du2YZ|wb5WN3d2P%5<3%xzcm3B}&A+!^!JRh+-L4dhMM1agfuZq&lwNsyFG7EE
z>%B?q<iKko3BenmTnIeQ!d^M}!@&ukY`y2`v=%Nxu;ER?c3zbDFpX!660>%$$x=Yx
z-#ZqmakL>4FnJ^;C*9TS#-uwt-Iz1ZVvvI6jVqZ3!$rVCz6m)++5{IRr)aU1M-ZZk
zg}iP|^5l|SH<lKw|8B<=&#jBC6R-7W>k~8TTK(&e7MJkK>2w~*i?BY@?^?oG-bLXO
zrbD3ht2)JGI&E%?5}UhY-H#x}8ueQERALr|3xDNS?vt&xKz&q?Bbxm4iO~<X;^$m~
zlAl@>3d+n~*Zn{<2i~_XIq<%9$#HALzbT9HJ@@;Ol-N?eZM~B5x_Ga=Y8HjUm3RH3
zEa5tW60Fw6dku{D+&Xob>FaMgEcq#a$07wE+e5J($;x(DuV_(X9manh*l)_Uwq3i_
zBl)^0)hpQ7uB}(Fug$Gjo>6UX-Ewqu>z2cl_H%i(*n_@_nAZVPOu^NoV|c#x%HioQ
zzB-tfm+=8oaIbIOa(I2~7K_=MJ_hBi<(@y1ln#~J_0Wi#ZQXK2I`l6nA}tSn{7?v7
zJGX8*qI2t(43kC%4X@dwE9SxtZ;!g+^0sH|79+9}4BX3h*VJ(5+D&o7m2215D_CSD
z9Jo8*l!hY?7p0YO;9j&T@x~=+lb^z!XVTQJb)g+WsZPNSs|(?Lw{#gy+)JjDVd54t
z*Tp_l#d(v^N-p%ROEN*K_R?!(^gUbQ2Ah!2dCN1#KhImiq_4dR`9<k$^Tt<G6FQQV
zpS7)9eik0qHz680dgq17o;>7JZ+>&^eApvxVvB%lVdB6(AKoT-VzyH{!Awo<SS0*R
z{4+bu{O~CiZ{qwtB@`0}?s;h=Pn@r(q+;f|uqf3nr0b+qtdNJr-7}@)NYY~ODXD-a
zzbKH3Hzg;@-^dA;R1938r*y)ZLbNDkKb$&e*Q()QJiFFl84p+6@Wh&qNm8Mo`I=n>
zu7F32%<N#M&W_o+iU#iY_=vQ{+3^kC9&j8l3VG6_h4;+N^X&aM+9`QtnZj2VWkj0{
zNqOcsTXHO%u_Q%{oG^SsS|hwZ_FR%Hi%*0E9w7Aa80%>;Q!iQ;d9ve#6S;)sgr9k8
zemU>uXy*LV;8L#VMQI}l6q4LGZ^~+oC-ppg^l%ulixvTM9C^Mj3g$Q-FsXBn1M24@
z;fLd&!N>KQiVlryH*T;=uZnSF>`iCZxWOp?L5^JK$;k70Q8?BM3v3$emCrVNq-l-|
z!-uAcC)#Rrycuv|x3rLav;~EBg^{QFB7wJW${NR;lCAfDNm54M{fokpjeNn|Em6rA
z-J7DrVmP|#3K_W_7loho6s<Q2&9&tBz+N1VA06C_177uePyk2ncDv(q2S~yEn-7YS
z@Ao$$S`ELUb7Ej~-8v^m<G}Rv&o`sNCX<95ot_s1d+O%%a$rl{p#vNsg|Ogpo|O3E
z5(UE#mnfY0;gp0UNx6m;g%c}y^4q7}Yp<|IX9xv@NERjJ!7e>I9J}Mv&Ek3M*d>M3
z<Fd5(697Bc*PXN4ykH%&FGs)QWomdgEJ|KQcIntaFq5U`e}ELMx+E{2`s|yMt@nTF
z3F46ROTyy#sYQac;3;dD3`IUMHa$pvAi6|%jgOq1m3_|##-@YB!y2^+Bb)KxxfTjw
zX_5m^ZP=iTCMCxvQ<6KzrrSr6FQ!*6A|33~^W{y+vB}8f9ek6n;{Dyyx#BI}6pJ#@
z9?@!S=8B$Zg?K_$TNKDWbh9H#A)ZqTt><WLN}<J@dQm8)Cqi^?sac+y=ps>ea8*pH
zGd-_KE30GAt6<hEx37PfAoUx;K_N)}LTjLvL)XQEcd*T_o3KxeT{lIC*i79NJ$JMX
z9i<&JPV-y-5T-n|q41=%A**V8K$#mQMl>P>_6UOEPjbx~W;iBVv4Zbon*SPWICQ(V
zD{Xs*lRQap9uB9Jw0JNq!r&i73p~&8nMI&-)$+}5gC<tT%W_d5tSwc5MFEpqssM{(
zuoJfdPKvi}fRoxjcyQW~;?^8&Yt%a$wipJ3>*amk=6%yTc&1k%9-oUsKJ|FyEDGeY
zy|+@C0vqm<A=R!ma6vBtyhJUngE>P(l$kWXhP%VH%^G&ln=;UjHTQ=Pxdu(kAFW|N
z+pG+TE%hqDHNG=i7@Ivf>s;>#%WZ8g5j9*3E)m5ubx{V|!F#`?6TL|}e3={#Qs}w`
z3_H;$j|2-L^wdw5q#N!4myyDt^Q2YMCiq4z!l2u@tQIy?L>CFd`+lM3hX<F{1~{jy
z0`JyE8ED5+d%ac7@hx2xhBMr?2M|hY3Q=2>Sdvb2lOYPw;{j_BDVOSD4WE$?Y7L*!
z<za>mUDi%BOewoSQFmP&hO^eCis1FSC_J$6e0`Hv>wIE)B<$yd)se8Dlnm*p=MDAI
zPc%a=$~byLF1nl>XIL~BfximPx94?prUY4+nB$GQDEy5$8W#cQ!#Sgs=jA!lu4-M^
z%9*mTC|IZy_jretpJ~8aZAi_D3%XBT&}W`?R`%5s3ToFA>Fm*hFrHX&Trx?)=q8#u
zvZ3i3My6MGyhc}>v&BWz%lCrkr*(;VK0y~DhuZN1U6g@#h)CzLe{?)S7b!=(D7k(f
zt<)GhHKj#}^F+qoMakD{?-*`>pdrfMyD0fH$?DZk=F|S$pNT1^I+K)~AvemRB=5OV
z-jryyoF6WqPGeBdfWb931D6&l=ZA}<Kb}+My|D;6MblSs4unlP$A;Ucn?BWJhNr#*
zwT&VB{efMe)82S2Qp)+MFBz8X6sMq!$u#|@M2kE*apt#2>_2l+X{cU=m~-Q6q2H-v
zHD;?ULL3&UdK@6dtQ%Fle%}g|9%u)r+6{qPl-Sx07trx0K^R*8L<mCTK3(l#Q{!#a
z@d`Cr#1|#s0*$YdMQZswIm3IX6K6QUx2Y+nzO*QsB5s8?HATF0+r$)Ioj660mSMCV
z=V6<agu8?NLtpOTKev2`U*Fo$hj~i0fiE|8;+HKKZRq1rQrpnCp;k2KW2I+^-=gr_
z(7~JQ+oyWPr!PD>8?7<NBC%8B-{eZuKGQEsN9Vl5{br4~XQwZ1k+9kqrGuV=MafQ(
z=8F=d!vqgcOJBkPQg#9#5CdY3N@s^(C@A<DC<!g&Czh<j#bd2$G!DVikpursP)`00
zdr{~wW)S4Op@}w~LixH30)7LAjYiW#Pq)SqBo3yr7sq1i#j%(^g#$eUP!<7KM~4%^
z+Np(trrA!7CohwBa-rs<PH@mI5_@5-=EGhPSv(l6;W@ep?2}@1EK+uge}{3+bllB6
z2ZEAgoB5V88c6!Yg>7=mblAkrbSlCCz9<~r(6=zSl!(KO2Kz-quV_IU<k;zmQ3(o0
z2WhaIR+SFBvl;c7MPavrHalTyX+}2W&K*G-LBRH(O`Wg>X&AN}t@Zbp#%kDpc4@G9
zbeN9c$k&KAelk7bW~nyy@u&xU*^3lsgI$!ufvdyl!|dZ$H;k2*SGy#bw6&Vf?2)>o
z@sY6zapW2DJr*I3Njx1EpT=Y-%z+kCB%Q7{`+(acO;JI?6sS7TY4)Z>1A>8=mqo#u
zgV*$%lCAfD4YGdlnlN1fv~=3wOqf2TI|0EjW_<lD%Ib6kDF~)coQkOv<Qzsy8=MIC
zzsd2tNGXp)%X31wqKiKeEV}=CJY-iJ3zOEyBS|?!ztt&cnC3<~3_G5wLCLQ=-jFL$
z`~V@P#JP|Cf{^fX>W=khKtgw}x8qT^D7oVFT6gD)>;A%na#66N9={s@<y=3;wRDGO
zpzO--9cv+Nnf5*F<Ur^8Nq<(>SQitx?79;j=e+4wbmLLg#RkKQ>7sO)o(;Cl?%d3s
zV%)i%<yPyR+gZ11=XUPVy1`xDt%za?O0uHEq#UFiOo#u&;H~Q&k9})oMTdTG()c@E
zk&6Ug;FV;^j$G}KZkmpI=OMjQ2FAxTtMinmC%JbX(z@4s2e<eL@4bOrO*;oM=0U<N
z@W3<XSoeHun4Hv|)<sZ`B!P$V2PdSHkuHmp?As{O!Wy)P5=!UhA|*SEaw|g-tI}ZW
z`JgO|+oI$;L0LC>)O#8iKibJCDKBj*Hxlupod!jt$zo9q-zH@wqoncBcnHdoq-0cj
zY<qLDifu9q%ip*QcS=}&%%n=SCPoyc<zOHoP{ckd>3}pTU{Gu}ianfEZbI79HUe`-
zgHg2YD2+67U(US;Ej2~BwMNtyV0Ni-oR@fs;h$5iD+<R(&Ho(Y9vB1P|HjYLHNc{P
zc{#pL4Xp^|C6@Z^niDCl1TW>|Y!p14Rq*X^l1F382StLH{5-7$4@^I6!===pwcoHY
z&U0%u8dJ2n7DYlu(zf4%cZ)(!<u+avaEgRf*p563R+EQUo*s?HlZ`TUcIA=NBFhek
z(gDKfVb-3pA7-HNEDNz(1RiBQeU}a95}lh3E_)oVpzu0yObL!&QjQ?;I>=A8x(zUe
zR=0uY4^!Ep<Dfkd1>Gv`Id%GT5l%6Xi*Sm8;Q5{U&5>8!YU-ZM!O--fo3qjQVe}%k
zo9b(anW){^gS?R!q2nS4vu^6IyxQB%U76m<V-fn;^?^5K(-+!3q-B6nG<8t#coV3W
z<hWctz@&TAW-u^nGmh3gcjahN!kHoksv&Qpl&l8#Iu)@X7_=^O#K?IUOH68Eb~>dL
za>l2$LeBV<R+#3)Mk9vw(MB7Fl-71V>IFf_DC5+6+l6@DQj6O~Rfk5Hb|LtK>UF!Q
z=uiQFQ@)^}=g6q|qz>P%sSa4*Ykt);V5P6{?{hUXICXzbtn3xO1F(J<&*X_#%l8YG
z@8a@K9T6ATcycD4ov>K6Qt08-F0SyzT%Z}%>#Na7!53Ok*a;J&>N>SDC&glFY4|eb
z4C-Zy#hHAi@Y%U2*#}OZHXn7u3}(Gd2ikm>VgmD4pE!1o$dO?uEWo_f4GS>&P{|e^
zDYphY5vHOC{UV_U89oPlakNy3Zj5%Q3+}{~C4)XVB&Vwn2g?)s)?j;fdeG>!r{J`k
zFk#YGf-IV{rZ9`9EG|r<fmJ5QX4ovW-9$DG4L%s0sT&7}%Q;L$kz13N(o?*ofg5I~
zNUg~p9NwUTo5rd|3FVt6tyiShup4*>|9@G=7KPt}V8Ypdz{UnrhhYv3q@6;hx`v2=
zGUqkeDULGvHJU197i=_D$acsaoiZ;XM`!&|PAesX_Q_1op;Z&V0f~^EbEW5?6BiF|
zei=-Il7{1^u{8GLQ1Cv2ZT3h~_R`HcVA<9^$w(`if!i>38W|Q6IXo~pbG1%&!#RQ^
zo-#@^iARR(BS@o6+s(_g4PMZa0RwqULxv3K%@Gq)R`$jysiv#Np~%Tv-xv}li~dU2
zx#<Of;QCazfp#04=b$m>N#2FX>N(|sI6$HwgC8&72R~lE4}QD6A0s*Co3o_Ryn)wV
zQquRKQ`_nL&?)VW9;=HC$I&7GPGg*soIopy=Ng-zXc2O)F9r`rqR&ZJ6O(-8i$ao5
zd8?S^Lw{DJ_=L?*F0VyO?(6LAczelrwvu>q0q9<99jCEeaIM40t;4ZjU_U*14X)}%
z$y<>YllIUb{U&X`!N~CmpDF!^i;|v7IvH1D&o#;o+0v<eY_7^hN`JhLua0;eB+&$6
zY#z}@^GSM5b7=IQ8^1)~xsIhy-?<(x@c+_>dt?F-oVffJf}`aJZs?!B;vl4O$eX+f
zn58uM4&jhfIx>P{I67qd2{$!Y9}k6Isx$ns=^t;5?vnq!(dZ&4`<o&c{7MB%*_W5T
zHHJ{ok>42L)pbxbC>M$dXlZgewxEGX4;p)50keZL@L;tfK45C72;a)!g#)DIKBF5N
z4x);HXf(j|sR6@<o?HA#N{SSeDjdiaj=|KR3fWjWJ~<qOb+pEVLSY{b*HcA?L}t*r
zM~^V;rvgqQ=_eyFwAmWNC!}_?O!CaYmetDeCPuzAm~s4+9<SIc=?{vnlD1&DIh?Hw
z;xYZ|4OL!oJI(GbuBSm!&A6Y{$`9zx4wV_fLkCC*71EF7(klq*O+bKBB>Y6s4{XGZ
z4;6E53p{@+>Z#!gRgqDP!jLNnZ9e)Agjgj-0ay($;0n=dcv@E&SHl|~p<V|_`5C>H
zV4G0P*qeZGvX;i2iZ*M;W5M-+F+4UEwYGA6GU!Q<5!&Ar{T7))aZ~uE$x&h;@+b5R
z#o0B)TQL%EwGqw77uX4VkwW?wC6`A6e?lWwR3Nj35ILAX1nq<2g^MuHia%WKj%Y)U
z4hpKG7>|`16j7l}hK=N*Ef^B1LlrN{)S-&0jMSmn#0t7>CnG|o3ZIM!mEL>8h|l=W
z1{339_*q4Ra)OA_Q3&bE6v~KDS&L|N9Lh6p4CflM>#T4t1+*f!sA67QnjjSw8`(uU
zKiNS}n5h(AyC@l0>Y5+47e(ks&QYA`3gTtbQAPSj(vjba1zzoB+>-Z|P;?Il5+9&2
z`gowt*yH3$WEG7)VtG+Av=)MTD6Pl@Jz%s-Dn5GU-DGGvRsYDliO_85`G*p35RDyw
z#L#lr_ZeEABgPCP+IwZaghpH8;ENQ;J>$hA5vIb)SL(~y0?s2jCPsDB<F!aRbWP@F
zR5=yFMahx#$-F2Xk@GO!FH#7h;5wL7QvvspQxh@&Ct4ZrkC*Erq&y*>f2GSj_=_7e
zPL)mx0gEuUlmVmpui!`)DW-UthL0m$2?~o6Q&bYeqQp+Ul!9qMj6pg?P+&=7#srgd
zm`<_UW6QQMS`L+wVGNK`+J*sRrBXW#s3w*EVG5a2j)(!{qY_DwzOyBp7{aKoiN;`-
z$^k<1jv5eCc`Dz<09R2tF$OFO<jou)<;rSf-OwhLe`B;!Dn%!<e&S<_!?TN-J$zmm
zW3QADWPnttq#^z!a*B?m#P1;MXtgu5N`eL8f=XWE;48uDu#C@A3KW^3#3=)SK;>2$
zAOkA@D!996Xj!KJR~DBsUMupxj3!W~g)Kt-y)wrZg$ZX62F7kF1udj01_E7S5e72Y
z>_YNGWxW~0xRe>UC^_3(BZu0mq&v%8^JB}=<0eBQUsAS2KPCV%IWYF}`f#QX9w0?d
zWvvbDWXeM{7)>iz(U1$Cxr}k79L#kD0jZ7}785mficdrlE3a}<u2ET+h9vJw%v_Wl
zKJP^45><ldqU7*hXUk;5=0Gd6DtY@Y%GlCO<Gjwl=Z2b$FnnOcep9w|R-@fkDX)vd
z%vp#HExDCDYe?I!^jf2FS1GvbMoK<O4kn!7&s{S_OfwjX!(WNOi_*rHDQq+eE1TFR
zj5<g;PD&(cQwuXCX`fm|CTW`%F*Z=-Js)UCy1#OxO<CHyAe5y|9V>3_Qz_U-Qu0gM
z+S8E|uDz{1Z5r+@^0ajwOgy(MWqgq`9o)s4%+wzE@66IJQDK($&=m+1Hg(jOR25~w
zTN<@1M}84<emDS*AO&{9d5M(?Mx})OMMz#s>6ieLP-6cPP}XNc0Sx>}&hVCuS<LVe
z`+?gefPqB`)COV@EJA`doZ>$4mxN_tlZX)~I}tEKA)*#hfK4v{)s9cghrTF@R?)O-
zKsTamc&W00H<H8F5I&gj4y%=4Cj7&qj13^dGU@vOg2ZYrR?B^8h%_t|ilvd}H)(h^
z<beap;s7b3Drh~i0qh__Vo<deYK9G>MofmlhC=N3hQ48N4+x>dkS<;z9+p9kh4XQQ
z@*O{OSEnI!LAG-&(muzPoM4XTBE<Do$Rux)pi5q%^9LIQZ(<oJSqLbG<Z_^-93TzZ
zRI(i-k&6Opiv`HC2*DJAwjAqy(iBv^UN4C})6^x8FnI(l)6_QvnRxO9Hk*w5HVE6}
zTek$B@vU3Jy!h5DLEdC`U$3x4o*C-qVAfDK&mqpOQ;0!<@WlIW!|5^jSqjT1D5q_B
zKk;si0bYER8k{i&9JJn>Ilz(#U|F=12!QuIFs0fcc+azSN~oM?>y*$;yi5j;Qh_5K
z@iu;*4MEA^_aVsAB5W8;O!X|Brl7=$E-)uP%bU!)hH%#cg<6!c!A7li@UwS@l?5rr
z>u3dvly5x}M5@k*1`w$nII{Z-0Ly>`PzYHtLL`8e0T-YEwhR%s0O2}78U@sqrjF;{
zz`SVu5Z;#op{^jojv)C>+%Wu64*q5@9PdIOGeq|mI+=}=%%`z4EH>+7!Z{0y-vUB2
zL<AR9n!&jSIJE<$m=*xnY!E1~&H`K$GFZ}@BxJWENC^=qrE{DG54S8*F(V<!nG+L_
z(JG4)$XW!VqhYJS>db*fBs{w?hQ)WKHUQA?C}6xr$~jK9PTO$xU}7uiy+z0=E3n<1
zsCZg_-$DPvmKWckq1)hbEbu_s`;HA_FpPrnrDyAwtN3i)5)x4>?SPad;-TTIg^5V}
zW1%JnW$eg`2B-+YFCHK*R?sHLG~@ztG)%dG9v3AMBReA(vx_tU$Ned5n!&YNu#<+c
z@g~!m1$^SM;a3_!DhlH=DCdrYX>id3ERz(%X&xXXYoyybF!;(i2BR>*J3$G~+{6)E
zl$@wugd642aDrR&lziriLd4Pdp@{+*GXHE8@&}lHf;FXan^7D1p<p8MQHvl|J|pdk
zv1*X{f?);a*q~ZzST8i!pqxA6Yf%OzC$H3_kYj_iVau{DJD^YD(Nc0qxj4UAxiSrI
zlwwqZ(cT-QNZA;b__TL1DhbcVsKBSKjVZ#d;f9^B@PFy2D2U*oEZz}BcqbHF!s%9M
z#3UtJu_5)L(2R@XHAz7tA8bnTK`D#ERTky$^+|;gvNaHhr_bGU;|?hsH`b7Ey~0Hi
z+=eE9-<u?nvT<zj@P0OqfdEi5uEle13;|&igSDWK?P3554Plgw$2KttLfa-90`{~`
z4oJCoxy^`J`xM-#_SuM5?XnSJwk0@mY&}kIymr*{hduUedn`8Qvv0B3&(GL-m85;2
zMai6fo5eBlT>IeyO2@02=go6%hf6Tx-k23q_1qh?NJ(bBnSMo}wdrmMA$gwdFkb(*
z!nf-%CZ!JJ5UF1F5uDg7GQ3XXwV3_1?KEDqSuy8z8pqNtQr%YTD=V74Zmac^y^I~W
ziFz449O*KPRM*uVBO2Rvb;pRtc3s^uqOo09PmXAA*ZmnIn%nJeF`{d`-IGVxcDpaL
z@uHALHyCnnmw7Ve-Y)Ysw3VOGrGCUgzDQF83WnIZX)N7pH>Oq-Sq~as@M1GiKtJkc
zTeo0FnJCss$~*yFm998-Xk|x`E-H-{pROA(&XKO@Y$||VNnTVCS8)?533={!L@-m)
z?20_5GTIeKOog>G3i$X+r8X#~<>svCr)u1-o}g#6q(>*mdYL0q59|tWrHZ~Ne0H6f
z<E>{@D*DGF@f~$yj_i^%lqnMrimp&kK010k({_?Ci>??=K3%%PFZsObimc=ds5hZ`
z@|m<qA5W>?bP(gU)fL{z7uljjrz78ND>bP4#1bh6kx#$gwD$Qj?9KIzvb3BmQuWF?
zxOz3rL9PlsQ#*qE@Q&?iec0c*ku;?~IfJP_BQvkY{+#Zc@d0kUzF8j{7U9~u<sxjx
zhiH`zAx@7pJRBqizn@PdLjSNlgtUBE9ztSZc_@2Dm+1i}js9VHhz+nA9+J76@xdYT
zoAn`Y%1)#ZT4DNTd&q;gZ?=cEcUKM|T<I|P^xn5VSN=(L$<dYh!7)59lVQG57Kz;k
zhNovJ%vimbd2(QUbv36!Oj(mJ8O<WIQr%*RbNg1TZol;08Z+}X&)s;}dz}Vx*hJdr
zNrPXG<=#4tBM8+ene}X)VkFPjCz++^&bT5&mHf`Ty?aSRoMDTg4ml8)G_2QJciVb|
zornpvNm}FZR$YQ2UZQ{tbF)U^dh`;8WX7UUz;PLtNdm9Gl_<=OgqzJvPlIiGk+}bo
zi7OqM-5zj)heO^;P7VEll|0g%c{n`5iK!kT7%qhycKGhs)+1F1q+Gvb(PvinOIH70
zrVDrmdYLZ5chCcClD>re__OuNkIR1zFGcrX92p&^q2mQ-M^M-)@BTh?U4+M^4|-4H
zvqKuf1gcgaa$dtP!#`;Fs5HEE?esEW;Ju7w{R5<s^+9`8KA^i|hUjPNL$U#1RL98_
zekB~DiV>n$s}IRWJiHe)0X;%EF%b?V$Jruq#XRs1$`==sTqX~A=Kz}Uk^>LG3I|9z
zLz%DO3G5X$1aDy<^fx9ab!f!X{s;<rKky-)8hGsY!Fwb<n|<gS!SlZlg+$Xs+NU)B
zbfR`t9;KI+SQjsOVF8E{I|#noMIvMJ%v=;O1_x3ZQQ#Ktvq{AGBAD`c!NJ^TM=QT0
zoA!)<lc?aRnY|_m#k))@;Rk1>Yx>CpoMiAv;!v3-C<qPgQ;!FD<ojeS1f2GLPR$QW
z>XflFUH`qx05LqEPhBwxAplIv3z1B{BCrsY&}TVA5xLN(PLVWu^hq>ChD0n11_L9=
zqA(U^X<iDYLeK@#ZC;GbNCce0=#4m}FNy-=IgUj_kO(xMOAC+s2K~~)N37Fob0ny}
zed)?TIR=6OB_)4F5Bms52|OW1u*A}`T-BkVmVU|jiNKeBF)${i{gUc{*qJ~;+GA^u
zgh|4ea?e~m1p-iMVJ~sU6C;uF3}HTtLJvDaf%>IKV+0E&4%AE0M4h#t8F19ET4hA#
z^{bW{^8bg}rhZlY3@%N@Hl>Lm!LRlxs($Mwfl#Y{>w-WyR==e{+@~rmz8JuD1U8o`
zrYqQe%ff?DuzvGViD)sRfV~u7bp%w{Nm9tdt&<=k(^i{7XZh5)B^-!sTNK8rAp9**
z%rHLOSNA|Gr%W3V!t54-(QX|l#jPtO;`IV^jnQr)?6*z@1pM_|HX&FB0p_*`4ifS0
zrRc&%A@6X}+_VxQNU`7ftAk^spB#~ny-b1;3rVE97el=WX7^G&Wgy<+ZIv;XLE`vv
zXH<k1=GGtiQ4kciDB?dhKv@zIB)TXJmxMj&q0)+2(?!UKD8f;@42uX^U3h_%ptu1l
zkn4UDU~mtKJraZvv&J!9Mnp^`zzuUk2)tboiA4z>^+(qRLd61|@gXJ0uNwfNzzgLu
zr-*3bV*y)Uq^wR}<~4*J`>DN!&}6T0BLqq<5Kgij5zc|si9x54gm9h}B^{8TPRayj
zGWI?nnSm3ksO{{ggakxw2jJ*OWVctG5yQV-Ryo9o2Z|{pyVqNNwY&b}8Uj9z*!vz$
z1i$Aw;pg>LVeAV>weg>mncPT>hF=u8q!~-)vgk3S-W8O@sCz#v|6qUzm0yhTeFx@<
zV*CR@mh&6n!J`?*1rwOFsn2IJfirXo$p#))K_(*vV6D;<f(54h-4hoNp>Heg!A-es
znA?KS<r?PPT$V%RSRBIGtwanrr5}V!>Iumai5y<I8A$bTYZOangLr{gz`*GROo6l#
zFO&(4+fAkMn4jW6gFp&Pv@a5ZZ%S~rmdM5UEDBqA;VU4A#tTmYWAegEKr+rkQfA5v
zlEPg;2j*Fu7a#KE(9rZ8pP8DT<1@3SmwU^J9{?P)K!Qfj4unfa&6T|5c4>l{?64?U
zPozXG3RrYuGD^KcR@FkW=FcFBn^4!v&5A$5@7$P?Qa_R2<&`Lp|8mpy!d$XNLO0}^
zEj({@Lq3{U!g_-&WOP>kP=*Y8WtGFiNqF&>GUU8c$bo7epyW6UkZR|ZF&@z9iEf^2
zg(#~<$z;5gC|C0L(O}|qg>f-i&?{{l35APNX^QbBM<XWZtr94)daV*Dv3v^ZVm_p|
z%A$<5J_1P|Gs1n+bb2Gxa#7lrjTr<E_aTNolRa~tDy0(FO`B-t8Y!m|8KYh~)IEZ(
z9adT<ovt>9j>J@#<rdki0ou<z+1%t!6`q&_>y<N&JXx=tY2?y+<3{LQ_lt1|46a&L
z1(+z?F-7KKBC|IN5#UpfS;7K%AVYW&E+!1;Dhgo&S;oF)NspYA@-#cJ-F-`no)Bjx
zMNh1m&>{L2br;B~JO;eekjT7h-?F6h9PlkmI_BzKxDT*xvc$vjQku7KY0~+Gj?xh5
zme-qi?Z*ynq(i%7$kie+jeb2^R+~xm5Ro1~fTZ?S%p5Z2$YOK_(;+*a1<zkfp!Z6e
zMv}cNY1(lv^vZ@qvc7jdRhZDfC`1Y9U?)AC3lw0r@<)NE@0COiSOFJ^I3uvU7brvO
z@!pk0=TNA;3rz?>2VSYw>9}`hSHlnPy?_~}x-fwopbOrA1!h=PK=^U!5xsyJZuF{D
z)Bu54gn<^j@Y}cvIulbP_mZ_nUJTMYq96%zLns_dS%sU;W#uRA#iD#*W8@DJ$;8x+
z*ccEIoic#oa5)Ev)p58m@qy>D2mn^;=%m{gxsuLQ@ATQA5=-KSIHZcl5S%Sux!>tZ
z@g97Ehh!Ccfy58wB)f9Mfr7FK9LH3zfp&gGnX^cG^iI<>L0O`t41NWQL4VN79y+t&
z9Ps{Vfo_gXP&lyjyFxIDHRGL@Oybcj3Ks~~JG^qzVSo=x%1naaL?IoB48U<*p_~BF
zIf4YR9#b!(^_Y6)U*No`Ty|KxgMvFJ4clJX?J#4r_RovZL90FxTG2uJ%5)Bm$Pxf2
zVu_&_@r&GPi6zF7yHpyWAVsAjT-7iGyFyO^uoM)?cVaNH2+~UsO^ad~PDdOkr-O)4
zPf<t-Ka4kp>$HX0(krHwuu_Xeq@zdOavKCV)oOCUxGG#Q78i=lxa&X;V`>zI%4LEn
zlVze_0@HFA&;{_ef<g?k)ch7H#)4|7E{7J8y}XkCf&R59=`sgEm=_8FAjDi=Fyf54
zhrX9EWGs&LB1+kjBz(r%gD_;c99-u<OqxN#XHwrfT=BkyS##HIa9z;?<`@(OFMK%c
z_JkxzHetK_4iJ~3r-xBmGZ%pqcpz1IdmJx8&$%Lv2~X!LV?zkLpyZ@rTy!}84kF=s
zp&tM%&lRssKs^^8!p)`C%j^cG6U(K&gx%-P_{zlhiyCW~=gqa%dk$8<!{v8m5TH9T
z<N!73uKVjAs^#_)RH0{J+yN51<WEejlx{abBzl2107lUnhJ6TY(VbS5v?_YxIv|PD
zT~EuK8(DYajj-!gvF;^gNG~XeJ9n{e%$vJdFI2!yx|jA2OiFj&tAMTa!jnk*pt~+w
zR045VR2=~^T`pUKW;#(Q0ITV)N5RvxU|)_lVK@)f@OufY(+ju)fS#X}j^P4!GtcOQ
z)d62Z6Lput35cU!5Ewuu{iNKvkr{$Zyi=FcnV6`bl;oduhQw8Mzl-V6>0N+(z-M)*
zTJhk)=R)8^DkdpM0>Qeg<OzUcKPeOA&5caJS(lR>ptQ#?q#NHJUxjVEw{t$9@VL%+
z{=(38p@k4<_me_S5g^yeDa4c$&)1z8g2ep&q>wQ{%$;IHUJt|<b|o<ogZPtj<;QPu
z@7A<PfjQe<Wfy2V`=D?sQ<4^}@<&Uf!{H8K=IuAysb#{an~9-CAwzG-Ljpx_a{`uh
zu?E0)9|SUw7~0N_xRb~}tQ4S^J}G1<);BS<kDW3#Ey8M3HQFg3!bh9SY9C+3{NAJ$
z0b@Hw8xB(6YQN>qI0!(#ZI<@yjsueUPU*G9kWff~^db>Jy-on4tk)?4AoiWm@N&{=
zLqK=OZ?s>IETY1HQU;H?<Ex<L>ntSPyepE1nDjb930u!Y_7Jpv9lMMNtHYY{V0EH1
z984$vA*6j?3WVa<O+vi>?Y1GNe_cqx{Xgo`VqJi`>R3CVu0s|Ws0))t2#&l_S)`yY
zVHPr|i<;FAbd@un%b9QTVnkP|1dQk^wSlD;P+T@BUD`(;S+s5lAc|ETN@Zc?hf-;}
zmy(m5@n!OpR>aa0r8=?vM5$LSQBfLLr%F_68cJQ1D#vOV()Jj=g}S$(P-(<tiG?>x
zkId2>R5V$+qg2sOV}{h#C;*aUBNHBV!j>GTG*2*MQ14O2ssU`aQn695#DxsTk|w39
zv+Rkqd4_Dc%b~}ht$Gn4Xe%h$sn^2-U+VR+7%i*GxZVkzgzKGv)f_S0{4e~q>Vymc
zVAU&$^=I^uVu6}^Yatw~o@1<Y6O;o4_Tk_!_Q8q_>bG4hLjATAs*ja<>WRtfJ@pP{
zg`aw>vJ4O(vxf==)q^(!u=FNY09L)58Gu!9Yg8~gzW5}6smxJ5+p`c-z3W*ksowsq
zr{rN5Weuj3Jk<r5UA;I!S1%6G)eB}n)_{@)gC(NM%E3BPX#`=JsWOtF6jd5%Ake5+
z1#1f^><018fGV17SQraNodYEH!Pstg;m~e%A~R{$eh6`aGG1keVx_M#R<Rsd8MF{~
zRW>h#UG0W3Rvs(s8LE?&fsF;s(g4Q-XE4xZ^|CzYnE~Btr;weGwbW<{M6tCp6(R&{
zGbgfMTbUeL)GbYtEc#X!OBRMpqh<~aa-djhR+yt{lr`wec*;6;vacRl$*v5rEOu8`
zS{B4BOKz6TD^o9u>h1Pml-}En#u=1VW@VP|E7LPe{J}hZfRtus-AJ@!(8|qXf@KJ2
z!9kkJ50oTyrQEY@VcFYR+OTZ$sD4;xdlX1KXxs;>!`#nr)5(D&|E7n-^=*1MoDW45
zb=<rWtLS5SD_9h=JQ^$;SzZs6mOSJcVfo4Oo3KP>`BqrQvivV7bh-IxPz|&EI4qc1
zt{#S1l{+ZQZkE63U{%iYDzS8DdYxF>v%FFasVct}VyX`Lwpc{8ykDp@S`IRnA}uEx
ztChmjc7T+Nro-^DukzNdz^G*9UN@EQy4=u@k^MU8o;*0VLaMknwqmNdHsq3Iq1U6_
zmaGO_u1!{qmG=`hW#t}K)mgYu50LuU+^j5LTb|fe-IlJ}m#W{&n~MUu$L8^672Wa*
zv(m0B3n**xmT#HWdf|W0u|XE(r0z({q#L_uVc>Fevu<#?!c|;2edVk^T)uSHCw4)Z
zql9t!<5A`KD4#t`A(va<foWB)|16(e!2v9=i~xe;tEw<plmW^#Z;=Qr<(#1kEc{%N
z3@8qLY~c=!Im=4(Us+{(Y!MQyLS11Lj4q2ni{nextb>rd)fr!<=!{kVx`H=Q9UB22
zUn-z|Y*8SrvR#oPEW=&VB&_CLK`1KsU6CrR30~1GuJ9+`^Q<#oVKFF1er&Nb4BJw8
zjb}Bh3cz7JRz>NcFghc7f?cS2q-Y-&Sa$&~u?TyG2(d^z!-x(Qa<4EW)_P}X605<x
z%Aqi%sv?|FR{q$+pjdgnBBfZJUV&6BU|+#j{KcapvK%#6Dr(D7P^BWf9K}*9{L4`a
z<*4|u;7i4iIZBu?z-%!)qm{a*39+aefsRV170l*Fv5;UZ5{kEw12EgGeBL7E(!`In
zvqJ7Xi+NN~9wMQ($USdBwyE&Gkmhp_0i?uNn4qJWM#U0hFCAOJp#!}t0}@xu5zvUy
zHN`w~cwO<1$BRcm#YB2z*d}d>-Wa#3I`<8hb_QS`I-x2`GY+<MkK}ZKTOr&tD2&^L
zXCRNzjN62+$#XZOO1&{;b8?1LQLCIGpb9E*b&(Lb%2{4p<f~_i2Smq$Fc?33fRH@U
zdCtHs1>(l7c^ad2LAgOe&NVOS3j2*)eC(mYyy+1?yeP;uMU3$QQU<{?zBAO9U=&}R
zPSYaenW+#n<T-WkjHaIIG!YBVTa{0R3a^d_Mg&vCWRj1RBxzIkJ&=37omPaqV!gdH
z)|&z0>$R6@Ns1VcXJrhJuWG(e6?V=CEd$f(qR+_n1C)90(d~SKR|Gtt?Ff?xCBxZI
zEuKg2vZC!_R;Yk{_s)p@Y$;$Lb9O|8SL8p9DU};Qqm0rAXu-+!0vdfX```d25>1q$
zKoeADF}M$@;L&2P1P4Aiu&L1xrAu)1kRIh+&{9~58L&SdmApYSX6AM{ayu*cW7$`c
z9Fi^Y%ys3#R#-_UG%Qyd3T@bxszU2IpHfGX#+CyEKS!m>&<|6&H15pMF@5Rb1a-c9
zrRY#dnW6*mN?&*f$og@lh9WQM04aV!$wLm5t4c8Pv^Od%$q_rnv?U*iGKoiY&IcHA
zmFeWn>A(2;cjWLZW6Bv`RcTcY5Ip5wIkWFCzSEug_R7`r!R)h9)6DcU9kYY!XZfR!
zu}L(B=h&n<3?va%^4TI~-k79=`Rz(!^TBL0-TGsYSxxgE=%%A)rJOUp&Y4cG6g+44
z_$3%h2O?MH@-0e;6x02D0O(~(F&#+0L4x3sq}VgFRv$@e$~1JQgii?sB%axcN02i0
zQ@1iqtCi>INOh&5E-9JjNOO;mJ$2Ftb24>&Ftb}Jn2QoAn1h3ZuvcoQPiA1!?!G8(
zY$>9PkfTkz$ZBUUrK}*%EbXZam08+KS9KV0E1h*wk}(~vv1h|Nv$B;k>!?{@X|+C)
z#im?bpFq^Ej9m{KaOLzmKEbSChfTQBg8e<BEpOPBZ!HB*`PN83cBEVD#WIoSrX1$O
zVMMM(XIF}~bg_whMd{NXT&GDt+qr3&h3!hP);XXAYuy@H-b(gflu$pJ5bnycE=gdH
zb%_F!tX+J-Z8SDnn8;TzSwPO*C|Q7d!#sG0O`C3)BT31@w)IK|N;8?)7exa*TKW1u
zQOU8g`W*p#9b<<^B}@PZxLe@{ICf|!IL;#7g+1WR!4^Ehq9ojd^bH&ZogV!~2xCA2
zA$Xo2g_YniwHKa(&u7D1a6||Kl;Hp=zdWl8zKmxnleFb+bkv#<K*SNGgqeU`T;~Qb
z;mp_;2!-dN3ZM!Q;{9G|7LKF15HFmG-SS%bMWhGH1Uvvop=&sB><fXz5y2>sjzvf=
z*w!hzpb{4j&w<cD79sf{?exM~BcF-`HLp8SX#4^Qgm6h5v5|#c;>;r#yvd@(cnE=#
zKa}_^_tq^2Bq)_d3H}Ie#gTq4M3(hKNT(!bOHgt|x;dDUE{lIqp1a^-@`rLnW9ycP
zF=Oi%I4xuQRwBmG@P7E^LbO?b03}+eH+~UsM>Yo(_9*b2MM;IDOEjQt3xa1+a&&F$
z6{Bm_CkJP;2gScjsk{J0(IpfF+mU_XBG}HkbxL8UIeAgW243XQv<l#8QLa%CNDg1m
z29vZ%2?V7F$%SK8SW6Bquke^0nfb8s9!Uvi%B1Vi77P5zQND!WP^+B-mU-5h(l3bX
zMM*HIp-#bF;Z*r`Z8%nb0dl;+t{l#(Ld05>gx=~~w;X@pdZjQ3eQS|&0&sIILV|A*
z!fR22<!$Se<EPix2{51<tA5=ZnwTTLw-Co1j<P}}Ta-X9iR!bfmDp%{P#_|>pwB!W
z4hf9r#3~?g+7YBgMyq2WZwjkZfQWZ`O<aVxqxB{s4~`A(%`ZaS$zp?0WC6wn;dwSp
zxkYJ%uyY3}u|8H8L_yq9R03ZJ_;%46MhHAmQlqh2b^_ehvIF0)7M=KZT6E&usk+@F
z#V!)EpWlEf67rwJ2U+NVLGgQs5cI5!Q!s;zkV|`Ry^<3rTWc_aGF+4;8Om}F!WxPo
z5f>#kUfK8v5OLB9apwp&uti6pcL6dwQ6vP~7?c=}HvMe`e#{BtVl8tV{Hz5b>4+aM
zn8`(1Y&iu7>%^uIUZvxOUYM2+e{JDjdg50I8S@B23`d$C-u{KL=_o5yIGhgH3qf@*
zLSh^V&=aH$^wSXpU%;Ra%fq4!v=dwODSovLYLqSV38?XcD_xYt9;M$Q!8eYAJtb*_
zMs=7(3O?1dZc+iPilE}Xi<028x}|TR-V@BV2y%kK7Y<O^T*wAoS?O@1=#76jV9kz?
zmT9nYN)&!ANE^nj17)OeaEoHat9X$Yo-Rp+x$E%V7cTEk=^E}rqh(#V4~jSwV6?&r
z-YG+03URq_!f_Sp+U6b-B-G-aQWFiSVu7inDAJDZz9A=Pi>A^4^7WsNwa?G@ufC^v
zwecpuPq*{B{e8H8{pbJq^)Fxcb-w>6|L=eO`ToLyXy%drGhbO})^MOH0#N5ltEUOo
zkR|g%)~(+}&HE}x{HhhqfGAW#Y8A+eg1xQNWzkusFySh$+?`ff4ye}=W!B?EEH_1z
z%LFV5+mAg}og|D_t-xhjL!t1|k;vD#3Pm};qZ`4LA6gf_05Ef!LJD44dnVi-N~~^=
zoQ2H&gq5t4Q`g0k(PW%cM_39Cco}LH&W52pEEf`h&I|&y-nt9~7I$qrRcextE^X8W
zYY!hODN8=?yZKv&ygv&#;rwx(_Ppo*r=kR?rG{cyKlNg&dI({zTNEn?M4p+3W9pS&
z-ZdJdJ!6^NLnOK)U|}DzrYOUf73VFO{;<NTg%AN=ajWbenyo1a%JLizJjaxUEb144
zKLn_PHLdOVxv?+ChT$D2_ANvz!K~t)av1RN`>67Nc>Uc<q7f2_N>oo}p;vMr!h03C
z14q7M!abvm8L<UVAfwjc$wOE``mV|iRi;Y^*4o2I)rm(SPhQLi1;mb&oj;L|@vC$|
z4`?c$_M48kE+>i=!KBY`JI?z<`hMnv??WDc^F@knQ%6$nZ#%O54W#?0EU+c-zv;+r
zajN5#uzlAN<+{0hex?s?-%r2mh;4U0?5K@6zU|0z&bc{%%4e?K`kQXt(;eMJc)sb@
z@A0woe`c`O$64^3jyy6tJBspr+Y#~EJXwB*5%}}0`AtV0NeFHExgApD+m7wz$@Mdy
z*gD33^XE9|M*Mj;+HcpZvC!=MB>c&YJ)Dbw-T~^7y)}lPQkE><uYcYF=)yc*e=1|V
z&fDK~<grYtFUq%4A9cNSdjHHCRoiL)n@)M;YmjI^-*vK##pAv3Gl0H6E{flD!*$~5
zMuI#Jf8GstI9xibAGRkczwOA|s;MI>_qQFlW2P;EGPqWB$^E8V9c$T5gy*|%tRj&Y
z=1-xF>jwQzH`ZRd(M=bxf7`8p+{Qnpz198v+hOLPO?3oC@eaQo=yu!xEZ}Wk|G(iT
zm4uVs3Y`6$ZgkW^llWO^w$d$r(~&BOt0O4${I(+kxT&f9RCV0aUH-hIR2)}FP@eO<
zj_vea6Z)weQmWB!x<P@;fUBRIMm4_c*87K=^)mo?J{7OubezIUVn=Fh{o9U{c{tp-
z?dl(t-*vpsLI6QWf_r>>R4f}yX^B6>{IqM0zv(oYRE1929_M$R`YrwQ=W_jQ+UTEm
zaAPP=bg&56_^tzrmP4ogsc;D?xxeW~Rd}!)v$X7+ZjMZ6Sd4#0xZelt*>Ad~o^21i
zQSlz%cI$0d#-X3>+WGGl!sliX`A;eJetx%B4i_&q{hyn2p1S{UI`WAy*pZaWzU@fI
z9bOVY<6Zjsw)jm)K0%r~l5&6Bk#=3YRMrb*eo%hfvCCM;j(qg=kN5I(t_Sn`nfyMR
zuX{b5huf+Z|F3;7lfwK_It&)2oDNCp<>JfAd5?TyXe)pUp-0O)MhiSC3W2z88Xy&F
z2X98Z>Dxxp_jW(q_>#hh5uGAOyLSgg*qH9kLlG@`C!*EpsY#QUiYD(QP6%cF?(#kr
zg+G%PxXt^Nrr&n&E~vES?H;JG|1oz*1O_|<=B3?bh1p14BUB5#6}f`Iu68SOr6_2n
zY4ldK0(@BQHt{ja3Et(9PTzmK%lC--f;aK&M7hfQh>C+(c^^@6@On00EeW~=Q?OCU
zhLE4@-WV0aa$Uu#5RFU5sS8B`T7|ITzuGm6Q^MnU$%#nJ9#CTVs>e*vBe8#yvR3UX
zH#5qWT@`KsT@-F@xJHBHSKnNtBcY2loaAN`r=UPzOm#Zob8VLbkS><yQ=Iw5N_-4N
zyjXSb+&Y0-XY~r0Co&2Ei$HY0b@VD24PN6ng{?CS4I-%-Zss;?XJ#<zQbWi&lun+t
zJ5djQDmXd(*=^3vpB-{I=jP82K23QJQCfM{hRu==ZH}!|uxXa(5M|{n@(ghGjge<q
z@-{1!8(#f3%XbK~&n(|zmSdjfJ9IFD8OaXWA(C1CO^8Run*Gtf2{BMn*yD?VBvm=q
zQF@@N%QE^z1!x(e(wypJT$sUA?^~~6YQ@K(3h+mGObD9tsB!NeTT$H=RufG0x*kvl
z7^Qg`iPMy&>?yg;E6DQttO3jjpQ;k<5bmlZjKH8OH+&>%eM)8;M~zFBEoQ_~RW@D`
zNvp+3Da7fiJTfDgs)Dj-Es83#><II0N`!UfEu&U51FCWc6Rp_$s`c!d`&{Lq8I+av
zqMd~_s-W~TQU>oU{)J}Cihs#au%`4-p8(sb;?|DT>?(iFAhRlw?WhG(WwbpryxSH4
zgYdPg$L*+Qs&d_q!=fsBGbWB@zmFsZJ1go1fvi<f-0}En3VVTnNM*^7jN*It+T{+|
zy{d1%V*XkyhX*Uw%ljS3eaBWv-Qm}%V(Sbyta9uTk@(zO&32zao{qZiAAyWj`<=m#
zO*x0CI@2n{5QpGVh2|r$^2t9^uQ(%G-+IM*s;GSgY>vjl_XkKhp0;&McIgC|tXI!C
zsL68m>E%9>l;g3jR}RRk*AUS3OM$Abom-bU;@eqWVl4J--l-UiDLM`@v9csFZnoK7
zLfYYwytiJ#9J{Mmh*CwxAY`{8D&}~}Hx_{23IvXW&lDRs;qNuY#!dK|k;-?x5Kp|o
z#;a4B!*nrZEvP^!*O!tPIb2qfw>lYcm6(!D5&pcO)3X&4YYL-)*;QccNs7-(HAQKx
zrXU%FWj9r}WaxH7Ze#?k|G{lHAoy0%{1AMT_JneA0T7SvoF(N5BA<UVF&+fsL(EOl
zny6>DC`?coc&iwN5dq1q()3`*59IvhIAWAr#^V4+b~%Ir0_2;Ecraxlm{n<b2w`3j
z|8SAT!=S0=K{$b8MyKv0lrIb;)XATTDXHc{_<7gbo^*z-ABwsLWH{uo66yxz@YDen
zMI2Z8gi0%ko2yj{9co1`N@IRXaIVth5HQV}4@nu(X7m#Rs9S~bpp0e|o505{TI9ir
z&nWaGOMD(EXOV=F<u07Q>|~PE5_q>4g*-T;^`1&(5<TEiWt8Do*9)H}rA1*%(u41u
zXoWvCYJ+^_A4LHX<R8WIF9LJ0@+7i{asePS%OIcwq&9+r2?93E9))WnUy3D9k`g|o
zN(}_2mQ@fC5VRJBsZZ%edYI+`!@E_gAmO3xQS26qT`!+U<&ot8p=~23+$sbJn(r#w
z!a&u`Sql<bK62uf1O^}C6KNiRYKr185A)<=Pc9NUzJ_2G6a*M8E0YEwmKLQl_C^f<
z)C&lR<W@02@DkWVs0XAEt{9R^IgH=Q$~Y-$dB9u61p#uX94^dwv|CCi)MvXZaU9|0
zQ4a_MI`K8Wo&1y!h*F&ju)#a}It0KI-rEOxo+&xE7PyC-tjr&s&LycKox*=p4}sOu
zD(0x)_+6=^0hMF7cK&Bb$H7i9V!fT9yrVKz5<>iLy_*r&ZU{3xUI5I=s#y5e1#W4B
z10Tn3Eiv$L456OLuZ?M4G;Klcw+j(|J-mY#p@vp_$?&DnOyb(uCDT{O_PB&WfXH|&
zGYO2FcIhri*qS5Doq;#0q1i>FSWh?Pb)hj-Q!U%EjMuCz<g|!drTxM0X{zJqh^Dv7
z`|BNJs|4%LK(7*_hOw0x<$k$JirSBCWAG4zHwDcco9+(4#4HL|-Y_=B4gwX%E@9a)
zvDzwq5HAv|>_LFQ*rkI5(P(y=Ualy+VV6#herCzQoM4uZcoWbVQH2nB?$|@u2>_1v
zV0wiGkWUvY(+z5g*whgN*cO`=P})*YwJG^Rm{-(vd`JlvOvx8Q^igjze<;rln>u1z
zzBa53Hi*HuDg88GB8$L0U5lA3TrNBs@hdtx0nZWjVe?BUj1$FcV}OUFdJb#ez63>4
zp@RWeu^2R@9~pMipx8$wO0a$qVk3u&lEbe*#*q=NqI$sUx^=nqo1D{?b&oOUyjX{x
zdx7s^qjrqp79H9#cotYC&EZ*KLpm2K7on2$0g~a5AV>(HXW8nP;5-mjlY|_9#w!K{
zNHV1WIXal2H$en9M(J)0FYHNHX?BKswH0AWR20@8e+fB-70Z*7Gf-%~Vbf)~^d#g2
zsK}dP0t)2Kp!+XYe1C=CEf(Qa_LiMLl0b>VjvfU(lTkU#MPI-(u?WoEI~<C?IqrZn
z)jM-V=%2XRDwXeyyH5zeerCRhDN-z8HR3y4;9W3E|C}Gug>X)ML`5)&qG3W<1!|88
zJk?P&%>+J9;2#6-=^=0+6ND*&GfZft#27N6jV20_2}U&iphr-M7}POEogRqfH!q;2
zjxX&%OL3H&pfDFHf2ePNls}}~;=}>2Dh7T63c_Uf><HaAr%t&j$-)K<DjeKSV^|Mf
zDH?KtR3-aNKMIw_jTl-uU<w2hl?e^H-$BGID||;_YMBxXiMwS5==eZiSE}Jb0Ix+N
zIM<98fw{Qa1zCpGR)|wiUH=FYgS4^S{Q+ALU0s-psoH0BG(HT?L8VaMlxPvn3qjpo
z@X8O=<-|io6peL-fj^mZWxayOQwv-a1hAsOq$!bc#g4=x7vA9m)JW^X1AfBzv<QeL
zhN9dB<9k1tj!=7V$VQ)Vqy0$)@{K!O>5v_jH?0e!ENccBw7?@Nxh8ywbyWSdjt6;1
zhJbD0g&C<PMB5wC4W=|oB7H0h=KvjYhato~e}N)Af&}h(H2A9>5&T`F#lDu|nLr*0
zv`l8DLMT%-krk~sai(F`!h1y;j`c>INBfaK!Vhu%3v`g{-_S}H2*;HbcNdA^mRx=9
z*o&*rT#}wSZAN={ht6-^G{cMHpgjz?ymjs2EB_tSgG+c(2HF{+-uX-+u!nW+Y3TS?
zFobYGTHz4VPiQQ1*3-*p1x$Dibz(3$j{U})t*1w95ukq(%fp(`>n~^yO(648xY`P-
z5c>L}z@O9MJhdi3_N$>2XW5X@Ary7^)vVwPQ#C(=gjpJT6<{i~|3<)62t+Hu)Kh(k
z)(I%uAmz`%?XzM~i4dFu(U`hJ)Z0Y?GzhaZO#TC)=Pm-|3VxHI;CC){0$vlqJr;!s
zyA!<xnu-J+D=fr`yFplpM~BzJkd52nPp~FXZm9Z3M@5HUz?87ti7a9IgY2P`2<CfJ
zR&Sttgaimg6_$7_{KN(Cv6>u6Qy223sS9LewrG(j#&PK=19C`(9CsMD7lp9Hr;?2z
zGWnRvABriCN1Y%u1Lp%nI2VCm0-J#G@unPTW)Ep2!1oAB&Tvo`q@RpSy`c3iQpkdU
zSjSW^j&7<KMmO1qK$?F{l>xGi30U$?iPpuRU<WMWfCtp%M0%4x28IXCHn5>@U|=<>
z01kKcAaFRPOUT@V(xnp}wsmU;m6j;%)&wjIzz~z`ig+Q5!tu7`5;J@cV!{UrOJwRr
z{BvV3W+Cy!F|=?-39EbXz|pM$oO^30vvhde=&Ep-8BLxvLh3IHW)PrRraW_k@>}Ec
zoH!wi!ov<=AtpRdRsgW38wOY*CWOw8s7*7$-*h|<f`qT-rDME=0RC^vbnigzH@f-~
z4umNa*~!(3l>=OzIMJ>?DOlc_>m^)p@7c;#LK@GaaE>@%1Si@72X9sdUI0&Lru#3$
zLyeH5ga%mzR!cb52ZmW-gP5sU3N5t;fN_AJuQt{e0Ouww(@q3)Q`Ub6*!ZHbh6xtj
zsz3?W+p0bZ%tD!9(xLL2>7qq7NwZ4P#KXc=Yh*BoMCCL3$Y!oIq8m*314Q>Qp{f$y
zBPeLk99WeVNi&3SS35#tP43!785nH}Lx(P5b;Ea4F9<!9zo1}zrfy^ubjwJTS*?6w
z3N9hwJYq^aCAlqVb)ZTHB?n9hXHzb1huUMN+9QpbL;_%MOyZGtk=jZA&;ViLTWkmS
zlmJLGph+P?(1Mu)Tmq~Ep9a%`4r&6fU6lOcWI4b(HbT!pOEZDN1FRz`m}3`filWS?
zj(lJ%sNO}AWMceHl35grCYRu|Ma7}SyBVd7gj4d8@{VH|@(v2cg*(6=$_rN!2(~-r
zuD{83#hwS{04W)xtwMw82ZgMN5z<^*?VKW39w5S>l!=c(7Saaz(dOtW8z+u<?MIrE
zs@Lfst*&zb-#uIH@*;u%G4!+cCfj5+CXcL7qwzM&tYKuy*9JWCopMW7kYxMZb&RD_
z(l8m8sk?M&kut@|%*&;nW+#MgOyb1E`cDd{h-~C%Xp$+&fy96W=8c2{|10b4;jl-m
z<4$4OJMOQWPW$$7yHwpfZkMWi*R~s_G1u~gk_xk_=v`fc$bo<A66~0t?m!Ukx&u4w
zHvW1Iw!5yu_|nbo!>cqf81k|``JFxO8vw9%&Nmu%bQioSAFW&KiR+^wlfEt;2Cmme
zK=67=K7-dO=0}ot!DcXf2{wb-H=&JS_Dy8(!D~n&32$ymAY$1!=|V93CQ5MC9*`cI
za7udaKZwfx2T{43q@d!~H!(om`o8L$s9+!^DlvFsuWoC4m0V!TSII?A8R$l#spYqU
zn{<@&){yZ~I$uMIfEin<zhc6OXE&2Yq+O*Nr|e&)8Dr8{DaM%MRf=%fwHj?N3VCa=
zy_kwQU!@0QhNT8`IvpVrilvLpvB6Z`cPsULe1dOm)p>@G)G|0P%FMRyL9v3>*@H9T
z6B|{ZFFvqU_4$HFrXDj5;k<h9wE3tPrZV}$7PtWoE_rUr+QN5NL$GT-%^I?l>iO0X
zlZrRq0TR36h(UB|y%igrr1hSR+R%RU6`DUZ^he-5&@@fCU=0|Y)|$qMo!Jx?(GU=6
zf+b_rdc3sJW+yNiLF+Od9E@5o^THyq7Y7J~YwOXn?4Ux>89JDT5Dpi9x28(a^JFg$
z_EettK$~4A%eNy6MOGNrE;m8CvA%g(b65i%CZ7YOlvkB{Mm2R~%xsgTLxr7X>2Pd5
zpr%?=p=Vh;Tmziy1PO&Vcu^3I|0j?l8cxk3&HqjHs)6BJcC9w}9+UB_rMKFIipN^?
zrfA^?6xV&sgPm@Oma_6ye0tF6tK!oGM&F^~;NWS4p{;GWdXcG}y*M1osLDu>u1>MW
zZy81WV%ag<ppdFaG@Qw%kn5Egp1p)a*}`>fZHhgnP8`pvPGrxCK3prl=Vat<GR#O>
z2sf}PXuKhNyzI$MW|=F4KN_quy0D$c5^raeGcL<^a~?{(e2?a^`$_9Ub<47$HwN@I
zX-huY34-l_05cXAYChD7AEynNrV(bTgd+eS&)57>&Vt6^J2@2Il&^9)G}>tBl4uOO
zYce4<r{Cz*r<=ST{51VWx|O`CSLz+<i!Db>b2<)ba*L#u@bKt<fuj{3o#c5)2z@?G
zS}CtkgBP_tM~#M?Zba#M%HISAGkmVo%-I+T*L5#svT}I3a*~L9JLn5*oz5d#iyNGv
z;ZZ{;`if|lZZz)nt{afn9h4PoS$EBpS<>K_G!-XXl;ng*3kOWN7171vorG|7dXRO1
zb$XCppXqW}^1OnzM?kU6WU)T<CHj?zz6C=bhJ6Gn9j@qN;L6Z^fK3u9JgrkURD-^s
zoS~}BGi0ozq<p7v=zM7u4%LEh6pl+bSc6}YRoff=iiH(Mx1wGEj1;4*{0I`g=ipR>
zn^~%PgWXS1!Ht1psA|~KmvsbzbHD?oOJ)8AB#UV;+YE4^^ox;)4L8R=1>7l$257ht
zD`J4@DiL)6Wg7~Q2_?BTF7|^t@GOwt+;A9BB|aKdJ#%ToC|G5F>UUx4L*g3JRZJB(
zn*kqi1#w^(LsvH<1~e%Ars|)~7(FCS67Q44lxWxRvNnQMGhfA2=Cm2(hnju|T1^&I
zJwOUxs19pGq?+ovwv1GB?0i7DR-{ccAe~h>PGqZ$jM?FjK!;Tn&!XfEv`wuuu7_!G
zk)v{EI1mm`s{o-qJdvVes$h&174xaLxP|9f)s>sU+N&bXD<OnYP~<Q}iY^BKHe*Z?
z<roE^OknB(Gr}0Ghm?%B;=E4<dVyOCF_T!IloDAiPKt@1swYFP^TVj`WUl-7#A8QT
z7?Es(C^Q1bWgHvt*7IV39EXMjVdx?S60D6=LxYk5?deET#wqd-7~q#|JE4XS$^40j
zks|&U1tFHY6Hmr%(nq-{8RDla@C5FXUOgFvmP+ISLQX&uf5N4pP)DYxFdDL<a+AU(
zk4R9-Aj|l70!d0g2Li1PU1lfV%|p8PiI}kn@Wd1u)+nX<WL%@Jrjv1vOo?tM9f(6$
zPu4WFApt+nXaS}0$tz{hhP0APk_Q(VWwd;b8?9sk?00`eKFmxLQ%wqc=xP|ZJ~I^h
z%RhqNhzc63J@FU(T`b158XDGPHnbw*xN&5;|B;d%?GaE#z*c-#Otpdv3{Vy}U0;OZ
zeln6Oa6!+c0Qix?UkRObfRxeMTm?g=C{tw>qb*WN@Wu$Ssqzbpl=0d;Rt#lQZSq(#
zU}Bgu@E0Zdbo1OZRFGPvfp%~Tiv7F2BFE#u^3<O~Ii=Zg3hZ-{LKG*Rw+5gq6V!mw
z7I~fG0aF>2Ov79gyG}6y%A%_AM7GJ36!HL)k$Le4NGqm3zvB_DpYwt-<Z2ozlNKZe
zj7Ynr<t|c=f^i-OtX&iQgVDmNibX`EGS(JIQp-#RuGacc4vjerh@P>VDGR*f?1tsZ
zuA$*GWnqfZFrr<&)a+);LJ8Z6gpY^g%2VOu)6@WcURfo^u(pfON&^f#vr~?j(pw^h
zC5Llm3rtF6`O1PZ*i{Jx_TsM{l}TejjZwBuj_OGYq!N%Rm9=AOe!W%3*8oaFmL(<A
zcqB?d2T=|YdB!xO<Hf9)4G+^2pMzL=NeJ=3n<ftNzdIqF4Zs+S#INJlx|t_w0GhCy
z51n6NWb=onlDD?6#Wbe)44?a*FOCo@ZtfSeagIzat53&oT>7*N0T2Soh(1-hTl*o8
zcGbeOEa72-__0eVb7(PLj_kxc?NK;B_iG%<_z`IHk7<f{+oL|<+WnQ@r|g`{05lq;
zl_tnDCDRC*uTyD;2D}wyBId~8+<kNqWF}9gH1f!+G)SiMFjX?7>Wn6a26zd37!hwk
zlQ7{n#R0sfXyS-Iwmi;A{)zF@C}oqGr_fY!<X3*EG4AlWv~y;qo?=Q<nWy}bOzV^!
zOzco4v>v>oD(Tf|K7Y8=iQjN)rxUH=)U`2*`Ev@c8+T^Ir}Gg_1?i=%q$U`DBNPKO
z29lItYMLbS&(9{_ApiWNk;DkIkZRunQhp5x-xJU^XBTruriJra#GI&h($0K@((&BX
zTVJ7tTtk{|5;85kq=p&jB{iP=x~W8}5g_3#Dd|cCr<8OgIZH}<WKt`rz)+m5sYZkm
z4dE;y0T{xm^MYUq=goH}l(BfUpcfE4&j;*7O@Q+e&ryHC=z2N~HQMq`6@Q`^*DDpo
zHCWThKLMd*I{7E!ft%UZErA1ch#)4kS=+khhpAIe02Yu>$WphiMLO~6u0=Y5Sm0V(
z;Myco1Aiz#?OV6}^w_#3U;>}XmIdbWDGt>r;gJ{kdNy|CiKL9grbtfx0i%4tCRz9u
zK{^2~os&cWYhxJIA|wQa&KY=QjwUZMp98|&U`Ah)gPxCwX7|=9+3-lah2vzA*bQKA
z@@?{Y(i&~UOcn&($N^GfxSU(J#Bi~#+uF=>_!)5VH}I1;DU3_(f#XWCuY7+s#m~n3
zEPkYKy;490*J6W!GJWfocsIUvOZ*n!dgTEschq_@CV<OOHz0q>Cu0EGP<bW;(8f`C
zHj%}+A>Qz{TBtZi=nXkRBCRn7coo}m9JZ1SBFsoKh%i%<k>_I}{V*9)Xh2514*3;~
zm>rF=sfM88##&p(vV+7T0_jY2BK1l;F!m5IJp_3al+$)xq(zEzK=~*}oDZe2q?w@*
zm@F$bd<muLkZq!{oE9a~t(>j+QR$Qm1w@8(8%TdnKq(_ANUtL#4`@MB8Bs#IG?CE?
z*9x~OTyc$AQnbVrK9*(3bRlSk`6dPq-&Wul6PF7o@W>WUUzmVem)=3}kxt}68<`0v
zM6k3a`MsfrMe^v_k;O8dl*nUI+2gr)a55G9@Hz;Hl~yMKvC>R(oF*DTrQwG*Ff|**
zNz=<=5Gk!wAOV!7x2SMWgzbh*R{7PEGUR&8cH+VDH)C~NX~#ye6t9H`Y?{}?;|h`i
zl@`KqCvt*k_$1K<>9UK0F7T5!0tOpFS7ZpyjM^h8SVO|F$n05|-dg!^x6%#!lD)GH
z#jpQK!HwuM+V<t_)3z^%EDV|u5~X|1K&4d{Wy$vFTd&~V=-YUMcf+^wrm{9%wP8Y9
zl;>?R6dlr@XI)eBIMasPP%UOlWSJ&|UnCO8P^9i5wK$>)PX12vMWKvga#qkpwv#jT
z_ZSdr7=7`Q;hGT|!7E(gtkQri<~FtU;NosH{B7-9pAKbvMU)gP64=qyDPbM8_0|NZ
z?qCPx+-$maV2N*2TTc{jJ)r5dslzsfwgIYa9mp{7w<$$U6e((`Yu=_*cL#VY>nI;Z
zk!1&t{Y9ZvUBt~iZEIg*CEREcs8j^SG9@K}HSdizv1n6Q>qg=21<asUcEOEOyb0LS
z^P?g8K}2N4c<IZr(wA*)iG{ngKS^jCSK<xbuC}oygh8;Y^wk75>qpzQvIKWM)Et^x
z?v%oeEy~o`i7Q(t-Nem$)fq*o**c>@5k9bfND#vHLjot(_shVuQ66;*R#ojFpM}U=
zUkjE$+-z*?63Z}<Kze@eozRL~&^n*CeLE?A<6+3q(>ER_r5-uBN7~~XTaz-jNrVWO
zv1FrMBhRWp*?s25<!p0~v5%g)u`?;x#?F{sE5nFGC4a7s6G@>~>M%V#GJk?{wCCP<
zvyP1C*;o_z-Scd$StIM``PteTwZ;%Q;~(qaPumzpO6{igZ~YV|0k_Ilp$t2$myJV|
zeLJoHT9obdY$GUjc=i~zix+v+EXt#Ac??m}VR?itLLDMA1~|8aV|o^v+z!~FaPJ*F
zbNhL1lV4o!=e?aA$;5k`d$R1VyFDvxZg*3R=J~vfqDtp>6|GO(x!uZ9venMIjAFu_
zaD%)%7oj=@Z*054G6s3o8r|;lGb@yCclncLP3tbdvaIRUB!Uy>R1ks<f`v4|)Ah17
zc-Ckw9WJ<FW7FX*>#L4Zq>>AB(}{A<b62HCmV+&&DB{SwT_0Lpw@WI~;z74-)9PaJ
ztu8QDcD+kFA52+h17~elJ`SCQT<dXoW){w_*&Zya@{;!3+qr4tYZJ6{)5BxV%{Dze
z7Mh7eFR11#uL%D=OnFByYWJC&B-MQ_XawHMx!#pv%r`_=gsjCc`u6bZ&sIYw-f#Km
zEKHXI)>}O&P%E6Fv3M4Cg}oB(r!zb>!F__IZER26IDr({X@IF@GFeiBi8M(aeB<^u
zw_Z7g3$3A)wwE5#OnZCrvAq_L-9sGOy>&^RNt=B?>3gfPd#Ebjo_gY<tT<y5X*%c%
zK%{wLQTRSeeszS29U!gWQDh*iJaxtaG7cb;5y9;&JI)s^+&8_`3^`a=yjPFhY=Yh}
z0Hbz=<`ISJ=)(A5ctKb29SlLNC;5`Cs4K3{#*7xdo`^2)ikYKTsw+y4maC4CING*W
z`=+S_Ma28Hb;`kA>J&q}w(lh4ZgshiXmT>R|27LkUSyjA0T<b3K!`gk%?Gp-#;R`i
zgDeK_=hi2fBuJhWKG6l@6K2d<LdAO_qN2N1j~t1Y7({7rZ(ElfNUO2s@$Y@>lOriX
zc%pU5z8gPLBJkw(<t_om!R=n1h7z)~9Sh@Q>k={@;aN09$J&%R0ru-&=7gEIYWKNW
zy+cl1VUV<zcVSu4qTUs3MXP&v{%o>9`+u$y&VtyYS-;E39}6Lk4Y<f%@ltRf1cgr|
z_!#;)w{G#-p$lU+<@`r0zsh*1j9fW_P#%={vVxy1U$B8duz678!)@yocB?+han%Fr
zpj<WiW%{ge;+DArX(N58E`k9xyDOAwQI@O?-+ILw3%hQ4q+*SS0&K%c72~DufY)>%
zB^i!MmSp@=_4EkRTBdPrf0JXTWl1Ae3<F18f`C}VUUm%)nXULr2?GxKQNqB{Zo+^=
zeo}b=M0%ek3%Pq1g-eS=9A=IqNx>T0IpA#U)3mSyUt%yEW0U&iF>%<O(c~)OG*<Nr
zMk)o=%0nM(eyH45F!A;2XvR`csgV=UjVYreytxF1dCBA3=KwGkox)vZJQiiG(NuT?
zoXdUc^$WPlMM>*PI;eY@Mo_$<PgTi<qr1<N7bwOROht=FpYo@BmayXDL#ds5@r7HS
zfIivI^(g-oy!!+OdPP7$vP$oYD^<x$Hwr3Sbkw}an1P%Du|o}2HTtDTAX4gB*zBc9
zs*dP~2q4LSTqG<@+FJrxX)y93Sgy)71VHUVR6QalV@>svs);{mJ+znNtQLh~CHXMv
zigSvxmDx=S!{q@?#b6Gc7!~7$1jk+m8Cr9CVBA_vhau#K$}s)XTOL`J{n9f6Ft&?A
zMFw?u7N8fW12yH+=0_QzuKGxfstR;5T*@e6v>?bTq$#@HwNQAls(=$iuNH;pN>=6y
z^fLui1vhW)?hE(*t=)Y+_?^B7ZiO5RgE?`FSDUlIb$!D)&EjV_b$}b@iGE8B0D@Xq
z1>i+lE1~M63|H$FymaHVTPSsmq{DrC>*<K#xJ6+k9WK{9miw~=He>ISGg@<mXDysP
zaF1o!ZYhX2Zo>Pfap~@u6#qRYRPm7>Er#qtQg3bS8_|HhjBtqVS`>!tLE%?1OM-6q
zM{mm;^{RS>KmoL`GX&~RRsG>R;+_jDG5;&%=8^O9o*b6;Jb1e(96QeVN1_Da@&4%b
zc>~{}m!%K+?Y&~8ZfL_5Bn7O)MXAtM%&(#)L*0FJd*q@l6iS3lJ~=BY5<pyEz?QF!
zNy`Z-+Tq5d|B=i3!K41EkZ3%>f!?rw2w`ab(Sd?`_g%>Q#F6i13q&y5qR>SRyo7}v
z3Q-69dqqh-I58g`D6pyqOeum1pA^bPs%|&_2+Q!~vFs{lU;vJATK^6r{4WZ49#&I7
z^;iI7T$LIa_2m_I^uUuv4A~^DnJ$=F#^~qm<ucJN%9^2{O7%HmC0QuA3}DYo%FjxH
z$gu|6?wOPxEr#f?VworYdp$l}#yXUs2nxgT^A*1+Q-3q?H;l#yn1(B&r~&uZ%{0(d
z)m&9Z8myWCEe0jD&4p~tq=UR;0{!?TWsS`Z$$MwKa#gUlomT-WzqZP>`u7_{qmhus
zMO>9t7A1$)mG^e070_ikWRRAtXiElZElB9fSh<Ekqcf=`o@tB3M4b~1b|&gT5KNhR
zs>!Q7Vlet}*&HM3CMKZ-2+J4OqA*vd1%5U&m?Gl9Z7N;f8a|}NyNulm3I~JwxdrM0
zj(9=YEK)K{;2W03T??gUabQ7+<G*9e6b?#SSC1euWrzZFYl0LYWz+!*+yzC}4B1UC
zP>IOXT21~gc5uN%Alb_c`T-eX-cGs-m^S7Dgkx%%6TbnoS#AFCI<UP};@h1nkQej<
zvf8|W7LfV2D9nV*4=V=<P;%ZBzKI;WDxJ$DJSXk}()3&aiA?2lVHzCB_w#}=Xf0Zm
zFc^|r*aPV6s;Z^hSuTSs(-U0~mP}#vLIgnOy;m-MLrLG~BM;ImZ63*z-l$A5ILig(
z*#HFUZKAb~zos)72&9X`#K{X|Rq{KE1b8LCHz-xExUSZ+RyDbHW2{?dY7SNTaER0L
zCIzh_Lwu1q`Uk_)Ht8pZr~3f5RTM=yKuTUJ6}9J&Fo)VOJZ&08YB@v2T8CtLWuzm&
z+AAv^U~#UjbR<u^!pRzvrw{K+or3{(QJ8cbIwT88ydpd+_G2ZX1BThV-VhPPwZ_x)
zH-_q0yfS=i%}_CE4H?Xf!bI)3FrqRBI%N&+PJ3emqP6#iR!mNC$tzGRIMNG$L{-X_
z8sGCEb*08L)!daEkJR2pP||fO>8=pEhHPK2<oFw-`^b&Q2$`7)Gp=vR@o{Bsx$%&(
zPQAAwwbv^-KFzpCkg#8ox$Bi3@3@bIWW6Z4LR6lbH<n3B$buY&6D_+TCD*%-6Yna%
z@=Dl)7_9OM9lz!Z@M9QQmUVft2B=rEJj#T+O!y7ix2O}7V;k9vmb->jTPLn~L-8h8
ztYAa*z@iMa*LhRf^FGyuU%s$F%F+!FunQNx!Ex)tPH*tJdL`7uS?Wxvhl|tu)R%G1
zls};%w#zHW-YE-oB)36X5NHPi=U5de07TB*zdGE8sTV<EC>%=v&5*N2AcRPR1`wF`
z4PH7|>|=uuPPOP8ylJd_l#~>x8~7oJGL3Rc$%x_VlrlG5eZYpnlO+c_vKkb`9Dbxl
z!6<mL2%&0Bl!kf<`^K|CzyT6|o+G$aZt5k79rqKh_~XjAA9u7M3$WZqO)Kybsw}hb
zNA~7IJo@{B56auj3qa~r9j#Y_5-q8yWPRX1yWBTz=D!Pu$<&3&My4(?s@dYd3BiPe
zz@_3OhV>C7j;cqCqry_VUJi&#W8tuu!qQM&i~v!|Pr(7qp@L+u3`s*5!c`6R0N@q^
z$lY}sBA;eaI6N$J;RnDR%=&0a31_M^wzZ|HmqpcH8J4zolAKiy$w;ilmK1cNgdy+A
z>C|edi?j%YJ3BSv!Wz4h6-2>;8P#1dScpt>h36tN?ft{iX!<TDok3~GK5OK%)ugYk
zUW7{P8ZKrHr2J!>Hj?jLfxwFbKBNpGdoX5=@#lleUDfqkWCFTEhZ`~#-F4}}>dAU|
zNr|g~)uoSy#7Qq;hb%SbavC;RI2VPJ!u!GXHoRc-aaFQz7q_$0<551r>3wW4UPj$N
zFfgAChpR?*L-jV7ld>T%)(dFj=7Q_p3CrW*szejOgy=>X!lrJ7A;jVBxCn19@zC9W
zbB$>=X-H0XAz0j8VcnK@uJF)<<>nIW`n<Ws6RnYj7?YbfS65Gfo9{&zM%K;cMa~b=
zCtXE-08r_LoN;q?RWq*LT;3_T&0HouEpD!@&<O7Qd%{ybd2YG<zYR7#6r_Ab<l>3J
z5)PGHTaX<Ow)T|N!(QhqZq!g8#{EJo*Fu`W)36wN<t$U(p<<ayNajjecsdq?4<Xv=
zT;QKDiXJZa^$LFs=E^YkKw<l!ByXj2JW%<a&|wemWtU0fnb9J)DQ;#j09&5fJ7O)4
z`ke$maRDx|iVJXyRYl1O5nkrG#VQ=6&m&e9g}mY#J&?oo@BK_ApjyczL6gJIxl?#8
z3()-JwS3d9-SH!apXJRgRCJmfHwyGH7Ub$@=f$>BZhSe{y`Q<2_x6nsr5LOrNW+IZ
z5tAn+Bax)fDZ#k$GgE>=$|b?LQ(^7rUCoGg>>q2<0V?xJxyH5>Jq>clFQi<r=wUpi
zv-M~Y`0K{Ab_3+LUq2hho6okyCI{bYLvePn#cV8S{wteW?H^!r*KPq}?qc8Dwp&Ee
zZplfuOH(Qe1VISh?II^hpo$|vYGCkvQgHnP#kxJ(Vr-KQ4*ovkLY^5tQ`$f{K+(C9
z?Chub0=cBI<by(1CD3c{t&X_fn>dC2(VIAhUDdldg^k#Iaf&1-W6*NkCXgUJUvaE|
zy%d4A9rV5P0))Kux&R>xo$3t>diA>ga;cBr>jK2ec3pr);01_<?c4pA%h;vf08_u$
z1&C$q&vvV>7_*Mia)Ijp!(*d+-GC@yQ5PUqz;yv)0le-%gwHVWj5V6$kM@zF0^K$`
z+Ba%+&Nr+yh3@SSgK57GrfULNdhb-bYA`Mp3hVDK4GN3vE)5Ec3*GLJQq_Gxg~B$b
z6~k#o?X+SDTdX@JV&vW0o${cnYYurBVg==4h!d2D!Em0Q_d{u*9Rb}eXq^=FidLz*
z<bs~B)PDP*stW}<0?wepLs|z<Uln{C(sa{o)M22I0^bK;H?%Z$WX0(n&<Ec(PP=tS
zfUhf_FoVqMeGx%sc&1=Zqn<WA)Cb=-SlCf-8!Y6gw+*KRi<RC?oq2KfvO;~MdVH}0
zlHO;1aIxtvLmeges!%t$+8wQ2vtJ7~)l;&|Ora`Ch&8IGH-pUTdCnlSdcOCtRj5kR
zJoS7>p+VUyRON2wFM|8iWO@Mi|9{rrrsujH*B0u}U$L9#Hck=e%T5=GdnITf;Lt*J
zKwKnLr@=)C`1h>XV~n|~IQ!XEZ=o$!J@LCT?PMm?jx%g;ZfjLZ+PxeRCFr-a0#EGf
z0Xa9fv??UQU-7Vt`JaU)o6LDQfV6x4Dg)rU*Y`3i4+h*bHNu5nP4X`EVojt9t4pU3
zp1aj&p$+w;YM6Vo5B4vhWAiPM3Fz4CoEmUojPptd_5K#kqz8lkuK@?fTSJrn3nYZi
zGHyqmDBoc($mdPHARnC^gBKkSuwvKQhqvwYRlZgE=&O9I@)<i}XZh=^toifTTZxzJ
zoqg)v`s=L3T=`(12TeLeYk*Eqr7HCC5=8cu(^JU`eY{0gR5_t%UxG~dD`n%CoakRa
zcIIvvPWPsy*k6v_fqYD_1Y1AnL~P!)&_Z%oA5I1CR)>rm`bLy2l?5T6sVuPrX}0ED
zdX&DAA+=q_C(~DsWpdPsM;>6iW~Q(ml?;r<=l`rim{U0bMgXZXq%;e)RnC5J4pTR<
z21aWtQh>m<nb`+!t1c>Ny#?(3K~08CZ1by7=|CTH#Ys!~gP%b^ic$;%w8k3te@^&W
z?E<M2<f5BH$|DN8&Z_o*PV^Zsf$Gi1RwumKptJj}UFvm@1nVuh7~aCATns2IOh1b5
ztS%U>udhq3X9QOQ|DCsI9N*FH8OL{Yea7(}pjzI_r9eaJsxIr{W)ojy<VehWNp#`&
zr2UDtd`%agcxT6W;YmKc2-AlYNx68HnstxId(}FKfqILQqKNQ&V|ytD6JTYxQ-!8y
ze`^r~+oQ|jabQ?5$@xHP%BfT%m$K>#8q4%7-BW|n)-^RJ3Lu`h0_iFJ!XTw5!DG3c
zy3T!vFbsW74pA67T^*t@@|bi2L)3TU;GR^`Q-jVIrMxHpY`&F5&w=B*%P6ljT~m=-
zi9Z7XA*YJyv#G2xv+*i^ak3^r3?==fOGdbd*?1SP>h_hT>kB_ITYo_o3xs+DZ{=^e
zTouDM8}v<QZTmJ0+_6v-9mp@$;hczFovL)1#mrBkNXm|z^wPX#HZO_5l3L%hDqT(G
z0GgFq>xHXaLcJv;IB*ikCEUx!yxDw_F}IzMH9h5E1#vr~1pV^`%E>zQt*||OOZfh)
zSPKzyQ{`P|rq-G!!)7AC)(az=$a*|cnTA-nscJS8xsxZW;uM6g5KP>GlQ6B&b9*7D
z@KhqSXh=+>??9=f<`+bZ4-p=VvJ@W6^%P>VHocUIKLZ#H3s0CVZk;Ji7Ea$2iLi+~
zd;Xk%8i8qGUYIPZ&uPH)@djZElBJzOwAqW3n<(rgC><x@McYl3S9&3N1eiT9Y>!ht
zZD{_!fq#5~L<bh7Fp&f2jEPD@AIfc^P|$sK7%|HJOa(7b)bvTD<07R@CF5abBGJ}V
z7<4WEY1$OPY$=u7L>l**!PO5aCBLCnv(_XVVSw5Z_y$}GWz!;~j!GEV{ZTuT4H~D>
zl%L4Nbtx1N0Pv}tcbAl)TN>rFFK+HX*S9nAwb%fisNJ9oh=8w4!dDcZ?fi%|QVN0V
zdI9@I;9|uC(RE3D0XX9*Umze`N#T&7f|@d`Px>$g3MLxsQfe6WcSoaU0H5>G_&I*6
znR~a<WpD{K1@s5djG-bZO3g{V?z<1ii;{+Ffdx1lZ4+9S3Ae^?meAh!g*-H!lY$u-
z#KG?`N<q8n_u}zM`1MDJu7tSP<l?AyDfklL0GgotNy_?y<$n&xk4&gP^EiD8m@OQ_
z$04$dhy8Jg51W;d>SIYBHZ$Vl-~>%q#yALIgYzS;Ml4!5UPc^V0n%TS<|kxFFkR?#
zU(TZuM5vSl>b7e<5Byjercv(*-mej^DL_C^&~)NuEbZ%}q^GPxMCdjgOoB`I;~Ql{
zFXm9175Z`!uJVAykQT`Ab$WngjQ&}Y9$7D9>UB6J(|4Q6DPnTIgYh<KDP9MX1tc5q
z>{ob1ybI^lkqQ%!6b;H-Jdu83#JiRbqNw6sO^9A&j^w$T!jjm|7s{}dSqTn89-9e&
z<RxLwn6n`Cy+!i05&GONhN&s=dLl4(I4q8ZxHTC36GgarEWVVE5H2mZ0$M$Fzy|NG
z&@b{Hc_gog4h4^O5*U1@5n?YW=k{dI0pH?MF>RPurV~)i+gywka(pqFJiuiWFjIiD
zP{6#20Tf#|nFhd>V`nY~y6I!O80bd3_=fK*tZy<_-?ebo=8S3OEJnRCYGE#{dnI$4
z2+XC&sVIoilPX5wyf+LP8Ckq($e|d_mr}v1%2+&+Ni-ul!K(Jc*4JPm?a9uM0i)hG
zeJgVzoibd5AXQ8$#YdF;eqR|QJMqRU+;?nwG$tzCjZFu}WU%^{g;r(pDz5f6at4%h
zY;Ih=(xqCY3PUCEXl8)$V5x%%_}Lo+JQ<8$al$2A{|Y3YNR~D>9Rw4O-?8Bhn2bH&
z#LCU`1V3^+7pW$?X?%l`&S)W^8Z(ce<FS-$V=8c)2lx2~ZexIqG!G3BDLb%WuDWIH
zw$uhHC=S)Tn0PO6@fRT(@se@!We%m(o2Umd*47YLaoT7U7paJiEw_|!aU#5VEZXu|
zXJg3{*cG(5WVd5!Dop=LQpKK+Kk+G*3_$ytf!fLiFd3-5I{F|r+nZD1k}4!$W_YHQ
zdovT<cCN6c#ew+M)!xM)U&#;V#!g=E!hlwrvMCt0txOBEBCVgg3R`?ornq2_N-Lq`
z<AzBkWX0Ujd{ecIFR4;mIH$i-TDT_vD5nHx{}kK(_NaxSJJacJMhkRuX0*^Z11a%_
z?h<Ey{BU*ofKa^WSEu9+dl^~ihah?r*u^2l<1-ogjfzbZ`R#}9wI=f44*@$bg$YIQ
zp1ty^j@iF@RW=Q+4X+k^Agu+jc`l(>auhBMTptYKbSFa3$82w>%Jp(yE=ZGeWZ*+b
z4T6&=!_9TyF_9E-=rZF{D)me-z;gnC$t(Q&5tGln-70U7zr0EwI`N-b<q(p@Ua)_M
zPWr%cUJAb5&O}0lJU)~0?PGp*t1LWkr<xyGgjEH2$Xz`hVT*)cT+$LeBU{LZBgYj3
z<yCHQI`asr+R7!>Y}r@0nl1b4R<qT<nALPCt=&Z3iZ_GO^qoi+cEP!;YwK6(jSm5h
z3O!cf&qT3~H`CJucC|7=P1t8|s;G&Y%t$BokaU=BYPx@AqME27G892I8SbAUR}*(V
zz!yCvo%l+NHPf;jSVahyex04DZ8B8RbvlYMy$QM|G8v36Gr_CHE;v5Cu1sV)7+;P{
zTrph|gb8IU<EG0H>~31mIMjA~yCBt8`|49uD)$O=5-9unbmpAXvAePqJV|0V<liuP
zPRi0B3W%IcWI%5riqs5?_iM_Ga{QL!%Z?m#)0t6DK9DL!^X93Wj;oS4ncZZ51SPzi
z%#iRp^#Z}=w!VIIF;qhyJe0J_Y<%ieBhXe4Bs@|HfyqP*_Ik5%wi@M+1J*fH2Tne=
zQsT*C4`f9$A^|3kY{N|5Dr+ITAne^_0HV6iFn!6R+!4l*jfpz$<8_-czeCfTMoFIW
z`pEKhIZ(~+exsQJf^IS7$rz3Ix)Vt4@%q3}WN9=xZUS{-F3BWtzR5<#9ymododj?i
zz7)Qb^5j3`b$A8zUXw4N%0FdF%*p5E$Fyl{135n0&{>kXEZWeNLOC`a$(Y<iwMr)H
zQ4L;|6zMMGCKDgmtCzwlgIDMEhrxSLXxo~2B$z+%`x})K_I-WGN`Kzhhk_v|WRC>0
z*&n{ZfjqA9CCw7R80}@kAQxpbPpe7bI~D!t^}U24d3TQBeSLYH=tp%jChn0FSH1dQ
zQrKFRzIIF6IF-G2NZx#j{pdR#D8F*vms$Hd(c=&g^##uRGFivv$m+tSc0cdid?}0V
zbA)v-O1>vv&3+MvSl5e_1|}t>g;Aag==`+1UJ`$BC*pPKeNi|yb@F16fGCeb35v8B
zYw$Mr*F5ENKvApjHox_OA~_**`-?KgIM>JPp%Z251d1YaJ?7WM6h)`-LKS=n-wpec
zHkEb{`+BXpqM~U4l?__AZlw7Bnv+~*&Tz>8?zjKuvES~0|LK4I&0y~@YIoEpuu{|i
z>3{j{KR$OOx6dQ~`u{)O|MP!&KJCwc|6Fz5Z2h+Gm4E*{&wl%te|`S5|M<`CpWBDm
zzx>DNfB2_=`FA$`pZ?ST`M><T|M6e`%jduNm*;A{712M>+;(=m5C0rE_x9iZ+yC&}
z|NiNBA720aKmY5)Otb5{ZGZb$WrwPE4ef7~_C~+WpQQb#|N4LWKmOgn{BI>?;8DZ-
z`tbiO_U17^D)!$L^M+b~Rv@Kh%;7IcIm#vbgOvaMfA#Mr<-Ail?-Y)63-)}rZTrls
z{hLD4Orn&d;^F>6%KvXC1m>#~Za;qRgrMw|`|)3YQyWRd|Bm^n(B>c4*uVdGYyH#z
z`R70Xc4tP*>~NXczHjdH$C_rJ)55<sH50KF9Odla%kF1^|IO#swq0;sd>&X|{v}Vw
zzd3L0h6CA^qr}h&?eAIdA5&tseV66Mdi~pr>7PGe8m*?ke|&jK{f^G|@2?3WuaU!C
zou-nS|Jbc8lebsEZ~0><<TZSIsR-+j-SExP^po)SP5;OC@o`audB@<tGyT6l`4hQ*
z-_a@g?~kJcUf}H}0Kre)E+ptLmNE%{&<%$B+b!&CDgSP_J+Tkr+Ma*+*Iujtdh~zi
zQ~J;CA6fkaQ9SS16xQ?O*b?{l)oZjrUdjU*mEK-TvGh~7j=GNO)>Y{7$8IR3suw`Q
z->1qxbaRVH3#k3uJK(qW>o1_AqToBaJ^qHJ+;M69c2g|MkKHP>_gA-m{)VMo73AMe
z$kFvv7eipCrk{krcL#j*?}aXBJ?`I|{(oc#pjxj6hxQ+g4i`voFWo5p*bP_uZ#PA_
z{MZcu%eR{lmp^th<I=(_F#B3sfA<cs3oiS&KSIC#13CZ)Nexa1%b&&u@1i=n{|(DH
zYb~kEZhx%k$6x9B@i%-M`^I|0XJ^05>F-|k7clfYi~b)ndd^?2-t#xC-7h<k1pDbj
zg}d0dn+Qa`{T(xMum0w`UcPlNGk?zz`K2jIU+*g>nm>*W-jcVI2tRf+E5F9u@1^|Q
z5jniRI*RghN5m0+brj_nUV~jk)&6`9&d=}R7v6#)QTLamqWnBWII_Pwit=;E%=!7%
z4ecL0_3}M`b$cm4cO31n-u+AYg*VX?b^V7s;@31I3mJaND$37;+<$pQ{MX-J%Fi7u
zWAax&5`ON6)U;pyMESAfNLcjSjqP7}6L|*^W1acaoA@OYF|Qi`VzIrHpNEI64PPBa
z`MD#a48J;x@^eRc0KYnl@^i-%fBEJ`_?35Yoxo+R{P-?@O?3jt{-p>-`EiI7C2YPu
zDWv?|5pmGps+W|XJMOwd{^}^o&mCiYcgof;yobEP{Np|GOGYE^W4@#m<;S6|3O;!I
ziSTo`N@V!mPn4fKB8A>pM^S$62=v}pM^S#obh?nU{fB$v*KDVS+n6s|MfroJ{g-y=
zU)q>|{_U?H{JS5zd=+Nz=OcY;BK&>k&1a^{-DO#O>vtS3^H)CQ6cm{m@25O3Rz&%u
z5mp_uuYN3S_H(yNY4g>soga?3?AFfyOKu?iQ8#)x@fO;*hx6}$3GK$B{*Glc{(+a!
zfQ<VZ-abF;Q*>N)?funp@gn@^j=+(9briDf=Z*mRe03D;=jV=A(Z}z*u=NWD|JTd7
z*plCQ8T}u58Awj`HNs{;9kbE#L~wxBkAy$y1_asLO*rx&yKRG`n%%bj<fvvh<VWFK
zI7*20OE2MESn2Owg8ceBILJZt4o;QvejFT1LcZNpBl5>?C}8?_Q$^FCx&@NTsT&D@
z&`oaOdIRw*Uf|ETTA7vc|FajEQUcKY4sP$iWpHbJby?$&exB)S-ww!L`(u~Bzd9t?
z@5i6RQH;6%@)Q64GyVBq{mzxgFBy)I&<`)hFepFqlM9yJ0Hk=k30d)DHx!$CyQ%ur
zkKKUpf4d3r|6?~KxaRz`{flqFZz`wXc?18z7vBf3(>S>C<8>OlA?o+-ra0&yyS4dO
z+}ivbxb4$mnxY#Cf6&b<f`D&;?O%KY`=TO$=WFv17(jcEzZ%^B@gk1hka6qnw%XU|
zez)6So4osPvUoR8y>B<ce1GiL4!PAEK>JtUzzyyGojvdmoddo+Go<`@U;;k&tK&=g
zg;U|hht~n!?Eh!4mGugx`x5nw^asA&znB^{f5lOK!^}2rt$y?b{mO@|16BPc>KEw`
zJ*0oN0KQ1S;t2j6K+fMZ(qCGxm0061*6U09*|E3kyz$-jCH;zX?`8qDzh$KRSNuxI
zqx&W97wHdt8T&7M4*&YwOZgS&+0AVBH;prX$$wUG+iz)K(jU0O;;$FO7wMO7_2!?}
z_~Wn8ub6vuAbkt_lK#MZ{@0r1uRhv;{_X$s^uJ}?Ip%-9qrdm?HP*PW_j=iXJ?#JI
zj{55we*fu24;!D}w^*l?(m(y*nx3CvsrR<~|N33M5(w-_wQ?6jIQ&G2sR-5nL;yt~
z8a?W_2*^NS#HG{>BMc&($@viT5YE&Hh;RsJaq_6xyHM~tZW6)^LXRMXP$YW=9E6IR
zBDx@4fsY6!2qz93(EV^Gm;x+6oCy2E%7@cd2^13u1-k<zeF>|YmJ`JoDZs_U;W|qo
zX`sIAlkJ^z#Z*%ON{52uV`T&E7N)kMu2F3?Tsfz3BDs`~U)01B@m+;7!-+XTVz-b7
zgjw=0rB0twP^)mJAPL9hGb*QW>)||%hhy@G<Z?_t9G2lF2D8VZRB1SawooNARED=o
zmp(}W*TCE|cp!^rhBKrOp!{&ectv1p6$c)HktKtJQ4z&cH8yV>{0_#zqe=w|JVnWw
zIStd#_%D>y3}?kFq>;M>bvft)sSw5Rp;Y4vp>oNmn8#+2!YPb>Y^H}h2v>~FL_7$b
zh|TO&ryBLKM!NqGp&GfOHiK6V%6h~GB<gf{D;QOJ>YTrMIz=Ub$U@R*KwM|CFL-QX
zBmDUD;Sc31I1{okAPqpE*mMt}YHDmHzCN$}1P?5E7)NmG0DK7$ux>Li0bEggE>vb4
zSdQ2Xo5@6Yp~Bq2vBgF{IHbjkt*RHNHgq6A0@CEgW{eFgv&JT9wSstJBRuY4e4(1+
z$e9<wkRJb2{Tu>1Bw}JK#1bW;a)=;(UMRo92?$kT(wR^%TM#ku?g&OaC_EQRzHkDb
zDsEc@J%viHp985Gj)y?0OUR%OluM1xOe{CHDw|+>Fff9G4Y~JXtAKQC6b!MMmLq4X
z4MWsdC{=?Y8D9VZcH6bA8oyYE?0lg@_RZ=IshTkgw8ml(zcr|(b(p5$lJ2Z7mCbI@
zOiQJcQD@;&z^OiZp(GI2#%FXZ#HT{lE`>vcGF!YExRhM?EA)_Ay6{6n^9tq?V?qp-
ziAOX+Fh#`2w#Y{9&Bq$l(enC7h`@x5hV+23RJ*!CA1#$3Zk1~^mMWZAso0`maJ4TZ
zlT6%Ju9&sNXXi*1(q>5E6>Eu2>F`TId0$lHjWzWchj8<KQ0b|~9440#=*8ziQ>`g+
z1LD@#>?u+Jl0a?0$vp9c`_LiA&{PX~X)d9p9pa0e*_TAdP*`h-acL}Nz%Z1zD7Ua7
z=rmU6xAT(fop*9Rc;!rZW7e_-rq=MvRZrUx)gChcEi)*_VkG@-*Z3GBX2?hviv_!_
z^xRTqF+<hckfClUyAeyZ<dGXMR?~x_>#9=SoqDSlM+0rQu<;QT9CBk_N-f$ZzK9!-
z)x@}z-c+S(tC+@1!GP);8OrBjnL#iK>p?q3ouP-!YGGob3}@&G(1tT0{H(pBx-XYf
zV$jGngSJye5JQ|q2<2~v<Sc<A8<()M#W{h#Q>6<-g2zyjkk9Gu(^6h2L%evP0K{$Q
z=28g-E9^zEn1f|hdZ3V$88U^1YE2pZD=}FG-AZFAS;!^ino;`yOUX4;mA4*{a?vQ?
zzab-MFuT8@$Z#l?zabDmkh=dVQtoLb9<fXZ8cNh}sNNe)uy05f8B=BDvzqT6W$w^^
zd3OF7T1)xt4V8mG6trrFX|P@j=8QJ$CDoiU6!TIJx?%Xp%^H(ttW{csCzPJvkm2=1
zL91r9i8XYXstp=aO<oFTzK?9;Q_^wV%JPS|#rr8fvQA&)=!raj4cfZaalTU3#!E@j
z#zCvDxk68cPRpv0CDqCnp9q~cLUKZ{F>6XvQgS6$w+_QE2Ae55ZznDxR~U1vUvFrx
zFlAYxe>AGN<^xiV&c!)3-Ei@RqEj8uOUc(eU=BZqYQ>?{ESFLv+8U!{MB1HIz2_46
zVCU>FjS8x7ERG7APubE9=|}>FQg3@@3(kT|s1eW*Hk1GgrHL^_F~*qU4Bc1h(x0N_
zi`33XR7;>Ztf6pFsC=v;-Abs&?4@Lmgiy8_8z1$jBDDs*Zc-Zl9kLDe!1-;cQoU7H
z@fcmbpxl%T-H_HZkPF?A(LCPN=Qhx+nMHNt7`#oi0bQoL#s-XGsPyrrV4)iLlqMT8
zrjfrrm<ipG;yqN?*eVNrjP?$Y*U3<;$Tk{Ed~V2FAN@!;UN0Z!1-E*g(PbLrjfX;%
z467oT>fBJ2H@d9jk;Q8+0ec>0c|))nL(2b9s&gAVTjWwu$>^12yeK)jUFI})PjvRE
z(YUylepA978^|^mtQKxaoq7q_&?p)aUFL9=a|k6YHx$8*uHb*e=c_K~tqR^omwk+a
zx0gaupx~6h+^UwwlO%i;P?IT?zQ+<R5PeBn9L_MBdbQCf^Ge%*2JB4mWT+q#T_$xU
zzKSl38am`ggjcKfWS5?umaY2cKx;*pVVsp`Lsx}{@-0!RjvtUp)PYt>$;1>kp%Odo
z;?l~|Wfo5))4U||g;wmcjZtDXln&jHa4fov<B#T#ZnDTxJ~cWmV^qQpWg;?^^oefb
z4CUF4i7Kor!bX?%jC{1AY(-Y)&Lx1;#KMxbOsnaV>L>MkiVj_AGJ{bA>QeAbs7g~+
zWJCR_K=O2}f>mKmb!Djf8A^U+D2^4T@-BwjRiSL^2Fo%jnEuq3Ci@vR%mOKstV*Lj
zNg!{iPYdyO3{plm3dDuU$Yy%IOJX;uLZw}|wAw?dl?--$DCfGt_P><+=pbPG5-1-O
zACs_OLa)b?4fLKZCSSg!T$swrekr*yZHf26q(f2TtP{%VWOX2VlGOQ|nsIuUEss^9
zyzRGLW0Z-$aPqVFkd4%eVME<;u2XQZB^&yedD9d&BwVk9V;F61oLR$UYvW8CnJCIo
z!RrE)!~?V4U(ulZtc!K&KI`HP7pKu~U+{1;wfmE#8c)X$@*7|>+}F$&K9TSwgvml@
zg4|F-Dnr8CP$qXnz4A-JX94byOL=>hbJ&=8#o$KyP_p$=gH0y*f*NeH!QqsNcIfH6
zq?~9aemCR`y%h2-UD#x%Bg^QAk}XtUjV7Iqth&ME@P=yXmw>O+$^&DQp^g-~A4<su
zRoY~QuTrIrMmP{vp+xakSyrRb;C>9*b1w-ydqH;!vUn*a>lP=dPG;7+glm&D+2C*p
zhH}droQBb~+2L4>M!&R`^RXTT=H;J^CaWBYccalN-?+|evdT9!Y(ts9OUOl_3|_XY
z1Nj<8D4RUf?nayB!K0^Aeq}gxjt2(#E)}ZW_LoqC%DhIJ-Dq-J8!E0{5}ykd+6JCG
z@^8uw{n>_OANVvhndloDw9#*E0APf&>RaXAy#(?_{o+e1#uE#yi+O3(CUuXhZqa16
zZ|KZsIs$Dd%|?s6t`(xmfsKoYOQA5(h^?`3n&I{$nr!Y3jo9eI-l-6qJlMNbj~{uk
zH)?`h5}A9p@B!F$QoIyA(*dfKv%0Q!0IGaI$p~%bM6(^>EOUC7@^grukM|?*^hS>4
zOB(vk{l`mzD5n_9nyy5(mvURkQR_!_PYg+F{m4U&B(;|U&Y7gvl~e7uOLSP|Pm)ef
zO4{E@`|U>txLb`z_BZYjFNIvJOsz}82LUO@{m6K}SDn?aIYX*gKl7_kpbs6XxKs7R
zl(~j$*AE4)6i&Jp<?1e_Hg{d@K1m^GB4=fFd-eAtyW3~B$h6pB3U1^tsn!y$Y$rfh
zW_G1^^&=x23E&+!l{xzh?^W9l$y{BPA*`;*KNPv3k-626(NW?HBamI~J6qV@NXmLC
z<g@XH<dJq%h4&*f8yU@<6(%kr$0RcwX;&R-rOX`zQo>jRNa2#m+p$n(j%RXJ4;kaA
zwRb5TVR=w51>X^%Augp@mrKh-);RK>y6RX|c8sSec+>T7t~_`KtcM3o?L>-r$c6@#
z#6v}~t*RX)iH|)HPM&IH8g=BevdSuYn<$}S0JB^YCJJa44_V^Cvv@Fxi~-PcDFMYF
zh7rg-N1X>p7QWja=!8!LU@5K=85UKZ^ir_VflTpOU%g5|+SM^W4Oz^{OX=}i%z&=A
zs%RLnD;{!cSHj4o@Tr*JN%V;!N27-<Z~UW&z6RCbRe!^f4$uRZ_G8H1=OI%&vPb=u
zi#=!^S3Qv=;KKk2%7^lxd4Df|HR=kw5-wdzv6C?zo-IDm>zseVQPr%;lCwIX!$Qt#
zWMcG?HC+f5uMD&$Sm5<HwDRS<jOASFx6Nll#ksuIi70t41+A1qD5y)RhymKXwR7F$
z>j{<WBqSF0zq{Pi_(r(PJ$<0mT>CFSHSU6C7?3KLRJ?&yahGunsLG|_`v|Ct`)e;3
zV8sQhvcjW$C^UruM{#9(v{NlU6!;t$ipo&(=Ti98)PyQ3a@!@o%-{n}=!=g214Zbv
zgAWuT@Km>*!pjN<e#KRY<S_tP++_+M#&yU&4PEL^^Z27_T@WiPP5dMY|6EJd<(q~^
zzZ8y`;Uu!33+duM<U9h_#Rb*68JB8=GM{0DxXT)bo#OsFtUrc~yG-E&#pkkxVf(nl
z6h6>#E)|@3mZvC~Y-l-!zZf7bmqJcZb1sMVL3Z*>S|F@!;cEcoi#x67;~0+o)ycK#
z;tm<#++|Ilz-(*#1E%6zW-x#%4&>ESq?LrXQ;M?Xt%eot8`g4%?d_Z1>fY)G&;_~b
zFyJqxJ|!Ji{-qSFOS$iU(_?)Jc{;fyuz~{HG_fzG1{G-4fLx3%$K%v99SE08!ZV@Z
z1kmchs<?{B^fs#1N>Dgm9oYwpl=HtgS~>U1Y1nbpyA+Nes%tOaCH4l@wP`N*2GzBf
zc$ezhOPnWWcA-^f?Ve%{-9{Kz2L#4d#iqBFEizq@e%=+)am04PusY7}zK5jR5MoHI
zjn_L^Nb!<NkpA_clB82K&j!V+H{z;$)60qRB#Eq{_=K+NaD7}#Tl`I~EE8kr$}(~e
ztSl3E=*Dg04*e*UR!`K6Z)2A3jw*n@8=reHhNkBpES0j1dqu9_CZ$Cw5??fXyFno?
zn7th(K3y2Bj$((t%IfV2Sn(wYa|dF@7hTXDh!tOSL3gBr_Z8v{by%>h2c)|MSBN!E
zek;Jb3>{x|L3cO;F9kZM!&7)kWZp4I`k*@!-urSr2pW*^t&SR&zG&rkI8ZNz@<F|=
z{U`P*X|%uLl)aR?8|yZ+g|7^7E54RQgL+#_e4*Y{DCknsq3FVFbvTWEEwP@M^2HHB
zy{#qgt0sI>mvwlseNA!4(Qol!-3|I|4avMA;h?ji7huKLkbux=Ye+z7v^6Lo6dD}K
zA4{tn4sHp`>WO-Bl_=_{<9aES4f<?#@r`T&sn}8Z^pe073QmZuj#8)&9yro16IUGR
zmWeA4aLY6{sKiCH`%>x!wXa?|?JmSs?{!2|ki;dFEObG4TsVCwXl3B)(Zu7*$_cLO
z9ja{}ae-=^bV7IBg*npYJVmMplW$oWt`0dG;jucPGCqTRd%0gPg^Y93FM)h<nwudu
z^(tL3t&XCrk1H2Iuky?paLWgcl-4zGP>TX#T}nypbg6XIN%6Tg2&hF?Z@Pq(c#Ac(
zBC9z)Nvc861n;=P^|{3zs&Q@&>ppggG0HmmT;yDu+2;~#s8682dWZg;OML76IG5B0
zur!xMz8gcF;=OB(RO7f#cLKwnB-IcnSbP4>M?#%WDRO{jeA2e=9Y`HlPRL6t`3E0b
z(hm&>o=}yd>HyJrVZt7eYBAG2-2tPy6f#e3I=eXIv^hICLkC>~dDkQB8&P#=ecGSc
zEV;DZQJToBnAKC1+k;-|+b)*0qc5cvB<<)9c+92LbDs_ziL>BUFQkc2x}`hNF+S*)
z?m)-*IAV@42Nyo<k^<exz3d!km8?t1c^pT)@*p|ntL}j0xFBO4S<8LMkVbi3A2sTa
z`Wr5uJlqY}R6_r;fK~?>#s%c+z%6|!XyrT(d8#idCvt2J7rJk3u`b;=q^ePS%K=__
zic|sj8$ZZBJY;--=ssk40|(;*bX`grTth}Pz-K<V+Xj^0kkO2}@FBw)6ZZHZZu*io
zx^Y&Z`o_%GeSr2Oz;~B&xjsp$X&zz=wKs;?LiG)q<As*F1i;!m;4&^qS07M)gSI!I
zF+OB}Cp5-~tnUH9gAZBXSiCMsSI3g~A!8dgkT0b;p-|j&DR}fO1u4i@pU{uP^k67R
zl_l#akKseL=q{-SLHj#D2DgbZ0XXA8b#<U-d^B-3==;&c8b?HxHtY4x@h%G;HJ80p
zp948_2|$T-KxZzAKgp$_ifDb->$w!Nu8*oCG3s3t`0~2YVLd<1-s!vU_;`DliH<M4
zcbMoCHEFzuIF$|+7_0+3<6ZXngbM90PNhO0?=Du*q20l1<=-4(9bBDwu?~2R7o_t6
zDVKQPVhkPHW#yLwcGYt0NC4}-jQppgY@-Wyb}1#9EcEHw!nX#nm`h;~o;N$K^C~gv
zU4}PmJ-gsw9X65osRu*(b(N&)sAuVY^1-S6`qb<P7K_aH84zDpA^WT!kTJZkOrh3c
zOI`w>S}HOzVm*;9-aF4cK(<^8K2|`sd??u}rPk@k?l7cXsI5z>BTtt_UGWg!O%H`m
z>-En#^>w<kI|`Rx3Y|6!I!-XIp5;!xH!+4Iw5Pp|qlv2^U0*mS62;Zmyp8&+Ub|pd
zmy+x(^yACTWFfDKFQLgs#!<{IG;pXllhuqPoeOu>>(uwWNnbinhL-}~IN6!(Y9wd7
z6f%d-Gv^g)Upt%F+yJz=(P9Rk#Z4x2;aOZo@%o}#6jZA(s6~^-TnF(>;E13WO-A#g
zS~MEX3tG{nf>G7i0oCfOo<O$Hi}qT~3yRTXF$4MHCX0DNF$$^G3k!1zccDK;$;D_e
znc)k$Z8C?Vw5c&eQ>v)n)6?tXLVI-pUoHion%%Os>Td`yi+R^Veq7M5UM?gzna3L{
zQDp%8hDt<2st!oYZPV)mUzHQe)f41$n`8rpsKS9AAeT$Q#o;B@QZ})MN;DYTg@ke8
zyE>3CZbrr(u1PcThC);Y!Vce{n=EoT5Zz>vSMcVOBz%ZAj)=;N(*b00!Mu6_SzKib
zJAf>Yw<DpU;2Mo<xKX`H*Y1@qd{*Fxy%c_{;H$kPGJ-y9@@((YK$ikO<wm*$Tx4ES
zjj4J-n>Bg1tDy8HaDX`dH5utuKl&*W<^}H3CJUQj7ooN~z%Ffnbt-phlf!#M$+eAE
zt}@k6>~QP509qZce=qm)15%(HIn@uy1kTg8(5i`*m0scCPm-L!VR|gGEsfV?r4t|1
zCR!!AZk#%?E=|sC1jD<~RvpEbT}2!_iY;GCg>Q5(#n)s{I}~4&MeR_2O$Ie?o1A#7
zCrKru{Mm(>X|k}1nQ64J37Ki~X7eJ<n{+iHGfhS}U^7iNHz6^N<}?v8RbsNHYi6_l
zc|v+w(|H|u+Z4S%y<7DsFC|a)Tkx!oR1RD9r#g~7>;u!el0obv%NbypeU4NF&@lVR
zy^T7?Te<N%@G+M{-aA|5i-3fUI+q>rnA;}j+BcWNS=&gqCR4gDiuVyR<Wg#gGNn=L
zV;|Yd?ic`VWxxL{6WD{Y$q2@U`9AP;*PVK{@kzkF`)1<XUKjJbqWK?CvXID;vm3~l
zedO#$B9yJ_H@%XjB!%}`36Qx2@;-R?G^PPG*hjAJXrC6L)+nX;BngaBVs{Hb)&XkS
zD%05kYT1H+W!1)PQ#90@-A8V2RF~a{#xn}X?jwy1D9nd~*0m`2k)Indm`kB-9kVSz
zccl)#1oEvf$g_{W0jSaXp`cY0E6;XTR^3N_ZPZBJ$KLS`j7Ga1xSE^rkKLwH0OBJN
zD_ay}arWiaMs}7D1+7nqkc|z9&?Y#Gg*$f$S$#=4t0AX$lxDjWGS0Pm31nN#cLzJ<
zFt^}a9e|ok0p~jET>{7E*&@?Yh&xnSx&uM81?cMdYlrOYh>}d|Gy;;9rTr9Xq1XGI
zl1>in2#7~>JnEk*>%q*2bTVe=Qt)-a4DOIE4y?@%8RPXPo*gpAfwtK}TO3%MEqqr8
z)@BE6aUgAOn^t8)Z7u<v0j${}+Z(`|EzDO|vdz`;`m2v&P%yp=x42cNwFBC?1?K92
zKkksr`k+Sg4%ynk*6e`2oyeN4TCW|*njNygfvnl_daMDh*&&ZLz66&--lNuoEOLBL
zE~UH>fY$7g%No#{P59U)1p44Zb7sm5)B51Bxdj*N_#W<{ab2I(9WtBo)!iYp8MxdX
z3SLIV<jTi+_@i2wbY!2M4GLEF-*$Pi3pMj3iL9Xz1sm&t(p(BYgV18zWqKdP*>9)q
zjjGU>K=!E!w@ZBkIK5p4Ia=^&pc?fSY^(z)^P!-Hbf%OGx=)3-`avc8EkGCxV_yoN
z3gzdHR?f6<NmWyEDLf_|=su?*K3dCGZTMTVyJm5tRWnGZ_GncHdOJ<-0l3T-7HlBn
z`1Yw@&~ij^jmqV6+i)BVSf|_RvL3KtKNPfb&givfA@fVYGY6+^ND`<t9~vLjn$v4N
zGWg-P$rftOg|0?n^$)3&)x;X<;xubOU5qByh|txeK^F?zHQMcBeCUF(riU&FTU+wB
z?`PF%IcMScl-1rRVy5Y?zLXNaY37hL?UKN{RG(m6EL*?5{fR#)(VJL9_j#k`JAkX%
z-o*Q({q_;xTDV(CumKd!r7W~lV_yRK<f(A0q`&}(=2FO|4Bjmy*r)^U-a?NI9D?@_
z4G{`+2Y5p{?hvO_ExZhB$L(SR?YLb7D(z_PbgidSkC%kzO=j7S0#!#LZ;Dp$1HhZ4
zU@ZW8lO!xLU~iJdZIt+%q<}pf7)io>S@}FaBrORu%H7^a83pH!#3hyRdc$UrU10eE
zKuwYgFFMLIR3r-DQ&6Gf2mDJ(BD>OfN#b5KR9|c|!v>sJNy7Z4f=mLZuQX(mAXBNx
zq)>!W!wW3|_}V@s7q^KQQRw;yGzjIIm_?y@oiGYelN2l$0BVwi>zV;bP0|(!^}1wo
z4clm9aHSu!#0Mf(2XHt^Bez{sPLpdOUN%V!gkYzflX?)whV#=vAZ}79fn#V>gDnS9
zl2$#)ISwN02VC19(vVDncR*~=fP*|qxW^d4)Fcf;9ln+!p$=!aORB@k?eEJwl#~ak
z0SA7PAVqK0gyg+($~!LgF9|bFi)!Ga;6tLDbKou^Nzjf3(@6@{^Z*DaX*E88aFT+p
z4N%R8)Ffr6SW3S(5JX?J#-C00<ik4UYG|fRI4eIzs`nrZYxIHFAQS77N^;j$2OuX&
z{J10}Cn@AVuoj(tY9-3X8n}{564G1@TwE0mb3SV+dWiqT3-&;>Uar%r`Ha3e5Zr%U
z%BnW!Y*9d$%!@)gnrTaZ+B|X%0BVwi2XDx?CGo~Oea*0r!)DSbz~(Tv1lSx3&t9YZ
zZ7%Ug1V_>!fMY$p78{b*B#9C@)`KqzfDc~M@Fhapj}K|8XHZUFW{i#|Wjqo}=3GCN
ziuPQmE*0Ybk|0zau|_WylLYbNGUYLA460Kh^~az(b-Gf=K#W+?8h^Hm00~Cp;OeM#
z33vrOYK>vlq+K)&o6@`38%L`T!=T!HjXA&@id5&rF-mWGlZe!tuk|*lH)*~NDos}$
z+!)lFjziZN(3;MJ*8tihD>_k3<X3NH#qm-3vDilvptN$MWjCluh3FrHigX_woCY!q
zRRt-CFmt@GZ3je8lE{tfcLxud1IU{XO~%=vBHg^a7-LrxAFn}0x?P`7Byvg`=Bf1P
zcF9ORx*bhOxb=Y<)S`QfH`S=B(~JQ%st|wyxKEOxXMp!f621e2$~FT5#-OHEB*4g`
zQwjqZ1@L)_MpnU>tsOt8dWGvBz<VW$53Bc=Bo2hCSNQ%hsCxI*<EeSK4t)by)l0kW
zdDX58YK%#>y9qxSlWKSC*f*(mD?0rF4eM4XzX`po@PPsN&n0EkxM;hy;G|||^uU<Z
z%nBhG3I9m~1`oVXlHmCpv-;GZ92PHEE(ycpp<qHKZ_@yfellqs0#)*sy+5gvx9t5%
zmCT5NOR0C*Gze<s-82kp<t<ZUQY&wr5{U9i8fAc1R&c=p&L>F_VPb`>BN-;X?}#rL
zv()mUr9Y{a6&G+xB_sj^#)QUQ%3yv;U@p6UZgSTLV^ZTT*TboCFT9{0<<-K+A84K=
zaXzSUmre(h3U?{b<3JY4q)`CJ<RXS33(w{%URw+UquWwAGdMaO5dhWB5_{}OjmsE-
zF>y9sQ=j%pZMqn9Hx{+&D*x$N)TK*?{c4n8^4q=|=a*okv8YTHEO1GfUwT?cbs9P#
zEvi$64_p$algEL@!|T#<VBzq(6r48}Pp?ZFe^Cu9Y~YgcVr1AaYFH@KMP(}3|3EU?
zBvDMNQ-uPIMRl4eCqAp>)Sh0{rg#i>=^}XPlJE)|W9r7DGF>_ztWu_{iT&izw4oQ3
zX~qy#<&l(d9&y7#cIqIoc#xes2rQms=g~)aQ3ES-V62V7;QdqE&d{?<-7-+%NlHnr
zSb?#qb7yEERJn>D7>g>mZUV-FzMZb2QQuA;1Qyk;A`Hf&x}E+GjXGCh24mqlWFA<z
z)6uN;p#X!i5R05NaOVkGK?Y;tggkXxKsxIrk@w*@c*;tstk_B6N}`%ptif1R(~LD3
zyH$%vw@n>9bqd(j!HOgpn>tvb1Y=VL<Evhz8Vi9FV^akqnqX`y;i==qrVgG{-@HvN
ztjL40OA9OT;1clOc*fYqxAuNtHc!G+M}rO3tDu3gc^FpQz}VEh6A9VJu0!sW*}th$
zr_BCMl{!t&rb?am3dMsi!VJcSLY;C3Zz|NO1H@Lv)b{{U0hu3ClL(8`iQ@ut>nDK^
zFTIOMgU{C4P^u_<I5suvkb%FcQ5iHa_SKamG*BH*hqU*0@E!y*UD7H7A52X-LJ#KA
zRG|f9Q+W<KY&X^C(1zbopF?MY4Nz6m@c6(o8M66zJ-Pm@86BHHr_vlsEIFK7Gs6W&
z9lAa(S?ErcshEM`RGFi`rBBgn4G$UaPMtYqxI21b=Q~yASZKofSLnfTs?Z_3-l;=}
z?0Sa|RrJB&Irq}g#`}}e?sa4xGTEI9Rq+MGsZhsjviqnu$22$y+3QXnI|iB<Ll^H+
zHwsCsJ@3%3iZ~cf{i>jY;ncATIv74RQaSgXI(Bq4^U1Q}o%)qg2*Y`N9Y%D*aH?EI
zCJd+69kTWvT6f4UaBAHOPIy4W`k-YGXHZf&U@F}q(;f*Sl0+AQm*!Rc!Eh>GMIa2P
z;$;ZJaO&ND-VsvqA_(CUaxe-)7*5TrD1_luz5Vt7J9TfD|KF*4J5L23)xtN$sd*8H
z@C>K&?Q;G*kH3md7^s<)B+fu^xUTyfr}|ZZ!f>8!yG(wkPg(H=BU&|SYzH-~;tNJl
zvm(IY5^7U+-3A1dXcw63lIorJC1%v4T^9mDJ*v=z5mcic3GD{*$0P+)71X1QPZ&Wx
z+I1xm*__N3F@iql4#ghSvt7rA;7PU1`VXE|E8yS(Z50KdrJ!Ez<Lgm)Q9Kd^RcL<?
z05Lhe`eMYSoH_u6>WAw(AfQFNf`<oCC`kiHdX>8l4nbYp*~I8f9)>7Y+jWw_txl5g
zV0x7m-Y|j()Bbw?aT`@MOsA8-JpVzBn?VdCO4~Aq;Ymu(uF2j<W~n4`MyPI0j{l&#
zwb$_<(6^=&K=8C`>{RQ`<oOSJlu>ZtDO!zJ;SnS76LP2j*aFRZi6-42^d2+n;ZiUN
z8T$vC+GN)sYHE{he;WPu=4eA=8TW@;n!ym`ShdKAO4_zm;Gv(`WZ54oYDGhgLq)B4
zh;g8(D;|Q+s`bf$h;ew<RYb%%bUB-D0uD9035hjMsdUo`;83M2GGYLs_#x>8aHztW
zqo8OQBEAa;`dM)f<4`}FO!-6ooOiYlNDy831&8VxArRw~f;Qb294crVI!YX>Xw!AU
zp@ue{2@W;1LM6t5hOVpZ2PCW&+!vh1ccuG+voK)cLJn1S-KE!)sIwI^F%EUF$>Kj$
zz6y632dcJ$8y=7#mF^4<b*<qLaHwcahk!#xYmLqdK83ufX`3z#4ppt9Bu1i|lK@EG
zIMlQa_Q9c^Rg}ayRI?0|7>B-S6!3Y9mZMeZ#HEy&O$U#|LvEv&;g%<bm_kd>#xtzK
zA7+EDZM-v>jjC1w5VKL$Hpe{8%1D}&nyO2ISdJz{+Tuku3#`pkw0Z@Kq?ip&GN&)O
z;W#oIUCE52c#?*pZTzHGWn1EoGp~XxX5#_3@#yi)MvbjtirIL4ZBrsn%EWWSB|#`*
zz-FWBZM+YdjjA`}CT4@$Z9`&G>$dSu67_E5`C>Ne-8Livb#EIIy;LtVEfoa|bD)W3
z*(CtAbHf2+Hfm?g>Ql6O|6S~PI&NKqrN3D*7ZZt)KP2IWW}{kX;Kik^YI7h|*$S$-
zB#5rV!fe#pjW+|cQD-ywVm4^()-;*a*iAY8W~16x5XNj&+pS3mYHfvP%yxb|2+PQc
zD!bs4z`oqnmq7NV*bkyICJ<IfVHvaGZt@(SC1!rIJ_H;QZu^emDClA$uInJ?Vp{#p
zxiW)byfK(aA$}B0F#)4G$MsNyY+fjsSrDqDaEl29)j2Lv>+PSzv%`dDIEP1vXF`1(
z1!hcSRzHf%n3aA#DGTjDA2J_LHpzKljJ!9P(75L;b(xS3w*O4MeU9!7CgL2=nG&Ql
z>ZRa|0L0X#;JXFD)TPu#=cNqvqBINh%lm=}%jHry4XY-25F|2TC>_RFOhlF*#aPUQ
zMxE33*o`4*n;UL~FNvKT6JD+RbJO?&JWb;ZFg1-Yk||C2iSh~`3R*R1O(F#5jIk8c
z;N?B1iSem*-o*D{q4NwdVaA^fr<gGGPbf>!{2T;M(AJ+gDV(6GKXIHmLi0`J6*@ti
zeRg;pPe{eq@#P4VcL@W%_?()+OM$RB20bU}#h*AUeJI(we`!ww0CfTu{RH~yATQ}%
z4?sU11z1dgpN=9dX5pVsxR`c~kel+EfI1z9Q%nGzjzTJC!kmucDJD=(mqJF!igkqU
zn|)>rd%sVNXlaZSLt5lJA--Z9FDd2Mw(S%0FR>{td18sx!hohe$2jz#nB=u`L{lSN
z7*Sd86W)arQ=9>dIx)q%zAr~17qd`NCx!;Ou{H)7ZwykN`icAwC%SrhN=J))B0t1Y
zsKkVi<{(sJqAt;GQ<MN_+SwBzrxT{<)}lUPdT#JN8XjE#%t?S+3+ZD3o|4k|n=8C(
zL0v*__$ZTnj)rN|<_7xcsGj&7mM!em@)bTwVi#yF20YAiO&(PYpKxCu*Ukkt=~95N
zxujmb_}s!q9uGbj`pD^#zm%Lc77l-sR0EKOJw~?3xy-fW&Zm}1cT`$@jyeIJ1mVrZ
z3msMopU4JugqfSb51ou~n1Bu)ML0YYZu6rMhY7#>@uhi%BJ!o-LlFrsmk-K`U1Gg3
zu_fBZq)rVTipr-r?>cfH)exVFK01QiO(2U-hDl6ZP#l+mT$dQf<vyFh6dlD$Ok92(
zMMX>$+&hYkm?I$WKr4^SNBFr*%H7B)iAz}7Bp2v61xZX?1s(4?0}LoRmsJeJ(GhxX
z)_u}(6Km)=#8Ny-sl{jF4z1@V?$CTHIzDI17Ix@_b$b{mF##gF1UwZvypGC}Pu!~=
zg-XoI`*rFD=m90=RcypWRmrny_M-6QQ8n_3>XZkNx@XR6kP9@QA|)muL`RVlmy*kN
zhxnq3-C<SoSump`blt=?=s}>w1j6X-5NjyH9rU400F2HK@g5kVbT!I*9wGGRoRH7o
zse*3XG<|2KqPv8*R|zP?7uV2dZ%!37+m_{vym)8xOOeQ;vt{`LS#<Ui<AqbjUSeJU
zc=i%&s5X=<p9MZTg4s=6+g}QN1Gw716!P9R#3|N}0m-CB?!p7i-BY9zMz%2ELPu!1
zS!kh4z~=;5p-V{tpCr|rqP>h1Ku5*NYXGv1=YcF;Y>)u<>@G&B-FDYJ9L#Sgm+}uC
z)hEA{8c>;~3+itZIe#fR8oJ6S;4g>e%O@Z*hXA?H@Bj@uTUxY`K}Vpr30%<Gbdpa%
ze?Ann(r8#ml0f?{naxNtdQ_c!0#S4+_*PW1(s~eCk8F`G4rJ?~l^c4=$_Aq76ei>;
zN{(*H$}T+7Su(N#7CI}?%8ei-++>=eOX4$1M_mdZva&^~p)*y|{8CERcPpb}_*q+=
zpfndP=v69n$$(x^nM)ZpClEtNRn6yu-dr-F0V6s~W^|&6&XN(mHU~*78W5thmY74e
zs?_-efanNCHw!{^mU0A50EW(*;^j3e+R&Klqhjb2>4*;?b+?`COZG9~jc3U~M#cKW
zQs)yWptI=yo~U~NT+#v|g&mR}igOLk92DmoVhzRl7CWC<_eZd~`Pmm|$;igOISWQM
zcGg++d0$EnkS^~_*yw`Yzo8_TjOYy|xwyOcl|gRpxuF7AlORxmC{jLw$UQ>9O`v_w
z0t)__1@<|sNf0Q&NuTxv)aT5j@k0fwNcr4|Ryu;jO?-yWr0ES{^O;AyK4-rf;)Ao_
zjCYJU{0Sd7H<X<!l}`YAj$mywwb5;-Bu^4@x~H7hP->R~;h@`8n0x|oeiFboH)62Q
zl*f8Qx6Li#pxdV0)w^`tl*4-0=ioW4Up_aqouF%%QX|@E<?fzxRwqR0wrS(SrZ}p3
zJ^=?hQ;upR3p!KgHj)LMsq3i;=+BulxM5CR3LgahH|4g5S@xlzbr-wJn@<Ev9OBR>
zLSoO9Nsfq%Gv%*FSjKavtn@+=ohc(7Afl5+&?oRiM?kg-^w3Eo?*XO8Co|ov2f5<7
zsM_fh2J{iEZ91SVXUZZ+A&N_>5qg~$RT=#fN>tg~4vjfq2em_GPWh)D2gXU8{Bs^T
zQ}#H{D@VoArw=Yu8RWnTT?$!4YfibP3ng@hEOdZ`o=XB}ctTY~eIgOj0Vr+)9(0DR
z^h5}qp>#nLXT39Iq$gWi<2XDX0punQm}kHoM^%<H;(b7UuT(UB0`HR)%sy1+kf+*t
z)Etfnr^Xy|R0I5Th8)$v{v4s=Ca^ze2-ZGvP(MTVdY$FZkhzXBIA_35jY2s`HPoM3
zae0RjyXkqhL@o3Qpw1B{Zo->!2EEkf?)bdDDKVh?ROo!dZ*qipo51m03LlJs$V;jx
zN6UZ53;@G(hFsLqun1(9r$6V6_e35zGY(qZa0;Cv4|N5Co*@$)X*mwDZl8}jDnT8U
zHoufwENtZ@%1aH$*%|UuGZV>S(ehalwnwP5Sz)-Bf>zC$+|;OVbw+!~2R%3BrjD5{
za)q87vcQ4D`B2cR4@{TAT@K09WpBf2dAfEZ0-cY_mruk(KZi)M89V=-J)q#aY-KoV
zFNKmp$93iKneg|X9%!Xx+I>jCb2@#}@FAZr`#Mn2{B#-EfaRPnBRi2fM-|Q|a5+a9
zvk45&>6@Q-KyXf%MO^@#OCTeh096-#0)le@F?)*S)r+hGgOWuZ(2Jc0HDddZ>YzU}
zi{l+3$tKF@oi49*KofR(rGd#gUH0@r?bg$2Q5Q((s1*9d{l@{=Y~q6Cw!s>=D3`)-
zF|JxJ3B1qkB9j|eHHQ_`C*V1!%j7O}&XXkmWTOum8^$9G8&^uFYjdB{mR(Wm6REo{
ziL9V5JB)1HRUMT`pJ!AHQ-WLV)8*I(_U3dswo!%hbUC(Bsq%FAwF{nex~i^Dz;h1a
zX%pa_)8*O*Hs|yv))V6?2ijAljUVwbH6VQ_0G>G}E4#2WM=-Q`0C+kkk2jDr$7puv
zedtkj^NAbNW3s7nt9mJPc;oK%lK5O`HlxS;)K<L&jvJZ{1<s!$)fi-)pVDn6r#Eu?
z9iu6Zw0}n>(4U#N)F;tqvoJ4*mCPp)FUMp*1Mu>ppp_GAvX>X`<B!qBy>MxN1O!{S
z**``LdSwE}+lFstp{(wQgnzDCq=)-bY7%L3uLezL+`6k(B-F7f#_)yOM60A9dTO=2
zn3j^u(&VcF>Uo6QT5W(~XNOX7)+GQGoOKBRC1>(eFThO>Ym+CX<f2`?+DFNmi7}L%
z85slla?HdUYR^op;r~><@>Lj^Bh1$Vw&gk2_+&UYt?9ve08~Nq1ys)wxNEhYEm+<Q
zSfSI7<cBJ3hg_fu+YuKiLZG;wRaLuhTU_c}(T=2tGHgfFhQnS9u}0~-BM8?@$jfc-
z$)DuPYh@NMz+FxYv4(PN@=`B=T}}(}F74QOmR`WRoaW*j7^E|u^MdS0rOg+{cZBy^
zIVY!WJqD_;(F}eT5OSBa@RO35cJKny?hxCx0BdP<TQ39r_cZ#g7lAE}ZtF|Qx8LZt
zUdRb_T3OV~>i0krFM?m%BHwb#Tml(ej&F)9PJk+7{wyFDkAPu|2$eP@8njrW%X)ow
z@@YdosKpwg-j`Ghb5J;_EEOeR^>sKxZ7t$jTGuC#z?Rm<Yu4m;ae~rnot!477Fza6
zQVpr&2Q?fM=anrE4yU<h;(<&2BQ)0{fQ2Q>lTy>K4P6M9*1r1G@@h0w7qa_&NZIn=
z;v7j;R%NI>`2yZKgu7aXXva$;*HUJeLcXcYE&-oK<d_dUwRT#ZAlhUBDiefeEg)qs
zft>HAjuT>A9x{9#h=K`0vlbvOaa?j8h(Yst^#)OBK3__H8RF1GeMuz?Jk%?VlQ=Y|
zZ+qv&(VkwgXo5Kki&XN`LA_ua#o1z>)>E7%*0m&}Oq{#4fR2f?#N9AXDQSRXLV&H+
zt3}40FL8229V3tiF0(T!^@~xWP02bSn$lM<1Y?ANSPK;*E(ISMl#sZTdhX1>DJRPP
zToQ$ySc5~HOF@R9S_?LRoG!*WvL{X#<B6Bw!Fb`-cQIdBgk8KB-h5|N%|gwNI40&B
z+s5>u4Uu6CuRM!=+DO>)B&DQjlFuPegM1EYX!$NcUE(x8HuDd}p_h6A>Jo7zT&b*x
zqnRnS7OGmls_x2@Bz#+N)V&lkuZ<UR$h>yuC6Ie=-UwBHT8PgI)iz%!CKE!0T}nwP
zbqmPLrSSVOa>$ng0pT~e6bJ~v!ljgeNYfL<Z#_xM#TTAGxWA^~dZFA;1pU?vC4nNg
zxL*Ahl@s^@p(dQ?=1VEzceY9=L@crCHIgMRh#m?RHD5r@L}*7N0y082Ge9vR6xON?
zJWs@wECaI8C%xdK`cTkHS!6`R#TCJTiUl`V#1NZ_X&n-7VpfM3*Hg(9*_<P5m@gn{
zLWr#eBuxa(aR6x|WRDk)CZZGFwg8<8l|Em9&V*oG3+}}T8P`<<EGc@BXOp5s2@0fj
zDJ8Gzu?~5gMu4Q15j4L?>A;Zn4Nq)@)HS@d5wgDr)L<x~=70CwfAic$+df@CKl8pm
zeLqU8dCc)S3;nnM;kW<&H~X!9{;U7}pa1m%G%PCJ*uVaUOzEK<Lx!pskyj}O7f-0J
zmrcx0C^XYnZHo|i-Ms(i()m`~E~|{^l-yFrRZ^K{P3ueKQ?-du5zOh(?a15U^1XEA
z^SSjlMtKOjGl8{obORf_Rpox*tnr;kvNOo%h2V^##3qbe#U1u{#sp^oNLO@tFuwK;
zVVXGAW)Q>+AO@b1NUk)GUH)7`JZRYFy(90HoNjP>`svVlT|WMor<|@&>Yy>i1zO8!
zuFu|>pXD>h>9#+Ac(b$Z=T%h4tFL9mGx@uWsBYe+#6!i`Qc|IEEv33-sD-48>Rd>w
z@m=dk$tbmumP)s1-Hg9pH##e7*${sIe61S=Kx^F`#XG(0M(HuMZ1$T`;d|jQPM!;A
zD9hu!aOBW^*NuYDv~XTrB^M5%HMMY%5b1l>z@6l%#&i@qu63iR#&_Z9OO0w>5j=<2
zy7`>&J`3lwTx{R(&gYLc&3ylD>js%A!<oz>pqPal4X9<pMx%a>xka+eAY$}4e5@~_
zUT%HNlTZ_c?|mq{c33L3P;%`kmrM{-ihP|RNNMHt3@79aX+OhNL=p<_QqToTI#H#C
zSq{NPfocw+MGN=*6s3ky4$=@<6!_`LeV*Xz5Kt7k?1MPb=QrfL55YvEeqU=FwnQXE
zG@xIF5G@#ayZ})k%|rOmfGTw!pOL{f2=%Oe8_ae6TOe2>gyMwt76Ne=KtF`x1cX1B
z4jWYv!j&cgS$RVMP9*LP;Ws0Xi2`s2PKktX2G5CtZ<awD0&l|P4PiG?gCc~&L=;8T
zm43E!YK6muQ6GX~!tf8FFj1o*1j0P{lms!Db#@3rFcCx&Kwu)uBm}@jO^$f+m#Eqi
zf?uB7;PDvAsbk|p3N=7t^D_AGkhtqJeaaS#&CB4EFFrQ?T{yDE#xWTM31Ta+F)9)S
zAem?8pAc?B9)4yI&V2$}o?6OJ2xy7ZY5-?hr`e#Yxb0j{n+M;6BVU0mpQ4n^bXnoZ
zd<o!spB=(neks9K&Agm>l_E;lgfbi=j_ML11x|;XRu0?-v2~J$YvEFAD(n2H?1u17
z#HPgt|HUO>?6^#f&4V<e&0<qYW;j}GTH%OS3+6OLL|g36&3ABe+;xIRjiK8F&!{EK
z<MRnDNo;5Odt&oq3H6a;*S%5(^M#TYq6SkaWg*HmMP-b7l28)y6m6|Rs5(X8cFM%f
zd<nHGiTkjIxcyM3!b?iYm8tMjax*QSqwNZ^j`%`JEqoIUp1WAGpi%xR))8l@sl_9-
zRWxS+#`hE@hqywFp@~-L$v7`A=+BSI@oBg^z+D<jVQ2_<y%cnSY}Aj2u-RCyXO?Ix
zmTC<uZBa*lte<+H%3gRWxxv;JYbdp~d98LyD+%O{Bj(!VjT5GF8GcOmPiu)UPnc_o
zF;1C_2klEKahD!~Bjj3W-G|OsET}xCG&FebV@(RS@pgE^HaPn~6twQ~Cl(d0Awv98
zC>Q*vN@ZwO@8A;17gg|L@rZ2=ns5!YYErxSq#jfPL&Ggetp1KKFd7}{5NIFE^q7OC
zg+2VS`Lh8jta0KA4Kds%g-)7R4DMh<vVlwC^B{!Ey6IT4nhqN9lqy4^Rc*(wlLyK_
z##FL$GpICSDGj%IF^LATx&e$CIvUsaFo22w*j0uU5HY#Es<c2%Uhx_#3j}5WYEID0
zOG&%xlJGuoa~Z^Aeke0rc;yCtNGRqd)M(xfh}+RfET-Z1Gz7)GlpNd^Q>Z(lERE?r
zLg(E}$`>-VaXu%-+oG6och04^1BLeH2Q-v&jk)w#sI<AzO39`~g+>z&^K-s{eXP8I
zhN7}D-xDa5nsAtxQV%9ysI@sCG;4I)khqo);xG+2_aPjn)#ZK=hWR8Vzfg&>G*l-D
zVJr=`31W6WG*#Q|5)-w#FA3VfpxuP2yp$4+2C{XiH$o~eAw`pgY(PrHq=|efwI1o9
zwhsL!+@+xga=f@p>$i(GF0u>-F_(ri%OTvQp%!x>g`jog7^QuIL<vDEtr8{0kY4Rj
zZ$r8j8JC^_q|*Axf5t3zoWq8;d53mWmcdI&(F#KOfRqao7)mQZPYh{QV19xL1`Teh
zP<lZlZYY#q&;Tw9!7L5MxI-{YLotE?%F<AcAciuITgM4a07)xI)g@pf0(EsM_+|i^
z6>z9MNm=QQp)62ouYU%0%>yt>LuRtu<~-no6U0#(;Aoe?iGW9ROw9wdny{8u(6<=#
zeFZr0jS1d3?+IyX$io%{S{ib-g}|1NWkR<Q*3wXn{!%zb90G?lY=>GCl+p@B_#_Em
zhS9QxE~pj|gEzr8py>u~f-Nfr#L#8YCDe4|c@WHA4iJoY!8V}jgwM25P?!)t)9_ai
zo@w}T2%l+qU<^K@)>otN!bUa86?$<rJ`sn#(e%Vpl!?W(0Z2^<i)jU0jeaCIbYee}
z8+x(JX^eD`PxK=`(2KnU`{+bLH*G*C_K@IEiipmBij-p!e)CdtFv4$M${kD(am7)w
zS8GA_bZPJb%_%3aVS|JKoR(WCgx)l4vgj&}Zb<bR0&v>cw^e^(bi8=Jlo}mQ)R&NM
zEWtD{r39D$9ykgLrfC3chhUmEfTaoIG%Y_x(U-;owJF@D;e&Q5<PFW)7vTklPh$wV
zY4!CC0XGdPT!XmHOQ_c~nVrE3`W{_+9z_U3&`pEFh^|YE0c|Oi<ztnqHslw+gkmmD
zJ)s=wPQQfQI-Pe<ms00epe$|H?;**AW)$Yq5a4hr<eL|VUHN-#;^MGVkt6kQ2y|)4
z4;%np+Jx?uBmKFgj_1}ZnNXfzPr=#n>nSxneNJZQ@c2FXST!NsrXjK<gxfR(pG0rs
z3;kM1hzF#4tpu!CSy&+`ry(nIbbfY_w>e<u+@(-O1HxqJqh>&uK0Pop!*q;Bd{5Xx
zD|d~_$VaN{5RTK34?BqCyoB5|!f{^8edA9UdtABng_uySf^c3+zEYEkKcQUhRrJUW
z9>jSXa)*Z!3mOUqL;^hxDagZQ=4YDnCn@9%MQSn)CKRc12pUdBA+)DW`bGu!w2D#-
zp*=65W?zOqLfgU?TDiOm^YnmJlg$l};sGJJr=fa42<~|)`E|vq=PA-k0vIF0FA@=I
z3(8gL0S)&<K~$(M`dCeteMJ#o0{KFf+7KJ4QY8X3oR>cfLFW8|zEt`?Ls(=832Iey
z;6sr$kBR|L5DscpyC4JxHTVERU{HgbAWYUgTnSNV&<CW{GiKuc(WEA89{!3TTJ#cX
z)ybM)6aHT$12jachTx)B!K`6&r7bvE1sJsjy~%7`Maoy(WZ<JrKmamoYv<pT9C}gN
z{A>YL6}sLt#0H1JpoaM202tINzBq&hHH09?iv=|l=ZL0Fj|v_kFsPx-M+gjR=|t0Q
z=0fhkXs!`JD>gaG%2O9Yf*K;TLr73V@b(ixf?CCQhk&4$Py^VSe;hjn1vNMuqb-7R
z3?9i46x8w_F$4rPxHSVnP=nJmn$864aF9F`Y@AF52ECLVqmBd{nzg~)-#BxYM=)jE
zmQ6eoh@3X{$W)^OiW(fr(PZjxgG0WJKk*^C>jV`w<Q51*MXj<AL>poQE!vbM*pS2E
zlE}LY5P`2Qk|Bh^qqax3$e4auLPrgCh=S13q|`dlZ8@C&A@r!#tw1!D3bYMH+H`6_
zt$+}w)KD5AniM<IMsPe=g$P}08%niFTcadY2w!?BC9F;fdjSWN_|n__Na})^8g6%7
z5L3eikRKf!b}eT=su^NP+3^K8$txrm!qkxW!}ZX}-|OhG{mCY|mU4B$OAQxeex%TG
zZ{`O#WR_QNeqL)Hmvb&Wsa3Vvq+su(XqgL6YN%`Gb*b|d<w70=C^ZyFa{)>(Wu-9E
z-<2iC1t)#1%J6<jH0p7M>B5Ry7K3vkMGf`hTu4!KE7QaU1-+!=J-_f8yu318@A{GA
z#TBq0qR1?>|9@dTko?~P0ySj*cL6~!rKaue15nG`Y1FK}eFkQYS6-J=l1q03L*eJ$
z+PDOFfk(|}w#ay5fUy3nV0E_17^>2R9KECjpd6|Hs(bCijT#ClUdlqd#8*_60X=X@
zeC~q$+Qq&<Eg9m-apl65nnPJSfTe~ClP-*lp$w%HSZakFa{)^Y#VkF}J8iYZUC7c)
z$pHyjdMUX81uVUkm2EoLy$+gAT&V%o;lh;~fFB+*0Fcbzg)4mw+5BC=(n~3srOf?6
z<Us3+BIDfQl67H94VC4cm{LRac~?$ALxp-zNU2rvdJlm_3~(41tki&qaluLrfEW*%
z>p;YK2tRIsAA0Dd4~U{C)YOn?&IL8K%tGfvnpzkKD3c%A>|97wL$zBM($r8A*M&5-
z7}=6!18+m7Igl`(FjE6k)P*xOph=yH{j4(eKS>c2OtoxtB=2|OOfMy;TgE!d3O}Au
z)7z}U=(vwzIiaSPP&2LLeynWK)gKFE>0+`l9_?*pYV?qmj!cfu?0-*^RubM$C5o(a
zfRUXbQu{0_7lPCRrE(m(01c@sT>w%;I!h0k<j8q>Ddd~_>;mlQi~#QDlE4?LPbmcr
zz#Dg%=)m0wre{@C`?j&!0?N^~Yq48h<$Mi0+LdL{h|h7M#jL&zF0_~-<){-bW=QMr
zE`MHr>)e@o+weJb)$KKWGCeZ}TA^(&dKF9ow|VibR*0LYNR2<rH>kvd2F#5o1kBF;
zOWP5M8+S!q8dQi2C1$B)TqSr7F%Dku1<7h%C@{->wog(pgMi(*U|<H=jSCBAz}C1B
zg?6aI1o*Oo)41{h8t^o(e1L}h_n!Fxt+D~TcYXYj`QBYN@_|NEM!-v{Nz^U$S(rpc
zTH4v!BwHvs?`YLvWFW(Aa^lFWEUPCeWLqjuKr(~L<}N2XvN2x@whk~dj|)9!uoqqU
zG0OqVMn*P#ckM_d!}k}6Y=~-d<pMMqrp{b|R*_LI5ZWc=+t^2+D!^%6Kr}<{YZnsD
zkRaOyMYBZRxR7Xes0Rr}GvID6fy|)?fkx|q-MHXry?{6V!qGa;7A^={uk_+h2wF!5
zau)`zBa6NRgLd0@wQri&myjEKZ#@($O}PO(&Qh-2fW6_0#(_lZbs}@62JASs`KEc@
zajJ76);dmpzIC?l2rhJi)_NP+B4emZAl5o?ID$7Pr8c5aYaORs-%Fea#`xW>#`yM{
z9OK)q)a9O<tBFxgz5ysq;oUm0IG0j5eqeDffxPRP<O_YdhqyprDkouYs8i|!qjeN7
zaOD^5NREFgZ?}@AOF9@@4oq5ao_|v^9P<Q8yOffSC+<rr>Fj-r(3#uBxpbz0YaNIj
z2Xd_=de}G5+fN5V$C-z)!}a9b#5+%vTR?WWxE$!U-cTgnm8Y;H6~6Drr`9=8z_bqM
zn=1`ruaNGf0Q=M7v-8E<xem9UF9Pq=@8`m%bwGD~QK3H_;2jq@tpmGrDP&%wy%fZK
z6n5tl$eL$P0@yAk-~9@4hpt`hk&AHgwBF%o^{UJHfV7f;XX4PQ{Dd7<TRxO*)p>Gl
z$vG&Nf?5FWapfKCh6Cl=dMeJ7YiH|omaLMeB@+&lf~9qMxLqj+JG|hol!G0fa$iE&
zbfnYwwZwG219)Ujw>BKxPA0Z(+nU(6ZQHhO+nCtN#I~J@HGk&8d*1&#=j(lS^{!Q`
z)++7l?)%=m%GKb^vPpi*(jr8XhY47})jO2+Tu!{0C(;wh)TCc03<n*c8n}L6DwwfD
zAehot58Plxbvf`0A<BlIM&2#pxpC6UYtu8wNu^E|Jc_5WvRLqR2w3n~4D?9&Awl!e
zE)5_2sbtX)H#=Q?(_hS*TdRf~_^Bl$#rtq<;gLTZJxRJ^pLtk`h%tLUJki*7WnJ`4
zS>s8es%8v(F<O1CxZVt0wl7WWM!~UMQMt|)6GY;^1<;Xai{l!^E5rqc9!|@yHDX*S
zXRX5TrX}LyDd2`p;_~$r{D@bBm<`tMF6Vef`;Hw>^Rkv*+tx^;Oc!mQmsYVe*Oj~W
zqB9rea65o)Y670K>gmRo6l8_8jo2v%I!Mh|jWKbT{g-ab88vYHa7?{7a^x1kYM^h6
z<UPnmNN_K32tH}Uv_>vFEB$P0&)rpDHe#r}Ouf{^(7b&cQ6D7>uYty#i{@PY4`_?Q
z$g5$+WA_Q4C=_U<I9EIf+`KG2f&2D>dYt*)vie#}fq(2%CanAKwkHKYj-##a9FUu7
zU5|R7{uqAn!814Tq~HI!f)gsdFn%cxd8D}2tg}d|jo%hSm`b~#34StC>cWN36+`Xs
zTHv>O+s}2TGm4E~Rt?;+57g|e=YpNq!n-r&dI)(j+J8-*y&fO19qM#fM&Y2pO-o{1
zuD#PLrSXE?5JITrya|VqgnYIX?>HS=Q0D>Yr6t}9=NAiox&(M*zc_aZu+NV4n@5E5
zDhBT$1*dE3$}jGVyaG~YZ3-1Toa#ZTvPYSGsH$2AY_wNiy2R^%zgqg<VO1Buz830&
ziO<a2HsP0d%Ru69c(Z0)*rOE-Z_P9r2+ujpX#uATwRGDCAHRmfP6O95O-I63GJc>V
zIdzI)iH)XA){5?TgcR3R4W9*~4%BLx-7dNFs1;H3+KLmo80vBq1m>vR+Fg_o+kvjm
z<}LmJL~sVIS&v`DyOkXVdn}}BzqiBY_IR~Y!rR2*Z~D-07nhT{3GTg(L;ek~uJqRZ
zW{#Qgq;+mE-Bc*K>k_o_w&nvCA-XWZI(JqFD)s7F)I&98CI;qZD>erjcB$FZHsIaL
zP)r8<Lv7>>k&Xd$wzB0C%cE@Z{vo&4o(V0quRZLfZ^mnQu{H%U;j&nJ>1W`%Y>sVb
zea#*{lk5vT{xg4!7Sb#Kp(BzZCZNK1J)fn!S2yfuMQQ*%0ON&cs(B2#rmFcmT(&QT
zc<^eeX`;3r+67GC1wBa?sufoitSaC-FXHm`tAHeFriUQlBZYcCK<AGQ!0ub#?eqY!
zi&v$|1%GWks3MooFK#Lv&%jGr1aA-OWBDN&;A~iVp#|9G7b;12oJk*O=y~5J`>q|&
zcQ#sjE%38p|KRhw!0sD6c=3mhqF!|7A^`iZxqa&aM}0Of`;d#%>Pd>gw(@ku6(oJI
z`#dtPeOSA$sYgC&zLOWS?~ok{=239NZP^5TZ#bC!oPVPYa^NRmyFCfP#n<_6;thvd
z`>7*9SM>T^62SeAVD*Fa`&CJ7e*h`-g%b#EyS$~hz>IR7kVH#kcyp*?d1fUvoXcS5
z!;hi1G3}NzgkZAszM(IoPwV?DP@1!F3<olTOHp4hNCpD*D?Jl}OV;LQQIV=qq;&pq
z)VkxX64{M9c*>BqWQ>wQNi-;RBsAO7F2#$yLfIy-uZ1pwWp`!^+TBtoBDW6(NgB$H
zO_DTLn*quf@D)QYI#U#cBM@V=mc!rKM)7TxWbvfw?dRr!q~waf&DUB3!G-DRxEdmq
zSpbc23lUVwdSU=&nGy;owEiQU0pfV*0aZjl7sBy7gOX(;pcae00&zb1*pyRyixPCt
z(ECu?tVgxiq|zGTh$D$0cN3GeEXM`E<~UjYaT_l5%m#!<?HOWCHx(^NaIRSzT@K=%
z5oiBN&i5|3ICZfeui7Yo7U8T}tY&-VOnd!F+WcW6<0xqw*{Id8r4!<s7zAi3h1Oe5
zp}G7qQirp9vJI1Xw`Sc0OSC18r{e^4uH0>3v6AF|H)5sv*9}}=|HyVeSbU<US${Gn
zkm<^=QWN|d*EWnl#yD+Qy38y0kM@NGsDcwnx7w!fNtG|;-6UC7!sE<ewGasB@B7Ka
zq%-d<5Q!2OO>HZ;+ITVHoJ*~OH}kKO>g!ZJ0>~r|tT6I<F-IeJ1e3HS$136Z3CuHW
zhB@<@EAZDLO9a5P4w7u@fZ67YRI+`hNslr7na256AhXP0r4iTyeSe>HmOLlKP(M#Y
zHQ<=vXrmf=mh`(C({)`YWSTV`Cs<fKFaUfSLqjgv_jf2CHNQ=xd0u!VzL}ZsgSj%T
z>wyE9P<86jflTr;R>VUX<vs~Qw+lW(-i}wdBnQ?JZI6<MR1p!4@luMc#y1<`y>!S!
z*jDmeJ$ZnEs~Omk5_bhH@M${hdg?6L3ifl_+&!u5@{yCaMMR|dmj1%ed_ikz0Q;J%
zGBy;&vl?S%rva#}lH^7L9Y~!ELAnANZ@tKiUmpSQ8i85rl^-5XAx&No?s7e4e(lU~
znW&GWnZ^8B%0K{p9>*_E>PJnOg2$Va1PeYYVAj`4JKgKoB|UOLnDCR1VpI;}MREQX
zt77X6c5<mjYnY&xU+0Kr$=)#49*#0{+N%MqAO^;G*45C@W2}!b4SUz~#7_Z5u+>hP
zTf~}Pjo-!+><GLeRY&8-K|RbX39Z0?oGLKu7K^kXIXe64v^c;$+{j5~qRLm|Y*YcV
zv?vR=06#YT9SVJG)1%`OjIvzk)l4?@JRI7l#$J#2HxEss{keDDhsZAbDWi&?kZ?Kc
z>=fNip7su`->k|I$|YY>vrN3r8eIFeB0qjh?klkkYIt{&R&74ht$%*A(DEE))M|b$
zfFA?b4JrV&Nu`;USVaa-h0S6-FrUN&5P;(b<@Fk1@CHM#kE1$#I<ueJ6-Giy;F}*a
zPFFFDzu#(qH$1>(3;{1NoebL;K%doO&}A7+w=!}IQ}n6m_Z7IHb2w{X;=1j*u}-Ho
zIBilgVV4ol<S6)EmG~8@at6f8P5<!Kd?`{r1D7tShYPEQiQ#Xv-SqPGwv3H%?6+{%
zcjIQhBWa!3?dPrM1<y&J4wt9EABSu6;82s>U#k@Ky-$sTgB~p&^71ds0t{+NS~vU{
z;FciJBxhgt0mC)vw8@rqx7F|Aynp*eVBFY4w%**SPhfTY2!>|T8F|}(lC|;+uI%;G
zSF<xiN7G@w?ONA9l_^qULFO!Q9l+kt2$9`g9dwnr4jAN-5H9NdqiM9_jOnq9X~xw6
z_z`tGUbs9{yFiJs6fTF~6fe=ws@k|5X0FZ;GZ7DvYWzLE0E#)xcs6aLzeR&0S|XFJ
zPJbBt>}W79L=c0O{}?&D29V3tR5d&+u~ZRkd@|)``@A|$TRT;g!$fr%eJi=<I~s(X
z>PQ<JOG%??-i_0Pwm3JAHkpU){xx8Z;%PRlbSh0nE()`3B32Ar(vpqZRjh<19}I7Q
z8nbKQKK)U!%hv<jx2}_C#kWNAq7hiWO;p)ut%g5knIQ+Wih?k_Dj3$8deTLPt3j5g
zN+=(eqQeJ_s7S{#xHTFK3a}{zy(HUG41=&}^}gl1_*)UJ(E3>i8DO=n1$K#$7vBY@
zSkW{L$^u#%)(`a+IL!*f^1fqmL$bELm?ArG)uG1`avNP?Y%t2W{!~=(3kTpM5pf$2
zGs`VlIOVSN`v4y(5gT9eZs#VcAd8-G#Y9W!UN)c+SwU%9GjfN;4X^Z}F!+TIzQNo9
z4XjgeV3SUmmSRtwNitDKa-*&=s9UvwE#VrIpzJnAhIFPbo=#{HXXYW*cE%{&B=J34
z7?ZV6Veq9H>sDj7ulzwtNXJ5s6GRiJyL8Rof_F~7H0E`9iB(VHCLkwU5{@TTmLzlw
z8f<eRV506YjS$90DIDHrr(11hj~>B5;m5MU!fe|XXA4MUv@KOaa}huaxW@#IgE@P-
ztaqtHib}G6-*JIpO$Zu`!&%#n!jFkIbaj=kRFt^`G#yFM5*B)0g+aJLx?+2(i8xs@
z;}Zt<%@TFUm>K!O6<RQphDv43Zry0$U4;qSVOi~>cZ?I7))S*DaNvFtW4}3WZ1H|Y
z_}Xu-v@p!6G~**+2@~2SV#douFE$Fl3Nki+)Ik;L5>}zZh>=hfLZRmfB!Z#m3QQE}
zf2OO~7_sOy+`$H=CdmU%%vrdbh`342iHX$87`9I^T4(7Lhn+b+&Q!w)(Z6dFEB0{q
z{?HPz{$9(7dIpoqRje>#WeIAG{yve^-_vg-f#{53d^aNqrIdmq02~xAg_w-t25QQo
zr0GX6@uOB<<dOHbt5l5_Ojde)c6G23RbbmrCxbA?<_?pbK4ka8c|yJ_-u%IdCMK$q
zY>-(3@-YG?UQR(26m8^40ibth9ySKHDv-$d;mG0^G(cLCJ@)(cCA0JJ?8s!9`$QB1
zulx0MRb6_%K5V>+LO@IOEH~=U&5J5V+<3&ST;nvvEL0(vNO~lZWqKmcUtoTib?WE<
zlVMX@wV3hlyyw6~%v5<*nDOe%K$B1zWbk5>5L3U@aWLZDSntKKRf^P^cIs%MF~o8C
z;52P8Hg^z<G5wy^(E=0`2=j2o$tWlnnD&~lz|&B5;BzE15Nk#hY=h40b9OmGO2e8>
zK<qb==z)XIQ~WRy-`mORj32gQNpK)`4JE+^pVP4J$_SU2L=i?V0flJiPyo!L0IDYd
zHI+0d`HTH86B|kin+~A*@4&U!5bDLy%f1nK-p~*B9Z4W&l19bWl-#<Zwk<`G^PZvi
z+usNeMzE$J;in;HoQqrgf=AtO-?sy3AEVhX4@J}~CSc)Ua8c~B!DVIB2q8Ao6g>eQ
z=hylnXNA&kq$6jCe$B-&EX3@w&?1u+K-FBlloXY8e#ogJy=>sLk$$$av!KA+5e1G(
zL5;g<mchQw1}jA%GpPC&3ik`ZO7VuaL;KQz&JNO5W{*e0rgImq<WnTZSsO7gX!Aai
z9*|`~yXn$zG!n?Nh|VW<hdRk&lLqUV!0DY1gnqt`MKChR&TmQ+Opy;{I$nrZtq^Mz
z1LG-+>wS84M?tFJucpFl#@gAyJ6!DjCn0MIw=$7+JEP_xYqf_@f|f%)ZDVrlT=y)m
z$(PQ_&py!fs~SW?U9%Wn;JYq?o@8~|-CskJ9$ddyzUX9vi;d5^kZrgKxWg(PtwUC4
zi;;%p)vO|n&!!*Xp9d)?JXHg$h-_~ob@js6xDr-Eye~mkX{&5PR$-|5Q?9Mg)FCU6
z{c4qsRps_Q4^n6Ns75w>D;EnZ7srgN<x>9nqZ=8|)AL1{4sf>(8J~ywJBYZd0pgEB
z%gZguSXuU~J~1+he$LxD(An&p6NhcC-MQ2h{_N+INJ<!PP;|j3e*!Lq4rGGJd>8&D
zDM8qiL(WY<Srq5?`)r$<8Pk%J<Bs=-&;2aS?7UN;HQC83+v)EG9xU2DZe%8;rrVqV
z^PLw)-_5-M9-&2Mm7Fxs0c4iJ^X5;T3+zkh&u3nHkTtUT`o$k$F{&f#<^)QY4`*XV
zXOR@Q!Mb%)O?ksAYm8sWwVXZ6S-*bGgTXm%6i^@KrY;bbbj*4nsA?1JSkLZ1NM$3d
zp>8gL`7Ii61j5y(x^kV|cF=nwcw%lWf#K++y2m=WX`g0VeW{*h>`){1!V1<4F51lP
z)Gi>@tr&j>s$DSt7NB;q-iGxUf3(_$HK@M@riY4<IpTvDB0ct=Riw3H)vVY}?*RyO
ztHNkw^&26j^PN>>wchbpP9mffki-0LXN}N^3cfsCwFg;=>69#!2|5aCAK9cHXL*I9
z_de*NIIi?<&;{g2GvE%ZH6YAhi#fa=LaX)Y8wQBY&_uJq4yzRq%sW@8$b#rv9X3|}
zdI$=>)3??at64=AE$wgoS5PnR{7Q82gy(BTxmB|rDxI$s{f*heZk{QxiF(#G5%+<Z
z7|Wz_D{f;;r12{``$-bStXZYfdv)gZeBlGb+CA#>Frg3RkU1qW+NAX>wB~xsgUA9K
zekk_fwn(9<D$AtWTV%FBi$*3i!B}^1GJte#5r?S`a_`-e!Ny3x>-0NVBOS{0*IJ`Z
zo;UQP=?z9xA{@x%CQBr>9yc;V{wld12bn(q=`Tb0Jai2Tcdt-@h}2K#%}9!<r3!C_
zrgNUrkCt?{+{m2<Jg%#SD_!tfTsuHqwO`{e(>A=^$eHF8O;-(1s=Y6T7dE!oR}4RR
zV6c<%&OfCr(nF^Ov(w`*Lkn6{-tR!+=ajx45${fEeBo=~_8KKk3qhNWA|3GjfL$j`
z*j|IRVxcTdb8%JzkwF*Wc@=Aujh1~TRnoJgbl&1m!?~DRN%y*tdT!X-M%t!@;~-<V
zYlND4K+&gEoml7?B(hpCWU)XHS@IeFgwBf*X%_ol%fY^PPok+CJdeJr1ePEcp?8uO
zPy|8MDRQq8rzylafnq<LEg3Ij9O>tiz1FM_;1t}ki6l*bb#NVJm8N?MMZNc;tXUkX
z=5y+#hnl9#`AtpOJfxvnB(4Xmc4&>TEoTiGz_m;mV^jDy*$axMQJESnYFiFxgtqXq
z;yPgDPDNd7%L&JF@M#8d$MkUm5dW^?F>oZgSA!ZII$TXm!s2@IbE{_1uEoCZF1l4J
zMpnLcG<SU`HIw$>b|Tkj<c+7rfG?nrTs;Lw8MW~Vw_l6<M_+)rX9Oo=^!{FmZ=P@~
z1H@42B>PuThA6Q7vhe6L>pV@~W>uMl#zh#m5)o)A(8p^$A~4FU?O7r)$*V1iVn&5q
z1ImyIXkQHxPeL#pq}=YqFTMy10xft3c_fUYKsj9v3iQ6+py-WEC5LH`KqZH>44!{C
znBuj-GlODxe;+2taRp(kRxqr)xM5*R2j)77FykUcZ@T6i8!(+HiVea)RM89o!aDS`
z4j+Uy-5CMso9pWt_*x&d!8dU<v9U85i-r}oa`|~M9fWnaY&|J7OZy>=K~`;wy1d%;
zrf~Ed=S*r=2*2p~M(Qx%4(6R|<ND7k_ahkq+n~DPDGpmTWoyjwMH+8MvACZo$)sCh
zx*e=LdUbddm8UnN0G8a|zd{H-OLf;dBhm~(%N|9e<`)5Nh1*5<@4<3g=2*Mu^sRex
zw`rH5i#q|gpuoOSPk+l+uK(<|!AgSYgxm^qj~27gRNB<FicnjE=-7fV;Zm6cgrsDV
zChVRTUB4HtZTvEVIK3vZ-2V-*I@#VMaAwskbL+&hMbTpZ*h)jwvv7XZEL$_EpZSy@
z!wU8T5hU{p-kl2HD!NuzLj(k=@P~~{I-PX7ig4ZVhfJ8-Su+9!%GW(8cBWF#glNRp
zkeWkSJO<^fRtyGX7H4&|0i>s<L!gksSr4x_!sH=SDONm$b>&xi%p#-MGn-RYy?4gZ
zJ4flc$xqBEtV_2tF>&5|6W&tt4OY4(ZiMz$b4u`Gl2o{XTvzqhkX#Ma^~eKVE=fq=
ziIVEkQcqigKCncIkg0bf;y}@We6Zu6fUq$z3Ere0zk^J{H+}6$3n*svHW~@!Lr5+L
z^3>H@*3_26st_)v;XHXl(hO#z^aRp!GKsnW{V^q}p<(I(S!9%c=5C#E=N>mkDkHxV
z2yXcMNsV8i0}4T7Rb>uAL}spAFOVykf<kO<`EGLY>oVwJW`<UIg@K-xz*z+}ux3I>
zLf=u_3KkUndD|-%e%<ArXtr9u&$yk?1q=8-xv-8SLX6H&67=H}@$c$Wiwyvg{R!MD
z(ugQUYTVK;^l=8K-0qQg%JQRXwd_3ke)Tbxqy2vMaIJ)BlMmu^KG=Iz9Pfz;##0mF
z5|B}VUPTCR7j`%Cgaf@E_ECcQ+BhhM2)`!#8P|}=LzCtS2zvt!ouuT~tjERa1{71`
z_e4FYi)HR78b@VuA{?dG;}=O7*{g`orNVNLRIB53?@EZ=rNgq1@Tr3X1~{{>)l%2`
z$4uy#Ds@LIy(N<U(~o%{Qj$2)B{|9sQrI8i4YI8q1(DN<T?hrUm`7Yh{E}Rf%CJm&
zk<Sv9_Vf@z1N%A2g$Z8M$s$k0Aw7Y1!aa}l5Q7PSaQ>tV7B|e%r*=uN^GFW2nNu{+
zM|uFx30FG;<EAqC{XKzam+;Y6;Ec^u$UIfCb8OQDT-i)&mZec8c+}jcb6lyHB~m~o
z!?2Z(v^4=+GeA=TnutEgK-M`+j#*gT5g|y>iy2&qyiVCAiCm0)eu&p(GQY<^7r&4L
zDJpo>)W$^#F%hIHYs20F#AOx91-LCsd$TVT`sTHpU4THPHxLOW@ey87UOK%OHBZ#q
z2p8dSf=k=`Yh_K<nV8mK@Krd**%Yl{ttAFh%w|A$5w`UNti-4_fSw3}OxVM+pdGO1
zDU7C==r{Qchml90xTqs%5WAuv9<n=1piA1+&xcxmr9%o=kjL<HVB?W7F><e}eK+Dk
zWJm0RpfH0N#gsG|(!|k<=Z2U%nf$M?Pd5K+i^UT;g0&SM8Na2~1^2IgUkOZF@wb&i
z(l!IUzM~p0!Ajh=gz=5Jsv??fYNp(f5<Sb&J5}wE(u5$<aT=I|s_9<^he|5;fEK6i
zton!UdEjU!#q!r1;E;s_wxoJ~$nXH>NvdAOEUJI~8CE)j&g{p65=nd@gbjW+h}kg}
z!%wRsdXx*JKFUJ{Z8wM+<zq0qXWxz{ORMTMt)~PK9YS)<LIjsE(9tT8KXRa>oQo&K
zz$p`EFsc|LmW2FvH9NI>vqTW$=-J;-7@?n05@Sk<0v>86wc;A>EY+q|M)ZL&X9bPj
zJj-_DmPT4Z&%t4GrIsDM*Ukwc#89CGx696=gI@&H%<0BY;m;5V-XubAGV5m}k@DEf
z0?R@lEF%P(WP|u76NS@YU_{$P(zyVbolSt>T_7e3-yVSfyQu7zt=v7-+2#3bd+@7g
zRcV=eADiYu8pk>x!39QeTNA09fIzKA5}d;ikPbM1Y~pPE%E`CjTeGQ6X!1@gtnzYT
ziqY<U7Z-By_P`z#N!%;c7-nHiM`3E%V6z9EJQom1!<?jSc?&ymeKKKCNBU+#Y5ME0
zn|7JOSE)FotAV?dq&E<&SvY@pD=n|JtD<!vfKK-JK$;-C*4eiBMU&E#yi5o*gxkbw
z9Il2hAEtF8R8Js=kR>cMOL6!Lj>N1R=1cEx`D=dsGy-TviC>KO<P|=-^WrF2(E<ly
znLw8`Padbfasv-Eq8;(X+H-IZ<s+v|4KzWXg*Gd?--A<;A$M*gi)Zpkw2lSqcEdE3
zLZbxq=ZAo0=)f+TBNtr$y6T?x965T(cQsV^E0OmcUjQuPr=5$)!3j81W3_))U=3#B
z$4&@LtO7m4RA~DRALbndS*mMCWg&!5^tV7dv|;1z-i++x^bv=K!_D-Tlj4tsDuEKW
z_c^e$BtiyyAoH%6nX?vAcJVB~ViaZC;Y@Ifv+ZgS1v((pa>-r5EJI;NW!mYT<prK-
z5C&Q!7g)bwU=&Zfz(grvaDs`IXO{zRASGH#Ib_u=!_^d(IujLnD;eAY7hn;!*4AY}
z8k0V0od<>K#gHfx4^4o}f(SCx(S^v+b5{nEARAb4AOUY6B}s;kfDW(GiO=6@VTZ75
z#C!wKhdGF`gxoFtB6>OzXv4Dm`VQ>fzZ(it(}FXRrul80uU*6=-E;49cTD;MA&H#b
zxtl=Nq7~c--!;LB-;ITrH<OfihiSw}_2#Qp^FnX+jdDsRyhbE6lbFkjN{MPjA>d8y
zwt$?d@wS?hQ>F}@LndMlFhSYZV{a*jMI0vP5R9qmT%>E8^!j~AsK*{mr?1ZK&kTnO
z_TW#V3s}*}sY*vso`_E-wyHA(s5a9G-KSIzb2x0Pz%|fv*Y1P5t;W7clgD*D&VB~i
z9N*OmT~Udd(Cz0w%E5Ifk8B?>h4<{zWq-_PK7u>ulm4VLWAtY}(xFb5NBcEkk4Zba
z<e-%XUCi*b)&)__;Cf*j1fi|-h9?$rLjzPxB0S(Qt08DU*{yIN#F%dDUpzoKy@<A0
z>Hb{+pxRs;mQdP=)={^0UCd{xKGKarV$|+{7>b1PX;K44(y(U&*tudRctU}|B87-p
zRIM2Rft99P)xYk`l7RYVV;cDNp?P7*ZIk^+8DL+vxVBDxfK7AK#fJSl%jnWw2g0}1
z9?UQ`q_4hXrQ44XYxIc8|Jp=Ed$z4&Ji2w<=SsX5)yRrN(JmN66V61M{G~k*16k7N
zN+c4JgwM6kAf~MXq6t-bqCYG=avNUWK(Kv=2a~~`!YYJlP+Cjz<A+$+fq!j0Ng5AQ
zW-z(N^o40Z$cd&xAtsh?|5@=Nu;8^7WG7$~Zxt>02x$`1ra(QUiSX0GN)TfK7dfl_
z?wf)bs2J1=%d9Fk-AK9+IbO$dyzp1Jzp@u5m5Xs>DfmuXyCVkZlDf}sl)6gIpAL8}
zwV>Fi0yvRcuH47irXAzuYk#`HLBS*@VS&Y;87`%ZU1!n)!UL+O=0p#FwM%GKC8pdr
z=&yo|&c}zpI9NOb57)M*V1*-=6^g(xiHJjpK(GXCQ-+}jH!ekwfAMh%H9^>;z>WoD
zOtGEtGdOh8ISa$IOmh$}B9VX{n>n3b2o{)s=wmG*Ydq0(E-cI?$lwQOjF8ZGeH^h8
zg1c0)86;1zoE&HrIB-7Fr16bNTx8R7zy+>mSTulc#Uq?T6YoepH+Da`_|7iILKPvm
zi@t6}QQQ^gFva7UG5c`GuJ@w*c<VhkUhxTsIQ4+zW|B1*=Wz`CBfPI(40sC)(}3%d
z@+);tDl0)>uH!O*AC@rONI-6Wh89Xb^OR~?%!&$G6tIM-ujg!orx-gu-)R_hKV>6F
z)pC+o-|H%Z)Dp0(_lOq~)T+|KjIxD1O%fB!*hfIFR3$t>fUhJHH}(rzL>yrp{BeeQ
zekVRRw4L;Lp!eWXnEI@W)07VIRuQO%EJwehgOZB>Rzc=Yg3#X__zi_n-5DV)0K0N)
z*qV!`2mnANe4v&1Sc<!fMxq(((p0L&KrAe{SwxeezK-*RQUFOstmax?ei`mnvT5vE
z8Qh;FiKC0mn`E%}EYA{DsKuoTolqAC2PO4D*BMC*rP^7_K?k+QSxVt8f7cHT*V>HV
z?satkEG+6<#K{^W2V276;;(XHMT0`P5UsEuixU2bft86sM4u{Tpe5l3tNmYbOK6KI
zoMJC@)R*Q&LZU|%zHruv_qCY{h3%S{I==j}TAW%JX4Tf4*XN4Vvis8Cn{oisOf1?l
zdQ8p0e07+ThfOU~uLID;jg^T~g=Mwgj^=B{v;g8Vnbz4Cn26n+VR`v!HJS+-*;q_B
z;8xXz!Z^)2E|OfFdzuPoENAPD{Mz;uv?#01iAM9Ic&B9i6?2H!2dm@@mbJAX^@IzK
z1V2*pj)9_S^sbxFH1+(P>#S5x>^jM&OenOhz{^c2c&+$MQ)b2TSD~&#pO68`RjYdU
z<V<D=m2>5tD#k!%jNkAVt7d)H(UKdGFKZT@ES4mLi^c13zF=)uwc6kxDlw*NIF;e3
zLf*&djuaYJBLzl7{4=1*RKrZx!O5CVw`|bPvrmh8eBF0B-yc<PpzWNhI#o`P{mee7
zc9Ng=Myhrk+6*6BgkjH#U+9M7F595$ek|JUo*F2v`Y8K<-2h*s!Qe`7k@9Sa1L&iY
z*3m-`pg0p;U-@IshU$lfdvG~ZCBq@x&fQyWq$J0}4w#mhLfG3-ul!`{xsq>;d#dq3
zry9Y02zbNZ0vV9aIMinzuHC#m7ipb&84mKw!UKE5s1LYFX?|0*UA25-c&26_8Z_JT
z&+L*M;WSOZUPqgu%d@bW#-!KIK+r~%peo%kymo}(ssS7wsE4%)V;uv(hYm<*sgkv7
zUi8flq(fp#S@jW;%3yk9o^U41G5-Ec^&;N~XbPgG1pffG#=+lbJ5$uRy&ktFDL^UC
zHzqN~MY}kfXpxBHoG#2M<OZ9MZXF#Q3|TdZDo{BnyO72)IV5PSw98>ewJv+{eLAr^
znW9p+lbnyqDP{&ZnQ~HqQ!Pacsohv`0O<Sa&W+S|%%J5|?uIx?X(U@};3Ovcs)yv?
zyCE5u2#2UalP*{6G-1q_>PcFYl-_Z7Y6Jp76OF@}mimp<&jl$w<GKU#8kWW!J7c=1
zi^+{~sFO)V)kb6%o1d>czpGnX=iyT9VZ(F#3e-<g_iI=i_+UwLurM_RRbK86xf$Yg
zPFmhs{N(d}e`V);^!<I4i$@mlGfU3`6N#AsViV8j*X_Dt@9-t=Tkhv??GM`?Y}c31
zYxwj1NxK|Z#WyL(2Y2|FiR;+j&rA5rP#4$7!`6{rpQppO`D0h#=Y89r->r1MzVDZ*
zhTmki9ev=RqUK!Ad9Qv?#`?Z?#{TX(zg#-^{k{J*q7F{wN@m{G`<vZf1xO(J>Kkg$
z-TSZXAKM@My}xIkbU!Omw9O`t7O!!yQDrkHF7I;}lEyBIC>$2NMCWjNO}bR?bw77i
z6&9X?UUS4F&#|BI8nZKh-6(os*-%Kx34MKKk$1R9+%nbn)%IL}bn<;(x#DRWcZ2q~
z?qGYWT=R8o(;YsWXIq|<Cy(iVkS1S)&BXrZ`Rw|>!NZNnevlL1LFGW1Fse(B?3vAS
zecYn!=Uw-EUhWcnS?H~zL01*!^!bsfvJxXHsYJI{?K~~j1D!YXx>C6$CDlTF^R7pu
zviL}`+WzvTN8{G}0R`)&H`fz_%jr0a?*riiof~9W%M&xl&FOjsd}~}vgh72vRakH;
zHA1rfrHAkbT#r)M65B(Vw9HJS{8@<{Z`37=_o2R4?}0u(`Qrq{x7LBJXnH!-uBE~q
z(+Yp?HznlEM{AZk`5cP~<Hr^a<NA3;y_ZCI{a;4Isy&j&$GLzrg1P;tcK4S%c2xW2
zF3qWP-pyDp7daNuo(tC%bC-(EBk*3D)+~=Mi)VG+PLI`*F`d&KGtCaxYd&jGylcm~
zeS&^zrgny26FVK<N)kD%>$#>GbEQB?J3ZA7(Wy|&&+WO#E^S9xnftk!r#N!2rP~j&
zx;Hg)TC<CJ<ZgU*?H217<t=W2*VZhv$~hKL8oyhxepvA=zP_exA@s-n`fXJExq!TK
z+PzODw}b9=OXdbKvm-3+#>IYd!LvC1!q`!(B9szPn!y;?T{#THSMgZ%?yd=&s__gG
zLfh_j25FQKU+ZP<(+_0kNA(FKdvMztC=~LuRKu38@Xex`Px~&$R^v8iqOC}*c|s@U
zUbi}=5uV2%jV}A+P);uw!fOc3Cm!#HojM`w8ZAhi?U%xByq53F51U`LDGxWDpC%EX
ze1dC`uOpEabOo(}+{dvcU_){+wy|TPy!}u6Z<RA%qczBYI=ITZ!nR^*?Hs=EKwV+H
z3_r8OSbNNiay_)|@1I|LcneyISP-6cD|rj#qMXEXFOOTJoV*N*;8gk|JH8AP4Rxn2
zXC!zTWV!oaWDd9UGRYdPdM-X9cH@|We|s!Gi#$Ol+WgkD>GMf-pMIzVZhEb}Dt7-l
z^}$5^k{J7V&HGvPU~#rQ@*A-BQYZn+*v81w$-!9P`p=oIfdv!`K0W@QPkelQ77jK>
zmVf0;|H!$y|0L0gxH*X_I_WzZ<Nq!ABh#n<ir~`;3E(r}(;4c2g}l6fl>ZLtL~U)H
z{!810hMtBVpY_YE!aqu1djAxH@juS+>6F~<jPdE@^-YcON$?r|axSm$VEko^;orP;
zGR8*c`hvD@_?llL`mcg>;4?7N)8lLZr7ra4_)FgrpZPx-#2jp$?f$DUe>?e0`X|fR
zi%#*&wS&Hmqun28hVK80CGedboQ?mD34Lh^8@rer8Y_qi{t^CDR|R87TW1GDV@Lcy
z?WO?rKUHJ<ivMZfKP@F~Y-8$VhR^<=Vu_ktIT<_P(}`MrwXCqQp{>zhp8io}z-MFT
zVEtq3pDuIDx>WOYLlJ4IJyTrd+2rAw=ShboPA5iAAb_k53IYI3LKM!4#0Ny)s1q;{
zPJ)KGLr~X|!uJa?oxQ;#!4GI)Xh6U{Kf6N`QgMacnm|QIm3Ja)&_Q7%P4@HvqV0Tg
z{N26%(X-B?tX*5fS^Ju;C`3*mOcV(b*H=`IT<ZJ$zQl)YP)#6=#b^Fl1>jE2n;KUp
zDp*FI{&}*1$zvi%Fc@mx@H9tul<ak-lNtM<3dukx=VN40zl-A)5_fW3UwdqHLEl1E
zyyAnmPLWtTo$+Q=%z&}ZR;T?w*d&1r$uSoj=kkb^SSp*vm7P4!RQG|_0z9AVW#plI
zSgU6J#6aN17%v`Prbp5RRjw><H9F>le+R$Nk1iQygl%hfAv+l|95OsfPBjKasxCni
z#XJ+#c0^SmXz%@dD$#*6zbH*72~ASU9`+nym5@O)&3#w;V1BZUSXZGQW!XVQLnD|v
zQ4T_X|Aiw-p8Vh&fIeyPi$QRZvRJ_dc!IcdqrO`+7u|0JS-1yUGw!V@VIyXf&AKrR
zUeew?;LU3=wnQjT5_N8}H0xcs061j2S+T9+fsD$>x^y9nQ0DA)p^FdRK?6KQR%`Gv
zh4A6H$4M(q#zxf^x|e}Q)8Ib$bq%_DgCeRNX$X==wINEDeZzqWHmej&g*0kb6)I)O
z%XcMUzBy@*eyfs!%EDhEs-C}a1vRFYT0PJ=3f7xWMOV{DYV%=eb$jN_d|akbMy4!N
z$k+%G&TTTXMZ9zp7V-@(WPw;cj_yy=HUw071JY9LQr~H1m_?YwYRRxOxj(B%bUmLo
zmqmNiMrJM%&o^xBFDH5<Y=QkduF}C<tT^I+BEBSzIu!M0>5_4pizNtscUTenG2NWA
zc&XgW1^C|6_Bi?gtC`Env&?7?KE}wis*XF6q|g{<oNxf=LQ%ce;7s+|V)Nl&v3CT|
z7nZ4XSSZ}h9@w5^Vt6LdIABmhjyf?U{YsrJmRmBj*3csrWeBZ~Xg{x<?;jzgK(n_*
ztxYs|*|0HattK0|LYJC<nlb;=+1f9^l63CH;kjCh&!PjSv}Bwg+vaFVW*vzcrJjh;
zU=yv9#<tTY^6lBaQoCjfVJ#%t^02^eju$1-w>T|E^F<}wcaatvmdr_;bc3K$PuTJj
zW?r1tAu50EV@=$!i&H1FfQAhX^Bgu-G!7!0%Q^MRM$9{5OnOW9*O`uK71dI<q=H!l
ziXLFjmAGP{Mnuk@Gz(`tXFIS8U4oEfk#x$KrzOur&h(aO4b^hC`KFK{GjTBfpddGK
zXi}V^AE)>?D;Q^3=g=x{#*CPh;UDCz5wVFQl>6B574Q~@5B1YPs{Woy%7RiwV{3*r
zBO4-1UL#t|TCSMt<+Ssu91~HDs_Ac_&V@a5>ZcV>s;A1+-8J1;7Uw+Y1&bCu3gS@h
zkuD`1W(FS=Q!3^yO+E)9rb~PbgmhdI_dKFx^2`mcIW^b{86%>swti&d2OIZ8j-2q$
z<@5geZ*3%0jE#O2kC9B2-|L9O&(Nk9sFe#JrIt}b3pC(D8Tl14jN$IMXg4b);8xu=
zv#+{BLsT<e^hHppw)54#aJ3NDDU*B4NsA|B$&Zni>h)um;U=}Cc}@%0`l~gy$Gn8v
zWV6Q8d8-yiDbEy|IUT+ARZ`>Z7SVMPUHx7Yu4EhywO^Kf?5Zq0XkHto!)K?n@!*TH
z9(^Z5j``@<`S(hW57LI@8zbQ51NU*?`G@C#$^meNy;1XehRZ=;$qh3YQfZl4=V8Zn
zG>VnJU1Oq0s}KP@=ShxH4&jaGqDGFK=KR{LWB1DGA;{sDn>YV@l)ZiBj<p(9s7PO-
zDNSJFJ9xEBSs)!kA_^n*K|*n~5kn!tU@n4d8f<DNU15+7vx%{SX4OkC2^^B3GkX}Y
zvDw3!HbMlU1tCK@1qo#dmO^Rex^gpu)w@JXg3+V%L~}=qWf-N*v74#paVVs}z7=o1
zxXCEhIaIxq+Es;eEM-R2#MUuGW-Ob@ZVd#%$hYYgvld^ag-7ymw4XL8yAz?%rf*hu
zkv8B1NTDvPcX#<h-f(o0XGftQxRqB^DOf5^wMIzCh?8rfY00r~B8YUS-|hk>`$P^8
zX)T*YV?8XhL(Xo_h)BTOXG{ZCZPvHkHe%T{aG9e%=DloR?0%6`t>1~R<3}VPV52Ae
zjK8Y%K1z?SU0j0m`Y3PR&cB`;_*s(@zTVoaPBQhI;N4=Z=)7*dL?7&D9fJ8y0y`s5
zlAxCojdRsbk19FeL6O)R-rWMH>f63o!oV^907<N893N28Nc<ZseYcg)fD;kWRsQ|w
z?fm}0?e&Om?D2<$@0#w}^*P>1Cpl&eOmie_v~=Nok$I1~y~Qp}QU)Cb&}X-oxMN?4
zt`oGRa1xZ}iq?J=AN%3LK;o9K)&@eUna8hErSfE#nlkQ#1kxzqUrMpKZ=BBg-Q}W%
zC;Yc_w=!=}){X8Ns~+LGy#wf0_i@qIJ@~`funfHOkDybouK}8xhUr)YL=*~wXP|R}
zyFWlBMb1IjLZ?xw1|{qTsY`!7Lwu*I37Zk7!4Whx$Hq}0!9`jhbh$;SE`T>&!<@U-
zPqIzE5Yc!qawP|Y<JdgQf9zSjT5FSG7~IF)*rMPvxQ-NyXlSqze!nwbsCB>7IPxzD
z5`o+W;pY&^Dx@ng#JbHsX_g-==WSwZySwXfrdw}6Z0D_=;S<u(oSF3Pp2-(d5Zye^
zUDi**CC?#`iMVFK$yV$7R-SL9aZbYi_0$(hZs;qf>{xNEgtT2*LP4~Iv@}NEDP;Jh
zn4~%8uawvEHN1wEe7)*sP8xxE<b9Mo{;Yvw_AVT-;#Jdv{98r~yj)E})NLK6-tMFJ
zXziL>gy|%4_1XN8A_WbMjI-tUj_p<0=z_?tp;gt(%7?`_&IbU<JXeYNpZBugF}GlJ
zOHZ1Dng;LrJrpD@%2g^-Ii+A@qh}L{EgRru>H9!!=n23K2;knSb!4W*uX8^m?}JYx
ze=Zk=&exW<ia}%ucw3t;e9IO`E}Nku+s5=V+JT%tokNzRt-@;e^ip3P`1Xpo?f#2z
z7|*ld;9!uX5^wd}+S~hxFZt@s>$Q~B!~`^~jDxdBzSV^P!2z421C%H{9;#ERl~%*$
zVi4=^?}4moF)POUS?HH>)Y&)DHH(z$7xvH1TMKem0?hTB00F%90>4uPM7=n8)9?8W
zlsE#QQA9WGJJzKeOKi65x34Ra(dRyE!Xn?bekm@`<aEPTX86+5hQXVWWf;ucVHs{v
z#H;-}m(Lj3V^pP9Khk5ECXRGu?dvB2xU*C~N*aSJia2c{DER$C_B3#1#|5(~6Af%d
zQ}atQNuq*CLvr6dMn^$zYk)zmBNpB%Dj7G~M9T45!5oy%)hdpai#OGau}mv@A76AA
z%S_T!d_Vh8R#I*$@hQnMN&1)vg8;@N5+Ms-2r+XKPx<KPbXvJCf{!ef>Tp_eh0<0T
zuFp0J*-r4q^_jmNO1G}^UFwC@YvwnpD@B%nhiLp9aWd(5s+arDpRD5=d-y6|%LyN}
ze9H=?Q|6dIy(Bzpi#;=I<YlQb4~r7+<HWW`33HBEz)PVxzm+sg4DzNUHkH|*k9rVC
zMYko))Aty6Fjo}6YIE`9G?W&nb|0;)O%5c26%7b9NEATq@eOYh3>*;fMxfuGzH_FQ
zSMMIQT3Q-kZ(~_cl8bs&#Nmcx7}=BOVCf+M7y<xlLpnl5DxWQc>AKLDPIS?CX^iCk
z2n#}z{h|<G^HU?pZybOtZd}wxWeZ<r*W(4rvYiNp!~xx-CJCs*kz}|MW15)mi-=A?
zrr)CNn}T>nazl(4>b%)x0<4@Y$6A&r0oBEo4#FIdWm~0p`j4dKx3ju6gUsjZ!>C*F
zx2A+IWQ1&gMn4xcDX`QtBcMKF>N|H|z=JQ5)h4UHxfF@L6+*ZfzT*Iw;B|#pWZC3~
z_HL6ev>>zs2FJAN6F~#*AC4*$CRn)&30c_x7#s}u-y;@<A}Y=J7)UOlx#@In9j%W~
z-0ctjv~&%78d`)bEjj3BdYDoSb-CiIvtN%n9_e~Hn4AaA{eJ9-AkE!#RA?K}Z@Ae=
zIqutRznpc-bX@ARfd}zkf0W+Mnu}Uis6SeoYXx0AJUA@i$p;of>`*a@UJWa{(wP!p
zCoC;fkkOkB>CiQmM>k_~m%pwhsM)pryrhZfi`9O-Y4*-=u&+C3(TmwHgEfvdF??%3
zK7V1(%Vpyp^#dYOzn(hg%`|@XPO+Y8-{d7V?q?cFz0_XHvuom}Jz51_m}tg);(bTv
zXCnqm`Yhw=<q@J=_*l+!W2%&|z01`+?2Br->#PvN-f#|&=h1AlcZm%aXQ@G7AJb-I
z&FAMaSLsM(ukgDD$5}h!o}r?+4>^e>sc3m(P~l-6pGPUCONz7Fxh{^Ai~I)z<aZx&
z$tdW87b4qKB3_`v*4|2ngK8q@CY_2<50#N~qb~C$;;+@{pKQ2zh`V8XNZP!ets>DA
z8VZUlP}f^)`=l2UGsU_bmo{6EZso|)m-$d>_ONh7_C>8idO~$QZb#$Mbvdc0DrHW|
zdk}T`)W~~2CrtMyMnU1aok3dts|0&gM4lx{F^%-dS8&@UlLsKR2XdMrD-~UhT3kz<
z?%ovMZBT8K-I|@qhK$!_XCK#Cg<7pyem3~O!;uEGBuWU78AkFM)QsUM%w7s_=J-J+
zs8p}EJ5FV2a}7<CSW2Ad(nT~!E?*+B*>0h*Rfbe)cNl%Vl1ME}l2NA8)oy5YbUA3{
znaq8=?)^Pnkij3Ccz9f^!=vkyAe+@}G)6sH1iS0E@_U>eGEsDo3$XTtU(1NVyx8zW
zm^1Y=p(asQ5*-K!INhJuUp0}lsb%eVY8<_{AKLD7fad;p_MEr<XE{EUr#617Q?w3P
z#b*`H@Kc;uxR{CGds2M~g~1}oc%sEHhU|iCzazW3`If3QZTClTQ8_-!M^GuUf6t;j
zi)j<tP(O%o`n$&c_Wc|YaulcOZ;afsfnODL)vpBUG}V(+t00&dRa|k5S|XTq8tTzL
z;N*y8N=@Wk8GyhMZKzL;`=v$5W`?^OYk8nRH#MZms!z1)^9WFBoZIN}Gjhu4p(<>u
zX!QmOZ^Tu9Iv6<t+}o9~ycm5<+5w}-&x(Eg%9z#x@l5}V(C(zy>WxWCq-4Z1zx`=$
zl+Uc|0pKZn>!A>Cjuo?9n4BYW1~*@PfbEW(#vEi-cpO*Dd55D8<^EF;B-E-L<diSi
za&iAD*@%?r9eXh>j?)lNA=Z-zn_@qoiVt04`8H{a%)Llb^r?n;pSEStWzMkayN=wC
z1L}8dlfF<VOevGjRRo1CQb2OT!#0=Vk7zByV}fg!4BJ}TDSZ(q_?G}w3i$msGOHN7
znU9~qqu(JpBHUxF2<5y_8OentFX!A8YGDj9pLuHXsQGIk)4@25pq7pjy^BJef}s>*
zs6?KVJ#VjXCTK2@58AVMsl3I`c6AbDC0AIISa7A+fpL|Lruhqsr248-0)!$fg$jQG
zU!xE^U*5@0`IUoIjFnj!>g2UFJ1g;eR0mjG)rRC1W`HL0y_EOMb+};iQu4`fGM;Q{
zR>DzspuY_t7%tlAvpvFhurZq0YD@(_f74LHNn_@y`>B<_VOsnmo?Am4;P*3VO$HKu
zh;HMfha@~E3^tdC@9yaGX$n3=tPN@bdXV?lT31-oxFSrf4}p!(4C|7zZSnUL85m8I
zaEEY&JJ(%!Q-oL8wRKvmVRl{N0qvysYVi^&hA5mP{OSnS7>qke`dIe?{ke3>ExZJ*
zPO4m^q=UvdiS2&tqlPBEsvhk~*V&TJlR-|*iy<+LdDEN{)?5l^0kPQSc$oPe6ETpw
zByfX5(2FNXlh@>ECh|-W^7%9@L~>zV?N(45LuScGu4hmu#wbztn31p;jNT}83v-%W
z#4uZBGFq^PFT(6Wa4+cY8+DsH;CB0tCLkNgyDCDDeZMZ%jt4@IjywEsjlO26=L#UK
z%pE$Jn_@q@*S<x-n|8mMhMn<4hIdI&t>N(0k-lO%rsrbPXJ%kt#G87*Nc9_2Ixi(a
zbP%r-|KC~w$FY6B5YGUmzI6c8EHFpMX#4|u>~E#)J}P~=dpof}Tj)1AetZyRwSG*_
zknd4`9UyLO(6Z3%?UQ?CA9jRTG0^O!J5NAcXg4W-+mLRGeYT+3sCL4A`p|I6U@ruK
z&ET;&8i3&ND0hKkJ3E9fJ8S|zdGrfV;DQ%y0xNVo(NJZGHywT!fW2sSwHP{%{gs}9
z?~4X2og)KJVEVD(Isyf{<^h{PI%suLeX{UMkSn(dk=LUEsaiJ%3_<piZ9py1D=mv-
zt&l5cK{T0$&nX5gTIP3C4D#kbps~2=^b~{p*&xg4^@x0$>Va6RTyJ5`>$X78GxRPq
zh`g%(SPp}|rV!N{!;<;X4-SLnaSdibchvzaRh{=ML95QdsN$!RpZHgyvQyplgW)FX
z4c!@%3W_8H>m~zqA=Nqt_oP6n>-FmWM1atsAeuiN`hh;B0HM+Pn1<;2W=4*|cg+ER
zflNC0W0OrT?N9(VX6Tt9bFYFhW$1PInFD>w^dU>!wE0mi0q`2baFgoY0lA@kBLTui
zl&989@CyZ%z5o`Hq3?$b2Es+6*WnlF8HUcl*9`<OG<*(Jr<d(h+i<@C82#0cVR6TB
zxeG`ag^M;M28~fX@Bt+HIe9<?`aT(i2o$nEY6mzFlHsL>0u#;lERP(5L9f>5jY?kz
zbcISUe>M)z+V4kXH)96@c|x~y)ye&CL$|RwGj)B(-`fLrjc(yAqzn8CF^W3dnVR}!
z6QIK*vo!(D<LI<CAB2tLLCoI*sJ`i(Lz34CmyXFf!;CK!YNM^ZH5F7t=`<EFogL8S
z$lxUTbR#Pu{=~0g5m&kiTrO~evEVMo2I4G^7)PBK`0Z;ecw%^v2!eV@q`2T9gD|$f
zSfqRCFw1}yK!m_(48Y6Cd>qM&Y(KMia!xQWpe~>S5I4I3F~8t04d6a4fGYz#Ncya~
z4TPP+)oHU?P&3jpAZ+$20{+_oEf^SZObtKyI&_eN-m&5uei?iqGa4G5N9xOW-(7;=
z>mctFWS_l&NwFF1{~Oo-1G4^$Ycta`{);qo{BJmx;SYrT7bZ>jf8nwJ4Zmt9OxOg{
zBZxeGMyQuWhJ^x4kOV0ee?#*wYr+F~j3Y!f#BA8P=GqTeD2GlPc;2dv4?Wo6X0y>E
zaEEU+w-45LV%=fX4HP)JW#mjg)Dvsm>e*YD&Q^s?U$<7bx7eVstOz&=giB?ys`G4c
zjD?2+NNCk#h`IvmtaYTSemwhtmpxGtSJn<3^54_p{JkavA;En8P3m~R<8th=^m&6@
z5Vw~Jb8Hd~eH#-dyECuiXH$p;hDGr7C)WhL!72E!O;F{-lp=FU5oOLu>EKs#?*ku#
zj{pu-S#_c;COkYMMFL*P+^|R?Bg%!D;#?-Fqj)B%-Gmo<;Sxdbxzz8qBDEZf_aX~V
z1=s0c@@~<t5YrS)=9xSaF~^t`uc;S}u8eMtqtYMfZk-f8l3Op{Vn<j&)nuO-U%S%8
z&+UF}-!_`6dielm5tqRK?>_shC;sU)CZ_*T5e$ET|9>&`zmfYt+=8&NqoISjos+G@
zA0YlOx<OXo`inb|k=9UF7oie1w$N8`R{VnW|C27NZ*6Ynj!*t~68@hwioX-B^i998
zd&d803jWP5&@j+5(&N)Gvohi{uyHVbu?$R%|F8@aPWo2nh5|OGR>t`Bf8`T!H2gzT
za4@p}75!7bKXDqyud4hhp^(0vxUspZ*%y=XW#%uDqLZ<;3O@Va`Ts=3|Bd{q;n#39
zX2k!)ApAF@@P|VA->vbtIcEc>zvvUCFV5mmOZ_Dk)OR%gi;VeywT!ugqmz)CzQex_
zAg%vToPqIg0_OkU-1vWW$lq6th|L#iVQyoJPp4{bBVglb{;%LK&#LA|PG*i@EDaOG
zpIZFi2NNs(Kk2MYtoZ-0_ZM~amHK~M_#<Uu`@>}YeXz3pd(OuGKYm%ih8G*tpRx3R
zAFND&_@XaAUn>>=w+18I|Jb0%Xa1@@%h#CrQ=UIu&mZ>bOY-&pi+uVbk!+Q1%>OVs
z_<!b_|L(Z|uPigzZ4d^6=$)_dB`Q%RvUcLd<eIcn)kCZF3lIs!7aX}ns`~ZawbKNH
zZyt>R?+kEw^BObditT*2N1hXdu)`f=T^V|fSdtubvQO`h*M{g(-qhARAq%MsI%0kv
zhRb$EK#tVT*O#+xz6<BOWvu#+=-*&nzh{`2@3#t+0;3E_4Z3^=^#rgS-}FHO|KZ%O
zrtZ5gL>!KALvs)6_2W-%210H!xGzDmthH!G)DR5^%1iV&jX<8Jkxn$Tp~)p0Z8)Sv
z)0N?pB^u(on)(nVQZlJeBhGvp4gEw?A9ZN@EQnH3aVEZM?kho#t~dCa-fkbb;FtY9
m@vQhGad3`8j}(#jZ+%PIhF(MxSo<MN7fUE*wphG;yk>vc8e*gX

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-high_error.pdf
deleted file mode 100644
index e03efc8c2789142d0bc4ae68e80f665922019e52..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67428
zcmV)uK$gEHP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&532i#%KdX4kdZIU*AxWzEGuXp>vqWl
zgd$p25hc&64_bjos4;pf!T>dhx02$|dq`*1M!k9#TF$`#&O*_u)`&`lE|{zvbviao
zULesB{bG?&X<-T}F$)k!Mv%}dp;8x+r+)&{QG1V~SOU*5WwjwTWJ|DQQdn0!<cWYJ
zS6R!B(%Q@1h2X33{VGayISVEnu4P<}Q!^tG($LjplPw)3A?M_R)wM)_Vakn<`)>Z0
z7k~et&G$d9)1GO6EH;RHX|O*1l&02Hu-PXHk*I7GgE9kq3+fE&%~*vz!W|HW#1Wc^
zLU%^F?5rz%PW})fx)+HFsZndr)J8mlRl;>f3=mOO7*j`9sKffRB9MTbScX8c>gFCf
zP{5)Q&hEo?A+(_66$a(9oj2T=;Sq!wA>M=;l~+d0QcdX$DcGW=8JW!sdYLzowws&v
zWS0NQKvz1Wx=NTW^KTk_&&{-uufck-5CvM%T}z7oKu*qI<>a0pl;3uwfOT~w<@vTF
zaM37-Kc$(KWd5cj1Q?MyyGZ-D9jATB`OmNseM<gsI_3t6GH~d~E#u#Ige8Of=;s&H
zq_nes*AW{Kl}UeYThhPnsH)JN%xUeHjr*I9+}|fViZZ|JxO`;$G4L~dl%EH~A9vLG
z(bbWZ=i83(67ZP$nW4cS2hVRh;(R)9cGQXG-*#;6;~4uHZ~2dd?ROn{{&jUE<@v7T
zQa1Ke@@ME-pXcUpI`Vksek{tj`?1CS$y4}eWSsA(@^3oj(XDTx{r#6(|2W@&Cf>@&
ziT|69xER{4j=U<q-G`R`dfp#DLml|IQ2zLPxORXk|FiC)@m;s7Kbm*b&qNE{D8KE9
zI;_{tj;hS+-*z11<L>)er3mfYvs9Pn$+L7XtoL0<lyB$V`tysGzw5UBO-EkJgB?{Z
z$iDAry1Q4WYrDyR)4?PEnjJj!^=~`OT_1=!wGYZ~I~HI+I+CK0z~8dJ)Qz73ue+-s
zf7~f`6ciHpDV=3}+X-p%RAhc8O5}%X^P7&;fKGN4Wq#Lj-KnK0{Y+@LO>z27Cu&y{
zofv!9zUh=!U#eg~1NrAeC;Lq|Xl_&8oKe`{b%VZdU_YT6>^t^{QkcmL*(uxZ-*t+d
z<4tk=naQ^ws^o7vR>l)Mf-=r;JMv8g#q?)*Og>fB-*lu#+t^W*``eE5+7#cP5p=LC
z!hhU}+Hz+nw4d)fDNgyMN_CD8%I`EI>f&~(BenDXZAZL}sj>gee1s1j{*OCK)pvE|
zW;(y^2po032!2NV#OE8~Hy!bmz!UiA_PFTZcAWF$#ql$}W*={m-*n_tWwIkFN+tV^
z`akv;O}rcIgYw&sd<u1T6y^DNVL#`3V!t2OHkV1}{g2_cD#`yVU)Z9!3`V*AfRwWn
zc+|)5EQ4T$Opst@QcB~=l&6!FA(z$NVV)ecfTmS%wP{yCS<g{M(4y3U<9#y}B)3s$
z%IktwVry;&yU-%W{AejRRYtWjHiKxG;)ZK>MJYpO*z~eM$ZiN6Wy(ae?0I1~8@nkp
zOpxQll$lKX2V3UYZJ8fhicF$oH)W1M?n1V*46kFiWP<XwS#SN>?8G5E{%m~dSrKwK
zZHDytZrWV3qC9z7pp~3XEA`QkA1>3j@3zmR?6%KXb)UtnXfZ^b26yEU%P6npUmEV4
zt~;3f8$vOUo$^)wfu=-R`VgA3Ug>9ON?#4ik$`t{DkOJp^C~2FZF4FlD{XTsyjd9t
ze&tk%E#zgIgRZOGNqS+b9_w<`pk6EeP{Al>G}6^mWnbwIs@kxg@sAC8`(dy~NmnHo
z()F|e60;R->E(Hd09`<$zarng91n;RZWSLu<4?s0q}QwrD)g+i3J8Grje1m2gd+Kp
z2X9fzO_?m{o5wL{T$a)F7A^{1gCPpaU~>SvH|4DTqeb(egSvGs^o6>cdSb$_y%juO
ze($FIGx)_1p?!k17}ex(x=>vEDF^)eZqsRdvDo%aY{Kx`XOU;L;zVfo)+LssDS+rg
zUBadyqKkzk8&$y|#g}MAyk<1$62}{{DTp7z3$3w;Bf=Y68(XJfe;Zq;5U|R-il~XE
z6srS)6^n%boMYE!zF4eVn;Ccdo06@Bv&B_$v23?IiWkdv%cFRqY<ES3I0kNt_;C#U
z+&U%a&#hN-UJ)T7+f`oOFQg(YQgw>0Zwd-Q8E=(wcLdi~sdoh6WGVOqgcz{u#WRkl
zO3E|Xr&)!BK##Cl8wfhV79N1>-DY(Q#AV7b?qXv=NDFyrTVw#P%q=nim!Dz-aIcwf
zeR61ZS0lu#F$oDlSOG)LPJ*dkEnFqW!@w{wMV!No8fFgl8PQfq*^~dhdgQPw>KGx(
zi^NX3ptbLDc%QZJaaNz)__*}j`D~pAd~(&vVQpcj7|VHYebPU6)#y+*`@9qhm?j$u
z0m{v`3K5{QkV!om8<?Y+TelpIf<zF8xF`$~&2wx~5Xy`IYJ$kW6z{kw>=k!hJ9#m{
zirp${X9nO<J1eXdwW!Zteb&x9b-hoRiOvcty`u$?aRz+0iZeh^Xgl}F(m0LJ@|<4a
z0$ZtUo#)miSs)!wUW3r#fZ$*cQ4>4?DD4q8xT6%2J&HaDY~^w(RIfFpsE6=JemRCS
zC$FWP<ddRRm;}PM+qs2A<6C)(9ZAZM?P1a3FMcX4I>y2U%S~yI0$e7_490-vg$|Fw
zqX;L!i!KV;8Jg-MRHx7*-lS;e>RF{vWkIi?kTJQQi$Zp;{cevgGCZ2BQmznFZjVA>
z=7}k7!STTXS5j8mz$<J5WzZIdY&*d=$?XYWks@CQ+>0!#k)-^Tt~A7_+r$5!Y?I(3
zXF#<&l9XT4`vZl?SJ4lpG~{>WAw;>ls0(tY>W!Lqt9S_14b(Wd8;2X<a8Yq2D7n{6
z;T8uoEUe-!(ixyMEaYj}E$KimM-)rJG_OO|R9?ylvAa@fQm?gJ;(^%tMPZgpguxwF
z0UL;>x5~Uig~Ti*lkK%<Z(Vt)yBM`;n0_<BC>?ZTs0hwWi8FRf(?N2L-HMl5UY3LP
zcR<LY={1VzdzSf0N(@ey94c=fb~E4=58mZz;Apz46umOzC^)H848i$!SA0BbjoQT+
z`8AtMsw~o>mV1KZz(%}k%@KKLSFI`b*_I-8qFXI%3aDLrc{+EE3R*c{$yNzaS-01a
z$cX)LIWrq?d|0KE2&re4{{;J_RsK`LL|Uak0X2^Gz>rgyKOG7y^6BhS0t`Yv>{1vj
z67%emiNTkwUs_WDm>H|U6N>CjKr0sbs+7x*APr_RrUR*R>%yydDRCMm;jGs75?qxj
zzbfC{hf2P^n01+j;=nXq7E`$s-m}&mz5;2R0`ze_%WYPK5}c}2d73Hkt5)9YOTP1|
z3>!yj3)J5OX=KelXQ#DxQ<{+H;mBfuuS|fA&#F8L!Iw-m@d9lrKF<6ry!{s;GlAh$
zojfoO!X~jsV*b&{x{5ivp5i){kJllxWhv}<Cfcmb-y5ToK=xFHSYPs$3B@s9hSZ`Q
z!eJA-bHA{NmG2CRoR#l<WkF5+_f%sNRr~-Y3CvK2$};tW2FATjJ*oPDD4fJvbC?-y
zo|-kB;zRm15P_`nwoq##s-Pm%0RTWYq*lSeZe`o-xzp3t_DVD#{6!-nrE1)02A>84
zK4Gm`1ZHnHP-aoGr0$dXPYFQDD!hwuW_jXdTSL%6rC9-&lclkfvhImdXa+M~&&qFV
zQ$@XB33{TU>e+5d$k%T}Oa?J<7a=A=Yaoinn2;ceePF_L^oICsD+3`y1I-IQ0Q*)*
zij0Ia;UWUQVf~Pf@_&dg^L$TR83FBy7GWmtn6WCf27XA4mwN!keoP5Qs0U=im?JXC
z3OT$XRB+-l3h|W)9A{DpEP|t1U~r3aZs9YpLwFx1u(yB&i8iM&a)vy6EgJDJ9OV6x
z)yUFXVHMkjIDG4c$O7RO(AuKJ*n1_YSSk;TM8@VhvM3xG4)Cs*X}rO$-}v{kT3DBX
z%AmFPLSr$^pwL+IEp9?R^Q?M>kW?%>PG`ZKElLQ6;xq$g=1dCUck<*ttjnfxKH!!F
z?0mp28Mp8-H{p>HqGSCKn)xAW6z3fcg6+f+VZFeGaK?6S^@H#`R!LHLrCX;j=!AFy
zLTsV_n8I3t3bc5n2L<B#7llYb17E>m4^Ryg6qw_2ZiK>3QqHarhB{VAuj4bvVO<IY
z@TjeTycqFnUFZ3kJH;xM>Wn9e(N20o-)oPohIp@<Os5_1RcnHGMj1dW2(F9<B03dH
zyqRpN9k1y(1+5Hd7C<j56fO!uyyDf8&|1e=VQbljt%WE5hOUJ*Y+Gz~a<{37ZiHJm
zA@e;0!A!#Dd+@$!!jHvc)tZ3#9+bGTMkGFj`CAjt-h)%131{!YDF6sEJpP-?<#Yy@
zH9_hDQr?vG6{sSysICF$Il3qiD!_`Ym_7~|?`{EVtth`_xgbq{i6lM%4(G`W3>r`G
zjX8K}7jqJau2_>ub;&G1rvXdEWa1{2$i}TGyJ<3ccjOCL(^D{j^`7JoqI~Z>`Ap@@
z7G<68tuP3um<&yU2qM;8AEVregZE7C;X4!?VaDEo+1VJHB~*iw+`FC2!q4C~X-%JT
z1^WZ)^6ubFK@N8HBIF?6os9YKaM~L3^^PPZYXs#A@1(WD9fa1<3U?4%Lo?z@rfx52
zvwl--ggXddm?`zIBc|AzU|H|;h$e7F@urjyfQTWB!r*LZ>8R)T3W$)ra0HmvFCH`}
zTER>Oj`d7qG!wS!h07ux2?t2*#ZNQT_0gxNy79|+8Cv#0)n_w-*@uH>wfSYFhR7Sy
z;ZRu=e%R3mZzLk6no!z^ruwF!6^ktYMTaB82-yb2)*~nd;>uq9aM}m0z*8X^a(WOv
z_E;n=b3U3YT9p{IivkI|AR8v=@O<-{P3A-rRK!dv4amDU!NGMH$rq*2cF_y1d_XJt
zvIAIPQIZoAG1Eee>!=@Z@WFHxoi`i0hvpScWSva?Jx4LwBU=&F%mEDiwF@YD;IDPy
z&k?NxNoEgn!qtPE@FSX7mf6*Xpu@Omgi5#YLd=AaJ#oia7ry&!>cX@nsFrXVbsB$7
zryY&G)(NkR2pO|3?r`;W0#2L^w&P!CFFK$iVm!MMhIKsZMY!=>y$0Is@{tyE?0GSO
z+BW&62*+*0xLZFIC&sDq<?cL8sCUHvHl;NI9^91gN<0!Xop9q)CxDDk_Th-9`f$K_
z-^eG%fKxMBk~<Bgkx1JSCB5R#Ia<7GPC-rscHK@Li(?7ZDXdmNwVMF=I&7bI>X2NP
z&Qs{qqp3$5gouwdJ9T6NSUxED4sM(CL8~KCfI~m?of#yI9U^s786A0^oGRPlP+*mn
z7jXI`e>lhHu<NT9Gg0}Oq>vPLLfwH|odELHX^=bxD~qrmQ@SzHMeG#3HNtu<Uos06
z9B*_J#$e!!pcmEzv7n~3<&J1@D;&a}nEiGNq89M`LBZFNRzs-5D9iBV4@1Ztg^PlO
zuXBAbv~s2Px)RKj;4HbelcyhE>6N{)D9Ph0BZ1Xa6^Z_+Q*6VRVjLF<v+P_?LFRU@
zr*4oyEH^n~j}AO?J9VYtWgV20Ib)7#;Q+%s`b~*ePR``b?I@}m6buEMSgGQH2ol5P
z%>+x_VW%of^b!9ZjH1m=V2?xuF?o%N2oe;QO34*a!dv2j*eNv}&s$T`^+g#NEzItn
zmN&Yi7vM)SSIT>!RNJX*5vY!))c4*2C%Q;vC7z?_Kr0z55b~@`Yw~$_WGLC`G;l9c
zGM6zD9fgPO6mq$;hFH*|;o1l0<&mUhr*7uPTp*RWK+L+y<=$Z)B;iQF4-7Fs1&7wD
z2OVBKpOnw6rXF^lt;yBbHfgR6NJ`fR<lq3I{7K^Oie}T^Vw)R_Lu<9Mpb#~~K7t4}
z(>8(#wNu-uDBMP{BC{UUwm}Wc&9|pLd*c=hAaZuq^ooS(K@6Ff_d(%=AecY_K0Zmm
z?0T!?ttc1}T3ipp`JWdgQ(aK9Yx@wk^CxAS0_ufn#5sqv>ukfs&sGPQD4aq@V)cYm
zEsi2nWLp5#R{Ny%kCklC!y9=gaS}*L&uE67aDN=)Ny*p52Z<An9N*{CG}*R~T@dx`
zY8M<Jao)Lkq72^IJ}5&ozXk|gs=SaFiUV1J#P!FuNs*KM_(!WtKyOUC=QD20x&DW2
z!iMOCyjK@K!;Rb8Fhzp|Uo`eClJUOAgkZka4c?wpYDg~SFA3lWNZYq>ELt{h4J3t^
zfDYTxZdCu<26A7&4&=W6VIZXsL4a;RAD7xf)CZ|HS<4b58W_=#A_IB2fe;=fjEKv|
zVv0A{NwpM_6;LW0Q{0Y4!aCj5e^fc~ZqioC5FQe$lL%|dVTv_tu%}4RZ1*X3mHarR
zd6FHcR8RQS8{m8lQEe?igG@*`4FLqD7dPM@NpoHV|J1G<EhvhfYp|dQbf?jRa<Y{j
z9v*xxgL6yokNUAsz74>HYwD2#E?h&86a=S7Y1)q`N5jwN;9U<6&e-+f;EX#DD^|F_
z>S4nfclE;R10^osQ>!)cY|{i`EKyNt8B16b`Z9Im{EU5aNslI5393XRaM6r0Wes78
zCUA9DF<z9MPsSG>`4r6sn~!>7LKC{M8Cqj|@Ur4E9>rPj`T8ZXJ2U4@kWUT1|3x8;
zN2P~D7h;iUGt>B|p4%AzP%jRDs1stGSfko3{~(_@)-(a!){0MM3Q!mWF#eu;y37MC
zrcDC^%Wap50TsE;=<i|GZc8^Et9G*&nGFw|b+kf;1;d2`;z_~JB8b&g6`(QVO>kbU
zRvz}4lnzF-nQBN6ggzSU54<Ux;fJNu%P<u6)#E#=89i<pmyVZ;w3qp*F`i5&sy8J~
zSn=<vzvrMP2gTyh14c3oibk^W^#`CN<B~Nq2Y9R>Olj5~Ga^93bi*Jfpv;>MD9NUv
z?nN1}i9Y-jcEZWPz%toZ8(>_`bO{i~wG6b#lA;wC6m}!aXr#S09$9I1UXP}391#v4
zoyCI(&!Yj!N~^<m;ONm=J5Kc?e|YxjFojhm4d)^1G^@zC-kfGS#w;~NhBdk*8?ec(
z5dyTKbgBshu%Q;|qJ#|ir9R*UBfaQ9XpVs4axlC}n**XbJv;)lVO&?!ndUQEyilDk
z9!4NE)MK>9)5_`KF?|(!Vr#@}Z?w1+d=o7$N~LI7oUj}^4TT2f^f`i5o}u`g#!mb=
zbbR@j8e_Sd4i`6iF1z?054eWn^uBotF<fYq0+nnu)3h$#(djqV$w5O+V`=$Lx3NwN
zL}E2Pms_WN(4*H7A7M==M5lb@ufoNeW9>vFYAXJY&<6w1=4#Vni3uXaO2v{IZ8lA?
zaEoN;?)YpBsiJSRMai{tEjI)-SmXO7lC*BPPcPyYB`0;lWgeF)p{UV}(^$T|Gd56p
zNQ=}z{O4~<wD1+g5H+c<z0o1BXGF#%1PR}P6ZzIx4DuzVl4c!70vwUXHQE*}z*H_%
zQLmOruhw(`HHwN3payrGH7RfSb8Ax7+KRpirHnS7E)@(}-_}*Iv7y%2BE|d=eqgG6
z)}mmFb*WAb5e5XbZ4D1g>&!oG2pllM;I<VK)_Fv<AxxD&#ML_Z8;tnSuQK8T7Xr;h
zO2KQW!G-XW1EdUMffCbvi&!bd7o87{p(dRZMA;$h(li=_kaQrl3__9~L8DOjXyFd3
z8h@=ZG(|ff?qgFTV}lR30)rYZ76cC+Am#kDRgEhz+k$cBWfm|l{FI(%T>A^H49k%U
z0n1U>0~9KVso-QYgp^eLRWq(5yBLDL_^U(lT>ROQ@m!2fX$VH^dT&8<vW|?921U!1
z<JzFD87qb!neG)|(kljv;tF%aHZ;Z>Vm}xo4SB1Y0uAZ>YS6MP<c>LC5tjFml3&t}
z$alk00e*|L1pqeq$rK~lP%X+-zP90Y1r)>J6`p7&c=LwG--=Jf@bG>#*L4S&frw~?
zSmC`JQI9#iGs7Ak|Bm=T-eW8L%xSD`C&L@P#)TKLiYhn8pQ$)=gIUN_<GC>a%}d-*
z1~^LGVHh-(vTi5i8+i@E0bne%jjS<aJ@0or8d%XZf}2b9VTU#qEC;;W5hNS|$RRVA
zE(~lf69WID7$}f~6A8wP#0lX!?b28QS!>F@UzA)iJoQfq*f<X~5t9oBWC$<U2VhZD
z{0x;4ZSbjzoUtQFIlq-nm4C$dVWeC|1alJ)euYDfXyner*s^S+0TaO%y9Q(^GO^;%
z{Ri6_?~F&0u(A?G^SL698GUhqpzegx#5o50B1m~gBTkq>r<)~;tqC$>C0YgH-Uz{N
zmDw<csxiX*2vYtLJ-#c8YJhT!lBoqeattW7TNwJvo4WBw<h>~{{eDQvJOG|L#(1`g
zQ|E|WsvCa<*hogNDYTv$SQUOB8CXwJl6NaEiShe}P`0SAl6hFB>MI5VsS*MfA;a!b
z$Mlt%S&MT@Em)MC9Rt!9CE3Kga8V3@gH%CdsGG{nFkNd=Afh*u3#i%J&E$g2I?o@9
z3=2&EMs`7-6^44ZHYXXt+yaTq4b%ynml%Q9^t?0yJmOWK$7rrq4Id<V9YNv*9O)bk
zk}^chO=^>o^%XfTxfg)+y9g=XjGvp-678<s8cqR6)pcqK5K(st=+gk|Vwa>4uqSpI
zm<54naU}z4h^h9{!R#@+nwUi}$|h#PLUc8KDPCk(7pr)G3I@o4bRl42yP4nRXfeZz
z-(_x>^Lnv_m$1vVNN1#V;j4g!SQLB|pbvJ@D{U8JJFl6|NFKw)XkfnR6d|OZU6(!r
z;b&EXBqh)Ad|CepvAAxulI^#?gBRY#IFUaBroA!^(zZWg#$SG9D&OxSVK8U#03l>e
ziG_ACp^*kOrpYZaOaY}G`xY{|U0Y5g*aE}CP475Yf!pR4s}xK?<mr*5%qFBVfW_6e
zO-g1<)~djNh&p=sq0B6$62Lq>yDxADTjr*&OHt%mwS=9f^IIDlm<NjjrozK~KN@mc
zF;s8RF2J6f3K9}T+U`eu#*^bY$!De~pJJ*Z_v+EDfkHNmLWyREGWRfY^z12+V??n%
zDvMx=bQYP!U>Aaro{m=L4eP2vjN{X_2=E@*!vNzrv7#46XEHsR;RQCCo-D~hX|=;1
zZCl#=m2_>BDauq3=m1dWHcwn+cOM{)Ede}^>F9K!m0!^<Fz+qF94G&=WuY^LaOp*u
zU~I|f*7UHCmG2%Yh0*2VThdniCF%+=!7x(lF$f^PoKiVZ7^|J9*nv5=^CUke@E%P3
zm`eJGD5FqUpcsH53DbhZ6t%wEN#rnt=c1`BgCX4Wtr?@0kOmTyi8}U$$Y7{V)=nKU
zhzS+0L&8-S?gKRoU_%@r<phP?E>we|ZUi+L5-xxmDE7dFY5;u!m<CO5ajHj6K41f+
zL6htDV8&$NYoHszPvks>4%W_F%LeE#x+@nUA(R9hXNX&kS09!QU?=qW88P}z>cGr9
z;b?NkEmGjZoLXxjUzu&a65)ia4NxmHz5_#DUEenTL4LRd<OD*E1mqvl(+4t9o8f6}
z@Y)0%OAZBS0!>aQ1DHT#EG~6<SOE@@5^tq%y>f&MCN@-OY>G$@%4r0qJwQtIm$7xr
z0gbI&4oJc^E@9?yYXgX&Fmw1y0kBR`CPt*I3g`qd;v66e#Yf$8MEBM$N2KFt0N%-z
zF3oJxCg+JE0=L<tZbbdnyJry5>8z;@AX1%Mw?w3pemN4sNe|UQ04I4+@dj+owm!kK
z*0x?Tz*gc>$W8E|E>iGJegQ*Ja8p7{P-1{39}b8q$duz8ZNBwMlqui(<N!zY%JG$K
z<k5CCr4Si>W{tLWOYDUvQ@SA{xyf*D@T#@2lOLcYvedQpBBodMY6%0T59N4oI$jJI
zoJ}TeLy^TM3pOE&o6OaV0!Xq4ryeW^%luuv5+?54dc}}C|9c|B>696n^SLNEnFbEH
z&i|fhYOQ+6{{IRKM{J+o8NFb@lL#LIy5#BC`_?N*&YS{+Td{RjE(%f*@|*=iW9!ms
z5zf6RIMUM-*<{TPD^1{fbq2TDAfz9z9Q>Odi07y4W)Qyb!i#VSy^q`T#BAy;Ab4M$
z1qs)8*Ny>bRDZTkxj4_(DW>yCj88!pQUIa%HJMc3q;R@HB;ZwD6o>>steZEq0->=n
z8rJ|p-Mno*VuIe$ilveTH0@~3wY-i;937J&#Ybter#Y@U7Z@?~&9%TNGkr9{6dQ_o
zHd!$Ls2oT_Z}LZSYc2{OgovtdE;SEDJ)6q3glY0gj87~xjFoN3&l04w$tj+cV9uy=
zB|xGYyl-I#Z9r-{Kw1MDRm23h*{Je4VZduck40nxG$dQR(w>@#udb!Qg(qzLokD(1
zqPix}4i$%J!a^X5dK=m*$UA65Tg9O)14alxluXm!03b>m+8Y2FXhUi`5*QltbnrtY
zJsMH)aq9SU);7`cCyM@i=sr{DUs}0a+4vkcv??0!lww%QrR;j3tRNqX9bg-0-#8eI
zpMB$CQh+`fq_2ju&ipsU4{Cv+Np=c3iK60d>gGdr`V|=k@q;oU=#-s8*5>XCfOGOT
zNh_M`)W_DzQP#F1T>Mgq!xUWVPP+BGAs|=nyrR_9Lu9UP=aJNES|LPNom!;Sc@hed
z%ufdhw_fk;a@#h%r04<lOR*ux`Fqz!g+g*WS|JCw%(J4@mV{1oD=Tm(fth%53H@rP
zxCXO?nKjOiqFj;?C{*_)0U?DN3*dX(eb<!JX0=E)@7R3zvrU^6E<mVvD)&}xzGqOO
zxT?nOl&;~$Ld&2cf-;eVw3zk4^oF3B_B2TlDbi2#+G&D(3+GxK4rM_>N#!OB%0?*G
z#P)i8<4kIw&)8TK8}%8RY=(?HQ_KNYYS~BN+dHZNAxTxF&`=Lfg$x&At@v|q+bNdw
zsaFV4o!j$lM@gKn0uJ0Mb&{<A7E%1$c0OB>>f~5c?5Ax9$C^+-ZJT@)c{`g-p*Vt~
z;-p5jzDrp5I_~<}w{!T65rr~;)TtXe4RsF3fP6cLEe7P<Iow8;(e#_QO&?in^VUV-
z@%6dgcFB*q{Y_3DZ^=VfV$}kL+qBAs@*Y)5QC_}Pbrd)Bv6UuWl~VfoluD7)e$)fi
z*Ux9uC}P?fGEDVlEmF60(<x%!Mpa>Px+<|ItWeczg}QTW1zo8ob*t+VMchrdB})BT
z-;}h)!=viUQg5pov@stQsioe>GPcpiU)-EuaI`C#dJ%GZLw$0Bwai)lSN^O_(mb}Z
zyymO`Jhg(V09?Itg4fn5Y(m{?-9PHoff7@0XT1rcRquhAay!dbl7HF(h@7v8Gs`Gf
zubA}q$j`S&2f9N7QiUuF6M~PL-depYVwQq;HmJs3k$nfBPfQkj#q+8QT7=bvx&TS&
zNAFFKyrp<_!JhEl*A-r8Na|h5arHMLVQud3()^)|%_l2!*E2TK^y<-jX2EYhNKrQ)
zxqU~HlC}5NEywn3-G=fAvz=q5xo{xdWThikpOBV*ZoNVfIt|J!+tGDX!me<1#dyK=
z&>1R5<HSm@tWH^gy?VsxI>AAL@?`b*>XW1ETdy1)U4<~gbUf#em&`O>5n43m^m@>v
zYD$+Ll(jw;uw{v}c?3y)mJIf}b%}*lxR#B9tl4Z}7+0AmMsn$@4q($&okpbd@*BA2
z6lIl>5l2weCALB@L735E2i!tkVvtvkpEWL&T=8@3lz*Zwu_L`?Ag>a)tw$UT-OHSl
z%0u@O0$dGVCLP=ZRnT>?rh7j5VSnxQ<VW0ouSY)~eLZ5FRx4zLs^cQz!1mhvc|N;z
zCzzR6;yDkDIFEhQ34_zu$JQwX)MweI^V?<ILnU?9JhTA^Q1^?yP&nOnW=E}+u85@7
z&QF(}=fS7%G8N+tcLv-sT7{SZNy%xJn+fM{+8+*(g2SWyOgL}Hscsga2J~>C9C!sH
zP5Ajc>zyo09Q_q!1W!b-$RzkL768NR>!Wrmy%50${pVmo87dGR)5}sZ8wOTBr^bQl
zYM7{<JEU8~LDPqfzxm$oid=%1rzfg!jt(c~*u73m%7*TAWajiyPN!r(O&j4*O6Ff;
zZpWuCF&C#EAte_fKBR+V!l2!UPLApLmhO;DH|m3p{ED7cbKon&6I!JBjx=*b>@4gP
z@C7H<l<JVa#Xk9_KInh!6$6FjsXlG<Y_2a&Ne`6Z*~AtEF!!>KAW^HU2$I3D&@=1_
zsa?GSpI~L^v)3F$(VXSX#(6X4N<t`5pXH}a#&_CG4tbS(MLEG-(Pw$HZ!l}~W(Ti!
zXLhRJQyK>l^a<GWlIOga6=lZxF?qniAK&T8eudXQIj+|lY6mO|BMP9b$*gigGlLiY
zNK*2mf*uUKsF(*RTC-vvpjlnaoiU^p_DgbuFo<5pn5zXY6XQytCSAINE`&8K5~CTg
zk+1C10}hIT3#rHS3Rb$Hwj|Kh0aEOmt1EhBt&n1sfcxAp8CmeJuDZIGg+h)Xkpa2&
zs{A;jWCCpqffm?Wm&`7JsXqE8l>>j?F9`$wTfcOfuu|hy0WTA8o=ZMzAZHVGEGcUT
zUOFz29lI!;1s+@%k#QC!B<<2`o+Z&P-8fe|aQm&mhAXbx`&0nrmHR+w<HQW_geNzE
zs`VQYY>4OTWk0(BlGJZqIQJPXM#_co^}B5!iRq|-r6Cg;P<D(oi}~DAFM$ZRD2!Fa
zoqB7%v+hy{8vOARu6hSv{0ip^ahBN)#ikZoU$$~=3WrMY_9IA)+RT|&Ax%Rj_ks>&
z&}KXnZt0*IB-S$o^8h7BCeI>b3Kwpni;~0P(QsoQWF+ZYLzo>Gg~M~KQ3W)nA%w__
zuZRhYDLfTcd#6ek2#$)$90~iVh|D#IijG2E)?UUuCgS%;Z&5%cF3?GakizQl=;e8*
zo29cF17pOFMY%|cc|P(u-Kl`}igrSb7{E3`$(fh_046LFqmCh2kB)%njG5~)h>&Qa
zqh>pV-cLQkVZ-y2_39Yt<Qcp3<P@ESQVf`;es%>~=M=pncTly%Rj!<oPF~ioC->~4
zP=R~$S>nRIiGcO^BVCgSYIh;|u<(eVTRK5rO)e`LBA{GwBQ0hqB#(@&cj3h#^8QHp
z+>@j`dPOD;LiL?sQVfT3)XibMzn@p7OQhM?3tR!2175%hFd}+EAe^c40WA0cDVd<;
znT(P0vyux~*_NpU4o(vJEQ;UeuPBQZQBz(C{%1&#;)R%m;X-$71b*>K#0OtpF+@!H
z@XD)4T8N`^62qvxqKX(tMX={eL0N#%9A6ge<>=zw=9S5Q;{8K_=}LidA@en$vN>aj
z7*yqzgbrkd!z<?;T=U8@2UeX|PB~!moJrzfhzl2yVO5L5#G^dQUB*GiNG%G)HB$GT
z@Qz1I1EvQcWCPx|TP2EhaK948I(|~pZBZ!1E4Mte)`?-B30pb%N(@6m+sYgVz~q}x
z?2<gH#IOk-RbtqTxhVM?Lvm9AyM`Qiw+F3U9p!l&#p2PA=6|oWxY#)!V5tauiaNaf
z0h~oma*hmf7f$O6UyA8BBp{+taZ`R6vbJ4-u@Su#e^Z%^4IkPv85_RDOvZej5Dxzp
zRq9-Yy&KY*z3sV;aXEY2k{g5Xt#TVte7b8odHZ<fIwSAcw_InW8!vQ!PGDfPu1SUz
zW<h|L%Kf?WnvVu^s8?chf>ggLLvxrIF;(7-ZVCc3DKD<#&?HiybRsZE=IfI`!z9$D
zJbEQFH*EhlYXz|XE1?-?Qg1>|Y7bUL8>XM{)|LNCQ<68q0d>lPpc(p!3F3NS5pgA&
zA+6RkS@!@br<Z@wFgM*5k^JhyBS%@wpfG>hQZTf;knQSCd1+}Z^%fInjdE=rq^+Wc
z!~s%{O4kPRzg>XrnIZ0-iE6;f_fC`1!MLYI;-`}RPTMkrpIikq8z2Z>*5=lMo9?Q!
z**Z#mD@_vyQ?C@`4vj^@Weug$qZT%^@6*)bm51D+jR@wxp)AXy5YHgyjH2!Y3<wr>
z!5QRyyz-T^jEq;hG784B7)YQZKp1+#89*R90S%fu5zqhv(F@RkBB25Si!`!sNv;EO
zL!EV28(jWgNzF(KU6j1W(nqZdDK7;}MHv-*dZ-h>oJR)&=K?}vqL+>V1k<o&OH$A)
zM+XJA3+2Ei6Fe5+=!@bom;q%%>7`DYnEJG2g0HF;<JU2P*fFmJY=o$}%1Nxk%d2&#
ztA>@C7l}wFI4V@8qQ$rh<HaC`LJb=zz_dsMgp@+v%<u>~EBR(n7d}J$nWkPm?_n!t
z!Jnk0@ahJKt<<}Y9hgeJ7e*IsrK~0NQkiY<w?;J7jVLcey)+_d5WR3-Cb|{O3zW-V
zI4@JZ5Vz9cO2`^X*=8rA&RpsQxSm^GV4G|(^0ORM{!#R*Y;%}M-KAc@J|9({(vHh$
zF_%+?(PGXdb;OFfLMm6Rn5(!;qY0e_rjo=i7~O0tN%c~#cdwjwAYx}7tHgEc(IVPa
zR}aE5;WeU?)@^#0%EB+gud+x$x^nd>q^sC`F2#OAldMGfiR>>{>3T&NSaxIX{KVNH
zhf&LPPOoHoq;tAAKBN=T%jJk_u-AH}?8EBGl3*_ZiN#<t?vH3=`}oq7v5hYctK0Yh
zY*qt2h<+9$#GkMe;ob6fkQ0m`Yb<+~l-My|2mu*@=BigtJhxR$4Lk<ko4YW&SaOaP
z*IojSbCp7GmuCx8ax9&6&5H}(aXVaGZ)u;`P$$l5s1pF|raJNPytv+7lf-%ld;t<2
zUBSIX>~oj?dO^E#cTJG1Eu^o62TTek39Yfv5Yps$pyJ&NFof=c`G9fI<y9n>A*<%S
zgm>t!&=7(mx=UHUvHZeVxViiTtz1Ou(s$#@zyL#nIJ)azy_>qFup&;-<>Dk@<lzO~
zaC`m%2EwJM%K|u*LCGKG%9m{hiJmUkDI*8nd0iuL&<hO$k%NwKtR)P<*L2sNesd$o
zGZ<A=yZ|Hs<msvl2C&aV)ec{R26drK+&rnJ1Ux*c3kdckrwaHL4|^wutAR5zF(L8t
zlaj32P+jw7?*-x7!7OPQ4^(==UOZ6XNH`iw%)08RwJ1XCzCpT@cLH%8;$KnHm{OP;
z&w#Whi0e#AWg{6WAk_!AGJ?X^BGT6A1^aqIQVZi1EzA~b+6N^pMoy1;L)qgGLdVZ=
z4WHyI2_1Qqo`GfuNH+$T>%2k*4TH;NUX<}m`^NByOn*X6chwv@`!BQZXRld<;+g|u
z|9S$L6lXdx#)}sW0{o<m;shc9k59_LhsX*ju|+`&;l>FYAFQG!XzOwn^FX;ZHX&O>
zc!<=TCHS_{x3f4U%BOtvW+f3Bi?K+Y0od7Eu~QU>G^Tv^*2rHHfDx4v-5d8+wrWr1
zX6Q7jd{Ay|=$jzoBd4fp0kCF#Qh4IzZtZ~HBIN)iJ3b$qe8rRP4V^wf)kjF#PPt*Y
z)#1{CCC1vYN#Xee!lUzNfJ<pAJ9yM};FhTktTK0js|PSy9hMzHWH?b1!ryfKKz{Ii
z|D=$;DN((Nmq_GYBr+2V-@BNJb?)4KS=qqrU%KD$9*J@UxZrM#y{<T{U#}Yu>(}ds
zgK@j}y5qq7UUwXL-Rp`2uRE`}!KYU5yyvR40q?mgZE*c^QTKjn9(W-!u59miYa-<M
zqlsWY0-OuF#sLy10tP!JV4y|K2t0I?W&|EO{V&YI>a>4Id+Oe(7=eS%<yV;k=juD_
zpK$S2gTT4?s+;EiRmxz;znrL82ou{?$nH4|2$=IQRAC~ga_iCBG+XfAH_aA<fM(k{
z{i}3neDqQu<RUE+I&uDR)=4?<PTf}JjGVeH75t+kzip8)=TvT0-pHxks=U$Q5_h!n
z?ZF9-Qx7OiaG0J#Im2Ok2w^>keLRJt<WJMn2g6VN*reo&Ww@!HVVyP%z0{8XpS8Ey
z)h$P|!{+-b?y!5%Wit2^!KndDfIToIw?~F279;~k)j%=?+i&lW5o@h|GQ0C+<}D$C
zs>8S+H-9!aBN$w<f`G60yh*&*dnP5`>piy)`Y?1-d<LBuI!+GI`c9F;jkR@%W}mly
z!zo{$MJ%Z0?@1jGah;;sV}7q+6E>COOD+MzxhBDyV;$AvEYmn5w&qH588vM(yQvmF
z5<mqflgVBIDq)T6j<tu|`$qt-*L?y6*Xv>-f{WR$OTtPuq0be?7iZ2ublViJbs)O!
z^$CqVR0os10o!<;OJmcqsT81_o=v5<17z#<WC61Ed~tUT(0k7j=;2l+_He5y<4;%x
zP|E>C+7#q>AQd^Bc8~;Ieb6==AN|nHGf`Vp`Er5UVw&#1Cj5%E_==Az0hV$_sD)(-
zpxEor9Ds$<=~<GjM9bqLOzU-=5~lS!SHIM%g$v+V)~N;Noqk>z8US{szZOlKD%B*r
zsU42MSSe@9huq2RK73$98H#+!oy_jfEV1kKfek56z`b6__J9u?@73uHl}>c*Bje4Q
z>U4%m<M~##h4O~ioingiCuiUph1_}_{#Q_ylr|4It@qyGqPlQH!IpWmj@yR;PO2$5
z{>60hegcz!-dhbc4LvfHR(sG(GU(j865Oa%(}8mtxL+@*tMgi>1|6LrB*8mZ<n<KH
zcyObklP|GfIRbbtM}ePa-ON?zxH{+$9l_P1TzkRQK`-mLUXxM(HsP8XN}v~98QPGe
zjtE10ZO|{SWOz~L=Q9<oaZz1$J*f0|kw-t%Mhe{5m0%N~55?psAE4H|qIzi{!kP*t
z82~xu9U@wSp$K;5CnXz~mH0#ea+;<c5KLH;loSIIn$yIzHRydYWtF4%g`Cd>e&x+-
zbr1xJ({wC92+*D6mcEj@e#M{;@9LG<?eMN%C#J)z`Zt3o{4<L98K8^I8)wuSyi7)E
z<Axgh%bB>-uD5@9<ND@T=7p=0jL|n^$`~f!j4AmSfMU~>#_Mcd=VSGPQFD^&<O*<`
zPivk4u`el>T?hnD44gKgRv)0knxtNTG8Hxe2pj`WDT?D7hqw%V`NW7R`s=wO!X@}_
zOD8cS@J;MZWJb;Kl@OUxlRO*JD^BBwJOKd{OFl7jiSTF!34tRu6&E#^2hGHZoCDFo
zkJuP&R%Q52u-z%V3HqFOuoZCkKu{={qo+)QVDywJAPk-|g@XYAdlKWN?7Xu`a$mp=
zL2_4u$6%Q#*~2rDt7?j8Xd<OoqJi)ns1aq!oyasaMQZdA=r)xVcY^ooN;od;9euMy
z2iT^GIMNG!+Dt1C71DYBC3<a&rfGs?`9)dH$|Ez8n&SeW0Mn|T1E+Q+^${j6t=SiF
z*90H*6s;6sX-|r<8h}lk$R;~MJuR%+=Z`N?G>B(6Ed;PxznHe!xim}z=F%_?cnX0B
zy*fd!J(+=KB3&;Lc$}^mqjx0);9)-o=Iq7#-Ir9TFfDhaE`C9S#GOqgbH$2yzF-e0
zL0;r9Bl3(0My|BU;NmMFei5;11e#6db-I#8>?F!w0>0Su1%5dzSIARq_fWKe^yEuD
zM1pe3BJamk`mbpO1tnaRII_viYurO#$Z768kTgm55sWnl2>Pq3w3US$n@Tr1;l&h&
z_HMZ;&@wepL(HaS3axQBCcF+nv#takhF7DN)s>1e%Qf@H*GI!<8j-`i^`;WP5{?i-
zFXvFB(qgzGRx3MWoTF+8n>%{VKrCGeU|j?NjYGdMkv!wj@i-B2`a-DFEY9C3K9I)r
z3*jahh06Y~ItsuZC_y2(Yq|s?`3Ul#5u<<TH^4z>h_Uk?vaE3IM}l=VpuRLX@zNwZ
zloYbPY0L;T3ZAfe1Wnrt9|cm63~`fA5JC;nmrl6;Mrh6lC^<)vF^6aLLC%f|U*Jb@
zOK=5To3dtUGB`q{xP^ZhB4~x@;u^1*hRM(fsgTLw2)@^cfQ2De5<(P4(D35*e#Tf-
z_i?>Hg6Fn}Zlxho6hH~maK|7JBT;9t>jBG%5OlvT(w`yfT)N(d=ym60yaaF6=?J_M
z_J1O@AZQ-ZNjbtafU*EabTu|HTUuzO?-)UU6kWbNN&QtW=MmcINsbZ3qfGEsd>+(L
ztN<Wx;AEX}SuD8Y7=F~w8(0KaA+CdlSdV9MJ2*+&Cutj;PpFt8ttn)B8LsUaiI#@g
zm}k)`IF0=Ytk)2y^F#tC9I>ls2s26w=n3@K5J&U`0of3d&nyzNA*$&)kwtWfi+aLy
zI$YKVi4nwUJr~xz^Kd;$AU9kqWOY>20)b2QN*2o59h%Au8=`lH_e?PHrE>-StL5$R
zAWk@3>FBwVfgrBNyUGb9+1T24D#U*u4HEINzj%zT_bK&|jM)3dQz|C%ea=MqpbT2@
zj*TrHU(xx`^_5`^Qz4IRd?DgdO9Zanv9}suh<My}n=s+)9io|^jJFrh)x7ccn~tK1
zVBfKqUM=ptJ|YzJm2F;gOk|cDd+ObThecfb6XC#PGbrauY{?H=g6jOx01>^kO#^gA
z$Sxcp7%#uIW<Y1MyGDqwYj=$@zpgDqav|-@*eq5vIy9|Q9%XccF|4u^7z1CP>8B(W
zYRuss1V(FXL3)O<q_B3&(yG4^XD<S{i4Ke<({HCPT68Q-g}%d!FctZ(+_H05z&2(=
zq3^u3oS2o7Nh>CT*m?S&8(-pBGVm10E)AqWcC8V3&BxLjsrU6<3DyV#p~u3N(o`6`
z)(FGcwL}!h{vJpa$BsP(tjA;N@Bz@^SUP}j=(mOV%xA(IKbDTt8{{2J`UT5-FyG0<
z7ciy{#hbCS%Aqpx;S7vug8U)AR3Q%nCm5gp44oqo$v$QBGm>3Mj|p<SA-KQ<WD!?)
zcNfGhz|c+iM1G2)>*&egcA}pqV%v3}J2!U-;ko8629EhwDFTS8H;GvHIlok?mIwXG
zbCZJOT>#)>n(qn#@shBH6MN<;z~YmFTt~WJn+%HAMcHIf{KR2%7hec}k1LO%i>oUF
z4+(xR5|X#hs=H=Y$T=8DkTDT0ult@WC`uOjLiPdEi?m6F#;eXV5vTskO1^Z<UIIQB
zEqT*beU@O50IxkOu6+pOJ&~Vd=+5LyiY^9ifOmfkkw~ZLPO@$)CZp}g`ckbJapVeN
z{Cy?pdmze}K4gF(S-=?cOSPJ*p~iCO8iSP0lQH^?Stv<9*uGS%9%A!w>}2xO&$_XB
z3fzH8uu=xrPMI%5{`HAVouPbolY#w1v?UYwJc&-xkMbL_qvsYElT^rM1W=^RbijcI
z;%lZ4Q8B3kn3()arR<wh7|!Gh7^bx5S3ue*=X1##_0~y>EA1LcTQL~<^i0S8seq}8
zWEVqGR+DrD#*M>^8AORHC$FxC%`cT|1o9Sm(jh6Y=0q}%p^&r*2=FkmvrOdhxT3dO
zje(`=znrvy4Ug9)TXyu5C@`FFz>zRscPp;ah#iCEjzH;Jr{l(UC`fQ3S;>$$6&G-X
zsX=nv>hYygv3bdP>M#IBr#5kG_j0by&-vlyWSd}c81#ujG>ge?p=@A(!x-UA=u7Ji
z#13GPyJd`UeW_F<oL?&Ci|f)G4rB9mb2@SfUcNgn64;-w-x9ZsLn)&t86*1py0PL%
zS8*1HA75OVtgrvkUm8HZH_`x#>T!~Hf+@&n=D!)rYCb`AaV4C8D6IBw^W>^fMD=v&
zu*Q$w#fI3`-+a~W{n#BeSFdLfDSZ-ni3tT8Op{Rn1p0VAe;%+-n+}(C13O;FAE`5b
zSu3COwNf3?e^D(bwN1@CC<>a6o1pm^is+w!#6Lp`J181t2AIXu(M%H`n0UD-aHa<&
z_MvEofU_k@9?Exn$8q6xEjlO^5a<6ulwEFL=D8S9>5l+2Nuq(#RC%`yDeqE?y&_Hq
zn7x(XWx{=7$2AwP1O_fHzc1*S({YLb_0{PTa3=us_<1!t5}POX`V|y9d-Ad46wzy_
z!<0;QxHwbit8^&hX&~bl?7Sa2%T2v42Hf`(htt-MeVNdmbM?#8`-y|F{q!%hTaqtd
zG<e>RzGw*Ie3?35DR`$Y1)*sw&RivJf+(W|-VxntzQG0Wh)S})bhwDC<r0MG3m5bM
z^5fq<{m1?9zx<y+Iy`p^pB}M|&>8>bKmPbn&mC9$JmS~?|Ed1p|MT-HfByTYC~}<j
zV_jAc`#i7z_~*Yp|J{H3r}j_n)7C%#r{{nBhkyRZKK&p5%YXfk|M<WE^Z)q#5C8n!
z)xRR_^UU4PZuj9I(|>RO@$dibkN^CscOPE=`yc-Hba=T|roZ}I5*XdtSxAR<hxP}1
zn}p)u_4XhB=l|pX{>Oj*zp9skM-8|2Y5#N3ZyxibcK+3FA}*P|%*ebu$A7+;qbO0o
z>E-|WKm8l^a^9(&cM8X`zCV9>`^;+pS35ayQN&&nS^Bk?|FROUJ5&h)*WXt{toTZo
z^WT1`eA=I#kD1h%->$KL^N(x&!+-tjUw_=0(K0(+W_{l`_xWSZev{+<Yg3cAQR^M$
zw6DwV`wsuB&#S#|fm8PLz`ER`;5X)t)c{et{itpTv-D@y`{xug+rG>4g4X`^#q>{~
zBa2qkpC4b^fA8pE4t_Vb3C0{%qTqL`71Zgi#pHnBR@$Yf-ddZA>)UGBb2R-F{JH7>
z?85%}#3H@g$A4q`e}3{O(!{@`8zdL}c67K#f2#?G@Le@rT)x$Y43KZD;ST4mrc0e~
ztL=&J5YFBCr+0g;{_8RSjji;b+TXMK2MD|0u_-I_w__{*h_@E`B)+W#7N574Xnnq`
z#*j8uqu_U{MLD+h0x0-%s_Y~0-Xk(nv;FH|z>oIxFTmj1eMh&)A6UwU0G+p*B6hy5
z2GW(cn#iiZt(II!Z>4U(yGM4UJJ9rZ<v;jyU%*HIUKnrEo&DDI|2<y-hz>P4lz(S*
zyZ>@2Q}8?0a8dkL6Z`SE)j&-CRufbCx7B**(!wj~{mat&(_cXE9|Q4U--Ler9XjC5
zU#{dc|G+|a|K&P%{{zc7Z<<tPx8GOv<5zlq{DHl(JdE$Qv)|?Pr&s+Yj{l8C|92TZ
z=a;MZ{DHOm#SWyPf45PAC*!Rq0dFw=#Ee`T`nf*(;>WttBfn*c{M3}BN9FA%ir<dy
zl%waZB*C}UI<SLpy;t&mMc~4}RFvfViXck=Qc;qhcn$pqZtc%*aK3*JKk*hi!i~Q4
zRFdz92<OI^ijsU^@j8jVRzvyQN+kY!tG$x%D<ZDoOGQb3;!RjWvw!!C_&Lo;x~DIF
zmE`+D?q41e|MugRd|$E1dB4=7;QMND4t}X8$+s0NZ_Hbb<)3&H=_Ze{&iw98{FI3}
zkg4-aKPCBoct}$4rJ^L?R|IR&mx_{nUorZx-ux^1zT$~rzIh3L=3U$nlrmPneHTBc
zItvf~RS`<^?GQ;^_tld^$@dijxcI7iDfzx4A|bz2l;r!0F}_yH(oejHbj<($H}O+O
zBT|xm>7^v!4(&R2ezDLb_`cd0zk2Jh<ok+9-SMTOB;Qv=LWD0BCHWcC>4LWQ?|u_M
zXFDx$j(_Q^B)_w?e`$yQ(#HJjk6%CdH#fR`6}`XPNBYzx_;cpXXQs;C)iZt4Z#Z1$
z&ur!FC<rL-R-P9klKkEXi+A=*JrdD=U#%iNzEorA$G6p5u?)S{Ao#s%^l;)Ww67k{
zKmQWiC6)gT%Vzu?FQI`}?#uA@`Cgx*A`-8EsknFz{C!2xh<>R!?GLqxbYovCDgoK|
z6#+?j--R#=Klw6l*w1gg4EuXt22w+Q8KIIzemBAs!2wo13Vx>=g2dlyN)qyIH4rVl
z)pq~RQO#<|5zV*2@=v~mb8(x$bqVtG@8BRz{T-a**1sJb;;r6lBJ%#WT61`_SgrYY
z-YirLBx_Z*Q1;eutH}*qZy<ig3w&wG%dCw5#$I6da_?UaZtp)bxHZ01$&_5*{yeEX
z-U?v$__m7eFBLMn`rDtwQH;6%;wS#|Gkrl;{|&v3=%F88jA2j|d_ORc3QKsa1>;Y?
ztp@DnTh03)X>G-?T3hi)S_9b==bz=Dd;@-yu>Qsy_&audAG}WE;KsMtX{-jY-&;-S
zzi+D{fcvf1<{xNnBeRXFZKb;Twi>W=d;={1<Qv#GuhDPpHh+f!wD<Vc;P$r{ajb@r
zskho{Uq<(v)qZXA?muMlZls!ht10*Fx7FHVYxM@&`O?^*e*-s4{5QUVzv~?E#WO?6
zw+AL<=K50cmHfo1@WNE<fZqFmW3N>QE610vei8kSFZUNygW}IPs&5p_#;w)2o}i!E
z$PB!jU%L85^t&F?UoC(yqMvaDU-I@pG}511uC1VuU)Sp^`rfgJ?7Ls9zM`LT?%fd8
z{zpc-f5xwbEcRcz`$hCSzKs0~pTpmNypo@Bp54HhKQzwxDgRjkg}?Up75$DYEPlNh
zzKDM6R&V}gjo;see#YFR1L<pLU(xS)&ws5+ezj@;^~b+>`X3p0j`^SN=<hvzjWxpl
zGV5jkdf5Np9rc%M`2Cj?7JYnbUsSl1(m(vanx5}qsrR<~|M^Y55&+z$TDglM7-1e2
z0ToV&8=}?2>+}%yTktp_xILWylqe8#I5`fAHtZu{#0Qwx!x;mVEMiXz&|=*rgctA_
zq+;O=E{u#-3TJ2-IL5*iYlz_eaKg($#C`>+Gte!D5JY0O!)dDoh(tqqKBJ;{u3%NM
z=R}dF3e4@{aGfQPG!TjMWO?UYF^>{bF@_S5#>xVkTbSBHsRJt=E^=9%NUp^2i<($Q
zG**trPzu!87yvyWfxx#=m^>IE!bwtxESBL6R0^-j=V2TP9K(nD<(PapEQ^>T6jL9L
z*GpcM2=t2~Z4vAjaq-Cbcm-%Sa&k%66M?x!L^TLC!i}+N5g1uEa4;&Ocq)fxD2pvn
z@u5t&aVqF4oGAO#F#V+X1cyi{`2I9>qP<lPs-Rb=qa&>fw-XA?M=H%Ls9v3-9!NpM
zFRE9YG25VAy8^UXh1#q^zxEMSAy?F9curBVJt@h(;269WjLj-0mQcRpQ`ohSpbFJp
zoYS5k@Yn<?0zMmmY;u=_KR-kc03c9ox`z;JaeX7;u{f{$1P`qKFf<&jZm}8Ucj`9t
z3ef7p(h|J@upFTb&>0pIA{zjXEtoO7@_l9*!4;=I=qt$|)E6I{;X!9(U<9oeAzW-k
z3?7W{3hKiIKU@Gqdi*c-b9B(rBeD-2N0$_ajJTTEL@*)4=oPFg=2Bz0;R(Duf)Nj>
zC}T5NrBVWX1pI74Ef<?n%-|A=O;*Wsusp27hY=(co3SmIq9}`K^k87hINqSHw$iP(
z#*Q&BagLl}OdTOkv6aZUK_vkIcFVP_8h5NKs&&=$%z8u0m)y#a6H5uT8`RRmf%8ex
zoz<l@+zpy(DIsq&IPVTys!i_-*wpxpZYkq4(wT-R7dlcM#G6(gJXBZ0hk%djBSP_Z
zObM#NYIh~IzjZ_t1ZfyPwnY}e?%a_r_9Lo)L>H9yxIr7OtxiE7EhS5Ct2F&mGVQj|
zaphQU^<73%Ido(_jim&=nR_9YNZ+p@7tLB~rgV5LWqof@Qfullj?TTAa$D)CMQX<m
zy0R<bbD*i#RCfTWKvus4-JN8|@1Q~Zi135^Q02F7&{SlM=%7`LHPkLrb%jVII?}1e
z8fv&SmS`n960DY6xFaw#mgvGeQc%P)wtVo)m7l%0ETK_w{>35-_?4vL7c&2^Xl1!}
zi4M-XSW5bggsrhal6PUL+4W8mpew1q(@?*X>VMaRJG$TWVCcHlKw#2)l{gw`yM+(G
zL*dDdbtScEo7zQ=!7F0JrS#@eyA_QY^Kd}5M}{~wdT|b3L8WsB@;zqgA+t)DSSUkL
zYFtTnb_P0M>1|_%`UPb-l{6gLWUqwJEtL~O`S;2y@}y`%u(HHCfxc6EkdA=pP@a#^
z>FrYzJxd48WFR?32RC6TnNKh5MKGyE@2Sy{(WrN1LJ#qCbof_-sg!yJgU3`lZ)Cd-
zr7F0RTr+bj!FPw!no1py$n#+8fevEN5UWQ=65N;-sr!^DziH(XxRRA+>~@HQ57PU0
z&=-ahf%Rl2y`#)8)NY%`A46-2?xQ0>|06-EW|#(Rx6V1E&3Z*OXG%nF&{|^2?*^?U
zmi%5EuTO|Mq=N?bBSEQVRk`1hMK_c;uOpLg%%+*Qkwt7JNSgbRpv3zrKC(_<BB<}i
z<ChrfJJRD`2|HTHmX8Fby5<T!6*_GM7@YcDLL!v!ApeaK>L>Kt2u%<4+6c7@!|x+P
zF}u#&i7UtzHemI3r0)%-lB9n$hA8?v*p9D=EvKd%u6Cj52JPdH1iwK(_oss~GDHI3
zku5hw0^h-!5n^=jMf)7e+u6-I`%9yO>SO-Tj<mob!uF1&xq&RAJt;k6EIJE1Qs#!3
zQ#y!1LZs~-QH&wd_6}moE5SBjJlY}3_Kv8Q0A+gz8+VAZy@Rnk#J<uE#K19VSNHKz
ze}hJK2VOTs*xr$EIFwVi51ij#uJv9?h(lEC9oJnUvh|LvI|0U)4qBEFW6RSAiZ!z!
z*^I&4#Ex{iSHfnX%SKl-)MX%f>A0pHGNzHpCkAb4u*k>gYPvMpXzu`doeZ@K`kGtD
zCNpqwv!l-OdKn-1lcL)h5vO;&@lc3T$EpbOrgw0JhRHg<Ywbw^zImjq4Z&tQxO}dJ
zE$u9^m4Zq}Ql>wU<m8Goz2oZ%V~rY(tJTtP=4uo<!Gh%I9XTLE39UOa!iLEluDlgt
zvWCGcdL{4}bZlRBIp1?@`xIm!gJkqd*cB)^lYv}ROizliDS&r0Y^mu~aN<YrNa`9G
zO}*MMQ66<9APHqD@5tX8VoUFp*(5}k-l0QoM0l0zn>6X!*|Su84zyM%2YXNMtI$<p
z2P0|N(1d|7>mx#`dPz!+4uaA!+Qp@nLj>u)65~86V!P0aCfgXPM8o(IcjV;>lX3jf
z{9#=dIT*pN2rc7eXI)K0af(yDBQ;SVMcY%NTm-V7ktHcas@}`oxdOB_v9M$<(`ve+
z`bqtsU5BphGJ}!9>PqlTsLJA3e;_KH$l)^!C_=W7j+|f7kNOU6+37)kI!IANtU(=?
zWlAvpsV&98-a(Wa9rp7C<<1qbZK%&4YTGeL8QDm+7hOg+8SO%BLmgoI=rWMgYLC9v
zJ7_*pw0GG4S5lh}0=BP!{e$8oXZsacJ(kTt?{&D8pA_Z76pK+u{_N;WZ68cJ6gAE|
zA-eazz~p#E#^2P8)4SaBSQVmw??}2GqC&co8smG&277Asp=vnSDLA-iGxRU>rYS^~
z)E9EG1_|Fg&a79!&cSur2TIiud)vTl+uJqhzHVx|be~A!`+|$J({5kzaN?+WU%-NT
z?1mrY9?)gDubCxmk?<r$mxW&5hNncBN1Wn%Q_r9XyDV(DKd$7hRnFl~e!mVk%14r=
zj~Z+;!57qElMN21OjLq^2cn$lcGNC(VLNKKbYYX34r<kpBukF(N3>8^l;dmgJ9nh&
z3Q^2o$;vXDg@d!zJ_E;Bh++Op?z?L=!hxuYCL?^6>TEQ)pDU@3>dQuEuMlMMN~*70
zEkSjXhW-k!P10n8!yy<=HaMJy(e$yyu^5eh>Apd67$T$U<)4fus~j1_qR}efxXx>`
z%E7OCCAHCjUo}Ku)pu23yB#BxO`e3R(I(sA(NlC+9ek?MV1O4>YBZVFAW97}=6CSn
zMw8R}imIza&xHzY1J51#H~S6!*@pT)ur)N9=wRy&(eQTwFs=j})h-3vWTC^g{sfr$
zJ9ty0nHn#R+NAEmq#8|TJF=QZ>pB8~qc|EZ?z&b8@o;rqJVcWN8#fct8hIf*ZZD$A
z=HAeVjV|n@GYwI9b?}+`kq3K&9Pf(QxMv9)09Z+{1kZGUD&?%Ms~vzUA4oDn`{?rq
zi>M!&)4P<PqwD#2Kk`m*q)xh`q2JtpbdrJfVhnX9BIsZY{YY-fOQrb{0boa-_$$Kr
zKoRPq59>)0>dIws%hh#Q<WGuDPD<L}$hzjD7weT-{tDPiZS8(!e>)O!UJ*6~FFVqY
zjOXMR_aoEU4PBXE>ICZ0k%~K2KTOWvaqaq%pp>1Ht_78*ld`PW#qN_5woK%#tZp!6
zUI{jRpIKs~)w~ze*#l9nC0f}|fUeAJpY=**Wc$P`wRiRx-m5-4kX8DTl?`f2KXO5X
zhw@6`C;_FUD>cNWS@NTkG1wyg$fgE8<dv`;&_Vi<nGN#CE5RstjY(!Ucpe?JQXQO*
zx6C~PAcZSp+m3}Qb36$dJ!Fi7Yw=1r!t$Vc$SDmp#FbRj<<fFxsOaDl^pK(L<vMd^
zsOSK4c*xWS*26&**Apq?AsZS{5)aoV0pd6hd8+-ObMjP2ZCwsNt6RQnH|VK;I>0Qh
z#1<WB77tnCz_Yk=U336it|XxNqhkaz&!gVE2VB}wE5nrzqXU-W;<f9EOL<a)4;{#q
zD|u^G2WeNw_!ML@$G|IjEoMMhu82>q@9;|a)PeUl^;FF7B>JQySB5KRM#n#133h|3
z?;)>t^&=(4!FVM#dor~nYt&!4*n`$FGU{CcHU>aYK9UE;`+NDT!5ZiyT<XZL=OJS_
zJWG6_*E#=!qpDbwC1*8q?|H~s9Z+H+Yq}6BS3qxUAyBRerF{7=V>y?)yEG*}26uU@
z6H)S92};=up`bbv#W?9_dVRUB6dfHOw-+a9b_?IXD{n`~9^o$c^np@yeSf*txC@ri
zfmCs(_vk>XxXU;ORK=C=qXVkq{@Tk0SaE@>Ix_FL(-a0A#gzi2pDOX8z~{J7R2{^Z
zSHh>JCUjZB2b$1j1|MibUv%^zC_<MVe4q${r@H0rysTj0SKMg{KOF!TcbUS6aUF6`
zLzlYKJpO1}7sRTUCVo<cf379!@=ZgdUkOLda1z<ig>-ROdg~6XiwmlC8JB8=GM{0D
zxXT)bo#OsFtUrc~E4@iaK0|le!mxcD2~TdhIwuvJc$TLmm~3b{g}-z_TCRjGLCv`w
z)|CYDNzsB}WeK|hkT34Eo{wWV@>gf8O&51yd~=sIeFC$s&mS-q-!g*%RB<4$o)WDT
zyp^&mTi$9|(Y|3V8*Fdi^j2G|8$cK2%3#1>No^$tEB{KWsVlkfe$!)p1$jF09c&5;
zY}3TPk{VQ?R0DD~+;coiXKX;YToIlL1t)-(0juJBt0$vMtvU*)tM9EU&|Z6^lyfgm
zL&H(e_tN;Gy7uB-qJc8mH_c^3;zn1>mn*rS^ImFsVrCagW!CPgrlH#i!!kf%u3%#l
zSC-i5Lht8Y5r!kS3x;JlyZavM)kY_Vy0!6o2lGi9(mwjOFAu7o7`x_KV7Kax_%?OT
z>j-c~Y#NGB=qiKj<4W4%Z*paIHSAnjoh=7eR#)rLjk~LL=trTnEKx7MJ1MEHFfAWZ
z<8u$j(DdAcrBar$Rph!WVU0EL2K%DfYaI%4!R$4pLv&%VtV18JvU)86E4~C_HXv4f
z(FJWltoWh}+Q63XE7UU7VZpK<i0%?xp{8;2Lw+0ssKpmu&<01KD`C!K@D%zAHEtLr
zeb84@U3NVP8j$cUOW)|7D_Xe*2kMoue^760|Alp`H~PNel)aL=8?!#Mgk1)>6<<qT
zgL+#_?LxgNA<vbhL(zrVGB}N|giTLO`QnJ6-qup<t0sI>ml-_RSH#wF^iy6RLoQ8U
zLw(-p;h?j?3b5j9sDsdGYp8?JXlt;8P-t)@e=Myls>L_(gZoT6p>Mh7+tfGcvt?>G
zvIL}}b)4Cju~8^EA+oNdMq?;dh-p`=IMS`IR&jt^U1NhvTr|54`8j>HFST;oU5G2I
z+`FzI2}62bUvxnmE}T9RlrnHtNqP-eR!(r08C2UmY6Yro(g|(23v<xrJSD0Jv)!^X
zTorOO!eberGCqUtTDf1ZgbnAUUjf_2X>Nv^saNTOX&JIJKQ1l+Lza&#;e$r@)-`WX
zivnR?N%h$2Qn{k)^41`r7LhF}1=-`RrlA#)Sn#e<plDoZEyE42&#l&>8t2xq?qio4
zMiLQc#wEi=vd^Wap+157GK2n{OYPSAaW1J1U}>(1?QRTls_k84q#DO{x)T`oq^O2C
z(X{8^d?eKAlp+Uc#wTrSGaz+boREfGtXG1ER_}*~15fB2nnozoIhZrR0Hg6q_p|{<
z<H`<Y38cAYwv5weWsAyk>YyuN+x5uWBdjzj@<bW3*}G6-hK%=DVhORa1b6tPSNfK#
zN!rm@QVWuHv;iJ-B}f@+z>)ZbSK10`;*)M^13JbB-O>hhjE|$n5$52+hh0&i8e1<r
z=St8N4wB=jtvpB$`Kk?&92aEFz*_D@hBUG<`KVEU)ZcKm$-~`nO(pc-pdtns#s%au
z;FdlTlyV-2Jk?i}6FIhq3*D#WRabH+a!6GVs6K#Ko)T5S{l*XS8&+;B`^bIB@CFXX
z1?akxGPs6}W`NIp@M}ZDEgv$PF&92$IAg*dAH+=?((L+}niZ(NF|%|ZpzjgjyDPb^
zJ}Ieb9%>e9ZwxgH)i-307h2{D0BbkEWn7RhL!L4pw7mh1@ge&=p)o#WeGdR0e8~F7
z;&nl~3`^dJjBO<9y^?BamTr8m1dpyvy)MYs6;y}29t;IJ=$JO7$MDhUEx4i@1nuwK
z3~mu)0&vEG>N22aZka73@41hrrg20Zve9eLag&8U;Q}@4b0BA~04NaybjFc1%mAFZ
zWwu?f=StXgZK@7p)Vn6I^SaPsmRqwc+n8bVc9V&Y9o~_C%qFtAxP@9O9V#%G0XyR+
zdwfELDn*$gY4CGJYzjKm98InKn<K1)s}nC~fY<n&)XV^|aocJbI@Dz4mjZT^kq-h`
zw=(h{Lz+Yv?97lt*i9Dt^ekbo0W8Lq2F)hVn?~z=mi99l-pC>Bf`b`sBDbjrL;00e
z@<3ECaq_{b{A_CW1B*rG`wVoSe(cW}>j!KY-d9qn8EnZb;8ROQCPvH>+2UqA^8nd$
zCD^QhZ1GI9W|e}|jecx{A?-qKT}d5zlz7c59>T5bq0nho|BO?g(Uon;26`oQ+90#A
z3&v%cLe#CPVK_o9?QI-QydOOj=R~5oY|UG!zv{IMc4f!{>^=13+nRE>-E!@OT{bd~
zV%|dohkEO>nsKCa;jXMsea}n!VmKLI3EIZVuFI|lIop-6ap=76ydt%=vxtuyfEMqx
zn1N^UE|a<NEZ(;sO0_7cmMy5oE{nMi;#a^CK`nL}&5LTW(`a7Mid`yrK`R2PWviaR
zW}z4RYcV5nuy<L^K)!gF#k`;xh19ab!d$^!=ub&<F?N{D@P*tm8;7FoQ)7mv>@=+(
zORtLy?PUPITnV<C-LkamZ**Q3^F}r@7qrXDh2&l4@rFw5GLSb^A_%DrkQT4Rc@IR@
zR~pF)a=Aq|1BKY>!Zv_ht^^l{hOEJ^gnNeA#Vc7T=Q@zB4J3^B&V~)H$==mA6rz&!
z8GM7@Ws$>y=v@|h1#dnn!bXGyz%EuC1CYf9^Rfc6xKjBUfGm%<qfSG?H5%7&qk5CB
z-78DjR^W%d67E&-)m{-Bf<9~VZ12)QSAurRjdTUL$TXz;{fP1h&}L1Z?aK9g1sotw
ze@#aE-Z)SQ{AI+tG+EdLy9l*q0K2sPrBb;|n;hO7O0I2`a+N82puw&00%#dr|K1kw
z`3(01-sIli^#e8n=V@Cg)x^q5uW;}uMb6)l9*fPE#%r?DiH~U$rRuqEoQznPCTBK+
z;azB}E2(LeFB>UrucX2^t|VKQJ?&6@O%}C7`865TxNUOct)3KB7v;|`%uJJoP0UQA
zg-yszlQ)|eVcw*x37Kg!x&fPMvbhO~X*8#ah-pf>XBQIFU`^v{@0R(<)SOL*Gj0s`
zk>y;;U7r#){^&0Kt^894vWI<OIu{wlRysxl7-pX%6#+ENK5}m(3F{U&o&g_oC2V_V
ziR~gF;ffXn_f6e0TdwcsN;qp9WNR{|>!NrcAwvvVPxp~2ja(o5$W})7(M>Rz`Tb{^
zz#i<Ij9^@t?*mUa@@#G)y$tv6o5Z(P7xTNK`5#C!k;sv=8_1V^<m?6!%2xIpLw3o1
z-utWs$Xo&2K6v*urU5kAN3QN@pAw<gmn|P7lm?H65z5>KsAV51Uw~S+;9pm=vdpeU
zM_1(LMoPwgXgo*98<Iu_6y_sA=~|Tg$j=QJ%vPGqE2-I*pS!4ouYm2=4)W}yJs<}9
zZz$Eo%Cj9KM<c&>3=F2f;~N-_zINbhF5w@mO;G@1lZcfic4Kk&<<$l|%SVFJr$Wfa
z21IBRoOK1+ix9H<igH#%PVFeob|q{$*X9+l*;>9I2}(K4E%+AGa9#;ouA|-+aBQ9>
zHd+dCM=*ZIfS}m|bQ%8IAv-&wdM0%mfu5D6{gh~-*8805ogCN^=pN1SsDEZ(4`x23
zlQBD2g53c#xI?x$ur@nnjMtlZcE}h9+GYoBabRt>@LdM1%?{Y&K-%0gt;&SjTmf1J
zux5vBZvbnyFkd%sYtPm3`m2%3bq9>^!Y%HQ%No$eEijh>{<uRf>w|>AJ7jAETeAc9
zb|Pzb$YTv;%?{b$K-TPdJ=TEM?2yMAJHeH(?NRGN7CH8lD=9Aopfy*(#=-kY_}CQ$
z>R_WeGy4nE`rxp+1s7w&-YdZ~N*{*IX6(9G!mdFbhJu$3xS1VI4~9MrI<n8s0y|dr
z-*$Pi3pMkkh)qKw3N~hd(rlOQ4K21^ruRXd{dU^kr@)Qd<=8GoxLxWS!0GKW$Wekv
z;{^JvBRGIE9|=mJGiAS^`;>Ug%6fQ8gaJbNxm?|_Lp~Cea;AN&S2Y#ew~h%1y3c8d
zkJhqOA3XC@e<Uc?4AQAR(j<FQQnNe&m)XLC4KR*xpQ;5dM-<m6E|*(|<6yu#-A<SF
zfCc-Jpp<h)uQjuFUkRQ$IAudUflBkC@j<OQz1AaxA8wh=Lan*b)l4eB-PqK`8Zosr
zYe1%kCf111)uTZd3feW=t<w3>h0b<8bfL5LN#63^R-Kk}rcKYj_V<aHX}YVgq&nX;
zb0AH-A~ap9PcSZKdf(pu!XH%Eo0^91^G3^e09UiUsqK&U+ehuz!relGG3or3ER<7Y
zUjf_6Q{h%hfdLTBm9UjEc(;&XqYk)x3q3M$2;Mt1L@3N1XdB9Lhgv#S!pop`+^%Mz
z9k**hr5$@aru9_n@rqEqWR~qHP<0gYreyU#0K7>F)&ih6DZ&y1_9jLAj1qs75;PA7
zMv5?By?mY@k(Na7?00(~)!A|0NL*2MUT?T}^j%>20YFWP3NJd!GgKmW-m;@Y#}D|I
zQpDy;<E4n-Vn_DHCNpfnd6go}Un<BHaQaF^rU-p16`2xtVbt(KO8~yMkI2>9#EU3&
z{R0^~<(inqPVqWn6rd(0SS|q6qzKnF1CW}OEePs$$>bV+qlm$ke#{gfh*TZG;iQbM
z?V56$Tm$j4DOwN&E9IQjgD^Inp9TVPQ^FoNhBh_WauB6x)q|YlAhLeIwfzwd^(pWU
zhz%NWkf#Xu7z3D^l%Z3HuVtuHhqG(y)#2pY`|=KZ$^+DZ13yLRg|#Z8=hisohD-e`
z!i>|R8n`I<i0I}VxJyV8v}3_^QUWzS0K!RGjSnE4l;G0_sOBST>ZP$;qF);bqAywF
z&n9c~Va9$n6thn_D?cTw_aF;v*uZO$iFHNQbJwR1Ku(Idxg;bfC2W6SEjsJeN|cQ?
za3z%@&|C~$T$K!SK5Hp@sQrl-?15svT&Gj>8MZhO+<#ojsxs$nv4gHYFLu&VOk46(
z=8<avP?I7&c%y$?J>FQSuNh`IY^IDI*c`@I2R4Vov)3@c#ijNU!I3g_z_A`)iw&eT
zDPj*C>%o^gfDJEY*oi><@exhc4EB?k8N*OyACEdEbIuNXMSISuONF?<B6O;bSi?%i
zq(E(Pnev!52GyyM`eRU?I$fz_AV#cYjXzr@Ko3Ua;OeM#1$YHKYK_sWNV{lse3Wi#
zzH_wN7zWkmYs>-OP@*~?j!}Bko4QE7`C4y-dXwhcpwe{3!Hq$!={R(a0j=pgcnzRE
zGNTi_34ZlfRvaIdo5eor0a7bBT6TkqREYjDs7Uw0!D)a|s4_^Q3p2<2+IB$nq=>Ci
z{qEo)a{zhsk;yn4RHU1i7h~)yV)GhQq}#Q9g2*Xln5WXC+to+v(d{Urhg%!WpcdU*
zZBvaZJIxqSqY42SfcvBfdIor(6k#72RJIuiFa|ZPA^}Dwol+RUD1gsXGBy=_+4|xK
zRj+XU19-0#@nQA;QpAB!^$OoV237B#dOS7n)}e0zt9oU(Jg?eSLX9!0b~oV%V^ZyI
z9s4HLZbhd*kYU~G<Ts&r6+SQk|GA<pb}m|z7M#?~j2;-1npq(PBjG<Oz~F)RNfA7M
zV^*E|lf&ZW$`xT)JQPf*<lQv@&`+j}L!e6DviB!d@|L|nsgfBna3%E)n+8FRyqktW
zt-NJQOlsw=Qvy*wDPtd?l@(ktfb&Tax-hXq)=?iO_IJb=j9F@V(bAvP%8CoPqUt09
z1IC2LU1Bi5A~Y_$er~p|4P#Q{F4x1UaWA}}9_3ZS<_|PaiZ~xsxJ##lNrk(_^EkjF
znKE|3F}a8#$i%a`iq}?yfzfR#oEaRQjtGEiXNo;mq{d|oz?e9juBokkQkyQu+>J$T
zy2^h#7Io>8VZR!CFuAv{#`z`KXe=sI1q)me=9iw<QI&=cNQ>%J;R9EM>Ev->@$kBI
z99THKE(Pa}#nbDO#$Qy!3LCg0ycikwiy9WnbWxcK_CG)-n<93T>QtcsV^N(Z%8Ada
ze(IZE)TVe0b?G8_>5A|Q8e{6lqB31N9;{NPtEu_Pq3MHORHhk2P?<-vhx4d49Au{s
z0*eRPse{1cId&dx!iySMkpp9G3<mF?+IEJXUFw#B0#8b+*NPPwi#m6P211pq_<^yg
za_c5wEa=<m8XEQO<UwFj-73OhEUMe-@6f1o6=pCNp2Nli>vlSdwLTPJFcxBwQ-;=g
zLROH$SU4e1ofbf6og%h<xCc*J3B`(?60RhwX~i0hMK#S>gRxtccy!y;!BeMzO&zRA
zg0ZQC6-qERRWNq-64h7;oEV!b7|{e{QwdKUCpLBPoZ9m?wXh-&#x5<az=JEmd*c~n
zcfPfEf7v_<PaO?5RIh>t#^zyIaRXyh^G*=5k6nk{DYJi5rB0dsn<{m7J)0_Z_P0|!
z=pxKuY$((zXYi&%ojO2lWlVh!5EYR55jAyTaXN8a0JnY$`0&!Zh&1?oIvYwAX%EMy
zMjbNnH#I7Q2FAX+a)bt|!|9Or-j22hflODlO27wGQ;yJsc{EjM!Pr!uLk`<b^*Qvx
zZ>Z0qGr<O^DrI<lV3`cr{JWl9f7XnS&7V_g4iQTZr`F7Hfl-I9Pe~TKQ)Mb<U^rFg
zsJ-+lS*_tA!`-PfhYWW|EqwV-l{prQu>KW#Fq|rM$gX$l&>_3tp+gmYFnG?rGL-TD
zWVCx7S%*w^r$SYH!Eh?n@tW*Ds?0GB4np?2Q^$^hBF129d(@3W%IceU=vPG?45xlo
z(7|x(SOpynpBky0`%WD@48?r1tazt>Wfa129$!Z%I$=0ft|AkLQ|k^{`wp!;WEVKK
zZUrYikYRn$vWGJ$B^)r7?vQB@LWmU6Mc}1*6@M_CidPW`!>M=~f-szV*UmdaDqaL3
zTtN;-K?uXCc@>2)oT}Ge|G!iBn*9Gx)oVNzcvJ~{ic|9<4&fP2<!f^OJCDDLO&G|T
zlp@YRaJa7f8>jkJfWmN|Y)vM=)2FQXf)TBXG`549Rq+KQs96zUa0T^Inr;IEO4J0V
zx}tjLw$vE)sOdr=s7Do=FoJ5-Kxj9>ACnSHRZx#IK4Ap)sOd@|vN*{VF@ip4gJKWr
zS<|s0cv3Z4|G|@L1spt(t&(6{3hGrGUmk@Q#Unvbh1z=nh{@^IjuDgn)BzxrKU~)V
z0WE3@9v(oUqzo<6t86+r1a+;kh|zU<7@}0I=_G+$ofP50^eQX7VFVAR_Imzt8&xt)
zr?Y)|{(~AfgBV7Xwq*>%laiX<E_)x$QYqq$P~CPp{)6hazmETazU?{z1W&7-m1@0p
zdH#bQWh5MUN><}lc*F?&gsszm+yljWiCwxs=sjlC!<AqVGWHKNb(dX#sHwYb`_t&J
z?~XEhEaU!AOEVZ^oL(h1L?zv~RN$eXxXZFXRMd)w7>9~l@et!cQCB<!pH=IV0TJWy
ztgDEKap-dHx(PVc=v_#xaZ06kod6D1x*{V65Q-m>P5_50oE!xu!w|7A9O!4oIgCU7
z+-1ri>gT+(eIP>Dbzg9(o)H2uPATZF+k!&{-G`16hbp@3y5LYlcby3iHMBw{#({>e
ztLz6NtQFiBoW*yg`+~DDVBtazRd(H_*ORET6*4gnb#Ir&f2e#F?l2BiZ3Q<x5TRGP
zGdR?>9fyEJMcZ`<I8?N~(OJQ#uq|rZrVE2ZRjVk8k*MYr0FpNjHEn}^aHwY$B{2@w
zEW;$mp)VQ<e4di!XcanfCDqNQgU8_^x6#XR)03i`LQBuaGpxcNW`nM6yfc`Ms#XCI
zvr*MH$2`qqBuz<8)s>)Ijv~6W)fUw(ur^Q0>J=!GVm1`nIDN?t$C26SN@g6zlQIl#
z<0rK$+fwT|^D4MvHXd*rj~>r#)YuB9n2pERHr2(+KJnaeMd*|;V6##6Hr@x!M%9~f
z6SG0>wxMoP>$dSu67_E5`C>Ne-8R$%>fScg^-{fLS}F+^=0Fk4($oQJ=Y|8uY}C$}
z)u&|j{!PvEblgmXrN3D*7ZXItACd4vvr(-x@Zw5Vl{pZqYz0+Z5xTC!!fe#pjW+|c
zQD-ywVm4^()-;*a*iD>%vr%m;2xB&??bg%@YHfvP%yxbpgk|JJm0fT}XujOkSHR{=
zu^&WbOdza|!ZK#V-Q+nuOU&G|J^~yOZuySkDClA$uInJ?V)pu*bJaUK#v6kP3h|?0
ziU}CiIj)Cx^vw$eGYdj>6mBtrpgPCZ)q4Bq@a!<58P4I+;h9h$M}Zj=%<4yR8MElu
zQ?gJF)M4Y}$s$`G7$ffuCN%CjOI0R%2it$9-abcn1`~0P=S+2^H0qULM*w2#O0aJM
zFm)w$(Rn2Uwb+}5`Q?4VgynK2oQ72sJO~n*Fq95sEG8mLk76ulLZi+xJ$7RV`pi3S
zgs+H|91~up`}3~x1={QyU!c*h@kKUD6MiDS!bgHq%~?|y0&~V#irL}iJ*TPRQ|r8`
z-GhbBGr)uye=?k6!q7h<mZ14L2%Mm;KXFnxK~sO?IB|sLo8T2XL7ROVJdP)%V(a*F
z1j@UDfm(b{P2iQFvp5DlC+NkWI4gZ5S-OAen*;#r1T6Xq^wR+^>0J*%KOF^FOn{$`
zA}nU%pH8?MHH?rS<ud_wIt-_n06HCoRLq1q9mP{jpq#FR4S^Nw2;DbrW(nWEO^j%1
zj1xmzY<HsjigCQ6?7u!+o9O>iGo>X@EH$+-psDQ`hyD|jZLJ*9)Cd<wRMz{1cj3fT
z%Ya3lm}<KAm!pu2S*WNJLxbE{8-opR3{sx@34VtYrdpo8qeVW!4{;PKG2x>*2$h(~
zOLWWZN}y%h*%KhA6J5`(MSY^{xxx3?@!<MrP6E_gNFM|6l#<5Z+|DZ()D`3hA7zry
z(J*cLxPd-8$|pWY&l0}W@)bTQVijmD20YAiO&(<opKxCu*Ov=y(v<*Tb46CQ_}s!q
z9uGbj`pD^#zml9aCJuj6R0EKOJw}$;a+zz#olh;3?kKhR9CZRb3BsF+7dp%mKEVcb
zgqfSb51ou~n1Bu)ML0YYZu6rMhY7#>@uhi%BJ!o-LlFrsmk-K`U21w^VykN#lR7nY
zC@P<7dDoHqD2Mn=^wAOAZUR|!GE8FPg5tOg<hsN-F8A34rsyb6V&d}SC@Nwi;oebP
z#2kU{4wUk^e1xC7qWl^eC2<8Si);n@O+gY9S3$>3XMh1E=dy}{I66Yl&ALxI-qkd8
z9AYV+l+@zuY8_h7yIP0lQ_}G{TbA&JPFS~xaS{_CqAS2t!Qpk3mVDw~?I=`Y7Vp=o
z8=wc0?5|=YCbCMNO|ut?Cy%m`Ph_V&fYd#6R)MWR^C?nd0zz~YDRCvaY<H+#WU)KU
zN<Ir_bcC*(xCT84l$bymogHc#if{*gC=&pqvqNnUj8M87={=7SdUH<n&)=znZre0{
zXHn5z!CR|3D8m=m&}VN>6*SwH<qKZCv$<0wvgmACzCae8z0~l+sbViRUH^FYQqxdv
zNLM}!d~^h}o4B^W68HviwSOgSd)E-Bnsy9GCN;PV4={I6iK;WQg#i~jLd(rU3ta)W
z6JUj|Bs=(|sNNLqWl#VeB`2=|$Tpq_eK9oy0@$-n4W)M5rg=D+Ut=rfA3DlUekC=a
zGD{cK-zIYYN^&%Gl~2H54%3%UKx7U9a-ZP=8g#a_Xd#1+Ky4GaptI>DpMd^+Bq*iP
zu#S2H?YCq$gJkq5JNX2n=t{6x6j^CKh)s_yu~{6*)<G#h=p`!~h@w-Nkf$U$x+N>S
z@I+_H$Oc&GtUxJ01R>!jX@;(d&nO*rC49)r5_=7usg&kdQhj|tWn>ILYpW$F%|#1(
zmC9T)pcho;5~Jn>V(2KV`CQPOOC~g6L}$s2P888uGNRY!AZbMdLUh(r<4~<ibv^+g
zIzrLSf)Jf0j-Uy^&{<P$d5wxTG^Y9}8Tter@d2dnmUDf{J_fw;EE&kiSbv!6d;$e@
z7Tw<yS?`}KS`cJshk6gixrSyAigOJ$4aNB;JD*thN3gm1`7X|qk&W->EEw7Nvd*H<
z`$}?vba`LFMiqSh8%lD?h~7|=i(mJ?eUMvwZm7W3)DfsaBq^Uj<Q^g5CeS`-0R{ie
z0{fiR)DbAaNuTxv)aT5j@k0eFN%`D}Ryu;jO>Dzw()0$f`OKrXK4-rfY6oY(8SfZz
z_!B;EZYVotDxU!K9KqUVYNK1uo;)eY>7H_0L#bT}ItSgR#N-oz^OFF!xe<eXraaag
zx@~TC4!Uj1UA;@UO*yQ0Z3oX`{_?q@?F3!Bk{Z!QDZlP1XLUk^ZkaYNY>K0t=M!+C
zGv%lTS<sm>w?P(krmm+Zpg(8I;D$MMC43O{-;~=LX4yxA(p~IIZ$1$yafm~k2#GyY
zCOIN5&Xm6zVHwYvveFAhbf%1SfQU{eL7%`69Rb-U&_gGUya$pRpUiZx8f+EEMdePP
zFrbfMZPNi|Ia3xn5>Z@9jnM17sLbeBP+gV1?a-L>bx=E0=9GWhabTRZ$v@|jGi8tC
zymFKrefr=sl|c@i(3P-hXw50NbfJXKkcAGA&~rs-8J<ujQJ)|pIsnB@z=O_^m7WNp
zGej3Oan?ISMtU|&YaEBiBY@n*0rL!)<H*W#M!XNG{YpvGC-6Qg!R$k24tc7bN6q1Q
zaB9pUM>W7dXUI_v?9UM@ZUXyrhG6Xz2lX>#uh&`r44LalgL4M_)JT+bltcZQ6_<Ai
zv74S}OXNbI0O}lJ;wHQqXV6Ps?vBsfo9YI1pAwx<_)U)RZWB13E8&9?5P3!Q<Y@Wt
zm;qpT&X9{b8Ww@f^7QAN@t(*7XU0K`8&07!<e{!W&@*I$gO=kE>-O2ykqPQ3wfU9Q
zVqqyKQC?~|&d!jRnoJ~zNy}$N*dC$IW`*Hi2}(6*a#JI})fw#_AN1Uin>uEe*edkg
zkOdAD&PRe$Z7?Q-yBw0oWN*W1c}!m;0-cZ2mruk(KZi)M89V=-HK5>3wlW;GSHhk_
z$C)^MCj7m}0;TMkzCIA}9HUPfKICJvuLB9qkIBFWEa#Yv>_p}qWjLR}<s4zmCNMb1
zHn(>`aE{5ME&$FIupyiPl^1;if^z^ddrIV0i%kUvC5t+s7mWrrV*8Kspg%K{;~gQ%
zCer5}lUF*R2~A#UU~-Pho<7LkdW;rzfpm^ip-<d@9DvOxE=X<}P2(2jO1Kx}s^yB%
z_PJGLa^tGzFk|`zJm;89?n380DdJBy>agLC@yNo)mC`YN+^4jqDN22Uy6cMA6x5}`
z$i`jOQHu0=MwKunxYa%;$2PDx$K=>X7RqCCY$H?UG5EC$o^woDS0~^(hw!usaLzHg
zwt>w#*3|UGc*=qHlxX8ed`t~U`vkx<r_0JN?934iZ5{xgPM60U$eGh=cISQQQFil*
z8`INeQ{z_kO6c&$-Rl+cxzKE#9`941>J@O@&}>L>{*<W3AmjX$ZtHS-gVXPHn&P1S
zJ4%86%)F&Oi8h;sc{$8vK7n{SUG_5oFCPg?Ik8>#^1^-m>2z@~T-qN2!4_`zPp1XF
zl7R7+;agcqtNRh*pKBKB;l7fZM4H^ILDO}9x~o+r)ag?V!x!2oO4a+Jr&h_U(Nc1m
zntU}tJ&$l(s|_@0tWXNBn>qjm*G(OOlI!wQFThO>bCai}`bE2VwU3hPT@6FY_0EQY
zd^x?VX{f#4)inH{%2&P$19OD=TEMnEr#C(s&duKR;5+~-q4@%;=Lp=j+RhRz?***T
zX-EBsDr|?XKohp3R-g!h;(AtP?Y?ETQhP-^>OGWUJDN5e_FAZEq^>)HaIJ*A-146M
zNv^zBX7K{t<+M=KP>xMr>IJaNX`!}DJ2sxB7qBj;xmpek(n;sM(D$R%<_qIH!h5Zp
zlhd{y1J&1P20sf3xhq=uN%fd^@B-5A5Zko?YiV>_uMYU{Y4lq!0$Up0)>o2mztL^I
zzzK9(S=6i7?|~#<1i!S!cFQSq1#GzI_@-LL2~cUwp9SRN5io2Kq0)xB1})a;vR<Dr
z`Lv-L)MAZL?<=Z>IoLU<EF~phwL2W4wia<M&9ns)*wRdG&6-?OOHf+P*wVz*Ld!lW
zsv#MEP{ZkJd1Z-%!)dN{wSi0gBQ)0{fQ2c_Q&Q8f54sR6t$nFe%d62$U10b5h_d8A
z;vDs=tjbV&@&&we2zRwQq8+b@t(G#o61JPl><X|gf@41L)cVrm1kol7P?;b!YXK>9
z1#J0#)Nw-1mWK?x15q#`Xx0M6C623K2i>6gysV)sG@q{|cZN9hP+w8?1s>{^#z`ES
z)3>~H;%HAVSTsS7!V*<~>7ZUPjpA%Ip4L;GrKW31M432uX#pJ*XQ}m$aY{)891{X;
zEvph6HonBk5gA4x4P0htO6nJ*x;E9<fv$<ZdLbAi1jJg%5OF2gWRODQO6s{Y|7Jgt
z?&pfw*@-nc)N(1v5L9cy=8t1)I7jxxF*Q8#@(m3yyn0jP3yaXy_QIPtM%66j?1<CV
z_{L|`^`MO|!x&z97W<Sz*z%;LdehWDM}Hdn=jaVB-vy{koW{o{|3DmisTZIw5l5XX
zl@)O`Go{u-S<6@DU3pT3y#+_zD`DgH;YA!aUSH-Fu=V_SBb5DVAwDaV+k7FJOb8Kn
zCDlWzTR>i}g!{wDAzukP2*1IVpo8!$TuF5hG(AE5){~-KeBt?n`)m5G7t;Mi&~Lqv
z5-4J;)vMp4IDsDsYQlMLzLM(v&Qj@wh^1z%MzYijqK86B%@<HJ5&EJL0U05i8K9UD
z3TqVu&l54#mw~>}C%xdK`bbd9zQ~A%iz|Ww6$@^#h@oaCrgf-u6SF$ha6Ofcg3UQH
zhxr1MCWP2pK+;6e90!mlLiTv!Xd;a0wgu=+DE0XQbS4DjT5vB$$hfW?U@6gqJd5l)
zl%PObS5p1$daR?rO(OtlWdzOdQ93YWeZvzQA$1LJZG`Oa0W}yR)cjw5{JZBa+V-jX
z`I+1L)cq)}<}t_TEcEaH?T`QbqyK21|LTAL!{46Zw^6hAw;!NN58W_#q`mk&7oF+w
z^TeR>)+eSY?0zkM)prpYs?gnjxER=beRKZO9Jfpputkg95u2TfE9)o72j)X5hbI%O
zh=v|?KFVGKBDj5YXf*(X_sbQCgGLfDl5md^J};BpV0`u-ic7-{c2N;z$A>fg!^A}q
zjIQnS$Ky!L$bv#Z7wAJ&_A@t+6S`F)z~jB00>Vz&{iY+S&QYMNJU;z=IT)2m_o}Ud
zubf`1T19hxmc;z5o;i;7{rSUNKf8ash%jUCBHDC=e_ceS0p3N#Q^uD?#53@hg@iX&
zi-{Wy7n3930+v!~;zw&Kmr~8_yOiD>U06z{d>33wt^Vctx|+xV&ZX4;#ZnS*`pZ(<
z?=k}Y()#5h+W%q^y+PscBGTPTYorcrUoq$jiPgnWEut4r$VJ4x>0Lw$`ok(J_dQ%v
zTtxn>1+-+_)dGUIy4KI<p!ZoopJmhc-F`lQtl9f#9{$k!iJpbj&ET&Lkz-^34M*W_
zofY~0lpwcGr(+!KnjvP!V&DwXGJ>Qt5)T?k{}W=x2FqtSb$!&KFht1sQB@%-MyR^T
zR~}#!2*E`Qo*X1s1nN2Tk`fkui}i}YLLWZ)hQL%Gq{fbwf1@W0b46DeG9iRh&lB<;
z;>`}|Pth$FOgu!j2q1ZoXc18JAXP$2@>3RVHt7FDEQ`ra8)8@l$88Y$8OW*^0)N(r
z9bip_Ef-?KuEiFDcmmKLuBazuMF`SmgQNGB>q`TTZ-6X2^2jKv?1+N<gy5a9OG8ZA
zfkUN;vSHnZxE9O)jUrlnN>EF!>~`4DA?PQ9D8hNsjI0$QitN)qR-4!rPi+<fh$jvR
zA&@5y5h08x@*TuJJfzgQBQ~vW1fYcQoQP2gz&Vl6BZTIxgda~z@`F8=f7kW_Uh5DE
zHu8srK%B=g2D!&hErJlw;>l$aoA&!DYcR;Lh~r*}Veue1H-rL3#)A;W;+g0eJz)oD
z$D~B8!)|Qxs2rRKrGXEQgd#u0kvTR$Wt^x#f-0=khd8Bt(U7&PAZg93GGPqF#=S9O
ztYY)(nEry;ygG)LA!JLH7b1k-gr6b^-uwYyM(hD_X~vz!=Ghp5X(6O0V%I`A&4VMN
zfSQLVL;^KW)C%Lp(h0l@o{CRkh0*7A0&7eJ$L0P>37W;(aMKTl$h{zv6TyAAjAj#5
z^C@4uq1732<8*w>)h7ZtJA7x60M34gEMR7Dh?0oKBX5WE?Tgur3|1j<W=EQ<NN{Ga
zV9Z!@Y+Xs&NHiZi+=N%crb~IPP{Yt(OSVdH&{&H<$f;YrKl+#!Sz;S?_KGDFtHH_*
zp*KGUN=^6Ls#Z62A?W3mtSoZ^aQIsyHR{NT_7P?2{(Pxd&|Sn=c0>q=@Rgl8*+Kxz
zj>K)TmYOZ~wU(wG`fJrwp}m$g>J`;cCR>L365g_>hy9k>Y*~-7s70SEs<%fy+7aL#
zOXg~W`*RIFs1%tHmc4-|CIqqUxNQhQEPI18TRawbTw7cT#*q4K8Fh5W)yEaFZD_P*
znmed8!7Mu><ztChpjSA3EE(wtxsTP^HuT!+8aNaih!_9*q^Q;cRqp4EkR`O-8`cB$
zZO7fyJwt>}6{V#YkIo$_83PE;4qk&;O%E=O_nt(M4KfO^`9PE-5Mc94as&cwUP%sM
z9<)?{^S}e*)*yJZcW6F=H#;s2LjcZ>OU0O>c1!n7Wp3<XnTV-9pwbt_47LQ{st}%6
zQoVPAe|n!;#5doe4u$W$lIpJWsc@wV-`UB^5ee|T#q26oYzL7?2;SMj_7Q@2c2I)E
zl%uR8qiPV}*)!d02;F(hxs(&#c}w}mh3@R1^Xe0GsZlsx=Tf6^x=!sQ9g0xc&W^0K
zPl#*qidO!Fo)KtA;W#_an~^xqj$8bga(j1N^#_rhy}$q=AZG_&AOz&>9r}?t&L>6n
zK8IR{`*doPK!$^u+!8ueqM)146|EGose=(|OXzU9PHhPW%{aUKK|pSW$OXIA56~6R
z4uxQu9f_BNu*{C+%rTX+u>(^Qpc(8yorHjy9mtdrFtY=`5(H*GDY`Q(WM((0%%P7P
z)J*{#W(T`d2#48iJXvHj@Uf22LvijCTVXe7NC7Q-fr;*e^kE|Vb_i+Nk$oV9wCqSg
z5CB^C9E}rB(+!G~?1NWOozsU3L{*HfcA+=n26;+!KVQKtJD^$tm}Li;D+IHAeK`D5
zZF7YCi=StumxnDwPXdeCE2Dar`BXSj2P2+(A>l$;%nq<z2#eW4xfa4=cJQ(V9Mw;W
z@(UmqvnRn@2#wjn0T)7JcBHEhp)tGR&LTum*bQ283^iU#a?sGef?9NgO+!fz<#Ou)
zCx$?q9r(o%L17;)OK2Er31ZM3zmigk0(D+d4WUY<{sijm0CR>wogM!cgB-(GQavN8
z^Gd2`^^E&hQy+2Y8%_NL5GI7^?BGreQ3`etEQU~>y*L=JfUVZdJdrrh4!COw=Gkj{
zLom;dHxPn(_5oFAujM_U>j?9_g4?iAoL7(w&O%**DkIn5lcIbZf^v2&>L8S}=c*3@
zId3@^oN%1I7(UaLuEuwku=k8|HHB?H6URPbHm@YRFJiDOss8KR#f}p~TXyV9A-H8P
zzSO|==TnlJ&Z!~dZjac?URd-neVW)L1K7$wz|I%~S9a{IVN;`ovJ$qk=jI$jSKe|>
z-5}`kifROP2heB3`jB~DgtTEYuHirrp(~#&%H=P3Wk(c32rAi=RyPEe>=U|5Sjk@e
zyzpkr!Cl>>52{b7tJmW_ai3?>t`m@xFlpC0vV@6&5fCQr3QHl3+7-q`*sEP(aRktl
zy)2Tj_BMjoCglpM<goV6Rb30}hM|L||4Ps_G@LM)9X3{UXxj;|NOY;&S<hs<&~W`|
z$WU=zmNQ7IqYJHdMY*U1ue_4`VCh=8-J?s_P8{qybnQf7Ldf^t!O$H<TXrybhtQTC
zbp6q#Z$SqBMBi$>lv<a*olt5W`gTI4b%s7&NsVZ8W1i4xUHW#WO6$_MI7&p<4IGXe
zLG0#d=K?c(bZJ-+`G=5~9X$TgrD1WV3c#H1gK%dTof<aJVYi6xA=WOsH0*+U5<au9
z#z~ikT{y;dY1j(ti!KcdlKkk@uprWpE_$vGy8TGB=PjiU>(Z_$u~Dd~ZhRt+(;*aR
zM@ZvGlBH5VUCMPq{Rp7hk%b_-lJH$o^-9`x0r}GFA)ljKmv)8EA-c5d0x&d$-|TQz
zgb<t^&WtO8S}A`=bZJ*apneu<YS#q~*Q8w+6dWO)9dWH8NM{F)e>Ac9_qA`a{;IAE
zsoCK!x)MCGR9BPct?1t;MeHXIYmKFjJ3>Ab;Fm_NyYk@HbV<~apd*^pF0y!B2^)qw
zY_4{3c&lseRZK7;0=|xr>1aCdBC0x?RC7gMN84)n;GCJvdbe18*J(CWnM9*otbCTA
zG77o8n$+<IvuHHx<K44>QGp9TM48vYgda_sHm@h6y{Fa<?be2#iP_Sz72ezsUtWj9
zH$a#7l*sDI*xBJ%4szjjkOV|CJ$Ph^55>29Mc9uw^i-3#2`=(0Stw_-(w}g$N3q>K
z5Y@VsT7_#q#C6w^)hHS-c=}#h!p6D@UTM&&xEu&^++9g65h>M;lb9IpuH-Wre$G4p
zbrMSv8ZO=D;I!)?s&H}I_2jZ}5!&^Q0Cqp}KjAXOkF@CaEU}SV`7X}8E6Ka^gRGcW
zaL3~()NW}yKlDazui;1wgVDo}Xni_pKU~y!9cfiv)OZ~?PJW=8^Fqpx99BCxKq_Wj
zYWb03Mp`fzF<wXJFc&Xg&-7v`z^z?J4zer4w!Z7|b|q~6)F^op#*LjHrP%Da)$^lI
zJMRJg$S;MIY<_sl)Nz;SWY4>T)Qx_Kr0$jN?MhI}?oTz+(R*of@96#1hUldjUHp1i
zQj3F{+^c|H1AIFl2}-GfE;NJ9CKlsJgM+c(j}*2WUWPUi9~jBN^72uGk^SxigV7e^
z1A~#{tEh`U5+f~H2fdLW?lV5KfTe}Ya0lMA<GS31_w03}{-lTvPb_p(!?V_ajQP5@
zFG(#fWI}wdXhAUW6E?LlAi2W9ER_;W)c%x2WYED@<wA&dq=9rGL_5F=uH3x65=^=P
zp-)E^N*5xudnsBMBJ@gf4GR%^CHYwfb|O!psS6Ey1-Yn+2EBq@2||N*5PW%PBLdpv
zalt`5IQTuZ8-aq~L)T+|&|x{)9O~6W_g{$?^6)Q}s)O1}kR{%U5ADb#?*uA*L`XO9
zi4X0SiQWYf?ZC9SAfg>mAs0mSO7djqp=~6}%)63m8Aw7`_TCP(p(kpzgEG!z$(xak
zaxT<p2Qi&9A#VpH#zS{x0J(V3wtqTcE*`q{ijgH462NS_0HYn4PEWvS2MYA@&=vrW
zeHZ@jN~&wJ8o;{m0*GD-0E4vRkr3DuBihkt4_Wa*zPb|hUP%o`W<}&8m0bb&>_>u9
zel5zm+Y1!q!7Hu=w0w&A8?RB80@i^O;@Ll|#D(wdfEl~+ogGY)9?GZPK{x5jx!b`>
z>6vo37Y62H-`FVhs?$0Tu+d%#TZURyw%raK3^8;)fiSm(?FgTnyEq6szR48nvH2cd
zA22>{7foQV@81!7|CD5+*1|6~>ag+Bs>Fiz+|Jx#0UY=`-Sy=H@#5tF>xFM|mwE@l
z#a-uaAY875>JTWGE8>Hp4#^bQPZcl$z`3~V++DikNfDb)l_;LTj-Uj0ewZMbb(d~0
z4q7jSb%*+O*Kr!C6;C$5Ua%E+eP4jBxJ&7l+3=(Yjjn1!S4prwJem7CtP^*AUI*&P
z6${m2(zweHeRh`EDioCKUJ3Cp9|=mkdZjO}uq*Cevjz3!I$Q(2;-cv5uofS89hX5u
z?<D2x`3!xEV4!yq@^ui<UkN`&L=s&Q=P0mL8%npYqUXDU>?`T{`hm~W#n0DanqLW9
zu8;0YI7_Ljwjd-2s%k62%@yS$A|anOD5lMDC@Zwf6#(E0xQi3S^`t0Y^JX?1D?)D<
zBcI_Q<YMGA9F}}L+s1*)x2tg|sO^8@Pga%)|Lz!)tKqVi{AKksKx2GwH4PoMH=DK^
z<W|FmLGBkET(4lOZK%Dy)i$)=-Wv5tL@}F%*4qnF4~FBdi_*_<1a?sR-SS2qwhKi_
z$&;dkO6&?W;a=)WX~I3#8z{m(ISG?voazmf;RbRU7@S*XZ|a$Bc40g^{#%1`6j7i7
zGUI!wZyQ~q)7(H<?^~n<2FJ)1v3F3E+t54Dzu7bBNkYl20p#vNlNnq%E;yM1W#hZ6
zyQM03SF^Q*9|scKfU$Am$qX19C!ov#v2h{FEHO5|MZjyo*jy1?hN|3j))_E1zIhX7
zps@F?Ogsh>dnZ86;9&E0G|Ezqq7*blUOOoTKZ~m45Gv@}mE@>|Tr;3*e8D`oOz7c@
zy4?t}@x-ke05&dCK?Anmg<CU#Zd|xEE6|M>Zta027t9K_3pKpx=QCh#e6f^EML;%V
zwi6ec%`$C@FXuCBp}BYl4cS*dk}Q>aUDEspfASS^biD(3Wlgg-9NRV~wr$&(*tTuk
zwrwX9PHawWCllNGGY{VL{?|F*Ue~U@y1KfnySlgPUaKm=t{0_Yay#Xr`Cd7T4td$c
zdy|*O8Ck=V<{n8ybA}bTZ7A4^DZo-|hBeT2GuWDGX7{yXmR9;zdA@iJ9ocMCK1Qzm
zL$KB@--LgV9TTXU5&jwL6u_&V)-D5(eGjM<(~s%vbmw9KQns;E`x-sVWV^x6e;&pO
z{fm7+g0vPaNqRg%Sv#MIBx_NA5NwOHBt{#Rz7ugG<pxoc_ht;))LG(S4}wM8pk?k*
zTeJz(qZ$Z>Hgwir@Jc!W=?2OHATUuyd!!iPtoZ0kE6QI<)lDX%meU6Av^!Bl08WyX
zzOy?sYe%_VzGmC+Ton0j#?JUeX^ZZHMLUnFf1?!r^o%0>SK<mS^OaHXTg(8Xncv3O
z*DzRLIdr-SYr}wQzHhiBlh%31&7qEj^Zk1nY=ts~T`lozg)NrEffhLvF!M07u?g!6
zllR~=fOntYP8+>37*0&2z>M9}h2u4~CBUwiF!=%W5;zP@jGTp={LT+~a}#IGV*{Md
zgp8$dMIVVVOG`iewi!d!ClI=;Wnc-Gs#*+waI%~UzY_btVd@>`Rv0W+;GCggJf>}P
zEh|5h)>7?ie#``j8JPC%njoT~cEomT*kw5Mw+YJjqDZP4fTZhzOrAL9%X@wJV}|$_
z%z`|x<4T&lC}7TqBx3X_b`Lld%o!uFt0-t0ldy9Kz%e{v<8FBG=EB1Xv9jw7HT0n~
zN!64UX2x)i<&PSIQq562SOhFnS}owPp=8J<DB(S!^lF%1Qgrf30G|#dud<Qr7m^0J
zV`_1{unIn>NKA)c9S8;?K`k{}t*l?4K?nc`v@hLMV{*}V-e7T2RHfB`Bzu9MKIkLz
z{2_pZdt;`Sz!frajKInHk(<-K(U(H%<uLnCInUOx>4DlO*4Dx)%Meq!lGc`>sqOtt
zD*lHCvKr&X2V*RjYF;(cjUlKn@!aH#noFTzR#8mzXQ&G}r(D1kB}9{FN(IpxW*rDw
zym#e0g^r|2EM6%!UJbDaslNk!Ft?d_QEs^Mxq{Xh2@G*4^ljT+j7a=g{B$=UP#EMV
ze*_r7O5e&>EumIX&tasq*Al+|ra4lkeEglfZ$)`uDPxv~4r>A$ZSUU)GlM~fF#!;5
zKmQ%nED9TLJZPxxq?7x1x)nO-kQ05#hrK7TmQ=YG!C~M{AKlZ0w)U@lbgLgVPIX`d
zEkwHGN(HA?vfX|@KX&%Hcs@<2*eAm~r%7WSC4nvdrrKnhVXTdnfGMp>g3@L1jsO^#
z_)WDSn7;0zf?ZMv+mBjPo-gkj^Kv6713X>ls#J#eD^Y}7p(;;hSQaILac+DBY#t9w
znFgqQM)HAyiO%Fb1eslDY-XxbK)0FjD`-#9&<c*V|N2Ad71ht%DTPwf04-%=Ec+wR
zD1;uKENKD_CHdO2B{*pljy&DJWi6Pbk@&%daMXq)l|aFuB`;{K&4*xYaN+*M2ac8&
zjTabh2vx&2ujDZX{;{EuPu++uFRr6|4b*$#;6Q_2(OHLZrC?mSx1Opak!pPzb$=g-
z&BU+IYlp1&WSYy78%s8fc0J8ICYE+0&A)%sADk&jqy0)xw80B~ef;$Jw|9BvjQmeu
z%x_&<>)s)^w~iv0g_VvAWtBO7IfB;C-X)PyFp_5`z5Q-Wp-|jW&_X7`q1Uw09ow9s
z0cSOeW_<o5Flm_RVG{tE?MN|PDn$rJty)b;f>A3r>J``4<Xpw3T?wbuweerLz9px+
z)syg#lYI7AL}nBIbuGXS_<?BG6o=%wTWdQd_e%@(BZi$Zm`&QtoA1_pl*RoOohG!(
z>4c*5o?_)G0!sbtvCa(FSZ!xrzw4k=bD`Bu?4Uj7+ffnAH<M;JpaS=zYpj96hSwAx
z^WfG5D7fbLO%3j<kf}{PjR9W~zS-6W@dUb{WK8(=`0x9h6=HEU&=XigZMV4UPr%ss
z>(mT>LH&a6-E2u^{3hQOiM-UM@`Oe~o{GqOIu9-03q><gxD_~}b8G_~Ko}cg4_VMB
zCLqQU+42BW=l5Sp_e12Fh;~Z?sPV%rKxVFf_)NzLl0e0nw2j#n%v#~Q$YcW52zScx
zHgb|~M0=vzIw&G*E2TAq7o2v*v_n+7#)E3?SZ9=(gteOQNBJ)uLCv)6$&*iHAll6D
zUjrR=MMm~#<wzh_W3)kcnq!j(NhhYR?o?ShC?PY=b4s%T86}nc@{2QfkVGb&-=F^`
zSQ5^;1QCzuG8q;J=rl>oFIvX}tkA{g(T0;Ry_td4U2BVvo7|<`4<<ZmSKc10^}P*p
zL+peSMi}#T1pR<ZYT4V*X+`Wvoj{xQ+T^fJYF!MgvyS$4<Q8P}*?Zp|==_bBb9xc=
zhL<*#r6!#X&_uO~h+><VJ!GH!mstx|3|XXAb4!KH@-pg~DoY*a4yg|`vWdG=uCc5}
z_D9WeHONh&W<<&W%Q4Uuh^8Ao(Xrmw&kjH7HY6(oe!4RukTBFX{jV0ieB1`3fNsY4
z-eUl@XN7W@04dc~)hSQO-a1@304cC|{J=iO&}b%uCk??+OmQ7n#a7-h%ds?+{8VuD
zG^G5%lgns~69#%9ZMjhNQdR=}Fw&~8@;kb2QfM4G{!4|}lmPk<CmK)uKhFwd@x{|%
zi_%cxOsIsa0Kpn1aLxSJdT8>}0HGRVU4Z%ZA7*h?s;KK%f)8em_WeXmB6Y4LE0C~g
z@7scrnR=63=6>?3#+A_Q@&limLsOdgiCPN|!mwx1=%oeosqY)m8n+E1n(@zB`TvCB
z&%j+}0z$FkYBNVkGYR$51DHQ6gEEG+@*k<P&;gVoaneU-HaR{}Ra67+HHN-42DMw+
z2k}x=gtY``hmE#PvH@MWaC6iI@e|eChU3V&erZL}1+#hi3a^vFe2yd{or^SE>U^j3
zW8mbMr!^A4*hP>ZW_LWzTrZWn9Ml*Vx!brbK`J0-hseWMKqtJjckjt-PiGL;XBz5M
ze^;l_b;D)rmZwh`uDO^;>Fmr!xa_j{7!TxI<KzZTP#ivGEd;+C483+uYJb(I44Q<m
zRWL!uG2x$n`>fU$m?mkr?tH9G+q=-mEtinoW#Pvm-~f>&EhRt)-vsdY4g)6g<&!f|
z={mZfSi5em2Yf|7Di<j)rd6bj7Xqp08g`C2LzI`B{k#A<rTAEe6`YiBSjsHQsBe=M
zaKMwwgZ*}w7GSNnlBO{Z>RRZKsTG%nM^APJYlLeMwDFoe;jvx62+pC!*2b_TFI<Z~
zt2JbF(ur;C+=Uq9Bkj+$3m5w=Yzjh#2X$v$ovp}X0Ndue>xKCZAAazek+c*);?7uH
zpO2IxQ?)3KP$$hFh3Qbf^1cB79h+R$RuC4~3mJAo?<*!zB+GJ;W`Gp4>RpOGY19ty
zfIOvIzjt`Pa-HgT$`FG<>%NumcoA?W^!lMc12HGo^RM*4l-zJa(s8BSrT1Fe`_k~D
z;7saTLK_CL%4mdk`d}7P7@S!KBGwoO1exqKTZ;6R{fwiqO!69FL|}hZ4N^2@^V{0o
z)6HP79=LF)=ZhPtGE6<vQvl!t<--plF$Kxtf6Gw^Rl|?KH`(rwDyJd^6P%C-VF1QA
zArDIPhi4j5ZDf@LoCS<TaKuIYz?^R@*U!r~2*c!_%O@~UmHmwY<z`@KHN0KHHqe1j
z^vjL#RGzt>hU0~=KU{rnusAeHh#f^{q7INAL3ZLaXPKfAc$pakhTKHN854@qB(DQT
z1eJ+iJLG2sW*TkR!DPQG@RISke3bS~ByELMxW!XFhXZkzVb^!eTD)|$7zju7*7vX6
z0Wn#yWZXv0E%;5E?$H?GXYgV{45A)kM7xbPPSz(8Gbw}#=8E^PcQ)4mgZv>J-%fQ(
zE)fZH22xb~=87NJ$0K;Zo!Z5{5~^c$23!(VFsTANABL3$spO(>er`fmJyj+elZSWx
z`aP0&AY9D9r*sN}jXy`W>}H*$C8iwDoVsiM&<m{tJdLN)YXu^67{-nT(dlAj<*Upl
zSPlO`#7qPZ&N_o)gNy^YmU*mE);?MjtdV(^VF^f0aZu4t4~y<iMI|{QWH4u;KSnd3
z=BMpp1PEz@!zKs&>=1K&7@L<|&an&wzd|FENF>`cexWMT<jWSraWdcnoE2M@(GNHf
zpV!V=<R*S>jtR#Y6Bg}!AA?;5_H$flLAmkP+TM4;j=)j4%FS{a6%vh%LoBGT!}fHw
z>>XAmGpPp?Pjx7bkg^X^0kXd`je-Qm(znEkovkb;h!P`kmQ;n_NkcW$pQ}-%RPFZA
z12#kp+)V7}A?~F&Ez6;rSt3`hD9~j54p(?Dl4j7Z`;9VP0H+)eN7<b+wMmvD9%e50
z)gYzirJa$B#Ns9oy|@0kHi?j!(WSqnqwteSfZSK2y|pTX+DO=tEK8WTNO8Q_0xSN3
zSN3mkdjmM>5uD}_qrOHsexp-hTYCn&LL0iun&01G%+F(@wEN_iql;D>J|eswg~?-H
z3}g~F)tR2nuQsAm-<zJQu4NLX%|dz)#6k|E0K6~o&UW1y!x2Kl7{!#`^g)g(QfI2Z
zr&}XOA4Pu~Qg5>bnWlhf#fBD#unC$jZ8iy#OSc45%L;H}@@daO!yLgA8z==vcMjE)
zvOsYU@11x)n4<}xshsw&L9|l17q!=Gg@7*w(<#{!YI(ZrWu6-ZWZI^VW?5SnZ|K3y
zuNQ39`3gWYO8M(1i4sH<@dGw0pD2LMMzjv)U<+ZoLKs6U?*JhOd)C44Lhp-txy3*G
zwNL38Vh7&XxMCq!Mnu^`>$ebI4k4b5wkyrvOa_(^850C<JVt`HQjWtbZ9&xRpIafc
z?OkYBkn!?z==c0Xm%x8&CSS$7{-laIsY&?7i9WoQ6+eP1yO<SM8P;&<r&Ur*i|8Re
z4iLW`6C~+0rHKi)4T+1`B65xp90Q_@O{Pe-UBz*lSDnd|k7$>U9FJ<Sm=!jmb_U0f
z=di=?&HW8$Djhk_8M-&ikK2fg9Z($|@T@K>#!qSxas;?L3pqA4i-Qag-kYnJnG*3Z
z5jfGAt2ZkR$6+f%(1Y0D!I>_nr3X3A9a~RImZaTDRvPa4i)?y*X2=Q~fmX1PeM`Ku
zg_DPSc9xZgQ-Gg@93xzsf*jj@&qPi_9a{8KRhUo6n^*%p95_gu^J~Kq65?3d$=8OT
z$%~C*LBHot(}kani9yy7;=hoXX9(NRvC<a52zSSN6X_B@e`D`sZBnunXo9_=rap!X
z<wX&<&@C9!)i=t9|5@h%y>!|x_<4Mm#tSJB%AU0IGeF16j0C)EdHW$+q`hkQ%@%Oz
z<75C_fK3ftNyd`vxaP*eZwIPBK1*|y#8DN*0nDDGgBgG}lsb@rHuNS&6CpS-gdZUY
zHNz#c0K_V$+vd0;AJkhLw5mCe=y$-=zoetgl7aq|wuc9d*_q=)V8SH>NFnchSJ+0P
z{FELvAnkm$4N|a$u3UEH;U0%duSJf6|4Rn#OOUaOI&6j4-&<hB1rz=HXq35Ek+Z-r
z@6aE9v$K()ifOY7)PAG61Gw#iSi>6916!~XAdCwph#=^PsyD*V>_{IgCzrktexUB9
z3C6(VGmYtgNsU-;b{dg@7+BxRXm*2ulMBtwA9Cjp(k&)R0+p?u34~hTB`lwRO9J^K
zhFbfAy(jsE2cmtX9t~?yvqheRrLCc+e;TiVXi#oR0{=xQzKAQzqe_aH0xjP}1<@`)
zd#F0zCqPq2ipz?xSZRnuHA5m1AC$U`%^N{O#`=?h5lirVgFqbf^L`+PxmKT{YPdJq
zgTIYWG7Kfn+kRQ03P+eH>%F{%P)uU91mDk+7g^s0CnP1!cCnxNWC0luS3|od@vtr8
zxxYd*CMX*ifGS6^!H<qP8NI?t5fvzkTFRUfu6ZHD(CF?9v}orq)`-Qi%w<`_6Txy4
zCv`~7V25uw8Q%abSGCUP6<DlyWH>7iExHXAGRxg<u&E@gWeO_wp>5}eS(H4l>?ap+
zt{0t786jIEBrV~O-cVMOt|N_Ce`bPc{g~yReMnz2L$Y=U?JKFb)CLx7V##M_{Dp(4
z^Gy6f$zL6x?__i)MOZiLpDV1Vqq>ab^u3Mefa>?p02$8lj(R=hsRqb4GKH5CaK1oK
zuZ|_XM1tr@SWN_#qE!&x4THLHDi$$T_3CchR+w9fr$H64%w8RBV|u(iJj{F2mmAi8
z#C)n3Ug@8gH2q$Sfk7*YPm!-Mtl>Q!(|U<ll~S;*=zPbmyl`PeHwdHjxj}QU?Gq<(
zTY?wArUILwdyd~vR|9B%QeDt2E0VH#W2^2>Ey--_*m*m<_o4Nvw4z%fYB_uNsgkiC
zg9XyObhq`@f%bXyHi_6B;DTvpdscJ|>iy;x+3s#Lt(JmmIVRi!dNf{FSDew*ytA~m
z?x_yg)LgrX<UOOY^-4D(W$;FHN2Oari+?mhq#O+cFW={6tdKbF0{wuV@q~Use_#F4
z_%45W=id7~hL#_8jeb}A^GLI|2V$s|_H?bF(9^Qtc9!cr;9BIeX*^(f_7~#pgDx`X
zeNqO<$&`j>Deb;4h`ABSGT8Yy=|>XKHuLpV6aq<Cbx3IPjnu4ak+ciw!Hi^YNnjfm
zSB|~NvJKSYO*Ef?;Ev-H7s2;}!b-okmhH1$prGpg&^AjdI{#hmH5Un#OU@`NTFvl^
zW~(L^Cpv@iJXT)da7wF)8k<!2IFM_+8`}i(O=CP_h0b|yah&&4iy#t)PDfk16DC)6
z2nprO284vRO=Ci%_E~L2ZtC#g9r*Pk$JH&52^br}9}-bDN;}XEbJ}S9NJT$j{D{R}
zF#se&+qQ1x8n4vYh^WJdwaMHh_%As7fX`3E+A>o>_G8{VL2z8pk4UD&+=YI|VZ4gB
zrK+AZ;(t3oB+)*MiS8)sUw7_J6<$q|O9p6>+43(cT)QbYkeM99ZG8cJSgX+<YO>_C
zm-=Zo54DAIf^^jfEwth$u$6$Z+O(H)XOLNjGCFxu!jf}knYkR3BD^}Z(X`*~xM!2m
z>Jo8p3TqjdcwRk=VqwJTL8O+W*7ief@@9D={^29cg1Y56D+N~_b|^)FL*rEw<Xk-B
zF60|_k9k2WKW5;WMb7KU<S*{Wcx-EL+bi?TdDB}_YU>ySnLHB@Cjly=GY=vYR=hOr
zn6xf2(PGG~Y3@AOuw{!KcOtxR1apS6?t8qpKb|?E&YiIPu)7qr#jZpF_R~^fJdpgl
z>`Pmnd2zV9I*PZWWv!I%aBS}kP<5BE>zi0$pY&WablB`~wdC3eenPOZwAV8^^XaF$
z_An}4=Ap?MfNGJfMiZ}24eLrxqDhusd}AMx8T|n<MZTOaWm{!Ot74dqr6idYP+keS
zSqYsUq1z?miUV1~7T|x>?z*i<Q+$Ezc3G<ISV<&hLWxuzXq<%kCet^DRtHHOAVWi-
z74<_A9Udotf$4<CvsEly{1`RzU3?}+e<aH@T65nNL`w#HXyVtMI$8M-a2-8YVpt_)
zjPy|!P#hW1towf6F=m$iG~~PZuDu1?TUC4@$}KM&{vFL}Sn?<qH5V~PQauStT_i+Y
zG-=A5vlM0UjtsnGf#GT<z7~bkMZbOz$#pEdeQfc;ROgvE#cShi?jjWJ$;gnTZ<QQs
z;^mgWaGrFC28;Sg7Y&^1sLK<At{EB>Y|N<ki_^b07I=Uz?Ld_PO>x=$kO57*@a;TC
zJz-1~Pv`vlk*13yMRg{MmMkDf8hwK#z(N#gJ%)5Z3J0A1Dv6JHXkP|>zTD0d=C?OO
z4)*gCJC(%8Ryvy#&LD0QSMClnEZP7myPeNnQbLnxUI+R=wBxeeJ3_F!X9xX5Y@O`N
zHhyr5$G$ko$0;tbf&)_wS~=Q9Dl)gwP+0Fh6Yz;pUdpHD+@vIR)C_Yj6vuax98txO
z&jQnVYr}GFhFWd|;o3Fh9{bf`aNxY7&`nM2@JFB=Ez^q2@8WPll?y-k1X9Ks4RE*+
zDh9Fl#20Cr!Qv@Kz#NJ1CH^iUIY~Y>m3mqZ<^;eyOC%n(_hHpiEMn^+TZ->SS#B8>
z(OngwSw-S?%?B2~@l5_`NNp|RoLL~zJDe*8aw<Zxoe~foE7lbCS%P0?>`e~h07s?}
zNxN;-P5Cx{?r^VQ#L@Z{GJDhInVjoHj|)lhfUvXuya(WFX*AC#388+n{vd6)nd5;(
zsfu;@&{#I*!DE6VXc*4y)F+VWNiO2Kg+$CAuoKY|K7SGsn^eTiu~BIk*}qXz@nV@q
z)^6sZ720!b)N0@7p~N-b8yJVzafHZ6j#8*SQ6fo+AU2Py_7_098JOF%DT~DjMwyM&
zL(<ZHFb(;;F)9Xt5(w+Ck8ePaOY$+bRWaLRzqn*En=3*>0viU-*VOVSt?ObNQ20e9
zuU9(T#LJ0~;8GM4Di7H;N6Azs<8kN*Ro4<?G@fd*)MU%Cp<?XhBtBN1g^L|bm4dy?
zosQt96uxb>qwkPA8}>!oI^iOE0<5DzPT6ZD@Ah)QH7Tl3Z>&*V?}2tG?2ZKlS|oKe
zY_qdUA@1V{7ZRBtrMX1Pq9?zt+pne;v~x^>INEi+?qPOBZ^I!8oN@*P(j@7%aij@y
zH0=tYNN$Q=eS<nsdjSa`PwI%-&VwwjA!1h(<S5CY-5$AS{%zloG3Io^?kiKm>6$fL
z;*kA=&rZdCs>>l>M=XdAIE=Sk`3NpUE=TLgN4C;&#1pKajB4o_Q~}mUKHA|`ab*hE
z^ne4XnCC}`mZ=zRhw{)ZO+~zOvlcrU?HXFrsm5+hQx!a71WTAh(L2EweKQc7Tv9Vl
z`BYfWF2QAyn@P+vpICrECDOfk=d>m;0M;*|pxwnnsoEesZJFLj?DrKA(Pk;8pt$vK
zO<D@1tpKor!-;{PTH3Q2uxHMPGX<cvWZ*GfZwuQjMBpnVebSCI`VQPOo^d9M1I*yf
zCQ{2+&sfGq8K5`8KaboOHgzLP5A`67M;PJ#v`6ybxk#$2djX9i5)KL8jP$evR~pBa
zTe-#Kr*S%Syd0)++B=mNn80VrgvK$1b73%ULk|-3QMHJ3e}~z8803RxZn885AzrZ<
zmcarXGRam4t|lT@fL$qVtMf7Epg>Mu_Y#Aja~3dxO9(iY#Um=hiKF|^<#_Mra$ve(
zYAowr7A>1<GFGCAfy!e{xc~<3aC_QyR&rlkxRwv8Q@wYtp`cD)KPX8v!#{bJ2mOZo
zkckLA3`@-_$bU8~4Z3Ib)0KnD2#ihi&&B6ynyZgVIAa2bW=2h4#AM<e<Z(oh{2G1j
z$UMbiIuW}w*k`-PT-)U3Qwy=WS<JLtM9^WOq!r2)x{USulWb_pHGq@5WaGEDqC~li
zr;d^^6CK^{;Xq+#N3WtpZYE!^{`pkpKq-ib^u5B|LHZvAoX`R=OyJmL-sL+EkRo)B
z15$Ez<9LmDguj%|7{PV9a4RvqvQe5R;I+xLKb`>2skCX?3qXp;Rq%kd3xavTUQjIB
z%c#ExFdv5L^^99}=*<dQ_is32&JfI(QoW?~KP(rRHqXU|4(f=?bad)0^FTV>s1$fK
z+j)V<%^o}j6ekjUyBCwO1F?cA8gy{$rdezL9D+A`sm=#9;+)RJ9n!_?SUw@49&pMb
zbiekPa}U@@4m)lL?%S5|y)X>)Or&K(TgXJYwUn|DZocK_x}$*Lg$K&xz+F<W$r`s6
z(TGx3Ru@~1Lg6^OfkZ*!nXrc@9fZ3zFAb8Tw3#iMeWF>~|BA3~^F#*^DOno&Ey4Yn
zU$a-#->;<i9Ii$tLi;dOHL>N&^@PUtky}3IT=;koMR#Jyw&d7=*Wa}u(psXNQ-M<s
zm2i!$Q)n>RdB#F<qMn9g@asB1N3%fFE1wZIbIt^y$3sGalL>&}66ZRbxwfBVY)Ui>
zcKRh{rf{viGC2=f$GK-G>T%|rYMTkCg{to$W(m%RWQnpFRmQ|?5_`PQ2Ly9P5XLb@
zJQTd?dxCmc+Pka#5}@Vx5~j03Re5_>kec8P5xR%V=@PT!UOaV+HiQ_<9HZi`F>&bT
zf=ABVi~IC+z10+FO-n8+3EvNwXC&vJ=T~EcoS`G6Ggxzb<J#xi!l-~GHdoU`;}SZJ
zTMZKFY^$eN!6&$yUF^JBZEF;YevWY!V{&(E4$=NBB^ETjjGeeq8c+sTA+_x&+aBGg
z*=sRlbRQR@NttjKP8(aEmSL#!idNd~0iLj_W(cYteKk+50n`owLw0ky-EX}xyksol
zWUa?fQ2I$y*V#N$2i;9#h3T_Jv-e<CQreKtMNS8q1+YP4i&-=1GOB4p)kf=XISuKQ
zIv{$dQlQ>UKWY!iYl|zgBfdi@Q0}yJx~u(4^Ye|n*VWQ_r_NAn8T%=s6%Bn#`bJfU
zS&X(P6ry;ZFI&?eBav+h&5Xg_(mEb3F+%jW-rzn>AbTZL3iC1TXm4XoV;RjhE&2_9
zNkRsffqt<=hG+1!WN^VofFioWprkU?e78(qQNS#x8BMraQ;y4r3DF%2YJ^Lq1>E@N
zpuHYtdHY`Pl{l7fBmB0a`Xnw+ny{+luz=AQp9o5Uvc8>Y&BUeH@n&rF8NvK{4}=x9
zU{OF*BDn0Hvqc7^tV>eybYwsV;G5vWmxgkLW;h)w#>Qu~vuaDwvU?CLO7Uu<qM1E5
z^6aHmW8^@LMD1Zkb^0C>FH^sMT0Plbef$h3&`@?H9-bgiaoJQNaBCO9OTs~;B{smU
zG?dcuME1qzV?--*u9&o5cyWaqpmGnTs7ij$Eic6ypg!bA!}#Iwsx$*lPy;#}$j>g(
z1Q+Kx?E0^GtU3i48VbabXHAvB`>7z;l)YY~HT_3sD*H_Sz6JUs3~ETq6#%WoBE=CV
z^bX?1s|i0Ut}y*LughABz*0ybQj#iGY2fG$khChzd_HKYA?fuR*jS<Q>)D#27iC(M
z`~CV;EZVl~igm!egzcMwzJePOGf*LLnL#fvUPG=a3I)qaJS@g%T{MXtDmU3jSb^nH
z?k=We(KZjd0G1nAiwGIjT2<M52ob~E88uu7Q6NaOt||BTE|g#=0M1D#%%O^;D*)XQ
z7$3@axSU9<k?_ZcR5vPv-TBR}gkaIGTMOZWU9i$V@Jnw|iNHpJVW5s$N=a(cUebgs
z9U1}@%ABYMcx9rIXNS{-e2=s2cWVYLiC)&875JDO3M}Kd+gDDxC%_d`Ukpsj5(0>n
z8FoMX4j*JD+t33<MU$+{Go>MI{2jiIP)WItsyAI4v;?;5*s2Mzpg_^IPz)DBD_gQ2
zFUltST-6nz@h>8O0oYJ&39}Qn7<wE~cIfoo7oefKQrpk!w?#|m?4o-Hy3zCY7GQmK
zxq0oytTFrm>h$6QePUDOBPzk26=cXK{}`=OqToEu4gg99txKJq`N5nxdRmQ^*Vol_
z-)Sin)jATA&Zzho)!P@YxW9tXQQ1p9g+OzDmu(4{Nuesm%J`L89-ngz8_$Oz<a;1b
z!j7$}49}a}mn<Z+G}S*QpZa^RUHlt#oK=h8mMeyerjrj)qh)G7v~(j4Ab+2aCULU1
zSW_~gyHV<GRN!8Hu#i-|X`vdsl>Z<4J-lMR&OUW_1ng|Pn7zS&0#-`jXiu~)pqRhG
zUlT>j-)N7O97MSW2a!r*2cjrmZM3?YrhEs5cJJqqBJm2qv<XGO8+T_638&in)QW71
zSZ}&I3^w+aYf8b8XuU;Bzz~=k%kOkYZvIO3@@6o&NyW5fKi3uva@OrR8g@EQ3BIgu
z?E%Fgr8X2c7pW;Oh4p0`4qW;5<u?D&NPojZ3??axA>gd^(ETJRxKyA~FdO{pdk~9t
z1&s(|>`;|P6fsu2dGq*F)a?ao`>q<l@vf8<{LY)^wykE85DT@FM?rit$z%NU(>CNW
zNJ4mA6AEH=JyV15Hq_-Vwa8Ja!Uwh#ph2(){y!9gQEH)@A0a0=lJ$G|X%`Y}buJJu
zsW@B{3b~6E3~C+k`2f4_uC=uQERMjeO;jd-y&5BQQWd@Dn|B~4W?nD#AS(2kG|g36
zK}+jm$1f(KL}INFcgzkc<q8_kXp3k<>;(<_)Ob1zn)LAzie|UlN?{fQ?dZ!;Ru-HY
zogu~+_@w}2t3HX@1=*cN3oN1SMGFhiHj-6kzfT96gSVJfH6Fg*K$B$pi(bOwSGco{
z8j28Oy+GH=V*d)2`nXH3Q-f>8j!OUm69!c)jGtgukZZK9wlbVOpEoCL-#?o^Uxz>6
z77+bPr(e={Cs58lu3d9|Iv=uZV@-TsK4VXPU!Oga@IT-6y-&$*j`tKiGxuY%&)#qG
zYkHoqLmz}ZnIE2qe{XfazIi`BZ{UC4{kZ&mzva{NeSBU$G~_l}*vl_GGJ8GY#rsUp
z{dm6Qdw(q4^znGV^nKeo&2zl-X{r6VD&LC&3pm|iqx4d&>r{FA;rnv_>Gk>CBRLyv
zy3)BfyK5NI)V|)~tDr=Bm{`KaH%)r)%Rh_!a@bYy`4ZccQqT>)@W`)m0a9}Qz43n1
z<tZU2M7m<m5nPXR35qxGxP;<xTH0UN7yo)A*XQ$9PSbcYV4wQfF!ppW_G-8YM|ZIu
zMy_1?;f$^P%}wv~u4hS?7sZvt6BK=gNa0bD{HapZK-1y&dh-Efc|GDQTPnU5-FfAh
zkG8_q#RFBPCVo;<iEgc0%YqaS>9&V%_0O?xWy`wHEmh0p${qD;2KW9~3s7kf=xByX
zz6T^1`WcR%H>5N4PLPl=&y$>hp{`4O!MRRl<?g*l)OhT>;(~_Y?%FWmxYP(vBzN6<
zt=?4ES@UzRE90|FSY3C_M>==RHjn!`A?+cLrG7{Kon|~xJ|);$gq&X`zEYNYHQbdH
ztgCAlBfp2gl7fNj{>*RlI;dRW`+#eJ=}nzV_mw)bBe<?AL5^tsRVVXURYEL(SwXWe
zA<qKkQ-W0`*zI4M{IrCD8_Vha&>Vxg+1&}n+Z@~DAH2;vJr#XTlMU@zj`ZNj$A_ts
ziyHUi(K<Qw=%vbTigxSc?QGbxs-Ek!K7JE@p@(~k?>(TM*B(<XyI|XUn3OU0Yh<XS
zYZlv6+?A6bG}VM!ON|;;w&t+P6fvJD&Zk1QdZpOYwVnRDSA)6Yr0-{0*OXIhQ~E-e
z>ebV!o8HY>iqzbdET18ZV6s6f(E+*Ttd?BCwtffj-TsM3`&7D_x_SVxb||^o$c=B-
zM{$k!>NKlTm)#oYrKFcnq>-+EpjTC-8og^4>~AyJGw#d7o4vfiPh(h5B0jzI`te0Q
zOc3_wXT`fp4xjfS8zz1<k#}P6lWgz4K}|8@B6JnqVVf=u(|p)iD10+r8)Vo=u-%ti
zwY)ckKLiBa6z)atT0*%jkL5^vBaeZ3HXvPYGd*7NPa<xIm!4lxy3Wf9JAYgLD*aQ(
zU{UBRB{vN2aVk#oTyPP2Y%OPBc+^}%jDLL8KJXy(u7!U>b}Ul6$}3{~+U`o?%ZRBX
zjDLKxBHWVu3FSSo9(ll*?L$}a$n;1T_m$`Te9QMGvUI7?$MGHiEI^DK%Gk!p(aFJB
z-}=v)t$_s;3jsaBpH~6`0u~N729|&MO#kq?x&KtriMTn5DLLso858`?_`}nu|0)pB
z2?-D|5YQRwe^FlEKf-@gI#F92r~i^Rp`oXtCt&^RR`DO9FS&mP!T29#1a!*ocE$vB
z^7^L61SA9ue<_#OcQF3yi{an4bTY<9=K6xRZUmZNEc&m3a}Y2v($f=Y|0OQ;rT9zU
zk%0L>4a6L5o$dZ>Fn=rgi~Fa^*Mm;!OSOZ(jicQkWrptmvLy(d9Gs2+EeU-|2^+hZ
z8yYK$3I1XJGgn1pM_XqHLt{sRKXy}u`k$$>eU<;%_m8EdjcrVw%m~>3Gb~YaD<@+I
z0y<HvFUtxW8`>KErRg6*1_Cx_4%R<?{j+3lS?6k=ZYUxxwWmtIcs6)==6TW~iPMRZ
z69^$|gMt76lMsb-A_)MI*Xslfgp;5lZV=RUqzL>%OlPjJNC*NN7#a}pexKeT38}h5
zZjPg(qsluGHRzzQktTb30MY(<bo}hvdhcFiQPHlg;jDehRuUp76efy<i0dsXM=te!
zdRyc}HmD{P#^N)7r~+`O=1q+&6BR5YPyaYxz~nKJBOC~|Zg`v}J52Vv(8-Lw{|?DO
zC+A~iP``ug6%u!RR9|~!bVlDoRlMwjzebT*I+gKiRLp>}##X2OHqa!249PJY8|U(X
zl~^j9#g&~r##Hx?)&e}A>t*Djdr+%p{m4M*#TYLhUZzLV301BlZZ$IMLvRDX(1$J=
zWrSmEb|yO!G88g2K~6OaMXD}A62&|n)OJW!AZYLXIhp9dnO~HqlY}NIWe@usVC5Tw
zWSaYq^#1%r8L_TnJ<5`Uh=xWmb)p=E{@yc3l05l7Hh?~9@Uua1kcwEr8F+%YbECdn
zGZ)<_f-KxUtr_=bl&}%A$wu8M1}|w(9`ME`7+WHgCy6>YS(^0@TmT$0-Hg~~aeqeT
zLtVO%MJRLjn$X!h?|=b5BC9p{sABj~+{1*GCS&9G7P{yDM$_P4_caZ=dV?aW9BBxW
zMzujomOaD%2sWz}OvN;6R#hq$$n!U4V7^&tjy|iB{>sAJknf(ic!C;}i>)5$>ji5~
zC!#Cq!?pP^w7T81W<D;HD8rMMDP(Nl5PsWaWQ%y|BrN0`TF3&idK}&zr>zU9@&=@(
z*rmSF$}o#Cht-ndWO9F059@k9ZY+uRqzzA>BmQ2uu|FU0iLeFs@3=?@Z?WQtn?rm~
z8gVG<$<ig`G#5({QgB!n`Z?8{^XputhYRqnyX|4*9#%7#m1l|39DJ0KXGI-vJV~)J
z%s62m&V{0SwZWO{qs8Xkzhd_go-Zs@`Jhm^i#@PC$Heedpt0YegdBBzQ2K>BTP(L^
zdbOcjD#{RA9npSXCEq_nNReiDky@K*;Jjgdz*<c<aG5SO|0H96&e_^8zmjzJ+2N^L
ziqE10rnF>?AIIi!QDzN^8Ks`+o52QJC5`P5o5<HE`%3MaNrcsqWXppByIEe8MBn1H
z7|mzZY~NqB(6D4q+NA4*m3qRK=P>i)tPWB6tM9AghMk-`nFTa#XqdlYV@2a2vbmg7
zFKooT6Go*sWp7V)Osl9Cvn3VHB2e@Ib1uY{0yQFXcBNT3+d12TRp}Ch9E+q=Mm;Tg
z?sKL#MQf;*vduSy1euA02?hkYi9?g(4E;F8v8`a7VVy&(xEV8IQigt#vqr=w4pZ*o
zz*oRq7~a=U0e$!POi~e)DjHoitQlSxS@as#TGDdGR4=EUPvsboV*H-|3hG?gJ*$3F
z;q?7PWvZ*D>%!tU&+md?7CegLQ0<W}B^+i3?-Y}&<}FP=`yr-_d<@^{xFqg)M9Jit
z8(ed0a1=9!MOkhA$i(;8?*<(?;hoFp{qtYjNT?Va{U{zHnJ5+Nh{I3OrWUAG3Lm7F
zP(lkd;6fSsl`xFqZn$VSDkR`m+%>Z=IzvOgXS(Q%piph)t8o-8hp<kX+*wXoJR(cJ
z54TjW9kC2GsU6O9TDaC<tg1caCDbOHHJ;2{wJ=I~rqIml=&h}g8fUkNu8HXC_n2@c
z<7%kgTK2MkXW>EfS}z?sJ(-CI|0V0udo1LbkA9hdr|ftyZAiX83|`)U7pK5KGz(M?
zfG6yYn%6y44*EiFn8A=r%gj0tJEo&itc-n$i5{&=1nitAIZ8Q*KbDIcIee0HyIaTZ
zmD5d_!!0*&&Pip_zI?-4jVe^6uh^6(Fs=YzEmIaqhmeTENWGs>9Bsr<NH~y-;F<=T
znn_m}WW#J?tf*P_+(QC~B<Rc@25fA0f2xfT@y+5JLpcQrWeJvIY2}(qGlJEdL`#Cv
zgY$TEM~Y<_rOc6=spe5Aq`$ruZ@sw52-R<>dMCAu3YA#OjHvO=BZkaaHj|wi2*P3P
zsb#YkU*&}d@^G{{8<d^#P-xRvE4xS=@P4FFmzA5Fd?9Z*y2#VR(09Dbi^&u$)uvh_
zq$9+M)zGx$*jEumx)bc1K*?T_g9BR2X3<y=%j}TTt5YHp@b+ob!0$F|n{Ml|Y#MmX
zQSb9!w$FCA<Wy@nqH6>Z$@@6y33KrmmEMQx(Y3!8;k@3<TetErXZz=BQo`3-d(=rL
zKMCI~MvH#et(EA5&D9~8UnQ_J@+1j*DbqMtZFhes=i4t5TgAUw;Qao&=atZZM9@zX
z>lw!fR5Tp_%1Ym5rPJ?31ay&q_i;VH*MEIEtQ&juF5$bXdwTgBfA|MEW(-VoBx|&E
z;e3&Kx4FH=4op%89R<)wmzTI>Z-}lFw4`tnl;*P5UKJnv!9suHrmxmILaCX@ZK-m3
zvP(@F_kIFtl<%!_EZ!@pbADI3XyGyc_3X9G>!Wp}d&Y`Kcy3QWy477=v~@SZP&O<B
z@B9Pkr0Yw7rlw&!79kOZqTng$tl-X1P)U*BpsS%%s8j<I_JY)<w@(lXR9~UDglTXE
z4b5?I6-n@r)&^Xz5vmK|4OcN|ul18`lg~sn-ilnw!QePHPV*nSe_gD$$uJD;VXkjd
za2Z@iibXUu*a*Mf7%$Yi-)J2A7X*nw?tt)fh-4Mg6&PY&XCF7qkCyW`v9;aYbU4$k
zwI8(e)=u*YX=qMQ_;yX_3n_|j9OW+Qr{Iz2kjF$^GT>&bbz+z28)^I|VGs6@BgqYY
z!IT{>j+KzMD@!PdmXMal$UA`ypAeHY$GlB>8C%6~SkBk0Zsw#Bm`C12x#7?1FJ|w=
z1uI@LEy%xSw7}2R{D!)v!_?Dt*dDE2Q;RT_B(6S_A5x^Kfst{#^wzPp0vlZrxjDG<
z{k-!2*DL2e0A!x4#QfZytODjHjBe?1Q&7{u9lwX7q(!-EMJlHhY;5#Q0<mQSoGg7W
zs0}?Km;oW&8?}zir1)j-N90}bN#xv8QRsYaX{#7ShJd%V=>m4PIC9xE71<W1m(e!l
z)X6Ne9Bma=yQi1>N<a1s{+9bK-w?iM!T$aLNhSUY_Uh}~urK+_^vk7`)c80wtc-)R
zN50j#|NcIkqXU#EJU*&Zsg+j4`L7_>PlZ6%w3uaM{VeqJIO^=H=$c=Y>Sy*(&6^8y
z7Xr-n8vp^k^#Y$M0-|0Vyy<uR2Fe@(&?urC_8n`|jU_f)^;?&f$mp{lHDQr&TDM9|
z(>Yyml^MRYv|;dOWElqYc36h%6!B`ezvVOfcNxD^s~_qyOc6&qviA0o0Nhxr943vz
z6-Au15EgtslRfrd*m1#Z$V3BM(bU{ZCP`EfX-Mvw$LJ`^ZT2&$b;QCuMJ3}Un@Bl6
zDVl@Qxmv}sa`C2mF_vj1?-7XZV3|pJitl9~$V$pBCO&?J)sjBq!61aOh(ySO7edUO
zz*jlEI+;?bi{K+mr8=0BT&A>Df$OzRLbelpc75V+htjR9e3N=6^_u=9b*0Gi?+}fj
zB~B()pnAUhF~>TlvHO*NX({2ImTyUsbkZDi&P&3hw%9YXMqZX0^Pni<E>3K7<Xg@m
z3wS9MCw57*!~kzPVpEy@?-38;sOYwYdHQbS4(5vD7i}(n+=kNP)ULxdwTb>ju%do}
z28jZQUB00W!v1|i-U#&TlQ+)P^6H)aR!d9c%PlPH335@7ia5M*3?uumYk>3+01N>D
zwILm$B2`Wo!gO8eOUFCuJ2i&$euf1h$*v_}z2v7xkY70fS6sQMjmQ?h$gaf;l4U!6
z6A}k>kD4H)3P+ORN{ne@x+@|&d7pZXwr>jJ70C@TUa0eClL@eLvK(z$ngCQ6SKbeE
zJd$md-tIe;lHbbe(hM@6tq-GaCD@!4K9do$or``dXi{XUXGTDMz|?o{I)evaB&$vS
z{_0XB_F4$xX848+T!P;jUXf*!8``r)zR-fu3K$&IrcVS7w0AI~@-4y2RY=If{^!6z
zxc@G(C=^j?#(RHq0nOD9=hl(>_{5#Q&<{)3u*bn)kfkO2T}=0rN}(<nTwiH$VvdG8
zpZ6!`L30(391*0syAKO(1Nsa%8Y#zoo9&mfPMD5Lo!0Ro-s%t2yI6Bk%L?^JN^`BC
zi-!h=1U&h`LWmtICeW*4MVEi1#McQ+%M@hvWJ5Z1PUg`~o808DX$fj}E<G)3BKl&r
zA8nYuG3@W@&RX<f_Q_z4VT})6+mFqkne%elxJUhjh}5sAj(IhWU%64LXWBD)PK}#O
zBdM3#O?h%n+^|QhpbHbtm`}Xx$oy!;KuMorJUKr^bPFHNd1_3R^0jxln1_A-UhX<0
z#IQS*!{d24)9hVhgT+~D(A&$j(OC2Gal}<R9N8oMronOA{%zM#N!*8=M3PjrJTa*7
zppMU@6w@WeS?#wju9J)WI|HPGkGNzMbip%`Z7LBjP+@CNCBuF-k#mzyMW~1B@Nc6|
z^F?Cu;NwRdE*|18*lv<GZ)dAW^n`|j;)<`F6Sck4zYsIUIvp1`S`V+~$kCVhP-%9t
za7Fe+twOp(bv>>};?Z?EsV6ICPRP3vb@|lDyFbQFcgIIS;kukbTK&J=B&s4$lBAeM
zdgRM^?UKp;klOt@&5)H!u0}1cB~CZ5if=Zkw#jbIPGp0|tFki>tE@t;)+}=k{%>%k
z0WFCV0%V4fd<He6xQa99!W%h$PzkElEA5Vx8QNTfQzVuWzjNs#nj@Fa5!h@uQP?U&
zs<b<d-d{+hmL$n2Q|W5gwK_T-wDL@5u`hc*hYB+ILlX~<YIS&YeG+7|nvF)OCyHQq
z{FXn**dY@|cewy-kNLHX2+fNPkA*o?KN4yZWhK#paDmhPdHug9ayGTBex}CJd;6j7
zJOya(DX{0f?mfxzp**(nQ=Oo7z$!hda)zJazQDzdf9^{4CKLvXAmfV`!x*v)u6{;#
zaq}%!Y1-}$<DqiAmk*;-WPi?}JBw)(*-+n$Z}_{$efoY33pt9@^fg9q+Q6>}y6RVg
z{4mv%Q>!2xA5mI%j9Mg|a2o8^-sj|qWJ*osT<(X!6>X?bjl0$Q#%6}M5^K4yNH;mC
z$*NDZ;`0DdX`I{WF&8;$bYB%VS+sJ6gg@-6KNXCe0PgMjt-Kh0RN4Wf+s}%9?82DV
z0r6BHzCGXvy;e_5QX(ZIzWMc>xlul|t_Ogp?6rqtxH(qLQekqA$SK@>@ji|_UK(?d
zRpC)wE$0ocI+XjIAV{cHImiiLu;s74$7CZ?qBophVR4*>_=>TfJUA44`BZ%95=+-f
zlVt8ilA@0_#Cx<Y11__MO$s`4KliEMa7=nboiL?LeykuUZju6$e>-S%DSnUE5<DWj
zbjh%-rJd9lae{viK&61+TP3rKv73IM10GR;<cM&OvHB+GeZojCBzZpTrdSJOi21}*
zlSj>81DOuSVFa~!nCM*;;uH*}7(*rUl<awZc{NURhP>aN#Y^QacDkdJAS=1dlEi{1
zy#|b@Y&6ARP$bn`l@cHnSt(R_3w((}?0kMBH|bXnQZZU)VW^YW((J6v>rowGaZwwR
zSC|2s$oE{{C)eSE$xF#6zrlFCsaXj}*@6B#v~T#!MxX5gzJra?#8zW6@CjQ(88?lY
zqi#+seciP9Sv<FfIKXc%XjKLheUNVby_+OFCJZ*0hwtX_{BaUKL#z#I0eXP<+FDmw
z(zqf_tQUce&kXCFvhCOBBN-S?lW>P{gge(wcvFN|*rjz^s$q6r;Xdtz_e$|1DTXMV
zBmBxR)+mfSNcw2kKK*a$l52PgSe;b4Mo9;aF%sLo)&~tu`tN$Q!=0y#I*$f9G0%p?
zFy>9O%2=~0m<7aQ=VM{!H%!Dp>XN_>ib2nwU$>f1jASBD2O<BSf`v#fjH}%YYGcSO
zdC&C>`hhV*ls#%BEC!=D0^P!#CKoZpR+)?ztl^6=vme|8y7NlirVhB(zO4z!2J-eD
zq1(PsmulMsp<Blt{!^p38S1G52rF}&PUfoEkM5=S7vNR9-*m(F*a5?vB&gO<c<OL(
zu^iJ=G3gUCFfZa&y<epIl_{N<G9WsL*RlVn7Qj(#uP?+CK&fvXz!VG2;Sm~tzaIN*
zDZ7tqZ|?4PEYK$URgNDYL|LsLlQZO7lwSvk8ymDNG<*BRF4?=?H>?<FcGB%fpiQ)^
z6u&J<H>F-%P#jb{;a+`cxMZ+rLcnJ5*eeY{aCnrPK(X!ZZ!X(x0zP^43sB&KXKVt?
zblcHTWr$ZDeinc|Xmzz1I*xsno`G+_43>Wk_dkN^$Aaq!6zG}<Yyjz?)k*cr!Ye~A
zUnfLfjs&D?T^TS0*-N$owLmYo{2FbATs{q=$uxXQF<90zznNr^H~$HZ#Z9ND6x_!K
zSw^o%<kM6S#9HNg4QpPv3Hm!j?>vLZtJ;s{AlPdXQLQm7nGb#cAXpyHU>bBs9kBAd
z^Ij!r)hQTN{ABVY{|Z!gs=IzL+<3jAJ3~@Ik>poMo&a4)wT^*ZDNyQqy?Q?pAT%h5
z<`0KHpbsfPXtZ9YL3+OF;Un-JbHH1W3Fkf>vWdlQ3c$t;JriW^6%eKjy$(Nfpbwc|
zWQnUbKZ->FUSk+;QoS1>Hxz6VAUs5QYP|%%P*CYJU=bPmKFDAoJS2J@eu3^G=nMkg
zK=4Atr$BXj*<Q7E_cMTz+dd478;0{8K)NVAv_UawjN<-xAkmMBeIn4ei6BIvki8K*
z!2Xa7FEtdHXtpPL<PZ#cwO(&j`ZAykRC@W-F>uyCKO(znI|#^Qy6uY}+;28?>%XQa
zFK_sJy1_2dEu4jPfnOj-P-lLmrasyP=<vvFjzjY}I&IDe;oy1@^S1!1Z#d_W<o$q4
z$K;%5CJ+j>(N@`<4631Y8V#7r4(N1baFTqyk`)mD0#YpEN;iPZ1&%Qm+{M^HoW&92
zsPh7`6XK?c;Xxt@>miZif`bgg*m`4;?x4dg1C{|10;4ei&m;43B`dQ1%-+a3!MuPv
zfeJv}>;lC6f;%;Ud$j;A4D2B3vu4*3wg*<G%w|B%NXvk5*e413uLHDTV8Ago{NU@*
zK?-_Ci);902!PCJXmlQ^&)<A^2tU_A-p0v3dH|DRGuZ#PU;B@f^<Td>Gd<(Ko@S2!
z?T%&m<3j$+Cr$T%`D6dv{i>ZXZWBn4AoBPTp<WUh778pu5~N&=jpkj}gb(l#_YKt$
zvtj#^YcE`}96GK4X|pmubbp<j%|?sR9lp`rK3Lz0b(>K)P~iBQku&)~PpomXdv{Gb
z`#WU%nzg#U#X5auMZkU_Tq=uIoo9n%EIbrILaQD_)CJIwT1Tqthtqd>*<)34745)5
z|6Lu<&s7-+3Fb>|siVD)^U;UWr*&>YydEaZ(Frv4Elil~A9)pXO(7N-7Qs^=T;uQt
zC*ZdmpehF`Mdp$sDx8th!7t?A`#yy40UW5Z>O@&g`1nLhguIZsVUa>clnc|vxlB@r
z@k~-X3D5MxC4%0wsS33swH!)!A`6cNm+4>pF44{q(-chR={yoK$Cwna$!Cquj4qAC
z(x2#VKPb8-zi!YJJH!I2Ci}qnN=*|#yYs$v-DvvV%Lg!vxCH)xui0NK@z0_$G5rUM
zVEE(s|JR59x99#3wjgZmXy{;W=Va^f#}WS*+#suO{e>OKNNcF5i%<z0Tj;AgD}A~2
z|5GojZ*6YnPC)*56~Ui6ioYwZ^i98f_l*CM6#N@qpkbhAq$i+ZW@RK`VB=u=LK&DC
z|3Mifob;{C4FzmWt&9oi|7s`TX!r-F;9z9`tN3Spf66qBUsL%rLLq%Sabt5+vo9p$
ztDC=AN>0Ysss!wRxBpWR|F`gGhF{y!n33QQg7Dvn!XF6be_P}4?wk#r{(?`Gzc7nG
zmimh;sPAa}7Z~&ZvW&Tdqmz)CzQex;kk<dF%)t0J0Q3JhH^E;E^7lJN#O4dMFt;%!
zp!;raBVglb{x9P%&EL(9oXi}*P#PwNKePD14<=Unf9hG8SPA}L&oAictM>oy;SZOE
z?GKXm_rc2Y?>QU$|LA4?+Foo-fA-S<eXuh9!Hd51F#Oy4Z#hP`|LKFCfcb0kEMI%#
z&v^b|J%7-rFV5HVFYxILM6y+}G5>?)5d8V9`R|4M-`n{AE6WUW8wP<Wy7wvAM0Hfj
z9f-js+oYAME?T80Ku+wiF%czF)zfzd(!@}9e2qcO|AxgQ%9YajW)IXS0%7|b#<~#n
znz1B4=VTw=9WFi6qq;ZNJH{I>8$4ot3gNtYLLi6g=*{_L`>)3NahamNMfw-4n|1{A
z>fJ_w5TJzy-fG!Cf_MN}&Nsc2z&|**HJE)jMvLPSu4wK~y}tc%sDSadg4<wd%Sy6=
zB~2+U&`=s|x@rjWT5M^dX)-O-a6%?!np|r@qcTmYl`iWPeu~cIbuvb#)H-}ba!mmm
zU22?TaEdzpzpewAtrxt(zuQMH_-TKR)GN9q_RgW{i6YYcbsEsyn2SULjSsQAssqKV
K#p3z>rTPVqI7J=+

diff --git a/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model-start_0-mod_101-low_error.pdf
deleted file mode 100644
index dcf06f312ad2b02bf07cb0c964adc10bd30f2230..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67336
zcmV)zK#{*CP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&-(N`8uc5ryPn|+d!FoPf-9*k5AZrp`
z2M&TYoq&mSx}4X*tSg!gZ`rEy9!k-<%C#FZ4uC<n2+S*Ffn*^jG*r`*N^7w%Z4|sv
z)U;z1#VeubJnN_wqH9i*5!2=<b0mBlJQI7=L0>p*d1a2m-D$GCVz6gsC7)FS8c}qW
z91MJ|LrG#0>5fQP#?MwXB;$6N2C4h{g!dJXYy=4}zc|DRAoKmQU)A$x+W<O>Gomkr
z$j5y*e+!TIXCWq>Kd#fBX}^)7)Zv+f^i!8oQ#DoxK3Fq7r$*eMCQItUc!0nnMRWn`
zxTz3x&!j+;x&)osOf}>4G&+LB+)Wg?+Yk#v5sIS2u}-GimW4i*XX-(ipjYA^u5Dcq
zxsDn{E|59Fn@frcg_gLDVN4R7AI`w8?-aNR+MRi&D&C#%_Kb9d5HV0tG40L-Fvb;M
zh&1Wa0*I8-PCbMXe%@7yEDWliNN7}Z;e+XQ-@zi7clv?T=nq82{y|i(56W*lLdJj+
zwmMSk`nMgCmq$@t9s4iB`I|3NhTA_#_5E$fIX^`GXY%Vq_<z$8d*r;>QM;yp+c9J6
zxs`r~1^;7j{c$($z^QIYxZAhgTL0LlKjkZ}jr*I9*x%SJKfh|nkMBA%){4i#&ydc~
zgW)$Fd48PgNXq=S<2?6c=4Y7DKhB-sbi?U1)h!9_TaI=VSH~IllO~Ef)PB<~kG}I^
zH=c##yKa#!7`Jeqk3W?*S10CgI-(By`KTi(s)Y8(9mn`Me}6^>`R9rJn~pfR5g+n%
zJIejrj?MS;{U=LQ)q($;Znzel-9S(X^dELx1tIs#<7Yr}eO@QO>Bx=a=qSoOzwHQ%
z9q*=}xz{(!Z#z!>SyM++?r%G?037bVp9xI+aU1@oBQMR)j-ou@c4UbO9T(Is>$d$(
zM_$U49ZC8AfHH6U-TgDl0(@NNzv;#+zp)z$_qW}yT``FH^$*H#ISP#eh*Cc{9mBuv
zI8W&vYyIY?h5V*NXO2yD=;1*6RxY0pUFK&(Dt>4;f80?@kmOR7Z{;%Z?4&FGB)pn*
zr{8p%8-m_XDqPmS?bQ843;P*ZJD+;lZ#qJKYt&szq5JmwYLgEG2-X5o*a*MvhCrqM
zpc@JPoft<-@TNij%xu~Zo$@ywsd^4|1Vtsl{<vemb`AAsczQlm)<5nh#kR8>3D0-k
zF8fe_e@1l0r$YRjj?|l79YOK)yN(W<7u4&e@DSOro!?!U(#v7N{kduC{o9WH{LtQi
zD$%3#`QLP;+CS705v-?u+mUq_@H+SzF$JIRh2M0X3UFXYJ~aBb9qHA?>*MF<gyDPS
zH%|dRTZTHeat(gh@!DTEcth-zZ{863XJU>hbL;p%z0dXHe!sKdXY_Tim-ld6Rp$S-
z4{kn>=!U*g1yohuiz1lNH)$)(l`XkvU}S2SyfdPdl{RmWBa4Nx*{-tDqR!}5Hrk@V
z!j>j})Ga%HA<@K^)k&{1(I#P*g%*#xNee9=qJ+``X(<8o-eyF~sSky%QAOPrC5@J<
z{035#hC^#B99Qk)L70{1W|A!uO|t24RSi2wVo{a3+bJ^1!gx1*<4YS`O}&l4pA8H0
zETe3P;d!==Q6WsTZHyv?w#qJGsLgUYHwOvKn{&6nl2YcU5C#=3ly!AHGDy&DJ9ZOn
zYIC~@HkM6Q6lGW*m!iOEt{%HlHn=`^qiis_B4=nmA5-z`G{dVrq)hcHAt?jD%1p`$
zFkIowbR(!<r5p{iG0GXCqL*}7pfDzXD0xKJHe4a7uSv?8H8{&TG7=E(k&h+WvHM1n
z9lLKN*x|cxB)H+_8%cq3<p6#_fxmCi>f`t3OFChFC7)4?wgO&moCwY3Bth|UFCR&~
z)0<zLJ1=cCb92na#2Etn+DzQ@t87<QwUxfQ%>;h4HtptfJ9hh~zT!33{DyC1&F}a&
z*l?2tEaHb7k<f`rSv%M}8X;)PlcxW&c_S?Dn-rLi^ais4uHvAOb-5^XAwS8+bL%v7
z5i72N26KfqM78x^VGS@=^$Kf1z1#lCOq~v6!eJ&MX4LPkSInqaTmznANT5BE6x#yX
zvGjR2J@CU(z9gYnSOcor_NhLr%4?rnmz;roo^aSN3f;~*Dk74C61CHN#WrNo=n7EC
z;WH!DFBGBez2XzDELP1#0z@pd{%cS}>swGm2vpyL8e+c!-}QJYrUD?aFUDO2LA|2I
zs0P$l>}Bqq>6B?onPm7!Q-UO8L;~Yh-Lj%M0~=WU{m~_Hq5Av1^$BTc_tq<<p)qtO
zSlM(xvmC`Du}g-?zbS0Rz~<H^3$54R=fGx0Sd1Lh*#15THMSl(s6CFTRnFiA#L!k5
zf(V~(nGc9?r3I8+U1Bj?-+F}XwSJ%(3)$M%B}buf*o&3k*$OGE)V_;aQ6=&Lbni_;
zD@So|T|%U`kQV3=ts)>1WY(+}9~!|H*Mh6v6e^8~wuOT|c|73SHhCXpJHNMX!58K1
zp;QZTxsN2}fOIhc3}9KSE(Z9mEoW0-!kwvvyd$Cl14LY1f)`e&0WLq&MR4J+tK7Tm
zOvP`J*bNui7V?4$>RZIi8Q<=Vxs)e>5eFG&*(!?;k(dF|zS@XoZ^D{)R1jXC+#60e
zgtu?b-G6k|C8R^E95~b}4p@2wmfoD?iDrE0lt4@r7e6HsQHZEjiW^E52~j^u!CsXV
zaH#5w!fq(>eNr4|o~2vz8sd5viS9@ooo7YHqU`p`$XFEAJ}WZzI>N!r$Y&TtPbJwP
zJ~_%BVA62}p3>nF<&5G9435qzdIdh`4CUoVNOh}Jw22cAX~jp9Ms~v=q${an=kruM
zbyrNBVP}QT1G=&)F)h(lS-Bz!`IQQ#cYLXW={>)6A|-j^m^!y$`gG|((jDL@dG>Jn
z^{+)iXf42D?b##h*AFfV`I6@li+{W_l0SQ)6{58&h>$N0AFB9z*zTW_mWB_Nw6thp
zg1MU(ffLN5#GaCtb&{+$=a<KXJ+6>nBuFe0r;}c&N0$f^E$opB2}s{nHRWP1hUF9$
zDF+~6t4JJJ;O)`b0i(^LFvcTdDgyW5Ks!e)J(9kdN0-UC!8)bu;YDU!y56{>q6|Nb
zU=D@cAkks@BPtUoe&g0Uv%Fk5E$}<=Vcj|yU`{gD1M;jzX%&<MD5WUI!&D*o2X93|
zqAup5;H<+dFI+7Tvz@Zn&?6BEP*H>k-SYTf6#g{aXSX&sUV?UaJyuZs)a2)mG_UBU
za~+NmR&{zQUCeHQ93!R7DnTxOLweuHXQkcR$apH+mLa!fq1?)j0*iK4DkTDXuF9lL
z<Fhd#4v7(l$k?RB`d*4)h2O<4Le(KDa1p?ApbxTa7!nD?lXXes$79lD^CF%oN|q&I
z#>XdGp@7>Z?T^lN-T8h+3o?Y<3YJz&N=~>AdBDHfrJam~3%j(Fk;Z8kcQP_PvpU?m
zsw4lxE&{&5oX?tbNyz2UsgI0PyL9Y3M#TbmFQu;9W#XG-bd_I;Bm2^u(V<J)Rr!?=
z)r<L+NVUx(e$kG9gY)r@VGY3JCA2S_(i)KMYx5EJ^SZJr>jJWd4GA*GOR2>+bz*qF
zc32PbrHo~(lsmv@*{o=J82A?nb3|r`P3n=EL2VOyLpoiSb1fQKmy$7BxhZV^nz7Bg
znJ;B^v)JY<bHRhsw3U%CZj}hv4dHk9Mu{_FD9I2nJ~*Whkm9$8Hd@2gFr*hF?>&n9
z=Bfa8(?*#zk(R)6#4qLDzbV;b$>SID_-#<*fs>uJmtPSV5=<V_h5<TiWf=R1XfX#=
zsf{v)0566`vy+kom9V#gflAn8G=&r4kr2R2;Yk@PIG*j0lFA!v9TO;!2%PNWlr5w|
zqZub!vFCgPiMY3LnWV%@xI)GorfQX3*04dmkRn2zGvU4luuHVL!ug7^f;(Ogs+fR)
zN*zx^lQphE^$<EVab66tp8<>laT2EIqQn9SpfjLf&ZG$aBU(iM$dU_-0@<=O8(JFh
z3_1p3ECZD!MkaL&jx_VajsTvEl?@M%MH6;p;JKVh!NLZfiva^NkXGUhB;5Q$VM)H}
zTnBWE3Bhqu^2@sR@q9c?c#Iy|5tdfJtd6z96A0%5@v5vhgLrx6IvB)DV2G?0W@Q|V
zr=khOaJ5?!7?g=XToXXyqU5LaK18O(q6my9IVnrB0c^!oMPiZm&>BY^lXY$Y#2Hx`
z6!CbpuKHMnNLi%97z!yYiy|t!nLzv;sS%ctefdK;b69A^;i5A^@<qTvj8Iz0i6aLd
z<R$TV{aGc`;r(ZV&vQUzFA9;K-VHq#7)7~A1ZBcv0tRoj^TSHDJ5xHW7q(R_ZdVj^
zKv~6)NCQQxgmqb|&%EGGm2(^|i1T@JY?5byn49qH79|%2@O4k#kzL@T&!gCI@V{p+
z#hWDHPzCu>?iVGOO=xuq)NTN)I}(vB*O8I255vXjy!wN%Vm!?B@vK^jUluGIf0y5e
zieE^1c&TmQ_T%Hj9U?`y%%bGF8b8B@HGL-aq`bWkP?A-qA2tO#@`nvGI{Cvm<dLa(
zBvf9?!>I}2fmu*^h?`@COGhnGYxLP21X{5s$WMT+Sb^i+*@cLLY4Ekii!7pi*6bFk
zFa<-1T6VcIl2TaefK@RWk2^w%trey{(k)E(<Ul}-Hc=Cyh&N$)-;fT1=Ot>&2m(M8
zvBjIfI&W<8c4>;a#}<WC^n5-w0bavlZege<Y>FulldvgPNP2Lz8cW{+q%tNTa89@^
z7lohBpXFzbJ<y7?)RfBkCPj<i#Kqr)_YA+432Lvy3uUQG5$!V;Oz_R{4;g~dVNPhw
z3Iv3THKH<KH{N1R7|hqLPWbS3u@jL<DHc4xI$wy^c!>3jVxiO&B*B^zO$nJ|O{kn#
zDwBsb0V`*sNfU}P-i1a8zd(8oVd`RoXO|Ex0H&+}VGaZ~0j917UP?4M3cRUMTQLA@
zbN!k|(a@#wFW7@)Fn$EB6jkH9pu?_hjmHuy1z8h-C!#Z~0lyQ$8K!L6qa!>cNXb-S
z0b47$<44^#OyTHt>V!cClC^?7hR!EP1))<+p;d%VSrq3FUFwGO0A^fkLOq`9#UW01
ziq>F$iLgLtNP!jNG0q3MLx`Oc6b#PMXAl^gT{y6=E*Mxx4-V_sRG5hhO&?uiTW*~i
zI~5#u>`Fl^5=+IbV3Ses%ZRqv5&B`KS`yRL3wr~R9|mRpNKz(%={TNev~svv#4HFH
zE)Z-?-k&#RO;F_%fTpr2I7R@bVssDnk^dPhftRkCO3Vec3VLJ*Xo4mjRA34PC6^es
zL?%>sK7~!SWdpk%ojCSXDNJb0i2F8$P!mYyFr%#*NGkD1oC8He2+afLawTssN@%2u
zgtL-%L%F;b1?dX-6ch^+j5Do*rp(|DgsVm3yo}wVb)t)4p79Dc6ME}7(@<)r(gS&2
z2<VakDwSKXC@Er9XduO9&}-gN8pNz>59Cj<%m7y(aaJ8UcZ+~!^DBo1eFu+H6TD_e
z<pwi>Nh98SQ7~f`pftGwyK}AimLxz*Q1ERoH5K&k%4P!wwZlvx+|G_?VNmcX7=O(<
z%hW&@fiTrs^wZ>l?6i=XaI2kLI*Jp}I;LEt?kCS1U86vTH&eNS{-_&^mvB$BfI&y?
zATwRHotv29t^_$*6tIStGPp=PQX`GErjs-<9A;MHEEhm&$Fs|fS2iL$3{|Y7mI}<M
z0vqUv?)an_h66$A(CtkSM!oYu)_va__@n9wD8;)|ps<<hC3L*fjF#SoHj@0=DajwH
z4yZ4zJf9;IaL1nd)1iPHyvYBMU<pu?eSB27KS}%)>l$7963Q5b6>x9zyRetCuFy6o
zngMH0H2Q6nk&@l?&H;GoKFOhVfHXma+$mig4f}gX>~(RblQYa_hW+}3LN;Kxwg5Hz
zByiqLX+1S1Q0(E9Ahfsuk53XumvWql$Xol=x}nQiOHHl)yv1^SJN@dP1acEoprr(q
z<E46D8!J%q>yv^3W(KQkd~8dquq0=f3>9VU3w!pGB2Zch5pJ-v{VGLgD=A7zJ55p~
z0;i2lc$$PLMff~xFN4G9uY37Cw-yS-9ozO|6}g>qOAwJ}j$(B0v*t_1>Q>{ZVs>>7
zvEW^uRV<3fBkr}O0P4_Vc|9GBtiV@iC#&>*Qg{ji8DIfM@CN9Zkn09;OvrVPS5l$!
zx1Y{EQv|It#@~K9DhMf|)ghw9QOg5JiG4k4k;(j8WHMhDA*(TRGUWHU^P1L?;`ROL
zas#5leN%fRuWzj|IeT-Ju@4ux1Q!}yylbJeMDbngocpESwa(yW8boyUw!4-+IC(_+
z8y6moyKCXWxw{q~oVz`lOMT%87z?NvU=@-QO6h0_<S)gfA@Ci_Oa4&b)SY%Wbs=k-
zx<KUaY$b1boeI&v-6oxmY&fOUL7;Blrz`@Sk-0`(qa*9GVuD}-qGsRfBU%QH6%0Te
zYw4fu(q*dp;n%HhnDTY08>W2aZAyzwB+5f?O<ADLL;7^1&BJKwiDZy7e>SIhjnd^u
z%WAZvlzGgNOFyIK%z?&=UR-t6dA;E2Ga^g1i>t2Eu2)wt&WO4bD!X1yeejZN7uQ{d
z%dc!fY%i|7s<<Mguij*DO1|Q_K&Re|9Q~>1Vh$c2Y*U2*CfptMglzNqcx1MDs}q)E
z-g++<R0tlKH|oz%?s=6(oxJwhiXJL$I;j+^Z0VeoFO?~slf5|Dp<V;+fyX@uOB08J
z^_Z#>b_4vbs~blvGe@+_!~x#U&cQuoZvVwF(q>aHNXBfmrR171UdtX{`HeAJGSak+
z$dVCfwad!0l2m9GA}1rBO?IL-&tFVQjZsyyH?@qRl11tlAd&;5wEFT7+Sn|0D_JFb
zu%bBQrDW|}l(Z|S-qdKmXoY_=)#u`$;4|0;%Fxd{jiw7B>P4;#ET$NTvxlbd>J<8N
zWV)aa2h!CE1A*JJ=^h!hc}L0b0nnW==i)bL?`DPXL36i`|B)u*{I8}zr!2s=FH3V9
zwgC#XQTA?}0RvaOY}t+IuP}Hol0WK()%Qo;AegjZ$hZ#pq22o4;FnMHd~<q1be=jb
z+%)4fr{hCjfyS^Txel67b;Ax|3{unC=Q!@$#W=R+bbTbVod#|lY)%WeibT7k3%?Aj
zg9(?iF`TH~Xr;+j^_MfX*P4zfAigdNY&{LmZ&RV9#%LjyQeqa2soD~=U@Vgm;zDzZ
z1MAAYDe0QRSSb&g;MDxo-$Pe$NrO%oL<Px9wg?@*HmoDc)-4Kgeoz*;9CDEsBcENi
z)Aa|p9&=*K^A{;G;rTNyBHYtPAk#)$iIPAX+|`SMWd!ysU6V)Tyrc_MI7+C~W}Wdh
z4RzVV>6zT@cxy9FB{OBx58CuGC<$HqJMAf5syHg984H{pK}x?eriFJw*HfbxbPT_Q
zM>=zFTF(&I!YOMVVxxqeMhi^mq0`Gv&Xvj*RS~4mn395+J!8VcZIA_1E>R;MT9+TK
zh1k*W-yo!>0(q^`ORfWiu~?l3+SYDNk#^mcEt6B!A<|$P?KB}Xqh?W(Qz-j&n4p9I
z0Z6O03ZuaOX|SMn9S{uNQu)J0Ng0t|11nCKCWFJ*P?)j7acEt5>J9K0)^D)__lpWk
zGQY-z$K3K(G(XW88Kpu-L6`7Tj6xKJQsW}Q=FIpPtaY=Dn1O1f*eMfJ7(Auzrr;^K
z+?qnCjON3p*eU4;sVA9gpf-49%z4*Ct0TC{;uF+EQ)$<RI!+aT)Iv{<5T%@>0SQM>
zz$_q@u}}OJ0zB#2g;#*7jBbMuz*LU6g*o3ccJ%;(@m#stU}+~pUs7_G+6H+1nb%7N
zk4jVF<jkfqfS<Q~Y@1R=8{YVf0`aCX(p06o!N_Go>uV??R)KKLuQ6e@BfVz*(2Zt>
zyh$y$Y;k_)XUJYdwJCE2xh@g|1~ENGP$@pJF@#Dngv`HTnBk!eoD4&3Gyp2)cTvU`
z$=DKlHi8{<Y-ffw!dci*M=IhaF)nB<!!$0uPKU(*#EmpU{Ewt$+-bvqXSiny#aYpw
z99RW=VnI*f65G%v0;A)QHRj9~1oq6=s|ph=0s~JqL56$EjBzsDQ#Of{;hwGuGTPHM
zLFhDta(+Ui8ItqU6phQ(fU}<Qxrb73Oo{E0d$Z$VW)_VNYD#|qcbF+NNBmKdlEV}*
zL$ya6kA4}-#(4D8*vKZZfR(P25!y}Nur+7b-{37cxfDoFIU*FgNWs-fGmSA6O4UkM
zHcG}ulZo~qa>^#*G>ySflYBK)p;{DnV>mdjKW4QY7QhdN&?uH;v1Rs~`MS3oLE+s0
zi!dVk9Pp!Q13WSyU4N31?OLUq@#4JCjAp^9CAqn7DoV3RhCc$AXeyk1?Ji1i@?w;O
z-AaAnPB)qlh2*l5U@|eo(2ArCXqA?x#7LTa9m<%Ayn>S*n4myD!270xKZe4#cF9S_
zL>s%Bh7V=n>KZ=oh)eQ=T2^++kQu2rL4X+C8CZKcCjfKg<ygjE$sL$MXZpm@6tJ<c
zp(#KORY@gd+}1TTgSejqkPQ+TaLK0HO@wGOmUl8BNZ1wP2Ve-hE~<(~!=}neElOr&
zT#_J2{&kCUmO#E37Xx)K0pkM7z%I5jTjU|ra1UL=Kn2RWB_jI)(h?P+e8ykrkL7oT
zUnf~(gxIY(AOnuQ-ITaUDk3YgO?W$g2k+;*=}UkFvAgM07t^lLV#XD|g1~T<I%A5F
z-6|otNKE*`0@A*E!_H7pdqR|@!4*P(yd)xaOH_bnoLY+k><F7L3HcksHolO^xkwO6
zq@Q!&Cxy6wm?dJ-glx@?a>PM|-^rk(n-)7memG9Nm$sxmr-sv`MJYuhxINULxz+7C
zHDxGS4*|q1E4LfU2_8&VvZq!WK}t`pv>}BNBV*2G7gvy)y+~vWaxQg7T$OVPJ~8Fe
z#V42o^PW3E%A8BxOALlnxkjcrElLh>X38a>Z3oZv0GNFEE6H6dt#8V@h2vkiE*{}x
zPexWeIuU?=WRGrs+(2>N<0o-}Jd%V-fAb?r$TVwvBnh-cKaVB|Pw_+9$h$H!f%BQX
zD3M8i>L7r{x}7=*0E5>~)4TvBaVonpZu0me=!d-Q7lD%)na!+Q1o%r!H8b20&>9j}
zF#jae!nO71z=vEDcYH}Ze-i)U<kpAA(o`zJA^@<RL-PjQ!#Ol>R|@(`<Y<>B{0dzu
zQ_z_>V<<A#&I_%~)-HiSY)mNW>XP%}IWPg;prR87XsC8dHJpUtKcDKAsqK##1(+mN
z#kEOPh7-&sCW9Uiixj8~CguXS2ng|px^B&+RG?@apJB0Y42Td-D+0hFdV>kD+T^IU
z%(iZFQ`-b8c4MTHq3~Uk1Je-E*yL$6_yw9Ahlc#?qsi@O1E4(e-vuRRq2(V$W|(LV
zzOWB=7$0Ed2%l_5I74dXP1URyC1)U9tWf69#N4QEIfXQ}tadU_n;(vhWq#n!8Mp8~
z2L2?6|7@KS^h7%60N_qL)u$(J%DHt)@D<xSCF}_#0&keG%cMk%RJ&Vix}6dB+2ABG
zlyY3{>O=q*e&`|qi~3lir}V8;jzxz7ye|#@2jS+b@X?|q63nR45j<z8QzFn*mjq#%
z+h<yW*sw$VR+Dw#27z;gaX)|~(eOw?>A%+WN*P4Xxoc>I&$-np*;KMHFt}&?P_EfS
z&$uCHzI7c2a3C$pKsy-KYv~hxqTALbH>8Zz@xG3B^+^b)wslGfr?&M;NTfzDT#(KL
zWKy@ZE~5*e4P_%{YHFiJI7|j19V%`{D?$K6saIk+jp~&cPGjq|*m*P+TC;?6r$PQD
z>qS$J*`g$Wr#dx(W>ND(0PrH=@E<tYJ6nnBbn8?Cu%3*pk#4&t$#3N7pRGe8P(3=v
zvLcO39Ym0EWB4dY>oZIsTsEKPrXD5;GaRzW-fc9NrrGEaT7Oa!1zL9i5`3H2o)3H<
zuN{xe#SuWmEa0Z(P1>-U`_?G|@VMh~`M8(#6Yg$Eys|~{!e!*r`B7-N5eat@a)Pzw
z1$D<ICkUPH`#}`CTJeAt;^rpMT`f57vnq=+fIr6u!Tzd)5$>;gB=%t~`I%1CoSOre
zXmGVZt7se~#Z+Xm2z<dd^k_hQcpH2k8V1#9W;|pGr58B=D8U<LZ~#tWli83K)i&g4
zGI(yAEQLmF@ImDOrr9>=HDU^O8&nJr0|eqCK?W1qqN&I#jlONrp%audQ7Iuljv%2$
zf(%6&?IwI~rgt-7;FCg*0dk4=E=Vyz?ReOzTN(Wvck<AZ18Ad7VS?=>aV(=OFq%u4
zq1c}rg}eb$L7Pq70d(HPMGg}?qe6Cy&hkuIS8z#EV(&~n^F*Nu*RW?=85>36m-9B7
zQsUqNXj4j@D16ifCGlaO`=gz%FoS!)&1>TnDaEN+$+9nsQa3jo6m8z(6x+qA#E*S8
zPLVPw`T1rm(;*1gxv?b#<g(A!#)CW}%IpVs%A#BxTml&PZPrO~4L^3^RgY|uW({RU
zzVTmz!_i;fZCl->cu6cv(fGDDq+po8R`(HM)|oS-$q~&6!=!*fDZ4K*hZI@h97wb6
zzO}k|+}_Zw5xLO>qa?~B{R(Iaiz2Bn(yec;wR~t#t2WP!oY$hz2q#kU66)#GYSy51
zww7>~;Uy_Ykctr@<-)c~KV1Y1Yp~fauEgGYN|DCxxJcudb}=gU@H00?#m;|b$$XKD
zQE{l0AqDsq?Wxn0lzWqfyc3>#m(b_g4vbj+=h-*Q*&=d$+bdBhwQMBVK8sS@=XoL|
zy|zyqLD<fW(}HrJwx19Y{jRONKGDxQT@$W+KV3(L+3yG3k&*Zs@I14sSRENN#!F=x
zr)@u_E9V)#2tX^~Ilj^aYR}%IDV0DM#7Z~VE|6XplBgmotaaW={j4%@sMva5+r1u)
zySH0B&`cJ|KkiLtOC%*3^=#Mp;zuuo2(Iy?mqi3>)}qukehnpSK#4ew=^UkJM8#5A
z(V&ZTs{=2KoHpuLF>M9VQ|IZ5YPYDJkR?~iZQ$%HG@J@nkA$$*iYY7XI#sluhL2r~
z>t*<Ws@IjE2S;>g$gu%ItTTW(m9Lz!d?U^}t~7!VmT}dsIasvylJW)ZwOc)SS+!N(
zkin|0eD4CVf3tnyK<%b$6Iy9k2r8BHzF9v|m9?E)uO|x^*K-zCS5+5@uZhk8P(C-h
z!aMmSITnd80aR3NTFrRsbS1O%F~lsVmmW;WgyQpOtxfZ-SL{FyC03!0?fIAEAKUXU
zcVU}ouH7Z@T|OAQ0u_VuWEJarF=i3#?Y)?TzqU@nZ^1b5X}c(VG@@K%h6gTR%jl8c
z#vZAAEDC#|RC=QU8;|p@C_X&kv)nh|nXHt4R<Gc!@H%Xu5~FQ>g0a0$XI2C1^`y<K
zvG;n?vRHaOX;XjgiETpTMliJZt=oupbqap=deov;dc9m=pXuGVUOB+A8Gdqr@^K7S
zOs6gDu)%5_bL*A^oLjeK;oMDA!9$v}4%)9+M&>08SMRmKXC#xB)hsqs*GV3Bv|}qB
z!oZ5&pRHF`&8$8-lxOR+xa9)5q}h+9X%^**Rv8XsBwiws7q*v3K;El5NmwnF&718Q
z$!6ooYn0JnG>%5vFvS67%e}+_m!R`0iyZpMM?PtW4X(H<JJX!o33(qD-?i3WX6_qY
z&}k3DaR<0z7)NkBxt>TPtBQLa61aGLZpQKT7Z?5=ULYoOCn-c@vwPsia2n~82a3Lc
z*}muNn?+;utAs{al#!X~>XiIf^vlF4j|(bXN+`}XPP$4^NV{wqGs|WRQ7(KM>(j%k
zPtH-eb%tkhB<(+Ra^#nwy&(dJiT_E74+(b3fd9~kq+#N475JVdXhbi=22geTC}{xH
zL?7~aeH1xG!I4hTzwktzCcuNF<ViYQ!|fP~>}Cmiu?YN?oUu&h(=q2+Q^ff<s4O5a
zWdT2wGcJBsS|E~H0xqIlgE>R`4ug}joB?vVm*E6iGkui&jCkeuA+H$@tO}okp`Z`F
zw=+AZ&vK*TgqlEDHb9p2DbsnzEcID#w0wy4vbMm!&?m#Y>8|Y+rUjR7pE8Z5*SF7(
zMsR;h%b2Kz&}Y|#aF)!H1?b8uTSGr}f}*?>@YLx?eTAF5&)u0GyLIl)^w=?TbEd~g
z%Uk-SF{!Ioj{z}#QOet&qh(YVqM-;Tla%m%b|Hrv&~f_IO><ea7zqM(Y)aPvvTC0~
zva<xF?-jKLgw{^PR0c^AdM7DE;5;uPza9zTqhE=YzqInOvGj|^^MDxY6@rC`sYT&g
zcy;`WoaaEU?ZTst7?T*U&IzC&^-KZGAIg2B(3N2BMRUr9TmF)1JnK6o_>y98!eT>&
zrWetCd&N%SU;WaBak04Ag;xG*IY$5!)hl@F!i%|rry|L+SLoD*+x0@iNkk~+ujEG|
z`<HHv3zz1l4WE7crH8_WWZ-_wPl_TbUA5kc!Q4N>r9z@^hG50zkcq7s9d<?&d_}?c
zUa?awO?Jx~aN~Nb*r^+y`d+b9DDFdOvZRavFXN|Duy5TbpB1kUkm7HCjhG`E+bg5$
zV#Hc@MBXh5uOUEbFA~QG&HC0JN3pbp7pJhlSf-oNn@9{^1P(bbh`Rzfq5KMg+<*$#
z?~30{@je!*0vB_9(k>C_wI~eyn;4&rLU$fw2hsOl0w@PSUlL-)ANW)6EB=kp!Bj4h
z%>K&Iup}`06c(8>{oQHz?-gMM8|9)@sA;MtW%|Qhqi8ec3<dA0U`<G`FzOd2j2XQQ
zf;U9CLa`81wqO=3YByHy!Nrlr&S=A&o-F83{^!)QXdR4Tvi?YSNH~D504#&m^H?PC
z>498UkktdZEYl!H+*O7k;+^Bpcq#-tRZ~AJOggVqKPyZ+ZxAo@+mkx>u>e3h$P^P+
zn~d=9XfYH$BxDgX$lS6ykfn)$a#!3@)QC7Oz)cy3j=G}?G-|*f^;6HW2yh=sLSh7h
z;1`9_^m&aCk@cl8Dpx^|gK<=g#3?wY$bht#cEX@!noGv@`}v?T7LSzChtz;Y;goWb
zT@^|i%E1zcwlWY7H=e|irm!Yy%K8Nd7KM|{>avxD5z5#iFgx?SqKT2GB)Oev#d28X
zUtIM`j0;+p+m?e7|IzIfV^gPESiDTbNIlf8(lAh%%dPS-qJFM12`NYEGAuS$FjY~R
z23EKUdboiXUWgsAXL><xAjHcHH^We%HS=<gq{P>O3}P*Tj`3ZHX(3Jk7RC!r!jMDY
zg$)554j0B2Bfea~4)}%(;j5V^NHg-e5?IS+#BBI6FK`8*Lbx!`8Xz7#VG^?MK@4e-
z^0Ugxd;h7M_FSSRc!3ufg)uY0GfOMKL6b<szXAapKXc(T+Ji{z2dwr1Qm$8JAU*i$
zO0MI=D-pJxkU0f@uc)jwXr;|Z)E2SBUy9nQintNAwMNq_n+}rYEt@?c%lQNO`0!@>
zfqZ*7!7CeJJ{N(Rbbtr-%CwJwEmtiq25dRg>f6AulwH)gghKCR(J-&X`8K14$)ljN
z%&-x!6+`R7c!=;U7k(+jv%K=#+l`?}gkj`#mLNM+RLv`~9hOe7#C9Y(FG^#2X)K_U
z*pG%3=0#!-a$YD3Pm2&P{BUKqhGZ&WEuy$Qn8m9!qPU{XjM|*0<h@f6l(CK!VsF=h
zW=>IwPrXMAeCoK75b)LjQ0+~7q4(6ay;9RNpvyBe9kE<qndyk-av=)0NX=bs;tL=X
z*A*gH^}Z|l8=H_o%PRuQKhnPAS?C{`-!b^g{Kj#<WqyZQ!Bxwzbyfm59uO$k=#}`5
zR9COWZ=kkE1&I_v$8u(zU1s0o`0fp@^<ix$m@F5i68K{=JGN7rERP^CjXvH0E?ai<
zu08}Pz)>yaZkEoB3f6!qK-KL^0!M)puOx5)`Y#HnI9T$Uum^FfbVn<BFHj=*{ap#+
z@QS;T)Dfw51c{%W>c!7qxnwkXH3W=!A86%r$;I6ej^hj=Y;ZI#0>6A?xpv?Qb_#C2
zP_NZ1YaA6_U15g}9yAspNy>;ekT;Mkv?zq$F!dQ|XAi9LpkQcEBOK5ZlHdR-?yN2p
z9yoKn^2`TigL-&_1=IVbTP)oyUYX}GVR{!h#c=iFfSjFR!Hw9g=yhv619GVR-7&J4
zbk-~w926d<a4onh6SOo*E&_*xI`8sFv~j5u*Co^DSE(5e=SD9nys+0V3deKjr|8^j
zi0VFE^%Ww-3%$5r4}0aI1H-wi>?`BD+|L8e)xirlCr=}H0p}Py2+_ybhnzyDfUAH+
zgPod1dXj=(MD&43xDG_7JGk=?qK7nM7>nH*V%%UW_R7>x)3B#sCZ{;mi-XJS(p6)(
zr5Vzd%#ZXG7Asm(g-ladHI4vlT2k&p(}0oIE8!nOV2jf70f!(kFAM;fAzf~vi~(bP
zrI)IryXpwHOe{KBmg$93>Z^$Z0trkmAc2PD(N*S&<Hd#JEE~tTv2Ao|&fErv46AK;
znU|&E1?*TpT7r~I1u!pHI4{f0yGtKKtx%6TDvkC`cU>P>&sH)4$!zYtOJE6gm1Ay~
zXY0YRTs^Xbs{>Ki21HppAL`9I-EE5y8(LAu1Y%>^t(U;s+#RhDFFpA$3W^dE+eJy?
z6?IWiWE!|AD7v(+6co9A2~g**OAH`(UYHKZ{B)JcArPMXhLx8u&BA>^TB)ntPP<R_
zf`nzFr^}<*P{urpp<xMcuDVcEZmv47NYqGh7h2QZvxV#a=E5uU{^rU9cm=7!uAps(
z2|6(-4uK##D-jVV(OtUoje|k=?mg9qlb%qGqP$VNc`69b1r-dvfGxtB$D(rC&Q+Uw
zv%;L`j3{r&^K`jc8%%fZdVt>C&lA=n7$Dt+5(5()%ibkrVt7R7G_aRQGLNO7g5~pG
z5j=QeIN;2~BcD-t?ZJ^>gxtu77i0%)iXOh<027VTNtJ*p&Q+1Bh4IiCrJ97~9uuh|
z#4wn*Q<8f`#(D;rr{Y&De6Zy&gTW8pe;<_Or|`63SVSqpL{NpP(D9CWKK>2XO2>hT
z&|Oxy2NkzJNgY4KHG0G;g5sXy6ftm5a4L<ft4&4$0oTMQBH)_%R1`7_NG&~+Hc3eW
z83okovx!lpbTJBwTBpHLRm=Lhj_dq$p48dmYN-&+iN#V4w0?56Sf2ov%@0Ddnp$6{
z9nKX4+S5eo%CU%uz!<nFMou$UX+`pJd`USF&gTM&=``DXP?Aadop$QuAOIC?`#NkO
zpOmrBs&y>uPRV6u70;e{e8n47ZP_^7T%#ieuPj7i1|T`?vLt1!7?<j7pkPuY@b;4t
zxi{W^svJQ(3VxMWA6pb;NEd*%j!%+A8GL#^M7coMYe)1`a*IvVO>#@5c9Ym*>-F~8
z(jL$43)J{y+xCQ(|D^Qos31apoiz;a0_FHBsQWsi7~aK$tswL3G$gG4c8C&tzs^|#
z^zW35-1;hr|2oT22H@CEd=?9+Yl8Izbh)tPfGb*vWeJYDl2E*0yS5mL#k-E7Te>hA
zy|rDcomLRtyge-;x|ur^{<^&*d<&Wd&n;-auKceK6}I$*4vkW}#UfDe0RUQuX6Ift
zGhCVvq{4@knw}a^v>_2bC|Hc?WL#D$Pu-_9AFMxET{>9zi+4_y(zw_yTDLS-&iR(Y
zimSqJX{^{h2wZlrni&r?R?he-g>|(N^jkV@X8<n?-zJHjFvnr)hB*$CzKS^xz_^wk
z-Ukk8M`M0y@qO?XQ#FjiTdZ@6qpKIDIJ$aa5r?bSKzrgP22`j%MmF)8@%ggpNcFA9
zPapHEUUD5N$45S$`rrbq3<NC|dVVo_s-9>)qY*ukI&*TjdT}bZdU1Vj_TuV1dIh(U
zlY8_E=I9@G!UX227dK9mdFsKPd+O+uTbgyQCO5R|Tp?nrUi%$^cR`7E<I|Z&)jsnA
zt-4nY@>O-Ox<14K_aAA_Kmr6SK)KVW$A~Ha|5^K&p6hZYTMz5cUy;o^jVkjV!L9&F
zfZZ@8m0N~85_Ak0yBa!%VEf;Dk@3WsYo{vT%>C6t0(*aqcX9GEIT^v=h!Ghl8-S_n
z6XB^tRVIpXP1Rw3Z@Q}2{X#~o-{hgmgjYkkIeU^uk5MRwukcNQWjGk$Bv|Rle3M|A
zYH<;oX}pHOwVCQ`D5N;^fstAHZ%P?9AW(h&ro3XKZ+_so%;=t_lRFbwS^Bt@z{-HO
zyxzIYf_9yHJg2G}Zx$Y!*Aqy(wdc!ScoVYC`uY?zYulIGF>zF{Yw~7(yOS>eWoCyP
zf;?Za71gpwcTIHZW_vxHskTfmPPS%C52sWw(5%-{+YJxr$}6UxUJ6l$9!WS5m2?VE
zg<{vcrH3<B=F`noD<>?kN2CxfU7V@@jDwGuP`kmUJRnOwn5wM9S^_pD=lR89(GXMN
z<+|hZBZTg12=?AVMO`O;H0<@u$q(e}>n5OkeQyGy+4Nb6VfMhMT3kW!0vzQbl>U)8
zmmdV!^q{DEFE$c&^<I8tl1bf<oII43yAJ|vZnDa+YnGeNa<;Flm=59Eds`DZG4nd7
zM~aBJ&S9?8u^}pk?)b387TlfHp?s+1@O*|6qIxb4B}DaH9EoU5Sk~y;a6MOtNRYd~
z7ic+5ZqKN)d2iZH)B6EM1?a1|m1B?rzq%KDQD^7PXX5!X@#@W^9`mr{;`7}Gciw$!
z(}UM=h?KgM&txcGg~YIV&3F^Kat3&FqLN=W^Rxd=0IT-`v+ofXoYWxvXS^9vciw{P
zm_st$p#U7x<qolcXG-1Yy^qbjyZ649T8m*Cr5K`Y`@Oy|g=4Nvx5AThj8HqwW_`RF
zPq%+vPWPRs3f*8QEbG1GJ`&&GH{m@<G<8>g%6aRZOKf9%>dt+n4<#?=uOtTfCSi^<
zI`{ieBw>#C_?3j2tL#B3F0ylPIFfiFZw}^!zO=OI2Fa0Lyh38e$Rm#=8dBEq0&{-C
zCnCpn3_Wj2jwD8|G~vWpzQ7KEVb2%(V?aYS6cm>buc1ttgCNVBCZ1Y5@lRXT@Mqn`
z5(i2(l&j(br|tuk@Sbo>GRHrN0!tG=NN`fB=OJ*CvVkW!Ny)(L?NYAo1V0U>9~op7
z8p_)^1V&nV2vHC(E@%Y(RHl}XeDDRd(cL2lxp0nvHC6d!>sP{ikPAvRGlWPQdNNvH
z<W;mW$er_y3rWgT(jax@i@3_M4P^!zLMgrJ?(q@~r7jwRDWRo?P)hxlfR53s2M|gO
zp`+%iN$oRgt{Sc5$|*uvwp>v+qkWh(iDeqljh%90=AvJ$)J$<7l9>taDc{>10RjiP
zZC?c6AS3PzEKK;)S;+LR0k(J{iX)*>C3pY^NkB%junp1#kFwRfCZHq$qmkY`5xkAd
zaCPyPGs_kN-s)%DxtL9QpDIEua=Dw0l7{I>{8Z5gkqD|wPM2Hl!IaJiL1063BOmGc
zD^qjJF|<r|or6cwE*x;5vu&{eBX2kR*cIGME`_IG4SKuUHPPtiQJP){UfaU`Xo7hL
zvGQr4jOZzpRHGElJMfqz;w!~O?8z9A5R{Na=det#-U}6&_H5s&Cli3t#dDB0`H?VF
zpeg!(XNp5Z7pFp=N3a5}#BYh^)FV26OYxl3Qoyz+MT@_;EC&?&e#RX0j^#2buY{QM
z0dl15BAm!mXx|A(8u;$|&hz$wi~rhM;YiL~{=U<k%j0<8X}#r{{zzEp0GB%8^ZTHH
z;`7SF2a(3&-{iMA#$=Q-EZ~k1_e%Fy(~OK-FpZEfH<7dEO>i2&f0K&|1NlJ|VGCLY
z*XMO(A4--j1lie)S`f!*I`O)vGQk-b2L9jVOw6qJf0I+PyY$A$m>kzf1|aH4a<*?A
ztxHwlG<*X?((}tHCI(5MY?AS&W4d3i-gJq-@hExG^aibr8=#=57H%lsz?Zx~;h2Ub
zqBN=|4kJ6lYeq6Ec*#k-@u-T}8L(k>OApCN5(C@m3>!&NpzxrP>;tC#8+xlZ=x8J(
zfLQ{j1~g@F?9#~aeltCqm3;%C#{D%8^D)8Kz7bU;BkUD+HBPL2#%YZVjJGV^6$AL;
z2~pI~L+~J+^o<T18N6=n9T}%?`Kpue?|4gCXvC#k9z#b4p(}cAz@*j1HZ*X4K8ko7
zf!2DX<OT__-cY)cQQjgy9~skaBCZ=aLAz-KA&h&aA8gEwszhhcjHyi9^%?M0UQZX3
z<+qeCllW|L#Sg+xKN3p!sC7JS*;it*mo^Z1{kwRjMh0Fl8K?wauT;snS-WWR2Z5@6
zO?8zpoh3!H$}Q2=MNoWS+AT7$TFhD_0;`v{3UbFE3GZ-ah-Lc82f(tvWJHp}Eq$vY
z$&glF>tf3f{;=l?ZrEjdDF&>xeWg=kWE}O<20<M4(*Cf3v-VXqN<N__1w<V6lKz2e
zx38jM0%*XW9g-VptkVzUO|N)JB1}3#gCoPFofoM%Y3(A4lQzvvhDn2HID&X=T)sUa
zy3dt{QJl0?jKZXKT)_j~r+_j;!O~Mxk-^fF(tZC^=MbFK8FGFkD`LfS=HPZnKE5M}
z2=jM+5EVMRW^NJ7J9W6=Yset_L2PiJQXm;Qtx)_C(ZctJ=%F0Lt6EgX@QM}{0e4f@
zApUWP0-lfrX@Rr|)Z8!Qz=$M~edG~fB~wG<MW3;fslmT01yzG~lnl9Mi2I8>VL&?m
zyaWqJ)RKVV6r#zcx3y_;eN~7SMP@w!6p9PtN|GIdmz)vWLV%5c4<_rxa|J=uFup3y
zFY=0ENz;%^!;+<;e^rU#a6toyvA-lBa-c0<wv7QO@nz%~L|H#CX~*Es;AQq0P~*Mi
zAA=MbFG0w#3_aAn%`mnhUCWHPYWQLz85tt33zZ{@9*NLofQo!cPx42d<XVFZi<dfO
zkZrYh5l0V*{EsLr1s{y55~L7a7An~RI{5HYzDLQI4Q7zRqYIioB0e3j{wW3h%KWMU
zS&h1ubUK4N<BQy8V1o26AB824PS4+m+obpYRVk)OJB2|bfe(CS{JX*+hK;28$upp_
zUv~Tp{5gNmS+Bp#Ao+9NRWNhL%2%~JV{Ly`o45Q{3c@7m44WcMQs1T+liq5{n3UDl
z1=8?Au;nTl<S?KSiO31jU2JW=wW7D{tJW0qC(6;=nHL>{K>pt5SEcCf{HhkcmD2dw
zx?N#Y!;(lZoTvt8UhD7AgPf{=)d+H`PU)_ICRFkf-6in)Pe~=xUuP+ISx3Tt3J|yB
z1>!-`cbN|sB{poXzk0^e4bB5y32cuf7~FJLP5Ob?O-i1Zu8h3n0)Bh-uR3=`U#?N(
zG^BvRVM$w;Uw(4by<dKk)GeK(ElKK@me+=~ZE3M2Q(YcL0ULKEwthw=o;i}Y60~%0
zr5NR_5t5lMm&#5KxA)~ISKa&eQCZ=FG<fQC@_@0SM;z*tqU~Qie8ZBcPNt(LQ(bx#
z$%&Jce-ENN<FXAR*Z2{rQm{Gd^>b0#OTPYRkX@%M4*E!f+mIJYPV>ulIPx(;)hN$*
zP)s~m#EXk#?-5iD>dr;Uj~poXrD9b7lAJLO01tLYUVx)-i)_NAmMAkzBS<8d`Wi;}
z>$qcpdWRZd`>GTJ)F%svMvps`=X-$PZ!HE`zUDhd`2CJzgyAB7UQydyGhW5`nKK@v
zJh<JQaTvr2|9=qeeMLFtDaqY9u<~tdGsb&yB<bvN_{^0)=3Da4`gy=dLTTI)=y>Nu
z!nB><fJ^vsQPXNTh*@>T^(ColH<(!!b2ms|)zX*vReq-`cv;)mRHX#8^a#3<CfbT4
z@Dd!hnyD1LQ{{IS<kfe)?`@Z_sR}aJ@-<ag;#;e$!Ursuj<c!`x}HtJo6z@J($-3n
zuLc*%cR4+qB)7`IfWLi7a@)k))m-XQl2nJ!6`i^Bkw3U49fSjt&|XIw0?VW5|Mc7c
z@YLVVfB)tG`CG+jISt+rf~vTO`!E0NZ~yr@yI1*C{r&%cs{c3t`h3ct|Nhw{IobSe
z9yX8md0zePU;pj-KmF%_F8^FUZT;(ie*W+O^soP^4*RG7^1uJD|LOnnum9)gzx~(e
zY@*XYbNP8)b+2+B{yDp?WxxH8|NU?O+o#@nc>M4G@^6=j{k)BN=lS0*!O@xL$-JMT
z{l(s%u(I(}Z~y84`al1_|I@$zzoM7Uqq?>EY5$`PiupK{s{dX$iAK&|HvB%n(90gg
zvOo0l|Mq|R@6^k2rgEGq?EA0~e73{#nbrF5b}}uF>}3bJ_}$C@V<pmds}iBsKUd<8
zWnRF_zx}2%q&NS-e4M+N^79(|@BY)A|Mb8A?Qg%Gnb9)axy<T1Z|?JtIcojb#sA*a
z<SkT=@?15&%kJk6|GUqNi<${<?dO4UiIsvsn76D3D(Lhhx*?d*KeFCGyTB;xEXxD)
z`u7*pKYuoSt)_o`e09ZiF}k|`cui1c?AU`<DFuI0Er_SyTFz<z$4WS(-dZcqsy|j^
z&(ZV``Dp%;>HnA#*3Y%vap`aSgX#bE$sh18yrUBX?T@1)ZSz~L=7rHu)$;CB)!xg{
zAFE-dyw$vZE#*I~wg%rJj@R)I@Ag{#7vcH`tH1n5R)2cl-m%FQ_v6@t8RD&#Oc6g;
z0;loT5^&?EY8khtYAN`WY8-y_0#fjgsj`o}T6Mosn&sdB0)8vM{sJ;}$U8da68Uj-
zTzS6L#`+6OxxqL6R%`n&Eal5~^i`?0Kiwlwrb!kS`Dpk2T3CPm3;5{YbM<%G$o^>h
z|07=jq=*_^O@hTAN4M(VFXa^cNj2`o-)ag!{;?YH$hVsCl0R0fHJ28zpw_RY^$&jm
z^-xj$`<u{j{{bBU{6m8i9OS350pnIBv%j#6@6Dg8tn%lIzW+|o_rI_=hV${=cGkO`
z{^3=B$l(8A(f@~xp8fZ$cmIX8`(+2Fp#HQ`1&j1oH3`yX{SVB@xzHc;c*o{PjgCJu
zM1E;Xu2=HyCdD7ew!>}oR+8YyY84{8x85uHxgtR9uZoiVT#>-PuZoiV!fU7}z-fJU
zgZ=Y+_=UHSiC@2ZD#_17wEeq<_DX)Pc#`mZSEKx6rH0G)t@cWOu1Ge@uZoiV!kY-5
zx<CCQeoZqr7!1DpD#_1-Tz`K={I}m;$<GzT3Hntp1wU7V2lcC-BtKT{7i0WZ%knS0
ziQ^|<-sc`ay@_8k5pVeR-z~OR^7HTrd;h8^$<Gx*RD4yG<mZaGC%-C6@^i)QfB)ts
z_?35YFqvVj{P-?@O?5)J`K1UY`EiJY94g<Ql$88jk?arOsy8J+R|KH)RZ)_kD|-K~
zbW6YR9`04zpMMj-WHj#myM^{jejM72{7r8?34X5D`|sZREBU!1*_^&AO7e5XWxspt
zujE%urvsx~fBH@Qn(cI)qkq59Udf*<?Z3A}|K7&@+i$;r@E>k;_f^#TZXegDCc!^u
z-h5^%++Fo%U-|=w%lMV8JUdE^>)FchU5_MxHo_ow{i>HtuRm7{Qsu8|$p!smwGwnf
zZ#4veRxLf8yoK`Z;rz#6LOFL#e_+}4|G-Nq;9<XpCxq<J<AcfItK!T%<)14;#PL;e
zw7=9M;gw$%6>#};MFOtgccECUUwjz{rSS(Zqy0x-1_6d&BP{i&V>T7Hdk!$_rQlDh
zft-4)+4w81kx1#SrtHE$RwHI0-@+EH&M&=$ebPAn(Iv>Qzk^L^_&YeoivKt`AVY68
zVTgXLMzrQzO(`;es^&Yw%~dT0e^O0u;CKW6D_-EwxJsCn{$JS(oV_Hi(mS}d{>tEH
z|Ee<kpZ)x>VSH8S`-kgKs<ic0;pSER@#i>-nd>h<@jpJ(C&2W-qPLMA+RlqH29<)J
z2WGG<zSTTYVn0>`TKiVB`d3<;{=3$u|CQF@H_G|X@-MytJJfc6@CN<^JHGY2PRqgd
zAFtE0TD2S;)vA4s?hmV#@w?W__zSHqxD`|_1%FZv6lcDHEdSygSO-=22fNLGzyMmS
z|88*W$BVeEM#R`#ZI-Xm{b9A=o4o5US-gv63vV?gnEkODjE8yyWq&pHkH3Kv3H}G)
zz<=l*@a36F$&Uvn@ReT`U&$|=3J(lA4(PT1SN2-f77<)uUHuaMi7)r>riS9LII2&8
z(c;$XM^DhNY-A0phOe%EiT>0>`nv`2CHfUd@QHo;OC$ZI<yr#o{JmaZ(a(-OVk5t+
zzM@}o?j3H)`d3D}e#Ng;3U{QhW9b$Bi7#XQozLOletRXq;ygRSGk<BE{!9L|2)Fs}
z?JN2dSD62PF?@-B=~i$2%j|!?3;l|@mky-w&c32Q@t*%)ll*Se{@ZW=ho}FQao;ij
z^BMiQhmWzkw|^P&vVTA9|KAz)*ERh5m+j4K|I{}B!ovO2|5wxV6D;-IcK?6=P_H=Q
z1Xrz`#o&gY2*kQuLfn9-yT$3j<F_!s04H}#e+s~GSCly*Z?_B!0iErZnDh&(ey)HP
z<0io^BE~=<yCsK6V1?b1SBh|ak3g0uBr&MuLGVtuk}<?P-O4xvzkyzEX{!Xc*>fdy
zD?&Wn0x<~J*(uVkfIqw8I=etphsf@^<#p#OqgOq=pl-=Q;`0`0ZZfqIn-&QzZ;=Rb
zP9&a@^CY-*%jlJWY`Z1q1ZD=82gC`fa!WKlnJnFsHv!T#w+w@bbdPR%7>7o}t*c+g
z<m0e(i*97}qZ_X`Bk!SDbIVBTWVCQg>IFF0+>+b#l3<)-*!B>x9YM6|Ol?bM6Cm;*
z$ti3`l_(zHF{<PNft157k1CNc^9jkFnO&Iv4AOuN#4Y3LcA*pHt+J^?uXd#)B?_k#
zE8!W$5co=xo*khMzA{2Lx$cjIHe*CbK$}sB%^K>rk01(nMXe0k*#w#&$=wTf!&{NT
zy+I4-%05hfO21qI@WJ`woc8>N$Ho_NB%h7nSF%PxmVX3vZqT1}5A6tx^riGY`*ol2
z!01oLj1wo~E91a++-CYpwA?1so{M(?EQha*5xglpT`UCP*gUg8lhf0Kl;8=;eXT3L
z)E!^^DaOV?hEHD!THPzUO;Fipd@j-g!fG50>9&7~pVL93N69j@jV>wE8~HwugeN+k
ziU64HvD7k{2~Hpv7;$?<vH41hH@N?O<!8H{rIryhkqh7oXmqnYS_H4}%~U6$#^JfU
zMH<}<OnFNS>S`q$TrDL#mig=N$TO<77BrHm5sswu8-CBS64yp080(1gnem2-Iud>y
zpURR;a#f$A^Qn<*;7GD*G}Fw$xg!bZU8ZR#|Eh~}p_cv`-J94QW<3`JLnS+b&%7C^
z@J$^_K4gS0^hhaxGqn0tqH(gG`kR%WXaY})hL3G=3lOQ+f;yTOf20c;eSIW%R;RKf
zL!@;i*=i)C@wwFMq~l70TjIO?NGRPEGnK0OW<d3+@ZCz{*dxkjLWds-DS!(~Y7RZd
z=-hZ86nbhV-FJnR%;(T^&{T7%yH0n>!W*LK^WX>Pp<NB5sgg^g!a?X$Y3&PHx?S`V
zwV<$OSHq#PrV<}RQy6aHN~osKmV0M~>+OhWdGpFMm1?c!mS_|Pxg(*`$jACz5zU@B
z(px5FFnMErCdEmGzV1k(-3U)TWrACeB>J9)dL?V@k>rCb-7k7Dx^7<V(3$!g0KPy$
zzoi@v+HUgUlhxJb#yXN%v_<X0Cw@fPa40<yWmLEpkAwlm9(e?O_`x-J1d%El<hu`L
z>#ie8Of1T9xSoJE98Twhr{0xxqC&dp%1H7#ozM^E7AH=^h4Qb-+UTTiID&agIVb2l
zWnie}nRO*s_?+H8rIjJAm9T3ky+MVj(M8cw1AF0_@1Wl3ZYNhjjRdmK6|gbjU-8Vd
zRD+n&Mc`kd+;q|PS0c@QjHLKFqPu8B;86)r_e@<?D_TpO9+jAOCkw(8qWeuNjn<LO
zTV}U|&C!zuzqZgFF4m8F1MJTz?-$xmn=OBg))MJ_C4m1Up%gQm25XIw|L2P60{L!T
zbn+FZ02h0Fh33)4AAcl=62`?JU!i{Vk$;a_EovGarhIuv63e@2=3Bo-wvxti>vFtT
zvgn=*seELdzC`F=TOPl9+PW3C1sB;!g&ETOrWDs)uBW2YE^}b?YTi;l5uK(yij}M}
zE)w<%Nw15pq&5t{kBH*!dfrY{$R>{@wg=cJyeo@4{!xGPNgh#*PRZXd3$cswq>{bX
zmAdjs?(6NC!%u}9<4Ce8V?;}1G)APaGgvoV9O*~E>`#pf)t4mc6<X&b$fi(yu&LC`
zh3Q>1v9+Q5dK$tNddwrqra7nep_b8oedIRZLidR!y%N>paI#d=>6~&75#`s1nkJF7
z_q3~P|ERy7Ms)?R>tac-(0hCDs=@g!_{|?gw{uOkP;TNkujIpZ*j*}wo-R7`r*?`l
zv(UbH&)dXG_FL~&&7jMARWqr}V1%h$({>rt(6W0^TN>ha?^R8QChO%LU|uJqR-w8%
zWi}ad|F}qFs;-xJ(&5&4o!(>`^Tu5vN|jaNEsbT^NxjKBK5Ol{0={`T`(3b^3fYf~
zr@Z!cOW8_5C66TXO;s`qxVUL5Uyrw}5u-7+8v0F~<ux-R91(pt`mPVUb0!m8O$`cE
z7vFd#J%k6}_=6~K>Z5cUmVHcO3U5<gLBTZ{$dSwSxgs_Na$<O!YWga;Hq~1WXN)FZ
ztv3-P9noD(;>f9FYV{_QI`V)V0qvqg{PO11L81(A(zB!9QtUZsEpIZ6Z=w{}RbeH$
z%8}%RL6_y1X{VC2#YI$JVc0qnT8U#^lUY0<u{@$|7p*9Eo=R$(BVmUjzv+>%U3@gZ
zw<?Pq23OB)@|C1Iu7vYP5(}@YWt1lb=}(C6B9QeAqpLUB%3<z!E7{UuVaZxftH~SR
z^@!hR*U^<C1*#-%Iuf3Vstls*2T|Zec0MzJBAJY!l9tNFBUH%=<uyIXPaUXBQ43Wp
zORut^ukCrtY<{HUI+98G`bLf*+eUp>SKG!QWn`0?%&Uy-ftT4u$6f*3UkQ_WRiEhD
zD|Y>nWdG276++BpjW~krABwN0)f_~8E>5E(xNos4-`5e{g;}TCM)lRHwl|ZGqUNk~
z%4|fFoT^9E@;5Q#>0Pe(Smh#kKjj#sO!UdgufB(DGF^G?s>Zoa!NK)5lm6wrX*!bZ
z9IQy5jP8{)>k(w<a9v)4r3wY(0Vt^rX1l#zL-*CDrbGADrj~JW*0kFv9?qnKf37IT
z)A+&N1F8)7Ic|w95>J9xS?J+yctXTHa*7jYQ-$2}NZ1x|e|RllwZb_pCisdQ<s-SJ
zj~Xm8!6#}^l<*a&%$0<v^N8+5m#ucug=MSV(1k^2IwYST$t{t+%|#V;M0b1zzw;5?
z;fY56NaihPvp6_Q>@zsNTtxCma^77@BOFAP7a8G^3+xD@<4=Xh*2ODdNo4MVEFMYp
zb*Uv(XA)E$!Ldn-Y;YWcN0Qw~eHMM}I2OI6U%H0#F&;$Y;h*#(tDFq!UeYRGT<3|!
zzQT8VB(c#zck3d<sw*mFyOj~jCSO;{mXU4b(NlC;mAqwMFu;Sv){9JQa;&?U@sA{W
zDyQ`kMOV9?iwZ5B=l1*W>^J(eboCw1$0N#?(V(K+uK+NPgpDdVZCy-W71#RXFz{D6
zZBIEH4~<%+?jgDLBC~y=Gb6*wgDAeKw7BD1!HXQ&Ts#~}b_R`@bYRaF#XFMCz0imy
zUD)d?#3Bzie6+UZ!H!gG&lP3kc1vskB!st}_V+SCm2y_c)efM_2g!}l-uk?k)3VHI
za>N^5zmK;q?{tv9K3CNBoAbvbp({HYmNiXgwvXhLEL589CHs^_Z6<=U3cc%*(DJ2s
zJ!P7O-qpCmIa5ypdAl5D)#9LJ%8qa(cQmrUxkI!q`#We`pDSWRfH&2)jOTOJ8ReKW
zc*$*#uR2bhbfj{pYC8!@E7z_c38mXP=~@_3k0d_s%nWxV*>WOhWp%@WdL(T6Hf|{!
zjpi+qMm>mPEv1!h3DA|99h9cFWn{x>YTQ)b*`K^ueRj~8+Lo0KXQ^$uplz~xYC1|F
zpFfgpY~2!HH~gcvWm7{oYT|J_lB=n0%glye^hg-xiZRK|hDp?*m8#^dvt6`D08%)j
zY};6<GRF@)=x^pS#^DA%k{n@pP)!7K6*R<=MAPBYI^`U-gMOBwZQ(jIm!S=i!(65|
zSPvsHMZHK7bJ@^9Ni4EbJcy!m@>IiSX-ZU4A+I#}tZML7o+2!B6)?*YF;Spd%w>s#
zXE9F_nF^rA#Buj|P-O%%&!Ip(l1aH!iLC)x$^nLFopv1vN5Y2=GR4G|S3#y6N$g|Z
zKLuIL-gzaj#SC=ii1MlN9Ue(Owe#MFp33}=M4uc{Ot36({&*zp22uYA*o2}VSJGlx
zk-zUqa)xh>_}5+Rp4PEXmWsUEKu|uChvNCY{MEi_PS!99NKEN6s@pB)14&(D&L5d9
zIjbEV=5kg$O3Y<V2SUY?^YciY*Iy{zmv1tb?@~9DrsQKVlehXJN}eO3bbBEbR3!nR
zCH+i|FW1b!o)A<gu5R)Do5?-R9%0JiQK67D)Ax6`8Z*H%DoB+hinc+jn38-{peklb
z%vyn}n7#IL09H((s!ARm%k&==IEtBU;T@%XDEJ%`it30uRr0A<6Pm2xjV3gi!H{;E
z&2;o{6rsru-Y7!wR5kJlonkhODzvnOp9+A*Os4S8xDL6e(WPc-9)C2g31U@46F*nP
zpJR!deA8%jGx?@>hLgyC4y21&m-7g$iwUY#Bm2^oWaE?G${NN_F?$`>A4A4WrZ8y}
zO=(anwvQR6@J7d(RPe>KJRxDS(Q*oZsX$uH<gnhTIg`VBlg00dCW3iO>;@oT%+h+^
z#&G1XzO5Er+`;%}CTkkzTN7@p0#h+1R;d704CK`lqIm^xrQ4MyZ#7o5Ev)5+?QJW)
z)vd%0pb2u-FyL*aySicJ+e&wJizJS=(qr9V3VtjSG#m*EY^8~PBrzzb6az9fT<>@+
z^-KfdV$1TGC^!MM8dw!uOFijPD$!A#uC|t{puN_jbmv~2hK-}1t*P;&x*}`GgJ@H2
zFp;P(<$^hq^Et1nmIpICDTP_PhMGpVB@C+pfw7e~cPsOjve8NJ$5|1LBen^K)i}G`
z>gv^^6J6a}yx#aEpAbby+Sh}kCoQ{Xw~*b6H)5-)YZga<Bg&>xd_q?>TpveLX8z``
ztg41BS60oIot0J9I=XRHwT^xiN~>Mei-jlQK@hL7<a0M;D0=Q@sf1<RB68i7z@`Nu
z`Dc(b&E8f~h?&yn2yW+u!D<zKIK%2~7qDVe5atGA#b&yo8;BK~>4H9z+x_Wk8Fe_7
z<e&wv<w&w=PJYvAIt(3~>4I)J0*?fp)9@79bT!@>Wcr{ROz}2N4?+Vbe5+mG=$Wgu
zavKg*n@jyez0LJ6Stoj<?;EG=k;L6ttK*i~Wx%bNGV(NVD@T&;qTVt`&y`$<q6xFr
za2g*;Ha(c~nIl5I&8gOBOt?~NH$2!!l&y30Q@Wo<Vo{r2eO~lXgyAg!D>l12h(?=T
z9Ymweo*hJ?We%X{iem9~esG?dPUuD=(j&>fq0eShyM9X`6<g)ZHd{7|f)gU^NMbaN
zQiPaRwaSrhR<+6jZdQ#Al{nMvK9YDr<*U}6b`#>NMG6U1ki-#0U(yBLxN!PNDBZx-
zt%>K#$`V}F$Z%>(OVqgMIubS@?!pYZoF_!_;A}Un3{!<W8sV`TP#GJZ?Y3~gno=9J
zfXdi#waaO4xSEMqX@Y6BxQYC1sp0}?WC1ynd{Do=HO(7pQ6Q{FK4u%1E|nvSE-wuN
zwK!G|BDCUIY8tILR+8E`P&6jAR^tZO#!~C3#<4W4^Vq3|Cz^lEY&kTujj5(lpP;@P
zSz1py+l}+%m{J>HX-qkqT3ZZpsO=SFOf}ARx+O5|xuO{2plQ4R&PSq7hZH%WnJX#z
zoAC9B6Y_|n|2-cXz3&<hp3u=XjVRN=gguC2F{gXF0i!vRZ2W4|(bO`h&CzHX9drcQ
zc04lnh!&c3)PKoh^h=+6M~#lF!Jd$u8tIj8WUfCFIzb{K8)-*3;4wDRDg88XBsTC$
zw?LZMNVjwY9b-M+(hYQsDf85kTr1Ut4?7~KTDBf`&XLd*2g$zG);&me`KlX`91~=$
z!CG!zhIB_s_89d?{dH5DdARGQsYL(vRK$Q`OhB#%Zs{YTbmy_lQ+-5tBKy*C(S3cX
z>Ck;$s=A~40IxhDih%pY5AHXt<X7z@w=TmQ9E=IjbtGYMbs5co&#dRy)=_$0Ml*9^
zU4}Cg_E=Bc^bswp<*cCk`naX@0DX^u?~dfO`dmp&b62ydz24O<s;|o&544Oa^VZXV
z%a|Ztt)u#S+TK88tjqqs&=~8ozB_;i>$1LCye3FjW64{Wu{{c7NL!m!!_SfM=n)E1
zkgX$#4p%)G1=-Uv-AIpNy`;C`h++_Ff8WjE6d4o183WbTK+T+TwoJAW>qSj-MC`KB
zW6!ZB3w_`MZK=;e&Kv<Kkp^_;i1H_QDYUJ&<MkX#HXWO)L5zCV1Us(@9oFvFY%P7)
zjm_JdOmud5YnbSP0)DO_TM8X2FjxaSV@>w>K!r9_OXRCPqHGEs+Ki^={dbNq4z8AX
zu?D=xnzAxC05;Z^8b*gUS^1%Wt;xuT0M=R<`Ojevuhe1d7#ug7Ec9Ww#9jj|#*`tg
zjXZC*w9ZFpzb3<bp#1~~YuH5Ah8~Ra3#;To6fbe)gRk;yL$mKJ7MbrPP&R?aK4Xj@
zWW#u0lR~XwOCCW!HB{uqh_#DsvDWg;1G42v*sMUdd?dFNO0A_IyJ1M1P+KjMCO=oi
z77_6f)~X(gPHXXJPJJz1*+&wyRphjp=s3Z++RZI$t*Bufq3zn+98IilJ(P1|qPW@|
zrx5>&*Dl!Ak=*90>&K_HDhqiIcETzfnWLCh*T7M4RaP@cIuq`y#i{RkNnaW#!y}<>
zPIgsxHRNnZl8vMDs^t}Fo9h<&xB;|SO^X>ki&dG-foC!0mTNQBqM%xhWX(sC55C{=
z5#)$ai&aMROtqLP>5e1@AQemwT?4AsW;`LAMK9LZVxB0*DvKH9i&a_76U8W`Rtqf5
z5s-ec;pwo7$&4@Ll(TUZWgQwbno`N|o_4)1CbU-r_;Ms{HLKjxjDOR4S<EXI@?(N_
zwQwO>m3h2SiOQeX$lq)bQZ*ngr<`6Nd{vfEu698#r<l#45S4JR0dhGKE)I_<mU30o
zsKkn~9Y`1xzN>+Ru}sp}0toY5Nw$qbtVL}%#wd#%2clJ3<Pp62ToD@)$(c>8I1M0+
z3Fg%T$YM(F*8s9SR<=5gf-7lU<3_b2UAyKjv8~{TJ(Aq3@YNnsHiSMa@@%irKu1D5
z;YK<FE;5fO#uPQsW<{Ru73aZX8X%{?A|rh*4io}^wZys<S=b475o)Ueb}8$tQn*Wt
z9Nr5hR~Dta%9M(*;np_+v>L8|3-|Ja$f=es#SgL(oTp_{iiwq#9^v566<Pi!>9Mle
z(0D~wdg5cspcFmVjZ;gkOOZ31V0aVSs*$AFihS8tX}J-;aU{28+0%yNE3&8!<)=)F
zjoT(myw!6>(M9>Q12a=(VJBv$q=lW38D(E=c@btsx;h~<MMgKUnIfAzAu%P*=|seo
zl32-hATb4NnybB2&PQI&S!6hKW4N{~XB%;<UxH^fs2rB^Pc_IM*2Z)WGKjThIRl1S
zdrL)thFM$gZ8G*QapN`cF-w^vo2^^Qb_qy0qKV+VsZ-9D<GVSMoV5knnoQ}qC|+C0
zkRyp9%9JM8$J(-$NsYS_4A$)YStfAYg+Eu6-F140r#tS{Z<#HDd-s*Zw=FK_S48ta
zNNysLEoV2#m$l{Wh6rUT`%NQ-?Aq^r)&<BMLAJel_i0Q6G+0}%ZZDrwLam#Z9HBHg
zSzDI?WDQWu+ETuNT9)8n?WWgUyQ^y?##~!&ZZcY~oyIeHDA$%o1`6|$P&yXn+VXP)
zgE^AyTVuB6=ML)NBgl4R2YJ@k9^jq+H%c+F@@#v*qmf_RJA<k3_&TG}*AA{`DH&%2
z^s)rnYCdl%yD@Y2<<*9r<s+f=so=7)fe5VxXC1-qg$r4IM0ZwQPHhj(wv_MlNLoBN
zn~mlBkx;tBT!L>k05wNK%W>2@f*hOOQZ^b2ak*#wOano)1n6q~Yq{)f_vo3_sXILj
zOZ)ko(vlw0`<&>V9N6x3FU@g}KWASzGw;&L%+8UpJ1~RGWs8HgSuSHd-o&$9#yDu3
zm3dAZSeqq$R|9La99tZu%_*l<d7(B(K+6DYmdo}AShIxrI*DQHT^+B#dRGR8@g2Cu
z<#JgAZCnC#HQ<lS<+2Wl<a0$if<}+Aw=c40xjfb&YnIFY23fQG^;iR~SuT$?JHe4;
z+dbBUEOPdfBMC1A(3&I2#^HTT_}I<gOC2_vllAvg#<boXHkaUHjs0+W8rQL<9%9Yx
z8T!y=HiOGuuHfYcZf1GWgVBecj_kc|Av+fK-!gfz12ywpQ8tZ26l|;krCBE18!fh!
z2$$@4@gSNGaN{yLwnGsvlllfYeI)Ebl<;V5r@uOa1C;qlC_!hM{X+LC@m34#;Rz7~
zMERLq-Pj=?38g#Jw$!VbiX+Km0{N_uDBA9&+){k-Ck1xQ;-VBYm`?3}O|s`oVwN+p
z_7WDX!#KWds1{l-QCvN^TuvFsLB~2>mM-g#1^baux^tFZ>y8b4Bs{a{ly&t4m1bSz
zL#<hQt@{mrIOS{>wPr$BcMvkmS~fLUBTX%h7*JC~gEb;_buZ{bLAy?V^kp?4I_YfH
zLnob$Px6${wrXiP-yH0>ul0Q*Go9}0BZ<xz%^aj@M?}-1`UK<3?C;CUzvK_1>qSkY
z`>dqp+riZ=D{A|r{nl2yv2d4=V40ZyNG9d0v5z3zxu?RVlmZ<P&5>j)Vel>?!Fn8U
z*AjZ9a|m9`HAEEVa@s~YE>}xCO1zBJj?2^x+Hsi%6xy+t-L#%UJsuIoLuOgF0#$n;
zZ$cLD1K`b-uoi&cToFqQ?9CPBXLRv5S3>hRFs_LCs^Rneh_obX&3>2nQ8hcBHxfq_
zo!1+#mA(rs-vQKIQQ$>;c!olhoo~0JLdSRfOIMW5g~q$0{1z+O7mLiWj`Qk@n7^wa
zuOO!{G~^Z0r%;hsl3nOAJl7Jy*Y**aS{uBGK-WLW=#*(<W_BvC6M6t@u7u?RpyrCW
zuIWH(u52QR*Cmsy*F}-Rg?_v#K8RH9;Bc-iTU#;ZX>xVqWv^%=@T_#_Bp$@rI6rj)
zajztMU<_?&u;C!Oq8Sge97iJSJFe}IsH;!TJ4kF$$3cEY++%bwHCINbcD|ObPVJoC
zre5uw-1fe_ojuJ1RL6mTMf9STDAMy*a>^T*`bWf!r$yDdDENrd&Dpt2xFWP;z;vzz
zHQfQ>Tv?0{5YCnGX#=YHh>CjIvRk5G>jcq<tmMx|*35^s>{p?9`@~uK2~oTUSy;Vw
zUV}`mBZ{7zK6L;&SCpH}h2&gGw%=KcmUUt!%EszkNnH^%7oCf%kTK^YmZG`ZAG~05
zit%zSotjT?GY7)`$C1n^=bX*#psCL@J82ZJE%_<uk*fo!xgs9C=-*P07whyj!y1Rp
zE6Wb79L7=yRt_c4UcK2VPPI=2$Cc3mV?DeU8>BT?lsz!kgH3gS4e!d>iJ<-Xh=yu<
z_A@UtdZU<q-0GCfxwf-cY0tIPr9#{v5uJ)7R&SwVu0U<&GR<RF@2O6O)bBmjsiiBm
zcVfgsR`O>v1oWVn99$f=j(}H?N3Gs#6w@y1m5<Vzny)!pZ45ot=4;FWZwOJG4|@;2
zX+>R3z4=;iJ@saqZ#|W!DGsjp)SAYjt9P`f<-x0i_P80HvYYU$m$2gUQFpUgTRkAP
za!Jdsry>=izxPz6YjbewFbYKmDY`K3cwgHNM9&pvYpH&h=OMF$y!psvob^<sD=#m4
zUr}W9>ZwSVY5Ro8>B^X=(4))L$JC?CDAL2F4W_3ST}y4J8dY|h-ch3p0qDSet_VE?
z-sg(g2YM>o8wk*QYFb4C^qX`_VE{b<K2ON9DbJU!FTSVh6|TR7_qw8dSiHY0%7LWn
z6~4dsRK08H@u_*24t*W0>XDuDIBHi3HTp=kyApoTN2=YWW8X-%8`0?xGS;n5egnO$
z@PQ8e=ZJ2x=Av!Vf+IC^Mi2Cnnpq(P{lb5)fWd?JxgtD&eMFu3XAUbbSB{8b<)L7p
zl2_FLpr5?5973w(C3}CQN?x+}N2=tE7&wx6hed-(jl7D6ky?4llo+X%mre<Z^0~6?
z16o<Z1s$Bv714#k3YlAd80_!F7xWQod8Va5QY$Mi;E1A=1P1hh#+_m?KO!2JT|ZW~
zt_@?P#+{~zr^Y?-f_RigiOnB0&lTl-q{5v#9gI}CQ#_9y7Rf8i4j7Y548cu2dsp#X
zYS0<olEN9Dqtg)qsP;{<mladvW(+_doK5G@);?03&WyS1Gqvdq|7oA8OQ#I`S+WNs
z_x4$GeiLleXDU+#3mg&io1WGlmAVc{Gu5fW2abs8%;Uh!!|T*>U~+h!3eM{@Pp?xN
zf2JB%*uW9-Vr1CQ)UYVinaWhK{|=e#6=gS5ohlTd&s3)u<&@8ge(IZ^sZDuI>e89u
zr6b}Ml#HqCGnMJo@nD8Bokh)$9GX7pnacFW5JcvY+rzQd8VA{-gTTy#?9f4A<~eq3
zZNf7(up$TgTnvWypW1e~o*n8o0|lNdiC!yKpwHB~!!?jpxr!g?GgWTf1oVl%9j2kB
zz8!fGn5k|RVbEu)+hOm}Qs*knpiiEYjXUdh7{yp03NYxCSmZ0C^*kXf$e>S7$U~<E
z=&Y|O+upec4_OJpihU)yl2T18)}YT+(-~{fSBX*{-B#-0p;N$09jr)#zETG(l%TIv
z!R+cGim@bcqOVlJL=*ItN_glvu~G+*p*?S<7FOgzU!jE+cyI)~w>)F4ns4phUsj%k
zhmHmd)vKU^zVa}vxPiV>^9~5v`-(&EklDXdr4E_>D^=>KdUmSRQQuDGL6<OtzEG$`
z&ft{_b?5-Glri-^Ktw?1M^w~>nbXN}0dD;($cKmCCDP#Y=`55gX%G8KjoM}4uhgg+
zG|<=4mEAQ^9ZtKn_cGe<31m8=8G?LpYRc|<a2`z+TF_T2&n}1UO7+?G!7tQj*O_1e
zs=6{B?<|upn}5ZV<DW63edW(nX?77yc1x{!!v%UAx;`aY=$0x|F$3LFW%k%hpOD2G
z?lRmhb!M00Zq(w-w^W&ZQpEaK=s~wsp<Q;pr4H?~>kS>M=!2f;+#{pR`;*abab)c>
z*)0{S;tRT^LhY}~ZavC5rk;b4y>6*vd#A`4n%eGhqi|*M%^Uhv5eMB;zbfdUTk2Q^
z9dsKSshs<kI<_~8_sO#2E%j?gA#}^*Yp;n;=$0y1kqO;W>vmcDhSu$}3oNy61SdSm
zSRZNG;|#iz9B?Y#F4G=Dh$~7LfraK({6V)=yox~RmWnq+5W1z_ZTlTzDqeyRj^GYP
zK?vPa^C}9VTdLmn`u{C;Z<GJuQuVex6_`hfJ;hS<5{K|~OXb_-{I@**DmI~$GwF(Q
z20Vvry1%hhzY0+3mM7aLli$*(toVZNC5mZmdumq27j#d}N`S!;#7Eh58{jC>CNR|z
z#XE0PjinxKx)AWxqY6#vo@%r~XxHJ7xe}(zQ;%kRLig08O;-YbizB%rx~I>%q1Zk3
zY}2v9^Q78j{d=BNBjDgcHbcU;<f&I%|9TWJDvt!7Dzv=^03SKM+A(}&KXm|b<qy|&
zfTKm5f`>aOlq;jf^eQ(U96WVx%Oazz@-TR)+NP5Pw>nqEgVU?5@P_VrFm12rpWCRA
zF`bs}%k%H4ac>Yq_t3T(!|+^5%x;yv53|%2<&31dt#bT(s@wWH{vCZ=bpr4_t=6m*
z>#fT3@99w{;lLBJ7_Y)3y7QB4J^jbkDaK2z(*2&^<BWPZ5(Xh-f1|0Z?E0OWy2`fS
zCH?i)DAQvZ_dB(821E2+qm&J$lCDcCaHpTR%Cg_7s1*&-cPeVdL-dWJj(CWCR;<qq
zi0C`dx{8SCJ6+CIHvu~}dKD6@?@;MgCxD$QU6BzTgyKh}6TnUto*V@sV~Fev8~v;}
zhrUxkSDErV_4B>6eGt)g-52as&xAnq9SXYYwqU1%u3bloohrKOx?rb<t~wL!)X)l*
z=o<|kSJ@9D)(ZCpd*-{+eZig#Sh$d#Dm(7d<4LKr6*AFx>fS1gf2Z<QxI^El+6ZoV
z5Ya2$8SK=xl|#TzMO$?U*r{l1NoPeqCEH3(TXbQtQ`IU;qF+?=6#&WWJ2h>=KG>;e
z6(!Mks@V*a=sSJUB=C7cc1Nqwi6e<_79Bix9&$^18BTgqx+%2uD0zle_`@jZ+LCt$
zqok@;0K_P%YKt*XBN$1qB&O;}=$28WOG|B~ngwg~ge+cxA}L0pn2o0|xo{jAC0)rG
zNAX-4LtFeLR%MxLoine3D@Mr!Zpov^GfHY~1yhWY$Ja8{#gTo=bHfqQDPh1yN!45O
zK46qoy*F-R6x43%>Sk))(%(r+y<75pF-q#)($$01y``(`p?Z^PDI_e+PLXBV)PdB_
zg#*SYshyeCCuH&do0`wlacLTC`kNJVF(5+zh=dm!CDnQcUL47cat<U_wt^~-h_36f
zFiPs|k~agRq|VOZi&4<nrD!r!V;6Dyjgo3xK^UW?+Ac+%NUg2Vj8XP)o3M;KQDGMx
z5zU92`UtZ5Q0$wii~+)GD=cFa?k4xnv&6Vt)<?h*;gru9wt_AOab263i&5j>IajsP
zvAi)DP>62@Qw(5Kdz&6w>6--#W(0(4E8Jp$pxWEi)p+}R=h<PP8TQVj!!uAHTY(t^
zX7#POj1lzfS28I(b+YmP++w!e8DriX3^eZEQ&k4N!}cFnZ||);gF&3*-a{P;jd~>P
z2q318gnbLZ)RDwR=aF=3Wp5_)oA(6+%jHON8fHvzPmsvKP}&(|F^DYPim@0M8nt)R
zV;4ivXI{AxKBBB-On8*e&#T7gv{^Mir_rkM`E4{!_(6JwkAzapSy309Im=jzQStKb
zUDWW7bzao&W})X9U|`1Y8%{AW^tX#8XnYO=+tbz`oD{aFsXsVQY@zuEyh7X4W*-fY
z<94aoIKFIw@{XWWE1we+cqDX|W6-lbz4(K((noSj=U@6J0YGiXq9352HoT-~J%E1N
z3a}V}pSB__M&O^en;LD5Fh9y?0Cn0KPB8#FZG}{f3v=3vrx>7|jwBm`6>AIKH`=%*
zzWp{B(bO0RLz>y{p!<q(JfhoweYS1T|EXp|OKzWPYBHdq?U+OV_K|JPJEEZxPDT{g
z`@p-feW+z%QQL=_j{RjT<YELWYJ1lp7i*(u!;3-6Q$OH$*xppjZtv0}AMitLg-Q&3
zG@DR~L0+O$&aOBur=2|jIc=|cZY=8URnPT&kCg|<pK}sWYc72Z;OR<A{^oRExuA~V
ze()Y9`RIjd)5i_^Xe*!i==GNPQo~pHTv1j*Yh}R02-oCR#_)mra+|(fut`S(zUGKp
z)XL`uHgcQibJ0hZ9{D4=vzCd&pDT(1$inXZma^qA*S1+cHB7p#)Z(MZ32<K!-ne+7
zoms*MY(QI>xdDD?-w1~RbZ9HW;TgEiw?Z5Se)Vlr^NJ#}so|rD1ed!Hx)VFq^kibA
zYl}%88aj%~hFV^6<lf35J}&xb3vM?+7VR4*F}R@ECIdMxF}BHlHoz2Z#Yqe<KenPG
z1_}4J;vz<Oy4xw;<MI}M?uhQ!m{Af(FmEwiLBA<TVsI6-t?3NVQF11$7{t*QdTzvh
z(zdFm(Q(95JXaEnuc~#lo>jGu=2Oz~G0H9Rg$}ISopBNa5YZ9vR5-l0(vlDE)wV(<
zM(}>^xB+^Q-2N&yVvtpGuQYo}Jh_#Pe2|@T1F3t)h(fl4=2N7^07A4CDRCrs*)CVR
zWU<?sm3#!uXbW98xCY$>N(>N2d%2oM5iU<3$^c-rm#gj02&Jn@@41E08)MKvd#4KB
zw$k(+K}B~2Z>{K{3}3FH_gXnsXtpKG7hb%*a;Lb+qP=AKf-Kr=s^Q70Vofz2f81-T
zX;d5O%13~YwqSOHYx^U?H^9~Yk!0H|hB(x;F(8@La2IYccTb3-GqQz&3vHq0Mxcd`
zfb9gV(2?8@K35cPD(z(`fVPs8#{gs-k4;~int=dzucn5sc3VyJu$kYMt%QGQD?j;>
z#DKyqov6Q+$oV6=qe)l!0RFNwefa<)vlAfq86MD}y`)708MFmz8{mTWN+<aM`ty-c
zx<<p?>IvF!%4~*YbSpdg08w-#>=i*)8V|~*`z>X&9LVOTbU)}RD;q@74ot`sk~_L7
zD?9K+d&<ZLEVQRnx*vj&a3g7kjwqiII_gOBA@i29*XT^8G(VE)>-#B_F?`RZmQb2A
zE$A64bIO38sLUxw%>iO)E35gK=*=k;8W_=@GNUhwXipi@bLAk@iUvZo=TzgUR;4;0
z0Eo6wbR!@{dx|4y02tbHs4a_8r47wgZzV$?&=GGSb*FsSm+WKUjeE*KCS(21RObT}
z(4Oi39%Q|Lj%Xsdo$cy9igR|&9Ex*xHI3qYlbsLN{T6I)e7=i4Wn}Z+?1_=hm$hg5
zypQA#FkRk9u&Bb<zfh7>M)X2S&iuO9>4V(bW1#|PQAbdLBq<*ta<>q01GLYcpx~bo
zV4ppUI)VZm>C+xSefHQIKPpg3%EuyFX$ulJ*oOB=(;Hy(9$RgF&VIwy4rjmN?-)7!
z2_H8W%1)We2Y{X}SlhVT=#+0yo-4T1J>;}TsT~QOL$@h0`2cXfFMw?<VzBp+$9kdL
z#!~0dZA0$r6}oN6VZCBIcy{J59}8_K=-QFQh!&;$bq_hKFGT2+)5gW7*vff6fCKFz
zM>S+Yd&t~|ENBm1PYs|yd&uC%oH~+x5c+S(ZH-y>kx)8|UFppSff74$XoHa0J!Fy-
zaj}Q|)r4g{d&o);6ww|s(g6|en*@D;AKC)44bVgT8hH<r7@y2^iyGM~$3^8%9~jVE
zu(n}9S@w`cP9lmUi4j_y7nK?P2%@X9w+)RsUI(?IGKc)r#({C9P5wEL>>+!c^U79o
z^kF@hsSI*(LPwHKqcw-z(t#4%T^2eZq34Kb8BeH^s1JyUHlVlxJZN`W=@%iiyXb-j
zXT9BJq~B)K8t3r11&|vYFn7lsCo9YD{yre~D<w@I;C-%y*+*q|d8#dsn%#Kt)tFt5
zYQR6c%TW#XXA2cK!2awmSo`3hzPs%8ILq%YbDcCeyW^)OQO;Hl^=Cv}-cE?!uzR*7
z7y1CGvxSKpcr$iSFLk&(K5uWR8|XeIIv@B=w(xEP9M6&Dg9(T{qIj~G`*&sl4A1Uz
zQF~z#$SlA9oZa6OxpQXhX>sEe+Fc&%2n5|-COEVlJF#w`O`S|oTdB>DBo<4S?j*`f
zjpJ;0d8w0$WM|Uy5fQdqsIw7axJN=M=1gvC@>}g*-tnR5y4=)0ZYf(u&vjYgpm07C
zO0mH-8QkHJ+)eg2PRrf&H4^B&mA-rs3;pawiVa`)?^y!{*JLZ>s6CSG89J_s!)M^{
z-OVZ8p6Tm@fM>V#N#jG_P4=~u(0n%;*uZjjlaYOqIa?Xd2e_OqjM)H#v)jt;9SF{D
zvZw=qa|GECCqU&zA3$(65VI#l7PYb|XHc@J9lhAnpeD9|D-ZfJZgRXWB-tQ+-fr?r
zJDRY`D-9-RH`&vh+^xH%MI9iWtyJiP`;QISY;Zwx$~4U_%8}$=%vH+~(e^%7WO8#=
zvomA*0G_j(OzuGEJXe%IS=7mfE8~%c&6Uz_`nY#!%cdyx0d?0AWmBljhLO!()mDo1
zv3r!55^lA3lVcm~&2DmRlZA3OIkw4Exf_1%famO{tg8cf&Q5sR0GzX%T-#uCb}MRn
zFrILrJt12BC?698(mnxrW>;C+ft}fcp^XjTX;*o?LC)-&X7{}h-O6r0xG~*THZ`}Z
zN0JV2?p}{5pNnRz>G9t2sUAU&8_h<7^Cv_x1{vo&bX%3v8&1Dn(-epHZz~1*Gwv<*
zzG$-%n3tWI%m;{<U1dK5c=<>u-HENTmnZk}yQYhKa%sN>1e@IK@0u3$yabG=jBjO<
zR`(;~&oPVX;Xaa>#5B2QLDSXzbZ3c3s9lE|#ur)#rRaUvQ=??jXehaxntT?Zo?E!B
zSvn22tPl#WHgy06SDQM3lB@DlPv9mybCX|5^egS+Sw2dxRyB;0t2G-2`Lb(O)2O{#
z)inN3<tv|of!V@*O|UJ`t|gz0bF&sb_#Ob2(0qdG*#dXXvTg~>dx90(Wvl<F!m_g!
zG-26l1w{yo>zR?Y`;^s6>=k9J_b9`%HEkUBimPc-*KI+#=7qeR@*4S*yYfny#S^&8
zF0Q6gjzwPT3D{*9SKFZ-OP-}CSeIQ)Ejxp>q;sD1eJi#3WPDqAuX*QWm!-#``bwI?
z&jcZNM3bLHkJApGAnkTyyC$%fl5Xo+f&cE3e(RaQmXdDkBe`$Cq}zJJ3A9UC)U(F#
zK@!gdzm%EnhEwJUvf+BiH`FR8K&3H%CdkDtVAxEAO6lqvTCAkYdVap-UAk(d7Apz$
zKB8EdJv)cWQd066yTcZ0YbLIxG;M(iY$;7`jhNh~mQY%yWlMvpMaw={6hmtKAcj-b
z^1P)S9H+Tb)drXNTWGGC0G3QqekC#e`k({BQp#7ISY9Q~)Cs%KM|4Z}oA0e&g;nWF
zPd>pryKq;t676_I*=i`WBguBJGCKmcML6c2r^c7&+Y@avfy#J7vnEKHBgmG|NA26y
zY<S4n9TElOf@V!1F1}6u+H@n$=h+HfN%Q$g?#|#lJ=8}OeZfOLuW{l#&FNEKcjD5X
zo>(-V9EBl@{-%R^VjB5gYW!MHzNeawCE;P>oTUXi#`jd~m2pZ*1CDV4wq}b`Hr(<h
zjvP^A1k%7^c3w&RqDR+;`r7H5=&L8e7%m{zBtyiJu*r}@;z;7T<NiDQNxGjS%FYhf
zU{}kbAYD+ciOui3so^`a$9Gf1gO}fEc=GC-8lNn}rnV<<zGYO+Bxi^3s>T<eP1S=I
zUB(!m_bm1)L)h|MN%W?ue@1@_{WE%#mhS}W;=ANyFaLn=^ioftF78{M3zg-*H8Y{s
zTv^L!<Xw5Lh`oiQ?vZ5U@!`4eY&^cqBgoe8$Lp@_Pm}m8S8nr3G8q>l>`0=AQnx@}
zjwJVoeusP{bP&J6k<dZ>3P%zhgr>(6zx7<vU3_l$2j|!6x1OZ?aZkVXBqfmhQmaS5
zd2j+h2x7wX+<YX_`E^U76WphoX)%(iR)`*QB{iR*X595f69MTin;B4y3xzd<f#-1_
z>Px3D>64!Ls6G-(w=XiHadEk4K*huj=HAuJU|PF6H<;C~hU2N(C~VGtbC^$%G%m!}
z1WDtb<~TqaciH2Cqj7JEZks@7T&d3|&>0tuYvNvXmvJ3Az^+6OvRllqqXY%gI+Eyb
z)nkqR7L5SXO7}Fsd+0!y^^GUiUFsTdt-I{+jv90kYW`2Z{SVJswB=Lv^D}GnQ}?5^
ziuvfDv(W$e-~aZ%{Z@Y~pa0^2|CfJzfQETct^M|Izd@DmOR2g^d*RAiS@H9D&&1+`
z8S<7dvd;K4Jab1>Yrh!^qQ-Y;;?ONOQ-Ju1o|}2IL=MdO1sTDti{2LE29sN)LFhv&
z3d3Sp0ueWW!7o#A=b({1mPgbw!bj+>-uD-8&dXqt><kLH&G3&m;Mg;|_H`bVlB{n<
z_ed2qqg;`9^SFpIp+s!HsDyjRn3s6E`@oyfbvK(HpXy&nCCBtltD$396kx`&ipKnW
z8soEiM&GTj&p)ixPy2tih)(zZZV|=Yd@mv-UyCTZ^0kW6?EYRwRAU)YVj;cM&)+NQ
z%*yvl`u#$JRQqco!IS(hq;!?Dn(ktXFY<daCH3srVw!)yl(5>KTuZT(l0xQtDaE7y
zZYjl5{a#AxC&xYV9Vf$55*hxxloEWSrIax_T1&!NXelK$?_Ej1TScju`)d}2W{zd_
zIq!Ye(P#D4b#|f8Kjx^_)?Zsj@KpMxcy#o!P^Mm^aHj{BOE=HGnr+%GmriWsR}fRf
zPVYwH?7_m7I`K1}43DsMx}_67m^|Im0}majUtFm-ddr-C9)uDWK_hC?EsgwuF1xrH
z0XMtY83X?OTuJmPywffk#*3;x#aKs>*t_@_;kiEowhceOPfvN|Qn-S6KI+%faKOrN
zi;djTy>V|DkBc!RbQ_eqCrcxV0bCr7ZcJ-xc#jx37pWp<n~PKt%g&)x4Cua#PZ4mx
zzl@4xNN^!SA?$UrDZ=UNmLH|x6QreA+da@f4z)H$s*76NIbjM7imB_CKJ74u-2~Sr
zV!|O^BteA>2fE8GT>ZCWKX6fDa~ANWyp0?f9JnW$4P5+*n-k<h>BfP>#he(CC!ZmT
zI+5rUU#Yvu<>A75lI+7*a<A+tVDdt0?F$=#+#xQK?A;hv+VeY%I2Xio2k^i}!N_6H
zlU<Qi1}=6*QW^N=R@|Qxqv#TM9vDTJh$8U>b+Ws=ED_GQet8n(1nfzYcpw6?(!`Uv
zIVY|(9XLn3;G7(@U(L8LZ-TD`eZQ(R3h_?AejRT$KWHMaeCdPU94J?Q)OZ?v@loT8
z@Rc8R_$pk~i<^vkN5WF%tSHJvLfCx8$$WdPr8LF1^HKx>+s<1-qikm><wqS3o-4S2
z=j^xgtImu`N5arIQ<-1&jqh_&B9fNLrD!*2#RCgFeX6A}dHEF|NsDJh8%Gc$NrS%P
zRP$Bxil*Xub5R;r(pOzcSkV!C=`%mzBM6H~QOy;vphI3*!)@qut9#*D^vO3|@jd$7
zY6l0U&-{!lUQC~^w)-u`%vUmqIsAu}_|{YAL#{-@9#PBR+(k594Ttucre?$a<4J~i
z$;IMxn0YoolBmREIWSJsW6z(LI-bYFnJ4c`An}ppGf`4AKl4g@w<DpQP*YP3C`WR?
z<vG=V4vjNSrz45(Pc@D@n@T5DuQT4~RNI^@lQps8()XF4{E@^`h`*C!*5^>e77Jmh
zU3B6c8Z@3&aVplxgm49guAv#{P|Ik>IVhb9UC(s7p2zoE02cbp^Lr(5-lvX!MAv^L
zly2W;(-WcZQ?B$%w!<qb`J-3}O--X8XM4{Sw?wP8<kHAfYrGkqS}#$7Pj1sHga<C#
z#2PsuIifsBqO0G(iJn$U(Wi{Ctd$Z+=azlSgM6*%KoKZbt__bQ8$k<RM#UNzk3JM{
zS-G6_v2!f3@%q?mIb5(~t6jXSD&2?q$UC#jg{q7F@JMdMd3vl6bNDb-3WfK0(jV5F
z8r5|uKIOZHMxM8h<gWi=dhYs^R;r51HMA$GVTH`Z#c5bc|LWp2tni{7$$9Tjh;ILv
zTE<P9RE0-y7s+^?9d^4Pw_3HPw^O8qH7@V3fB~ZGM&4W1imro^umThCAuG9(qrk^d
z-%xm>Bdla7@R7){BZ=<zgn1m%yn<{Sr8hcl<1roSHb0X4y^eGf)K+qodDuLnJIeH$
z*M@_1gnF*zK|W=k+v+Vvj7lZfvWum#f)MeMHgyF>;!qS;a3)T)(@_|pQGDPBs=<}y
zqpGK<M9~vgNSAyRHJv(f6t#^`9C<}nTfZeXPn-b`f#DUz8Z1&74W-z(nno*jY59Qu
zc+YFH+E9UT96nca-)ff*CndLcsc=#f97+1%<}GFCQ!k42@Q7}Qlk>0wt8y_O9!YdJ
zE8MQilU~7UxwsB1crNc!;Bw=b8b&8ZAmI~|crY6abY)+zA2O!9K%W)XGZ*Ufsg0u|
zu+Iw8%?10cpy9mhlLs>AJrC9OqUz2}Nzp^#=Ac6>9B-$b&%KJVPdydI*yp<#&}x0C
z5=t$BpS6GVl|Y@9i~>i(noK6WBVu-MK7mtaZac@m1b!YtOq@R5&cUyXwXAkjU2keU
zR9(*itRsj8*7CuqwyvA%+D|c0%oS2Y?^3YgE%HQyR<Nhu^|AJJ6ZJ~*_M+$s9Ok<8
zDO2G>f>vlDy^FW3LLKQnKh{2Of#uc*JuQ^(su47_207((McFLMux&LP%CK#{3Y1~X
ztL)19cs?SEcNqyzTJHk$=4u7q*z_Gk@99l$tlHNtW*g|nCN14jjx9^kaecBqu$?aO
zXyvnWVMlA{K2g}wihI<B9<3cr%|}G>jAdzT91&Y8ZLs4mBx!|L)!TXp7kiNlOIl;Q
z^0w42`n4@eF~0PP)x^eold~E4ybC2-FTmb~5k2MT?f803bT_$%>)>?Q@?2a)8MrW^
z6@B4NY8-vyKti7o-32RL=#j)*?z%s@1?Fks%LEcy2L`DN6I!pz^d=P!Kd`r!PegIP
zuJjR_v%OaLKvA~Ds~kymRW>%^B;FDOUI{tzrdzQZVJS!Q)`}G-yBV|QBcXKrq7OgF
z{huph-NNqgP1ZDVH{N7S4{j61S6D|p7Vm!@I5aO+VI`Eut3LgKPONE3V+kHXwi@vg
zE}FuMLFqM1cd=Dj(gW31_0>Y^eI)7`%1d`M6^?(evaVqe_oN%FVP$(2H%Y}5_o{Ch
zbKS*1cqGwZncxErS1s=)j_5r3y^KM{Ro(I7@)QAKCGO0tjPQ}jnktnXv1=~!!3qhy
zC#zs3Wq^xRu#z$0Na9nx;dm~pz)HZLiz%>9^k9`;KGB0!iCpVM55gQ+<96{B=`1|^
zUiCdg#_u8*tdp!;US*ea#ypa2JW42b4yg{SVC4wwK`ZzmikGiXnzOK1X?CI~y~-+|
z=*u8?dJsj2Q;~m;_FiR$bM!xw>>T>AVujDthBa@9DsiV?tDYI_P>P+{Rj;zbC$7+!
zMX*ksp&}8igvEN5b|(vfS6SjXTfF84WyK-mq7kg~qa(#2crFd^7)2mh3H|jV1)pKY
zF5bUN0uC?I*JSB%vHl&&{JxFEw{;}>VUrHTi&MI*u;`=4W9B74>hP&~k$z5Ee=qu|
ziOxQfY&iflMf!Piq%1mC&y77&@*BpJ=tbY~bv1g?7mPR3ixe^*OE1b7QWr|D<h9e0
z#67J{<`sXZD>ziW=!0Fv19-tLT`&E<3;ub^(G|W{{J5vAHkjP;b`8B(^t}dOfa}J)
zLMh<FkXCpIyu|nURHzEPNa3!2OMIJT0P@n+3dci1NRK4E=tW0lNcoQ>9~6o(;h<L#
zos*rNgbiNw5tB;Ei#}rVEgebB)x7`CcF}?*bB0td6ujsQUTDIiFBk-f7oDS5oDc!+
zKOu=lS7?{>VbSNiP?jZab0{^u=<7WfG|z9g^#Mc7aU|Jt*qOGsMr^mlwh@^Dt|Siy
zD?Sz5=__CHf!Wp<zwRe!TOT}JBes<>utG>;TQ)igUv2BC4YP^uJZfL+lT*wQa(!s}
z{lz3~Q^V0G+cMj^m$R*tc3j-qws(ke7_pu1^A!_f0<G5IhxrIjfvZK^a*SJvsn^#|
zQaIbPzsVf;k=#;^PUHpG5kw!vC3Zy73mN1Vr^_SBr&eC*H#UgLFubO=<?kjdvI%oq
z@8z!vj#0TTwk_YbHRkknfLmu$rQfZ`c(h$uXFS?3tTUVruC_v!WLti58@I&wMowxI
zFttYF>MO~1P_wq18X7FnG~(kL-nP8rT+|!5)Ed|Lx19Q)t9}zOwZb`NyQ%HT>quWX
z=ny0L?0ngzn>6M8t&x$^wzdPX4JKS_HKRXl2WGLnidqhRX@ZFy$$f7EomSYsOrX<h
zXjgMC#=vx#vH@4v_)W=xE6@-V=JZI;0A9>#wfMC;H(wUdGuNjLvdBE+o@?ZsH^EDv
z3U0-OFRcJqEb*lk@QNw9Zv`P}O72?&MfhA1%N{;B6RNacwm5Trz!1tE2`yFT^S#=F
zn9f`tFR&~osA&x_iwSC4L9-ZHe4i_cF=Plw^?pk6FD6^JPw?p<Nz0$y`%)9aw8F4&
z7hziCmnMX1<zePsof^z**L52xS9AHue9%u_QF%NzTa8V~F2b}riHgj1QU>H=%I{mj
zxtP-X*1)-#>v{^H%V&6vV!Szd$8LIN^QvbqI-Ypb>UK-e!Bw!xrUbqfy2+1(Qgl;a
zD4dm+z|!jB>og%tE8rLtva|w@F=hL$pkqwQerv#Eo-d$Xy`PNT<i9nbErN4acs@<p
zdMn6AvrXxCOSyV0*}zTUuF9TaCcR5qaTA5$kwmwI@v3*{F+sd4dy`p~?xGaRs{)g;
zU=X}33ZRUcG;cs<Oh~T^5XLUltAc_tlQV4JPU$lS2V+X%TL~mEW$>+cOE-bTD!~Y5
zf-+Vj7VI(+Rw5cq$i50attC3F27#?9Z*Sdj%$NXU6}XIvhp@tgYvLh1k{F=u`Tfy%
zp^TzuD7?gtRe&`n;8;adn}`T2y4=u>Pl(P}CG=PYVPnb#T%pl7Wdg3)A_hyx*{U`Q
zPFa5I$9gek^Q~AnCeT^M0<t6{tQ#k#iI1=XoH1}`HE=T~;8`UM$V|GISRpg<@>h79
zO>Be}ZfCPp$Cv!s1U{?4Zw&BR-CWU_;AeHmpR-x?qiJg(7Rr<dxI%SpFU?>DQDe&9
zTQ8)>ggUF(-=@sH6&u}vowdUKn2A@gh3RiXnl(-bCZt&dRAYjgwV)HXw46iY)QXnS
zpyCy5ke6HH%^F7_6X5J=_k?5uoHb5Wwo<`2j$WoTzpbDPMIqP<L~N$?ysh+G$||95
zOi;51s>Tv)*1*)*lBPbQnBJ-Gp+<#BYtZG}g`~BD3SH?BKN7k&Rb}21F!_T16F{s1
zp|M1WwSdRilI7fh#~e|<)y4D=J$NzwT@PNo=nmangT>y2Bx{h^+e%})k<s8t^2ORM
zWy{1BT7t<Mz7rFgtP#d*LW8vnZZUzu8sHXN^<80{%NAI1d_yLDSc7fe1Q2V`&07M*
zo-2wMTl5xDf2*kVIG3%W4x<5An9eOjtB-)jD+*9Bvj)h;1T$+F<YF^F;D$r)NM_*S
z(QX2jwead$V#*qz785|M5ut7X#99SeYco}GgI?YeAl7dF5)(YERrHzgVU0W}HZ47b
z4bP@2e{RG3X+n&(K(^R4HO+|)5ZQAjcaaH2)<D15TxuPiCTv-&<CgfGYo5;%Gu8me
zn3Ci+oXsZ8Sc9hCgc)mfMt21eJCf+{)CkaE2@z`*{UwOlkwkan@9T7Is14Ma@L>(a
zj0qpsaMGLbVJ#f_@gQPq!r5=ahc)g4?Bc^3*9A7aT1J^oaT7H#H6|EYyO<gih^#?e
zVZx9#Zb~e3=ss5z{Y~|IB)4<zt5$Tbsk@sFHcBj0zGv_=CWgRv;WKZPQRB2HLckV4
z7@I|}kJ~2`C1B%*%90ZB2rMeGP@ucFWCZ+-uc5s}33w!TE|n#8y#-iY%d$3%ySp<u
z1b26LcXxM};7)KScyNNdL$DAWg1ftWuz%S5>~qfj@BP+1v*@ap>aMDpXQ;QkRtx*@
zbR5tX3U%&1yR7liB+^>Y3T9;p4kLETtX`l~NGxyA8?kd>=*;}Iupkq(azL{`Om=up
z**2^L5eF>dY2r(!d^>8n_>(}=$E*y;QQxYq0!Jk5wuUh|tK^lgdYR(TlfJw+MlI0?
zl`%9xy$B`;+`rsBmZ=Quj2~}q%<i_ohi<pZrh5r15P4pKqk86IL7;jTu0d$+%gIm|
z>pSv|*tor=fU&25d6378{K{sg)nVL$rene`^AQps``P0Ocz>r1?t|j$O){#5d`OAS
z9SBGC|AgLWL^fIwWmp?j#Ego-QOkx!K80L(v&+_nZ-j?m4m@V1g%MJ92HchJ8K<ZV
z3iv`M%$^iFBf;{G4TQ4<q4liL_Ouw;uGd!XHVDx#mg2J!xPfUQie0bn7rRzPc#tnq
zg0;fw7Td^nN)?%p;P@Z}=s`v&VgPM47!Iqus?xj9<f%GOF}!P}D11rYqpJyQLPGQU
zhz0JcRxLqw%+3%T0FL?8vx+<C80|2!d>Al%A^Z^H+C=dA0hC3afj+}Nuc@<4YB2mS
z&-2CYyplpegF3bM{FJp?Axo3J(d;bSS+ypyjcsWdL5Qd0s73tif~68$0|FFKOx~0S
z!gVklL&l_tc7%>yQS7xrIjnV19GC8t^Su(?#<HhcC;srq8LTV%Iig{3MjqtTYi@b$
zy{z+l0=B{g)*>0~X<-yUz6-Mfi%k<FSCrHCgvSo5Xlovt-(dCTL8NqoNAafcR83Za
z|GEu7Zo9HFBXe|1q2CzcQ!7z)+B1dV{SHx#-1hxRoE<@VTm&l4-Zzftq>jG&9kPBO
zm^uKhmYwpx4{H$*efJc`<Ox&eA(m6P6<-P;NK2j5ViOyOaJ@^_o2yyeJP03-nNiyX
zRWS<>Eelb=vCId~YmKUui87;bII*W8gxZhk{){U?gap`HF~RfS0NO_tVd|lphXw=}
z!6NPL%eNjE5ipj96@rO3AjoWmpKVFW?aG{O|1|flXvt14%=WHm?d%{@$HJn`3(aHz
zj1kFWDQu1KnS`}xhY^y7HWBTxB}_#k*{#y$Vd}!C&F!VmR#8u;__$0zmD+<3I)ePb
zV+ueg`i{s~Ari{2#BR8Cm2cC%olS*zb>Z(iX)<4A-#1MF8ynW<2cZrBI`6g^&ic+>
zn9&j0!DVhhmi+{!X!Mo3h4Kzzsio=D9wbR?Q$=%)zpct*LbR@I7^2OP&hqUf>R<ww
zts+vUJf80mNrSYpYgXN-yKG6K%KA-iPVLnDFuIM3Y~%F0wPTHUQyT5Ls^6$<L@}(J
zQVtQ7al7b*THHy))6+J8e&h~a%~VucyX7B3;V<G<@}#&rHDyJ=-sHQ-EHPP*M{7Xq
zn5yd#9)FhQ_`z|LPs8&A3*t?qc$P|X^b;b{@DrI4)&4*Lxn3Y=Cs>+XxP5MqqCCD%
z{V(b~E9q&hW{4H7R4iyaQ}^TY>6P;HZ{#OR@6$={R+doyrrQj5k9yx_ZVVq|)sH@J
za%xOJD}wvGlCyRHq8aQdG%T;cmZ|TSgQ6ZuZeff*c<_#y3tS|CCF~WnP%mKz;LC3R
zn9N1^xlh(E2(zboQ&I_9%Z&!5pn+UDb5OarK=w?q?1%1Z+`spbs1&`F{MJ2PsxgS~
z7lnWBWtJUMT34?QyO-V=YCo>~lOw9Aww^tTnv)rcqnCv=vNdU?KHtPX@pUk|lGUnZ
z8;^BaKC&L`+?ZBn-YbFFO5Tb2tI8OM-c(v(eVP$2$**P5QSyw_PQi%)&SX1TJ-I|I
z1wPs7r*sfUT3OY=%3ffaPpq?v)1Td8rw~5!Wp!jxQ91Q^SQXXeZXJnJKOrb>jdVgO
zY>UKM^35Wu!SyxW#5mk?GFWs9jYFwyIng$v)!c`Ubw^B@r(ZPCR+ct9IBQMm8Jy*Q
z)(-K<V-AXNdcjmvuk&z9NG45+&!!H!*5sn6eaGegCT~=qhJs@rVh<aHn)RImOv0!h
z3npV2C=oUYRBj#(giJ`Abt2*y)(RS$YQ+RKG&&iZ_Kw12C?#*wqgjzV;$XT~okik}
z6)em=NCO>cA08Wj%xN{E)9A8GlCx+#0~%d>vqKbOs-B~4Z|xBK>GDjk-fxED0Q+za
zU6Jr6p`Uc1{dl+cv_Zy*F3%KJTJSE<O&hLFxT3$YC*1FsXY%yCYGO`oK<%`3D`xoS
zm(gY_we1WfMKnc#Y4f}A4%6Ke4NBc|pW0i0;<h$7(yZRgTGj3Y6ZN2j^r4}A=cbvN
zAN<Vj1S`8(gEbXKv8xHbb}8No?qbo^S`7udfc97!lnq23b0U7NLE2cHy;OgknSsTJ
zD$Aru&;)01XnxTT%F@>TGcS6_PmDT<lb5Z(ew41z4L#~I>erB1b4{iUb^w)TL19n{
zsb*nsEtAh8`2!kOZC~oz0IqBdt*8<-l^czS&yl3m==#m=R=#m;`HvMc<{G_af5C2A
zsXrq54Cb!u1s-4UBf*+L7+(*VuXZ&f;^HV+@m%nwd0VzBsLj)@OlM%MAQ7yg)8!%~
zXd51&W>2fWc9F3KVwODvI(<}7{KxX%AB@)*eGj^+^u5O%lc`C}-O#f`fB#7A`uc2F
zn!r@meOj=_dOq}Cb|G3>sqav;FD|%6-(&Y&#3AQiQg_1+;$|1G(@Co&4$KmVSUS<#
zS2C6ogMtvhZ@GAX>usT1z`ftrP0QCqeEfCIX24k&G`eR6_wwtyWZ1(XQ%^onJuN{S
zadW>xPlEn%V(%yb?7gkCyj(b<!EL!}`B_T73u412vFDGBfkzuoqMn+OdRmNfzBtw?
zg`B2oi=F|^AYMxBsDm&05{vG&3wOBy?>$;!W!*PMl6JhqwDijF!f*`+_q|Y^dyz5%
z979$-w<0zH6ns2>>9n__A&35Cl%IW|%KYl=zfH&)a(Shi`)&2@KI?%J8`QosP(<(t
zcQDCs@MSZP-j0Vjd#4>$LhrbcCtnw-D2!W(dHaXmd1V&c&yGq?YWv?3YV4U`P3K+b
zNXwqB05{L#yvFTnaWIYm?iW;|7vo}^zqnc<3uKr-NfQgR@m<5XiA~>6h3Jm0PPyW<
za$dLPM9osIMY(Hn%GyyOnb64E_3WS5zhv{4rI_>QMK%0+-&n@H)l0*ldws?1%GO3$
zY^ktYz={I&fk9?rnt=ZT6qxnpNA^rMoMhjuldn1QY$QmH92{F}E<G$CwEO9?r=ZT`
zO<AnhlUIbUL%6M1piado3o5a8e1Sp8EMy@yd&<!7f+k>&Jvqk*k@nWB`ti*X6mucj
zS4yeEvq<`;43xM*`cCKqChvaH0CCTo{j`S&EoH(K&jnWZYy*n59j_Vz(cFzaG>@2U
z&MIhm^Zt%y;G>Maxoi}B<3U?oX^hUBF+HdAdb8PKKyQ!Ql-5qa1p;<Ilr%2}jlBR_
zN%){7qG|gjEJG`!N{f*~cvZC4fT(an(G2`z@8_i$($yZ!C7;viY2+nCud9<7@Q~_-
zdiYzM(wA~g(DO)o5$A^!2=Ag2|LmH{)_6ewZF8&BazTGez663_2HB6Ksl=|mpA`kH
zUlrO4;KKruQL#0_SN0+oTl+{qi{XMT5-T^I;T((S6>Kf<pt|28GRw-$KQ@^DPJxVL
zN_k9S@%j}PXb;S;gSz&j%pc2cwp&J;x6nI_vau#)$6fdbuO5Bm4aRC?b1IyUj+~b?
zZaRPZmyL;&5)rO_h8KiR+Vd{iX8S5tUf{McjuZoO=4j*yQpftTx_GxVys_Yk?a3$Q
zF2|R3o<eUq9$Qwu(fGoV{h~0L8QY&;u4c77)&&|?dSBKH^*dMIk~egQeCH&gVw`XO
zMCQL*oT_{d#KmEuuzA5WP_DXn+IF0#@#xOa+Rgt-fQoqNBg{TInfL?M2<R*pF$!1v
zzQvG)oa^zCj^GnQAB)8MW7)d-Rf6-b-^z<O9wmaMYdnRgAC9?gIj<o{wd9lO<>K!6
zr~bsLMCG0WThbMLY8J^*^KV`($Rpb&GrcL?EE$_#;uz|4D4zR~TxoHhMSduA8u`P2
z3|2@pc+^>~Dm21;dl|x**GU(}1B!ycT*a8&r>aR*q0jJ|sv3PYqS`5Q+rhr$Au%a_
zw`AkHDhXx_NJY>u=g(S$*NDK=VOuu8Eu2QWt|Yl0Ml~K3bxI(sXui5&<FRJzN=gqp
zbus&$cM8*D6z;kUw6v#XR~M$=U2vJfhW48*D`{=(jfL3e$gDUk*d<$)mj(=9n=UIs
zB{3=;({`oQjm5yi$fmNcn#X;*4^y&%3^?w7Bp6u6lb9zNnj&c@CJHUx36@bVJFfpt
z(8+as5V@;aV=vcaD=I6vkzx`!V%<Z0<Ql60?jT8x*GpHFcMnA*dX*v+nMwR_Jjjv}
z(UJ>LGCbs51+6R7xX^GYgGI|m4RFc*pG;a`xaq;VaFu=49ym<mX~aWNfal<$evP9l
z`wHJ@;8BQh^tbCI`c9!?agdqiEmm8IoiG;>ThZ%ulQ7J=o2e;w678bk9I_%Smr?d<
z6<nUxnpdM4zd{=BM_O6TR14MFp&je~qEv!!hM{arLCwR=xPw5hDIi~(>{Lg6k-7=T
z<scBhjd=lc-M$HYn9aUK(0Eg?_aQraW1}KM{>;dArIl!ih>#T_b%Z^3@oCoVM~z5Z
z7P>#?*j)A@?=B2G6PRI0DKCn*m9Y~ki`C2ifawqcH7?yneNYBpBZpT|edNo&*vc=-
zZVCw9tJ`tVX7FL0eF%-K>z2a|{oxL~@>8TUnC#Z*$XZ<`3ur~o=CUy)BF9BoLobL^
zNh2Q`>Qk&aR~0oa*KOCsnb;tISF;R$q%o|gjqC*Z`yOso-n7fUsHJu=BZaXz8Zrw^
zX4o7U!Y`C9;)i2u?~zm65BT+8iBU^(z?*4RP9ah07LfX*R><GJqBol!4pP|-Q-7Th
zj9^1;!ldztIYvabr_atutdL+2<>YJp!KI{|4mt+Ae83S1N%EBwteUJprf?h*=0p+#
zK6>7ObnF^HAV~A73nl8!V*(n96|oVFQYBQ26?#}Z+XfJ!#rX~i%G3MSL>-8Au@MYH
zIEhISIn|D6Bpf*J4gwFx=7!sGucsV*Io4W>C3bLF4{}JbtOQZeO4@IbP~b^UrHzt<
z`92qXNT9<Ac1X}3Whw0C;f)e}I967JC1x4+xe36-JE1`bMR%9d4Jw-Ry@;M={@YpD
z^xG;kgz$2kDU3s<zJEACg7*bMIOV>0juT|I`b-2R2~&4InAd7y8)a2^0Z+;PmCqH5
zOHgv4IqEE$%U0OVlY*#aQ(-0I*0}WSTFD5Mzwnr-Z+*DISIAF1w`ntOb*~r)!p3qe
zn?AUJ@3;;WN2604f0crE^E)CbE9t~CfPuAIXXG;S=$^1i-h&$}VQrsehQY)wuGM5>
zStxTE_J9F;0N}x!gBbEN7N<dTq{4BT89}7Qc9;ofoguG(lVLHBs886)gBu>oXmJl4
zXZ4!p$0=%Gbu|ez8|@HKN`oe=n0flM5lTAh>BT2pD7}>s<=*d14ID6I3=uy7aL*nX
zh8&T-lox#<V6+v$4z<N@sKIAPf;g*Sv~j0csj1Ds7x^@@Izd7rZBLrYePAf5E&;n)
zoxO{kcBs+jUgJBJVzmUf6!;KEUs(cS>|7`jNNb~9?7#&JTncODF>F0(PJzQRv1%{%
zdY_>x^MWik>Sl=P&0-6iA9JC7XGRB=A!bo2vO{x<MT&?*8**|9`EJw@ZW?{^bCCme
zY1c8sP3~)@^<owMAjBmh?z2dO#;(rS0c%%W;cSj40uHhxw&I*Yaus|}tYj|xKQ0*>
zgMU0lTqvsA0iqiz&sJc8n7#9qEyEH+De@*R#RDAxQN`VuP{+MU8~d!iNe)78xqbWk
z129(Dy^^Y7@|3TgiOF$}YkIY?ZY`ynCTMH8pB5<l^y^&g(bnWUkjcS#NOSSzgX>2!
znWBCj+y}`AR+%g<7eV7s+tnncLVC_nZeP$(Zj-;Qn@?Jc%EI>F65v9IE>_~Sa71;r
zaG-F(GAQrV)Xx;H-Jx%v0)M4KjD4CvOUpNPVIMobb2sza!!FR=vb9I`!R?vHO3*B@
zt}2t#9AP4jnezQHyG(ldNuY{;`+S@RS@O<ZECUnBj`&V~`>D2y9;3W7p#|^9cfC-9
zb)8!A!>%SIIzWxc%5wW0XB!q)fo3|k9jcFG8zfeuW(%s_*6G7fty%6~7fia+@)oEV
zr!k>sT@{9OUHo8iuI?E8Hq~!^O5T{*pigP>#*m6|ZmxYAp!Ez4*>tvdHco=It;*ed
z#$~R>m1cKj!Ho`#i(pb4E=+W!^$xU)Ke$~+m`+zQPKJW3Mv%5coiW8W<O%zrogMWB
z!o?%!5g~O$4;hI2NyR)LagdbZ=<66EjwS|;QHwgV5n=#qduCd#r2|FolHqwq{tUrx
z3$Xp9O0<F1^nU#WxEuZssk|`<Ip;dWC}yXT`2<IfK-I6o?rOm3%koq|i`5ZHEx06h
zMPq(iPFh@PVj}NtIq?Ow37_lW18GtDx%(E|2`b^HlNf*_UXgVkzB(?_!?HONZF&&-
zZx4EK>7p|o=%fxqqL;Mq?S<w5*vcHCJh3^3{K?=sIG+xAFcc4kGjaqEV=fkTV$=Xu
zWms%ox~O1%Ro=Fdv#g~Nd548n1qT=31p`Xk^h&2z-N3D(-wK7+3%?c4ojV*TwOzih
zG(9VV)C6zqpsDcgJEJN2`XW65lSU6AR{dDhK~uxL@rWseuq-i@R3Ws^I?iV$Ru)qF
zC`o5mb@FRQIj|{!M>a&~+Db!vBnvVh^*Sg9n9PK%{o>!OQZML+=tRxR<ebM(Y@>;c
z=WMUV*N<91?02}u@&XU$OzP=$zF4IcMD0TDTS-ABB+P9rXmAz%1G6~zTwZeiX<=qR
z7JrB1H_Pj)eXaF2yOy-($W(ezo|<4ve}i-0>Y?GSM6JUmqk*J`Ykn9)esTvSA~mt+
zj%FAq5g+FpFOo@?tRVAy=8tA>-jicNlK0G<M(%~Hp-BYC0YClD%W(SE!bcynecHGh
z&Z17<dR&wOPs-S^%jn&cSeP28?sXA;Hkw_I&NUUO1V_1;<-n`h4a#*W&d;r_Td`#|
z9r){qunTL5!+T%J3L#ZrPgsnvqddCyLT~5QlM|{>u-9RZ+XJ>@^VhTXp_K`*{JNae
z*Rts3G4KukfL*FR8bI^Yx!d*&Bg?KWJ5BZ1JJ{<<)+$APQ$wT#f8@dH{XLFYld)MI
zgFn$>l&NJP^dz%3;)K%5()5YoZ60-V5YlXy^>;P6R#JfnVPHx*Cg{R3%aOop(rb1L
zghBzmPML(chfL!HQ<ffayD?J)k3D+?i)aPn=NUNV-t6|uEszVj316|UNd%u-!p17O
zbZ*eItSbIXYVWxps4aq%>hQzqa>w;yJFZl-W~04ESy0BkJmV`!o;JtLVZ?=+z^agg
z)Pw4<knL1&*{fdoq7-bTV9ifO)!042v}M~-5kmph2Xk}B?Fw}oAgk5mr#4Q6v>o3K
zYE{}goNFFP+LY*6+i0EqRH<sry*_)CI#_Vw7>s<yT|k{XSt#P3M&ApD>Y>F<Sh(<*
zi4$eUH5eJiNAh2gwQ-s1a7he3HuBsfr5QQ7c4rVLbhh(Wk(1~dolUfr_ANL~tK9=z
z(&OQ|?5L<s3|`bzja_B(s)y!0%{lJV7wCr2pSEqtB&FryC@S|Qj?=fTrkR5zZcAyM
zr~_9RyuIr`mO&*TEUF&3OVBqc6Q1+WA-&__;VN2~79RJvdvgu55l8ep4v)-hg)UzK
zbm*nE+EvCnFhtlF1JVVd12!|aVEP=%t3AuhQ|a6>2T)r{yfJrq3R%}F=fHRDmH4O0
z!YP)L@a(@?tj<X5V=oo19n+6XsdhUYWgeo9L?bDxGuXotAXQ-uPhI>0tpvGro9q|<
zxr~P6sj%UZSwbP98|VjqAtt<<#1c1P!kKS(ToR!fU8%<>d?^#+PF{>(AgfZ~L&*0%
zVprtqR?$wZ#b4&PPWPS}*9JY8q7s5AXDF-u;K|)}Ny(2p9=>Xt{d{~7m1!SB5|e7R
zUIR&t%xra^z;D5K?Vtn)DH{1?N%e*lpKeNT!3Ymh)<uT7i<`PX-9X&ByLvcEv2P|L
zh()yUi3_bJahX@pKU|8c^b;`|;KZ5+WoH#}@ky0&d6mWx7?78rL_Xev`lvo4#HlH4
zv0ABkSG#yI7rA74&>Kk=Gq`d+DszWTMk=MKKH8xV;l~@U28PWlRe+)qtq2c!%OWNy
zqk60*bd$Ib_dDmOBE+4nD}b&+uF<%=_d6%uCuA>x+LfwN>p`zr%K}k3<;!TZB<{S+
z=-FQS!eaw68n?l66NQ3G@E)(yenQP(D(O6{7pgyMgYi?_r?>JYinot=9_6^*@DB1>
zi%qt87Uj6-Wt)W9vn-h$;eMc?F+gw4zGBn{k{0SA0jPo}_E6k-JiK(p2Ald;&^`$~
zcMyn97Bzd8!*n2(%r=RG3cE`wd0Q!Pho%~F@1bY}@1~G>#qA6l{6e*ADzS}Is_dmL
z)_V9Q>I)Go$i0&qvg!}rWF)%?3YbUf4KAvs2y)3r+rk_xAqdrEB6fi>6t?|E;wR2G
zG*JGiUN|ecMQf!H<#vV?H_Kp30y=Ch>+lBQSaErGh}j;@S5I;3To~|UWn6^YoJW^{
zi_3uq3JEED$Xk3`j`@Y4vlxQcSW)6Ktr=z<0DhBJmg$q&#1uH09J1&Q+!Ntqr4TZZ
zBAU$OfZ!-<jgK8X(OPE`cF79jT0j$5TcR6mjRf{PO{pOVt;GbO%r8crV~r*26XXK=
zDK4ZrrLL%n0n{8OuusWHN{J_)_V(<HmYD7j4gwDadUn)OsfHjM5^6|ideH{{T5|;X
z2N=H~=q<LmJWf$7Jdk0O+~AQE<|2ZQAtjqn(1|pnw!K@-=Amw;3pm1ay;DlHOwds@
zWJLr3JRPd&{*(f9FpLs}^ol5|O*P0V1WitCo-p>UP_2oC4S3-URykQVn6J3EK0(Qi
zkQtr;3VZ2%Kf6?PI+#WhDlHHzQ3j^Y8Qkl@t**(b>;So#FJI5~hdW0CZ{S&JMZ0Uz
zH+V$j7{z*lgV_eU<@J?O#Chk!t#(kD(;qx9T8y+nDyV1xHsA|cAgk$}QdFG%2nmYK
z2n-p6RX)YlAZI6)j4na?f0W5=l-slQwJcPf{aT7%)V{2AP*_@Fwk!;Tdt){%KqoAu
z--7t&3HuU`6}hzy2AP!q?DS7y#0*~$7M2O$>WVw;H2%_mvPoWS3q?lsnMLv$D}{ae
z1j$TEN@=fo^GgkUpCn18mrI;tsGGc|pF~jvht(!-afAV`Q9gWpjCD%kIJcJs?EI>F
z;SEv{`$0ZNaZ>%WR0i1#a2HZEiKqRvw##bKNpCKWOPn2SRMBZ1En#`lslkIlHCYA8
z@LGbJf(K)`ay0z`0NoxIV~fM(54v+7h75&?Cra2%Q_mp(R}57LS+u4@&>Rqv5|amQ
zE$Xc79Rtr#n9pe`VX*^d!v_KF9&L+&A}g1-MWG@tmpJ&{5w+6^ddYT5%6kfLF4qn>
zAL^lO>>z6K3|Ewp8L2GK%iv}RDGx8<c$PN-ix{qhQvNd!s?M@<h|{<)pJ;-!$xdXV
zi4R)M(}rfO)o~XIzvQVwc?|D0sX^V-mseZ$$M8Bn6%9SX$|r0Oaa)OcmpLO1DP`Sv
zz&O-WsC_wvrZLIJZlE5FaXoFDg_w5LNQZ)(`-+kwze)V$<S!yr1mlckqm(sKiXufi
z7~VmUNU37S1+7ml9e#6dQPk>$RIL;ZdmxV49v8U`8btboyOWZJD7yw4A{zW)6RQ|k
z0eBRWQw5`yK1wxw8xn!73VKgkW=DAT2j5HPt{nZ<2Ekhen-SxqsP&I^bqaslEf$BY
zxO5>R8Ru2MK6D!qgU6L-F+^?cN^t7OGnL=$!+X1I!fYaaMKoWF$nG@p06tGoU!#Kp
zOTJM%MXUVgG+h0>4rZkkeT^klv;2Aehb2mMbI~oBgrj+~+oMMEDVO15-1?7`eu`hZ
zk%-$$>$^jS-9t1c+YCl!UQW6uWnlD>2`v+iNA?Pd>jVr(7zg89&Fg3!U#bq|#RRJ_
z^mmzwwn_J@Zs?{WRLHrZeW@Mk;Q+{cRkZ8|&S}^4iC8~Hy>F!8R|`7bi`4t_uAL4$
ze~9djhkSyNlDb+aP{yc#>w4t%9#u?RWLhWfaa1n<Jq9&Q<@hurbmJ|hVEwLRsTE~Q
zq#Ihj6KW}2hOI>FkWH4iou)*OQ;a-K1E!W*vPO#`v3{LIp``x8skl=7C&t1WZl{%Q
z#PG)CqA00>7mU0Zc;6=5tCD&|3RjG-*yqBKgPLCp##3z@M`@yW7IRB2gHqQ${i6B<
zLqUiXy_Oe82<T6_T*_)-9?;;_;!3Wy9`&{lF{+EF@WnU#_f(C+waIeT-H?{M0|+Z<
zlJqvYwblN<saElh*o~A*=Ly4npiaNOcLP7pncAP>kEun==Uxd6OVKKMGk9tIGk3;#
z2N_+b?CWW>N<!?D3**FXnIblExt0|7RFEOe#wKD;oDV^0wzUG86SiX^tsu+wjzQ0b
zquD(m>k&(n$|afY>%Y30mP(pv2l^y$r;3Y$-HY+u(U%!yxoJjyhN?*P!pgTbTNq-G
zo=MElft=wgwX&Rs+Yw`039fG(^$49)EY{s9^r75Mx0l9UDHxgD_zm{O7i|<wEK{xi
z4kU+ikQQFas-BaE;mZlw0!Rp@FhBf&>iBvQ0nWlz0b%}ZQHG^%eQBYWB`BE6rv;xz
zXPG$=l<KQy8$gX0hrg#J1(o9T5SUtqovbNTsBP#32r^}#ahr_W7Yb)P_zL}Hq)>EA
zIw4G1<)K0ngaa(ZPX54Fj^a)f1;4sLOzCbd!0rVWh+)g2o2%552q$a}XrVzfNiwKg
z1T<C`DGWKTfuu_G$i;FJtG?7lG*UKt53NvCTm2mJea*-z9E6YzY6lpjW%L5(!Q7g8
zt1`HwXY_0nh2<NYAVt0&YdKAdEhYW!H;!>v731Y9onDUX8Zf$a4_U_As<qo9D6Fqy
z-wdMJtx<h_Wv3{Os@!pd4{dZq_o~6?b<+23QcV$B%DA+J*X3*%u_3%!tE83B-gT1k
zK=f@@Le7Xa&ML*8DYP>yI22)L@qRWYK}&(&>SWd<y{)Cnf~zXExHuajO;zc!v;;Z?
z*<yC(I}|VCf%=U7qF8em0p??RsP1-=aUOq81=*(+%Fr&fgXChRrBYkaeEd~zkcWJi
zsv3R8+~XqS`m~eAr3d<J3@w5d<uZWcRmXWJ>-^WXE#wT;_ab~+B>8}-dQ78hM&@QP
zw|Dv=UE7!nMG|?!E;#DrIjTSTExq;2T~9I8D<bW@?YlGjUTsMeb*+_RO`HZeHM|3$
z3gc*ubV3zNXw==)qUi=9SClaARi_8oH&`jJCE<wi1B<nSa4iVp`7x<40!V%{j<CA!
zIG&a2!ySH=b3W;gRg+TBb@jFxU^T3hh2N}zIr{d3BsbdLmkNd0ZIJnb6wZR60a5{{
zei~_4FtlCu<!{ucO)!BB4PvKoC>B6Kf~d#vsj-}LLS^}`H_n9ypdX0efDzAdF4Eo9
zJB_e9p(E4LO%W&KcW3LZCDTEanrT5}w1(;V>O+FD#*nA1M&8cFd({N9H|V3iX$#54
zxS%q02XbQ0+^)CCV1<?5uq`#k&BZo9GvOYy4YO!5T!z>bB|JM&4IhjwUFO;<(TZWs
z5RKQ6qRTJjtBnA_26WL)H~lzW9{kfV6t9ZNotJi9CP@*#jFu9|6MTmGleP)tGiQRY
z4UNTWT8eyD^gdJc*9A$@Ifgl`pH=8|44d`3(bz2%cP>`dc)>RGsI`Rz0kToQ`=N;D
zVpaGl<$v@?YggV(k)iNf(Ioox#<pRAFxcgy?IW+|%PM<?<jyobhSYaT(@rIn&wZ<=
zWef|4M=`+?&2~fuQJ&rg!^kW)a(;g~YSDaee1Dz|@IOwCt@I34R`tutQWbnXpN(J0
zg*_`cP<($^esvTujKALL5&W+BO5Wkm*2GWjd75&S_wMw17cbaIyeztOKwJ~>dVce;
zcHk-adgZzCzH-ph^LBsJBzR+r{PIneUvj1D+3Us9|4(Vp^X*2wPsiP#jrYg?Ibp1$
zSGh4kzvE8Ob!Ju1i|*;o<gC4_zKz$Np7+Uzy!T23eXG%ZLgZLvDF@d!_xHkL&i=A#
z74pZY$O2xdDKE#vo|k?{v$6}&JN|?;PvUq%3*RsH?}a(xh)t(#*-U-|Q}SkGhF*~V
zH=hSQ172P)1nraWu*f%p1@6lP-e3YcQ+7r<EcH9TjqEo1Cy&HK0Urz4_13Ap3VWoi
zdcch44jUfaV?}<ix#q{$@(Om!ddVo*M68E=RypLqro?o0PgXffn37U#SffQO&UokG
z_ouT)qtDH-f;n$|#ir^UldqE9fX&OWiUHw-CjVtRqIRcf;%P6!sArpmEqkKdP4Ro%
z!>cHDPI`3o>TNeET3ol98r;kSrZAs>d713Z1+9tglOGnpLG3O$vgyS%Fn83s;SCeY
z)Jt)M4D(HO#MiYA!xQC8_&JouEp2&Wjtvdb+7?T8@c>`l@e|)b#h^W8fzW={r(YGn
z1>X?Rh{Go*G6Q4}Hm3tLl4IWO*;|it=kPq2FDjgQ%WNiJw^nSVRC}pvQ<^s!pANl#
zA2rkf^Yk0$Lgp<G=k<zU<XRqJgk9So{4l5peVv(9{4r+<X$J1EyH~g4r@;m7=osKn
zu!CpYIwHt1!~3wFzHz76v#p=Ug`!+q;sDuwvZ&W2?X97^`_fef6+G6ke7aGHs5fTG
zp2)hP0nVSbGkFc2*Q-#PYv>KuV=`#zux@#f^8La7U{k_R<K(8;)36Ha{iY#{VCJF%
zG5fj#53)xIk)-koBKJr{;1)uGG_B@4N6$96RiN18>1wUx5rGJ*KqU<aa9II=MtHlA
zVmvpQUbN*)cN{CX=)@F-s1%5O!JbLaHTQdKmZAAL>5^_ei9=gQ?o_U5+TO2`JH~Hx
zu#V#Y@H$++lNH_Jld$KObVsgx)KBIiA_8-dt)C~y-au?TT+|5EC#?PSc{VwYIkZQ1
z3{~*2`h)Q~zmyl<(O*?j@V1?FbNJ->4@TEndC>K{&K=DkAw|!!^}~&s*{h&j9xoWi
zec-tF7}x;@wldd2{^yl;uV4SP3Ct*F2XyK@1N&KSR;<g;VNXN*_^giJk5*1e3Os;0
zTxgo+6+Sqg=aB#(X1Cn)ers8!soK-^hWt>@rwV88VCL%PVs32zQF1h~fnx_S0Y3f$
z004Gw4i?sb_^kip^YMLDF^YS+NvgUTyO{(2W_<9BnSca<QB)Yf3}7@h2Hph(J{tdh
zXOwVsaQm;;7W7Q?OaKnxuqyv*1Z?-ONwEA|7=TgD+sPcjsAOzu4xj)q|0P_>*u@+;
z7V|%S8RgB*tc^t+y#TsE787vd+yG`4CMJOXU(H2<f`RQ_0c`*7AnD@h?(|=i`CG_e
z+>b86i%}IQ+Qrzx)#*c+srNr@X@HxHyZJwqD6o~7xreo>xr(I72lHQRRWWyUbayc|
zcLjXtO$F{hOXCF6ANu{!l$^PPrJEIi>)+Fou(oqEcL6X;*a0;wW^U?e_Lro8HDm^G
zvT<{KjP);*d1aqz`Fdf9H`g4i&hfAD^Uv~U!jfl_qbHHT)`W(FfTo~|<;DO&(N}AQ
zO~g{*VXjfM4P*g<;g(aEcocx(dggi*qLbrmG*Jyt*!59NY)oLfk9q?PPRdkYA25cF
z2iNzmjo0oKc6I%lYMz=uIjW-6Bw}PSFbTay<>;jWk1z9r=q6PpVt9hq_uoOh=>*af
z$|OX}s59RVf8+97D3T0B*w;TyQ|+hvof~|Ozte<eW>oYyGpXAm^b1coJgBQVFgs;x
zrY&CdCtjgRE}h7FHY;YvS>deJe;H_$Mu+8|j!*Eo$4f3%$mY#S{l!}Qiq#B0o9Acd
zW4KqNW&glT;>VIG6;)<L(Fs?sE@k&~#2;{t{JRfZ=8GADqt&UxSol!*&=@uC2ppxh
zG{qOT$<Wq)+CmZM&+p^OE<6QA83rj>GP2HyCm>6t%rY6?TXMUzV`b!qDs>nOF5)^m
zVRXrgFvdGi+$l=byZ9i+lwnUMVWH}hg{RO-Qtl1LUQN7=?<fjLcMMj1>tDpo*eup+
zM{oovd-B28E}%G*;e08y`KU7Nw~&I7&>5#B*NgkJD(`DEMQtM3a#lo7Uj+tCh*3H0
zp+{7rh7#__>~vWgG@BWp`Wr06dc9Y480$=mXmjOYC>pc|Ke6wa_D6HtrQxb%&~a$c
zs>7bWsDTSk%W?PFmGoDBy9w9yy&)3O8J}<Q!Coy~X*`lx${emKKwvQJp0@J$7{?eM
zw@stsBt<!K$jTA-Gf4VfU}~cP#^JMndzi5*tRWDbk>-^C!XVEk&K6liMevpHt!miN
z_hD^8q9<c`@(lH4)xr5}v?tmTJgEIV6S~=sJ7EU(Ddne2QBSrZ6_2%KlBlxFqUeu_
zrrfzR^&Vc(m+sd4pLdA5c^v!;EY{E?Ec{E_M58Gx4Uy(ayGR~1Rm=76v~SH0uR#^t
z`^bWkU)A=$iFI*>wB=fu9t$`0o0L#vjt<KGq05oXE16ub@0R^y3a^doJgZ(16fLSk
zzdcW<Pd0E?zdB&Ar4X{nm|k#{H9O;OA6QUHIsN4FSS2fH(~eMD@=J)oVSiqJ1&s}(
zj*Qe~4XcvgvBM$e`O&#jzj_>HIXu;Nuh3~)03$h|I3rH?Nh2p<jsYH#%1xhgm88;0
z%=QdnR*J*rOTqH%vXp5jkHObMdQL3d6U2Cl1ehFN_w;iI$<Ik6a_b5=#|D<)Y3Flf
zRIH*gj6ieGrBp+7qI0+9*m>G`+Q2m!lSEyM<kCibZTatVC)OpZX%}*=*F;6w$in~w
zB7Ec#DG8>5JW}{}2=0jP5#RY(vf|Q)eo%8n$0rYe+95!$K(;ZxtD6AR4DwA;7m+O*
zSvIX6UKOAB8`fLU^TgFIXP8ar9{s|infVOq{;hjj`>4WA^GJQ7tGesl=7j&GaL$Hb
zMGCGh#-oJW%H)-1T*JD#(SJAGa$b;`l#y5ZmS2KOiLKr<x0*mDYgmHAF_21XclCDA
zl?U0qd^V`yxs`&Jr6G{!K8E#^axHn(G1kOyI`wb&vI`gyg*r$PEJCU{=1AAP3~LqA
zNK4+jIp>`b;hJAPjKwi%Hwv`43m3yV#w~7b$7~+ZWnPDyt5y!!hZ?o^XL)Qq>&}<8
z?(>ssQmq<}X6>3;WPQ`<rwxo&mMG10nk81m4UKy&cvA^=v~FyBxis1NvHVs`hmMb?
z5~1f5e0mQ>T??=;3U1Y0@8nFWSBIg?`)?DJg@&fV%0Y<4K4a#050yjyp*GE8PG?}_
zm___$pi``de}Rh~t3d|to-Z@<X^{9=9%jt&QSQxlEtg+zH%Ts^BJe3Av^H&v*Bn)t
zqD96kjTyqD%FtEvWg(0x$rvnjyGg~dX3XD62J%omGZ53iGJXqnV6!k+(f$6^LxF@Q
z;?5NbZf<pVtd9~+YD3CgPDAmj1W%>3az(uf#qLGAImztaeYB}P%{KCr{DGIH?m+}>
zkg=UWos`8-+7q}sH?8vu_4rR&Uq;stn7_tzT5MIrkPPEbELt@OsQtdDj>4L8z}Om%
zfVX_MbBb|*?njI8Sh~J05dDnA7<0TI@k&&AKAwiB(O6@Kc7Qsz9FdV4|16Hmc!Yl)
zBGW6rx5r@HBoXgpn-hL~c}zwD-8N|%qUo@*?zI}vsYAr}<#pE2@yY3ins(({Vg(SL
zx=VnaG?RE<`FTGxwq|Y~$?vtiWuxF?x__oREo!BuN1I~&o#e%4r0Aq}rNkI&rWVEe
zGKq_YKSjh(jo$tHX16A_;BJxRGV%3q9?j<+zoh;HKtDyiZ-O9L(Qx832UC}wLBAUr
z*m=S2+tut&|JB8?Vf?|XbilIV@x=-8a0fMR970nJN37hp*&^$1YiFA+gp@2s8nCx6
zKPlJVa6>nE8L<>N-9^2f?}A)=zx$Kd1N2r=O09fuO4Z6!J*vz2c9ST-1l*{_6Fu{|
z7j%_Nd^;4nn!b{Mez0%w&RX(`%IoRJw!2M;weJQD<sdQ(%-%zed;SU5)iuq;BO#+v
z5jlpO7TNj%DI<OYxg0TpNjo6zEJ9a$^9Z9%TOBzmMo%bWYE3|>LP3PKGT?EAQdNj-
zx{N!0Wt`%edMd8-QshYug~YvfTyWn#cfQ;z&pfb$ySh%pYjP1I8C_rRAog-?{=3He
zT4z6~FjO3N3qpunJo_7Cp()-~&S8_%NVz~GXY2KKyF24b+g_VM&7`2Hj_%}GK-Xk}
zsEWkeLEeIK8WD9abzJlXGhvQaCw_T>na&9XSD23?MP9@oT!oS1cxgGOvZTUTX*oHZ
z{3F<?F-aL~+?%vNzm|#X7YmH4nt14iXVG^su7$Gui@7=pp^BF*3k$ATY>4x8NijDJ
zSbMtm+hX;rYfvUqq_n3B!i!XNaI%gUUfMU75Mv8t)(4j~&noZco_X#-VDmktXJ>8|
zlyTP)3`-9iLmLNfg?v<GY|1q%(s^VN<720i$ZhM96qtG;9hgX<Oh}Mk=nUk?r7rT`
zVs68ZVrCYKB4%q!TO?t!gg@I`{>IOdLNA-7rP{#tGuwonIGRRRWcZHP=If`u)Q|s%
zc*FZfaEREqaCdirqLO$CfBE@kIDmR-^3R2=?C2;wqP&Z{Pl4TN(C#j$s|%b2GBKuG
zshwW^*<2{cyK)FeM%<#gaW?i@0$t8!Z1vnH?NjH+ruE;7=fZ4tYaqb_b;9py!V-Sm
z0-3i$CTiTl@E8(n&h0C54J8g6bsHCz=-AV5)sZnTdN-;Ilet|;m01A{43WrIR9Pmo
zPI#uPG>KX_CrVlU+bo)N+WSV#6XY?j9KC%MAlJ6)`za$xMbSsiB!%x!R1f{<PP_<f
z^0DA{^wl>qDbf{WIx;)faRw@i>;24H?eWNNUs8!uEo5CERjeTyJ?#=Wcm>k^SjzNL
zcK{MwcvdpLQad?&3NniG$qy;6DRKw=I3x%*F(}!{qNrcTh}HKmk0#V>qXntbY4;{%
z7C$+vBlS9_pgV~?c|HoY!5P+8zQ{gN`c1x5deUSEwM!&Ulc!QD(>~pH%y9hD*#>C%
zEhN1%2rj5lj$7l-_(}WJ6#IUyR#KqD-78AEO^{swNt(OQ4qXbzgJ04lJs^;Y+F0g%
z^3#X>OKfY>EK|36J6lEZAAMdS!urzU^sfCCt+D=OsG@%1dg(%#ZNZ^6lKx#1foSZj
zqZgj^@~W-f7F%2Miw!(`;F%tuiUgu495ZL?Ts$Kb5K|CPeOOnx81>`dk%k^jrK6op
zojSw$KO#fX6jqY({uHD~Q(wA(S6q5%{Z#n&M`0yVgeu34R8$Jo`^y*!Z4{b3Z*p8C
z>unL)(d)!>taD?ifOuZG`S04#obthTZnh)M3uB<#Qfj-At_KP&a+`hovPv7-UAm#x
z({+(_Er9iLu~T_b$C=p2!bTPLIyMx{dt77pu2W>_d8(RJ&1a7y$>(n{UZyXE;3dSJ
zQ5D$^c@aGu)W4fiT0q0%T8+uz!FKk3s*@(!d5VhKIR6+Jhzi;!mw+QH&3f%mEu_Ef
zaBulpmzccO7x8B68Tl|c2U}XQ+r@e}t{UNS&Rgre5_d4%`LsJW3z?^U;EE#0*S-JE
zF}Tlkt>M$JfF|dK>?78LQnyuNn3uZ!%r1^R%(8FBKTGrM;ERU_hJ<|up~A^sD#oy@
z5G58n(h_UM<m3ypdU9Z0I>+-FCoQfER`f)4I~N}3bx{NG+78yNUYK`x45w{+aQo!(
ze&LM{T{-`nJ+&6#b@2Z31183}jxO%mGI8lzwT^Yi;we30CWE3*c029SGkMJ!tAa67
zB5OAJw*Bi{0}e*!6wA@sKB`yLNbX}px@>^6$N4PclV-W+lqmD|P%gjk{#4WF5(hk<
zQj^|Z*0qM}x3>e{(&3mMu@@cg<2KT5Q&lN{Y6=-jiSp#oZ+o?ZKBc%GY3^DlhJ<b&
zO0UeY%KlO^U*HR$$Q;wj1i-$v^i(qMR*|_k8dOC1Xbhj2bz0ApONAXiIPmh5cOiCD
zw0?HCi@{E+FD$OWTxqH4m77ETD%t5ezt*yUrAUpvAc#r7jYlZHBViZb9bxEm^)nIM
zkcV!(QvQg#8`V%yi@N)5)N*_DCnQprJ48#+cad%l@kbd-Tr(r;MWQyD)P7j~{@f<m
zN>xv@X3rA0>t~f02TaFQuO>IDLGxvWsrzLP(H495nfjm?B+B6CWNBe4(-=XM>JdVf
zsWY*)+(5V_jjE+K*YPZU-oXh9Tj`TL#^|P)g)<aR$8`+O%JA>{?PjlkC}bC8s6M4L
z)~xEace?21TTJ6$^t=xhW(h?k?;X?_@EiIkDP%X9jnIu1A#MdOzW?HaO_tc^1+6(0
z(laBmE;c<B<4J!@s!mpr!3HA)&kPa>(oE)QY+im(Phk2Sh_&??th=MkmHWK&s3?f>
z&?-cGgw>9y`l!JZbwv0FDQ@(ATedgpTbMXHu|zR~DVNCddrTLf;QV)8$DLs!Ozzk6
zVN9Bw_bF_5NqsU0x;v@0AkPHg)5nKJU8U&z8e-NRke5U}jVmEKER7VkDo93usxG>I
znI{=@8|>EK<>8KDO;6@o?1v$gsIN;;xX~l!v?5xHx7}4?93Rx>FeY2_zXz!_&uj3R
zi5WM$`yM%7v~-C^JnU&a5r&=w{n?YWycl~#&IPAC(2ncZxjBOi>aj6$8*pR4UQb*~
z@+THz>#G@SvjR3l9}r)KD<738YrMFHZ>hQB$4Ilqy9C}u8Em0;-wqOLc&-Vx;k;)=
zAR_F_A&vyYZ0B|!Qq3sIUI^wQ6L?ICRpNd5321f-Xa%vQ7p_vqsl1D1Bp#~CcNm%n
zJf=+>l?@bs?9#muSoB7?;mTTcETO2ZQ-V^H?zMUpzsBl`9FSaiWI5I_j2nx)AwLCU
z(jf0FQ`yBiO}@^6|5S$Mj`ohTBUSu-#6m49b2jazQiEWM`^aCNPbX9jn+e5j1~<Q-
z{JALHEeuX2j#m6J)%WV+a+LlQeYY)JfcCTG@s>f7g3Ka&3OkY93OJFP*@RGGk!<hx
zv|!PgO3`mO;1?L=?q}DE<ALQ66(eOfrUv=VP3~#}K2^as=QZK^-?AW+1)s|M6x%&;
z1wIKXt+5=g>sBItYR7&a+BKbXFy_2RZs%mNaMT$OdBoRIBg|mquAR}#T(vBIlFF+l
z4-T9OU6zN%9%Nj7?WTx|i$u)h7rfp-dl*N~l5B<h4L=}oWp5}ZV_p#{*^9y{XoYw7
zsdeuCfeMPgQLJ4o+MD+}sxjIx^1?nN-8856+b+Y{=cVF#N*oC!SLCH(yb%O%h|H0$
zU8WPck}G6sM1yq21{oKfUlfizE%!RQOqxav!=1<T1`j5=aZje?2-c0$YIxIWxP|1B
zXTKt?uUW~#v}M5SRYIS9AsYS0ett!t3`IYgK!i#CmQb@E+RFU3<TcMXv;*fSS<Z-=
zm?VPHPxxlG48`an&dOA*Fr5IDsok(1$gO9(R&CIYwoP47PKXyxly2ufL)uLrlx_oW
z<aeFkCb-86FubpujPjSofsB88=Rhyp0w?P?f9)~9$Uy21MWqk-7Avwo7E?a5feWBs
z)&<6BUs^Kysexic_#Fnl>wz4^_XfZ`f|Lf-f=sX@>>pqW^&4?LmvZ@Q^yY1E#)GY6
zU*-l1!j#nnvbw{*d<kra@ZyA5fahu(+opPTBE^e?=c3$v09(hpObgtA^-}G1ge1Up
z66-aFM@ofyA^~lJj=$6ag+|7>4w2m4B=y+j6!y<&`V9vya>^;Z$ha8`SB84o9%uvF
zgH>CDW8m6X=^OGgXR_Ea-2VV&91m?ETxe(=yar}~RV&-8fUE|)c$E}$@iRDG@6v=h
z)LEt#tQmf>d2XZycJVlr{;TO@n#rP`_4PQjlJyUGJU&Jv)v!KJ*fJ&~GXKUpFplq@
zSBTcN>yRf|MrT=MepP|&dtrX#s9Ft?se;(MdtpjMCX<j`+Mt!1?mLx`-;bea6US2@
zgqGlP(!GttkVflFy_r)Ai)2D-$AS%Ewb}=^Wg+S6jOqf#!LZ<9n%-Rcz}{p*;jwyI
z2blyXhYz5)tU+%e#@zb|sK(|uX+RsYj4aUkmLOQOjM@XO!QSM1(WNh218L?#1k4fm
zD2=YcyfE-7z=%+l=!}vABOv8Y!Nuj7`e4Jrh|rh}goL|?;IjaRA<*AUA49a66neE*
zy-z`Y-t^(vTr;0-fiiv}!Wxu>$0_cA1(SFi+a-g184E=P3*Y(a1lk{-<)?*#5X<?f
zgdUE=q}BTwlc@~s9Fs}u_!l%sUm%&&q!SG6A>-zG2j7bW<Lcbx_{FtQPdC&BwvD@}
zA^0DdpO{k}>FEy+!3O;D>!a}eu5RnIp#+3J<U-A$+H3B)6!{%UnYcWYYyi;+2YvPR
z@zCl|ZX>}HIl-N-%x*FdmkPpC4?;RN38ib`<-&(Jzr7_nA>5@<6X^0o@RJfI$&n$V
zN$OzH62d}FA~}2G(Qe@*ZG#s<Q9@#IK+j?d2xTgA0<B)Cd7%8jI>8Ddyqtn11H(FX
zz<c#T&P|+PnX;!>Q8ovbCak6)ttiXD2)M>cgsy`15D=hobpnxVu^|e3MvAM2<N;t-
z^z;VzbZ0LCTO{u*5HF)tZ#|$X@mXB|JFfi^Wc??u&Bny?Po$aqe}`k4KSIcV#iSYk
zuXyZ#hhO!RMjb+!P{beJqP0t6A|t@1DMHnX@v%OaH4=l|Cy-*A;?{3o@a{yZl*4EA
zKdx6MM(nQgaXRRccq2DhJBJy&acr^}h6o>CvGAns8A&#*cW<xA<!HiYuGnik+pIEG
zRs`>cAf>b0)%w=E#v{XlB()eZe>n&1sBxvOx<7tJRyfp<Qr8a|4B9r}d0&=?k!HKV
zmp#~NKO4C(eO%=eA?jhp9T~&I-oQo3>Bz5`X$-f)u?d@a;~hmdIfA}fgH+#3E3%dm
zSLcb53;RR;dDoxhHJBSyL7Oa_m6(`Jl|%qGFEU2d?9=bb;yhN_{X|yTt)wR=u@aHb
z)9K1J;x*i=x8lDa3NJE&{4R;kaLY7Yw#j@7N!PeEzwsxX&a5t-{n8)UUL7>uGV4#D
zCHL{bs;J&@oEbY4r?*}=t{N;g{ro|*$xD#`x6S^t#J`Nj%F6za&6qy||Nq3$|Bl>$
zU<+dAuBI;5PHv7aAA$J4;06U_dmwfoFQ=ofElw+DZey(Bt_lq4|GQqo*xuUC8$kVc
z72u<e=I=^7V@qJ{p5@;yMgB$?=$V;Vm;m%_94r84PHt8p%D~F<FO)&r&DhS`RM^4N
z&K$t>S3hA_(+`+}n}zEy@?(A<G(8J&DIYTwHFlCRx3;tbA{oG8{$i=RncHgsxc=_{
zK}h{We5?@Yj^-?Y4+P=A5rq#3<$r7A@8R4{-2Q@3)PR`9ho=7GiWs|^{{_bUzcgd*
z;_4=9W$f~g0_2SUMKiPf4Z!?Qbp!q~$lsqBaR(r1VeMcEVAQmB5O#32{)h3GWKC-`
zH!D{lO2f+hv5Nou#md3-uX+wvV6KAy#~TP80c-y65k9!=oF7Qm-!BgKf6AO(|B=f9
zbT3ZU4`2GfUmUC-co9$z^FO`+ZpXs;pD~yKY{12{1AXFSJ|9@m2l@o$0N;OsPe2gK
zQQg7%1IYn=eAoQ9;r_Q9f1q4{d#9|m*@vD!fH0MR!&vSgpx1w4NzDI^lPS44nz@?-
z(IaY8V`~>j05bzKI|Fcu)K+e8PCSf2Kn}>YbTM|avNm;PaCEVx`P<b+f#{!`wWEXB
z2bf1K#>2wI!otMG!o|eQ#>vD=%fv#(#6<JoLjQvV{sYd58Uuab(ef`7|FwjFL395>
zy}Vq^E#Q~{%xrK>|Goe~v#_!QEC7G=I5;>z6#j7m9R9^)2kxl=esTZ*c$}<2P5uua
zkoYjt|KR<9Gqp6w5Hm9~0%lrNb!G+zX21wV(F=5$8HPGjQwv~%LsMr7oN7c9GXn-7
zhL|}Pb(V%m=9LsB0&{l}cwR6#vnmx7R-i&6C_f(<>7X!&WH8UXG+^9<(*<NEFtMlv
S9J*#^mS&b*s;aL3Zd?Ef#A+V^

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_100-low_error-dirty_hack.pdf
deleted file mode 100644
index a6027ca201421ad9d2782af4304b31b09f22a614..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67677
zcmV)cK&ZbZP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q${qkhhEflIM#e1|vq9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R_|JK*d5
z`wP%!{}g2s{xCbApQ22{AG*DF^oJ;u@P}^J_A@e@-*>TRP_UByB>Zc4z_`7?Ma$k>
zb^eb1|CSwK*Zm>NX#Zh$(>_I+gg<n9|NjqBCgBg=+D%bLHxT~N&5WXjB>>@X?f^6Y
z(f;uv^!0DJ10MgBWVFAZ+jV`)G1}jEn&&RX(fY$Z(|@_=`@i69Y!mW?V`r8){i~(^
zy*sbp2>riF>3Ke-_xTsd?xqKlVBZ~7?+vkdRoz5*-|+w1b6~v3>EnH0e2w=t>c3M&
z{uWE#`+aP~MDyFZy^pf~W>|F+;oENZJ~!8Yu6{-NzT;aC)_&hQit>F&AE|s-M^XO9
zGMK-$!1+E6p6}P;Z>)mN_KTPm<@+gK&o6>jl<zw}^JC%J{<c$lt1O>OUzG1VzR%Im
zwJ*xwSc&#NBl`2l9r5>W#`e|$KgF#m-%oOWJ`sO@73KSmcj%8>KN7z0_PmwV^J6tc
z`L<&>|5$sr|HevmJAcf(kH^1TiNB>H_HMrjTT#BB-utolDQrdgzT^9G`ML5%`M%@(
zN%Xn$MftwtbAPV92!CfSp7*y>S^0J?{@&I3eq(+LTT#B9;(F8i$01yl?>qVv9rml2
zl<zyv8O+-{it>HOyYHQ%^*7eR-zTvBc~AT;rSW-w5wxOwJGEul`4BV_zVFuiFRNaZ
z?>oLbe6D&?zVG;c>wm6#QT~qVG~T!2{NtYZd%DwGP5njCit-21{?tQ1b<Ee-uRr`R
znQ~0`pVq|JJ16Ja?)Og1+5bA_|8LEAJI33O^KSRLP~R$GnHvAy|0}-OIqti?zdGN#
z!nr>G-d1nk{$oLXZ=SX^k$izgYl0=q@)vJ|i?+O?I36;K@)qkONcq?U=}k$M1C;l_
z-jt7);Z+%w^(J{!-ZFdqLTUqq_0+h|`0)=y4R=kW%_q9PzK)&b`qa|879}lsMZt?Y
z2=D*22sOzV*CN#<-@@~zT=9iZN=<vL_V(|&zQqZ8JiKTTDazRR(!<!2CpajJcW=s@
zEyqsrjWIo5cpd{vN*h5aRt15Ut>Baer}_^v!5nrTeL5+v_+-JSw(;rBo+C)&)4OHG
zqiB&o23yjJ2WwDbGO?cylGbeA2L!oN6mlg$(8etu<TGwj#?TMNvW{C^uw1cmNxm(Y
z;7u`&D3)N%^-=y%aQsbjjVL(&rkF+)>>NY9v1H#E$s>?rL@xeV@NH4ZqceBh=;BfC
zfJG6H&ScwY;?W5nHSy>Kj~X}B2^Qrl93aJjOp<egMJA>#gT(tl6U$C8=={N-eGmNz
zf@#FT9_PkflqG*&+cN)nQB31q|9Y$W_tq=8^QNHNl|r#7=yp9YG+vO>D^Kr5=ud9F
zH))+5cr7F$c;k}`fyY_cD+hl#IN_76_Z*$p!bJ!+yeZhuixMBE@oZ6I*3LCq3ds9=
z$09Y3Hbep@kEG<JyL#Q2bZ4g<bH-T=Qn0*nCDUNI2w2EBA*V>2;G*OdEtc{KLNu|E
z*NsV@T$1a?(qi@B?U>@Zb+L8gwf<~<Vn$u7f8EjI5?(o-&I5T7)<^nXOBl<$C|tsH
z2(*4xr<hEq&23R)b9b!!5u{k7UJIW}%%X7NuiVOgvb7edkLqzmlYc%j`oUKGoJ&yh
zQ;R}DnYrt_A86*l`_?4~-nT9}Zf*ECWih_zem{~DTdKFMS2A7~@0C~0qENW<u3wZT
zTt`rX)w+1Ef$^SOrw%iH{Y{4@KjrUOq~K$FD7GV6+3xBUElRAz_^$)|O}W;#YnOT?
zUl*l%1^e2y^$Pa2x%J93s?Duij&5$<a(L2yE{_&_&^HnDIzWmkxO#L9&$nJVJl(}t
z2lMhWK0pfY^{rbDuW#LAF<aBepq#bb^GA}>p;EgZ8d0;YTaHMF{sl#(<)M!s3W00q
z)-6YLZrze$(#W9UHG6c$T)5%wQ8!%P_H5l^L{@@<d)e-q8tz=XDNeX@?b><;i>!nL
zcjueZaKz!Fv=R>7i#8?RxCCwTQ@Ha?n%cE4v?D0hDY#*EA)N1)E`y1C$#gPI+(PEM
z*k`IZZxUL`g}!x3CP>v@dTorpXDi%b6Y@E4dB*tXc`KOowKpNZD4lKI_-blGN0Rch
zwsp(T!o&I|L<2|fyfE35hkWYIZ;qW0d!$Wl5pXR`9N6c>+XPR{c1kChsi_@{grAB3
z%nma@d`iWeIDbzG#l(SoUfReL=j$n{n0YQNN_7kAIw=(^<Y965OsP1MwAgz}Dxk?P
z3Z&vq$w~4za)Kol0~hEiop7cQEehEWr_R~6YB(6rt~FT3!__uCv8H2^ROn~EW*31g
z;L##8JD91nV|K2hf%`o^B5iSYd_%Vf9LI}7p7dzpJu~w>d;g7gN*-CJ@Rdaw(I!Ju
zp83s|91CYGNzo!F44;tJ2(OPlm*mRg6Cr^I2t7Q;dK%2si<U*6>^R{>E+IMLXP%m0
z&U-nUIlnZxl<Rp>+6V%LB=^mmvRdOwJ<lFJ97gP-MZg?Kp0A67IgSTR>YU?%`ngE>
z;rP$s<9ba+hsL!VH`t_C#keu{rZa2YU=;r#N3Qc^<oUcP9P5PzHjVYlXPZ6JG{=SE
zL({|)ZM8Yx47jjcT1Y<Hf<n8($Wwihz}q)vjpI$p*85+Ql#zG;qHts*U+{KIRPsgl
zrs%L3j&8a_MsCMN;b%QX>rFy)E%`mL7l-3V2lwKDSN$Foz>&M%?)cmRQZWDKgJR_S
z{Y{8g!*A%E7}#95&WX`DFg^YA&1kU6Bq2wq=f%LDy7{~u*iv`s00&4REO?wJC4RU>
z!SKT+3MYOzCE-X?t|3L?#0sAL_9^$;E3DBOLct)CMG1MZOOFo6?znWbc-}g8Ng?&P
zEbaXSz|Qq`=d3m_ScmM((eHSf8r}_yl2?&kIyMl@WU2WdAO))~$&05x`=(^;{VzR1
z9CCh1SR6mKNRSphW$luo$S2082dNK4m*}qXk(0Bs@A<&kbdY#hqZVOgGya`xp#YX9
zIq=km4Z3Jja%?gsxnpd)eH8g(dgUV0!7e>t-jp1hj7;9aH|Z+g-z}Xh-r`NMC<E;g
zt;S}q=!sT{CsegXf!sqkJCYRQIi=8gj>e`GTD++jg;IJVMCX>8<*A7-5@iQh#gsbJ
z^P04>I`+H@X1#Lz`tK5?ej_+21gT$W4YYFTx>)cIw%K(P_KC6Ursxoxshgtbj<%tr
zv}49;e#;-il!rDHo|HCZRc#L_bECwFMufl~K`{JDu35tj$3!bu@O@14zs4F4-LCCQ
z+n(VhPtu!*!zm>#9t?{x_y^Gf&og{x5vW|Xe6!o2iPiD4ToedvOBG;Iz@(Ncz@ixJ
z#BG3+;%yt?q_z(poHnGmH3!=o^^S%uhQZ)^d7rm=-?R>%=@p2_=c15LJsvrW0(orj
ztyHGKhPz})wQCJr&`SU>QA_J!&d?BLCXKJ*?r?3hh8^^#476j-{ozBdLDTX_YnabA
zD+6Lny~=Nm?~E44W)IFf*ZaY8TboNn4cCH8MDa{rl!12e-Y@AyZ&D6lCP#x5x^4l(
zPV~tm!9oZ<^^+y(hC9Gzq%i0_X_d4IzEO)X=r%5^h0PSvMS}3YU#R)v!DY1p&grVa
zyLC|p+OgDLZ&h=AOBaRV40r7TgwmQq)D|U{q|@AFhywI@z#2r#rFvMyXQYE#!)J7P
zm|;VgwbKk!$}UjUT^EPptaYg(c)czP4=g-i-=x(#pI9CV`}tsXB<v?8LpthtLw)oU
z&5(;Sj-HT<F6YJ>7R^QAuR`<fdEJ~TLDnVac%v=~e<O~@MZo!R&S>R%d5*NJTGzF5
zrYtN97V5-3-XY~@8n9LyQgh;h?o$`^nP;7qef5Nb+Vw;_d$b^oCl(x+Oj0nqiDr&$
zXu5`x>6IO?(beW`anbbhz2Nz2T_T=O&_&3hcDz6rWuP4*(s}G39Z%3j%F!-LuAfIM
zHO5X&X%XT)k#ToX^0nGKhT9)#h_d%CO8!i;dbN}JwEy;JVv4EGBqe9ajj|}odv26B
zC0Z@#hs&qa7}PUhaE;BtrA5m5;o|6z=M;HwEJ9Av^c9=~VN=er;kN0fPxYALsqa8-
zW5|AgU>E4LHy(?Wa(?Pdh9x`2DJWwyO}{D8B2P}7`Rx(=&s<a*suv;V-1u7Pcj{P;
z*(!?=hefI$2S_pNMisB$w*sXH+QF%IL!cHVwsyk>bi7FrhL%4Og3!26S3B6$cpG)R
zLQNL&Maj27<EvzmTK-PX@E+>K84mDmYKo~ZEsCayTcJ%&5%1hKF-2D=PSK-f7;VRS
z*d`_6?qL7Wmpk~+E#KkSw>I=)o)T@~%T1m5Wy?hy`Z$!-HuP<%70vlr=^5g;DEu~b
z@aFpVsb2Bv3lGjlYs|4o?9})-xze=H^o!EbIqz`4S>x^5=}TKAtoB9epr>F_vJ<5F
zqJ-!$!Nb$imvDfToxlggfLNo_+2I!o3VsGkLd*DxC981pSZf-ML$Gw@z&{g|lYhfr
z6#9!91UYYLqD`kzzAl4+-+*DG(X`Oht#Jg2gK6x=v6y;sET&K4K+gb_MZne3;Y6@@
zYN4QMwo~KD%cPxLsQIW99CVAsURbO7uopxY4@PTvjxGZGq}Uvbl%3+g!?<QT?q;3?
zLCLYre9IUOBz@w-HaTTFY~p4*6=48h6b^3aTNqqQ#9>B*{UV`Pv>**~>~zGa1O=mm
zG}uk6N{8LqjQY%?u-ibJov^etBO7w(jv$R7VEfOePS}Dp4BL&?`uj^`HEch-G*~=3
zOvi8JYeXAAnVxX7RGa#E)C0ckMT)b*E=u9R)nW8u_HnBl#!AbpT@p;%T1{v6NZrx+
z$XJ9p@(lSNix9^oo(_voW3m(GKnp37PFI_K!0nNysGwj9R2}FvdsCtT!9dK*qTtNI
zYx+&e*85+BtRK84OjiIcoi;cVrVr^(K=6whUq6eoIvqg@f~gayV(J7rhmq0-CxZQN
za{Mk*%Hz=ToDi<);tvFi?!O)n+119vq_y!#QqItCb;=p0xls<oj%R96@~e(F<O&o&
zKu9TZ?qk0oB)puuW4#%W(4Fh;c$6(lt~kBc-MQkrzwn@36s)Mnug1Te>&Lj3?$8XB
zUD>^3Eu<~ezGs~r=v+VP&&nF>Vgi?4ccSB*H{FVEJgU0bU|2C-ln&Fg!Is&bo4Her
zJGZmkYQ1wi>o)D&&OKT;xU0JrQ7l18R&<z@gOr2m@P8P*b-m-UZ;h<z(C<wee}^k_
zk-!VQk__3As~yr!(^2m{q<6}|_;_Y@p3?Lr_s&CF_j>Q(79ZigH*l+I=OD&BNSFm4
zc*Y#-o^K74le*Ko2+ENp@G$=1gmf~}Wl@rS8zov;gZ5BD>D*kTWM@%sWhi1*8f-lu
zlx1;Slw2n$>n4wSPvhc8I~gVArA_5VB3`u9plCE%EQ;aVq>N;gG#(lcK{=9?j7pDf
zZ!T7`O-5n)8+YMO39FBpRH@d)h@!L{3?u}K*e4|&kR}BTip@r`hm*=pNL$)QV9sbT
zinbl4kw)&zx%Z%@rU<vzh}r_oE;Wwx5-&0QbBc9E;n=A8pF`XOW8nMW_<6bpSQIcX
z$JeQ$6@k3OQlDLOBBhn!rF@)?f`_vTzWq(|XiWK_Nbr)Mr<LG=>1S=Yl=`#w8#cyy
zZmmXRiZ<7xNT^8K_FM37QOK#>#)|?@k&p`8kw?L5^6<*jqtSS>QKrtWJaSrO+2K$+
zK=?e&+B5dU3>2PaAy$jPqpYXzvcX)UbF;x^kHZxdUI&gT!O=^~5hPv*`Kea70jALE
zHt_smDm!!>v<IS~TctgxPJb@KDF$*8PB9QXzf-?C@`_tc-IF;Onm%-MHX1*SUZi$Y
zeeEz4wHteoH}WEMT;yQZP5qTud%L+S(;Im#LLa+6@TP3~Lc52w3^0nO4(c6m0@acn
zm#YVubZ^=W21aeh(VFM394$&XQ=~vO<V}>4)!<&IA{GRL)<upOIqzbLNiEDyr<6j@
z_>@-28K2S$(|p)y#E?GPXv2`w+O9{vAP5;{oLX<Y5U*Qmal5GM&<N8m1b<MyZWk3D
zD&TL*7Zmgy85N(@;oCLU0qc9suX+Zo^cDVnu4V?O?yrfJy~1|@*6-q(Jke_Te!=ox
zT;8c8;^G=l&ZM&w7K>I2J)GLb6`q(2G^2WbH5w`SLJJBzVM0`0r&i{qSWGPqU#6Tv
zy-cw<ldlv$I~OJUz{%6*qfVH?te5FPo9|LgVBYEz$IcNsGVFu}n3uX?0VW?R*}@~`
z)?g>XRP>-<B=jJ|=U^|6mI~30(GGRNow%}O&<BU)boJq2c|zYBY|l;)8lCnOoOTl?
zOxjA2MN`%kX3><zg-JB9%H-G#n}xQU$flve2ZJ+p<KS>Phlwb1YtmABikCES!^{+^
zHQ9s18#Hj!ShXmjeAA@$iqsl*1MlGfFU#1X@LLc}IQtLS*g)zq%z=TlQ^-`;5D`%3
zyaqePQ6|4eQ-$n;jiw6O4w<7<=0)V_tRKp0r9{v^ndv#SYT`E_5wdfx^c-~J;=#=?
zgK1FGaNIPO#$Fr>-bb*_9!bhxx;Y0d+qx$iX(cmo8>UVp!$Km52L@-Z)~RkdN07u*
zMrkJT$Z&lGX_RTZd6~As3tBQ@Aa7~NkO93pVnWKw-WVm-bhS7XIa%u)L!xBSU+FqG
zy#NqgpXxTyZe#NtG{!v1yAWADr#uh`Nc3ay<K_F{$IJJ@Z<qIDB&U3HmNc3-@Y+jC
z`aX1OJAEHIrM=N(b&=sXI^^GJj8l>mXeIGnWAhU&Laz12;K4}rIq7O*l8<~*Nb)If
z6|;Qk&x#bEu=&a5wMfZ*ot+(TFZs?^5>GAw-D|DmG?ojlbr`vIIQ9$drzfw$RlO*A
zE7D@p9{Qu-q|G-NIX>YtrT=hI(o;z%<4WwgM!6wdI+c&jRk=v%kJs_l5s!l;njnnL
zBid*_Nv~-Rjox$Pm*_j!vDE21*TV(=U;1#5OaOutm)}BgwEVyg{nJ+*gcJ^WlNSNA
zlm_1+9CAuWMo<h#hfF`=rsnG7q0mcph95Tl<Bic>@}D;vUF2kcQ{;kQsX!_F^3u1)
z5DGf-8w0$$4vGflLJ<KiO)ke4G!W@QV-GA~c2EW$tX9MaObr#`TN%7?fRx;4bVI{I
zR1px32ADoIV7Sn8iyuizk%Cf%1G&O6m>N_e8!N{rhl8+=)_71T?4#j&s>qPY3_ADd
z5oY~Vz)2+iWCVsbTVwcy)Q*-(o*CG(S{dHN$d?8)j-S%w6<a0!L9tcR77RCsvz0+S
zreD3G$}4WC*}cW}G$^VW_p@600lnFwG9!5C012T&`jK3E1tGl&2vCZIp9uPajkxil
zVy<n0=TAjFH9VmzGHOv6as{EyN8f=EtE4CZtKkJ)AzBSj>k8v)c*7&q>i{V~qqh=l
z6N(vo6A(_;(wI}xX3cmkxE?Tu$EKpzR*p{wJ?Sw*`<tTQA~Ps%3coZtN(@B)gr1=|
zyM}lxM&hkDqWSm&J7F(UNZ+F5@<`xMXrzh?WVR3@2lI!ZeK5Rm5$0L(hpXKYZOG9<
zK~)svu`+`qDwN5vkvy~oLn3vk;w70nR56v2Iux5&L6_}hM5t8ZlM$iPdruhg8Q<Ap
zVmu5#t7uS85HUImAzhh584)UL5si*RdB%<5Ttjx970#uAR^%2{%xg;%q@rRYyC~-;
zJIDz$mBMQmB?C)c^Mm%H2;ImziW6Nyyi7W(NZ&|0@>{XMtDTHn^1c#^?!iFf0~AId
z540J3oIHuFqOnITFG_~iLQoH-6`7z1j8;j-N3Xn_3@xYXA9*(snhibwP~r`uvEz>z
zTJHKjL(6l-m|;YFudJ8QXe%6ik>a>#ym%zSR5<xceHmN8c_hcgsBU_^7Ac3W$=r-8
zry{s0IdVRk7o{U|9;W+63Lz9+2XksF;68F{BIf@@E93p~a$SU!C&crwbeRW#abw1*
z(kUTe5yqA>U^M>~9LXZZ6fe{8afB;DVNqg=N@7@)*r}INFb#+?NQVdtEJ@6mU~&%A
zDOP)I*%n62p)xXz0a8laFkq}yYKH;Uq|!f3Aydi`F<^XDA_>xWwqz4S7}Yh=7|c>R
zKuF$E17a#q<+~W*Dk>+&fJK44nFFL;S#7Kv+NAPtj5bQ8=tR~}d`xk8b}_Su&kJMh
zl@fvskP4MF#Ggb?(UFw+9b_G?c4k&dumD_8$x9r3B{&_H@mWfNA`_H2WdIPU+$sZP
zK;>TrclQh}%k=-s;xfi-Mc$Xu1j@9qMToyw=GdYz;S9pS*e#`?g*3%LperoGKn9y#
zNPeiSH)9x=GUFB{XM1bpP+OIBXPIk$Y&m+|WJu&o%9iNI1Ry2{#$H|@&h)_pq{ykP
zwSk>Xd58w1Y2_*!a=|l~F^-gjxsD(p)ltJ@qNYyqi6~;_RW8akD(lja<XwrGi;~0V
zoyc6GO7L8i9KP#pnM~LmXk}I<Z@)zuTbgN{*ZKF{P?Hgc4{X?P%9hS*wA(7>by1i(
z3$dXkw{m9<Y1@@vYc%dE1$W&@$tTIdgcJO^Yletv1|xC!D-n26+SoFMjV57b6WfGQ
z2Pwx%i6m`mVWuSQQ;WzXZPOyg28z7r1MNunS8lW^OIsI&vb3pV#jSlR1^Y-!eo0$<
zI#R;5x0R<&!<|K*wyuMT=XRxxFH)w1yEv1X+5`X2EbS5%W@!&yfiPiHM}0|EQ3kxF
zQM+>F7a`||1K<c!U?-fHSeal{O2}V?<fW932_Ok2_8$RdeI^vZz@Ov{Z^@X&3?H!{
zxJ?2WSd>6*AO^uABxu7a?gM{GSOzwU7;&-_0V5P5Y7qt4<nmwb__TcJi;`#+O{)fU
zBf5r{DhqfcIcyE#g9-1jTKQ$dKP<}F03s}tz7HTstmb01+=qrp!$P508fku$hF3!#
zIFKw3kP@nb))O1R4iY2=Ra>EE*dS`eWC(01#C~t+8wU4)5IPL$;sxSi8Pr%fA4e$P
z@iTXI8ZsATJI5mJb6m*@=4dWLTwjGu@+Jwo<P|!9utD%9mVuImfMQ542TIBT(vVFh
z+c6TkD3G>TfGmp;Oc7|yvEC<5LDlQ^lE^bnUGfN%N5C>oeM69mCr@Cr$+&NWusyzY
zOW+ybx+TnuZ@m)aO=kD?3QOdfp>7Ul4R!Mz;@mog7!(Lkyze%g9)q8yuzZ4Y+J^TN
z@5UJ5#Yd^Z8B@SP>%Ex+EQtV?MJtH_c+Ue<sttnoJX@!P%6Ya<3C+aIWZ)<jIMNYs
z<LB8Blnj0!f-Eh<hQY*C&%$X6N}T8dbK<kS$*gM#cP&t;MHw4x)M^JmduLc#kYc=!
zR-j1v)+0fr>U?Mbk;;K1yT1Ui3`hWlkOd<|0%#d<0SaKt5OE6-t^=e|KwW9-c<v3%
zi^dP(eHjqy3KHxHlHbG)!yo0~Z}!6RF7z=&bZ?=P**M938au;cvpy!Av!M7bAT&cn
za6zRRoNItnJ3xwQ0dUO*f%57sz%?O*C9O$9b~}QU5OGpE$64@j%OVvs5`vsLG4U9!
zvM7P9MIbsFwhFAy99TrcvkPNbd{=4%0R4^v##^ME<7Df!4Ob5)wu0VUgq*Sh+s%oJ
zr{(t@^e=3A@eLZf4Iak=4}`t%*dPYOC>URQwr;tK&(<v=5w+3|NJ%0d8opYXh_pWz
zYGP2vj;v^aiU9oL0n%axZE{RQE)Yk<lndx_Q4%q-GjcJzNCR-(pR%SIT&o2;X$Tu{
zGM!n#CmtJqr2(X(FfM~~?l_nR7cIatNg<r(0Yb7yx}5`quZ&|b3In_ol;F%w9I-{o
ziRwkTQ63E^xHV77XPziT9E~5ED1agJ&qg7Cfaxb#QyRA!wSgZBCK4aD2vX%U(w-Qr
z2AMAyR#1)&s+ETILURquxg)+7Wl(bRN<9iWHb@(`EZedJ`V<~5C5M!Y^NW=$)8Ixa
zMkN^Sy)lZEjZukDdl#dU@NA3<eA?QWBHS8o*!c?omwt+Z2oB2P9YKV5La`;BZiPln
zQlb?bQXdM<xF}we6eRM&rW7BPvM5|-QSM%!R0ttk1A%z@+&wq$kg{=O4f)n9Tol1=
zX!7^HNfId=#}*IoXX6+M05#)UJm<y`5H>Mb3;NhD2B6RoM#*?=6N4bMZK5GyPut{x
zlzW%kjEJ>Q!F_6<jcC;_8xdw(f)mHq<MhUBM?HVpW6!q7Vq-r07K{D-jGb3W+V@$M
z%-OeD923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY(MMR|Hy{?uHPO=h+V9_1{+b
zb{)o~)L|SV)yqDD6MIF5*J->Kv!Aw|#%ne!=DbehSh_{3+iHDfMYGp!wSKafu>&_z
zFN238U1pK$y1HXTW4o^I7}40St2;(Cw(IK25zXzoKVw95yWK5DbZxhL^61)b_hmL-
z6td_BL+<S|PlnvvWxj^C@)Nq$k2uH|X=*^h5IZ-GrCaUB)M_H@LBk7PYz7MGN8N1e
z7R)FU#TrSOCxENc6{ilZ><H3DrP1Qkb>qc3(iNRe1+Xj0iwfc@ZXzWi&;5=FW-6Lp
zk;ha<yW)tcuy#fPA781|2Boyzob~)vjl0zo^o*AD=;T;0b42QaUE!@%(HDi!t`l>-
z^^8hI|5zlxqfX3`U2=vpW#U2673#@HM{j4^PV!~Z6{E?gOIP?MpEq5Rm3#s9CNxhz
zlNRaYDb<?}V!XDx!W;P_Ta@T@<eP1!234O}BE=x`>DQaqK3|5txt>v$mXk%QUO5L>
zuZB6uRe@(}N01-hu|2I1`#U$1rqm~AFx6*d=GEAr(|t2Oz>U{8>qEmLTwAwXgw6O6
zt+FA+>5+zqgQVd1^JzrrAC`xZmJiEANDM3wWv}QmJ;0>VKMW7C0XD-!GIujRI7EK4
zKIBc=i4;OBOy6t|dGPkl_OSNu$^nEc9p;|i`_|{mKdCM`x-vgFhUaB6%s0v+vD?7#
z^bCa=tM@Wb4vep^<}`>YYw{(dS!7nKTMTh---^}km!4Z=X1?aR8}E9r(;yC;Nc%i#
z@XN8>Tc>dZq534Vo~=`i<k|Wpv-I2<S7fM?-+8xpFKLJ~Y!TEU2jY^3^;+w0TaU04
zF@ZKoYaHIHOEAPs6mVf~)(BjWUc!*fSQH94F2gcO;Ptl>g}IS%vw7)huuU%#_g^w`
zr6aT315WU8$UDiYp&zi4N18JahbK5O)guJMrEtRz-~HNpr0Rf_>z6G0%*uYr>fg(B
z0nb1$(?$3WdSFe`myjQSwm$iB`LE%n=>Cf%qr)_Gyx{Bz3OnW9--oV?@R;;L?@4@i
zNJE%F)#^jeYxrgO2Mr&UhL^6LUIq-jmyxW0fE2PmXs^l#bXUv}{Y-sGHsFiuIGMt)
zghNy@LiB3&A=!wB_kt#%M+he-!hz&CTLi9{2i`&X;zE+k<N@y-Koeea-~m|S04ZlE
z^A$XSy`qNTE$oB-#^j_9jd<E0K_Tx4KBQ9vkNrM)kECa_4_za8{`aAfXnIKdl*XS<
z)Q-xd^s*A`;w3LE05M_*!B@LTWK5o!ivq^rKq?~&+`@e}i5Oo5QywoknEUK#<#%M$
zp7Gx#DmZFpuL(l&E|W_5!CC2=e)0e(8T^qrRAvbZLIeBM;{hJ|J{b!Er+uGO^MjH)
zW$aAXf3Gq?3=im2R}4Z30Mqh9BvY>lECeO=S<X;IF7&BWBuyTD5)F|d5sQMszzDJ^
zj73?RmqMu!bU}2R7b7zg0cS9JBM#|{qQH2LW04Rf0*&X=!lS-HzqIfX>$KV&32JX&
zx-w9XfnY#M$zRdKKEhD~Pe>6gv9v5#bttH%Uow6o@TFf2j0tJKq&gsWCJ>PJ*qS3@
zlJKS6GZ#;R090DoOPuk<NMt-in9rin!;Vm(e(BK|!9s}x^-?rZXYFSO9QCVK8Buxt
zs%3`!|0TAmUll)tOH;8;X(CAQt38UU-+D<P)T-aQAP|n#Zz&M>sS1lP25=pL&1H(|
z3U=SJ@E{bd-+WXeT8t=QFU40K0Tp(V6tZyZB#6kg)n?FHJ~eI$2O`@Rg>fnfe+v{d
zj1TwKJ<!T2(*}evyG3BMTgORp>k5f@y}(>!v|9-Kty2L3fBlwC2$n&Bx$S|2M0|TG
zx^Pj*J6tq3twab??05d^;MnLVN2FsflVHR`5~=RRP%nbny%bLwh<A8fWz1!eIDXt2
z6`_T>^+$db1cfb%_>T=xmP7=JE(*gXVGnw!v?A7Y5%M95aMUitB0^RdULYkXZh#8p
zx}O9X+(TlI1R=z%aZHyH5fce;!<-NTZx=*jQG!SP(Y1k4u|Q{hNXhZ*20$qALV3(7
zB3k%Zz?K&&tCN>`4PnQAYHuMl*(=-#fl>>ElPpJsb0BqM&}k$goM%Nz2jr)dGC`S)
zz0XHx;Djn_JG&_%0a4olIQkLU?G<Ol@Nbt@4l&|^V#>(w^;Tc)uD`g3fKMa#zDE<m
z?|Dx6d3{wF`@&Ie{LjfuZX`y-FA7}JjHPl}^cYg_3QA(sy`PnTFu;S#FGl#j19L<%
z{sAD%`3>;k(G25)3C!8l=QEkW8M=gI0}rbplMw>2R_O`B0#p9(iHnEOx0Uwbrrb8n
zZNcYq4RdZT%OP?s4q@z8B8HpN4?-pNgye`s4lmpcq<XkDiY2o_yud49;Pe8fKw60x
z$^^#krqX!KPjR3@AcZB`7YV^PCAeBk<YIglg)O}B6_7*Yg{Ocqd0{0W8D}9WGvx(I
z;Vz&9^Q_H_4|#HEXnKy%Oij=6nOW1zz2(FY0FGH8K_h1e!X=~TN?vliG{H=ESQM-$
zQlb_GEV?imrQRT`YN1&3XOP5AsB7hB#UJ5!Zp=ujpGfcWN|eXH+;qJ#mu!*H4Y_6u
z&l}y4kLH!I-XIGZos~b7A%k97<*;xPUi_sDIj<CQpqd9LInDy4+IeM+2Q+%3o99{~
z%4$(E880QumHd4)m^fWwTuc`9O4~+4;i6QUVtmQbh{<`Y1WK%4s{~3cpMtuW59zJ4
zC}XXUK$6FdaGx}t-pI6El(uDK27$wUh+)rU&s?WUsl;{DCR({h%Be)gs8<ekkDzOZ
zm6l1TtBs)}G1X<cMfPfd_A^g5H+fTqC+5I<<xC?_)+=WkxwPK65jxlXVjKd4t5#J3
zCdzh9k$ITN?2SSM_>^OoumB#&5MG3f3B$RHLYP37v2R(@BPXRi%?@mL-;$yy#92wv
z6Kf`Ph<-)g1#&8n0q-;<GOyaVEa^N4e9MxKxq27w18kct@o>D9=IvXWbUvY@Gz7Zk
z_2ymsu|pf_(C!#=wFpe3Uyqj6W)eL_q{j~+seKhQhm1M07+t}1$c|^h^Oq9ny^^Mp
zWbaCvcAN{nvf+@d@10K-CiE`~Q35*HNe|}&1z4^8QQ+x&B~b%bzy%`C2rTaf%8+`z
zcO}s|6e{mR69UkIS88=S?w#4y@Pm6VV1}tKOyCCSg7;s68CDe#ejIv4FJOiny($$o
zKp+-jpv5lyHg1B>#MH>WWUY}GgS3t)NJ88Y3Wriw;bwDL`3ZZmC?D7u`9nl9F?Az0
z21G=s3}851&H-X|94<_J;CU<pfK@s=>9$3#q%+k!eKx4XlDHubsp2sNXNy<vce+x%
z2VdYJS%qF8@dG)@uH0~-pezE%G1Y6JogY!=ERr6*(=<&`mMAHMUx8xKAGETE&MY_w
zygyo?n`09c4($A{5KLmtc&8<kcr=T`1w!=>ubgxk;DeGfli)W|NCzSVa2!`CCjfMg
zAOWn$)Qf06re66MI4>%f9hUB(;Lb_IwpVsL%-F2`^CEQ6st<%#bdbI>okJtC1i*<{
zV(3NuB6nJ1iE-pEl?EtCQK<-5HO#=S&{F^`1qJe*7)&gJ^b$nVqF9F05y#2tAR^RL
z6jH(u<4xf@ZDF?bifJXR)FKh-=ux-a1_4gBnjA2$3KxvUg(5TVI*`Md8bzUUnPAFf
znW&e*wA=-B0lclC5Q8i=zeS3%pc<;np+#gbucUvVe=SP7%mEPQg#rKwF_#yNIAiXi
z?<EWwi(|crQg$Q>pK<me3>hv5*SQaqW>D~%)VB^-yf0za+;tmVSG0gR21UUO9}c@c
zAqkRA*zUdq#HHxzVU*U)Mc@P;NLAh*$4k(2u1I6T)49sn5W+4fIVl(y9ge?)NO)f8
z2f)g6#VZp~&xMC@b7}Q5yMgJ%a%nGN_qj8^GV%SQ#v0~%b8YpWgO%@a`5hSq=uQkd
zKn=R<{<?>1xxEBc=ouJyfW$8O6B8??+YJzjUZ4$tQFMl3AHrI6rxhiwie9)5NaA$Y
z)AHs<)}44G?0QwKdkGoR3ku@SU921P<}TI?6>yX8rM&}_(w+AzU@N`wB+@?Uu8S6x
zK-?8oM?g%M%a)*-P815jYP#!D@boO$m!nM>&O<f)UIOd%0<Hj{=O?9OxPaZvGx}h4
zz?aZO-DPkB;;0t{22e>qDR*vUhTszK)a7(0Ch8|8`6rzraaG;#Vmfqs7vLW7S>35t
zJb3WA5crUaNy?Exu<j~(0-)GW%EWkcBNK4e<s=6v?ePog#<#~;VcYKQoX;mbt}~v$
zFmzpLA;j7Jq>xht$aQiGG3CVbbti@(F@HZPWDF2<rx=mf1M!7jNesjw{-j*_@f+N`
zH7!zL&URPX1)9!2C|t^vqy?+|(bDK}xC5AZ`;B&LnegdmVrWsw&>QlQK+)TrfF)h5
z0kGW%fy^U@wsRxyB(e`H1?Z(u3K@#^O$_a0r%X+Yu-a6OcFKqF(dM$+#}_fbH)%z{
z*iO-ggVeX$Z@DuL0+4T;rTx0&fMmW?dTlWz6cQl4NCZ%?6M!h|bxHt;eJ3=$oOId{
z(B1JH?Uy5qsPLbZ!DH_DDk%9n3kf&xiliYXy-rZV*7J}(1Z`i(F5|)Kux311o#+e)
z(}{lwX`hz@q4;%^5U+o`ZHVb#7ZPy)kGiy27oe^>)()uakOc<n!ekMGBX3j|DX2@B
zg$(MVX0-!d<&5WY=9|12(N!t|Bf3g$V5tQZmkmmn_K`;xts4S}VpWGySy=g@RGRLk
z<RoW&nf#;`v9v^~PAorB>J>{=lm^zR5|x^UQWvGlu^NW7Jw|V#?ky-(8u3_S;f>NG
zvor@4O;+wGRkYKXA$2thfaKW7gh!pQCC4ev6O0(tdsMM%0Gq8;Y}6}pA%n4`NvY~A
zdm?R~AzSWp=rL%kUIYl*3QBhB^{~K~dOa*g%W5*NcLFEjdM98tM+`Urg}+vvkO2U!
zdL^;`j2==fP*ZO$gk#lnjCF2;a)7`-9Q?&TSdl^fwrfSG-*!Uvu`*9RF<HH*-l44U
zQ*Tw40per!P@$lD@MZv(-oy&Ps&_L3u<C7%3P#5lpX4u<IjU!S7DB3bJ!>V^+n@E6
zJnW*Z!IYAxx&X7Q7YFF-#R0l{!R*HxP_kgKL{wQhSVt<2AS^RgMiP{wN&^i98uhAR
zZ2^VdAifz;MUxE+W5K9%fW$r++s!T<+O1AxCe7LpAudqHtL#v$^i{?xmIEt;7Q(K|
z=7q4U-7v<=V`V)<b+R(Bv4B|`;8@@c2D+?XmghV(pgZjpvh%T)8ZCh+wpOM>gkWvv
zMAmC7lOv0|rAd-S-^yai!f<KS%z;4;6idwtb2N>z23;9XS*K3+)gvp}l>wH;?#fEb
zf_P=g&60U#>P1n#-5!k6dz;ZXgR;u3%<_F@dS;0~n5Per(yXi-iFOQHxmirG4B;#|
zNK^TNl7z05dzLLMdpk=TmQ5bj56f(i0*MEW`yh3g`}u7;IdJ6P^l-SoO%I3jp@^c6
zn>S(=eJpPUi$a!1gJmPj>w(gehdd)JKUsbgmZ&V>3d>lQ{{@9EHy;hEVU{0<1vAUl
z!w{=-2W8pK@)sSf%2{3|mhMci6H9xRSBfE3<+nmi)gj*&i-?x@3w1`zLB>*~<wRq(
zQh3@9kaE#<7(Vt@-ntbSm8{(BrqW%P8~QP_UkBZj2gg=O71zdAOcmFLT#_vGdX(Fe
z)nLoD$%?V^exjzV+@q>G3m57EQXiX}mE~*86T7P0(pCFX^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9j73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<&t4xnALV{JOD~y8CWf5p`e5sms5OTLV<Es>%vC3ap@CK@5Bf#TJ
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g*V@d&7xNN)_=q%F}K<2F_2zQNMY0L()tR7GjV!FKMEoDOg+gnI^sahvcA
z<Pn;2o6t3R?q*b}H->CZ&TuMfl`{lXK?SZZ5&~B_%WI2#^(^s#=vWX2<7W>Lk_S4^
z8MviD+_*JQW3(<PHz>%t<^^40zj2F?Jv5j%J>rKK1-Yh(F+M=bAXvtChWZkW;)~O1
zT4X#k6=H@wr|zB6)Ki@%V!?T<@~Kea)$zcHU}~65@{y7xZR)-Ua<8}3if~t~w|B;R
zGa!7u_A)I=5##Z!jN$QB&G)Io&iSBaU^-p&8M%IdGS5A_olo$JfakLvVe+74IQyx^
z^T=IRv^~rU6_D@V8L^)&1?*$aj)?Gz{HHOcasz0TQThNaIGJ8RqfcfZ9H2y^i82&u
zf~qVA_aPNLTFjN;zy}95HTt1+3637pqnry`3M(-K_Q#`=H)zJp+zv->XXSn@`zn${
zvIU;Gt~}TZE6Ie0<w`@L4ZBiRXg%js>PXVqa$w-+s5BY+VJer#of$f&FFl-~&UddA
z9SSK^bO2uI3-16~KaSK;<OLld#V;s%$boWI2}YjwMr9>AVyBq4<O5MA@rcg(03)t4
zot!!S7hnI59DZd?Im4?et;zv{r@Sj?_Wi|ox-;KixmrG$eKu;EnSQ2Yb};=cf7CHH
ziN^38n>2@kB%(?_TcpezlXNh@T`6onm~Ez8e+)9KY2E|fbkwYrbEelh)5(>B=gc0z
z1ViaS<f>f0MG28&x}OgKy-X>l1Iaf?5Im9;duG<^BPmUphR&4mDS?2*GduAJQl@_D
zR)%S{@*Ewht~AsoCDR;f?(wmwPWoU@rj8G0b}I#QQ6dF%aBvXzO6~N?3{2YH7p09Y
zMRXBzv}qSv?aZZ=6~vjPJ$0cnOIzux4g+qbvo1<9rlU3XY*=Sjwo+ytHR~&_)+e&q
zl#A;Vh}xC0>tO?~oL<K#nDy(h30GRMzelv?4ZHHKrNAlQ8tKQ5bZfm>Ci2{r!+bc5
z$d%~qO0kwMHgT^gecFTTH0ftMHx09}T?y7Y2b5r~TLa5m$=-_+>L(MzT{+ez3CyuB
zQ9zQlix0Ss#wH6B`RXML$e9}@3s7&E2k)?H)9rF3DLL4-UdcddCiD8DXkbSxU*9Jx
zIaXG`BVey%?9ix$3E%*CE8GCb4($ZTS){wL2b?+Bf+tv%gnN*_fuo?)qrV7Y3@9K3
z&-0_O5*()X!c*}1Y<LTf2tj}{93bVFXLZ4s@hoMMw!DpwS`z|@ID(Wg6OfDR+yEw=
z8QTJ(@H|ujQ~^S~-wVycaTFKgg)^~RUMs(d^gx+_2jD1l4F`^WA#gY%7zNU?2+0N8
zIwcoW;=<uM5E{rLBp;-mUN~#yQ*of?btejqUjTs+E{P*Hvam~>dE|mOS(F$LAyD#%
z5})PXy2XG5rLri&AEB){($9s+vVI8Zl*DWaN{&c32Q$)T@ej&#7d%Y<P>yJ9-4Zco
zY~2E<Wo+L{#26ah55HW9HtP?dL<{xCFXHXU=77Q;1)j4gsc>|O29#|<@GMG>u5G<y
zbgla2;7s<Q`0r9GF91<=2?fD+WFNQ)wsUTsQrKxuUX-zc7dbSo0ytWfYZL^M!`HLH
zBrQ?`LFqwq;aC;cl0(ZYJSInGK5V>4Qi7Q>={mH<0)KLpFCjS8YUhAuo^_`53*vfF
z5)5jnQ*c)}ReoI?j+I}4951jdhjXeBu@)tvxBAvC$KSVJDGWm2TBMu++#HLL;9G?7
zT9jaU+xq1A>GgF245-GcU-yP4=7{et#4(4XtWe1oC6G&^`s`{YHkuw3hzKs|GmnQu
z0;4&x3J9Eb1Syfx>KMqI!s-+t;+<X-7vb$_y-CP}V?%rMix79R*dP>HfN?>1o()rO
zQQ9Ev+yP3gkJSZH5O)-nz!w6(U9^S~0uPkbXsni<0C%<Qz_+VKC%&B)o%nXDZnsFW
zi-hdwH(-i{{O9mN7CK;1{N5o1JuBlB%-|yA(w<wd<iyF=8jPR}7iCF?vYdmkh9XGB
zMTw19Ha-GGoU}sRIf4yr(GloffQ(KQ34t~SC5EF-e;a`xbAq^7%Nz$kYe7gl;>QbS
za#0prPQk%Cu_=UC>3E?RrlrGQTez2=_!UCNJc1Czk*0^Ye_?Do$_f<@rvvsvP@RjA
z7)Jv11Ze~PbOgZ{FsQ@wuqXrV#1?&uUu}aLWs7_QYP{e|7bUSr>32x*jiX>sN!p-M
z9VU^2PxY*uQ~;|YsCe(9B>1du=^Lo`1amEdoM7;U0~9tFvH@3CI-Dqa<KGQfv*V*>
z8f=^rg<lKOhH>ja87UmxqFC`NUgU+ROHyI(I(+wq%ezy$hP%*cSr_huBF+RDtuTUj
z%FvfWT<)82Tt&LJxrYP^wRor0L_?}rVCpD}w4=Lk$jRBFY4ksR{fA@i^Yi_y?<rnw
zyvgs=?YwS(AFf~j@!x;__b>Z8-~W^U_dox9e<2Ft;C}eY1HF|pKl8|F<p2SSyIs<8
z8|#n?RK2q@V1;0?*u3sWC`e|?O?_Ak-5B=OU|LwcBF4U<N@10^Ma`kWX^fvi9kr}g
zCY-!8i`D@76!lsZ8yOg-xVDI21$)H^q}ja0j<Ovt+>G=zD9y7YEv{-@Pln4A2?CyP
z7a&H&{~|iI0=$$v2Uq@0$9!-b&e&7$t3eCBio?}w@ZR)_D{tN0Gbt`U?z{P0OuRn}
z8{s{>)1GO+krvcvf`;)^S7TFp)e@Msg~~mKSaQ3$6A$|62`Gt31HZHWFxY^)^SqZC
z$ZaMxfQJRoO$9gs>u1u*BI*9g^2Y!?i6hcR6?Q`j)Z6Hyw1KJ-7NWo^4Z=C{QgVn0
z3teL{V#F?Nihdiun*JoEG9l2#Rq>@wxb&)=@56{YRRLQ9^BIOd8QiJxl^eklI$2OZ
z-OtU^ohE78kS-xQZmR5)D8%urOI-eeK-gad;`*Tcwj(8Js3R!1ecSQ6J_K%c?7xWM
zZ@x%LHFYHA`nF>VA_e+qm?1tS{5RclAHawDvo=Qmwp*sIYq$JN55mX(`AtV`GbAGZ
z+%{hSwj;dL+>AftJpbIDzv;+b+|-ej`@4>GMsl<NjKG}F?f;vOJSF(WqJ00w#9`!N
z@-sHg$LaE$Zg~dTt!_A!{M&Br`Z%e6#-{x|yZ&)U9dV~Rk}|*R7%JGh@^BFTOyzZ>
z{I(<NZQ7}hq|9$Sj{D=F{h7(wA4l&$?#L6`E_LLY{jHof#FOD5|CtCS`^o;BZan`R
zx`}Xq(`^BPZMVeFK&AS)HvaL~c)2un1L6Lz8;j5q-0x@p%lC4szv+m(3-wrkZnv3#
z+i^_Ya6hY<q5byY)s=WIDX9z6f7=0tF>q`CBrbVfqrd5f%eJu_3HSHi=Es%%vp~;v
zN&ohH9cBY`6y^T5BRI$_zqnXRz_*<2$ZGnzX%GF|jx;vj1_@#78|g@A?+wYw4!>VB
zVdSNjl4Ad<xBOP_87{+)q&(kt6t2?5k=_tpU3$?!?kM%Ct0O7Tw;h#9Vp#At=P!EK
zZ#qIfLq)Zpo5JSbc6`RJ#jRugv=7Q}J5v1{JS#~V-(Ot)+?B+iVaWf`8h_KR3ynbc
z)*_5=51~GN*Fb-UTm3^N{Y^Ils9fkaD^2N}ZVGjt808A2`c!y-(~){{=k!E*zUvrK
zy-=TjMu=A_)4%CJeLIGy*6&p*mWP2x{xjn=Hp=fhDr#k@BPa@c`K?yFYy3YqciZ)?
zx~Qjuvm+_vdj*xwlYCM9O!MKNpBQ?G7`lmYRk!zB{ai2E_xttzaKG;Lq8)ClPW!*~
zAzKd;8dp$%vjSs8>GF-<d04fJHZQiz#D$`rms}5`l!4j9OYo+s72qsgKM^*V3QpN5
zHMV%nMEce7K`BdB%5h-OJkJM39-|xOLuaHN9UlbRvYco*)!@`nYE&@bq+~HRd^At&
z0OG+%QIB+vkCq}f?>uMQbYediX)}h!`>Ntg@a|cZHa-ZA*=mk#okbcNaF`pX;?Hgr
zKAk2e6@@>%mahU#Zd69C5EB%qZ&P-Wjba*bM5?sGXaWSz5%4J~OE|`}F*rnF+#7#m
z;ZsFFK1kQbtyuYS6}z%_q3oQol4I_6&Sf@;B8W1n#!8K`S%B9fRLBUeuERIOXPR$^
z|7!FdzS%;D;K4Rqvos``s9Be0vttj%2f-Y!MsliLJutCXK*)`p{-%$F@Q<@B?$IhI
zM2NCKn-d~flF^5BrCh1NmKP#~&hO0$5e)Eqb3&wvGIu6iDZv9|;?r%?ymkPNKykk&
zihNhVM>=GhD-tLV-6Kflv`IS%qrz}?G-Yrv=TKAHHJwMzy;y%@+Oh+}3$-ZK?H60&
z&DyP=twRWbFS+lUQj+Q6YhF(NCs|uQ{(RgWt-?Q8xwXPSqD;8k)+hOD)g{@etg;}T
zS<!a$jy|Y@D@SK+ss3z^&X`|+aF_yWKENO40FF5cMGl7Ah6L1b_&!<Mx4MLAwXRU0
za2l^RoujD1s#H)15Ps`CxUa0Y+NWaI@p1%`CMY?6N(KzfQSexP^c??CKrcM$Q8xLZ
zi$3SzTen!1F6oFo)W8pgkr-zDrkqDc1H36{#RBxUeI^$``~QN4xGC|FaSHKTI2lNh
zqf_fd4Qurn(dONAv5a{|`JlpMd$vw7y7p|JiP5!t3pYu2wu<t}leD#R@1weTx%XM!
zJXv@oDGrM!|9)C2md&Jk<p}5YsT|>CJSpN`TB{JBktn<hpvl3}ad@Gux%`F~Vi8;0
zBYg5t)FpY>w>~+tJ-jCbv9bPzUo2`~fnO|YURxg;LDSC1b&p)PBT309+j=FZta`;p
zX%+Z|8x}Cj2!={dDaHrarR{-V!7SSYzhXT0RHt-^R$d!I!J6%HU%?*R<G#`*x5s^*
z`9l@*0T;DZ+?T-%Rx*Km$mCDXFt{T~)h!mxCR*#%sC+a8UI+HJ!vAvOLer4N+_%4p
zO%~>()yhdLA^^H?;D)P5I>=2L0A88RDnOW4De2l-bEZ|i2Q=oRDOC(Hk&95B^6N?r
z`-@Wxp`y(y4F$2J0q8DQSp3e3umPyh?IeQ13Ri8F(lwDpyGRVD#o2U9F+gB!t9TEn
z-@vp7<-JNrQ??cWE*DNd9fUY~PMrrcT`{flvnEcOa~^1p#OqfyaO@NnG;p9<EDG5@
zvQ&VAnK40K1k*7=T?By5SPoW&Gw1vi`!n-}boOFC4v16lF8E%vT0*wNA0xFM4+T1q
z5s;lrsI<X+J1l~tx|5MQ9VT}EsR+P8Iz56yMnb<mPqe~I^60Y2N@29VB_W*U&r?yx
zxuNY*&~W-RD$HcUQB+|jfNo{Mj0om6{IWuUW@>ZxNcW#-{&I;%YCVh681Wx2M0<2q
zAXeU<l8@Y<_DDVky!VgfgSfT!c%>waXflN*nPQLL1|yXxdlVgpDEmdp`vM++dx(w@
z`4lm4-5@Z@vnWYYa=^^(NbmBa_X5K5tpZP?XkZjSIoT;ktA`&lOBQ7?8)b2~^3{;B
zvM3zLL<EDBhcTmW3&(*POi|qB*-~eM!lC4CZIxe!q?{;6qrVx^rfP%YmTwYTAuPA@
zMc`+;6$3W%%wCkrFdB!d@4S?RWH)sHI1H@<S&+(9u1b%Bq;?B*))C`xw*vlvL2bA8
z{4o4*tK_Tr*`|~k!>`yD&XT{PHz1O{%Jt%S{@Kk{4a3{ovbVJVzl1pu%+78l4>)}@
zN{DC8WxI510DH|YstNE<zX@o?crQr<LPzWpJ_M0W=?qHB$eLOBN^E7Tj57rMzbR<N
z8^e@bhR2{)av5>}Otsw!!)2-#28=C~5!=%u!<m7hK;|x;3P`PtdS$1wFGoX>v)7>n
zO}i*mfU>enLWM+6yChWJv;5jqd7?*_Xme6>Y|2bWy6K{jPmsDwQFFjfS>>n!D9SF=
z1aK5zl@Dw93yl8+?{Xso%PH#JVen_HV8zv>1YRXeIBzFUmV+ovrYd*DT(Zhx1Hw|&
z^gBt3Db8CrBc7*L#>AesbDPpj;TKtyQ-2eaoD6g96!!@m2A-_%Hd?V_b4zko4aQd_
zL9Z#xlz0&R-liU;0Q6zC%A~~3oQhM#dn@X<VuJ8Pq3SFC$nZz_X{4Lmkii8&D6DE5
zKQ!@2+7(%+BwWV~n49z^SH}G{RLnOCOEd>_?Sn0YcjRB<r<k(OD!#8w^an**?x{$z
zuy9gxj#AN3y2Z*khj*D}+9%KnVp9yqe@`ChI&KXtP%2Lpg0Ue>PQ1|$)q@U729jWb
zaBvT$hBi~M30DI<XtbIjRGFce;D(dCY<`G8%!=LFP8JyN2*ais3MMsdnxR|W5FQ|<
z&mIL4z7pah)S98)X;3%HR0w1e7H@wgoW_$B!fOQUT}FMNkgy<qQiA<LnGF<@Gbsi3
zF``Xe2utC#vNu`^rwN&qm?P%GM!^jrIOxMsfyo5)Nz4%wh^M2JlPSW{)8S)6+k6v_
zXcFoJN4fAV9Z@Xig^ZH2VlL~1;Wce#wltjHm92&_fAfMy!NFYVYFRbw2vT9v<kt!t
zB~M=$63Q730_Gsb#Jf!J=Y#L)wmEUkmO1l;+Depv$3xI?F&#;Y59|6lFRWbC4_{b0
zZG)3yV+<`mDK;M<KW9?-%PBSm@iQQv%%5lBIxDj%u%68e253Z!zv1A_iB>SBqnb&Q
zf-99Ucj8Fua)JPu+5`o-D2prokrnbxu38yZkxpQp8MuxZg+(C-Q(oZ=4mya^u?Phj
z6&tzh0ghUK))hT@LSA}p6=WQk@cRH*wFt=@Vp_c^Uxj&PoyPp00OLoH7#jRU3rKAb
zZeZ1f>39onakY30E($|R1Jr8~2n2>}xG?tq8lDTNb^J^qKR)x9pP7I883<58^&u<a
zO+gD2<m2H@iWX4g9$acf<a-cvru4xMxcNoFt+2pNVg((ITs^_>0sF)Xeh>Kxi$cZ*
zzLs^NqdpCD>sma#J;FF0uqQE$rq5Web`!=dfKL`_pq;#E`bt_5Yy;Y3@S4#DO=J_>
zu=Vboa3SeYE(E1_Q!aSNC8}S1Oi-hU<+XkiEs$a$G`*W*AT+%NF?a+aqmge)0o|Mg
zDm0nT2~@Hu1Psh*yY`4%H{KTQ0bU@qx+Z{7_|+GMv+U{<vpfXPXa&Fr3`Y|H-`%4@
zJVZQAo3P4n01B9l^njBL3Kz=MjcAOxXbP0?Mn0Jdl`pdktO*4aZ%1pFz7Bn*30oT|
znpOqg2(@Vi)CW9HQ&bf(JFO8HJDf-+2f;zyPa|$0UXND5ec`mRR;ZtsdVD~Tt~m;t
zI{YbCP=0tnE($S7@fK}5OD;;t5C$Ur7eT@gIRs0P(MSunCdg={7h6-E7UH)q5*UH&
zrRm&B6xc<`KWOR!si!I5=;#2{tSOh3aI_YPfF1S6O@0ud*)9SxVWG`79Zc7$P9MOz
zi-3XP@n_J{k0h}dhLRY))`S!aZ~<#VZJu}{L6;9?-_$%B&Fw@CHu+#W%;JW^kH9Kf
zO$f|n$_BkO0at=99Nk2xua^LjO@M_RAQaY&I>REhk6e+zB#*#`Y;ycCXl+q)9LaZ6
zwr@u{s-UERp=6acouiYdgCI#KvQ146B%+fn3L&O>I`CxO^H#ux{KdnX4qH^~S`<P|
zpXx>ipV3O*jz=AM8Pc5E1Z_Ire;~IN;Yk*SXx(|rndxvIk#i$BXFQoro~{5ZL6;my
zx*b*<yrs?49-1Bl#~hsqI6l-3qA`ZLarC+L@Sp`IIZgpn*$tqR7{MZYK4lr#{}MEb
z$?bM@JYE-R;7{V<Fx>-qu9`3>dm1f`psakEE()h)>O=T<%Rcyb9G~*+b-Xwih4`u{
z>Sx5P45a+CBI;j6BQbdciAG{pbsg}6TqMjV;YiE`|4IX<e25*DE{w5v2o^kof;FPK
z(gZ{8SG1~DL5hn&shumYg74kA^iqDA7-K5qfRz`_taITf{j?qM{bp6P!PzT+q^l1n
z&2_Jm4L$EwlT)-imtHrY=h9czhK8lAsttyvEJSQz#asARJBoFh((8LZv`l!Qi;yd#
z%hQ2Fvq;Go;H;bJI;DkAUfVY%TRAeC@@$|yK<AdHnV%RVreJzvjF=q1E5`W7;L=dE
zD9KCd`v3?J3WkEa-jpedVy|yXv`~H1OyJ$!!M2@}tW(*Cj9fN>4nzvhiUKg9qIMu<
zFA7+P)7+HDick_WsRCWCWECvELRRevEHR@&VMSv<81F!PVzg|hLaFp1*0C`FtFqEf
zwc+tnHW>@%n8{^=qB@`i;Zjl%)(prXCcst#gOCz6ilF2h0x1(1<fCaAES4F{-6tjD
zj4C0i1BH2~Am55s!A^_iPKg$G5OgC`Q~=8*y(!UZ<P%!SBdIyWZv7-BOXw-=xVJwk
znYj$%qRB8RED)7Ksu!T~INd2HK9vHPP#bC=gxWC0ICN9iGzjOTKgk~f*y~2PxP|oP
z1Zw>xXmB|v07rjPme?E{BTg4bi-PfipETBdP#|Jic#MZ>M{Dfsc{T|bDOSRjLcxM)
zpQK-e>pUe~B1pKv$`d-5NKwKK+ac43A0DPf*tSo5ZV4n5n?>T@&0V(=-MM?2=zHzE
z7Zhw>PsN7S?RW;Xhr5t1@(H=~Pi;abOmCa;BZqopOZ@EE_im#hr>2}|_VGdC*EvVm
z*Eu5|+bZz>xE3jE>cUi`Id!cN=foqsCeXA%01JsahF}zuz#r49+*l{mqTCqpsYQYN
ztkEJP{OfjevoTyHN;u*YNzsckkGMqumlXIBxJJO!o12uDt48~aGV~kmFGgR?K|~2&
z9mJEU%Vts72^<2#MBQPDFmcqy7lkx2E%4_ax*NeCV8hlO+mP&V<W1dZTG373?k+uo
z({9ouQgH58Y6SL6dh1KoXo#{db)?-U#bTgMwF3HkLy&SQJq`Fe(v%vU_oYoWc;QP0
zTa=O76(oR$6jN<e8d9X{EeiBH&O7rnQ-{onCjeEcneDpN3G+rgE0xuDO?Cm=QoDF+
z3vvReU{aGKedXCT=?2d`)a@)W8+w2IN3ODJlmdROH2gQ^OD}+San&y^;KgOXG!riS
zrHaAq1R+J3qaHDl4Wmw&3T!5(GNG`U=)KfvGcgqay-)?hR0yEKXu@||qs>GimTf+I
z{9y+3(ep2lDw<66WMraEJu8`L6Hih6@TK=3o;sOnWA@<R*+DhKCl7tq44--IKN{=g
zEA!D{hdK?kvkOPc(^~bzCr@iRVp`yg1_3{cto>Hi!#ga9RXrTmby^@IX_CDl=d-C7
zcJp6BJ0`3pm?5f&TdPvxG<=u_bEaJ;2Qr{PGpx7C?xA8_Z9KC6G@3nRAF2d*+K}Fq
zG&<!p(&~{0BM2XZznW@<k1GvZ_yN3pRh%R0%%caQ@Y{;?YQn!kh=8f&M?;Y~8Rixx
zTgjQ>WR}W)4`$};jvp=y;VY7A@*}#cM^_IXHG{S<mGoxNmcaQMobzSWY=fpRr^?Rs
zo3M<6FSLy7E`;mdgblcIZh*W1M`#<TdU1hh8rPi#Lr7BvZl_@!chnK2?8Pg|X&Bc9
z1XxxBwqZjWt*Q7-bE?=fYiF8HnZ22&vuxv77u2XM`+3VKtu`g2PTM%H07hvQ#*ou8
zuJfI7Sv2(@iRT120>4em_@!^B;@(s<nzoUKL)%fZCfpPFI8OR@>Ek%*m9NlH)6Z0z
zsAW)9I#9s!^uLhZ<vYPPaGnr4TAdQ2;%*JrlJ=m{;bel$JEcP>XNPpK>RikEb4QSH
z40QTUX#H%R;z65frs|Y~D^hjf^2)G{hSG24CTs8vmn*Gh8nm2k4fw3`#~neMA6~l#
zfY$Qty(#JW!)Fl0(M_L0`3&ni*pRy;r(&e#T<NUjcc8m>9cD1O9HwlW2A^s;G|{d9
zfX@@1@bc?TU&7<B>rLO#-BjAFC3c5(olhOALD$28c9^vLybi$ugr}Fi!Y|Az!J6LT
zv1wQwQ<hT8B~5=c<N<PEovL&ABTWFef5n?ZJ+MXK8IOE(6LM}tO_Ff1r<k=H-gN#h
zg$gFdBhr0txcjjJH0N|27mYF`j42!(E9wAz;Avy5BiL|4nexdR;?q=}urc1O=Z_-P
zxL3V&9Mq=5iH)Wjq8taMBd`NIr_mQLw?J$3v`Z0zE67|M4!3p$oq&6$FcdL8n>e|k
zYnam~vnUy$qs;}q#+Vq`(kXHT1)O1Mm`Z~py~k8fv;n=<n3C9N2=co1;SVqsKy4_k
zWGb85P>#t6kHAbG^Rf}(A+Si;a(G~vkhU9ME~XN+4G$ngByRi=ZVVODMLtgkQ=uF5
z3f1*(corKjrT8Hn3d}BT@whitDsHednCljVrN~rAxf!A+O!b(V<73KoZ7AktsutZ)
z@yl3rx}hG_VZu#si7Q}2Jy;kx=9gwoInnK9loO>_BMV5lf-fZj86n;m0ik?orFcrK
zKauHS0*+rfKWo!DV|ODhDB2JRBn8>fMqn)1P_klUFxb#Va{?c62+Htc2xPRNl?+`e
ztO#dAVvi&t6S{sw6(<{X)UGU`E3uF`x_E|+Ccd2vY}JLq@G#|hGgZh~8K9kbhm155
z9SudBY)Ix$hOEkN187+rQaaDB&{u@+GI_{`3?(P7qM=;?0NMzv#jIMiumes*;I0<w
z7q~(GJ%`FjSM3MJmyM~z6jcf<%y{J%<sa!$P6#!HD;pueGQ~e|4H+Odc;Yfy$Ogk`
z3?&^GWuBx={0$z5D;p<cs`&~rhGNaGpT<JXuAj!9O)Ss@qzw5Ml;UFw0vBZq315jc
z5d_X1Y!6*v3^O;{<R<h>V~o^HXRh5_gnJI37P_g7tH`&B@l#=Bx{V2T!)V5v+>~}>
z3tp$@cwdU;$Bby%yLcZh3ZnUM{z)VUq_kSv`HmoA+NkAf7xg$pl_<L!T1->`6PV%A
z_^4Z?%u~=Z(h_)S8E>X}Xc-xbm8PEqq#TS;SQ(9VxdvQW9UL&TItE&K$X`PYXHtit
zH*Y3&3^BZC3JONsGT~&>3uZTyI;MCH`|w2%wB1bVxWsTM85eL+i~(KOC01dh3Zlmn
zZNaWvoWd*RQd|LZi0rzx(y%gLk3Nno=6b}tGpNKCebRn=Q{ORwsPnggSi2^9OQLAG
zyd_nHf#+2I0*3mPaJsSDHy;%Sc>Oom(8>=rympLs%bUl#p%{SORAvlG_jc1JVHp+%
z<dj#Y9x>w!@`7cyKrmyL5hX1t`J*l_3?-vs?1)cRzM3KHy>i-&ab!$;qr@I-PjLw#
z@T$yaw3DiQ8#lwEK+dv2#@g)Mfs8e~C05vHmC45hrONhuQ?_(KBqtqPzMuhZsB#Jo
zS>u&=$aJN3eo`Ko$@C=LvLQpf(iwUFRLY~FzDgxU#<8_Hnu(J+O(vN(v?9T@X}C-<
zZ5l2Ne9G6112t1cyT*HF&Sx&ke3bMFAw$}esrsQI*&F$#2S_=7yy%z+RavU*n#lZ8
zUh|gad6evW1ZAQZ7JK5hVAd?Iqspsgrc|Zg+Emi1PNK=A(=@{vDuOAgHz>&~Neu1C
znH-$cyefCtXjOh5O%eN1ImniFW+f@x#5*ywm<=_YD$Dsz*|MMwHs~hseWq<8nfge|
z*s`rn8Re!GWJY<@3Jzs@=Twwat~*RQ<+{VRoO0~(EvfwC@2oE!m5FXjDyNEQN-EbC
z#<cQ*M&@~|M5!sIe29<0bUI5=fX<}Mds9;Rl<EdeE7Wrg2B7!M@;B5)3upka4^R<!
zDI7`4NkJ8wfG`pafn{QOpcG)lKqmr@flavE+xdv)2FQd{EH?qiljVRFvXd-FJ*NU%
zunD9Hoh6@0+^K=)e?Lh{3=5Mk5*g%+0QN$)ZPvC<IW`?Pz|-Q>b8ToOl{fmh3r4=H
z*Nu<!ZM`T7bfGSxhBWzS7pV=suagjv0&<eRDbZpFAne$nrPGjy-sE3|jvthPc7j^4
zzK6j%K`TPckl6m0Iwcb%KM34x@|_uKDK>;fu6CU9P2rXX$grlcO+z8N27i<x)Uzq1
zl-ZK4B2^bDF<)>O4T9z9E<)|PCbtjYRSj;P)lNK<W?QEOd}&*!M0{!Llw)aIpM-nq
zHM$Ya>_A+ct_}jm;Wr$hJ+3YbphM-5_zZ1|UAIA8oS`l`tg-b;4$T@CVR0x2z|w0a
z2c39A{7x615W5T*7u6$&c5hvBXt%oL(C)2Ia_r$F_DzDZ^z}u^aF%lbW&LEAG6MHf
zlZD(yBk+~(l!&-(vVJo?w8`FWzztZG>O<ftD6BA1G#RdKWQ#p;Ms^(qz|!e;6hPN$
zs#|6NZf{CX%AC_CW3s{V)nq+3;1jg2a0n!((vqJ9;B=vt7+q3C#|e-wDWU_lP+Me{
zF^#n;70m$M*_6S?%+}@0z-_n;NYUoQ3W3Orl;=6}Ut52+J~8%3$N34~1L5$X@v6z1
z`=&$-w+8ZM1B@-X=!AjOws#mN7HNPG^KsicB@A5KIwithQ=f!^Qw$$%am}T1I&t8n
zbrPOhR{)9=!=Ls#{&D??{FAYFIup6CVKmWzpg10Civ&qQzHd|Nt-){EobEYTADbFP
z9i(U>L%8|9^+=}h8_5zWg$N06%2}2fv{mVg{DM5RFXb6Gnj8&C7){8+G_W2`Mn*%l
zc^kEgz@HnnifO5BgR6+!a%`&zJi1Y<m~c*`77-Wfs8viRwo$8yD|Tr6A`!YNpPpvr
zaMEkU!LU&;1q8@1Pyb7)(+mZ8(OTVxEMBO--Bk0{Smd*nwGZy)MY+g{MEKOJ0EY1<
zF#0zoTD0mxy4ujqjil{1aB#zA-G&Zs*xws#<))E7kXUta7lGWJfL%5560mzyYMaCA
zyaGnZOlTIfNnW8@l#OwtkbSTPMFfk!7E3T?oZ2Y2J{Ak3LdZb0KQf#~ZARO?<icoE
zdKn6<wmCOmkb(#x0~BXtW#^qx>>&zou_q}veKv1WG{u?~wG{t?<}_;?7llm9qo`e~
zYrB)k61?fII(dt7>!(8=(%x|VLgM--sNu!?wA!2<6uFCc=TRhDWgPHiW&9K67XQ=3
z+OAvtN6vb?+ppbJgT5%fcYCrFSIr@B{4xPy8u#3|8id-VV8wmaB$7}sb@KGSf93nl
zU5J&rpPlQA@@%^hYy9X*E{fHLQfw?+AL91NSF@99Uxk!DUB^;Ux;A=9dj|F%+a7uL
z%}7dZ#<j7YeJ{45DC3X@?AK@Cd`a0iU!1+qzWL&Ckiq3B(zTy58Ii4RAE(aqOKUrE
zQlg%FV@=3U*;jzb6yf9gp(Pv7LrI8s)FC{@@-_c{o*QG<Y@?!~2D@g`&)Sk#hRBcY
z%s(=YzOIwAWu*Onon$2b$8FM2?a;h~j(+y-`fDTpq;9`{X06BV_KWelm<go&bMS5+
zN-U@=mB|M$UAz69+vPX?R>}gd)ZpE<U3JO2tFAh*?%I@zWZhj-l})NB=g4xL_t;gG
zF8oHSF^e*!`^2%ww2V@R`d)r6xMJs~-vw9f+|;}9>Gv{qIIF?hrmY2U%GTj558Jk0
zi!~<P0cwuj`li*b{@v=%OkDo6^ws!|3}KGSmz^QxbY*u%e^XcP3fuk%b<?0>N1}^<
zXG9`Q{YuVyZoiUqoV#-WWJv%%g!4%dB>rqHcG)(ZwP1Bw4Az3ZnI*~BN#Cp+C+7KV
z-Ey810#y@y7`nyBQfFi={qem?2=L_UN*w01tTT!gFSjEo)hi~}Z0i*hYi)aX#>5mw
ziZ^5wO-6HV<tB*$B6?S}C*P_)(%17P8|hgi-CB6;c12?na;Yo#p0DPvz)C)>yHfuT
z8(C<YT~JWH$r+5-dnarGANaj#^E1LA3UR4dvj3`H$^LummE)Cm44cH!+g-hKyz-xq
z9xe9h7;YK1SZ)2>Z8S09es0}@xBc9@WhwH_NONW>a=OO`imlt$C-!x3Td$CW-ef`w
zIp}ROA*CD$$b@#Ms7%Rr3{Gy9FkbckVca^ih&${lsI=}|j~v==-O8bjGP<2j>7XGA
zthPSYiPhGpI>oB?vTo%YyZ3ABGjoQQI)xPWYwHxN+IK5wGODbcan5%|o6?5a`)=h-
zMwOK_$Ff^F<K!Y7(jj|l_fwr>EM@M%tFM>213@2MQD`=he9_C`ftO(~gU7(#>TT;5
zBJXYMl?RN=cY>M`-Q_#Mi?S2^DhTmA(&-RAe{_{bO4E3EuRb9(3MX5XB{e>_9?6RV
zNDP|kyVn81LZ@{=;M#F%;Uo8Fr!JJF{Cb(dvYxnKTd$B=_(0CBnCfy<<hCix$zLmg
z0{^xP7S8ZS?kXo?6RE#lT}HqF&<})i-wLxbR21ogxT6=Pk0!egJS~05zX5MdAJXuE
z4cr-5wFn^|u!<Z>3i&9r2x_2o#ZlSJ79CKr7(*L>Vo+TbK@9N6y$Y}b9=Q)$wgW;r
zAR*`%%5fiEAy5o7>Vp>n@H+a?n$C_XX;EPn2ndUp{CUK<c**BS9E_J7gMHlMcwT!8
zOM{L~$A_c>zz5lf)WC@|aLU3xN3?SA1A3!M#?TwuRaPebrG0AK!=sAwmM=M7fjE*=
z#8EbzxRMVfVwb$=+Fkf2XvJh^7gONm=_;;c6X(<{(ZD%1>HJD_MxS~^PaH{f*(NEL
zzKkpx#I*>VB+j2n4RPZ5VUeM9zQ>-QdWz4y#e2n#!7|bVYLwWfed^gaV}i1{AmNK3
zH%ZCiOJPKsSZ7!n3N-bMAYkA_4p#5JEB5$x;@>f*s{(m49+^--uZX6|7hJ`LW!hV>
z@GyY%cc9A}GUdAPXNg3+V2L!e7EKNddetSV0K#p*I$CR8E=fS<^c})adMQwaAWJU=
zv-FArgN>&P{}*90N02IVCcDW;9>Bi~Dyr=fIf*6pQpirfri_`0>*<&DLVU7cQVY|T
zwCW>fBS*%l!E170vL0R7DVN>@7k0}fJs{IG`&BER_w~{56V3RIEqaTU8QB^M7pDJu
zC4roWH=y5o=Hu)A)@_gYuU<wi#E22mEGc>0-?7B+;q_aa9@(+|mX-WwX*p?vH{|yg
z+Mb~jP``EYBM7eF75B%|l>@Co#J3j%?GB;BB`H?s)&+ri_InTf%lYaExZy7B_a6Bd
zyFi%eE4VBNSCM~lArk!VrI55h$g4=jU=4pFWbf7`g3@b?!WlrI?@}NUq}Fe}C2rK@
zyCpfu!VcI!CnZMr5btPFMnDB}{J0bzJuhwu_CxOrF!}mpXoY>emt7DXBaC5EVp$)Z
zC^yVVkL;-T1!d;ZU2{X{tiUb=y7da|x?yN}^aQzM2Ohobh<EIXNA`(?I9voqaKeP~
z=;%Qje&0g9ZYY8Z^#YvYLYaIiG;YCArYJtCr!NBA;FJXM!47z&kv`Y}kD_@VoW_s*
zHxB~s7O7&R4S&S2YdmZpJycNfpjVLAgS^UKaas?mnVve@@!bGGRn&L>jq8VSW%()h
zmWsg&6yQ8T85?DN*3bEsaq8=n9_S*BT*rS`csuLDl06N$tO+;!Vp)#`T8mcjd?D6W
z=>A$YmvOJb1{uh=_?wgiSDBPW83CV*lWGyJq%f#HTSzbglC8`B7x@dpM_P4TGUC{(
z+^+bnwT>>6V1#vzq#)lSch|xUekq`9Aqp$rKd0)7onjgJMPX_}PBoy3G5kBRi!uB=
zq8kF=c#smqH{}8XZ`jSWo_QF#HMC;n#z=`sV~L?RjqJhjD|6|@=#`U<d3eIJFlA;j
zzwkoLqJ@#c>bWQvGk0bT%+ZSd;{~W;c_VniXCOn!3-<z`IbNU^)&tj?sfQWs<wo~y
z13ZWeOsfIs!wVt;Uv$_kkv)|kQf3~os$589jPP>dpfL^0fwX{puKb#y6aWw51)X3N
zCnezm=FO34c2qi<7hC~S&b+`0@aLXb1oi~XIY0YAoRk?0gg|d0#mJQlIQ3){^839h
z=QYs|y`2ndTse7OdHyhJy5JR=>gNJwWICW%qJD!=c_rE-k==zm*_uZSDVy;^ae-Yj
zS<x%Liz$sRlPDvz98q7$iS){Kht-mx`YWRdNU2U#P^MpcCAK3)(*-t)DsHaWFoa?q
zDg^LSEY_lMc<Y9AA*M2;6r}}TN;+KxLQfzywF)OQd(~MKuJtn-Ops2M)ddpUIu_F_
z|6Fyrm2}!!pqZ*T6L_5!>yYB>iF3QB0lUC(8Ia|bZH^RSuWa+MS~^434kabKz<Qav
z?1)}tRl=wWkt>kNz23AlI*tg><Z>WddnK257NxG_@_`uwg9Dk`UXaF2=k_hP9CtyF
zJ%w@@-i5D$ta0y3bnTQ4S(8~Q(pAB*0pHwZUuF`!_fw3c0?>7ZAZ*K3DiL8@-jxT4
znj?#XMFQ~qu}CR+C}rY`z-zvGD7V~k)>m#hl4%zO!DbCu_FlQ=nNI7KT#hQBUdiPS
zfeB3R=2=eAW$I=WmkZasq0Wp8`g?_O<st}i%7IAem09jM8!Efp2UxBP3Z8!N)VWZC
z^$5}cft~m*)<{<ZA{?mRhdu>Opbse!@Ljr~*Bfk?-V4Hlo%pG2Va=XY<z0yH4Q@9V
zxO^LDw7^Wb!MsbcgPGH-#%P0Y%7tLxhN&B2Ja7%js^10|KQuxbI$hOG+u+jkI2nyS
zHb|2Y7l2v7p|aZCj<9krQZgZ9zg$574M4K4pvZ>AP*%EG2Tmf=de?aap9JgUB!#_*
z^D-f2JcABaUiPk2XiRnEfOtYYXk`x_ORQnGNMOv(9vaN8Ui^#P0=nrDF7N%JS`Ry?
ztJEz6!aV9aFc{1$MIXUnu5!5%4HhC+S^Kb3yYJ9I>;_IDU%@Mte<ISzS(k#<yxj{g
z2q%H(Z{XT+9d&>*LYXGwAH|+VOetf<T!n)fE9NdF4VW>VZkQuT?8dR+An^Q=i7vF<
zB*2pkEnvc=<tq8XTI?=QPJ&3We$`7jQ(kxiuv)U}RZ_AKmJlXUS3MGfUad-6L|MYZ
zvx>=)=vmQCa2?mFZdlmsR5v1momdcPQ(@9XU9aRWY?xk92A8Q1c0}g3dSM%&PS>$W
zgapG;phDEdCv#PEX|QU#Q%{4H61B+^)y&n4b4ZmfN}5G`#J@RyC<!jb?n1<v(+SqD
z84aSDP4(b(@=$cozs6+%m)Vh|xD9-0Dsg(b6Mp1^n(unk0G-a|XggY(7~Pemj#}2P
znB|6CR9C^BhPngpdK=wvi@9$QdqcJ5vYo=BYvtyipJ=6^2qc;4f9|?zP{`d2G2(9O
zMl{8yUPK#6!=4wa#LZQQ;o;_@>y37E%~cd3U=aOQiM>~XCyx9Xh$T#L?z+K{IO>Yu
zKH80koX4dGYZ}Y@y@dYgD(_B&NEe*NeUsmp=AD~bAWjG(bk{|AKR7&OJ-NAqm6pml
zLU$?O54W&PEDyIZ@5_ffRyFGv>A@th-mq%93Qa{sVGJn$d#`_iueW3Y20$+~4%B;L
zX~m=@U+Jcau)#BbNSLfVl?6}p@Kn|<{qSVoDK|zGG2snanqI&k5AI+U-&&L#<00j)
zzsX?DMdBZUmrn|-F8}8Nb9c&vIi!^J6R;maiXnFz=r&4znOM9gCKn}n{1BZt87#<s
z7#2S%aeUB{-H~}o%8{hxxWN2R-nm8Lm8%i}X|z-OScDrNPw?q8)vdif@#)+W9hSyV
z%FKPE;xXs-*#cKou;9GKhN6%S;?<)$I+*!rjxjpp`NuX-KUxbBm3RC?!iqqGIsh+s
z%B@MFSA((olZ17Ok0U9r+D+`o@LSjLI7ieT*%;Bh_$$i94}qarBDHFcSP~jfJ}CWT
zr8DAdYhNW~sC(0{60#JacKs@3G@X1<Ht9Wrz*T}kw?~X1&iErf6a}LBm7wma&}d@;
z_WhHh9h{uQQ~Q$wr9s=gH=TKT6!hM7<_XFE8hg9z2t-PL?_EbAq3t_6Vb-*ixQZBc
zD#7>HhRt7xIU~I4z|RP;&o*xx&S&bff%BG?19Z2rxIkS$J>Pn+Y$sME(4BRtY(ZUP
zEN#FlyDwEg2uieJ^wy1uiVDYet#;Zybn&t@gDz*5bEx~9@mhy_6~o{bjFNB84Opcy
z+K*IOz&vQ{&@8fuM3*)MX`ordRVt%P83OZC(Uo44r83wFjB!`5{FT8z5OE*UpU9Sx
zp6OD=Slq*z*~a=GrM<2CAnsKs<B~dcvQEZDeJWbF)L?SumKF?=aw)Xr3C&y5R=aN+
zEf%OWTJQkzzd=EpeRv=uo6?1X#xgFYa%Yhj7EFGr42;zFBa6kPs!!P%RB8uWxf&{Q
z0gHx8St4?4dtWectKJ|eeN)erj^Ir`Vmbmd@yy8?j(YiEhC?qOl)A}>3<Q15dSKxz
zx^biW)&I}h+w|O;<Jw{K=U1Fz-$7SIeUX|Puni=Gz;<U8WMacNKu|sK4U8oJK3n8k
zYws#|y{GEbMFHJMe77V@k0esmBDwAtSLUn5FRq+?iywS&ApGWqM}CULTKrg{T3DgL
z3%>82ng0lPNVrXnLjJw)uZhsY%@gczZtj7S<K|qAZsX!oJ_UfZCR2G{0&e~M6uYAv
z-r5JCanJi=KM?leefb}V79j({*h5`m{$<S&3~YQ@GjO!*QmqIf0V*pg;P`FKfK6)b
zg*yBJYhZTwmSF`eAI6M#!mLfJk7;tLL>o%Cf|3x*lF>A^yaqG8>e##mw~sb!DYPun
z9D39$P7GmlM@DohOBuh<Q7wL-qgwntFo;XFaiox#%1t^D_G>E4<*4{KWwjfH@A@{C
zsB{3$HAno!RB+JAhtd)vc+UhvnLw_$k&!^IiBzUHpWjd&EEFU|pM#~UAzAIXUC|^u
z3YhiKZVD1>)lZh{kP}>xX`LO2(=><tHO94sRNhlsK@_ue&<Zk?sn9<x$OCw)OTlcp
z?9TiuRpJK;nVk7SpaYC|l0smtrXsQ?psSTp9TLQGCwu2Sb==8@@+3t%d_0r!U<X2U
zO<~~&LUheaf?7eu<~s!{Z6aezccV>24+VoZk->+>L7T`sH!7lU&5zuu2&XnHIcntN
znSlNTdga?kjTp$LsldCJGHarA>H^2~epb1_tvu@9=~9F5BLgL0e7Pyca39d~&Y-<S
zFF+%>F1jY$RSPMof{TMFrAw)At&=dSRBJ1^IFu<c0#BTJ_8LGNy<f&IAgkBQ7zaob
zIsc4@J&lkimcgj^BcpEJ@<OR5U%CB`>0u8m`4}f(>HGlDnq6ldkVUgAV;|x$&aRWK
zygHwHz(h5i7VmVbG{|&adCtJIr>-l7$a<1g6MFF49_kAkhXQ_IO5g>ST`fH9%Jx$r
ztohEK3eV4cA4Vk@Y`S#&g9kMRHLoniUhS|eteJPNRDiOkf~F)W3(w;4Q{uaM4KegA
z&QBE>qY}c=!qYeZKK1hcfK(60?;Ojuruc$CXaahtMMa2D!2q7jDqS<Doae0-G64Us
z)xpzcB2m&Ce=r-~K;9sQNt=)&^iNc&Jv9*(^$ms~)@&-B>1=$xe`iVO>pd|Rnb?~!
z43vxA@lC103+WMHgKzhQwlTqYVn4vj`oM-TLHX>`jV4V-O76f+=ZP`_C#lEK5w8$#
zS#B7M6Cu#l2$vBzI1{r^gfv1f_r%PAc|x=fF&a}Ct)o_m(K=}55VoU_0~CkJq;auk
z)3{47XlxJ-RE=5_WN3YRXS|=viIUK=RN<Ao@{$VIrBvvKg<@0>CSq(&C6t*=k~S5b
zY9jm8R34j&BvDgtpMZi*#k{&uuvaOQy(8JtRQ?}Ayrx`DCsGdb|BF(6OoC~N^O|&P
zy&X&i@0yjpXDVqE;apSMpD?H=`Q@a*P^A=AgmX=$!s3KYMjM+j@jWxsqD^?IPGxMX
zFEtgyj5w}K!EQp9)M=gaKG#T2i-|cLDrQ;=MD&%KKMCzJEdFN_+GSe)SmU{DioFZ%
zl7llgPOiH}Lc+-iZJ9Ji%5NGwRIB-C;kjm`{*8TK0L+><WI}lnvP3K?q|qcatWg|Y
zN});hI&et^C)G;tA8^t|%Bmf$Uw9GlsCG}>1g&Cxgp+QKk8skh@!<`kY0*<YToRT&
zF=Yw4rHq<w;bUQ~HI{w>;e7<Bx+G2j9w_9tPsz;V_h(_FCcXb3$^6-Ldeca%xQi1x
zGG^17gzhpK&=G*6BvE&|lvT2-W~%U5Lm?R^0%oP8#!nC}n@YgXgq=uH_*oc}OTkye
zC1WVErvM>TQ-0Qc=u$92xIvA>H|2>u2jghU=qs9P6G-r*KLe%0cf&-$%jhN4T7KPL
z2VT&AE_}nH&R2iNa5QnaXOBa01n=gTf&osXyc~)il9q$krL+DlbHh+XSz0Mx6qL$U
zfmhUP8cBbL`gb`gP@St+{t>hi^G%<+cv0ZfqE9;MMZqUgKE02S;Fxrx;B9acot5_m
zuud-uBA4(wJ{aJ)%zNo@f>LoOK-EO(l%eo1e2yL=y$NQ}5mQsW!QG^mM=Nb!t-zgs
z_}IXFJc42Xue9Z%17r8|;lo42`lWE*;2$SnpgHAVq<N!{5gvT;Qt<XV;`2yeSJ4wa
zikcQ6ylCs)KLse`F1QxgYPu+A37%@_7bQM0%mqB@aF`tC{c^5j6j=#|>lkHV0@o5?
zEP@Ik{eV<%b$MtaD;4b!MM;l30w5*>2Dr3^g$Nqg;K8AFw5qeTY_davj4q+t8R`lq
zOd4N`RFkHIlTP<8y_HV(F3G(n!V|b@<mDBJPe=!PmzZ7)%{ERh{N-JFQZ6ao*Cd${
zcysLcC&k*|IxiMINDsoLUCK(U8Ycp0uL4v}y1H+^!OsPkqWxYDo;JR*wHlmWoMI0S
zMO%jg-O)Fm941V~*I;=#N(58c5(RKS-%Ha6_w!wC;OyR0AM${=sqYB?A_W?o^fTYu
z?g(LfDQvf9cj&O$a68(BW?f48x6<}8%Ts()QqWOc;nSYE;fJ(!huM}TOg3G@x1m&1
zr0ovq-9zJdk?I@j!Xkfg+EFLs3y&oo4MB*Xp|Elj&d6hhMhNk;q?f@xd92_VvD*l0
zyd-$<EvaFE_Kn4dxrxwlWARaK=G5a!BG;<C!nY;|u{4%M#-8=;fysevTDo5BNl*Tz
z$w{Bp#jC`gaOT&w8UVtvrX~i8O`QleM)<KJ-^nfCBSz5-CsJpO^<FLu4)t6v&n)lh
zv9w?i^FrxbCLP6>P7^wcFW!0?0(`8dxy)^@fCjf*gKV0ANW9fhs%R2|!Ox9dFMPm+
z=eVBMCnB7Wsrza^6Y$|L2Z)0~Z`GGlp*47Rd=TEP6gN^jHVjTfZ?tnWy2WNYI8KBl
zo4aCLY<+q7nk#a}+zM{NZ~qQ%!AcBnF}0VD;%ZD>P&cDnyq654Ta1rt72HC%OT_sb
zfNi3o3U8qcr8m4c=fCkyq(fBF)S>sH>2!v~bI>fuc0Kh>I=3su)-18ZSSJ%0&@tut
zHXZR&@Owkp70DTRzUy&i((_%fCzo<hWnrr)k{FB;AC)pbjepds2r#Zny@JS)FZdhl
zQDPSKlt6_d<f_m+!=<dkJ7A3hojUYhFyU1{)<>O+lruj%sz^CfG90<`hMWs7sbb{}
z4T({P#z!><@_E-<)lmPaR+H5~swIp4qgJtKAC=NpF%))rIztV;m%~&fBvxajA+85T
z8v0ldd4%@!QKiC69aX8IO%g4RGquM@ox1SA;b-3AD46wRoB(+hCFLBUiHf2aQ#iF8
zr>^{-E@fr;U8#80u>gH@(4zZX3PWPOYcV7iYi%$nJ;QM@cV0iAiDW6G<HdX;HS|zY
z*GtKRLWyA~V;6MYCLHhdL#}fZ;S4$p`R$bzcR~>#U5W()E@WggPL_jVNd>PX-k3yl
zGAe=`3?~v|57;%IBCW)_y(?7!y!fb8q2Q=B)IDOnO_UCgsbTNUjyn`%<G(0~FNYD~
zMuq756G?K0?e{{B8qfNu!{~Rcli%ZQegqDCDCzn$ogx0DA|RCMU`hdXB<rFxn&5k*
zBS!bI_fAg%W&MM@nz;VKO--C>JtK0U>1yDN9B5jbkYdc~FrA?Ur8Ih#xa5Gt8E>l|
zV^=iEe?JvjQdb2AvuLtLI|Bzc85Mv~A8(tSXDq?yAC)S)<o>9`Sd#EbonC>U+R_9=
zV{h+M8?v*#k8OkwXp_+Ad827GNogc+8gG+YK*TC1$;35!yzOUE5QiaO{)wO=gyn*g
z%xFt8PDj(0Oc*|}zz+$_h#3B$5LH~1JCB#L)D^>;a^1r`kN{@&bw_w9@39xfKgNE4
zeJNa9cmz*KwFY0|YN>a95I7r_CC&sQ<y<T`rvlOO-}XHuw(4iGlp~TA=YvAy0bCTi
zqD_2Ku+(5U=?ZJ{NuiM?>VxznSt^QTDbj3R%KBBA22*6~>Wt^{NzlY(4BPfGH7kMs
z?^#HudYpGLy#?OWkRM+`P2Lp$7;{BQb^vkS6lq0Bo7Q8047n&0a8U_oqAp6$n=n4u
z%@tHuFqWK`&j0l7KRovB{`W8c=Qo27=i<=`jTAECU;gX2e}3+^YOk64_5Z)B|C_%(
zuk!1^zeZ(4Ti@1wnD4Ll?Azb|{`^n>{MYu^_Uh|z|NQ*#fBD-#+4R5s%YXl`|MY+S
z?SFp$?cbiet5-ySwYlx=b{l`)diM5j|MA~{`){v$xAFSl|MK@6ayA#$x{*@8{XOF&
z-EUUq8rtvV_Byf6ueklo|N5W*?|=H+|5aQDni}5MtN+(ZX&&<>XZ|6Zy|N^e%MOdm
z4{!-+<`-Q4Z~x1`6PNQ&<-AikPPhH~hqu?P+COBH5m?FP09x>q%m1-buXUkHz|?$Q
z3Fwe@1B7QKl#w{?56nmT41c-C{@p*V^_Tzt^UvSz%xIY%E;HNr%f0@wrkU@5I5iW3
ziKD!)H}7TlHN*d~z0z40uKBM9OCMRf_y5CrV>M**zI+rLO6~ne*8A%QHru|-@;>$a
z<HhvX*U6^U^vB1S8sB?#PyoLg+e9QDRhkOT^JTS4T=}jQcoq7x5)hd0TFOQ6Wi^~R
zn*O&-!XKIb*XiryLI<yP{rGQ8|Bp{TF<bA^3B>i~=#WV3T}_#_zN$tLkE)UIoobNJ
z?`q1E`DL{|u@7PWoqzbW*XmEm>~F08_GecAfN#ZnY;v~va%`jhVkx8iol1zb^R8v%
zcP!<r{b4C1HQ(7EOZhjeK^@lzAmNXRvKQUlB2rap|9A&{Yd`)0=&1f4-5$SVDR=l>
zysOC_<I8Hm{=KUS4ESX=>z`+26~C^+yqTJQCDQzZJK!aMhp&uhwts8-|I7|R>_rU@
z<?oCRk0S3{+kVGVwmE;flu7tbwSq`~RO|7vlz+1tJP+TW!0cmb{ox&8*Ff=)520^=
zLIwbGp}`4)@zvPi6t7B(_xV+&d{9%B-M%mA$FJo4_#J0s`7pkZo&8=;e|XiucBlWw
zqW@D$&-vx*J-=h^e&~TD*jEP?-X!1EM4&zD56sAYE1T;jFTSlCqvN*}ksq3pw41%z
zMDfe9!PM}sB*K@~%*rV6uJ@*VT@i5XkBXvvT@j#`kBXxFz-O@QTC`uM!TI_-{J>XW
z^4kwiMfrM&u<w0T6y@uRH)qgiHI%=s)Dg|_UF}Wzx*||<9~DLUfiKY$`~2M<@ne#a
zA*nui73J$e?q6OJ|NiYw`MP4H{`gUkgs-b1lIll2QNFBrZS9}kvHSyHB2)atSZ99q
zC4NXn90;@b!KWx+4-bJcJ}Qdxbw#A!{-`L**A?Ne^iffiuPau<@{f8X{K&Vs7SvK!
zzWf$HCOUyU{}6<td^yB>r=7nzgx{2}D<V?Dr|2c+>xzgt^-)ojuPes*tdyl6_zwBr
z^Zh;XLrNq3VLrGN<;$U6!_F@jnh0N4Lr}nvdZK(?5q{(!6-D{FBJve{R21b$RHuti
z+uz+2Kc+h^I17I8D#~}3_Am9&U+S1YfBSXAzj@H*r!adTA8At);g6{|ubC=ymu0@D
z-!Qn$A34g&=qN0~J<9WqM3nE1uqW*Fqh1Go`0HvFk@}+=LsWlRt)2bL-az<XHCj0F
z722nT^N)XocEQ`fq1lW-@evw8S0BUM=WBV2ia-Z`R1{wD>x#4gy2sgnSC2h@-D8j6
z)gwR%?{6Vg!Vi9o>z?!*AEW=7kAe8{A0uq`)ioOxPen$1*CXLO)ezC|UCrn3>8;{F
zd{o=^m7$u|5S4~s;V4SY4}FAlL72bw2=e3K;2;RldvIg^p1~on;k%j=9e!D@{3t)F
zHUG+*g=%pM{Gw_ke5abs!1V><N36iFakWw_<6qedOfHd-={-1Qlm2pWYkX8$<9k2P
z_^<B@2nYLRmA*eJq+|1!KZl_hbNyi_{^K)!QC0tn)<$sXhYw>I6bWAs%n{7sT`dUb
z`?8wbuX=O)J-s1)`@5R*xqn#=frB{zEdSsa@Eh{$H@?81IPrb(IgNuGUp}X?8sL5J
zYQp<{Sq<*v?`m!Sj@~vxGpHH~->C+OBfkL4Kllaqg?atPY4ax(puNYh2DiU_h+{Qm
zIeb@B+QToa{aWSSzf0rYeaPrh)%y4ySAmUijQRrY6G8OHzre*){>C2oQ}=)m%M2-B
zUYG#*`>6P){J^d7!h-99ZuYNiwX$9~un$&0NZ+yL{$grS{1HR-b=BE;wffQ$^dkou
zGp&5E`a$}xh4fbo;DhudhT!YE_q#^=L(3I_-Ou&<CVg$#LpspUs&CSd824`UM*BS@
z-9KViY7K9sZ^P1?^c`Eq{)Nrq@88~(A2FU?&zIjd&iEnwS$TbYa{DHI#}pR7UJM_k
zA9~fBKdtfoQ|L$3JsOZcnSGPKV?F=1B>B~${qwi~q4nQ0?i}-9@96J4e2q13?#BAq
zzaIAgcSrs448MOm(Zj~8_H`?eQ2NXNtLga)mU>^i|DWHKD*<$Sij}(<!eJ)@`a7Hu
zHvqfC>-G@!TSQ<7wE9wNh5?bjgt~SC$Q;f{H2@taq2U+Tqb{6CWxOPWmvc`PL@b<6
z#gTqm;dK6jpM1C?OCeBNI6VoF12dfNAjkk2N+lZUWfM+arBXmXNda5sniEJ+8s+>H
zP7hNA2?%C1O(1EwQivg}Kqv!hOw26f(Z$LFx?7mq@-~Tu5iADr#Es-qI(|_TOB8m+
zLI@}31i=zQ7Lb6mOUT<j3ThQjp9Vx~2syhaGCa$u;h6j(z8rkOU|BgfL!R*A_`FO?
zfozfC^ku0i6HijmYhZ5a!<KO=Lb+~%au0_yEMnw`D^3pLyS*s4a4;&Ocq-OgI2|q!
zHY1!@l|aDYkT3pe_#kwzPM~l&)0!Y)M>u0EoCcm6-4IR#Pjt*b2EJMqE>H5&KgCOI
zy4f5c{$ta@>KLpE^wfqELTm>8I8{J*b%?(RRY<mC)9>Tdt5s|uq>%CRmeE~Z`!_GE
zh%a{unDsMi3{n3s{&|msK_?gq;3XGA$(zpvZ}QIrP$)LdN0kONZ6|2(ZCycw#UH~+
z9Jmc$3OHWim}ojgsf$hL20%T6sj0tZ(7M=4xdxnDFqt*74urxGoSlXI+b)LSKYohw
zC^zzK%)w8AM{nwZETC&gSM(Hv`%Neo!SM=*a4EINPdT~;f)kvm4?;hT6Zj}ZAtIAO
z?7_pd9%y58yOyg^5>^#!g6Lj&or|)F2H_SSTUlirgpeW^TuSu{zjVt{DQ`OB2*sAW
z(<Kf32o<tdy2}`h%9p|xF;`7&7$$4cLCP9rje;Ls%AK&KWUO%9ig#l8R;Sbx>#(mn
z$zmxHa2v0Z(#<0u>ZPz72&koK?w6FSV}%-l1X_Voa;99euyn+tGrUzqs3%EecEWn7
zjM?xbh~?zIS~ZLpa%g$xCPuKmSX<pf4lU(nNA$f|TfLSjT5$7vl2W5nPF=*qdQniy
zWwn<2xpFu30Aoz~5KCF5TS@OrnV4zM61#AWMY-wWN%*2XC>G~RY~4zFE#=Tf`q@y-
z2SXx>OMzGGCDmA_I)VgS6Q$dzvTnmK@=|<(kkKMyDLZ?E1Y1KLLyRqD_^y~~m%wh}
zR9V(yLkiniO4SUf%}YVg2jf#}VT5>#C1H9=D+$Pcj3l<9*b|1ZaR8`5SHG81?N+S0
zSjtFk2uc}J&kcEOFNF<5qOGQeA<`C8Ut1O6>}l|Sy(Ih@Uzo-#L#EqHVZR;h<FVjL
zQqJ}~?56aWm^ujnXAfm|Fq>7v01=col#js>W-uz<OqTEJQiO|3$k|u=1v7}KcPa&g
z_d^J~Z-|K)$arALL>o$PU<iYFDLLpTNyR^P;Mc9}Rod#gq+}plz%A$IP;vmX$_gFK
z1Yni|3!(K55fDRZsSIY5U@j{|OvI>|88y0k*9&2#4G}9tVKgqKSeu%G0CSVRnU|E4
ztF-lqmKlt3ZwRLtifVr;HMN5=+6(~}V`{f%n9fiZGlR=}OlZ7@@SmY@^Ow?drUpv&
zF{sX7O0lLC-v~q+3<__^p&RqP4dJ05v!is`qE2fFbs9=$XNbsnDeRXrP!Zp)Lk241
z`=#`18K(*&vBu<|Yq2R3vLXCH%%-j(5|#GP`p6Q_vW^Q`hIhZEI@=XF<dTy2anxje
zqflBytE9X!jyRt<{**w`kQq3}L8;!xLj6D-4rslWEe3-m8j=Rb2(b>4sQi$I*bkww
z?3YqcaxCS(QCN0Eh~QvYc0=}@7)l-wqw1xw<JySNC9&s?(Mf(I!11NvjOmbhW2>QR
z@(IOPzoff)lp53!Q!*6%gkA~36r+Y<&rumjACPi|B1x%bz>ZK7Q$rNWP`DIBir!E*
zRO<-b9*Ur1$b1}Qvg?B}=|JcQ-(dd4Uu;wvT&1VR$e1gJnA@Q=um;d>3~Jbh3_q8W
zX#p+?*S0|w`BHM(bk)M;Z7^4aA+XA&ER=Kigu=2IvI2#i<P3icMLNHfnqX5`J*U{D
zDx=RBhMqcRSn4+zk3sbt$%R6hgP%*vAvN{PXJrUl1gg1ZoFs@`AIgSoWm<cZgk4-2
zhmwMW0ii%czDhRAq;V<WFXcz{BdLM#{L!UkBP35KY>Xkye+W`z$XpZ^%DfudS!B<J
zqr4RKT>9!I@S8wPc2>X$rI%NdgHTj+Ll)>@s_aY1kJz<q5w_?>DW)z9(x!2&MBic)
z60%F1#_<#iS8gN7*+wzBl75XGw3k9YAs!W-+z_QHx{~D>5@ke}mYq0*=+d!~e<Lu~
zgYP}n@xlJ?(z=oMBPlh@NGThNU~Wh#5?yk6B3eW+WR7JZtI$iLA@NBl9=Rc1Q)E1H
zLoSu5ki$7XL{bgrnzs_jq4?wmnSCi_4HB`J?s>(=ghW)>azo;$=+dH*lr_4vXk@Ut
zlnO6&DK*`u?njQ%)cL>|wY{MMh44B?Eh!MU+~&%ElM%=`J7NSf&ZrI}?AayooI&!a
zKooPUl%Ziqe3a!g>}U?kIvPfE@nfY+h9a9AVzPxvu}0FXKxA`6QqEguPp@qg7U~A~
zK9in}EMH;Lv!R2BA_m!{8PcR6r`{g6#Yun@8i@@#-2#5)HtVkxIf%g;MvWN=?@M4G
z5L~vz8bp_sY3V6a&h1jaxV9lUk>M&6ik5D;?p#XePm--mLEm|43X|rID1f1WMuyy2
zmx8@ou>>Q-89gA>0HjqT0Abir!&dxj@8aed$c%W$i0fr243Z(E)}?Sz5PuA^ehJks
zyGD%H$e`=DSnPLo4B2O01A_1~Y3CIK_7Y&@PP}lkOYMBYn5pnfmr`q^qg3lc>iL>a
z7TGJ_6HL1K!h?cIHDCFpU{cH%o)j3!zeqK}`a#J_lhTdomY0I#0@jnTrdE;EI26j=
zV1;>6vh)&>O^P`}$A-c`8EiU9fp}gJl8W<wDY+(^l=W3|vPo4(e9vfA!AsajlRz(%
zRWKC1t;<GLg@|m@uopyRa~`D?9ySzA$`Bs*Qg8$y+gJ#)Xvmx%3i^I2wT;>)8z}%A
z&Ca*HQHO)C*^4H9d$%kh2-B;G`J!&U8>Wk9WviTJfiUscBl(u75O3&zmx3b#`O2a}
zBd$=h(P&=2gj^g=>hFfhzbSa>C1tlm&34S%K(mlyiXv|?E=Qx0`7s!vFNvL}7;93Y
zH*R+g`Y|H#h62xDO5UlPL@MI;Mw7yfjAx<1S(j2hQ`b$~d^D3Pxna?7QgxBvJ(?`i
z8=|Z=O#?((nX(^{a)PB0Z-}x+qcmWjmq3O$V2Vcu2!uhtB=+uE!gkwrd-Fr>cssC<
zGC$`N%ku$#G`zyNqI}sdjrLO5a4Nli7<bc<W9{)H1$oyW{ZK*PA)F;U5Aa_V?%$vr
z-@(;x_ap5XZ&iL|v&M6lD>s1Q#p_ZkfrVAtwoAa_u@44#Q;->wxcQOU8Y%5B1syx&
z;U%Hx41ns2PG$&znv}+0)ZnCNyMf!Kg@AD0eq@)fc%_%Xb`0!FZALyg&#-1zu}Cj-
z61*9V)RolWmWw&5$X?RU<zsJnboHZzVTOm<7YU{O<`T?^F?uO=viQJYWSRDX)g{X`
zVufA`M>8?q+VFUncBBu#6c_<r(bTLSw=aRU7TA%F><cT9mS$i0BnoqQV<_DsjsV|S
zb22>R5&u%y&(6t}*_mN9ogvx`P=QO}JZy{zN;SX*u1pP9F*5xq9I7F@r3V%33TBxE
zoGgg!=pmK3Vpcd_x$iatyuuak%_=NoQWna+>X4VZUb}KSSOrsjlEi5^U{887A|-k-
z^q)n`68c5R!%Hc35b+H?WQ#_+flEQp2u$co3}NLE>;NQObr2EyE-43uKzknAorofL
zvD#oZ3d&7JVL81da@)b2uDH>`oD}Ei!i3imS8h%oZ<}>=OusbesCDik%^8XLE(IGH
z(eN&XCq?G#y9D-KV)jzd_rMsXTt^8?4=UG>;g25L#Z~_j*ms#hFNIyr8WlC^z-#%X
zu&aeZ4V3Qhr6prlU3n`EQ}2n`c|a*<r6$J)uN|f2Q(7{<u7?!mibVJ%i9JJTDo~Rl
zpNK2_g@tE{y*gGYrrog&n)>w|ob1<F;2u(?u>qXPGhVweAPilyIUo&{F2kZq<O<@?
zrSw*QmgkaC%;hNj)TNZK0kz&bI^5&k1%jl64nV|>beE0#qz>XP6E#9jx-xfMN-^&U
z<7hy|yUQwlEK4}|5z_Kf*iC%^7xKyu(zLlt9maX@!ctwz$}(AjY;#$k4`iD&AiJHB
zB{DX^3iM;->~WXv8RE)aw&xOQPm<X2sL7S-`7i<vHEm=Ja>1%DrG_(c1fIIdxli>y
zf2vm5GvnMy^*#`fgkn7zQmK~LP_<RuNvNI$?xaT}n5sK%(HRM&_>(dEK>j(D?Tn4#
zE>-(%Ouq#4*>xjGQsa+`V;QFr`Snt82$sU;ZtB^gQaY^DQ2SiaD}!q2PK_Pv<0Y``
z%UfeA5JQ|dcWLKWhs`oJFS0edOE*7(FVLt`mOkxUYWIP}6avc-NY|A%#h{k^mht+W
zGVD7tseJ3LWubWQ4FXe%RXRfWx{z3xl1p_99&$-}3~XxWmvR@wrf%MmZp(MD<5F)N
zs{U(DT~e-v9r!_w(A9I#66$xbN-eu1P2}?;p_nXe@dUxRx0r%p6y&PoTIdzC-~lPu
z<K8IUMwfVkP~5ascf?@66n2d4Q<pR`trOfY^*k}H3#FRTsg6n{CSI%fN|CoG{#{&f
z%U()x0adxTl4g6T!(A36-$OIFv4psXJF>_5?rL~r7CRd*d&J|LR_G3+h3~HMIwrBJ
z`xI(|W_3i`_H7y<E`i(BZe0SmsoB69p+4PVv2oZao+8x}E>*b0?sLoUN*k5P&B651
z4*gtGGPr1n?p8NtU(lB?;qoVdR!5w2UuA~wh6}kb8lo?$-0WzG?nsX5i-zcKmTq|L
z7J_XB4Iv$=GB0VNOlLlJQ<uCI>IIj)6&j)8mba*2cf^SDMFqQ;-7zT~V<}yivQW-*
z;S$(+$B4LjZDawb4)Sxla_D4WqdWa;zlR73$;3KIsX=aZT;g$Qdn1bdrJ&mhalf|u
zhJ0L0eM3O5r7@>~TuU97boHfMb%&YS*J4)-V_NEIVE|L@E(~DO&U{HZ27;h3p~f&Z
zDhSav*%bullG5GN;_t$Ab-W4qqR!p%Zs2RECy2~7)Dx_nz6QH0k-3Hj<yZ~_rCJJI
z9YbEOE@5Gim`Wei@f30?>^bmNIy(-Gu`|U?NBUV`rdlN=1?#$m;*Pp@M+|3Q{CkPR
zMcumhR;3yql9T$PiMk`lgv<G&BVFmGP-Nh7%QGp_E#*{CnyD`(r<#DS-b;J%dDOGz
zHO1#q&vol?m2wsZ`098Byc7(!!xdM)2p#E5eY$Ev1Tu|LN4jL6u8wPoINqtAA{8&x
zq&r?dU5Sl)pRdwZKM;6KbJRN`;QQPfGeqFr>YCogRK|NHLcIibTpIJ^bFt-x5iB*F
zq7qQBj*Ka97v+wp>Pvy_L7o*CsOwVb=*(8&=S<EZ7$+6!rz7e2C2>+98K(p_lBl{8
zEM3aVGJ8f^MxO&+<F+@4`iAhFL(>A`DcDyp*nn4T$On}AiXH93I6Ax9Js1G@VP?kh
zY2x*eHxs)Mok-l&k)_pz>dNSI$s3gDOX$@sj2Ioj4WG1oUrMb)+Pync+g}R0M)Dt@
zvU~SYRoF8`=WOg5SHel7_od{QA4feKZeru8Ygl&#0PDzT<U^YC=x{NY<~&B0#2Uoj
zkdizg_6C*Y0iicS>_O-aR!D27a!qx>g)W7h;ZCURQyn0qOJT<VB3%-ChD}D`txKu#
zI7&IyW2@(tB}%ffFcyj90RcFqZ3EHeL&`JKTY15@s-cu+V|`RgSvHn9gDe{hrCe`A
zs`H>6BSfp$Fn!Qo-2r6tL3?!v*zHo-aUPMEz;hm$xfdx*5Mx4Yb>sx|K_whMi#~=r
zj-T=a4)u$>-;h?0CFMg}IhLIdY14y}Oo**MTb58|;)!9<R(&bO3vAUr6Q?;>dl71;
zrEg>Nx!_tI8`PDFt53+XVG=vF(S0=ajk_IVcXyybF98z+q^JYZ)u(ZUQrl<G68nX*
zv{R@~2*fURe3n4GhuDMiK@~PxPYzwG_r#Nfuw0jttO6YP6e)S_p`IWPkrb@Yng3=l
z5Qbga_@p!xma8KzpLc2FNJs3-CDvz2!!BhUGVSpWZ5-K&y-OLNB`}?cuS>{<(4~;4
zr1ZWeDUh?+m5!{>ouz63Zy3UWF(UY-bp9j{s=nS0)ZXb*tD!o$AYL8n#ig)e$3fMp
zXeZ3vmCvjLi0*xA+8{2w6mKBfy+B?yLdeT5&3l%-R9>`8n5c!W@fgylOc<4Z#QRX^
zcnlFTtOK-vDP$QEGjU&i6+GL!^kd{P_AdQ+K^S(*Whk(hfKy|YEPSnm>?40oOLm8w
zgDcV6rPLxY^=dh>-22ZZ)U4H?J0`5D(OwfKT^jnl3+vU(8RRuMlP(O05ht3fm*0sS
z?b4T!Q)owH!<&NDx2v0w3#Qd^S#k@u32CNGZXI_n2YUa0y9JSEp`NQ%_KGW=kXs$T
zJvST-`T^SbQrJ=5=uGPL!i~;c-9QWq?$vS0ecYrR!^z1_%JK3nVOzsX%1xRvlGJ)#
z7$1;|;iaj9m@{h6tE8Msd0r55Ky&ql>%=9nZ^${N!e9m;x23sCtEWllUa)%F)D<62
zX>L%l;j-o?9lN~R+@|`$4bPOTup=q53*gnuK644!|1jZP3eFzbc`jw4T<46E-1Rgc
zxzJo4Ns--X-tKS`ycBe_Aswv~nb;A$%@Lrgmz&`&VvHNIk#Me#RLPgXt_>y@Gxd%8
zpc3r$T_p|>=2C-J4i`zM=hM%X{UJG%KD|pC3bJ(x#hWzh4QW`Wue*)*OVlayO-CwY
z7b5FYa#^;cRw3!yQLDgad!wDY{8YWkRK05@d6Qs9Dq|NWt5-7POW-jNGp#pj*s$b!
zlic0=mg--K<0L(KLyQTh)#32#O?onXf?pJrE(bC~BayHd{^|j#Sdd=4>j!KwFoheX
znm(DJH=fomiE|9eB!pHk$7ye}KqKtri-J-vhjPGtKw3$tbD`cMUS$+=9SEIuDb?e6
z|GuV5sxA`px>6E$q>lF{qqIXXHEF+Y*olH?^?aW3CX+N?aJ<nZjW?c4VBe5kt!vux
zSmaGgbb0K%FkBrz|K6w~BP_rrzz3)M$RbCCJDo6I9hq{yNkR5}LTIMpz`@9y^kY1<
zd82-e9Jt;jN*yw=K|l5qf~^tX+mZ10lGroEU~B4oBE*=C+Fnv{7s9I=T3N)Q;3Wq4
zflV9PYxj{7?X}4EkxAPj7cYrDr@+}lfpt8v?jt3-qF3w#9UA#$ZyAV{ODguYd);3p
z>BsKiRSGg*gZF`c?8p&$31r_9hm8tyy*Y2?j_k<jx|I#6<Dq(=x4{}QLH3cs8c{>`
zf!>@!MYa%K9Z^R%1KxIrh5u66^=(nMYCPU=CAjHGQ@W3o=xE^MEohO{a|^%KGll0Z
zzbh3h(teR<^HS<fvLn~!R^rM_$qy!77a)jBVMm6KD7!OauIwYbGlH({L$h;q%&vrQ
zbPQ^sRO9J7y)G0a3GBCned*9qa(fH&)r0Z&paVZis@<R+9y3d<GO@s9VUCGU!oM#D
z@Owb0iItWNRL&N5s{^@nDeQD%sui!J7Xs)~*zv+#H<WUoLyC5kbl609T|#oTLssY5
zSz@oHYVKeuw}qfzH#28`mJqh1l65A96I8NuD?;w2EY!kL5Dw02TRla}c@JvV8In*+
zHCnqA@>)IakYpxTThOjdK-#KRcAa8zhwRiC-KC)8gFz~X?<M8p3#sBreR?T4L~hiU
zEVJt}C+=W!?v5|F1pw;^<FW&qcES60NQVXlaEG+$10%~8wyOh4xI?CEpbd9Gug>JJ
zJET>glApW62t6R>q6}HCk6{4X?WY9j4(ZjW*Viw#`YB3%e(2SR_qCOLwPTC!kfMzw
zw_8}RCo|zDhtiVI0E5($>s;C){TD~q4(Y%L*tQ)|f^q(BVYM!$)*VgLr`p7^14Qf&
z;X68DvpZy$2C{aC^k^K<TY#;OBYbBH=9;OE*_0)^#K3kLq9G}^GShaTgEv85Pi7%W
zeq4gJ(jX@VN5Lt9=7MV+2sEcD`nd^~bKN^N<pX&plvW4w`b9yhc#$poK=0lzV>BS%
zm%^@3g(}7T*ByTgv~?-Py+0^cv{Tug&#A#|^>Hv5D%}J6&IZcsDN?Q<r_MY8vEPDi
z4TO5xPNjJu(#wX<^Au^KT20G<a=3G!kJ25t(;9sV#U3<kB-?(H!k!`Ce5z-NIHx&!
zq%*=Tv)e*Yy(kZgH9)H91O5!#2Rp6}wtcAIQA=*nC~_(FRfqb4loZfw;1;mGtE-6#
zherO4bo97oat}Eu6jvrUZ&iowLJqpAUBFzo8^=&$&`m>t7zBokdDXX5BOkaX?Ye6`
zAl0%o_5G5B-qi2LN@(nMV<B*l4_@fDx1acvjXLbO6v(}g+AVP@Sl7T+^HN|ixTGAw
zK4`c8Og<qAh1g;i`%7V?l!QCPEhOO%Hkzw+hj@h?+@bFSL0EvT2c%r4+toP);dXUi
z*L-WIqj)F(Rm4Yql6Gf5X*Ipps)TO}=dUDTKfpySNwuV&0Y|c=VX;~%RY}5(S$@M8
zMPJwIUrF*jjfd6GlSC$v=(|ZRyQEQ!6AduZzLEs4E!b$RQSllu<RpcScMM0`*Fb2P
zB;iVTX~}!&`&$R^Qp;{?)8ajX9S*P_K_zA&cUaQ+qg6#L0a(Y9gf##YT9RN>9I&&!
zXf6&W2dHI`E}2Ea610-fNm>smwNwPpA8_qV5_y<dEz;r!tc)*`o-76&RFlS<i=6U0
zHOluj(|wT9O}3V{plvd?Fjt#wEpfWZ7G5TXd6l5V40EhvA@c`pz)52N&d)wIQ;tQP
z3fxnaV7+npqr-aWKll}<h8q~}c+XRCY(xD8N5@Or&3z88x)?p=O4y!JM*JkbD`I`}
z;x*vgouuNlH?Bn!U%inpzFG{tEF=j+8?O&ZLXRDlVAdSnIPJ#njI*wD0?!<mgd)a<
zSCpdF*qS=;97xmHI(M2*gpLfTjV>*hHt=a&+Z}-clEj(=ObL;HNgEZ}P%<Um?ow*P
zJ;dh(pMvFIQt|o5<zHHT1p)If39YmLi8H}jtaa$}q8oU4OIjU2c$`ZL`(L#X1=k-4
z^>9fj=H>KN=G|-{4o#BK@-F_i7~bS>i)EN(l7<7Lo;ELOsc|Qhi;X*YltS3OR#no-
zw_~095);m$@I7Q80!Na_Lp3zTKwzCpG3>!5A;qu<mxMIKjx#-JIE?T%og{K_FdAxq
z2x*cOZ2XQDnza1UXjK5ugM#?2>J18Ff%-2AOzPQV3<_ev`jNIf%V2s?48L{4K{4!I
z@@7yD3)|1sgh?U~C5Hv>zl6<diwy;9kp&dledlm_1H2?KDMRZR6u89eU&`(Mt=A38
z(tX4bWoasQPf==B3a~#0B`E>>m(tNTS(=#c9XdVV`KF`=7WgG8<X~bf!tD>lK1x!@
zG%ZXnk@`u>mZbKL#o<Zd56a)|5)Xs2b-S9PXid=m7*}QrvOf@=CP|zTAOMnvDe+=Q
zTYfm%*(ib)zL{JSrh2`(qr4Pye+<aWz0`eh2-@z0;&S6N2G*6p`(vCc;y^|Ouq3gk
zgKdPzu%~GC#U_3MmT6ucK&>SSO&7AQD9}3qe@hz9j7i}tcYrY|T;&chCWY%B)lk;x
z>Yaj>t^i|Fu*wzSlCU_tIyW9z@&>rH8fsVP#>H9fP}Xi;29d_>Ng5dFT&ub}B)BmN
z?7nlLrrtY+&6Y+mM-_4M&B4Ly+At}xH*bX#(s;{EJD4`T$+uukieot!j7f1U=YlaQ
zjq~;T0cjP1W1}>Nf5Bk-^(Oy<F)5DA!JrzVK$eTam=MTvGZ=`flOzmp;ZUi!`)X>F
zO=<tLgtB}FE&*&x`JbDNQu&{dwo6+5bgWzX1!NwEoVvBuIEC%nZ>A`1;TkX|n&F&K
z)Gpl(W^f#vV4jf?b~4W%yARGK?g8^~B6Sa#khAmz7^`K7*|NQkMF}cE|5%iuMD&jZ
z*|=y~9Tju*DH`T*89SGnUh!{|!p4o0IM}#R$P31QX_!QU87>KPD7nrej+%wH)TE*9
z&K1(tG_I^QJF5iaqAI>97nj1u47e>Amcg3$pF|lAgt1K$8JV2Griqy1O}hC~Dn;q$
z3o>!>73ETDzb1D7rVUBwCTl|PXDX4Lta-!%W#l~Kpk$=*`=gf8le8>ve7-5&ec?7b
zrMfRl%qi6!!D^nQO||8y$dPS~L+$_rJL{5A#4wz%Qv)tLNvl1-O13I_;8>Kcau67c
z^0hn!*ivnk>FS^IbvlYQSn2nRvK3AOPm*fG%S&J^id(q}TvDx=sf)nEFS7635Jm3P
zB>-pSi=<1yqKuuA?wc~UaFY*c#k!RFO&Kevf=dGH)aN%v?3^;gY|2>p6^xB4I8HW&
ztlSF5rj(^y!IQK)tmRlRHt(>L8vllnm21J+6td-7a2uj+O3nqNV)G=09CQv%*MLo_
zIy;}4$L9TY%B0JLLv2cV-w>K|Dj1tGb1HD;*c6&@E4T!FJ*n%v<l~gGz9}E4-fPCD
z`ACigW3MW5QWmEimRzWMNf@~0Zc0bG5{ymhC|`n6armvtmtY{4f08ia6re*&|K?S6
zNLAmEjzgOIrgSWg^Z~8D3mphX<ugbEd2&qdkoLX<b35KA0qnj>!&$T`BIQXic1cJ%
z5)51}l7#!i=3R71>ED#2=}Ry+rKp?<#)cGqI~0sf%kiMzziBrf()^vWR4xT0?eR&V
z^#w-zq=9d5WKtX78=2J0j#J`}8k$4g%GF>v#qE%?@5YZJW#1`o$CUNODR1R)FdRkp
z&f93Z8w{t(c<4UhlE_0B0;fop&%tnrWH}uS=M7d~2P1>;R8uHoVAB7QcO^-6!1$~Z
z`KPEJ3KKn?vU+qBYa7WgVK~J!9TSE_N)Mr~hEq(-H(@x9z(abyQ&JD9^-f9sc25{y
zqFU|=!+D*hf5LFyX62wTd{+_h=mCpU(r|J*g>aY3?i9iuD!Z3}mB+zzDb;(IF7A}D
zow~SFzRKrdIOS_O9Xv_N^(oJT;S{lQJs3_A+X=`R70%;DafTipi1|@8%<jSL!q;Fp
z1*)74MrLYC0%a$XIVFwV9ga?leo%OJY3M=eS^j(3SmaM+yAKLWITehcu<TITqYOh`
z3VT4vB(3u|!Adx?g0DF8D;PmhDaV3=;4(=f1D!Jt0Us2e@+=rZ;YrtmOTmq_%XlC6
zMk>#O5xkLh-4cQ~(yr|vaCv^wq}m5>n_YW3_!!gsM@{f4V}8J2B5CBE@|3;^BUY8j
zHpOXY5j>iNO;DK1A7KQgsT>kUK$><_-;0aVC~bl^;;t<pl)2qd#46RDBI?FU&xI!`
zSOK~|1Z~D$*N5PXPS^b*_@dKWH3R`{x)=lnu<2?L6u@$N7(w}4UJnmw#ksLowyf(z
zQ23he4?*Ee&xa>zH4xMNAt-_6`!E6$SpE-}QftH#Au@t5yXNA6GMXL{Bl!L!kBD(f
zAe*Cr-DkQ7913Hjo&P}4n)LfaK`VcUadfdY>G+3|Rvr)IP|(ulVH}jmAAHP{h6y?p
zwsLwHhwroUdKicdlq53HdFwM?0}da5OlJK;Iwqxlas{bTZ$FfyHlz<9%29YMi~}KQ
zGS(l;NRyU+C?oByr5_4OV+fv08mzfMSggn4^S!2GM6fALtrY%qrKH>xUPVqC)cCWp
z&+(Ri7wExl)}+}V3R079e<&qQ;`UHVTH|qWC?-ux`JwTrNh?2mXp!H-B^9IXjl?(s
zUK?chft-}%!le|WbX*ufJST->>risad0`yN&L)HXDcRYynGbKLjmG)ecsrH<!fd#l
zHtP4Y@p9U@Q7@^!UZG3aR`6#voZ0yP(tw4Yjju1w)gfPBTBc>1tt4#Q>df$|8Zlb4
zQNqeIVm3-x2Bx_*irBW<KQ5zkkC=@DHvJ=Rv6d<wB%Y*Uv`Y+hEY-Hez^Ed}PWg&7
zQ`r!2v~A%hSP)ZV<*QDc>Wa@gZ4y^J8{c&r-|=R{!%n0AKO2Q|n;I;Ia{6IBvr+oC
zq3#xn_&OB7a=Vy~B3OPG&ukRI^1PUhBDf6{Yq58YmExC<7qe|@8*;svjpDa;F+dS4
z-;3G!4%E8(-_$l5kCWMmj%cQuL`TTOVm1g}`B=>6w4ch!Vm3-$dRfdy0o$5bEg{=@
z$jlZLSn{iwjZ#*Q6%#xA$gyI=b?KbL-Vj~yoTIramEgd)Vpi1ZEVKKpedJm(t++UO
z7CoTcA0IhVOq`nM&_+Ki1J;qJ#6)24gJbn6()}a{t`ZaB!f%;<*LOLGs{BO2pd-(S
zXF_D0v(?v?Do1`16N2Z!FJi)f?i?EIr$LIIv(@*&n26<>6?gr}J7OY!`#B5k4h&%N
z>2})8Vx29J$LCCOHo*z6?h}E2jvOPV0h4&>88IuW{VkKTg~=UaZDDSQCS`%y!3W8S
zq*zD364Q2;*mIqMhkg<h>d}#(#5AB1&*|!VW0cy*rDh#DOH4STp3~W|;~RF$u!&ed
z=TsAy4HKII#!RdRI5V~wWQ=<Hgo=6&+eoIGxGd3n<T){sso_#6!;sG5oTi=+Sf|!L
zGbhB6<HW4A5to8eYDPz%6B9YLPSD;zkyPshwfdP!wUU5?17U%l6V&M^(rBFswNppd
z30n7OCeAwYpO{FTbwYVeCo*TfNGKI^+S|B#9r{kpx|tohPt1<w0Z0B56PLUr|A~p4
z;0YS=C$5V}z`NPUtF&n(n0;V4n?08i`NUS&BgePZ@4)!BL=o<@N5H)ar~DI3)h3vu
zIzDrRON_0Wt|M28iKH+mCYh_&E`iLI#5-`5n3)?Zi##v-!fa3RwlUjNeeas?p`Pmz
z=Tu(jEB=u`=LmB*ks9m3QR0?su7?KbSz@<%YB|x>jbl7~u$wUQoRIv4CFle-@|nh>
zQx=a0gyO`+TYwh>Z}nI5RWB<iBz`*un;a)5GGLu(>KCF-eiO3-cO1D*TtfN-ohU>6
zL{6+Dyxm0jj}x%MPZ-~h+$d%S5IKJM0&oerzLZvcB9YW_ZRg59b^Nf|GBX}TvcBK2
z%#%mC!zWCbN5H#@@GD1-78BuF&fC#qB5T&6qs7dmS;wW&BWKo82JwlkSx2rGb5KCa
z)nX!V){(2lth8B2-WHdT3)89HkCHUUUFSS3$tPiX6Sn3f_lr4Zme}dU_@vg43_N?7
ziF_g}+7Uo+BJ0+RlBE)!F0~v+`t!~<K9NrA2y!=J?mzOvm`JB}YOjx%;FJr-9Ek3D
zTuM5E5*?)<pU9<kgtVIjl2bkyv(jljM_w2c(T84?EIGcxP}g3=le&(#ljDPLf^%fC
z{#AQRaJz}@T8Ew$vvOx0c~;EIo%JM%OhHh}wPGT9){$$)MDDCZ&x)BZRLAYj7UZOx
zCgfm_rHs#(B^(4usd(r%aS7SlahlODDfySija*tseiIY1#g1}|PrMaA2Tl>Q0+b#3
zMNA~ZI-551iEu!NDa2<*13Ft^mWk)g1FwjQBv?mo5fg8qM{W@l@1zHhX!m5u$JC?T
z;uG(!N8q@Ll%8ipwMNp<TV_X<P~=kB(Zq-(eJ8}?rm{VeEbDA(&J()sAzE%`aG$fK
zHqQm_)<-M3A@>r$5PN&Q=L&KU>BMK{$~r>IP2|cto9gw1(A!I0<A!(kRNs($d#Z2G
z5{_!X3679+6F7vkne=G_tZ=pz@Pad(E&Uq-5RbBzPXquuTS=d0MF2Wm>h}x`Nh<gZ
zjEO2Zz#K;@%AaCR$~LlYoh@w}X}8Yq>Ic$tclCqxMQ2kbuh@}Cnan4$Zk@!-P2}7<
zo9Ow8oLh&%LyA;uSDJe!-8x%(JCbf4CPSY9;v50xo{5ZFM+whoWz;%bDmOA}T?&pQ
zB-DCQP`Zm<dCcd6%v;i@0YkbJHd<4B)={GaSFv?ayx(tyrU3Geh_;E0)|Y^jrJ@gA
z0v={3l3|?{DCLw1?luwO^(amGEa=w}l5H-CuCw+>tz0;Zs`A=d;Mj1r6F_YOy>^zO
z`OHMOowd~F#-uH^i8)&u9>kNflD|G5WRxImv%>VAwbXYh6=zX(MxytlROEBz@Sr!>
z{2pcyp8ypeVb>;rhi5_Et-wCFNKG4&eJ+Vy98B5JydLl+@rYzrXUV=jUn}e^nzkoa
z;8|tao>-%2(Xc&{?&>U}(C4Pq5~^($<nt`4(Hl3p1sxd?sn3$0oJq0H;!D*;3aqoF
z67QZR97uq|o+W)4aM^=&;&bD<{|MtY0lYnn`fy=$Z<(A!#?7N{A?4<I&l$v=5{yqI
z$vOhK%}kPY%j_CbZbD~%CJxs#k2;6ko1xAj`IM@B<~g1OoR1rB+h>OQ%7u6)Rpz}g
z1gXe-VFXf<Q&64xws#}9)|t|WA@I)hce}-}jNOo%Coya@h3e%@>M(%nXG$don*B_v
z#K^04=2pkM-a-$vm(T54z=?t&_b&=cxen%1ubyM0b^Do6HICAqPk{B0kZlvF|1+fo
zBVX2;+}5v#s>mu3UQ_xmGGx6dDCOQ!e)0*O?KwoD&B~5-%Q!mV4tps$>yaVrOxmYs
zc~+b`WCcM8qLW$7C$cFV0n#p|#zI9I*|E-)W!iI5$tn#k_Dt!`&~%URYZI<1M+wO%
zlVKg<&}O>0oM|7GYN5&W3}2ZusTjZ1{X^wAi<oC=#RwyGrnF)>X`d-GH2k<Pg(9N7
zea?^-8t&j{&<c(8SVx)5Cwzv^fNt$Df1DvJ^t~lznLWcQ%0%VUArysRn{c#0Bi_s{
z@FH0X53Mt#Df<R9u7)58)9d4^+nFBg45`izF*u|;BR$p;0&OBa))`WrdF4GrcIvto
zpCLmvZq8@GP>rkgQL6HZ>-QO($2{)nm%_ep3sSbr0WT>F<>FpDmr;Pupe9{ri8G`l
zBY)OW%JB(P#u4ajB1Xie@E(o)S!d949W4uB6zQ|hklGBd#-kMEvoa1nNx~_D1X^cE
zZ>|JdXGm=h-0=q0=74E*3>h9^PddtEJ`twl2!b||y6Gq@`9u<}Gg!KhB4<d!g}Lku
zskq3Fb(nB`!pL?68k;b}Juec9cQmq0!-{u?EYk>yaz<0XkbD)`x&}DGywv2FSPKoM
zoX0LhbeS%X5|&Tq#X16*O@xy<N;N*=+kA)}o0Zt=bQzhE*y{ARkvSl>dZ3hRr)#Go
zV$P+Y(b9G=ft&#Jb-Jv~aO^%^R_4rYb(Cy;!aw{79X65f?extDuE15T%c>l8Q|mG-
z2X1OgLOziX>i|%8?{~1wpDwd9%=bs=u!+=nr%M@*gXx58K#__?8JiCt2s$<9N^y0R
zM110f;s6#l`G|2kvELIf9jD9KjMtFUWo$l|6Iq(^m~#5yTp>Kd=~BHBL*aC&-UzdB
zx-88VhT(LjNSz4QaJp1)WI;Sal}#khx)huZ2>x>^8+S#-|GA`vpVWY)Y@bmj%n}4)
zm!e&{vz{ceA4tM3i#75=o(^riGG`s7A)m;cbp#xnNS$@MY}QDfb-EOE<jy)>N_ytb
zy5(Jd1`}_G2g%GQl4%{`$R?6$olX_~Kvs6?=oM4wHAa(?e(*G5(#R{{))BC5BHz|A
zspQDF^&F!eJD*sO(w9#>!X6>UCZ1`J$!3kW+)Lrng;03MsDM|jykjz2BbU}uQuB#q
zT8C({CrP=$O-5^^(>f-jHR2E*la`J^M8}wL^->0EvHN`0NQl|2+*yZd&L>i59g}*E
z)LE~2y888MFDYoWKQH9OIs$_&<ixs^I$Rd;0tZ=No+8x;TlhiEDs9jU;f9Wqm#>Cb
zdcne0tJQfa?AkD66Q!E1p;oKp)oI=RGTZp7aGAF;s>llwHIH>xz$MSR`on{Obqy8v
zv7_wbmlUYhFlX~sGW7#NXU2XeCQ!!Z1su#VQ`ZoGN-@4F7U>ZzY&Bf+Dx}M6MO{jb
zplJ^C+NT`j3#qb>U}LM{O4p7U-q?TbkYhXsw4-+M7yvBTs*KyGosVX7J2v@UE~Lsj
z?P#L#(%wRSLqrM(wlY)JX~8q*5^@MF&^0c5Ez~z;W(!RfWM&I>T_Ca}oY(@=>@-Ka
zuw^z^yD-}*EBQhQpwskXv~osH+u|Q0v{8><fZ1KjLb=$b9=!^#_arHI?WzF7r%{bw
zh(UZBRq2H|#i!A3y^vh%G})~evTGgWDqmI=>TFrat##UBw~(K0sb8e>J#DIEh|o6G
zafwhRJYRr79%8^=l#Y$mhH60?3e2@$d-t@VDv*Y4h+kX_+khNf$clB8y?oVqaD>}h
z$cuGaS2qxT0M9)|st?=M7o=b7oSPJWN^rh#lpU4IrqN6tuPm`sJjgdw4|tImxN8C3
zd)}GM7ebyNVYF6eyE?6XRH_9>Yx6?3s~06pSgWDD<*Q^#2#K{2h9}NZFQwRC3j0aj
zH;xe6mvUz|&}i+oP+s$eyjF3biZA4~iWBNM6N1DE^;@<w91qBP6@qdtgwhYC8(+O;
z3D@k^8#<-&c_H3T92lQhYAbQ5PcJAmai~x~3p!6I-S~oD6vAXJ=uUBnzh0?dy$DNP
zBQQ^##lGuq7H6sVS|Xto<qMe$;!rPNy-GY;d&lRRY_;QSNtjkPtT?4_FDR~Yrkboh
z6laS2+GlZw*dJh4dls%1aj0OgO7-w0sk)l^Z+27C@KQK!B@RRR$QLqU#Zj`Rg_}d1
zuAXNNsH@|N)z{JQ!uq3a`&qcggtD41Ty^4T8>gpC9BSMPk$K{nddB;CD3AHVMJovK
zT9qFwPWz}-+%@s*;ICB-fQ9T>A@tUQCsCZnX8osXmCTkbjG(6cEO;nI9CckHE|kZ7
zA<aq%z_ltpR>V=)cmj$z?7KE;#8L0Lk0U~JRdPH+(i@Il5eh=TkRdCS$b2D3Rs^lp
zt5RY`P!C?nh!qH^`xGe`V?YsJFhGPLTMI^t7bQ#g$6H;%<vxP8>V-f$5nJ8f8&oK-
z`7PIc>lhdY-ggcTrkIGOetHdMsh5tSNXJI@tN_3(2Un6Ul%jmWT``2$T9sERVv3i6
z>7R7`UNC39Ncn?Vyhvd#Ygkh1;DEvG64(p8o-PUJ5ga}vhI+16Iqh{1h)hnt;8PmW
ziIiK&g%v^78wsx>y1HF8IO*cZmKDrb{v;_ki~wE>#>xm&I~%-8vmTx$a_(FP(yNDq
zVN<gZhd~qeLVm1>#u1b>3|X-k?79(>)JTyPA>|t>vLa~3{!icj!*dsHd)0jX%KLg%
zZ9lc<F~{rL^B@2HxBvFdzO~nX^}qk+?@w@Vv~Pd^25}TZIGDZI)JvU}#VQ7+p&_AD
zl)d9}ZU_w!N;hEu7CFSn%|3qHduM6ybpdbzHlChF4p&Hx4(!fHjyNW=d1nXOOiiNT
z!GQ=x3JX74#c!s+oiR?C+^`go>La|5LL?joJd%6-P+X*7=&t_hvO|9og2xM!j72zc
z-X5pQGV!+af%MR8u8gMe%{}zpeqhUz7~+M>b!K<T-lc^y*K6_5*8-X2^w;(MwHlk9
zZC|bvApbtr3MZh}O8;CZFmQe@llALGQj7V$NZxtfxl9yc`j^WjlWEp6QABJllXnIr
zE)!+B(lQYYL-E~}rhw~Y{Cb`6+2&)N$br4q2?D3AU#=3x;Cio;{;L&20C=qsKJ<L7
z5MRGoAbP?0SRm_{%i~*FIiI(A?_+658`RSHJVjo&w%6)-tqI%r_;~$eO*7xWZ*jl}
zIlON8@IMZxhJdXf1c^rd7S~|-B8TE|<HQXCMsXmA@S-@gLvT@~MhKxrkr^R~6@?3O
z2rOEMLI^4f@8fVqc7Tuy=Q4o|iv)O<7!1KT0b;%cZ~%YeAfOXS=n$S0apfc7oQb3k
z=k`KO(@@my2kyfmyl2$!(HrEbfSyngB9{?-gu|7zrd)(WuueD#hftkx4-SDk;piIz
zWHN+oC@OZTSK&NMp@D@$VgpzoiP<dFeIQfJ&$l7)08tNT-*8HLxcY`u(!<X;gz1dB
z6AI7?N8cBr3N-@S+n|jGk(^Lh12M9nq~wUG5kTn;;W(idhoGGBo(RD-OJ@&(G@;dB
zf@%b6ln#NTFckgz;I_CK;H>TrA($uJM*<*E_?N`yc?;*>*gVh<T*^Z@&~w|TZ4HjS
zK?EqAdP5Nr;nEwxe?AA7NZ~(E-64hk#EmV4^(<GM5Yn@pb)KZ44~P*!KhMm6f?He-
z1?YsA?<Hh=7iIt!X-vZf_Y$hT;*gd!I047zCB0mLpAY>A4!|J*D8yF?|CtU{u^ChW
z=?ow>pQ7Z)-rUz`SD`xC7#8pIupxwEC?2>e#U_3mwul#@3OOh~ufdWL8@GM<pT(YZ
za)*yvZ0>WU_leEBLVC5uCXfYwZ?Sp#FVEr25^e^_F%*idc<RQesESC35K_935h1n|
z%d-2#=0zXw!m(+ShqrJrq#_*uLeUdX<}QuRD?RcuT>`!@E|;5E0(cFF0w)@rhGQEx
zo|VsVC~Bg?WjJ;{pjm?~+`RA`JcwiSh<Gk3&vHdgv}B~IUx-A;OElQ|VpG|@lpJ0|
zw~%iNi)dwhOhPjdlGAn629$w?G_NnsB@5&U0&r0<8{A+og^l8>xk8Nso*yf~T1m<k
znh=P}1=(y!f)I<s*~-N?meZ<Z@Dh&YKe0|u;o@tT!3#Im7Aqy>7G?BfaKw$ZRSR-%
zZ8CF@hgeG^#659w$67<2<X9BNFI6#1Y|}Aui*4eXxRwTpYvP*k5kfdFs+d;Zxv{2t
zh5%&zL&HNxEG1U8eCv1-^3Nr{7}3z+ejkeh*^qSLMM0@1S?Qq+Z#|)ChGq>jMijQe
zvo;p@p5e{tQV{3vl2#JXGwyA?O+W}P`{_-|-G~x0o`3$Jgy1qU2C=tzg}9U&55=|N
zdF}}XMKrwOC56{uu+}u54))qdLzlg5h$9-<gAJw2o}wXMLQej~Q`sdXzl5w8DH&EU
zM8k_^%%h%Xme?sIA%2bQ$T2C(4NsymgWW<7Do~<Tz>QFpL_<`Ln1Z<&Vs~5;jtBVa
z#&mVHFd*IpU)Ri-F2-pLoxJ%Q{BUEsTHRn*RtLD@24Wp1A=%yUX@i(kpu^YQ1tXw%
zH@NCv3Ok3Sn*xeo(rtOEZwR}&*f&h3b7}HmGM)8IW)>W!?zZKj8w_t~aL|p(M=yhe
zZXmXyrRQzT`DP5#OHm8WAigFI>;?=(C~BbrC=m==Xa%JRg)B6nEkYp+4e11u()gQN
zl=9TLq#6Nj>;?zjm}OEoAV^|%b(IFv31f`)iU1V|Q)md36jQsGchzaE@)A!9Mra-4
zX*NDt8d3wqB$~{S86aj;s{=FH)G8*jChI9u&ZNQ-8iGq*3cD{6HTW`S@U*>@LR(x)
z?%g5dSk{m@?YOiJK6_nC&a0vjTF2sikx<NOma(PR0uRAH4KA}WASt`&zY#RefFS!Y
z>j7gH!gCsMXdytS0jw4Pbe7HM$ud7LZf`^T3t`e?@R7^lW*Y)^TDjRiNn+<Iz{XP7
zxWfVWX$aXLL;DLU=VR!Z%Q~)dLlU=qZC{kBz9HHMAGQo`vr)$Hrzn>h?Xdx=HMGaz
zBpaiQZ3Y+F5QftRWfwu5RtU-%+F}4%h9H~<AZ85hFvR7Lp<Drm!2B^Jis48bqpSCh
zIp@ZM8*SkI;VIH(N0whW(#DXm#b{!fScdc()$e?XLV-99u^3}$+aXwE3~oCF<BuWv
ziBSA6%7bD~tWceXPZxr98a{9Iqn=ae3gm2fiju5%Nl^H}z9=Z=Bnk&=V`qtdP;B*3
zClFg*5)&INx~m%GjbNU}fczntry)RS2<B;sA{qjETE!Z@lq}tmY^i7PdyP)v2%BgK
z@_8va(ZYOQN=`JMBA+5%5!JVPg^cPuOOQ`pk`a*h=#-4(aC8!liHi?`Mh$+k(U(RG
zAtunM;S`QO`2=)HH6+T<!v7}$Eth*h2oY-VAP6EtU$PHw1|dkO!4V+@3%!)w8-1{=
z6k0%l+Jy6e2=QqM&l_EPxg=Z&-D&W!4WT<PCD9`Rbf+QI{w;F=9bcW>7B03SyT3tZ
zM^`Q&gJ2IqKGPVVWp)km2f(L6eF()0w272Q(J6P~bQ?l^+AQHGz^B2(Ho7jTaF&TK
zK#IYmCIr?rgw7As9xqKR1lBZo)P}uxG(2j9U`;D$pfJf<I1Ggyl#)3G05tm3hTxnA
z&!iBX)23&M(*n6kB&R{K4SOre@URVIja;UR`e&sWhftgbZ90V6yc8?WbR=YS{YZ$W
z!PzTptIaBr=L0UW*`Fj8pIZ$cu&Lc%SCC6VDcM}_K58?D=@JaL*-$h<gWGHf{%P=<
z4Z%MxA1%U`W(+=ik>F2*PhSZ9Y4G_A#soCP@(*D@4UU2#?B}ISRARqYBbq4W*<jlC
z@Uaae8r;(BF>I&-NJP`dhnsCEjG*EDGKd>}%{>wa1c9SgSMggW_YkZ?k{Xf}gdzxD
z3RY`Z@3<BUNoubfe+Wrx@Wl-xNe%9}@kWwbI-v&Q3tAZ~!f0}WIV1GGYA|<%!REAf
z{+m}6c;bf8p$0GAP_V#D$uHAngF=x0XbAId<>&kHRtQhrXh(yu7nu+`)XEVz1P--@
z1XLk(sKGZk00uR<=7zwawjxXH1){aZdx#LOLV_9`c0(_02K!ks5TIqskr2xBF*xIf
zV4enN+yKnecFTX`NPs795aDUeni9fz8hmj>7*E>}lEQdeSrem4vxdR(35E7E7%79W
zPJ<mY1nac4bcQgUx13v}DQ&vJV>cAq&)}dRZK@eO8ML8>>dgQk>8B_)yF=|j3JU6J
z@W2g0Jq;eXQ8`-gno1AcXcE!zz>SR8XYjra;XV!Cw;|l8mG|wFBz9afP_WNSs4-Gx
zBlJQjQlBBSQD6t+H8}+Qw7s&#UU5NercUwVASmdi+|y4;P{Zp(G*hp5bim(BST-r^
z@WhSQ=*n+!#SKA44X(H$sHklS%!G>C_HTY9#W$cbF5sxa7uSUxy_CCVUC7Z(xqovZ
zN3Fv0KYnEJ!V8k4)w(GA(azr`<o$$doGify$>5sn0)`q~bN%pAU7ojoB!Y<|P(;7S
z@LcB#>1TM+bHPUqkA6=0sAY(K7ktzlwhI@2)Zl&Vis@%=S;Db|w@4=})bLvA1q*#Z
zO8#+U#)Ibv+5+)yen~0j*L#E=+%JtV0T@SH-%H{N>*E7oLwY!Z<2ytC8N%bcV*VMP
zk6khUtbB1@&{2agt{;W<HF)DXFfImPTvyOPLy|vd&_7FGTvy1yTgK$;*6nrYbYVvg
z4!bV!sKH~`k4^&5!}9T?qX6&n&bWYvS9=$D)bO(Jf{z*=|NSV$*hOIY(QyFefGd8W
z!Nu1VKhWU8>qn}&<DK3WA<)WS*N=_>`0Kjxqy~>&C!W;cu<NH0xM9FidBy`Yf7Mqg
zKtm=>S13S3vP>6})R<D!g(Wp4-gH7qt&lLcjNOd*`Y%eBO6B(mU5N{2;))$;@bLAJ
zE)Nf1SM)#wP{#oyeTr19=(b)6K3C*F1IW(>BQ*d4Jz=C4NSy7$k{ZInIV1mB#)@;r
z{WC<9b4C6$1ljl4dQ6FGft_~D^+u`YS$B0HBRzOz6n64S3cKw!HYxA$_VrlmrX;N^
zc%Z>o_i+JB4JmY8asRB+?7G7K8A9m0;{F*T=zB>2E(cy0w$u=w&;>0uu;B{)cPYi-
zAY{xC_RvFGdS)he1p_p=0XqSv1}|V2!1PjT2L-O{NQ->S?0VNArJw^U>_G(_OTd{$
z;gTHRO>f0mT5lAbrQ5GFBd;M(v@1N|V*p3L0hU%yz8>1%SoyASfCeXDXE;D3>e>|#
z&;pV)a(ln_o4d9*_M^MDH++QsoxIoJB<uo$8S;2LkziJ-zFm2H4Po$Klv_HuUbxcs
zS{+C(ESTXGb78*>?!d0}yard^#}(tx;LYnwtZU`XdkODa#f!E#oOxfA2gO`)3i4<0
zAaEw$wRADKMXV*rkxPNYh(Xx6lJnXbSz@OHbG=cjdDixZSMTFY$ZPQGbtUAr^6PbF
z<2CqhxZ(gBym;N0?mLk5t~h=M7hG4mT&tkK?%LjniSH2FPm$^q(X3X=iwiks@OyFB
z_J(WBrNAe{pafkKJBR#J;$2I>T~`=DgWs+bRAvXS_bynO!Ee`*an}G0b!FVO^4fLf
z+ch}kx(gWshg?@8T|=;Z7dFh&+4h#nY=F5Yi@^yj2EB8g0C&2G9|%3iMZElWT@W)X
z$K5AM>>5H)C^Lg<?pxM4=<lv<y#1xy`&L~44&~p0GwZk>xPWFIzGg0@S%-VCZv_PH
z6-L~*(A@|~?tqhZ+-`1}VBk`De8c+IQ+x?M)^Wvhp~pHRru*iO?+B~z+tn)Nps?t@
zT!CFkvtI7NFABB#4sYN~@dZM$uNUbK2Vn=;?3P!SI8Sv0b)n5VoEtBNJ;M;|d#US*
zVJ>z(G0LTJPmFT?#9!3>E0%XJ_h8>keM6KAH`d`W?7|&)SQZ?(ucr{&xegUAu$PI#
z6)dpBis5^Rzl|?Bz#mMpzJ=?CL$L251|1AidGBznb%hV?4bLl=#NJbQ?ykNav)<7+
zq^ZIOc35_Ncesgm_yfD*2liItb(?yIFx{q(0(;A-PIg4B_ua(Z0XKxAbQsEfH?7$N
zej2Uc9SJ&oLv;6Y`1MV}-Qn=-i#xl+;nx=h_|xI>>x&Y+!{OHzT(DbJ!Q22s@9VH*
zD~0q@*fnma>!6ftPk{w{*&}_0I)w;b%+zry#XT?Zmr~qU=_MSOHZ?qbT{y6AgIrON
zUs7@9Y7!E1IZAB3b980Rvp*c0Gx5Z>CbmzUOl)Uj+qONijT76pZQIU7zdT>u_pWu{
z^GBV%tE;QJyY@P3pHFvHjVxfKH``Xp5X2%)>0+i;^xZ6Bin@jD0cm*j<)(CX?KheO
z-;OQzre1oM6sAyG{L`HRC2a@D&r@TLkZg06+Rg8X%VU1R>C1KL>MCjpQmTY6Ll^7@
z+P^7;C*(R4VPaQRr{o8ca2O#WV~()0P&A8I<!%yjqgPk&1&LJQHRX0=L1Aik17O;Q
z2)WT~s!7yBNDTDZjoi8*su0Cx4|gse0{6pJmv6@R?E_9-!&}j`#u!S)au8#nX?5Gv
zo;GU(qvM`NQ>U7q29-wv4bcM6RU9EH3gt>BP#F>0*A24#`l|cANC15~LX9gR6k6o<
z-)T}3xUU3gR6^9aL~oYysJY`@8G(3~Ns&rin^MDMCGvqCeZ>PNB_`runLN*73ic!i
z*LGOXM+erpH~F*%GE78i&b@wzy$cD*;-Oq)Kf0%nO+mZpsvh@5KbffBu4i?2RI#++
zh26eoQZ<oeW|>s<MEgEfsRiJHUS)3AL_axWx>mS!w|FTqUAZ>91QDD+G+sHF$r2Kn
zG{CKJJQ!^5;Gc_RIJrW%?V>+AB6k`)!~ZJr4U!A_SuKYL3nJRwi|Fi2uJv4l#IBRA
zG?Fbv?Oc+iD|s_FvMu4<x*T8$kx}6ixbC<!!lmWsr9gEB9{=kXj7P4F=dE@Hc<il~
z!UMu|xZH&?2Q+uA8D3QnpPS58zBh99F95!b>T+*1<uiS~20&6)^>JMac79YfTn7d(
zTV`GO8(i=r=)GOfG(A}=p64$QuDnjp-fxdgqoPRd!g`&VhuZ?4RBCz$0&k>Y?E=e)
z7s}m5o`Hu1zcWw?8qA-l?e#+d)!%y-hepBpcyRr_t~EAy(9Q#=(5Q-4{ouLV{j~*}
zbaZ;?|E!ViS7DE*Zh%VP<!U2er-2_Xg4#Irth;{<K-!-LEH3nDM=yubLudl!ACW*b
zho-ea8g(4(V4K}s##4}CoutcXlJ$rB+YGRagpF#sTM86R;kFl1jc13@K2g$y({Z0g
zR2lpDw#$!tdmg|zTlH-5BvSDhn>DK%t{)czr*Zc>><C#Q1JCZrSRwt-LYGg#dLGtk
z`E03C{+{@^Ih}J*tXE>X&xe%4YSD+Vy#==8ip?#Mq1VN4&vny~Jy(EXhiKt_+x))l
zLcj%qBD8@1S-scqAb8}C7e>FY1%3W#Cv?P>)51r3V`46`=_D`BQwPJdWLNExvS$ov
z*0_Q$T&t0{#=~A^2&xdUb>8evJ>6)7VAGr0RByGC)F8R7f~Qy_Vqg$W=&Bo*y*VX{
z)Pf#g`;NLqRM#Qpk&O;A)3(n&y}w!54sLfTG@vbc8AT7uhbI(5*rY?~u8O~gl+p22
zT1EKzS4kDcNBc&Ep_JUro>=jND#!}JW2TC+#%IT#2>mvPn!1|Q-zW@yKY4Vcb5q%I
zr(Qt<(da_G2oFMcbq{wkP5%{$a|(as)qeEc$`$lbbiIl!4z9dx#pmG2W$s)ux!J}Q
z#B;tNs@<)vZpB^yEY*V<06kh*tt>8lP=DcQe51qfIwDk9cX1tXQ}rII8ScUr;J9wo
ze&*D^*SR-pvvwx7KWe>ZXLg%K&9N~H>2OwV&!{C?S+S%&S*hj=!NO;zE6Hq}OJL$M
zD){Qy-{?Y?dja1&K^lolyd_hMm3x~hVah<%63-F*Gbz2FiGIXdr2T#gZ&fDVRj?I1
zKlbY{T#CeaRlExnReF}eByAmDr%{S8xI0nx71@HE<Qt`jWk^!5%&q-SX-~bXY6t6b
zBCi7zhd_t!Qxv;bLic*C0J&ewO%bw3cT(+1;89U!E9w{sw#h4-r}s$j=(ioAgog>u
z3<)&iiVk?_#ho!%ss^XIXs3uPYE}oKKxeEzde}LTh?PP;cYS3CfgbmRW83_553XC+
z=3mc53n4TUmH@6;mz*G}(j<kA$;bsi)m0=P1$HZ5j*M0bv|fq@^n~g@n+Jt!wAHbO
z2ZiMeBfVJKot`|iGvzdNn_3Sm(oEX{+VdaG#V6ryb}km{0mkng#u=cDD7tV_)YZgY
z;*<v(3ZAjiv}~KrpR-FV>5aOnb=jnLaC$Um-@c-Q`*-$sIwZbtLV`RM;kDe1Zq}2G
z&8?*u5P9}=oIoL{+S!D|ud^2@%>`k|K}YBKb@a}7%!!GzxZA9jM00R#x@uO^idX&d
z#k(R&QQ+^U@tETq_%T)}-{Lr&Lq4&n2*tWmcdfJ+PUA||!j9uyMG}?IZlw*>)R<dz
z8ZKm;N8XPohIbAWaitGixD^#(0<~%RQxhY}nzGu;*PXQ)+a_Gka;^<rdMs)y+iU2s
zJ0tE7_)>60S1I8p3dd+Ot9=)7d^-w4Uzw{JT2fT9foBu7S<<-6I-5Sf=w7`JFsJEV
zwc)VX>TBpVIVXX~Ah!I6`rDoh_pxjmKFz?-c~x(~F)ZKYeeKdiT%WeZ%<J+XT#-C1
zb*P;3&HHRvfaIbsY;KmIU`5~S0=d_!p8B8*;>Jgfochv?+)7e2*SXp%rPfqP`-)#p
z1k$6Q?lB<?anf0g__4kS;BS}|@sDDtrh%cJZAWrKtc9;gwJ4DtBzJPsb-<wIKJ9u)
z=v;JtuqG3N2NoZN<0*y2NcgyF=v8eDf?DW#Lrldwh~fDin;B^J4e<_i)32b!aHK=i
zEiwOLui(F;89iP`+tKk^ufvooeu0m1e0bne&R-E&iivenWw9dlAw-v}e6^ti<KMV5
zp9>VSN#>w0N!BohhR;d%RHYF@8i8s9CHF^adiPfALgy_~27Qs)qz;%u%i3@_o9cvT
z*Ey}Ew_QE_TNT{bvMK)Gzx^rkGD4x5p0C?0Ir`ShT>>C!{XiPI4VQF)eF%6x%YiMa
z9Uu?-)i0T&3+J6J#ZVvy$dU5z_Q<GRJD>J&oX@lg+04(c^5n+7$cp47qr)M>WKRG^
zqv}$9`>fO!1hO_+ZA<~5lOKCe#7W8QG;^q?>BAc@%Z`gg6>>r`Wl-<0o+NpW#vKfF
z*QR8A_rGr~gw94fiiGjZw?nz@sqOQg3{P@nypM51xk;79xT0$MHlFfEL5AFB4fsHg
zPeRFvn@*p^ai~;_0R<NhaXMoRVe5AYIFk|d_hs<Um;x=3a8dCsU458?1eIBnAD41q
z@Wk=$l1i}Jt0%itl`?ejK8g&@e6;CHw_Zi(HPI{$Ay>cAqN;n^pUdlA8y{j2@p2r|
zi=R5dob<rm#pft7wD4L9JQZz5t_DYvSu~gQ4+^IQ8@q=Bs}1dZB;>gq9C<yiF}WfO
z-`Ts3hOH|4KHWl-tNWtdhcC)0c9RC@1Htv8Qwho-%YHS1Z4wOuv#z&s>&njg;eb0I
zyu%TTJ4Aek3gx~mv1i(3Tm+qO-R^~n1d1xmwUb?>x@^enQI~ch)=8}&TzPY~L_P0+
z)(h5Fz!6{Kupgy`tqp^{7LvDpm$ozc59JjRwQ(#<1>~&tHRVT<pjcNC=hN?Tn9dnP
z-ufB~SdjRhx3e<(oL?*{Le~2lOa6BMH1GTEEbShJwM#XK(BO4A%UV=!MY!eIh<Kf@
zMS;+RXSjH{S<O!{UQ{m{jsGX>tQda1`G;i?lS~ZcvP_@h-uN()Die6>%b$#^V2(db
zZCUUY>Dp6>-o<#x_(xl~MSf4KtkS-%Baq#C#!*y1H&Ec~MJ?U*+JB^_VqFv!!7Y=s
zJvwKr!Z7##=w@?^wyahfYJYgW^BP$jL*Zk^k6{oFUBG}8LmXyPK!&P~+7CDz0!PwO
z4V&aZk~Q;4Ju<Ydvtrx|;pwc9ej@>;Awk+6+_qkeZQmvnJh?aFlgap~*Cd@>#0kZ<
z$aWNL{QMhlS6naJCPh}(!x=&X@I?kaq5z<IPJi6QZR7b(e1w(=c|ijL8Bi-&7-lLN
z^5X0jeh~NB{R(3QbFTjuaEFnoa^@B`k%Rdt5S(8|l9Pv2dF<9jhBq}B)Pu2tEq}vd
z^9z?%bl+01iJv$+DL|<K=5HhEbjL&cjlff~j@veC#ZeN#$(0Wr{d_~oq31)!OD{kY
z@r1J^vE8#`g1SzHZU-PjN3n_SA{Siu1tRAA??5<>U4K8O1XI5r#GUDW)%JuIY+@?6
z-6P2Zi(nus>E7keiSQ+=a*NOz7{gJwN`aBqREdkCcs($uT47pMO7SE4B-=v|@FV>U
z1tB1e<0SUQoLr89IWi1Rc&6hXPz>;(>m&L=6_m)hPdPpWPS)BQS$5jpx25sxxszh$
zZB}ztxXTiqJW#WnO|Ph{Ne6?xljMSRbPg9S>XTTnQ2o%QK_mzNHG#U*1NClgW;uW5
z4K>bbVfq~#3kgY+F8fm6o;>@q3pAGwSE;FBF)U;sqe%mB&(qE~+j4&`U^A(6?tko=
zuXxu1-8rMKGLJD2&4g`bp*O})ti}`E)<lvI2d?eSW=z;aH8Y_r`1HbKDes2*?#%pZ
zj@r$;hx+S9LK_-`W?cmzwjp~yaZF%Hae2OXiCdU5RKy-I_=tJ9jL^_^{V>_RP3KH+
z%7M*c6OC{|p(`yOBI1HwV?rp&N!$y5tQ3u)xH_!)c3yp6q{33$c<fm>=X%p5`Y<D_
z!;yw+Pw|ozb^Q0dy<*xa+;vjG#lgrDXgA)5CK_kugybIba}7g(yy3HUa<e8h%WPK@
zFohG7GY-?aYSYuOBVJvE_3M7c8C%csbhKB%%fU!a^y^i^b(MfB3KyLF)GD(IRXBSi
z6;&8Iis7gKan6IW3L#fw%)oX<tuf^y=F|C7<R3`|HQ~HT5>VYLY^<swg*%AN)dFlm
zRq5*Ab>Xhm<kzVBVZ2HzfNrF(SL`2SFg5lYTg0^e_M7Y^gR>q!Qj!O`hoRMmC79)W
zHzfJr`qemZ(ougO4A?k(6B&*(9s-~sL)&-#HuC-o^+Q;Qb9;!W1ynry#)QI=Zp{iS
zdFT72Z4e4`6MGhVm;3bpr4#;i^=%bB&dw$-xm)=L>hXt7Nwyz<mBH2Us9x6=>=7E@
z8|2Zo5&ny5(gwobrTR+~ib4;W4(E%Zy?q3^vK!8NeT9p<#_lXu?*F}E0NMg+8UI3<
zm$Fp3Cu}u87lzD6Oxy~)em}Syz7|^U*F@OzUh=BQ`3)_->@dEDRz@suy@jnn<Ff%G
zehHv|5^__rATjjR#?%c|eHV47?H*LdkXKmN7mBWeGlwJaUX~Jx4pEjenyN5#Aors4
zdxRj8MRc(|fsmavUdD5;Z%A@PU)|j|)5_}sZ_~Ezz>V&cGERN=dUo4xYg29CrU%p-
zR${wAY3%6;d~9>5IJNZ}O{FW}5TK^N%XJRd+h`0e;c*ER?@pGtNM@Ix0)0LMOn(o!
z8a$YtsYf@ljs!|5_<RCJ|IYLzVQ8P@?bbI>yP{37@O=J0kvX-_PYe;0nputMZ^;f_
zeym4i?y@?)<&m5^M5tuFaQ@9<B)fHC+cWhf@IoA3Z*;!9_BTz0;d@LFw!dGSqY-#}
zBxF&#_7)>(-jK5PA>^0zw=g?yl)oW8`nqSyRfcIO*$D8acoA^a@-TOv!J=#b@Rn{Q
z*~LOP9oyIfn?wLWp~I}wgY%nWz9u5|TP}GM><9t+mqa)oM~Z2ZA`pBz__5sWGih`I
zgA9Z#Nx1+MC($FY?P)&ZM<o1HK=32%AbmNApoV6kK?esOJc2=82&3b4n)7DbDj{3j
zBqUVLiWw@xJf}8~vFBPe|6ZH(1v*sjiW5B}%tVfBU%=_u&P6$*P@Tmqqw8d0tUsL)
zAPcdV@Scl7{Q~l;co-TrY~!AgxaLPV2e_>jWH+CWNKgs5S|w!wo!{arEW*-LRb@A!
zUK<iJ)Xge)_|XWLfD%2{l8XK{!nl(oqkNbZv`1lOA0aiShdyuUA@HmM#IFzlvCR=z
z4DcQJjgmy?c4Zk*V#z~=_1$J7@ETma5)15yh`HjZ%8x+v0R**+6Wwok_<D0bBBnO_
zu=OTD-wIT~Ac69ebTM>(w?+@Nrf=1Fv4@DoTrZR9Ikm!9KCR4lUNuY|m1Qd8?J>O)
zJZzPAi3+g_-^_%km=Pb8YA+E+G1LVw5jE6989d?2@2#TY7T>q6MyFauU12rQ$#Ykm
zA*6{LLT#<G^3LQ9zLlY?>m{gJX+V)Psp^BOJif(En}#g-7|9LjiI$luDQfyj7_l9i
zG@K|GtU~<$iI$u9`;C+`o$Yh(ET4<H5lKnqt1?m^a{!d(w?8sJy`e4?&M5cN=Qs5+
zXw#jM5`NeB!dN1qy%-}pOF7_UdVhJ6&L|wG8g_p$bzGVFUT{%xgDn~6te@0A!pS9K
zI;IU@sk*Y;kFI2@*&*tW$OV0y-nRyiS(#OGea-PUHhqgHrMvnDk32P9_*-EeGVYEG
zt)Jwm8o!{~;B(s|!z2Qs7#@_Fk0<(qA>WiO{pfaWiUD<Wy*55oHkda}V;XAxy7o7#
z=E}WTbiE7)NLBF*ZI`w9DtJLo*vJts;t0akqNW$SZ?%%9P9hKKh<OF$4WbAatuEUA
z)0Y)~dk{?ftHc7-NIe))D^(qz#C*;dpC`L^MxYYa_#UGX#4{(W#Ny#{ON%E9b+5XC
zBC$uSd8yQoTAGZC+)~Go#izy*L!+61*K!cW9tcfeIdMe?R0eJzKk%Ze{PzKxd|4^)
zn?Z3w$VOM=c~;G(eTBkmFintYdL`XJF({;EVm3CJ!B!*gZ+scamfwRJ(h96f@nvSA
z*0sg`TuJ3R2HfT0kTd{+$P{ie1$y8#s=#uiLJtfhHuYPHVaw|M1m99yaPYbnC!=}a
z(3QYb*nZ2j9EomA=A#JB3u<)%1p>XfKxwoUjGNk#WVu~q56hPVyETa2?GH|3=jJ+}
zKaC?}dF0F<QXp2}gDLD9PmK7(>fl_L^U`$Xh6Bj_Fqn{&bs(LS8P{CNV?|cQQYyyc
z<;!!RrP8`&&V<0s(vyQoXB&@33C*tAvcO1fV$cxu|IxS<xv%}}AOvU<MGbzMu)P}i
zAYp5a5=3@`?((2IBI%&-@l7{<nl}t6a|9;gX*Ja%@J$b!M_(PKd>K|s$Z}8d`q#P!
zFdn4b7gh@2g36#bzDXhq06sES@VHJ)esi~YB7ot&DRfHez3G2S>bZFYGhyR<B$KdZ
z<9}3%P|V(===aV0J9oBt7@cN`TX_3VcV^?w`&oI)z^!&bnOZ13v(Ykb<$F>3Anz}c
zuLQoYGM*jKHXd)}z0@MTHXs!Sq;Ewh?#O6o0qtfJy55>eQ|?FXR<qm%_+CG)Kfqe2
zgGOy|2k@}70=Ns;3UPUVTBkTetgo@&P99u3Qwj7dX9R8?t&l^4ZLL^Yb|EaBg_eNo
zzp$AJ=yl5Afc!z{+d-GLcRcmvsa$D0I|;}<apz)4w(jlh(z$UOJ%_1zwmwDZdA7EU
zQuAbQAg2{m3)&Je7*KweQGB#Mg|k{|lL#o>+)(fft=xv|8cS359KhHv7foC8xN$w{
zECicadrgMpiR!c|m3QDmH{Kz=*d(48h674xLH^Z$ncUCK4uIxKF!7Gg(AKo4Wdn>>
z(fJ0e?Z$(C*Rjx}*6T$zN><x?T<^0_<6LmAY)MtLTI$VEe}#ZXcBeM&jZi!0%A4H6
zI<3C({>#C_h{ua#UYsu#;Ce7Tlk}A>HwS^&t^I{c|3oOdYCP6{crFQBsjA36Tx-d1
zPt!jLPA?lF(pAD7U~Alp6M>_zs_BR7%!ZDoTM3%;;3GkgR?c6PJVaHq;P>$d2k&|C
zSnC9FoSe#D8}MfGrGq9xHC%J4Mt$tuwemZ#VGeV?=0xh{p0hES%32%xNdBu46*K)H
z)kRQ=i#>Xb+KPn+)i1r&ER086;&A;eR5Du=JZt*sFyM~;L90x4IqfVpj)O;*^OiH-
zr~t+hZ>3!UqE+XlUE#h3$zfO0{f5&rS}SeYIHf@A8Mjf2e)EBQHpr-DLmMR%Xs68G
zfrG(CGR>WGNKor?uzP>DTvWJhkB55Twrt<AcBU(2yd2mP{8u;Fu*!rUe~<Yf<A_nf
z;U<1lzxnW{&jDh&c>TIvmC$(<eu_r=Q+$~dpz4Z!HLRClpM5uK?~nuoj>kIfuPYB>
z1q-bwKma(2ESsEbEN~>c_3tJWjXWdd6zAOH3`O|{_0b@Dhqhwg;fqF9MMCl`9%3o3
zf%3rQX!tqlw$>q|q9EfOcZh)sM~i=?J^s=G2`pD@RA@&JMe=3J4M+eYWUG`Y#Tc<y
zpe3Y^&sE5CjtfwffaV6ym1{L|CCU@PMC|LfSks|GDQWepw%s7Y>Bt3FC*Ea}2&>IL
zUD{v!?30Sd1dx)(F>VNw#3wAaV2+88a!w&yM^hc~Ko?FY&~8pL78?*ZZadnUb4S1F
zsS}}MiWDa}l+u9|W?a9aR2A@C<HGjF|3Xa($Rk6?*vYYzfE43Ea&VA!nk!3Jl-V<&
z#D?5~vPBQ7O3zk!U&wu%CV4O68df;T8Iph$;XrCl07Z?SyG}&T+H2<7@jp_T0WWoh
z0cg}H@dWPS@}VQ|h_fVzhu8|=3&?7mSnnk+GghO|phPPfa%v-{yvHf#P9lNjqrn0(
zM}Ens9YwcAB?@PgJgLdn7<0$R929I^G%BO&kgTau<MawbC&2{UYQ9M~PyrfiG8mgX
zF1-~#T%%ueGyE;qi4M??vPgE+!gZJI2pY)LN|5)IW$_!i#cSf}JyHVfC@HLLo?ev=
z*6UuQ@Xf#bN;T5;C`^?%qd8QOB&dz*P9eLgjWSIMG9<&L+d}7MRfoaH-$e&kuUbUf
zlS+Ct4pU6Usar~w{K&{q$VJzA$}Sy-gGSV3uI&|ENDde}LE>sk*%!KrtQVqrD?nc}
zZnQX#yxszBcU<+bO0q4@FcfcET`R)9Sl>$op=@rSWGcWmwbUg>bAjw>feu!;y#$>&
z);b!dOeS$v-f7N}J5YaW?UyT5cUiwbf=Qg*M>VYaS*XUm)Y?}_IFNhBCl{6m>Ilt#
zD2|mZJjt$u-KT)i7H!!^1>_Dn6G6I|8tWiFv2(!-%f-;05`vD50#6gIIooy_-?LI(
zlXP3<Y$j5Sc8=yT<ZRuv&I{14Bp&5~#tax`P0qK-03F+731Bg#qTm6f)zI~nX7@3X
zhhTi|-6sfZ!WCdkwVZJBSjX$Q0|kYWkI@K#Bynn^uv0W~YSEfgp#7t3m-a^AJ;ElD
zL4bLi8}a$pdLi2()hq`_M}DsDi7A-@PmWT{jN7cPd`H)*qvDB=0D0IldhtmB$~uGZ
z5T)>s;9aIwutv?$c+$O&=n}4i4M7k-(dIK-l`)iRRri|2ri}w}#^l>32U4st!p8s%
z_JQg%CRy0&Z!olSUsL<|V_$!_SDHd}4_){RYKCCb3%ga?VIOx4<c(xcEqJ?&Il2({
z0XMOq3TJaH&W`q=<OpjSZLG@hTyfG#2S{<CapW09^~42;uc5taRlHOVIVFQqJ+jnu
zn*1wCA1cY8di*S|$kO)lH&oHuIU2|#SaWvIJ%O^`$IU8HbM}Xaik*jnU<qxYisWoL
z8SNYKnOeBOQk(*<X!Kcr_P2-gX@s_ynbOpA`{q~jjYC|jVTJJ)9jf73$n#<L<SJ7x
zXd1V0#ibgqVxE1^?nyMFswLuVHD_RahAJsEXGn<iEbk<|q{5^fQnSR%pf(>E4qW;U
zVwQcBLvv)Yn%#SKUom_o^qXY-q(gLp{z>g3wC!9>10P7Lea4+6?Y|667q{=@n)NI6
zw?@AUwxYbo5|VjsRFQD}R3U9a+Wkb6xJ*v82eS+eD}t6Z0cX%<9}1>CI6YkcdIat9
zev~KXry~cJ7UOPs&Lc0=`p)1Lo@Q?2_+hJO?WsyknovS>0N)HXeO2Nbhz>xH&<E0o
zJ|`&DT)rMrO(m~fQT}p}Ow`)=Thq1pStY-kuU`YICN@A-4XH<!YEez1R65C$+HCp7
z!{1m-+JWpdm}uD)8Ds|{ZMOFsN`=H$KG<;C2z+OW)@ip@ss&y6(c|UAP&~P12#;-j
zda_Xa_hl`rPu39S<Xc?_H7m2U6LbwHJX8#ceqFNmrFP<ag-(m;bG@&s;{f;S`UeC)
zOTeCz3syCi2^%!30P#XwADnD}pBLUQTu@E0zo|$)G}vmrQ4?`+=gMLy6{=>d1|+Co
zRi_r?plD^d&s$`}2p9yW@>n#c1vE{ju?y{vv`+kHSq5SSDP`s&&4LyB8;}&jSvItY
zbZ3(11D3qt<Q+gK#9g%Ve!@$$s}OdHe~;gVF_Zd=(_$`kYQ^D1%A4hQw^d6j0%yfF
zEj$rGG{O(NOW{?sXzCjYUS2?RsN6fILtIjF@=hsIukU6`ED8%$>_VffB+*q#n{0_w
zq(MwD!*iI*N~j46P?;OS8djTiWQOWZMx&|R+x|Ins7*W+19tGUSsS3A1V`Hz-5U!>
z%RR9_7S~VHc8FE$N>*y#(c4gGal1Y5Dz$8ZOKURZ*}LKp9=X`Vo|wr9+nGz(?Wxh6
za~#k~h?JatE*wP=dDdzobnYIWvna@r=yiP#CV0IPl142I41vP>v*^SgB%-?l2}~-n
zcv4W65ua}$`?Ie{B6+jQWlgTo-l(&L`9O$(e9002b?rj9!fInDbNhwxuJQsl#W$0P
z8=Us(q~liIRnXbsXwTB>M*3!j_0Gf}l8CDx47w%lmbpp@YR6n5<5X0b1L5=B>->LJ
z;}@z~;#B}vxFr{`CzeG5Er>zeiZgxo>L5*)leaCPE0>e?bo|_D+lGm8A&gg8izE7I
zlVZH!%R>Ilii0F)E{&v+fUAvejK>ZCY;zu_STLauXxr;#{&8qS2GbVp>(y%vJJ;Z0
z{5eXFBKlPqrB~kQb2YveCiaykDRv|7l_oWIL+%u4xk|f-!M;|fF8jw_rW}OcN0HAo
z`fTTmy@Y5_Ezw3%D`m3B4079PsR0#BM4N7%(gXI#p5Nhj;Y5)Xy;ifyTn1E_J~dt&
z=9E60w!9x4Q~GWno@dyKYfq%3?n=F&SSygHWoge_F#on{2+=0jQVRrZq_frz6o&M5
zbnt~h{4r^?9sgiY9=XgJ+)~`Fwg%divMzPCsx9WXId=0iM-=3(pYa|BXY3V?rYh^Q
zhh!uEfqs0BW{aePu1<=x@6h6}vZ*QwZUK^?<wJ;-wX6-`n0|`|c-BlBbKTEWHOhpB
z!cVxFMCQ<M?(r`x;GO&{)(sj05{>I;WPVnZ_Ui&VKueJm0q^T}#n#?QL%7FxLM)Hb
z9(+Ak$pby)XVJp=YG}{m_>30SbtgJIh7$xHQH4hk3oB|W55gH$Y9<fH8P!cGD*_Jm
z8tX4cyc&D#35|{Hoj?(Af36V*#6yl%8N|au#ir*4&1Uk{_eqnu=T$lH?r+jIZ#PMX
z_%%LOLwiVT*cl?ZTMW+onfUT^%cgwzlYo6S#ELcHPqoeapRgP#hjh?i0ZeF2K{t?x
zl~j=oEH(nJ^C4NpBZ#$9#j~~098n5pEBWg*is~!i^nb!C&H?h^#o(pg>oTZE))G#>
z(|8lIVTj=HsSdo<HA_yUSdF8XNt7Tni2}UQB$m`Z?s@}b2BvL<)O4rNuSZSyJ?H~o
zQWV>n%oR2g7Xa&451U^TQJNPR)YLuhgf*&J5NDt^d&=dHkTV~@ljAF(Gm^iuiw@mb
ze3gd4_stL5n!<S{Ghe3^U-M7n)MM8u<<z`fqe)=_x;5GJk~HRA2$iBOKm_r>7>qt}
z&>yu8i>Y|kXo@Vr<D|^i0*s%zzD29AKuD>t<U8XnDX2UOgaZdE&ixQ{rQBA)VLOw*
zW?b^BN)799|B6<lq&HU|4?X2KvHY#hYCifxobkegdq_cwb20zct%H;$2Am2-rI%;Z
ze>VC^$*()ug6O-)z4yns3fzWDYdsx|)`@x39`6qZ1Tgik<Zm?q;}4CIfa8+pNRm=#
z#64g|<*zVum9$m1`&f1v&^tZjltH9-4xk+A7=8)4Hm<IA0<&LCm0)T&&5YKS-&EDk
zB&%%m_$awDnBkbiAqd4xysp~4ounmt3X0UpJUA#{1iqdhVGbEVbqQfE8D_Nr;fzLY
z6nJV!vQ{_P;#vHi3ZcZ(7fl>!OO{Oo#}$@RvH%Uw6)kEgSuP{XY7lr^(0K4*T(4qX
zkOo~$mTy^QpmhrxU^-3l>;+TrSiFI4BP>NSgW9Xt!^^G~2u~;LsxG1Bkh0d-&!Jbh
z2Zt9KrEBqn%sWfQ?E)hek&4!}L;AHiODDgbVLWn06Dw*el?9#Bx~>x9RDw&H2}{4(
zAh5opkueD)qjif555ZV<VBT!#KbB5AK8d_smKzW~o67g)cBern(z}d4$jP2$t&zOw
zkz}3`FbXp%T5C}Md@_?-n(%GYkyK0gvH<NUZujMt0}e<&7RG>mb`0^q4Ju2D;CQC)
z<~iUpa&+%&cTnJX(_*-sUCFrPU@h(c(3Q?bg>k2hxf!yjS^?baJP&o>CDV~ETFWej
z_lArkjLcrJmyYDG6?o~u_@W_wQhfTKZwCaxN8`_@n9rBOr0+5o*Q?C9g(QE@V!B>$
zUoGSkUl)e6KR?U=>iT$ei~>Ks>pJVdufDp^>vXw~FLZjoZak=VeI9-sdb2)WTmgOF
zPuGCyQ^1es;w`Uto2`$H2lg!;4~@aIi*|f2jc5=4jiEFCyD|Rvi<D3Ag*7?g=X=am
zRq$(!%FB7z>#VIVxZuO333dBi&$4Dv*WVDI&un1VJ5a%KN1e^1UBeTb?@7y=;p{Gi
z<>Hz>v8aQ7mOuaa5De!E{XM1Yvl8urH>VSNw)U%d;ZVD-;hMMnluYT#6o@w<yiAU&
zHIwm<g3oWu8}DWz`{O!<LDSd^as-$Y#ajmS3GCt<z3Jn^e6Lk{{OADge$5uTk>S(h
z{XiJiWl<pO4kyeYGItv@s(<rYX3g3L_!p>r6|%L;UX}8gKl;&}H$Y>nqb^!4uaNfP
zI<P9?RWgLDb5*`!GS9EnRs+{j>5SR;tcd8JU8Z8uzS%p$`su)+ub4LZ(#O!_Js{N_
zm-8X~lvw-W^%?u;MOd`Z+*=oQ-H3pi+Tr9i+&1k)z6O}RKrB6Xq<wsTmB3)QX2*Za
z{1@nk9Xj(m-It#J*M(Qw$VQ$Q&N~n1(ka{AzROD!(X2hoJV2#y&HVawPgCzDfkB_U
zJd!{?Y4vDJ(7^D?aq{iR5ow1^j&-29t1{TIvpB6*xud)h#kRm)3RT>uyhlCTMsLLJ
zGsTii$7$8F+_~=wdCH&R>1eClzixbvvt^|7LTfpMTA%;nZtv_`$@i>pjheyXsdRcs
z?)?qoE4D-Pb6~B_q~Hm02-)XM*L$Fe&n`btR^}kgeW?ca=XEK0+qD&|YXkqn{^3U>
zjuzzCz(+kb5hXM^KWKe!5zi}5UPx@VRV$vQ%U>O3AvkTgLjnei)0W9LRr+=w6=jMy
zuF4SCxyx}N`F|nK(0PIj&(LSPgLA)xzYm+=(Xa`Cf9%N}?aO~OI@mUNmxU!>TQ%@+
z-9~3O?BO-f_>`T5e_AzguV{4mar3i0j%{^!20X`cUYDQy4(Y`ebbK8$PdhGs7XQnz
zwQMz2ZCvxhzdBj}@(E)Wg>Vs5Mj&Fty>j>z3^gF<X!A5O=oWDG`jkFJYm|wNhp)^Z
zy7^e0ka{h=0Jsm!y4>%2sdN8ZI)%Q}P0+OjxNj^DRvIKI=gX73zrO};%AT9M3CrTb
z{mxhND)`lSx#wYmwB_YSntgl(>-?(zu9ba4;hD&1{`#f%=XU?!+*9Zo3U~MD;EQ6_
z+$qZ^u;M*}BrlPxuJtZ~cz(_L&+7w*ES;FYLua2LTL8^KIAd!g2S<BjeXD=2Yz)ld
zSP2;k|M?~)BxL2}WMla+|L1@BJUst2F^IZ40u&wf9gPY9&G?6>&-isi$RI38$VA9s
zsQ*Rz`2G?8H)RmBv3C4l(!c2#=@<#wzSJuGN9arLKZ9WYA7g|JN^Z8sgbecfCdPzh
zgiQZ3F0XHI{H2TOzkL~GjE&6ng=}02HNRMl{|uaviJ6g+Q2Srv!e55J<Q)iE{-*=L
z-p0xHe+}l}M*hY9r_0xeLGjD9y}q@B?LWp0-Tup#Aat~MGXC$K@RyW`v9p<>u>wHo
zALf7Ns$lG3<797W>_GU>x+%c@e^X=sy8mZ=|5+(%V`~#fQ$mja8J3utrK7PuA%mFZ
z*UE|*8`>EC%hG=YnF!fgINAQu^&gkHW?ZOwxT1+R0#6kecsF=?=Xg_LNmEI`#}mN<
z0|P-o6H!I7A_zghuU88ih$O<p+@h%KND=x5n@nHhkP-UVGS#BspPk-*6IOA7-5f*5
zM3;9YsntPaCr|Ql2cvI$a`^1ndhc9gRn`VpaRL8kDhg8)iI7CV#C8{yelPZUep}@K
zZcs@ig2Qk26?N=J%a;;cA|_Nqnfh@&kInmAj;KGxs`hDy;xNhcQYSs;K^2yXLC)LA
zpk@cpGdTA6s0Mgsbk5jFQ@HF+utt?oJel@tRLF$2#$K)c)?Y929hP$@Cf4~8C!tt2
zgF7>6^k?-uMkDxKwx^N1?g3EE>WPWSlQ~X2tVEBj9j;Va+;VutoA4HSz6Vn>(g@ea
z^jvm4crbWyoRVe)j$B=WERtm^u=$WCPsq;eb0Wc>E4Sc}P9lb+lpW$3$O<u&<R7;k
z>HWF!5>j1-8nh*QQ4NhC+5|Zm{k<2?M0v{nA0YbVK`#bDfy#iqbLe<+r#gMt25yE=
z6j`JPdQ+awND(8J-y78<SbXGNIp7;tQ0xhC9%Sk~6o0ICko=LpGfV?E3;WW_AFES^
z%|lo+*M!gC`T7kAP}!`YM-;*aV;{#YHJR&F8yQ~u>P&*V-PSZ1Y77c!vZP_i>eL3P
zS@#V4!r3j8u@(N%vZ>H0!(O~8f%DHubM{yk^_Az}eML;%;R|U@EH=4guIH`QpNOrb
z4gqr!=yf}1Oud~a(1s=~k}24UQO>N>GDSUg;^%V>&1J#Z+z;=M|EvqD@cI8qwoQ4X
zmthfQ2?bK%rt^GM4(WP4Z7hj({TZ6NKs{Txw!0YX3bz6GYrRZ`ZnWf#oke{~9JVj$
z%Fw0YG6Td5|FT~e?wxGNTDVZ|;s$-|Y<?VmK-A1;<6UAlgC1e#T~Ws$OH`-}HICm$
za;B<Wt#zXLXtaL!E89Ip<_}F*I>;C4;0S2R`fYeBSl4GzM2S8&ApMs%6OdgrwOZRL
z6=?{sj%qijoa+}ZtU$NBNUKfKe^I;MZ>1(1u*{H>dy+Oc>tyAdTTVXnV*gwz#c$q<
zP+T-BfNOoYD6{sB1+9jJ*kA*roX)1rI^y-&u3Won0%bKg$>Jc-c7_iv!Kd&~wC0OS
zrq2RBJR*goHu*YHxt@r{1;U&-n|);N>iep=VLO*jdLA7+2KE_Zj94s8Cbv_{rS(_d
z;t}ah*}GF6lM0%}Oi2aPa5O#8tV?ml0FCghU1?UX7Ooa>6^3|WhXU#35f2OAhpfp>
zu_~ISOtTGPAr{gg!hRth(vZYhLtifOAC?GCh)y9DJj`j)$%DO=Y~e8pL)3e?$Ysdp
zh7UE9V5)u|iOND!1tY75RYU8di=IPTOIj}2>ZSB^DV$@G%&MuckWTquXFN{I992)0
zCp)S-F3rz)&+-<`c@@OrS|Xf_I86=SsU}p+8tc9HgH0CsnTQ#<CGL5}DCAjcU9zfh
z71D;p*lc_$#P`?l2OPMNol58Ya$lRtXqfAKsU9PKQva$Z4Lik{oTpXJf0SB63(3<!
z3Skyd#4<*@<)+^#lR#Q=)6BeV4+&OHch(n0quI(;<IGzQW}EnZZ!vEE^j-3OsIhYG
zh;^`D?Qo9E+@<DnRqZh+9++fWcQR+$$SmcNOgE#Wx3)rVoY^S0CaSC7^_x2hPebj_
zqMJjNl^4Tvy?F5SWI7IdLDs$dSlA&K^D6gV$>BlTkaB$py0q^;_Lsom3|J`$zK9ok
zPUm1L<X=j|G^P}K7PdLWQ5}s!r5{(=m{BSu;7&P`Bh&)~quJ;YLnm2xyVV??S)D{#
zJaThpTr}n_%eQQm=)wj13iW>k$9_Rq%9I2!pd_F%)9%L?Mj0{X6ZL1Kxcos(NoU9p
zv}XBjte{!((nW^!O~{EO6x`VK;Zz$XoY<V0sg#P0x(G+1xO`2y0mbr7qA}j+(P^xq
zHQ6GRTIR^rMDr*F)=%G(uSWd$FwGfUjicISnQ{zuTIAT~5mR~$`|q797^0yclgp-!
zK1%bClwlaN)@VCpA@C-zmbMYr(0$)RoL6pdbA`Q-7$Qy&L*DVrFDH_5RO*37-;Pkn
zS3~|J#k`85GMxOl4Up^>JvgAZXb_8Wx5x}Wy*?!&gKn8J2~f3O+jL!zVb{QCiF}{)
zw0W_;qoi586<Z?=Puj=DjGv9WEcZH0jRGz#B6+@-Hf`lz&GgMyC5Npwb*Yn0d=kBx
zj})9$uNCP-%~qqBUB`1U^Ck*;D$zMrY<H?s^6wV_RtawBxl~{GJmdS02>ZxlJYxC5
z3Wnld*%&)4b^07hz%Fy|KW^ss`fjd<bYqU*C45$OPp{4hhT15xqY)Y+*rKHK=L*a^
z&Fsu~5E9cEsK7otJjETlgLNI@B}Ee9G?%sZD)>1L=KB&heYDn5icQ_`ij_)}oU2NB
z_T$MTeeRTE@L#!{ayv@J@{a{>W^QC&pRDTK(pKEVvb*{)E$?HatU3t?GZC5i<{lv@
zT>koNY8s~E5Rp(R2%SRC2<`MjN{XIAu7*sa)AUQ&3DFkcJ;VH>sS2GEp~Dk0G{ePH
zAjAK**6)0SQkjQrxQab<qn~J#bS|p#R^UPjg~YjWn)}$faJkwn!_>cry}n7sZEzI<
z2(PWR7J0iho(H<!Y8?9I1&YG%KnQS(X5=&E8RFbz9yiF3l=9WHH{ag2Ix(!Z9JKHO
zr}%|6G{3S9bWG(6D~N3zWiRO`<5Ol)Mu%T9;bp3||0vBh(l{gI2y&Mr%MSUAEjv;e
zBOz^D5}y|(AuWxSa{?PS4v;j%zDxc)x=K*HoU2#az(prG_k9oTRv@FVkfR+Bs&K_5
zFZYJooFH417=26UXIIBzOO$pM5M?q^Tzxt>xIjSzEA4dYt#xY!F)A-&b6`dFqWodu
zmFocnHpfL`ZuVaG7xpHCZt-z_V156+fV+aEd8tZS3YQdOOw@EdsYNZ4EMqsMH6sy}
z0TI$0t&Yru_*M2t#C_07#OzW*$Q-b^2>_EO=w)Rx|07fUd&v|H#TK@w(KhVl$ydSx
z`U;#D4^Q=#z8`-Hw%qRc2MIj#_V@eA$_Z9}tiHYt`B1J*{k@Ws8XJR0l(Bbm&$S%$
z+uvt*u!j>vCO~&Aw$!S<SO{eM{1w3VCwkdfKLhh3mNxS`s%n8+{oL-kVRK&YQjn!)
z1H_-NM({IPP|TB)FZEu)K#9{I9!+e+u60eiuE=_;X6vf_JLb$sRcOSU)}7+gR8|L4
zd72MBeJHXiMVi5!Eso(jRh-)0nS5H`F0(4F`k@}vBx!^LTXzo`$gPF)Vd4l<LHJ1{
zQQqeZ#Z%v<EjPl3Ocb~!UDcgrqC^>qhUA`Ew2p$@W*^g6<}PH%$Rzxv-%<|G3TBWD
zE|#%u+<YmX%q3b$dxT;;IHr;w;(M6~vXXL(2~UX*iPA^BSVRcs5hxkR!l>!v1j>ik
zCzHz6;rtXSGzXKC%hWc?NZmGx-))6nT%HA5;B>3Y-=tp1J*Pg&U8pkrTE*gKNR!Ba
z(Y)NZ&9aSZ>=LSYF2%po^DiloPncoPdP=wh3q8`S<Yj5G4+`S%V*#7P#94=|(8X|E
zKZ+V8`uS2(>r3p;hTTacqnhLA7(0zyS;`9kYI6(V)fN|~bR4d!jrS!$74!+#O60-p
z@(*qh_3ab!g=5~Fym6(JR_^RKSy&ifZQ)prQ;NBl#o~uy8QD>0;pm}&7=nOm!#co4
zD4))U>N+zPkF_(lYYgS|h6a9<U5m&0o0}3&d2J6~cI~V-ESvvVb}debBGZvrSRB+X
za-4`J?3)aCLUjGl`vQ`a_sQ2NyZS&r(d=O3`D!nA8GlPhi;>2qaZq(}rTtKcBiSbD
z?Vdv^`K^o&%|Nr6no!y%!p#Yha~WZq*{J8ddIi=R78LYHY<;JWb7bg63Sg4zt8)S1
zH6O;+@C^^Vh@d^JEW<iGq-%?Ez7eGfG$^`Rp9CIk?_gM&INs7lSlHaIx4%EkZ<kaI
zj-)v4y)P+`?z+vXX}BgXVW%hL!@?!>X<z}ixM;uQ=fi|zi1Q_PwcT3u(NO!#{`eeZ
z_OBxc6ltE$!+ab69>a|~>QSEtyQPeipGU=x>jW@wHHWDkY}x1~`TE1f*_QBygZ+bo
z9{f<jr1oXwn3afP%WcVV)goVsa?-joVeQ)|au}w5-{!7q32C-3Juhma`rx!2ZJ53>
z?eFQ%n0I0K$l#3Pj1At{jn18$@o`(bMfSo(=-1Fjzna9Y+$z@m-245K5<B~ctVU`#
z`Pn65!w#d2Ayh1FF5$j4{i6;GEp?jt<l+$3HEbm7xh_S@$Ikh34)H~`)MZ+jX?HM-
z*W+-y!K=s`hpX72yZh%xUDe0O5qI%WM3=~$2IpxD@vfnwxHl!4B)M2=LSX(uHNSf?
zwsW$R+L<n%qqF=w6YMW<amh&dyf45Yg@g|*zp1O7X}^-hsa~fn#9d|R%&6ULkyJeB
z_{o}^m$U=1ldRdx$ua^nzBaG041KK$*e$()nht1pSlnnjypf~CT;fNk+r_~X-4nA6
z?hMg&zZs6h)a9a`DF4bv-ifNquSVJVF=nzmHVlc>;RMm-S0U7?BKj;zj%}nzxs2Z;
znbZfX-Ivt>TdwG0)aX*=c>AjGW{qx><l5j!F<`tZJN>xICfsDjI$P`ahD7e)m>?lY
zVHm-0P&I<5FnuAik>v{)uTr_v;xLh>%{?$lW+8Ew%@E!Yv2=mLZnKHTULIVb-D>py
zmrQC&l7c#g0l2Q!+HS9v^LysURoCZWUYbBi!od+xhga7-UN)n_XoPmW0CC56`E!&5
zHbHEc8x(jfpk+j4R%m!E!j<w7UzH#$i3x@Wp6bWvr<%Z3-?;jj63gi2i?Q?UuetY&
zBkOhVS&kp=sab&L1fvyE@mYl{>;&&GQuNs8u2gq?evs&Q0<l5_Lk^+U&xj5l{>2JS
zo4p}?bk6tEA#|$D&uL62fHsLW?SuG+pG)kg&&QCkgE(DJUBsp}@`{j)emO*&iJqKV
z8PV9V;<7{JBGI_xK&SRT7iYxJlmxEjJ{UZ)+M1NuJ1t^%Q~Z?}i+u%#i2+SEeUcUL
zN04&k>^k?^hzX;IiqMIImFsT=LoWK0LEqz{y<CV(3o%Ee?Xfz2EjdOnjp^-CPxX;o
z{J&}#bwwv8P%{&l-OQR9<+A9ygLuf^xGRL2;Y2UxCuNDABFz=<<GSJhVF|R%KZ*r%
z-Quakxy=eegjkkBobU%(EbKic8IhB`;Vy*6av2gR#CY)HQtjo^@MB6W-6T#>xD`l>
zJyntJ(Kq%x&luMK(vj=kr+vfy-5uhHE%m!?1w~<#9F&sypxL?bJxWXHi0H~W%?3z6
zp)cx){Nj&Jg}k>)VHs^Z^*#$e{0o*d{Oce;v7FZlGo`TP#f+;05Wx`pnYSv3R-g(t
z6^hdcZt*a|t034h2u>lIM)Wz!<L2smjPCsVeoF=)jThi_M<-rZa+x)e6<>M{9AC+3
zQXucE6hK9?zi>pkaQ+?m6&k72#jV_gZz)9CNQt?jPEKQklM<hMrN8+lFgPba4KjiM
zrL;$`)ft<QnqPi{`FK;a9ErLW^L23FaKT!i{Smp9o%y$o#zesL4-F-}KP;Tpvs$U^
zCWSBJ*;S<ezO#X=GO(Bf4D0WmWMR>vh}pdSw}%%`6Ub?RX1ICye!d$kT@gv+vQR)b
z3Om0k&INVz!sinO6kWYYt4O#T_ib2xxM%2<)t?l@%<BAo`f;z7!bNf{F(e1%l_8uF
z1UHD(k&b=FGwGrmWC=u_6uCM{dyP>to4uw-4NXQ>J^G>c(?y*pgRJNmLsA5@`WYph
znPludQozM%sM+mLQZRK%@LGky7Y~Sf&+*~(?^A)_&n6LJlJaALn}N+t=|%6^9)WFG
z!z7s_Mj`+Ny<zx9mOpaggY4x=7(p67DAW5vU64Dkw9V?ETP@p~pzIKDswkayJ-Rg8
z?kJr)Zpfb+-3@ThWnehz+YB<-g}w}byB9#OTYRT#w?_|{-XtNl2E$T@x(nrgJ{OWd
zvw-uVUf1|Ws9&2fcq)NnLU<ngeQJRm#dQ0?JcAVbRD(>iA{-uJ2=wW3ycTnKt8{1Y
zZpVOaVqRzY^23w>eSbQ^zD4@BLb$TS%ffTCjPFvs+Y;kM!*h^tKY?vxTqpZ(!MZAT
z+d$%?+lqAS!y_d@y%2#mK*wBbfI=gq-39=*w~3v%*#*6G80X=jh0fUpml?LB;7U-h
zTYb$zyD+MOSUL_p<sJcV3kJ(=Lw!$B`Z3Ttf_b`T{u^LA7}ZkUvdBuX%Qx{6SHu1(
zTGs|lfp(J3V2$w0jSC}9u*;``bm@lA$p*_>X15be@@Bp8I6Mq`ia|Z>uqBLoB;NHk
zU~CmGH;87{n~-N|dKYOVo|V3=2SJ__sA_egN&J}m2SM`q22+qb>Y(MSPJ88$6{k=%
zaT7^T0xNKtDQ@~fNMkjIZcK@J1(E^P<Nms^YOVddQjoMYdNsbHU>I;P4IlPBU>{PT
z@EF}c2N?OMhK`_j%s}rT#+`a_DaIGKsX*(}^nQQmS%LVOrq}9g2KFJ-{axa^*_Ub&
zgwGg(hg|O#%oXhi85lmQJgr{5ZwRFHIk>0{V-IW)82&d#9Rb14LHIO6-2mu(!{-2X
zM%iw)b+>bn;kzCz^IN8i9Z-fye2f7AJXT@fJDAwV_&y2b+jt-<Sn%GkEofhGnx`5X
zLKOS6{P$oiMzwA)bjA{}OLRv0(@|))9$ymMDO(uWV}|X^Hl8<YhV_N1iK|<Iu1=^c
zOmin;UGTp!!|2m(DJf6Z{yMxen`7|24vw31fw*|?qymkg>Kjg3WI1g}sn}doEQG=#
z*4oOO6M<FKjwAk)nf~n#OpcOI*Rq1*PXZd|vBewUrGm#;^KJlk2q$sWSlXO`AMvqM
zq{tBAL^ZJAVuJz=LfN}xzTLxzTKF%6q69=?fnG%9;z^ce`kKB`azS~5wS(nBxZ3&y
ze1qCGz`M0TE)8s988c?qQMUV6CQYXyP035Za5*N31aADb5D=iTHGGk)F(LB0MhdG0
zWC+1b>F9JGX)oS<c8EULAl}9(KDs~?W70VOFRuL$$ogMgn}w12zeqFZ|Ak|j{(+GH
zg-J8~|KYL!8-CS}AF~c%L=k=Z2v;wP2n_+3APZC~{DI+BQcnQ#7)y+9h+VsV#l07%
zPzwL2?|HL4E@Xe5huvC>$PKy9%q~dZk!_n<H$d?ChM6nrKo3y2*}1zWov8|&x@M(r
zXTHu@Ugp0afRw^&S?y8l5Q7W{65pi96nP2O26UjQd^~+emOWMxSJn;~@Y~hl`dpQP
zkzl#{A$7FZdNJ}?{JhR1gx~cOdt@8~a|;_Gvn{7=wm#S#%RFfEgL@3w-~{?^15)`Q
zxxh?PRGBM6I_NK@*S<H=yFVwotU5`?PXYoGMIt`f?9d2dBkK97!t9??hjBlpcH&<c
zMT&&HW>S6uMS+}(_oDMpc~_}l{0_19V3TBQmZ=;vfJ1b$=fsOfds>IaVR0{}Ya3Ok
z<mQVP;1CC_lHvo)j-fqnX6JqDrp`pw(;GB{v<UhC`s`nx_>a?m{$%~H&zSxJ{{M@i
z{~NjgXKz8o*ul`=%+}Gy{vROzU)v3``c_|i2Qtzc%IcytBF5(WDo%=DkpBO)i|JdL
zS-KHY{=d4+t~YHM3d8sO3g1)%P0(Y9IH7lxc51aro!V`^_CiQ3u>?6mn)d7W9-BY{
zG*KkZ>(BGyMB)ieg4-scacc_vcdw2;?*m<!N>U`IbFG9-77-{zqz;tfxiwpxEvsUi
z3-aTZO~#mFp;B-1{@9)>xWYSJncY)vixMOQ(|GBv&HwxoX&BGOQ)jS;D92n0CJ23^
zzzF3s8ezKq@7Cj!A7B<7DX-p}CigJrqsUm-w5!s%E&$)m!Imljm|?huPe?d1j}@SW
ztqO7bZmVV0*iP^(zuR?NHlQ?-WG}AYk)}htj<opb0XjnK^%+==6DC>V)^YbcNl)u)
zlvfgQEnUBL#JmXW$ZmA#r;^hgB<65FMosX3nDsDyf`Z4xCqSh7XJwh>2!7Y}6L(q0
zOu0gJezj|k6N9kVBgWb@^y;xB+2>^6UA^9Cphx4(SXT=<lkp5Lj?1>)-Q5DnK`orw
zl{RZ;wJRo})K{Q?t*xsEhI!+MJ4H%Ss#22iLM5L`eIlCl7d?@{4$iF%YQHXgioFX5
zG<Tw2e_g&Ak&yEd9WQ~jM6uY2py`A-WqgUM(@3U>+L=Zv!aUGmaFPa^CW=uYLrwdn
z4mFw+J`O`IUJ#Oht|=sbsA0PEy<iEA5Doh!^0Hr|;@*6%GdSJObHO+JFXveCOX9Vz
hk#vrEIAG7!2D$Zh5lEnMt&groEz{`c=JDmr=s$m-bPE6g

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error-high_offset.pdf
deleted file mode 100644
index b629c7e6242145463bb012fdd78a014c93388d88..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67596
zcmV)iK%&1TP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryOJF?&tGwd^5B&+$RIOw
zD!>q6zynEdW_V!8kN{!VpzVR}fA7tRwN`M~yLE2A+h}xmG4A0`GWZprE9~oh|Igp-
z{eP^T=huJzdHl<9{%GTT?yq0}|9}3EU;qC9IKTe;|9#lk|MULe|K<I^|Ks@I{`dDE
zoL~RvVdvNX`t>hg7C)K)_x*G3Kkn1M#yEfU_y7O-<^9L~{xK3>U;pLnKOMjA*87kC
z{_A(Q_T%wKgzWaak^W!*{p&yc{kU^-_g8B_nxC_cclY_j+qiD~`uor0-~YG2oqt;&
z{ri7A{@vf~$M~QA{y&cY`S0H`;I{*{`D1Lei{|%p^XK_7{jN?V{7JXF{kXPIq5UVF
z=J;`sw)FzxPrCUXTo?OE_~+RF{J5{~{r%NpKc4G1?EmY`_uhWkxz7%SKbf74AND+3
zHxRz>_TGM<TbYDE>2@2pGP;5AC*7v!#>xfA=3m_XeO^DtZ+8FrZ`u9bug|Sa!k^5o
zpC4Np?LX;c{c|gm@O`)TOm5}uM#7(TyWf}Fuv!2T{;4H+&#T#G_xr1N|8f5D3HUny
z`U14sKesXoe=<9tpIe!PKk4>9(H~oxgg@zKZNDS4`F$6A1~*o+pM-z*1dQAJdu!SI
zsLtQ9|KD-~?7Ba;GTMJKyJ??WnS?*-_Wu7LTbYDE>DF#;Wpo4KPr8|LYhejM_=_jN
z%zv~$zJ$L14R65XpF0`t@8@=1pZgf??>o(N-^J1TlXs^7^3L~v#ogE@_7kq1S=;HK
z-u3U(dHrV7|C@xK=X3Wy|BAi4$$=!;cNf+BKrCKWHxb@1{6BjSjQ2Qwyx)tj@qR}A
zcY?@YV#)iwk8PM}eml4KRo34Ot4<<(+s)qh=K9aouPEPleD8yG-nWjTeBaSW3g6XH
zl)tbH=5Hx*zHfu)`*rvWt6;PJvdxO}{S>d~myK4G?>j#8W8vBUwo`kHET2nXl<zyf
z@6pe-FUnt7iT1uD`tzqJ;;+4o?JWa-ZnvU*Kgs#2BL4g;%J&`bkRP{xBz)iPc?+xO
z$7+c3ZO3l@vG#2Lg_Y=b{+M?kkAJrke@R5_-G13@MfrYuZ)NXuvlZq0j&J4ibLETj
zeaE*-^ttjy`M%?Gf3Ca;e`PJ6_qS45`F1V-+SB>gF+Vq3QNEqx(rNwU5-!U39sP+8
z`_oIx_Z{a9=4~BC`M%@b_fFCJ3+v$T8`%E*O#CIG@p*pPXhr#UYRj<mvC%~MzFY6V
zta?$t@A&TUx#~svzT;ch|6KK={1wq@ykEolr)T1?$xd%E^_PuSlt0<ppK|D@jQRTd
z^@sm8Q;zBWZB2aXIXTaEzfW4u{?{r0e`~(mHQs)lce~ev`W6Ap)cEiIU-8Axao_Fz
z)%lhc&h`2Cv3m3Nk2mW3@U$g~qy`qP36?C&U+4xGZFxm;C^C!k-quHuQrQFPO-Ydh
zl=r{hl#iA{s|?E0N#2zAo;`jcwE@CXHLf#${DV-#UDIguiLS4&V<)*jwWO{^Nef<4
zpiu|m{ht=0CK=;eq?+V=^SmineBqN)(;ln6{d=x&ae^L-7cC-185>`E7+dlN2W9c@
zO?k8B*eSj-riX^-F`%Th5rkq@5NO#7PFZlO{~#00Vdv4OlhTS$7JO<OpWf^_f+Rk@
zTUI=Z7WreaC7n=MgA$X8^K_83X7j!v$d#gyEBS#oZt)=1xJ4O5KNQP4ZgIhK#m1%m
zZMg(*ifKf#1Y@p`@`r-sZ<1?7!SOf6G@@YV7~+j3`^HEfffOTh@yCL1i$WfqdE!PF
zkMaa8ig<J;+eQ<QPVlISM<;mHc%V+OC|BVCDF$TPIVV_TV%joDye~Ad>;!|(AN<+(
z(2pRPMjY&M9?V5q`_JoG<{vMLX}s%SZ!!PgdIfjh6m+|CQ!EO)T@MV67k25DxA!9S
zCy(Bnv~CV)3rPsx_~b%BISYH`;135Ue6sbPqtjZr2*HLo1;=?&;=?qaElSMVxh6{h
zd4KO%q{h+4mVn74DLLt`UN<J)+3CidaTkLWEN@)NG#D-d7V=HVDbgmmC^<!or96TV
zO)TVfW0EJA<hrr6Sp9c9rg&~$Y~6URKU<%eQP=8UceJ>KS5Bw%LSBURk$%?_#_}!-
zmoOaytzXqCCevwiTa-B59qWDsDb}dh!lw|kC|vj}k8+=Etp)0%dK}T@pHGZ_uoXY&
z+9>&{Md3!7dFr|!Xy(BC)+Gntw=Owu9r!n8F}~+{Kavths<*9IGF}hwl~2v0aC7Bb
zzbI>S9YG0J>*2iy#(Qp^I?VL-HyxJz+<(U+1s~hPZ99^c?XF(Y;*NC~|8-%%Dc3r7
z?NX2A>!MVzU|+koUctULw_bTiwYhc6(ao(}4o}k0<<Vjf`X*vt2S_mmSC5Y2`PM6k
zr?>d(U|v4P2S~xazIDst^{rbhW^4KwgtL}s{zy_fRO-}2B5JmE%Mt0)zaWUTy!7!y
zvEkaeb;}W*TeoDGBr-^N%^p257hZUK)D4ffJzKXJk=4e)yKHw&4R5a9+)j9M?b><;
zi>x*W-p)6r;fljUX|*}<F51-g#v^ExpTe7GlGLvCpdCS}PQeYU2jP6T^cYOMOQxG)
z;uSL2!#-2Qd6UpeF7&NSGC`vDl51o1JzL=ho7kW8mS>EAp09#QUV9Vri;~&qjjyI8
zbR;Q1Yg@PcEIh1lLNsvo&I^-0dC8~T{N~vCut(a&76H$~#D#r6d`+NYwo@{}OiArn
zB>YVLXLgwR;Zq{s#Ql3}Q%qdA=cR)@alfA06*KRJMX7GFyH4(k74opSd*-e<lC;=+
zYF9v#Uli<$Hzg;@-^dBpt{8YgPsxNcH_@Vy{c!4>U8{zR@$6cIWjtJMgNijBlcYdD
zQ=44`u7F32%<N#M?vB~HiU#iY_=u#%+3^j%9&j8l3VG6_1$}1befItvos_(?OyMhw
zGNMg}<bLKiTXHO%u_Q%{oG^SsQX{-R_FURm7N3Y6c!1EuV=UERrd+fv@?^&eCvt6)
z6Mp8Y`Q^NqqnYzdgG;%d7p09LaFgV@c~e$vJSpedBgJ9FDOv=~ape8FD464Tz@*MO
z4v3$NgddLo3_dPxDmpZ--MGOfX%*wf*qiRGaf4C(gB-c;lacrHqHwGi7T7e_E7dl8
zBx#Nd!-u2^6>YUS-VC^~TT)0WZ9$=3VdSm8NZ{?8vc~bIWb6Ge?Ua#k|DteYBQ<!t
zwN+B1dsB2-3`aLTAtR6DqVThxTkB0ib1nHja2AK-M+eX1fLHw<+<+rbyWR1*1EgU7
zO@(5l{{ALJtKm0vPYfKcTld6h9GF!9)ENynnIz=sq+Sf1shjHMz>&H`1~@>9%>v~-
zDe=R#6%0RITj9hH=T111lxxVXaAE~de*2Vr?G@JO4545U$)d!5uuDpZ<8)klSv+4I
zyCjf$JeKxW0dR7Cy*aDR2iCFo<>+^4rUt!XQSvFWOV<X1nJgv$1EgTprTyY5&%P<y
zdjCr*h-05$+ANNrS|scisIqp+P~;P1lS1kP(It9oeB|V;?0Y^iHeDnh)~H1o*^GbZ
zS}1^}X&-n>!v<M2DLFQolH4&iy*`S3F=@Gobg)b6%bSv8laa|g_$FD!`@5xk#arkU
zi!#t2(Q0hwik@i2_JpXmDA@Oq&5k6+_M8%EJx60x0xfjvMd2<z5u$TT%<_~(7m0fZ
zPsNlt)AO0MvO4yB3TA1!ef@WBq<$kfC^k~R&>Cpv(DkrD54PF$684F)>!s+}Hd8M}
z&l7D!S82zL)BKh{geealD5#V+WL0esD08F4h(?6K9zihtNv>JL497$(R`7jI^S{O#
z4!y4JO52{{CQs6vhr_u`S||*QF!%@20?#viW)Ub{wba>d(8TJ{EEffvwWSEKC}2`c
z5nxdacH%a`N%6J~a8kzy3a1STZq32AM!BQmh+!~zUf%a@zBjFdXVL<pd@c(4)I-Tx
z6zs?LK1yW@Y<NqCM7!3&1!)4%L@lj@IYUE~nIyi3x5IVJ8cxugGSH4S_lJsHgQVq;
z)-csJD+6Lnxyo;i?~E44W)JQ<m;PXRtj)DW4bOsWi$YCZl!12e-Y>~SZ&D6lCP%|A
zbiD$GljxIIg2g8Eluy=9H@pEZBZWccNvoty@QqT0LAG&OEo|l%T_kMYw}zS@9$Z!%
z;GCWc=&g$~(2k|{(pAmzEj<*5JKS{!5K3zbQCpN)l1_7zAqvn#fi-L?m*`;)pOFk|
z4WH5DVTJ=;)=o1_DZ4;WcRd`2yVfO&Kzm&jURY3H-=x(#pI9Dk_VdB&XtST(8In=Y
z8{(s%XvV%M<LHTf(dFDY!=kwe{8dQ4J)fI1caU{$bLgmx!rzFiaS?DooHJT^U!EiF
zs@C<aoVgbk1q*fJ9q-uXXBx0p8@uMj1Kp<{=riv+EBopR0kum-I(xLR8BZ)Y9+{+I
zbQ8@S+0b+iBa@aL+URO?ws>fI`Cg!YTGtj&6?74Ds2v*Uq71ZSi*#Q5M~4c!NIBX?
z$@TMSrNr1NDJ??WCo=9XN@}aUW4Qf+geZIOqU6sct5-XjPy26wCZ?F;Oj2@&JSdBj
zyyroAQ=-*!et3L3jX^yF2G`gOTw0`@A0CeWcutY;#v<etO<%!15H{r;8(y1k`c#h@
zp85{NHiqo?2X=u@d*iW4xzA61$*^RnI0a!$rs+2&TI9)zJHI_*|Cx(QL-iuWoEx=;
zey5Dpn60u1aapA3aex%FZWQtQeJfCUpdFlQH#XFw#L;eefQ~l_o1x`T#71a5r>h-o
zYJ814v`~{pd{I&tXw*s;spaqF4DX>%oZ$f9rly$k(xPaJcoo{z6rty~i7C1|af%)-
z!)QD1!#24S?hf`3eYu1GJn|iWeQQG><}J|%zTDJ_U$$Jdp^rmIZA0INSkauyO3x6#
zMd7z0gE!Z=PxXpVUr;z3tue<Uu~XyU<Vw>%(=YCh&UuIX%^F|NPG8z0VYM&r4tfd}
zB|Bj^U)&+OOrUsL`VtP1vJ?1#7!Yd|Iy?MALBY>JNN5>9vGyulJl2{<<Jefba^Rl{
z%E`ZBFK+sa83Z|RNTN-*P->S!z;D2?(P&!e>DD-c#KAQ7;#f?*I2O~VaG_@a$|B(D
z=x`!fJGD@dG~221<YUrKF4TO~2@bkNVlS-KeAo+H77C*^sH2O(KDlj<MaoX`-(g%c
zU3W9@fuQ8rX6iCV14*BFuuV>x4x6}{ZbcZt7lnfx`W6P4JK`{-!G4j@D_YnMa_n@(
zs00P0!)~yfR+SFBvl-=?MPavrHalTyX+}2W&K*G-LBR2!O`UKAX&AN}t@Zbp#%efz
zc4@FsI!xDZ<ZDD5Kbf9zvlN^9c+>;F>_v*Z!7lE?fv3ah!|dZ$H;k2*SG%+^X=^pz
z*&}5~qmr=*apf8EJr*IZNvIBsPh+wZ=0FQ6l1^8feZcLJrl_D`3KSjaG<#E`fsKKf
zmqo#y18w?E$=3T{gRCEXCQMHNEuA(v6Q&R8O+fIA8MU89S)Gm`1;NybQ!#bIK8KOg
z1}B2^Z*u%DQtrp0<vFprqKiM+SakpOP-Isd3zOEyBS|?!ztt&cnC3<~3_H}+pyXE_
zI^+rzKS0P`;ylNGVUzH2>W=khKtgw}w?ipglw5Iot-Eu@^?pI2TokOR$FIh}oa@K9
zmhO-YlwH}qV=W{t)4pe&9Ozs>$<N9f>tX_zU2me}o;SUUZoI0x*kD*OJ(Ld9v%!|x
zork$|8+RUOxz&2-an@_vd7OK+Zg5v`E23C}lC0=3DF-PB)8YRxc<XwHvTu#7=#cMC
z5`Tv)a*@CbXi0|b$kmSBP18~Dyrg%^!1#D)b>7nSB=^osTJL)A;1-qe-W#~pbaD`5
z9wf{H3Z5~?x~HyTa#D9%7eP6a1Rlm8oY<X=bXk;S-$scR)}TGyp>%F8QnIrsw=xv5
zDh;-t56ZH*ElREvgmsfgy{B>Uqn(VB@Y1GoBM~p!X;3tpEEdJ^ZBj-uN)iu^hoBru
zN=Bu}wl^26*e0W}{Eeq@r-aqVOrlh4Vnk6|4hA~}g4ib|9grpg41&!@v4@k&Lr7cN
zMqtipFp9PvrIAMN%enWUrKSkC)`-#q%q}&K^AayH{Bw$RMd8>e`JY4F17qO(-}rgD
z23Qm@FUQv@p%sC=#8RJKb0VeH#>@S2Hf}uJRq*X^JCDYc4~jNk^7FLXcwqWj2QGL0
zS?3K0<2<)kqcKH?Yf-eRNZQU@@NQAasXWGu0#1>T0^5;S!D{mI%G;ySc(PHZ?ykIY
zT4dSbQaV8Ryv*7&_R9<u-es|^7J*k;Pv2#OxkUG7gUcS5D=2&p98-d$my{z&d=Bzc
ztzH96q19{P`NI@;=s0K(wt`-j_ME!?xd^8i$VE8CK=Axd`R2$cZZ-8z=3r?0(979q
z{4jcv+D-Ab!%Wm}oI$?Gi_r0qgIPD_S3d3S=BZ3?<go~S?DD{yvdIhW9+EP^D4IGb
zcf1J{OLAPU9$?bFNi!H2r5Q(Sp1W|gDB(<z0M(E;Q9@ROd!2$<5DZcmIb!6zizOzp
zFgu+R3OVCbQXyx2N-9kAVWSa4@@S(CLqco29`(XT$SC8KdfSC~-4cu2MNx-Fn06uf
zgW`3&DCkfCe^b67py$Xa_@oTquBi@K-)nxA8nDt=`1iS*8JxOn6Dxa#dH~k%;+;Iv
zYN@|q`7SQ+)D>}YjVEW)*$In9D}@xNc5#I#<^sv6w68`Z1vRvwuoEUk(RFHNPHu~-
zrJ-iZ8I)#<#hKJnsCF(&_JNb9%}1RugISvCK%06gCNOXHiEHPG92s`P0?bR@umF>a
zO17Y++#2jen2HqoMM4iUd=B>FXekig80}COyooDI27PczPFEiemN)dR!S?L*pwVeh
z!EHBT!lbPPSu|x$VHQnUT$n@yt4xl~a9C)&iEJ7gd@wjuHx3SubC`%Cw<ay6r+7&N
zH_S|tT9Z9Eyg>suja7>h!Z%G?uSl(7H}DSr|FVoN3crPo31|NS8yiR+hB+{hb_$v5
z8X^M9oY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt=ti`PiA@!t(y1^><HO8S9%UQ
zaq-~hm%%hBX*g~gOJgq%1^N+evqzG$mtM{R%eLN0Mq0@X+=i*s$gq&e;eo-Kt97ay
z?hz#Mlu?>VJThD#K^kS+ZeFHs@Pd{M7|2^1GGst+j+l_LvNuLaH9aj3K~C2C#*ipk
z^jEshO)mg8u1|FvXt%L>4jN;g<XwoYo>Lx(10?z}`0?_6@Z;tC;J3^BF_KfhIZGPN
z8_@QWlD-e!+D_kxZfS4ySY2c|t`7Nk8sn7Y1X@Wv*Vz0-i;!!5F?cW%eNMWXnB*g0
z6q0<(Tg5CN`m-X%Cv1Llc`Z_MUw3DR?j_&ZO5(`{pnI)#+{SXjwGJb<F2{a>{q*ED
zxT+T=UqxC>+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qefKI^uDV
zL=%Luc|;q{C+RiKq0xJ8{1ScVx|TY9=TcnY|D_N2$OIrbarrF-N6Qb~&_8{}LCDP^
zZ}K8wmXhE*Hiw+jkr5Qb(IwMQxT(4NP!xKJ&hW#gf4nieOaAjlql=vEZ;D*-D-|gB
zzP$9UF@%DS{Kf#Uu8X2UxKKnuOOwm71r0=c(AWbDm>raX2dfqF0aHUo_*Mol93Un4
z8Qsuu5mf|4qXDK*4Hz!;JmN=Ea!Wy|!i8Mn7)%YSkd2k&lfyw+M{B$&6!y{ZJXK^!
zWCopk^a!(lD&QoNelh|>hpjPuLSjeDB+m?NS*;9jV&qGM8OKk_@rtdI{Giw>NehOT
z!`aFp9@DSh5akuO)9l{jdKv`PjQd%w{D5?Jh|CBcIzU3GkbWeWUO`B20s@pG;U|KA
zU?Xl+RLpfOp#D_UQ-caskx`4nkSlE3RQe8tSS3XPSPdF*g=jUX))mIppu;27>i{V~
zBV7r$3B`=P2?!@^Y0Rl;vu3;&Tndaq*;Lfp%JIpdCn+PezbX1HGK1o!@Jo~9j=`2c
zA!jJgt|8uvk$9_(Xg+FSC+tNE>06Xs9&Pv&5~-pBnJt9K!Tcde9}F*Cgn3r{;c9n8
z8*+3IP!+{^tjwT@3S}~EBoA%DkVqY>cuA%XRZL~14#go>&}BOr5h_vmWJIXs-V;WA
z#&<TD7!SkGDjJj%M2wC?NLQv%Muf^*M5E(So^fM1*N|Ojg>xyO6}d$f^V-q`si@e<
zF3S1I4syawrSRHC$-q+A{2;w3LN{`b;zm~xFO!Zc(l?Th{8lXRYA55?eqRYi_h2CL
z0Scp!2ilB1PM$<o(byxF7bQb$u~84D6`7z1j8;j-N3Xn_3@xYVA9*(snhiPsP~r`u
zvEz>zTJHKjL(6l-m|;YFudJ7lXe%6ik>a{%ym%zSR5<xceHmN8c_hcgsBU_^7Ac3W
z$=r-8ry#f}IdZDZi_#G}57Yf3#U>P72XksF;68F{BIf@@E93p4xh_KPC&crwbeRW#
zabw0Q(kUTe5yqA>U^M>~9LXZZ6fe{8afK^EVNqg=N@7@)IH{LXFb#+?NQVdtEJ@6m
zU~&%ADOP)I*%n62p)xXz0a8laFkq}yYKH;Uq|!f3Aydi`F<^XDA_>xWwqz4S7}Yh=
z7|c>RKuF$E0%9sp<+~W*Dk>+&fJK44nFFL;Sskn!(xmclj5bQ8=tR~}d`xk8b}_Su
z>V+}(N(n&*NQFuo;!h%{=txTZ4zi9`J2R`au>f39$x9r3B{&_H@mWfNA`_H2WdIPU
z+$sZPK;>TrclQh}%k=-s;xfi-Mc$Xu1j@9qMToyw=GdYz;S8IBv0F+(i`^6hfvm6y
z0~u^~A^D-Q-i%>f%8Xl-ob9cVLu^&jon@~1vE}ITkRg#TDO;i+6M&c;7-xBXIMW9Y
zkRqqD)&_Pm<sll3rj@H`$OX?_#<)@r<~o9aR7VYqiJH2_C!&azSGg$HsH{svl6NI$
zE=mrcZz6MvD#3G6a`>*hWinxNpp{vbeEk+>Y-y%(U+3TRKuty%KCofGDO)<L(Qd1h
z*F|CGEVd0Txs^L>NZYRTTBC7SDY)xJN<L{HOgO=xyJm=(W-t<$zY>8LrHw69*k}?~
zHnB|@b&ztLlt|L16lO}&KDCHU(l#w(9H7X1KG2SIf8|D-vb6O;C`+3%R=nD$Qm~Jt
z<d<}`rz0g?XIpvNG~8L_Y3n(dP`4{(e33F8+{Ky9)E@YEW@*<}VV3sL69^MFWz?5M
z6=lF%8nr7&ei3qhxB!kI1$M%DiIoXPrG)%NNM1_lm;jPcV*e3P)@MQi4E#yX@YWu)
znBgP#1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsv
zqG{EDZbaAc5@i8zB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OCrs0
z((r1?0|%1D0a8L$(0XD6*g=BCplB=93>!p^m<)jpf!Oa2eZ$}$5JHC`UA#a%EQ1;g
z=i><BJAUS_PDAE`Z0A@ceU2+R!5qy+i07-2N!}zum%Kve4>kzi#4=E_5Ks)s<v>X}
zKpL{CWIIM87X{K53y@_If++%RIhKCX6jZ&mmqeav>XKKOJOY+!>KlSgs62tqCgZ*h
z!uI&qErDlz>y|JtzV%9wH<{g+7M92}L){$A8tUdb#JP2fZBQUQq2FydJqABZVfh5*
zv<>ek^u`$AMWxi>j49xtrElf{YexXfqScN7c+Ue<sttnoJX@!P%6Ya<3C+aEWZ)_l
zIMNZi@$+m5N(R3VL6#O_!(d{nXW=vjC2n+qIZ-WdGV2<`T?-UyQN{)vwc5eY-WgUF
zq!_QG6(~}^^+*t@x*r-qq;lZM?k@l=0}?<XWWflL09poIfCAVuMBD;|>i}sKP*<8d
zo_hoHqVYp`Uj~G_f&@E)<Tr7{@JBiLo4s(o3w_KG-CO8nHcm31#?G+Vtd9xjEGT{p
z2+a@?Tu^BS=NjPD4v=D609>;{puD;Z@Jz^HNo$gj-Hsq7M4W`qaTYw>vPi{@gdk^5
zOgu)bEJ`425r~e4tpckv2Nsd=?7|op-<8+^K)<7a@fIoPIN3UF!_|X{t)TZ7A*Zas
zc5|ZQY59Ez{R>-Oe1nE=gU7MJ17YtwHi*G63dWb7ty`|*vvo^IM6I*~Qj&;=hOZVT
zBJGcbni!O^BP$x9A^^X5fV5aan;g@S3&hbd<pO$Klthf|j9knvk^mg<r>toP*J{B|
z8p6h#OlKDGiN}UtX#lAxjLV>$I}WD7MGLS@QV6GcfRL<_Z0Eq>E8`f9!T|3CB{*{v
zM{H4YqS6RA%A?@~x8|w+nKud%N8^Vk3Sh|mvr)(&VEPHxl*VmFZQzH3iNr@Of<*a@
zv?s=@Vb2!~D=5bX)k?#9p}7X-+!0@kGPrZ{Nj(ZVHb@(`EZedJ`V<~5cMd5R=NBti
zrooL;j7l)tdt($S8>14R_AW*x;n^4!__TE}MYuKGu=5rEFZ~n+5ge4oJAw%BgknoL
z-3pDEq(mz=q&^gyaZ$V`DM;jlO$k0IWl^}wqTIbcsSrZ81_JT)xqEKhA!Xyn8uBeI
zTol1=X!7^H?Icn*jx8SE&&Dwj0BXjyc+QO>AZ*)UE$CzWHUNc&Fz$@UwrvoEwoNoP
z*weOsK+3)E+l+{{&yD-kIUCWcQ#K;Zwl+>&TaVKluM_qB!x?+FGZqK)*^gM9=V$D^
zO45GLqGZl~%;K7OuKjWWr9*4xee+z~<r0jzH)h4IdhU%`q$IQ6Our(~+VnQWCV8Ii
zGG6~}g>TnoOiEqGv88(1M{r}W$nd(2*JAe5w%d5kX2qP>Z5&ItNcCE+udHbHdac$^
z_A++hCF*7HaHPvDQax99jA(4n)g2=m+jDith{pC@JvpMeJ@;pfXl}2&#fYx$bx$5$
z+v~o}#*0E0-C)SQJ?6=fdwa~+&{lpzm-rDE`65jXC>UbrCb4v@)0k3CWIbqj!Hdm6
z0r{w#ZQX(yWujOkDf0wyRl4HTA(b6Lx+pYSe7at|xJSC8vnc>}C3#UmT*XZ!B;>u{
z5y4DBvn%qL!f00<F$LDnDB$BOh1#H$l$*1jpQ3TMQbEsXNsdmA^)g4K9M~1!N)dfg
zsCJ#0<1IBR1^r`@s7IZcBfI1bWy*v?(G}`RrK7hqZ6~Q&bj4^=b?FMfq<Yg8SxF73
zH=%h_O<JT6RjM~##L%|7!W*fPElPAcQfFJKLDeUgNHK_1{d&{dr)JojOO3L$oGeoH
z$~m}tHOxV-3aF_aL4MF<ds-iMJvWl3)F)>!)n{bp)!5bPz8N3j#_OB)p<xlOty?a_
zW_*ZN*%0FPNW;THQt<ovG$Qm5%R}sz56eUB7+4<4UeRTGfJvi&7#`vPY=(zq?q+;&
zZ28UlkS}E?QV6XueX~8}#oIUA!#cYw2N14wn0tEfTc0ccq`Ktj%KYFMo|nlmb(BS7
zw}IhF4TTx2_cBiojIW;NG>9o{@+G5LWLBzM3~_GXiq-9x)U7cyU-R6JcfHqb5SLA)
zeV#P<<yh{m(>Q`qeUe$v)+t8vY<-ehQg_A`8LH%WzU|#>H^d#b2<ngnaqWhst#!Ap
zN7#v&K%1mB4sX>Z7~-`R@L+D%2t1Eon<1I8DBR$949g?|?QbOt^C016^ODnGn_eWI
zzhvS{M`pJNoZ#h<Z<13&KVT(~G-qB8PjF(YM{Eq2zzsWm_iO8sq61Q{U$W>kEBhs@
ze=pMoJOjN<7vVeTfi+2ALVo<&`sByuzlN8h`!9}+4%5)_g0mwi?38bRA9^mrW6}q`
zC-K=K31I?Ns}DJ^;g{hbG<;MNUb=RA88DzPBU%3dDfarHy($&xu9zYEnflP)fG?`!
zW(vO&E>Xn@(W}*m_C_e)3z~o)A>5b<2a@A#5x8O=cn9T+i=A914|wMQn(&eX55Nis
zNI659uiy#n6*UBJVITB2CMR`iglc~Tg}fj5kZuhq`+e{oNzY~<dPboB_o0wzdPw_}
z#Gg*oj>@C-vJ&g!B`+)hG2#TlSG!1LOx~G`0><D%DkBQq!hJSvF=_-;9xphU`|N1t
zcVyF^@!zynaMjFS6NKPhCYA7mv(h#F<N;1H_#<(t%-Sdj4eV3O13dD5G8O_(`#z`U
z2O)LJ*qN^XUS)t79?++r7=#c2rsai5rd|<P2ukR)oS}$Z=u@{ynmqa>8X`j?76pTW
z5oA#qi?Spyg;F8tg6K9cMrI@e&S3OLT+$b}0^>Q3MM97WB%VtPkNO7v(!xiq(`s`h
zsJ(sZ$v`;<f&nEZe?^LYgrfwWkRn)OX<4r7P*6+1Wc)<nOTQQx6TAJA=z!RnKtS4K
zYmS6T!k6;QT)YJWP-$T=amEuPk?{;+K8r#RJ3@i_C8aTfg%StqrD&qg+RqF)>Q}8Y
zqVoDx%Z&a153x=Cs`wc^nu={o6G4Js?NL<ymL`EvtA6W&KsZ*vB|zM#DlEPjz;y&R
zmno(z*nP{wgHW)3Q>jF>7*W7pimy5XD(oaF_QI{3AR^ONn?Yx(YTVi!h-_OF#;G9u
zEl|ubKD<}=Kr5$A8xX?m7J<=j9XG|TCnVza0&|VgZn4>K-3kc!>$hw|unYpsZ4VqI
z;@eBng^NPo;i0){B|?y5zw=iI$3{OnA{~2~1S1xbNOdoUdJ)X-rFhCfyn}9)F_%H&
z`0-{`gcj!3ANf%b6t*bhKMp`y5)mZ2C=8c`J?Np(idfS{NJSLks9lCdgsd*SK<=P;
z0V<H|eiC4C4~abzgb=gFHC;wTOeDY!b3zEbT@Z;y2_E%F&jv!p0-f<8CC9H90HMGO
z<uRv-XyIc4TVABBPG06UgdO{-vxU%PuW%y-N-YphvK$f4fz*jXr;&tko)sk>ke^P<
z1Z6VzK9$VC302f~c2hzEqP7EY^dqv{E6#}F-!7{hV#EW*l#$&_S6}U}zqp2gPb2oe
zM-##Cc~AIxeN`Cy!clGf&&f<4Bu2w83S82RrE*#H7*g*FN@CQ#pOt?wz=O&!M)<x1
zb3`%z0U*oy4e;R64C8?b%-NLZGnv2{x`bo{533-P5dyGQ=?TFCQ~vIWhlkL&mG<DK
z+&0W@!RK-fb8arnA#yAZVeD2ShMUq4LL~Ks<cLHLFWd~Idbl-iOJ;+3fmgu5=><%I
zv=T3r35?rKrSX`b;y{By3QM#v5`u3^aJ81m#rP}=TX^9sAcw{aPXS}{!b(6g&O%aV
z$_tXhT|fusS(_Ih^5oFa^c<g=nx5k`v!<74%ZVQV9J4@zM$Qg4myDV#dCBe41T)!T
zQLvs!iCPq}=)z=_dV{R0g<{R0K@vBiu9ce=e}vz;F(ajZBE8EiQ6B$t)APbyvPD8S
z<eDu!Z*)UGnpeVl!(Pbfto)%28T863hlP{y;xA>$d8Lp8)jUASaTg%f&MRX)pwScE
zJl6_QR*RC!c)6oo$=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2
zklrebGS>PCBzepT?@80`jZDi$X<IgC5IEe281_u|%yp`iN<24hqLpi;oJwSjdgV~}
z2)cGyX_<7o+88<#Q(cx@WUmHjKl5bskT+F$Vh*fV&NT95y>h0JOY4mXp>y3Y#vw4c
zYE>0rqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0p
zJ1Z%AV$FmO(XXhxKu+Z~;GKp<=2iQaC7t(xZ&}hYSMS1ofNhf{9*&pNynRcPP8B*z
zL!eteZ{BqtJEV~g>5d^+i@-GcrL?RzljyNUdi(&A+E+1i>@i0cqbryW+3_rR{!#+H
zSJE_+>|IIIj(ee3HXM@my;D_TLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+8
z3@OKZR}!5=pz<y>ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$00}b0%o|;
zt5Q(|1Y!{eTI|Aa<0a@!OpV-2)*5*+Nb87#B*YEj=1|Hi+-xo@KVdHx<pUcde~3sX
zrf$T>z!uRh0~ijMbAVVKhYJ%Qcpi%YV3m$edTo&_=}h%bpA9OpByNafSMeHxv&Ad-
zJ6$Q>gD>!qtU@o?@dG)@uH0~-pezE%G1Y6JogY!=ERr6*(=<&`mMAHMUx8rIAGETE
z?kqS5ygyo?n`09c4($A{5KLmtc&8<kcr=T`1w!=>ubgxk;DeHTCc$r_kPfyCz;Rrm
zoB+@{f&{Q0Q!k?Rn0n=3;J&C_c38TDf;T4(+g{o2Fk`d!&x_DOt3D7~(LwUcbPkQk
z5&$P+iJ=$qi`;36CB~7vL>izVMWrG<)i49QLQes(6cp_5#9(3(q?aI?7R550jyO(E
z2N9v3qL31P7&?XPwuRZ!E2fpOQj0{SqetEH7z8-gYI4AMDqJuY7mCcd>p~7=Y7~Xa
zWr8V_WujgJ({dNk1@N|lLJYE${1z$3f@-KPhZd2&ypsNb{<SFSG6z7I7YYC%#9Ur5
z;*7b6yq7R!EROXeO4*Sle8$;>Fl2ZfT=zaqnnA&5Qr<dT@xFvvbJuHdUC{#O7z70`
zd^nu;gd|8d;kf$_5SLp|icwlK7l9Lau&eU*I9`IDb43~xp3YUqh7fi^$w|Su=y3cU
zM8fkzKLA#qD_)s^dM-SKn@cOr>;|S2%cZ@9-RI8u%Eb4J8f%#6&9#+22P@y<@;fpJ
z(481^fEsky`*jc1a(fA?&@(XZ0Eu1lCni=(uNxo|y+9iPqv#C7K7_UCPAf`U6}@mB
zki_XO)$-;+)|+@E?0QwKdkGoR3ku@SQ>+*B<|&qj3b;x4lHP$y>CSf*u$5kT5@{cF
z*F%d+AnuB)BOs>BWlPXZCkh2%HQl8YJUt8c<!BRz^H2@Hm%uu`fGYs#`AO**E?_tF
zjy_l&@Fg@+cNv_3IO+v~0aVgY%AE(9A-Kdlbvd1hiTX)N{z+y?TvhkGm=2lV1-J)%
zR(FaO4-`HZ0v}Q_NjVY-)?Fn}02KR4nHX;#WCG5*oa6wdJ$@nG`1bfJY}>t^^ZA6w
zb;k1-hOP@OggCpO6mp6HxlT?Yrkr@b?!*uz=I<wki~(Zq6eIF^Ail6GiGdizpOh;<
zeuI0rrbP<O+3qU4K-1X=g-e+`X~8Ogv@|+g?f_=qexsdQCVaY?7+MrE^u~Tjpy+K*
zz>+T30NCz>K;{uc+j$Uo64{590`$@+g$%{|CWiL0Q>LaxSZ#_%JLO~Z(dM$+#}_fb
zx7~_>v7Mp=hh5+5yyeL_2td9amiFt31Csep>2<`AP)LCEA`w8nZUCaJ*DV1c_MOn6
zIq9|`pu6KY+AmiYQQ<!+gV)^gRZ#ME7ZPsX6-h%(dflLet>-0s2-?1`UB-jeWzBf7
zy3rX9rW^kd(mo#rLh<V*AzuIX+7Q#f9wgxYAN6RlE<inXtQ}C#Aqx!DgUKQUN4}^m
zQc#aD3mMcy&1wgF${Ek)%r|*4qN_v#Ms$_fz)}k+E*q3C=_9W!S~mm`#i|Y^vas?)
zi8S3y$VtxlGWkg=VrhvIomhUN#4DDlC<&}nBq}itr7lX8V>Jv(dyL*f-CIy7G(uTo
z;f<0bvor?<O;+wGQMA*TA#pVdfaKW7gh!olB*!Vq6O0&?dsMM%0Gq8uY}6}pA%n4`
zNr~z#dm?F`AzSWp=rL%kGy()|1tmN6QY`SLUW&zNSxv^JCvXxjJprpZVz~J){I%+Y
z3;<x2mc;rqQlwa*rgSZYW0g9_IyXT%KwuvZ{$d}j$e?`NwIY;nJE8hmnWt1tR_`f2
zloftTS7jL>Dzk?Q1(m{^0a((B6@XQGGXt<nw?+k{<BKZ!OJ$BqZO=kTrPs4oQtAGz
zr{rN5Weuj>d8!LAyLxeeu3j9Vs~60EtN|qp21`Vhm4kJp(g?ybQ)MJUDXKKkU_+x`
z6|60wup72-22{~x!@^iF>Kq`k55{)03x{^A6PZb~_CtsZl<_J%6f1p|v5Muu%Akd?
ztFn0^>}ofRvGQ11&rqGL3~Vf5mIgQ$ID>&MtC!_H&kX2JJB93gtffXvAd0P(sSqJp
zn>ms7+REg}qHbxDWYM>>Sh6r&8Z~oZ*awQGW`#MLMp=WdjHj$qC;RG=mF&s@%VKwB
zrDZ|9vgBsTyfXEosNQZ5M(MrHXq-V=WmabSzA`<t#2?Jl2S{mF){8_t2CdvICRm1W
z796Ch{6I-USIRxh7M8u8r47p_kLrhIwnu@)gT{T3I?Vn2Hk}-}@^5-LT;HaL!>K5u
zsN?31SVbSpTfw4`<<Vf-$ntuiwB#Yr2+L2F--IP9%eTTZmgRpzq07xjgKC)N$6>+D
za`iC8s@y?YcC-9N2di?HSBa%N)9b|2p5>KdNLBf*5L0!?x5Xl&<^4jP(Q=Tn6lpop
zSgjPEwgaSGG+l;|eU-Ov1x6(+_qwTc*X4nJjO^D%_vFQ~6;j2su@zIrvmuux3%wrY
zwq!Nfa&59=th}G7DJ%D=s?NfNdVti&=4NI2+VaG%>b7*%zEu5I-dq&OJvNUotLT<j
zn3Z;2SwLBfw|vX2)(ii0jtzT3PU?=NOuDgq76vXiH|qwMD_q5e(^t;w!{tk7ePS1s
zIZ7CpKOR+%kMh~G6mq%s9hg?-`p@#o6&%0<%LpJizN!jyMH!$>^A?G~QqCEwz{1ZJ
z$$;X}#}@9un6s=j|CLpy#}*;MD%2H5!RWFGv^c(0%{mBqTAlG#iq2T&uPb;1)v*!a
z@udRV#});`D%%w)!ZO?yO~Pv46@;R4-xaCCn&1`9;tGG_JI^}f6&8bH<i{2}!>}!d
z*LYU5ssJ3uV^x$63ZpZUC)kCWM~e1gfpr()5{s}`h!BgkGmPj^A@>S1Vy$<ECb1g4
zs~ieLsw%<>W#x}842qTKD^iNp=@m%D0`?Vb#a}!sBFj;8rJ}YR1yw4t%TX+)!oM7)
zP>zZZ3%*qRn4^RV1I!k)Gg_%@n%EXqBhXRFw1U~(xGl7?6$!;x$N`w`RX%T#a%tj6
z+F2oYp2a*WC=ZcPTjZWMAlp=UU+m^{4*}$kuP{MJF^!5P#92DFfI|m*RR$!kmLs4M
zqic$J<nX%U9gi2UfQpIq#;{G=61_2QQ+4heEbR=yJaj`<lxAFP=N`%F0JlQ8XHXco
z3C}=Yp&7RcS(Eo}MwNPF$mZk>r=nIlLqHW&;OZhFaFw&Xw#Zk{5)X)u1z|9L_5dMy
zp!=MGTMERDSMxMR>w<EFf}CqU&=vL@ulU$QgZa`Uet1!kYl;}-1EdUsWqfCdFTp5k
zoKDjs<C!TCGvqmC?~JCN>NF7x&R3PHLWNg{f)T;gFqx#1k|Z7Kz6WwI-DyR*E7sdP
zW4##=zO=neOH#ymsFg81YSq+F6?RUAmVxPX(P!lP0m?l0=ys~$6#-AR9bxjIWH|e&
z#q-ErR<u3L3Kfv=-Wjo<Ed}gj&W?!iiu|WBrE&vklu`NsEjXE8K%-A)9~_`WqKPsT
zXo9LN2KONmJX*|^;J^n5HZ}U8bP0|gyGJ<}v=mli2JDYVC2!D-nYkT~+|J7VSoT#U
zhhz&pb3J*m6;_f74a=2=LK}9as?d5)Rq9C6*m7Xt=cqIp`e7=U#+?~DrY}95pze3C
z6di6-rsx2?(ih$VvVI(?p~wq5K#E^b@{j}NsuGMm?TyMxa>PzCZOI3sOhSpy`2ZuX
zGM$_`{TH==M-IO-rkvqbl~&~d!BgIqGyDFcp6<-ISFV;1W}l6kW~QI%njK6(%O7=&
zO<QAlj!lxoKoU_UpDj}6jcIo<zg;P8KA3H$SAPsLt7+Z?-E`Hglyj!nIn&9Ng6GU0
zzXU_+K;)`izD0>G#dJR(0D74cOb3#0kRW&@DbCES)kjjAG7X(6;Zqv|JD%BzN02i0
zQ?D{itCi>INOh&5E-9JjNOO;mJ$2Ftb24>(Ftb}Jn2QoAn1h4EX0OyvpUl9d-F;Eo
z*iu9nAxE2bk=4#zN?AdiS=v(%DzmheuIe!0RyymVBx5>SW6y?lW@Rg7)={&*(rSGo
zi%q$>K7puR8M_`f;L7QBe1ciO4x4bL1^atMTi&oM-&z8k@~x46>`1qk#xjxTrX1$O
zVMMM(XIF}~WU+~NMd{NXT&GDt+j(f1h3!hP);*vEYrPs+-b(gfln_6e5bnycuARUf
z>)HxPvUc$SuhH1{!bHA$?FHn_joJ$kZ<q(~uxZonawI7^*tTBDKuIR^`r_8WiB`V8
zPgHWOtbRwpUdPxWQ3(^k0q$0~0ge;e368T!cVQ1WbFc+ZuqX-lAbA5<L8nK55yBWy
zKnR}qM`0y6OznlI;Pct=790_R0A)Bp$}i9Af-gfYWs<hMjgDFq0*E+*lrR(67uUG~
zOgJ;P1w!F@sRF11gwWp$&BAdN7vhC8v0Gj%zlij}Jpm8EQRo^D9Q#7xa6~W)q+=11
z3$}GiE~vzX!*d`skVQy7NIJc6*T|>hK+Wq;6dJz(0wG)yM{HzampJpt1#hw_F&;vo
z<PRl2%e{4r0SQWFQG!20TXCeH3z2305Yj1$*%Fi-kzNjFq|4$Tl;<vZnEas}(b&2r
zV$9gO1y0M@zLkhEG`t^vxe#sEA3%r}>WyE-+mX!yg*^&9XHin%=-L_(wgthnC^@>e
z^@`E8>XU;r*@NQ0OQ^g6MA5Y=2(}~pz(uf~bL*6wo#y0485?+!L((dMqeZz!K_EGN
zJsV8YA|()%6p{<qs<4(EQeNRPIWqHM<2{lR%#=yjAuSg8lcRhI!J$?=2Q2ffGo@b;
z*Nc*1P(z)9yTYmR>)LRv`~u{7fn7PAQ-z4NC<(pQw{AK9zV*t@AoQ(8$_c>Du?Pvi
zMF_7&36{65PmZ5nUnjtTYOMNoZ)jqU_})Ssb2!Qhm26Q0xg@I3u2y2BNufYQa6zAW
zC=LmX=EN!>aM}^1L`JJ?AYTfrTY!jn(k3p#+tGTHkO#+x_U0EM?qsn+D6#<Kg77>W
zrre^mLD;zilvp3D2cjVExK#pQ2>5o<8b$~_P*S3?T6O~5)v^QMt`?p6c3O1e+o`(U
zBE=~ZvY+38DH8IZ!v|UDfI;zlhY<9vj8ia!i;zouZoQHdCtGVUf-+o`wKJ6E9E3F#
zK_V_n9K5pe5g_8E72?hjY+#FyK<@%%bfQQIv@s|#93A@G2>h56#KT(VIQUr$LeddG
zUNDo3ve<G84%UfHA-qb5hF+MK4u5UoUV7qJ2pRJTLJUWe9(4c0*mRT?DjZG+?1i8@
z7a=i@1n3FU2Kwm;f-hiDhvi{W2HJ@&`V_y~1~tkS`2^H>!IdsbVvo}Akl-6f!Jd+|
zL8CfMA_br7SvRQwRz*<p-bG39S-sLXQ11!mS_C=4;0p&RY%XL2uB>D@QKaMF4Op||
zqh%Uw+!BRf3(|&h>p&SP9NeN<@hUX(!qX+GFn1lk`@-ejDP6-|Xtb;g_dyY70*qD|
z!8>K>OR-(<n{Zr3y0*E;4iakdPN|8;u3~|yqbQP&?!F->XN#uM|MK;pj&;t@_piRE
zc(w5+zi+qmy8V5*e*NeF`1LPe_I1AhC;#t%{dqWy$187Ujrix6KOGq5Wr9Jqh*Q2b
zga_LldU}H?)=DSE@v@40L|m9v*n{P}Z<T)ju+*w4(**&Irm`3-n|b{=lY+Izb&W*7
zij}s^)d<iSmQ+AB3%Lhv5KO*6_yE0MI83ml;0`1nU23kv^`Vxm@=gm3Bvbz@kM}}W
zv^<Xuz*}Jp!tCK<8HyiZ<f_Eweoe)JKyz7+aQd`i+0D%8vm~3ecGNk<wXGVh{=lVz
zj1Fz4_vr5C?@i?WS;z_JkL$E&+8^&F9Ep}f=X)ywk*94+>iChRfy#EhxL`Mf@4VrS
zU0{=ln0fNrTUB~15^>Gh8smmo$hRr85!gA0sbWnO8#s*>z8fpG3K<QTU4X*n1_122
zJxy?STYZ{>O<q?nt7O6)AE`X~2LeSUsMCa_7vY^>iN{3OK%t<>Cwk^C8VaIe4j@+h
zBY#6%vqG$u6>uTHmNqD7vIbm~>!ODW)t|C*LLZQ|RGR0#U9S14gDpqwpg-6n<Ci`1
z*iLx;t{b;j=hh<O`L>&VY{1p;`ejT0rXzQ*t0O4m{I+9Q7P-NHhSg@@@W1I4r{cWT
zDNl)i+X)%?JUTzM%ypQ4(-CLxy48`V(7)|ytnHd7^QSz{byoklBUC1XE$`=7QSR?L
zc9v(w$^V(I&5yg_k2~th80rX$s%QUkM?l=-X8D;h#rswBn{K?28oG&af7i{Pk8A5^
zYRexN*&lc0eP@?C@&@eRbqq;j<nJeAC=S&<`J0X?Sc{mDpSod9b+`VwBQl%Tt@|@_
z_3IA);|{u}M|41||9(!Wg~prwXX4L%-0gqdQBQ!WBPrK+9SxTjUy7eq(pYcDZ#wdc
z>FP+z^KHlL++U*A5r!O-5B@hD@r2!vI`UB)-*!Y%Yd&;8Q$YH7`hL?9FQh%{$TxF*
z+c9&t^CA5i@a@~X`kO9zdwX_a^ZBkz`*@#!3jDub?B8@8A0qtEdg`C=8A6<WUJk<1
zra<r;K0<8BOv9g>9P!;%WB_NNZ1FQeWH-uhJ9@cS(2<n;+m5t1-MozAA^DJI{<x!r
z9#=<Do^P+eg?P8iMnALg<%hKNn~o5w&PN?7W{qz<GL<i7ub&C%vkPOt=?0N4pMjs7
z4Cmi<o0DSv&!vx4hSqQX{9(|`PY8wIzB;gUP*D7tcApQ?@i!eSLzo>YbNaU(`}`0@
ze};GFQ#Ace$3jCuM^c7;+wnSgLH8$vBueuAO}EbE0(KJ!$v52`7AH#4KQowaqx`lb
z#BT&Q{@eue@omTUd<f}3W6Ymo`yY3dbU)P*;jCx-wj)a}q!REm^wbZn;5Xf%J7m<t
z&rO-=-*rQ+D{2@&(<kzwbNq2fsU|}mLGf>Qj11Q&-@B!&eCRa4(-mkvd(@H2(Ei??
zKb~``({Cl(=CaAW|1sQFDfxe;HeEUpZCs&TT#AoC+hi=d(=)PgUT85wxxQJpO_b}K
zv~99o#!Qs&o43LoMUwpz1^s53FN;#cZCQ0~(oP1-*oGH2m|4ckqBMRfgo#<kO4RMH
zDsc{Qj;bVAl)g<otg^Ff;%v*Pn`Q6FhxD*43XPRTp$!iO2d9jcNT(u<l1PMFBIPu}
zF(qXgB4^nuNjT67Tc!#C2F0@gU>hHVGF`G{;ax^u)-03{Q55+Q5x<B!hM=U0a1zGA
zZ`LuK8*fM{-h^~EHb%tSvhw1QB)_-vj1E}jD&hF1Y$YE3MxC#rC?euUSE0xtjkXn&
zT$II6y?72-m?~1~h{HUpl4X!!1t52#oSF(`I>4W+h~}aMx3aF&LDCvdg@k0PR#QX>
z0AWC$zfh%{01<-XS>{vBLYX_|_%BNAVWr|b5UX3{%R6$!nwJLwaPG~^hmiG@y-sD`
zrGV8VB?hBY3A;|g9|b80WG76`6$F9{wt1aNlwfwA$&n`9MKBFG`Ovmb$%e*GSuz%X
zkMhiJG~zn!98IaZ4uO?;iLXDhUEYo<Udm)ZfNUeQfCH7h2?4-ix^K$W_Zu~vA=4d6
z0XM5xuH&d)35E#Hb*y6@3YNW(RPxn~HLPO-3%K{KN6x3Cl~ZX7cf8>V@bbBJOs0Hp
zDDUj$bA#T9NSY%kIhlHe;Mb^78hT8ad`wS_!0X_?IRulrd4`k`43|^iy)`j~zI$t8
z3SH1Xa;x=g^JB%1Lhfz2^ZK>f&x84W?*73nl04-gj1$x6)+xuj`%_1>*&|0fb{A|8
z)weD=QiV*wDI1`w{7{0f%BP%nVVAKV?%_q@UPnP^W`)x4+<MzOjc9A@qk40<>XW0j
ztxxQPZrg`qC-jqB9}f9NDZhT~gnn+0{n)xntjqv{rmRYY7#so0E8l;NMzFJf(Ry)j
zy<#-Xi9}RH5EL+wQc%DME0!Xd)n@eyW;LDp3qlsKbB-j%RY%?35f0wk*m}iMR&wG6
z@uE2$f)_-Grr7I@V+n+1b;{u|M=KJ%+ef@iI(t6iW!CGnhs)$pwEh=f*)3iMPim`s
z6+uCZRNZng3cW?NQELjmg&}KE_&y@Dy;b5Mf}LnodZj+_q?t)EQ>O_-J2uyl*N>4W
zX<5J3CHAmY1Xa9eVNq0v*zwIS_DM+ahe2k+1gqGoyrbI|MuT_5rfwXB&bKX)2G4|z
zty`MW_{3hGAn54O@ora2-_`MH-@@<m)AAVq>VTVgf{nFK9EcRH^4sPB?{y*}dlS1p
zDT^~_F2>=g`m_iPEX7+{8EmK?wI~c*jv1d?j_F6@@*|R#j%Wq8AgH=2Ee%K=s~|wd
zT}Ld+A~9?@RL@q4Xn-PR<$+g5fX57#c$xU6ZOcAG?XEWot(>18>8$_NRF>7DCa}Q5
zE8^F~A-t+EAQU()V6C#uCSHzHA`oKR+bIzUf%8Y!hIlEqzEvI?;_p|5iHgY2PwDMO
zwY5b7#y(^Hms6Xp!9{;6B@*Z@?Uc5HGUSWGh$(=+*h3f)hw`#0Oe9G&$fAHjsm|CV
zz%*wdL50`Q*YfP?6e|GW`N*b-PQtZv)Z8=H8Cit*R3%iv-&Nr@Nbazw5-Lz5<4r;{
ztohH-BrjRpImr|x?9n|xuJ8l!8iiUFt^u@XbdcZ-Eo;?EVFpp|<warSFBGpu!UW;l
zdOBL+^m}AJKuyR+;ZU*Jt)g*|3}A}J86z583;1^)sZ1z+xk|<;AIHJ^%E$5Kz0z^=
zq+8|iLE$sz@g2xpqGRKwWGB08XXGiiyK=ASHQjTs-WMM$>m(t6CNw4}h;}RQ5|&51
z_1;JESG%W#BUFsFThXzJvYi!%Fj}~pl#z$51B1eHBq`%q_~{eBTd7wkepgotybX3!
z20T2l!|kS@&QXTgZt2HRMD1287HqtBD-6g{>BMer24pALt<^@x->O^1pT4kgx-NY1
zhZOY@sRedR^-jIgZU$aM4|)@#<@yK!+=$a<w-Pmg%VoD@2q>O*$@cZumF$u_5r|qx
zR{J_hi4$=>XvI-ht{;G~?9zsVbIGoI&rVHuyLKEPtgN#AGFQPW+YfoKhGf4;lY}Gm
zQUn=vt}M5f?U*q`DVT$6m!7p$!4B1RdkHkkE?rQ85w+T;zlhN(ei!&pM*QWM;GS5P
zE-5)W1%3j`$u7Qi{lWM;qy{K%c4@1^UeCgMNlEVM-a;%u6zF?y{E#a6y@(xemtMY(
zYx>g5*Dp*-l2HeuiCvOZk%Jx1SW$8YrzVL@b}}IdzJ$YQVC`uKu}MoEf)w6_Xyx%|
zWyYk$3T^h+KqRV&x7A)tG!+BhUBx3`5iWM+f5sAbfLPg-R@>Vz9&ATVkQL#^Z1L0!
zqY~&zN~lU!c2%fpHrqytb24RpYbgX;W%4zEg;?2AQF6s*1&8GeZ&T|Agd3J~O-gJ^
zR)Kw~IEs}uwM|S!mqSb27M<Kl2_eYJf{G$Ctm&JSxJrjOub7yEQwZ)Ki$cVRc#>^M
z)M%YWj$cBDFnGQRCb4QQzan%dk8ow~DVj#-yoG{o^7sM|gVmyguv+ns0!9NRsbBI&
zWfkj}z&Kd>`X#^))XN4X*KcSeAlT9>%g^v$3>l%IX))U1MdX!3?(QTdlXc|niWZ?k
zX3mz0JpsC6_yDvn8w8_TuHHCdW$6XHidAADN=ez!CNgM(EHwYhidQjsJ#EGfBIU`r
zK`7douLe<L*0{@5jO+$;ne|ah%e>%m@WgoOxo~=$7d#G*uH37Rj0XcoFTrq3K)HdH
zas+`(Y6zK<7!90c6ND^rQA}vCZa@^Q7#bq_SlXaNM>GMedR9lXGMOU(!Mw5&PCNr;
zlLp9%(KGG{pEJRd2E<8BF?HM{Nh1ivBf2m}*Y8ezya1peegpW^&&dhuIGhl*1?ou@
z6RZ42l*cn6Y^r{ssUU-+&Yo3*<H-$B@J)HITIDmI2&^|R5T}MHX~1us*@4JR5MhNn
zxhTobQ?c;C9bY7HIOGB^e5Vu46F?+lk>3=w@+K}UNI;}pFVwUrS_B+J2xEVUYlda+
zk6;9mMPaJD!q97zYnV`G5hjT5;KuI?!6qh}^}<ApM!~M-SPBjemqIT%G+qk55Ygfm
zwE|cKz?&7sBEVRz6AumAPM@?bEK*z~G9dR<<KBd?42h0iDr<5FR=*W;;)CLS))`9h
z2a(i|kx^fTglC0R3A8-xss*{=^o*dC$gZ#grF_of5yk;&u?J#vg8Ci7pB(x96o0Y@
z>LiFifMv15n+#7km~()TGYj@WyW7|U^=@NNdLs??_nvOV<Q6|N#ZpWKe!Dj%Tkn5S
zDDF46i;Gh?_Y3hOp~Y<Yk=QKM><PKDD7l}G4%N=OP=TS^StkT=)YP>uykGcW76n^3
z{VPY1@?;_P#^eU*nLA`kp(Wso^(HoQgES!}r;fHL`LlQ;x=?xHOjs075^8L3nk4)H
z))l-CtH05~K+F|We(swRt->TtwX!n+qQmNL1tE!?O)CgV6mBu)^akik$h2@%Bx-6*
zL2$YmPGoXh5Oc*kugAb#K__B^!bWX{D~XERR=|?byMlsQFlP1<(=S)Ifi^qw>s_6M
zQahrF)xHqsU`=HXF1##FH*2JhSgZVjhVK+!uBi`{lR)7O0#^ZYgc6lmLfx8x^MMCo
z?P3c2B4szh-XmybQ3^?z-3Y_{s2AW?2vWRA7!iPst#B=&N?9RW0uFg)9&tp#VzH*X
zE2EmMpe_NtY)#;~0J5;g$cST+&<l$-hk9{5L%pzG831F6hdJS9H|1XwZMt$|X6l3j
z$RrlaqL5i#eTXcYwsC8^1z`za6ppQ_7sr-2NAqG8!{&8APQ*;pnH6v>!E)j4&QqNR
z?uB`(7jCk7svD8Yxh-^y{zHDyK$#P33}NUn_aa@r)3hspT&FF!STP_iwxJU}pjs9$
z2G@I_#nIw?1JKBn2_JYXNAdx~=M_-k^R7+<?c_IZpW*6331aX9Kqah2$UCF3=(~Cm
zy}hARrwy`0&9YVq^p$D=?wWdW2BuChM|WC48z7BGs;I3H=pi{YVI0%ANkG&@SvfN0
zAg6#Vz)E{ql(^wrj}`>VMuEDcdWf|q#9F94M*n9=K#d7#wfm)BSdzCgW2kT2Go0oK
z0#*d!G>d}SD3y`n6dmz2*7P!_-SY?vKJ4nn2|9bB728<vrt_3r&5y^NPbnbqOrWpb
zdG+gYbzb$x>K3Ly+42*&{LM~#V<WmfAnL8@{Uw;7$s-&kJ<j}HR#D-i(umwU7gdjR
z=W8!Va_?MOKHDhXx(KXz0!u>ELk<*_$P*kOuoITDPjzC&6E3A5`_832={aLfmP)K)
z*%p&qo26Z>(Y4C*FGv7lMVMf#Kyz7GW>LrvoKmB08`Wu&!Vy8qGa>Oq3^D;yur^Lm
zFe0R$*h7#9R@pHVUOy`FEJ_vdc`%~Sl0H_|tvk(kMkxgk`67U6c%yd;?p&Cqju((h
z%p}|Zsbr@Nu?)Km5!Pl8TB*sQ3GabbeWzbjOcN<&5zxS%MJuydYt33QmcLkx6=h#R
zD=zaSTd|p0)Wznakj;4vEMGddk8Z_v>;o$%lTu8^&akO122_R)q~UF|&~ElY;TD6`
zu`FO)tK;rOAV;S)Yincp*lV;)ZIn}sOF1U6v$xF$pZnGc@$Mg#`sztf$wttyV&s7a
z@iDW&gZMZ+0SPh0Ay$(6<RefZJ_(-(l^_tL99is+8!FR*m-(U^qc+cJpnUF~1?8YQ
z=AK(5&Jy|dkCXi*bnTwp+6~5v<CBDo?JEljZkHM;<Civ1myu6AUO2+-p-`b>wU1RV
z@Cm03l;ic0;23vIgHyR~??urK56WFP{BvhX$Xi!@?w58$ghUx!S{=4FuY2r|8$}%J
z{b~0UYq0prtJI|KYajjm^`(g#m%j{ud=5YBVzL`3z7O{Z!ms14=ZVAZ|1ew%k$82F
zc2kH{so%S4<*?80T5s%_n-?g>fTIC}#u|<A?dI~TDDchIRT*^}4jRn>N4vPb6kXcI
z^;MzZi_4qxPP=XjR$#_;QRh<e_3M&gg>!mclC1I^UQ<#Nm=W$;BWQRMC^mr?v=fAg
z*JLB03AkO%5>{FFz&1NJQL-V%ti;U*Pi%>#4H07|SgdxTq$fpNW}8GCd}zN2#|?;f
zlAl)!N-lw9Y-Xh_5+?~uQQONCPssb6C@e*pW1PSlkGkc70ES`d4J|#ZrjW-b3jhih
zPpN}+O*I(+sKYcF091Nj`oBsRPaSAgqn}f%8m2WTlr>ChPN`j3t2v~r@k~dcUa7rp
zmQI*caCO1DOqYI#bxAjEs+K^ENRN}Wa+chd>YnK@XKJ(@f6GpaOlEm+BjyMzfQPP(
zABKxTd2CF8q50u>DFdc#6wH8;=FSY5GIX%6xdC&2-CP46%%*z7fW9?B)-~X+mer+=
zTYuyHq5K1IbX@9!;SK5!EDH=5t_eJ^4e5d^1I*wo1rfKw`<Vu)Ht=4{NELZ9VZT>B
zmX!m;ZUb$0;s9Nr!T`Iv@F+5rDsfPdH)D#6X4*{I>wZB_8Acthy6_=pEnI5%LbriO
z6m~*T*oUGKJfUT9MAFPxnIxGrQ)bIT7<eQ*07o@Q5C7=XLfQbNx+oYCay_h-u!icC
zLBbDBb>oPpx^YA};k~38FVina6enEv;s&o|*_0dOoM?7FGM%Oj)6As_<28PTz9d6y
zz}$^v;J8VRpq5Oev98C_n|k3SI2}iN=-_=kOhuj=;EJs49dr2xuuo7Xz=*-g3=p^r
z4v;p7LhJMl=(%BJk=zokKXNDlX0!oI)l?0uF_cIZvl^gOO;xp8&;OnuzHpFLm#e|e
zRUlSxO0+OvxcE%9zZye^B0%Q=MNXh(cUC{MuA97<-w51BB{RC4*4^3RI?A!qZKOK#
zojyiEX?1#ybR+jD2U$L`MoWYIW|8-v9xu(2n?se{d*ha3-S$q$(bOF2IMU_Xu{WmX
zNY9Z<Ni9+?nNX2vjF1cVP1)R!4d;{&O5}_jbYOx6e<aTg?j%zIzs5i#mHlhHKMjQe
zTin5>eDX#+h1}Au(Fy&al^l2^$}~ElbtmCXTa<xzGC<c4UfA%dXB=$9OKmF4*kDQy
z&pf)h{QFoD$Rmq_kmv?UM;`wc@{+0cWCPTTDNU|5Mx*dHX<IA;wpo_AHl>I)2)gFF
zIv`S;63ZH_ih<X`MS--Sd^Dtt1cmH56)u5QfNp!3YLxyX^jCv|V=Cs_8YEBUFE-c`
zjtU=X#P3lZTc(l_8szm==roc|fXjLqEB>|>&ZLyghHxfTFm9;cl<_l-Mi<4`91R7d
zDhh{rB&O2NktY(I(W`C@Hers`u}F*(VmHJnF&n&D?uq<`ibdjg8)7~b!t^FZz|$+z
zP9jcAyV9W13tl}kQz8;87i3*@b}Gt>{J?4r6HCu%VZ&veB@^=dBBaEkbYCW>*wEW_
zGNw)23$Uw;GSJ@Q&<>DxXscJGqQuAPqG+h1R6%czQAdDOSd%<)R}A=6n5|;N(aKOd
z?N}5|vY{PIltLR)0L~CGgx0^>`C-ZSCnU<D9gI3jmR_ls@>eRDkohYWZ@6+(a*ZTz
zpO8F;Vp<xC;Mt&W^i7EtaT8O|7zKd`v%x@$2C`WaX)+0TXcTN2$t-?v0hy7^5@XZt
z&d8=z0CH@wAP#MOLRb#n=fHJbA)*}M8Lb%HN?KX3>3{{!Xbc<_3s-_lhW7FREJ}=a
zQsy%RJRLS^VPRg2P2R&yY%x`|Sd<KCr88zx@&Z+`>>?Td2+)KNgjv<kSd<I{<|#0Q
zNgX!x7%akxKfz2>fQhOdt1%Mb3RBD$a1I|t$1D=L0@+1a4NP=dl#U6*cd4Qz_Aq>5
z4*d~sBY{W!0ixpr{b)}0asquG_}#XLO0R4go0onOvGAwZ%vgAu$n1v0#V%f0i^O<y
zj05Nx6|-&tsIY<`y^*MCSJxk51urp_=D<tbLtctq^bXsNI4M&N9|I78<pLs|-!AC$
zhFpES(mQT9E{=<6lgv`Fi_e-Nmg!=U)*`gAB`mxNk<nn_QzxG&z1hut3-KEn=aoGX
zX)H0}TfAg!({+na@F85cCJd9sMYYj@uWW>nw3{l;_52_qQzHcBdE>#lPt7{T*jpRo
zwoFV(z0Z(sZFg-3Tr78O1_-scY5Yv<F>TC?c|8=7jD}8C$}&_~wi_oEfbDkUq^_w2
z2Qm1}WHFWJG62q-N_ZJVsBT7|S>`DpnRApA!0MO^hS|leAMLmc&)_}K3bqZXMa*=m
z1S#&DN}@7k6PqBDW3$DFCmlbA+~G>tV)~2SQ=H2S>&ClcsI_hP^@Hs^c{gK^j3(Fn
z*0){BWmtL~uSLNTzCvBUZ^oQ5KgRAyYX*_)#-_U}^^Ko~z2<=@ByWUF0Hok#38%CO
z{4_MT$2dtuh(0C`qi*3Mk;N&iKTS&u%bt<~jS*i;95k4FkIXFm1vM9xOd4!r6>LmT
z+s1q4m&Ge+nvdQR8k&JHZYZu|PZzIRJ|9>j<fg~9uhC~ZqHm+mY{dLY%j`}308a0t
zYH5Z#HR}}wix`&n=pIAOuy~dAH<^$MlV#vN#yE&fVYAX$u^1C+tdG8g!}w6fm_V^W
zqHU74MBMdqWsa}*1+s!Fq1R9ZX^BNRj9DpZ%M6Y@p|fq-!-hz=$}nD($dJy<=P*RR
zHQ{IR)s0kU{4O&6Pd#y{7Nv}6q#qq2c5;pYq&Z#lObA`qERolKx@HO7m{V8I%ye$f
z5D+lu&<q`%nwp{i$h`4^Rv2hQc*g{p!hUJVTpGYDv!vo97bgc;mh+~iaFLiOPnL8g
z%45$0KlH7|L<?{#=OcDB0FtQOL?mBj7jY!9is4wK#J33Ck*Gjms;<sltfi+7v=d@M
zH^>ZF6Vn9(iL|MbuVvuhk?JG(W`G!|jd23rp*BWXC7Nkp0Hh>!R-&^9>#X(#lGRPe
zoyqEk9|>I<e?1<8D$pcma4j^Wu4BNxYbxbzKx|(WY^GESj%IV~6$gkVSO|UGRB1Xi
zjTozB9r!F@RX9Kbf`vLIdv$97%d071#*oNPs0<tMWH$Nz7b##w=vp`UJ{p|asc{u*
zhas;W$Q}nsfg(aZd=U~xMEb_~6-LAcVMGK#9{S<)>=5gSsVu~jKY(E$^W(qs(vTC7
z`m2CZf^fDCJH=3uvfx#y7azi4VG3Qrv{0KaC>MjDMrbdFwD^_|sskkA$W*VKr6iXD
z%nU^(GX-yhsG&`uDJq&-c}?Nf1}{*-;TXb0Tf1q?h&;Xcp=axsBhtl!Akrp(h{1o<
z`dL#0D3p8~hSdDl&*~N?V15YjPhINkXrXB|c^qsI?Wt|O5|pU=BqmYY`sCnx4UT9}
zee0H}L{h2->bocl!%(xebp_ZiQXo|M)+>%oA6u{BU$313=nlYB9!bhE&aGPxac<p`
zf0G-^!W+R3LV1$fI*9Vbmu3*;NdoL3%G14dO01OrY=4xadvuOYjP9vlj=}j^ouY+=
z00JO4*X;pEUsD2F*bAQo5*uuvjj(MYG6jr5A-mD)NZdCAtU)2eElL~od4UkORa2Eg
zL%eW-&@qj&fa=2fIobwh2Ycv2z&ntLl9x9;jHm^h7s;0+Vcn`zTzieSU_*RzQ-UN@
zG#3Sr32e9l^LKJQxdxXMMnp9?Fbh~xE^P&Aor^N{H@PYgS_!zO+*4YUo9pyD;UXn}
zI^iOvnmFz%IE6u3A5wO$kh}GEIDsJbb~u3`n_e8x6VL{C0I?veI0vLunPUz9+r$jd
zc3d>0)}Kg_wf=;Cto6r>G-~-12vX7|@>$!c)d$d(%%+AQaRvw^C02HnMe5i3B4o_e
zc*&Sc<0W4xTP&pX#Prl)lTkN!9RV`$ZM4a!dmC+X>e)ss7*cUJ?!bBOd{g2*xHJXa
zVQ`)o7^)a2z*I4gpsL~<umX-G1(d9$OmcGWdm%VC_q`CDo3$6>nJARlH)%tWW&Uv?
z%?bm4)<#HsMIzQ7zfj0rfR)YK3JJP7YbQWlK@p+@q?o|<_0bY@A<#@o0!W5l(M_ku
zyVh{(&W|vJ#&Xr>5P_y%0H9K~sTTkV)om)YT%=0^WL|@<jG!dg#>`kD)LxA%9!i>^
zI*QV`Q-St*wT+oc>1gE|UcLCDP&c;pup_^M;c`1=NF~E1&q%ya3U?Qv;8bdTr@)~d
zq_yr>9o3@T`u^GpmyV{|Ip2f1>8)&;qSQfz@_L`2EiN;lTiRV$Fd*CRdOjhL-hCTw
zQts_<@I%k`NAW|C?Vo-m+HI8DroqkoV?zb$+4oPZ%VWQu#<FOw)B4ojnOSVEZnU@+
zpSIm-NvX|&8{zToI*M)39<SRcwxj^OcFHfe&olPhXGwgm3`e-Lo~hdh&3cHkbl<f-
zM5G`WLzm;TU+!^WpY3udp;!^893H7-C+)ZUh<4rWQA}}r|N6P#?6DCdQ2yiDTm>16
znd`^;x!>*UuNS2lwKBxJ3YdY?&;4#+f85Wuv1<K`1qtfq?`PjxwPw3WpYPzx4gjmJ
zXiP~Z=g8ufPl+Wt%ON(Q(72!i@nZLLZgNvUv%Y4@P2rteB{@rQ>M`JJ6P!kr`Ya(S
znSO6lQgZmNgM(7HLS9^yVBfO|48cA-H-RD82iwm9(i)DPC96j6g~ZfgjoBuqu5m8P
zCZ=W`*S5>4PZnS$vse?ivlRpBTaRE1^F)%g=D!k2vK3q@qYnh{UPd2h)m*7&L^ET?
zN|KT-)Y>8TGtC8*7|hfP-~>g&%(-h6kyIm1C0TPxQ%NpdpPEYF3_Z|hdYO8hg>-MN
z2+FyasmEDN_o-cv8t=;Bpsv-KQ(#%WzAMZ>^s_Z{hUcgD6;oGO{nGNfV&M%MKvxvI
z0TjI}0v)R35v1xC(~NXYDxkfUa-Jr=-by(~ncP-(KLGIb&2DpIiZa{$T7+-(tzt9`
z6vtLqnh_jTdwNmUA}N8EAsrn-*|d)IjIX9GBu6`BjYHXVWF8~rqbh0BG}Dz09>th)
z^iy^}&qO$xj$(r~Sr<`7y_Izl)@tV5y%amr8MT{$PhH9V2JA-EAtxn%_n~kL(^hZK
z)++}qOY<024m}KL>qiBq0FzplOjnQG7QJ>`p3^AL?zGJfR&Pf;M%x>s=xOuoy=|Rh
zxV@tl_kY)QGf-7sL7y-+uF*M~YZItoeMGoCS>wKX<Uq=>j8`s0Em=r12Qtyhf#}UZ
z7)<YF4a7qeKq_f%Ju;<LJ#rw|)?*D-2HhCcz5V?)Dw8%TaqK(H#+iy+X65K#mcQ6G
zJ-~iwhwgrsfehEQ%l8EBvO7)J>-%ooC*t#NTZixlcBffA#^80M<h|*&z9{439jy`R
z&d3BZV9s{$TZb5hqmd)f>b@1(?&VfOZE$yaDQ8v!R|sIZ9M&?F*#{s7%m7bH+ySuq
z9O>^^+o8-p0PO9qQw|-uJ5M<v6uOt54|hxVYwI;4$DK|r6wdbYJZ70}FUKR2le+6+
zL4;6u_z>V5>Mp4Q{-ds17zSm0QQ&b)S-cM!0yBmvzyZ`JE|0PV%`Sw27d>BxPzYXf
zkM&U=CfvhA6<0extk8$dgjodI(E*RqhhCbQN<bgwc*M0j%E6TX>ce%i!%Nr)eT1>l
zqqYa`%d!j2_-k#Ae=H6=Q<3Ze0BC^Y?n74vAiMjR+NUU8G-mD7xGjga&cMK~8U_Yd
zJ7)$=M!9#v`Pw)WoUffT!TIu8L*ySaAIzD;Y99)5n7IC?OvnJH>{Dh$IHkLa<iK&A
zXd_%8NWT>a2M>6kx>SIY*{5EPNkO%u-X_FSVOCm{awQx}w)0a`IVSF}*}31JL|su-
zKrGXg{4jA@O~uVboIszHTIPezFeSJm+MrK8E&w0xQwj*6b9$MVF5q+md*-EpHR97G
zWgUqr{Sz5_eM<iXJZd1}93YHD&r!rhGDY?!go||HnKGoLPqy;$pHe&#6xXLj3K)9=
z0qEJnMF<k~QjAHIeyhNlSVMujCem!bq<vmE^B3cHVs=*v5Qx|5Wo<%OU4SJ$4DyLN
zUlpf<1Dn9M2LtQ+Rgo#E8eV26AoBK#(PPE4+zQuRbE9toflq-b^${G^%l?D_Dne5&
z$`vg>_ZI|)OKt=N-t`K=yKsCisVacb>V<Jk0OU?&<cPbA$vkK!J8FfYB3-q@DNy#S
zRv5~S0Gt`{)>ZPJL2+GnEd<UT{Wdg*P|LD?4FQ|Igj3ybd6ifl{ciGK-FQ<OMrZiJ
zeut28$G`N6^e^^X=bpdRD_{;d+g(832x1HhBNkIR>9>pz8K-vykQ_o5V?W=F()_iE
zcn+<?E5n9LEWFpjp$RZ=AK6EE<&zZm&yn2>E4-ly-Tdz%@7!8%AlCJpPzfs*bhXH$
zu)p+2`ErXggeLe>AYrcnH}GXq$e*+ocUlOKAjK9JLcJjoz7xQn@rC`#kwE@`Xm8Hs
z`XeYDJB(kd`)XNDY+*E#@mI9S_`E=SqVpdh1?L6fZ>Z@;bjYLx=PP;*tI`=pourOG
zA{!uOKT<hiuI*)?ydg<v==PD6Si&e|z=-9Ak%{PbJTebG&<_;%N1N>lF>etVIc~YC
zaz0=c0@V}Y(^YI9Tj9Yy9`K?kNo$H;#>OYbcdxKEAbxt;_MVGBq+1ub8h%z_c{1J0
z<_D8#Ah_aVp<@8#^#COa%$YdzFDi2(CH_UJKUsSv5oljkV#CiH&Gr3-V%wD2Fp|Km
z7L-g?6xgEVbQE8@NXZx_zOq*CsT>_Z%DQ61SZrib2ug6K6znScvM9kAQ^smqO<e(F
zEkIY?_y8Y^5VJOA>YORaI1PynhEzvH86)!Ch@fyHl*eUQjEFqXYQL2Z6Ra>H8K|%?
zUvBhDykw@F<kPrdmN~wOc@tjXyrO}B=Y)IZ|D@*Ss<6|5I=q0NnQoHOQ9waIq%0P?
z2|%B@M#Pk^d?dF@*2zV6mIOjxQxFn*BQu`@&pP>Hr|_;baVmMOG##W;EeaOZPO@8R
zI!MZLnK&0E*?pmvJY$}YwP+xqt0jWZqA<g)fon>^w0!;+LO4^pI=BWL$wRS#j`~f_
zxJPv&jC+&@s}=Yc-=;gWB}8|^o^#6Fr2_Ivu<xMcCWMvP3*iPlKD^*)z-TWV7N973
z!JJq+>%9<6EH9<Q1*Fyh;pBzyfeCqGcL4p$3z!3FI)@7$uVEx!*cbqAS(NIQqh{(E
zpi~xtw?TlSctKboe$R<U0RRyfhG7GUy%*F(!{b+_jaz;p!S^v>$G4S%j5s@2oLnPX
zr592IGHDn1KW9F{LfycymO8-`kg)4b(8dkcQg4+Sd|?5#FOeGTg^qyqVb9>Y1Eh5h
zWl3dBowGn4L+ZR>3;?ReY6+2$`(SA(NJU6pOjMu+Fr#|YZ4M+`CxUE7(ZyVQ<YD$$
z&8~fm6n-x(f}R_1Q3l!}!g?3(PZkUGLLNXsofp;sY^biNzJ^r!!#i$!m{DC;-H4|<
z^Jn<OX;1c^t%0d145*5#^T_~ewhK*oQDTi0Jcv*_ClbNIaJndafld$?x{er3tF8#c
zg&43}{LGD4{U2Zl`~!9%R&|3N$cx7}qyfCdUQh!_=JtXcK<c&^+<@n5xUAENusec8
zSczPIN<59V*gHd58Y<MdA{m=wwS|1z09x-daz|;=U{}6IQGE1yQ~~7`!E(vsp`D2e
zrd|L8h-GlaLpC2-X(ic*P!pG_yg97u4#04hu603*v%0MdcAW8bL3#K$+3TWXsimdW
z3vB=nS1-f?7+Rf(1Aem$*$c2CXDDWa7jY5zX}s)R*Nk&ZC~Fm#)~J$0h?rB|3RH#N
z2x7x6p+^$orCDwVKa^WScM-x}U2&j@x=RXvrbQotIWp?b6)MW8I~Ux4M%{VA8Nk=&
z8=L{KY`yELMHsXzz_h{X<OOg5uadJo!4V{O<9LR;aXh#w{M3l1dU21!RpTmP%Uam0
z!V&?8E_BoFHy{YQNq~V5g_W9KL18zp*R5{E^m+6#AgsZb>aIHyrc@6<Nkfi<t7t?+
zW`w&W=5#n5LBe)IIx!1WC1pgL7*od22(YQCPiBU;NGtIIU_b!gqHGXT(MOkL1mL-f
zJR|<@2oeycTz!a$m6FAx5W{QeZ;0VF@Vj@xYOxcJ9x{+T96$}$P*)|7hCC-%G_XLw
zTwWp~gR$t?OXy+l#Oumy!FB5bgWO%Je49^HIs@<(1OzYOt2{L>H&VOa(tY7dTyVX)
zOT52MbkXg3<&Jfg`wnEb_>csw%W_EWxKClRb(g>e6Rj6&MH*zCrLb4PUGDWM<|Av-
z<<V+c3d|GO0@hJ?snHh?zQnrAxofFwTwHVsdRH#GurMy3dZuA9M$cVgREf&RVs$U!
z_PJ`SGiJ}7IiZCAW6`^H!Y?kn;0F-5=c=p2uswHO?U{n?^3fd(<a3qhX{eCk3gB)i
zqu|2tXsEI0DDu<NaCv0yzT9@mX?9fxTJe6lxD-uquC1Pj8*6(@A-K7^dNOV<E?dcS
zVI|x=!1N5Y+j+<zVp|UV4d<9^Dci-(^Q$-J=J|bqS8?+QOPjlSg!K$%=C3P`y}>5x
z83_|;m>2jhxK!lqyIh_PiN5XvM}-y56Y%7Q`^HBBo#ww-xG^cgZuw0KYwD~SMdZ_i
z1t60Y3?7o%k+bUsrUKa2EF<|6D66NCaDX&09Iyrk$(@oaw5nVYB$gE`17tP-K-jY#
zV*~3@OJ}D{@d3<yki*T&m`S?E2jLQDu<ahayWlR~++h;ofS%z67PC@rRgv>0jNY9B
zag1*1Ltwu?gfog_M@8u{0}jHU12Xu75QaJy2z_NFBt~46i2>)zcKn7~*kVR?bCD*-
zn@hh!98U~4&q+sy?I-0Ls9w6zoX@UV-})6!x+t9VgI{q?64+}DmvoGGU_RNJQDHTg
zg3*tklpLl?&3Br;<ndpWfo^$ZR`gx4ekbIxlp@gW-hTtt>9$V;;OUbR9EuKvCaxwn
z9ytM%&L?H;+ygo*C<jPn-;Ez`;9gO>_DG(d-u$zLYkm;mA9k3HFti`?#_Pyd{G?z%
zAd;b@`bdzHYrx9<r0~cA(Hlk>P>AzhJFU~GqV_GeU~9Hp8xI@0;qBQ;504v8213xb
zvqS@mP9W_kgSqY<7LDx~cdL`15ojN`Lq|&DPHB1F)FsnlMR2sb?k#MEj^|SMUx%iT
zJCY>?c%`GFK^WNgCNFrbA+002tQRHKPhIF8HA?Xge4*$8#)lO^U4(i~P&?t+o*Wif
zsAp-#nz``37;9EfTZclaV!}ys2sTrHbVIPgh@ttpVwO-yA}Davvf4z+Lo7&9G82nf
zxZf;Mfg=fF>`2mpK!o*0IlhwNI+Tu*^A_cStO|%mMv;}o$Vf7GmYhSfNeP||By*RS
zwj<Lg#MStd35i{m=@3O<LU4x=EjhU}3$KLfo}+NTG*9ZM7g`k8IY;WIQ}>rsIaN)h
zh!B$=zyPt*6gsUI3Uxa=%@$BNI*k_pKWlH(vs;d9ht2n|IKz7fw<A#>q^1F41IZw;
z-5CX$*sucx-2*!?lKlHTBG+2`t#a2})u)XDx{vri+WOeiCPghS>P#}QJ?B)?Bz$lt
zBPR#Hs_$uMR7%h}l|>0b#2*PtHT#Um9EfJdsf&qps)~{c4b|d^rfOlqF1~2o%v?Cw
zoNsQSrNbTG7tmgFD$UZ`RYDUr?uV(cOH@^O^E(z_y0R_-6FMieE-k$CH%lGZ0p6qO
zm9Wx68Fkow?qVK*pCOmTn}mtGm`7=%yXvSt<dRTcyVoT_r{|DMLaBvzS2c83P6=cd
zl1oC^z5$;EaiBv!2|8uR7oP-sJFo`f-F<}IN)aA3;q1UlkW+##lOd;sQUmP_!ArkO
zy(Bp$;ENveNywbpbv!lvyMF#!5u0aI*#tW^uAE4j&J2~<u~41t*rU8?a#>aGG*sh6
z9aZB*)rMEHo_%<(lWucvd1cgVsDpRt-0;Z4<6RZtUaYioNJjn_C7yeog2VYKZz!$T
zugK(fPm0ioUwbD9+z}#m9ZrX}^bP=9bLg^XB=>$w(6gmVczejLJ_k$X;HLX`IO0y_
zBEFJxaw{FFZ`G<_@VY{&H^HNJC9rMWRflsF>G8&!0=d`g6(7#q3T3qO1IIeXf8<EV
z$AGR1vi~xd;}k<M6Fxo@={a#O8cJRV7}gxTxJFvZIh3mon5#M7Ty=nPT~W1M0H-;W
zj15UHnN<BROoUmN9p$qb2ydKXa;SWoQ-sXKa!qkI6Uv3e>wjV5&gaWz%oUYyd#G_Z
zsdcHt6ru0U&y`$6&IAqh03hkTEn*hZ_eN<1*M_p7h4WgfW{OLL8O{Qh+fY6;`a5*}
zHR$ia71@)LdIvg11+Ox6<_TV9=u;HD%ILCafc%<o_RiCEWrt7Cfqu|^;+6285>ZKm
zu9BfFU<c3y-BbeUHQ!vFASRomNqvEt?7b9aLfxq-mT|^=r&{PP+{CgSU2rR-5S=Ny
zz#VX=ym>gmQTbj3UrAl`Sg5h3OJ}?;K)I&)^a16X4Cc8=t-3fDwbVF3$(XEGBoUgX
z9LQcb;%LQnuZ~4gM59lN(2na~9gFWkvnW34O7hJaGajG!QlA-*ar#!qhRh!gEI{>k
zw)O=XFdOf}X?4xkeho3WB0>zZyP4J+Pp$4=Nr4-xv$K5xH#`s!-7wJfi*BgSUffw-
z!xL9QB-%8YAs18Df$Lz8r;r}(@D$Pm9Znah(HrnExA;`--2@r%6!j94l&1tw*;vk9
z!$xetR92n|e3O#<6k2U6;}MgrPbF?*9`^YrDI-8_DxVcIx=*FrLelriyl;~pozA}k
zgTx(>IJ8;VA52|uLIc&>ya2I+H@Rwcf_+@oU^nzPV?FFe#cNJ*l}*uiC5kLPxgF=4
z*+&-evI{Qu!l)85wg9zilvKmw5=@L(voClpV#J8(nh0SP<m(C!AYb(c9{lY^j!lq%
z16~FRL1`TH7AUQwY3#)p%a#zZoSDHv!z<9W%8@y4DqweJkn8M&U!5yRP?~bu1LQRo
z1Wb_E6iFQ4Ga-IYiE09CNH}=*u9uB3Nbl+#z97BpwHz$^PV;qE6zo)-^GwRKTSn(9
zv(*)#Z`eb#E3@-NRO}SH-ZUaQVQz8<=Tgry@to8R&m@eh@z!J-@toQSMm(oB0$BNH
zqn9HQU<K$5jS^st<{IYA5(k+F8SxfQ<3(H39zY`8*|sJE3$4NQn+Rh42(pBaPy?0t
zBq&S4^HdSD>1&Me)G4;dNyJqf`os`&)p!V`cAuiGoRuVHifZ8EhZ0mgQ9@|p;bjxh
zEveBkYlHA{#>5cJGLE+X09DUbz^{mSYm5^X_?2K(u-gY|C1~nDX%Rq>p!owEljx9-
z0Hp$8^Jq*w$2iKC^*P(5C4)CODq2#ct26UV3~{>>m@&lv3KT|JT9|^_1hdCfBdf#^
z$Hzp>=apc*6Sz`ZaevVf@=7pqICzeOQy!129|1}XBY^kf9*J)e3vwdDfp?5Nb<<8Q
zNe(fze<tkYAtqlU5w3*YXM}@v3mgywq``DrjNtKW0`7E;@hWBCc(N+@$_O5$;FC!S
zdyg>FAr54Eght5d0Uj!k66hI1972n2A~(PYuC}?efPYudqzb?Va?d?jIi%?bu`uu!
zf5gzNVUY)YDD+2;FwGh`EW&s>Kp*N5vo)QuBf91aQ4XTWrgL}{fz1O^y#X0Cq+*D7
zh1C`aEigqHp;UX>k6J!&@KUu*rUTb1BZ+}C4zjLXhld79LIUT7KJNnVk^C>ZOyH6I
zFS^ATE<@#dJf9R`dU1C%T%RZ0HC+h?j2o{jsSzh`Yq%oO=faL~BKaoC5?l)i1di}^
zl%RT7Yv`E>n;lMf-Xv*(>myB?0++EsJ^}IIKa=zUZW<;cUR|mlgrL`Lgh4TYR5s@#
zQ_I%(y~5#1bu|}bMR|mpjDO#uH;Yg1R{FGwu=nknVXV#V>`W-M5(^rk?pq%32~gKZ
zlz#`=$Ce>jk?TrsFhQ}F?nKNAjO4MINq%ldf?{KD#(`>QgNbcyy(I>xZ^b6fjX+Rf
zuO_&7$Ce^tB>I*n*%j-vO*RM|wL`fjCL_<u<2Dg^zIALtNN&1)Yn0pg8l^TEXucap
ziEq5pYD{!1UC<b%A-MUxqeSQt6L?IxfQK0GrXtHj!_0uY^;%jWaHbc%e!@6vyi4S|
zpfmnTCYs__e&$A`sq&#rL<Nr}drQ&e(hy&w$$327h>Ke|LSV&=wKP2yjjFsbS5Pg{
z<28$_?n#mHF$kFF<g7Pd9`6dVb4%MBj%-}CJP=iA`nz<JS88$POht^dR3nrw*f_Wj
z-TY3_lMmg$PDYFKu5^OseCR@RZW>&|;!H5-jd|W$MF=4iV;AWGD?n3`541$tGC){!
zlLkW{l}#E9*9!m@hO0_#ZRL2H`zsT~-1vG3kT(%MJ#_aq!PhtDd*0kfL==2wF!)GX
zI`_+f@wQbw6m^=sCoz9%Fshb=1Vf7h2~vh`X=Zx-Un-7SJo-uP@uiZ3%tLi@i3y@Q
zz2_Y+D<D>P3bHVfXLjfcV<OtSNJl2f247N=$&mHgzSJmdDQ^-c$Ox191XU2hE_RfO
zyN6;<nT{`1T_ijZ1x1HHs>jOeM6TT;Y?-*8c<EfGGyYdT|B2Kv#R)Sjyj`gGiOdl%
ztIR}pi7!Mn)8`kan#maWu~^DsO+6BP7h`^@QQ^(Wk8_JT!D3UMh-e@3U{9Z4NO&d^
zX@I1s`m_o`fuEBxh$UNJcz`DCmX|ANR&@Q7P>w2Am)e&qH8Jf=m29-3Q1n;z#-9@9
zE|4d8BJ<6V<8}g8ngmK{rz~qz4BKSjzFe>~k*7mG*U3PBI#?%eeufgtPA7wg?Ju>+
z5QSP^oKm%kVKWZX85MBWVWcUYpaB@KClohILrI1wvbYT8E}j6v4tr1MNd7XAZuypz
z;c9%TQ}auZ_ylftAno+@D3&mMF&*SXVv<iuc3-wb5oQi03!k{%dWKl*Cy5GPkESQ9
zhmy=sCwCk*08$769ri#}L~(M{kl~=eySr8eVP;oSCDuT)+RFjQDlaRXsuU}nqfpd%
z@Af7k+$LYe%+y6g5uejZ{-!TJNfhK!#8Kz6<poS|Bs?0g1JR)tUUwmG`9>$t!TcPd
z#_Jf2#sTWJgUMlZd#i{JaG_kJcY5>4jWl|ff(>{Zx?X+JJiIPF9QQ7Fq4T*l=%!-^
zQpsOYQ;)%uxYggHnbc=KppY8>UWQ21hL56W#3up?>@TPh?}O|TP20ULI!6<v=1OuB
znv^>UD3pn0;v75_r9P3GYUFjn{n7+9U0a$<*xyYDhJfyCQ&VYZ${7AKfd_y2Hz#Q$
zMA12M(K=pl8&Yr$l7H5Ns<oyW#?e!e{S%&omv(gG##Y3n^`Ih$l~*T_0!8U`zDhV}
zqX5Ea2o7pH@_7cbsvMc%UnCqlavL1^^~uVSu;&x6C?#B511zmmLmwbz)umG4qR7g>
z2SB|YnNWExZHLD)6y;V2?S_G<;`yaWlaNod*PRzgL38?_*00JnFHeec(Cy2_Q1VX9
zr71q`%e-7c@I%UcZ;6ptkMm{6`7%%WvLn9C6C^C%Sqt&pe-*tGnXf+fm#LwI^Dq@m
zkfle_2U#p$;CMF*CA<lVvXd-^22+y9L^m^m60qPc90g97!@v9SZ=U|+{`X)0&mSE*
z2o{waP&c>>`7i(R$A5aRq1`?W{`&tv)&IvoKcDjFzkjJbcYXa>*R^V&=k*_d{_FEU
z{HK3u|I$8f{rNvV|NB4v`JemrfBG-~^*{de|MBPl`T3vz{M<LUBJA_b-Oq0K;h)3S
z-u~m?{_7wA`BU#cy#Dt;{PpRG{aEP${cDmb-8outh~A<7!QS3@ulZeX|LK4I_y6}l
z|M~x_UIrdD+}5Z4&-c4|%*zJ*x4LNs(O@qPXZN4z<){dmZ+iK^{V)GYy_|O{=bgfF
ztnbf1ynSZ1|IJQ<uT{MyKjGJ2{<oEY22dr0^nPCnD2$cP-@pD)`Lw@xK4zvz`F4%{
ztAAeWpZ@D#{_^9_jF#EqGVA-kxz9h=?3du`Z%s{Jh_82)1WNpo7x*`yS9^NFXZv|z
zeLt2!%zty<SZ&mPzx}9g41NIqp7m~jvf1`smNzi{Z!e~Q`FxMHn*RRr-Mi^8qwD*(
z*959e=v-BrQo`R>tLU(|7HP7+tpv>DTWj-U{B1RSb2R;L0NUR({U2l2#~g^&@ZXsJ
zpPzgJq~6g9G4<`}db#M{YMnm2@2Vx8($}R-!S7Uq4f$5n<;u6!_QXDft9Jg~Uwf_o
zbfW*p>TmzZ>L0+<zhe`?{@bzDo$*_1wBKLKJORD6bR_z&+O;6DlwrV}{bectW;LXq
z)eE5D?^9(TdG{WX22A_gJK#tA`4?bd#e7F6n#^xUhp^<gn&Ondt!C$!OPPY-sg}pi
zw-QdF-&M)np!3W3pMt-42YmGJC3egV;J-Ef|HuwNZeI<qlbi9|(ILI#TWj|}u#}lH
z<*lZWgm0^XROhWGmYr{__0FY*SJ3;HrS*63fPN{W{`N=c$3LJ0aIVwfbk6&3Y`E)H
zCEfjgS1IqoRAsl{SM=jodVc(YZ=-FjCwzAHyPW>+RsY$Y{u_(_A2NE*FIVsR18et-
z9Y{g{?n4C{;kTLubXol!Gjeap=ensc*1hceEkop|rX(GkZ#Pl=c5J5{>2D<ozOB}Q
z(R=H?lJ6^m73)hyNxrWL3XCrmCHaZh(C>}X{(KG2_wV5+-U2f5e(k9w-wzRf+AkF)
z`MzSN6Z%pO<!>t`wcamY{VVyt;%L8m_pjt9-b4|}{qBzVIn8K@iTu)6NxmQC{^b$z
zuRmVN_Z7>f{G}cR-&ZS;{nvVud|UCl=f5_`@=v^p>lfcK)|ubEiJvkN8B+bFpOSn(
zJP@ROsVK?!6+xf=rJ^L?S44=>mx_{nU-85*-@F7r^DeF{wv3f;-^I_VPFxLrQG}9w
zJH%O}fWPphQ1X36q&E7hdMWw7Vx=JXT2YekE5`U*DN8@`9`c6n_xHq48I52Q`O-^C
zz8%`CfP}Z61m9O1<5zF}m3&_j6ail<O7eY0AacG`l;mejr;Fs;zq==X&URYx(|_r!
zB)_w?e`$yQ(#HJDk6%CdH$QawDtdoEAL&z*;O{eUJ~LJBuAUjIe#7B1f96xpjv|8e
ze#-OWMv~tfq2+DXmwJZlt?#Q<RK=HS472#QS}Qv9w^}2=`S;c6;lx{LUp<_E|4V2$
z#Pc^SoAD34goe=UFT>mCdwq(EARqWrQORe%uL$;xFBL^F_<hAnJO8z!#UE<1*CpNi
zF8cZjga6CRxGDF3<7L=C@-jf<^ksyte|OAA#RH0e)jP_>@NG3DA$hC${3ERaX!}+Z
z^7h+mASdBlVEHFs!nxr1-?{|(`FC&-iv12wvDx1a4rvhIYRZfFZ8dONz15Ts;Ja!8
z1~yfr;CHIY4P0*^e#Q%Yqd3c~jQ`GFVD=Jpn(yG0ZRp#<t?{MG8o&4RjAD8#jPuR)
zC#u-~Qo;7`{Tz;B%=H&P@!vnwH#qaZqqh+~^uvoW42pv92j)@8@3&g4FUW-7tmge!
zt$F_=t%2?Kt+wKiv<56P=bz=Dd;@;tjeg?|`~zQnAG}WE;KsMtX{^?rgG06MUq<(v
z)sVvEt)`qN-&Na4r>$yR`L(~T1|TTk0Lwr52KGhp{l?ekA25LS9={sg{`Mk{)xc-=
zRujS5x7B`a^6o!m@otd$z13{|fuq1~hpp8cXy;2~fBze}5X|4$1OL!D;EQL5l5Y=8
zz;b@6_)31_RCuw}bwKa^zq8k>BOULTu6_~yjxYBYQ-k8qII3@u(8jIRx1OM%`H&fS
z6TWoyi|BVfq`z7KUqnCS2)+q1|IkQ(YPkZ@`*pp(qVFAhtIiu=tG=S2aqiuqpZ-Ti
zx_`#6RFtz{yZc4-JHCwl3!lSZf4q{Pah_f3$3HaA_$mKcfnLA%_7(k(D=dD!7`}*p
z>Q-<5X^r3i3jK_^M+ef^&c34G@t*%$ll<zV{g)sA&C~zLxO2?^az}sf;cKjM5#sf-
ze?9E~?~eM*HT?e535z~HwJ$1GO6i~eUro<<u+)3o{r~)?UI`?KOto?s!xg0K2JruI
zLfjBE9$u%1sNaH}2(bNd`cr_>4<~XN@cVE=(t!dFCv!*i%#aYyU;*4Dgjb+o6hthX
z5hKNB7ES;=aQIOPIG>W#pcr2O;CVRX1_2@u#f%q#Ih?jiAj#8}pj!oX4ll$YSOLNr
zLlzbJ6$~g(An7fEXF1C85Y8YJps2&i+!QMdXl`L@D_j*U2H~Q4!-*uA`xMLv;f#bX
z#<Xx^PQaKJ@_-cT`$<WiKBJ&k;Ur=U$K*3=tr+5O88sY}FE*!eOg<cz;nfY2A0T^U
zIO7{ZCK1l?mk9QY>4d;QaRq2La&j3R55oB?s5S#rt7J$K7+E%OFe;*W;?$@ZOABhY
zP)1xbYlJhH4ha8nQYat;=M~i14N(DCpehGd&@0fieI!-5o!EqDfUzw$18+`6u7vXc
z9welQ%`jYqFNBf?pDNVH8uTTR8HP^<W5y;q!$C5uAQQkbcq>Q=a_XEfVgL~5e*{&i
z?mBrv;jy`rdfv=`qhk|&VVDVkKvz(oj#I%mu@wSzUiS$eSp8wN->Cy|Y=)&E&?Gj|
zatDc;Vl(0aSdQ4t7jo%pK1GHI0>>5`G`FXAYcLW#CHY!+?Nmg-gc4Doje!xgTJ-(F
zY}N<ki_MLR+@S#s>G40+&(T3gkH}R3cK_JQ=W-lfB7*4zI#r>ECu*rN^7I7W9l?kP
z3>{a3Rs)_YZd;@Wh)oWYbI@x>up?c-6=WnO7==P)2$?VR7SZUzz?8ziL0!FR%Uff|
z5IfRy<jQT`ppmvRpdyn%004H&wX7PySRLd@SHx%58&ay(R(_mV<gx0A@d_que^PX3
zbsaSg&9s!>7X*1ha)m3%SzJd=jnC-Bwa}53G*)PcP-aV+!$GMROZmo&B`P0;;_aBL
z8xsK1KrO%BAdaphn&3*%v8sSjr;cd3kEs5LE+{8@gEm@Qoq|4EN~GRaY5KL*>O#l4
zKRZJCJ`$92#fZk?N>-LZbksrMcSUTbba*Uf^+oc85VJ!^oMEgtVQ?!wwUqG|lwh%x
zg}y;kt*Pz?x;sge-a$9^5#a~-p-Os<kjN{ke8FHa3(-Y%rmejqHVlO&28muofw7nx
zsw0nWxrIA;17nHnv?G4=iqP`GD_0Kp-m-*7K`nSCXtaZMIAs1`(aJJX8G{}!l-!{s
z?QJmULa!9Ju{xu3JJP0x4D}AKx)5<iM>5q=s(=p0!YC?>JN3Ov91XM`(!AVqEn1~Z
z2CZI*nZH+7+$TkBxRjo9*>n*01<5cvvgF3p#xL5#VD6m`<a^A}LuQpQu~3HM`oEIw
zEZ8z`IromJ_B-N|Lsa`6+=n4v{f;<^5X%2b>J@@hqbH-{Epbku??kcDL6R8a!~dM#
zKBZ0Sl25Uw5iIo`IYvU9^u4ebK}!0bT!;Y@_}&q;7$So2@UH~<H+nCPHK&FKl{Ke^
zRxz$u0(Pm6xbqN2dq=|9AVo(<uzHA&{Yq-mkd(7Txu>W0aZlAH`t^<kxWUA19ij6f
z;`E+`ig%Q`L+!T7Wa>zf5+XM5AWn>FDAf$pVC~j9XS7*6NB}}q=2vo14Z{byVu%K$
z7oX}AO3>HAwiuItuUTzs8ahn50Xz5#Vk&`Bw~<ABO2E4qNgUEE<859@@sV}<QvSov
z9J?VB@@_a^jiZj%u_eYqsjj&~PlZk!fgF7OE};>6B6OP4M0QX)hEhp(Fy@9x%e%qw
zi@{=cowpMm<Pt&7^6L%F6(-Jd`bVz>Njf?>A!8^@d~yQcGTVis8%it>;)@tCho5dZ
zu8pmx93$EqqhmzcokemSN-WxoYw`|pX;e^sV{uf_d}FC8C_dylz2%i9I14)XKVr}j
z?qG5bB~<N*Vhkl+?VyCd5`5+>!A*#Kr6Z~(#zf1|ej;PJl3E;7O@k&Z2JPxTKI(7K
zsP4e)hDgaf__afH;(g%!HpJs}McFx1Ehx7^v-nD?dv#yhk<#~;t8-5uDAvp(?Qn=q
z{7UMzb~OWCCjOT`sLPO4xZ|2uX@`4tJ0<lULOz}tT}_uJ8|@t+ualux2XxyYheSt8
z-4H2w*Yz?s_>-dB8Ix&@Hy#R6>R1(FG?qcf6QY*6lKV+D?RoH!hF~)tZ2DoLmUfod
zN<k$f3Bn&pa&k@PG<MHNf>Mpf)oSTCb2W-wm_fFh4sN1QD(*gTCQ}CQUa1noWDO4}
zxg!65AmUAZm9k;k#{>G!mbwB3CyJY1xoV#j;iCY?rm&@^Q^DC%Z*e%oXzJC5O|si`
z<fRSeI`2q9k&>Fn%2II!Xcs!<Mub<X_M}PA&Yq?E=0IzO$uQ2G&7rHpj>H~Osoo!m
zs;dK~>LuwRI+DR&30kRRoXE(pAWw=RHu8=<CRf6ip%smrxFgl;mEd#n(fnb`PSU}q
zdPQg%Cp+tE8j4eNJ{`<qSCT9~CCWu0>lp;AVX~FW+zD%JX<}i?TBg+$hJ8Kj_v|`!
zWtSO@96dospex9}_CpSe4nno)htDja2#I4lG7LpO>N~WhNQ9ma?zZT%o?%&rc+h*=
zp0|vTAJQsa$wE1OBO&6Uj{Hqm!nPfQl#vah*61>_C%nwjWgr7=pAt-Fs=mI}J7_*}
z6m{7CS5hAx1Z;<>(mUAnqSI<Fj@A%$dPn}xAg|GrqFk7LscopfzSQ=?q(f2TtaHow
z5G^ox2icH14oz2p#`9Peo!;e+)M{6PmXXym`g_Pma;gxQdIx`DC^)!hGxRU>rs+!9
zIje(XblTcDvqqP#jWg}NKdDl6#NIYA+xB)1y04p>F5TBnEyKmxX}2$UILXWOq^QPY
z_(6UHx(xR<vxHA1JPFZdp)b(JMVE;VhRWzoJ%b_?_j-r><4WFI<s9zh_U>?_d?Z==
zsKF)^9Nd{9nx_t@OiIer*+IE^MQj(kP;Bj2a`$+XnZAl{CR$ZM7Wrt>*{gQamDHDH
zL05{)y(dNOEwfoTI9q*Z;P?u$xc6eCjYcCJh^i35R4?w?E2xe?S5h6-&R)=+f-GK1
z^>wQysLr<8RG#{8nJqzeiXgtjX&6nL9gf8il~vy$3X3MYy!?~VWR-9DM;onju+~PC
zRlcENNj854xd<Bl(|uP3w%aj6+2on+JlbR%JbE@6;7BzV4F>ow6)LX!E2xgjyx!2D
zO-}18s;&+_7b>(3Ja^>3*>C92Hq>`;PDPW6zM(-I{ni}-jA$~^cPY>&3mvZY=ZdP~
zi3MhAyfkW)y5CT#BLC`0aTcxX2(+Oz8!hg-R){7CHZC5ngq?v#Y}o!!is~K7<_3Li
zG`g^pJ@yvanNmG|<iW0dX-|sSxMv9;08qnT37+WyRmxdiS33YzK9FRD_R;p<ftF=X
z?^1q_uIJ<Z$UD73DR@Ogzqx<B5_IKM!?LFLLA&Xo_EKqnw(L{nTJs|hHON?9ISYD{
zvHFogUSzB#fs^0s5cm=059*-gM+Ug}8jb94+#$NsAaqCe6+g1S!HnwSLF<{P&5ulH
zH*{rwsS~I}M=I`A{V@Md$F-{`cUrGISwGUX;7Prb+T3-q`=o>|6FDoZ8*Hh5WOw__
z5*w}NuLL*p9VzSm(8_iKbY*52hq@mb*&sl5+*Ic5FT7W6J70LMva*p?&W~KsAUgHa
z=_mn{sUO+ZzO#hg4a(9hVLKadNFHh5rK$bM%mzp4m0*;+#w0Tve54Lqsg87Yx6E$@
zKnhpHwjB#q=J;h7{ox^F9MqytR=MX&a&?59(m+F8Ni|(AEe~1aAo+A<g(!B6rzCjO
z^*0Zh+Q52vz|>Bph$}?|<FmaosXY)?=j5pdZKj7j)kTz<l7;eJyFpL&(*b6=B1{y}
zEFQANfoJg`iA)Ee<w^pIAAFQo#K!BrU&%swpb|a}fTdhuIO|wC5UvCp9mo`q^`%yI
zkal&9PeB$lconaNW+|X6SH!2*KD-h>b>O{CJr(mii9YF|`g7&3==h_Dz6Mp_LtgFb
zM@p=gRZPsDOzp@T^{-s)LF+gcmWsUEfS`ON4~qBq@>e4Vh>LLPN~$>-!{J%t1HI1q
z7aUc^nk+f113E0^tPUtK<-X{JP`LtnV+(<DMJVOVcNxpM)LqFiIyQs5yw!;)d9DPd
z?1fNJS5grJw0Udiy2qC%6xE3`Id|-TSF((bZ-l$t(+5h;wg2){<1Sc62U5kI#xam8
zSAfO=RdMhdUkNmwzxHwgR$QQ}UU-y`gr+dyDDJX_PnGyk;B#Cks*a3<SHh>JCUjZB
zNYmpkGx$Ig`l6#BxqYsL4MPzEPt}Vq)Ro+$1Ha-<OZe#ku(<Ml^uxFgxu>B^of$y-
zN7K3>R=qUwlOp`NmZ-}&4UO(D-}GTPiR|Y>y0{NHkAQV?LA5U9QjJjNGmH>-S;MeX
z++T<F$B=QCDSV*#T(&T5A9t9-2RhEBf)mg3lmwFvEvN984oHhDSIL!hgvhWZFCFL(
zhjjv9Tp+9t<cmA4XVBKV%U_+XHeK9-@y%V<^a;$iwm)DhzGVgjsNz6gJtbNxcq?UB
zw!GD_qJ6_!HrU?2>8-X_H-Ik4mBE0&lKPYwtbE^eS6|6}_nRJTL+-}siqI4k*rthX
zNayG~P^tmB8tyqBr=Bq&T%6fj4CfdZK+Awt@x9fPQKeQLh11pdRuyQkOy_b-Irri;
zG#vF@30|y0b?wEw#49?eHZhS<U3;nRQeAtg<%yYHD3w{er<#UtBMi#`fw_W>NnBZC
zqYJ&CcSRVE*e)2B;q2~vs8<`E80yx>>#Z&Ml&CslUmjFFF?P+fz;4wW@onmw*Ac+C
zsc9%ap{oq84_D$DEANQ!u7;f}tFz_6%Iazzx>4C_42TyOO3M=U;^j$rAgEW^_}qgr
zG(GoVsgz}G6}j%askf&-ey;R229okCsmFHcLt(J2Lm#fPdMyDfz64=5AXa?Q1#LjA
z_@WE?O0xSa)H2lJQi2mJT#G9yj=`ySB@5+z_ezsva0FfnbdJGO=t`V(>Gx`o^g$aE
zMEY_)2pW*^Elc0%ohw?o1_$buuzyf*YyXLLsyEu-aLQgu-HlnFS;AKaxD{VZU4wdC
zOYK6vt)+HnITT%(ErZkeO4#(olrN45>TNBxzG}iJb(z6~eMM{?N592`wRPw-W$ZEF
zS9~c|gB4)K*H8zc(biB0q0!c02cgj5Nd8z_hLi=Kpe#$&i!VB%4Ji(MnfeBOwoL6t
zmVi{Wjx*abHVOqNMAntmXbhzaG3{y<M>-`AGF-J>3C9MNxM+4?Nxh)<rB+V63vp$Y
zGSn3$VaO+OCFmV4oIVniGH_K%at&8jPH>eWspu836{t4l9x~j8Ip}hp64is*Zdn<w
z3OO3#u?$cdpTTyKV9RHy;hgj<V7oZYDTR>%8{>j$S=~f_KB?jYxT5N=>p>%X>zX&H
zMS-xcq<ZXhsa#QYd20|*i*s`jr4{E^)6j~@WO&yoP&6*Imf;51l{3kJr17~mtozud
zh8HydTx_{Cvn!>N;j-C*`ZA=a_PNw<oge3t+5nd3irDVP5U1MSHAbp&T&FvMVNZ%`
zh!ahF{+o}4I-OGF0L}QMZEXgmj*Ao0keTL6@X+f0&~V@hokP<IWjd7v*Z`w(WqUHf
zXs(2fr#79YmT}sghL)j&u7GXVBkLPsrAcT16N}X^ZTA5+I#Yu^CAl@|l{TaZa;1kd
zWR~|yJK6w`@u_4Y1{{e`c%`k7CO+wwHlSmC&@F91$M`sE9AOSFeApEQs<HL5b9~VJ
zMxLZAU|V^R9P(8gAUQ6`n1Qw2hYaZfB{^!;AN4m}ZSrt8TvG}CH>ijKhH(M847erF
z+*G%e^El+GzM`DSu{B)izOmJG>AoRVjg-6&@XAx73b^0+LGIxp<NG7`A;TLu7#E=H
zO3L6GGMWKC^TFLVp!9}}X3T{T8P1rn#|LrKhU8s7re+1IFSBLYxDU{N1o-YsZmUm9
zYMO_dh1wfK%|i7Jnd60)xdOo24R9G3q{{|W-=OUcXp9fp-wBQJA?tep@Zdw%Hx{o8
z(q&lkK4feovD%eXOS5$2b0v86ECngZ))iETyB-V$Ip~-+q{r~l=q<RS8U*d{{21IK
z#suJu1Jz|f&D=6u?$Gz6sc9S$hivrv=D5j1pKyU1^*N9;ZbFF|pfgv*pX5@oqqghy
zTnU@5kE(+h^{xqgd0pr*%TKc#eb<JMw<{5u;S28u6TMKtPYT#l=}>{e4A>c0sxq5U
zq2_9-ROoX>YzjKm98InKH%C|pS0`S~0IzX#=?VaBTnWz%+Vx7<aOqH!kq-h`w=(jd
z%N*WO2cM3K<EF_%pPnUrYXFP664u~((`cQ~(takxdqVpO4rZ{4Tv^i$z!@*A<bkMO
z;^c!<`PtO$2NsLW_ZjFu{n(!|)(_Y)ysxBCGuV<>z^9gqOpKT%vc=7K<^i(Bm3Pg6
zZ23sCR7%b0$2J(!F4WeQ)RD(zQCB>KTh~LO)2#lCQ=ie5eI+$pO->sm2X(=?EVCH9
z^0*m*E+0vj-~{bQ55+l=C@x#`7V2O1+6BA1l5DPretcW&vXIxrm$1u5#!<|BXy8z9
zT~;%WbS~VL)v51!NnZ>n!z)4CIN5dC)gWiP5;hK<*PU0Swssb=xdCYLPKz0M7Vk2d
z3(w+x>!DPOf@;}<TI{lz>mYsw91+xFm(jea7CVh*q{ek+r88t+c0jdk)f3n(^kRQ4
z<^{#rWibQ!;>u%Z$iwVHYFS}nt^j!*4W16~Fqz>Cxn(vEMXA(x1|-at0J>-Cb#bA+
z48WHw!KY@oEUo%CIxmZP*Ft_=&@L+%l6RTMNW<)11~SqxI|!)^kd|Af*9X2TCzQ()
z<Z_E_1`4s$g>3-2c&7{dG2~^wA~p?`*kNoJ62^t^G9Y2RcQ%ZS@2)(31|W>X?NpK)
zqbzbb5WUMHui(umMfeaQ!?KGN#{gt;!Mv=1EZ$^E1IY4tJL)tPT%&OfH>x-3+P$)b
z&kFpoSHf=<e6?4^hM>=yJlnf8(3PN_awA;<E;6sE##A++&6+&hyUv5nH9(yHnvC?l
zai9?R%ZPPRazP{5MW`(U*rn|+mC9Y(<nZ25a&4oOtE|b&hFjkS&@#CGy)EAJ8SV$X
z$-TYn2W$k+)3#8miItUJ;owh-oWCJG7Mm@NrwoTid`z1tRnK+fWW>5OIkOQA??PK$
zNll}C+1}BzA$;RXvSr!RNF?k^q-aPad?lCw+%`G!R!@qmi}Gg|W~Rx)CT6D5!X{*<
z$(zlKFmKY;gv>M<-GI$B+1!N0G@8>y#I#1Nq+Li%gEft-Jy$+Q%j>{fX4mV}yN@jA
zN(TItsPRX4>2KwqGLSv&1Jk+4Aoh{v3^2?-M=Annn0@5l_65>2?PlO(u7qvxEU{e#
zBwW#g;J&F_X3Mp2wh~PmZh^OeU{)8!`v@6wB{f8u(#Z9(k8EY6*4+eyncqLl1g^XA
zCq?XTpm*?eBhTO#(#vq~zDay*buqsyn*V_$6Nwx-yMcV!N6u~#p=@QpF{G#6=e^HL
zfXr4}OanmXO3?Pf?90_1?NcJu+M;oU(%{Gty9FRKfLivE@&%}63;uN_E6eN}5})oP
zH+Ph_+f1){1@(rckpYGINKm>K<v#Lr0|s*??3-b><>xNy;45Ie^#ytM(Ki4&Mn4ji
zYGUQt&cvVl$ghozo%{56d;_D=ZU?UB68^E;6a^qY60x$xZY<8eyxL%A`AAUuR0!GF
zfCz1ZvogWv{dovkeMLE|A*XhfX1fwLoNMz6*laD|j|8P0<`#U*0I0bVv|LBME8y5X
zOKh|h;*Mbai~&Kj1?V#TYlrOYi0YZtX#{#!miAMkg<9`(s&{f=N1%H&$D{ttz8=hc
zNGD@<t^{8P%-~i|Qv=p!hm7%h6VDDA<3QW&pe+up%@)4PfVJ5HTO3H6Tc%Z+P@5}2
z%K+BwknIg%%@*d1`DAyz{_4{)C>Y;`TihX+HK2`KU@imvafe*i1(AGG#1R;J40}6~
zH9O?72C`;{>~A1zcDx>IKx=l$V~sDt4w>ZjvDhJt9N&{GDK7+|H9O?82DD}qK6V9x
zI{46>nf--neQ?;^f{PixhntCItv;zcWH#fgyF+F(aJf4ayllYD>}Yy0^kLAEeRdYu
zv9kZR%Zq)GdwjdJH<Bf9!Nv?wnk&I)5L#@zOz(p@`|Y&7Pk|e^%duUGaJ$qufYaM$
zkfQ{T#tHOSM{odTJ`$8bXUcv-_bKs~mG$tH2m^%jbGf=<hkPU`<xKlluWBl;gvW#f
z-RCsKM{8NC4S!Q&*DP+7Y6j`l9%+(2DXCc=fXi%Q!3G$|w@=lAmLrO56qm~_!*Reg
z-`nZ39<X3P5|nbz=(QfOfv*J59GtSDo<ODf(D<O%oL=jZ!4J30W}((x=;{H4%ywf_
z6KllO(yRfQ8k$%mLRXIlT_|YRXtzq|Ll-*R_0WaR)|RX!>(4EY#UE5(`};)9G~Lx#
zQk`#_IgqAZ5t=U5Cm7cNvSxex6Ms-$Z)zI4&l@e@0bI@YrnW!YZy&W=3wH|%Hh`kJ
zl7(_=>?>e9c`DpWDKG${xe~Tg2JaRUY}5gFZ=pv94#9heh6shZ18qY&?odmoN_ZL6
zj@#7?wBvRSsI+5m$F!bGJzf!tm&~#q1*(oh-juA~2Y@#z!CC<HCPi3cz}}>Y+bHoj
zDM9maV5A81)ywDk5ot;E&VIM|QJo#<jl>mI=k<nrN8bgO9{|*(sPLkrJVPa7=Pf%b
zbo_vSDMf6qG+v6h7dx^qHkn}q&Z`t*{!&4vfYVnRGDYZ9smPSD3!{b?S_1I3eMGL-
zCSF9L>mSI_Dc8g-c8b>tqX0E2!EynhCPlce8GzKJY(Y@3OD5Oo8$}GR^kb&@K&0vb
z4ku-7ZP%33<Qj;VP0@lNSSjbE9)z*s{4@}Vn-ccGF|?_{mV+oos~+SW2a)vyuI-O#
zs84}+Ky1)}gFHpJ#~8rWqzs)pd@VzrI-FfouMQ{I-j{dSQy!oO9QY|hFRWD&J-5aw
zH(csp5oVkg)xbr;M?^R0z+FO$pdAaQlM<-u0T52gYJ33Uqy$?Vpqh`Ush7rXiGFP$
zh`wZvKbx${hZ+0TP|QBzto)Ry-h(WxVFRy0Ce{^I&s|#`fSeTZ<C2h^l(7AQwdkx<
zD^WJqz?D>rKyxv0aaA(R`K+brq4p<Uum_6ua-B}iXV~IEaQ|^7tIC|S#SXgqyx2)c
zF>T3DnMbYxKuwD9;En!m^>|~QzGj%=u$eM;U~?E-9oQTS&tAj)7MI#b1V_ry0mpiH
zEjEzWq=-FmtOsA}06usr!<PuOA0N?F&0s%ynK2AS_VK7wGUx2DSG4Dhx>Sh!D?+F0
zh&8NKObXN%mnn}~V^Ez6sXqqQsneA@24ciY*7&nk0`y=s4z7+`SAbW*qt+O`inNPH
z$EI{s^PQvBhhb1{zQ!Ej4JE4c;TWYiy{U`To3HgYs5fc84Ju7n9NZYxnvO%)7|@!|
zgVzAsBQrX&o8VV(WySGP`LWnXJwR&ZM$2wckqXg21{LW(I5-V33RMOvbYbRrU)v6d
zo)ob)s^1+vWDX#2J~A0+gNk(X@?wl#MSQ#l73p?;K0)M^GR#xy(e3IZ_2_mK(Zj6|
z%%B$CTWwQ~Dm%>>P@@U~7=Zhv2zmy1pA_LcFsN)Z5MT^yT15hkOgg17fKdRSr(|p@
z__DR*2UV|d{R4Qf6!Bs8{!+w&Q1uGmKL%Cro_ahr@7AGj0IPasw>+=fRYHw1sdhKv
z2V+w0ZXNq3)ow+nKagSF>f|?}cNIP`0ROq7EOsthlNOxR%#0owlbTr}1S8=;DZt=?
z_el{ve`8ji`X`6Q%atp_uy`n#P|3S%0HB{t8HYfXyk+lCs^l$ue^MngV&F>Z9X1Vu
z8hJMjgIamZl$g}YTc-q~d{V|fKr1V_U;yWnB6MM5g{-4KOnl!FUod8=<wZ+>QY$Mi
z;EJk~2n-k#8h44o{EE=H?E1Ocx;_|_8h5!KPK|rv1@$Pe5<dPw^Q4ILL4~_?I+#?r
zOFWMQERrc>2ON`&7=lbZo2z(jH5eG(mcp6A(dmc)sCK5<V?}CQ#sG|ov+0`pv`=c&
z#hAOXs7+V-PsgGzT{7%fV-F_3?W=Kq2{syw%2dGuSA_Ycr*%}Np###QI#u|<6=6Dg
z99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_t_UwihW(<3g)&`Krh@$skjbWq-K08ID8N`$
zr-^dnv#Ouk(~H^^kD)GI1TS3?UO{6_-B?tnOUHv%%5*g~KRGmQ=tX6kF$9%)BzriI
zTEjth>L9RqkexaRES_WM(MNbu11oZ1tc}6o{Zre{(6dY3GEm@2N%dN>0%K9<&d@-p
zauq)?7FBND1dIiJJ6%JgzMVV>EUH^Y7>q@AJN+FRb*{n;#=>*hcwpU5N3qt20u07N
zEON@wI#0+7G8hXd<f+pF=&V!3whzC-Q&vK;VyA>FiE3K024hi8GuB}2RwW+YHg)jS
zDPU6vE0SPr>R^Quj7=4cuX>4UECf!BO%;r2g0ZQDr;ZbwI(SZf^ES1xA`iwcEv&$U
zE5Li>8Dn?8wfFn7c@myF8f>Uu1r3bN!?5B8#-`?-AY>oA4!Kii|E5ZvGW$1G>g;+p
zRqE_-r+Cmsn8Daks8i11O@%sjfY{2I`W_%EAoC+?>cZl5;<x~A{S@%wrFRi&@Yy;W
zN)>4j$EHRdGVnJwDuV{bzPfUR2CBp9koMk=wg-VsSF}pN2UAmy(1Uq2RcOK3RGvc)
z+fDU3wBa|@=g^s815}kVJU*~YhHU;_Pp*H~jE>EpQ)vznOAe>j%y5BGhptaa7P?bq
zDrR6fRpzK~=~J>=!$XF<Q)dnt?v7g6`A(HN7K*U`6?!n7Ds;%Mck0j~yWXKg6@4&x
z&b=~}@&07AdmUMaOm?S2ReZs4D%A0s>^`c@F%1qv_PSHYj)5Y^U}}5RjY7(5&pY(1
zA`XUAzbfcpICZRo4u(&SRL*^;jva<#K3P`0Q@=6_VK|SkqZ6GloGMq53B##%hpc^v
z)*Z47oLaYn6CTL0K4{s)8I%$Zm`ZoZv<D$Xis&Nn(!7d47*55j2!!EOybM7YPQ7dA
z9U&Djf)K7C2csZ_;nci}LKsffYp?&`se4WSf2Zm-o(epwgl~#d^CAx68BXPEa{fDy
zzlu#5$eENP&OmUuuKOFO`c;6!aGq>UCco3CtoVWvt%@|ZgPK+G1tX|g5nylywJA-v
z0Rbgy0#jX4y>nY?jC#~`ArRD~3QZV6HEJNV8{m&g38pHjM;V_mf_l_+B@kJh<cb(U
zpR+-+2lcG!*bqFanymleNwoqF9>`Wn@L3A#RU2O(g%`ymK~RO-djN>Z>D3n_Ci|%a
zKq!B>t^)#E)D%2CfI>+bTBKLmbZ`jjT4NET>+&!}san%X0=GIT!h`8mR(Qh*9!%}^
z{NpyNWSCB8`||t;HEsqmj3{l(7=|Y$HM?E*KA5Fa#2KNw?Q;AF)op(r{{em5bpi;U
zRy!-zdh7E12R+J2IPjFL#;fp%5%>vPr~kMIiuDq^bbru$%&3Pe!60PpA86_>yZ%s9
zciHx*(O=&kW%O9a{h^j-FvK{$N^FQqx^Jn#LqBnsWq+us6%8>C6}93a#(|=)cnChL
z)+YlZ#^G645fS6i<=k}>aH!F{kXYlCO7A)W9IA9hMhqYnKO&s~4plfg3QC3{;=6F5
zpB3jY4)t@FDSxP+^Un5x2wm5G!J&Fa2*fz0pu27h4i$7CI!YX>=&tL6Lk-<^COFj4
z3Y8cK8oI8sABeD4a9?m1-<9qQ&cc9&3prHTb(daGqRv*x#5mNwT^9eL@>RIQI8e0}
z-0(nzUg^%@P}g=G0uB{z*CF6g(e_4X1)svUsA-!n3=UPTq9jJ5no|Hs-Z<2>4fesI
zo>i2@I8?I?lNg7-Xe97?N|vKl=){#&H=7O~hlkuoFT+hwif#%mJsZ!k3V)aly0-Do
zU^c2+1whP3Rofi%G>efmB{fx7f^IpA=+ahORI|X^JSD4Fph$|@P-NruB{v*LW}_>a
zaTHI=Ftm-I)T(Stt>etA;ELIJz->HwJhM?_E0|(79$(v37bp9~bHf#(Q^J7FM%CMR
zA21tLZ^li`2DRIUx=F3u#yd&WyN&0I*{FBhP!Fhk+fdg_^^$3+Bv_aOMJ!8G2dJGJ
z4j8jhJ7ZR#lGXb+HP6#=GYyvhX2o1g5Fvj=!VAqtwa&ncD_K?MK&Y}6RB=V<x(*Ao
zQD-;a49rHI&ESjKps`!iWKv@{ar(_hwXGnG*{HT#Qzxjk6`C>I`Ed}IkrP#R!4;wT
za#LRcn=i$F5S1~3usRCMm<@N6=kP2s^ON-v;D~U`cML~C7ZY(^2Qe43*S|Sey`y8i
zF_@qbKMJOpfKi>}dT2-AyihQ+AXG=;783}nb6j1mw|@@L4ilQ;93CB>3H5Olm@&bu
zeiWB6i+(*N3*|r^Ha?y#vgLs>^4?%V<DRorWukYm{b%a!b984g5$AZ$R7XmqUJ1Sk
zKulc;zFPoHT}fSZUdcc$_GV#zd0#MLxm*dSVbuf=f<z_^rNbDDiOABU7>k+EsB=t@
z-57$ldB=_L6|s_I!mD(D-Zj2Jn_c4zG}<-3$VO?xPo!7)NKmRdYwAK^&KOHEJG{K-
zG&Ou`oj0|6u+Vu1m@wl{hEq%!`X|H^G(QJ{6SVawP6{Vz>Q5Xej?jD)yh0~vvrmJ^
z@q|=t9bb+>c~>w{i_fVEyb^R4$Dro~z4#MnrH>>__g~tR06?99ML&UlI^ZR}>jCJe
zqX3Hu@Y7L*#Vq{O30I?r5pq*L6HuqaaEb|_(@{vpOqkPAJjDdc=}OoTSh0@KebZ)^
zu=j0ZL`!3w7}8?96Wv#g;}vE9wQX&p|4Yr3mOQc4)WU$KKF2uppO|cG<%p(6xG<u!
z-Y2{ZC#G5kEb7Em)AfBh3b~ktiaIeg$c?oz*zm?6<*A?GcQ|3H<=H!0<P-c5N1+lE
zKAMA2iHW>Kx6G~tTBe;n0dhLg_1s$2C%T>+e2*Ouu0L}Upw>eA7=WjgH2&sxUb&#I
zAUAxJNj^uzv}tn#eRPyhe2$(a?9}oVJ}F`qXe|aj%yLa0WelHiUmn-a1vcqQfUmhC
zt6F?+VIz+Rp9_8D^vGXH&KeVkKPjpK$if~YOKiE!wd2mGmPvP%T6~T=0iFcm&BO~G
zW(l8Q13JRYP2h)4MmS7BhmIl~o(Z@4QHaBYU;X&fyh0KA((s{(1eePP<-{&Ey)d!W
zwT(%g8afn}Pqn=3$bFPUd?xzn2yQolEIJt`F>yh0Tn2JoVjP$IYywks6elrp`Ee8#
zF_CcZC@x}-Kz9d9d0ali&s|aOMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=&~vly
zla6;a4IPJAiYFzt__|t$*7L5`q4|__e9o37?9d78_ApLj0z`BLcq%x&j?$7(+^Zdh
zO3dQ@I&}l|K$87cY{W!X$+KzpBJt!=Hu8z=ln0QyXU;0H6=*(1N=!hAjv^(lB$w?D
zwTmovhgr#I!Hka3braX12Z0h32&1z@O+yjxpbupNV03n<?ST<WS0laW5khayiT?RJ
zRnTplrtd5&x+{2VRR?AG;u`ww&8dQB+p>JYi+47^6p1W4Tb3`7MQ1NHyl|@6OHJ1w
z&t7U8stxJNXMvB7V0IJN_E!Sm0Iv40gl+E{;#AX)0m-BWci{o%?kQ1qMz%2ELPu!1
zS!kgvz~=;5p)1J_J}Ig<MSB?(Ku5{RYXGv1=Rsdg&42**Y*Rz2-L`2S4(8X`O8JM5
z@{?al4XDi01@*UyoWGJB4PE6E@R!5%<r5H@Lx9|8cz_0-EiGEepd(P*1TN@oI>{%X
zKOYH7X*8^(o<RF8nav;>J<3i#fhf8Xd@G8qv>wE!N0!(u4rJ?~lpA`<$_Aq76ei>;
zNseyG$}T+7Su(N#7CI|X%8ei-+$7D=74aFRqppMxSy^JQp)-}z{7R~??^Z^}@UymB
zg3?^HpjWBPB?EdvWiBylP9TPkvYO8Yy}4vU14eX~%;-cBoh2iBZ4Q!FG$2H0Ej13+
zs#NC_0HPxl-7E;vS>gzq01TZq)t1+&XhUPFkCLHJ&=DU%>TWsLm+WJ}8_$w~jEwb%
zsm>=*KxfhYJ(2bPxuOL@c6O-uP@HRM=Aby&P}5MHZ?f}=b$<k#o1cAgmW*udo3mhK
zV`rU3pZAsI0O|6+f{iNJ{ToVh$%x)il8d{0-#*B#JvUU~YU&77Ad-|%Aaaioa1&^s
zvw(tsW`TXqYU&6S;G|D`0_t<-(fFYPm85)bL@OOZ;wC=BXVUZru=&iRwmxUS8EOY-
zzZvfsarhHHZf+<$Wh$Ql^c=z3W@@8b&YnCe$myPPT0^N_2|5Sero`kEfb)|8wz(05
zeWpCt8@g?7bq>01%3Zxnw@o>$cYO|?!~ErQL)!_ub|p2UjZ*IJDQ9&;gl?HOE^LaU
zoaYm8pflyD23gRVGPgk%bf&JSCZIoO%HW1MbtQZd^xu@*8fMu?g3?{=N^d?9C~=5G
zn+S<LQzkhgF3yy{8etjFnX=LgMRcZ&bbyFXCPAOT4;=y7CeTACjl2hv8lTK`uNrI>
z$3^8%pD>`0U~SU@WjRw8ITBG^NsZ9!yr|6RS5RG*z3tGL^L0==ROXa_+Hqi<w8=l`
zkuznF<GgZ|9DVxWGL=CNoY0l9X=u$Uw{)R|&X9!;kkE5QXc?YRB~hOsB02!YO~8ZB
zkd>YYp)*7mG;!8DLq>WwOKTj5$0LB;!~ydRnB&OGaz?xlsPC1MrcdB~Qi9os${g}k
zJCB;f@!-^$Lyl^If6kDj8rYvBRNMsi=M2HxCl2ao$X>6r{24OWkp|}s_^FX7=O~Bz
zGb=9d5Mnny&z8uAJ^|D@!o*E@GtQuwy4)R~w>Q-d=sqPnpYWR;;oT;1JXgX8BOvmM
z>dDda@0bB#c+QZEIvN&%%<}Z-objH>182rTiyKa%GvuMJK+rQ}f`gXh5bO5&s3Q~9
zQEKxmsl~!lPNKZjaGaeXFEyD+4wIJ8im*LGoy`ivy%Lma&g7;>eycOuJ3i>SAvbl*
zEU{JSxgiT2D4dT3rTV~_4DNDB9+SNdr{yv2Mg%$^r7xd|g?<i^Vl#IBoi(7~Otvx{
zwO7KPLC2Xmd?x(8#{#A7nRXutc#hF04IlC`+1G)D=Er1U1D114Ms^}|jxwB2;Bt;I
zW)m2kW1F9MKyZ%9qAmc=6|f<k0F@Vg0)le@F?&knRf|mp1|^F+pcjn>HDddZ@}NI6
zlj9vB$tKe09g|l&pb1T0X<%}W$(}yQ-Fl1`b%At_QlU@We;k0#CN4;B8BOCB<x2Q1
z##PG|q3v_4$mGUV&0)s$33$#incRiWc~ZomY}8@H9pjOOjVq;N+T5qKr722%g1YO9
z*c8;I!N|s4)lrJ{c}A5mCAif-CdW3gH^=1IMi$Cra%>}0<uUlR3!ZaKSyw0EIfwAH
z32@Faxwe7LIo8zl#CXbq_LOMjM|?~TNZ$#7XHJ)uUD%l;7}`7lJe@9&H;^-@)9lXs
z(4*|;6E~)(%cjPy>Xp#pjl0(?;&Y+dIz8T}w(1pd+|X=DaQ>92#vtSTly2*CdV|yN
zbeiIz{X0s5{>;3kK8ZG)g?Ty5WIlm-IbHTM052a2N;$Dz_VU7g{ONRYFI?Im0l^k-
z_D`n;y^?_Omf>4jNUQr1;m<XT^l)EEO(IS1)u8D*x9(~c33d8Z!|;XniBk1`=&4om
zYP6JGrY2tvP|qXW)@lO{8Y`57>!uDs!F5vypyayz)C+Kv!`$R4seaKeUhSjgdRN0x
za=o)*AYV@JY8q;<cQp<Fr}CAr!oVD1z80`8&*_a%hI6wwJva}5N@%`->Nx^;t+ulS
z%X<MUblOq>p$gk!E6{}Ps1+zeptzn@S-Wppt<<-o9rYf{upLbs4tp)sG*Z_cLAX{z
zUT%3${v=mkE3<e3?s8hFX(-1gFZBZ0<+M=Sr5zj3(hFFZ(_AeF2I-`8Ug-N#YV(Eh
z9pSxJ&dF(8kAdoIG=rZ7gxnP^{G@tJJ9q(UcZls;fVDKbtyc&9_cZ#g7lAE}ZtE+_
zx8LZtUf={ett{%*>-RtsFM?m%V!P#(xdJxab9_^+;smHP=Fb9h@dy~Uh)`)mU4s^D
zbXl*@PCjj@2DMlt)ccBRVGec<DoaVpSA89hP+N<*mS*|{64=sAZOxioQ%g`<&Dhe!
z)I!TXDXJkEeo({dYI$XegTraAb+v&@{3A5iB7lV{%2QI)uMJ%Yme#)1spZvZrY^Ai
zd_-CDA90R)RaRvvJ^2FOIfT1f9np?g#8yk0T?yMwWp)MlEP`V`@YLFAae`=*1*l9A
znzewGxdOI)H+7s)v*jVf*MTUQ5HxE6;u6QzuY+#Td|uYj6`Idil3#{6^iW?>^#va4
zmBvXNn$x$ubK+=EFIY4|j=~aEf9arJFpc7DHJ;W}oTa8~Nko}AcWD6~6KARQj&Vv!
z0~`|qY%Qx28#cbg$q^YwAPrn*XG-c9qq;WL*MY8yzIq`TBLu`+$PjTQ_{boI#Ff-@
zXa1Z0M7p0VVrM7T;84q@AVW~C1)D#Pso@;i6UWr>#LG7{yzuHxjV~-hQ`-w~-WXN0
zkh3FBSK}Mort3i)U4}8d@+|f#gRtdEN%f|we~$h%^v}^7TD}WVmpF}&P5yy6^inTC
zT_TP;S1K#wXl6>Sg|e2f%DeKU2;UYQb+3et*T#!DY`k{n6|nW(yb;R&v=E;a%5A=o
zOeTZ~yOQdm)GZ({SHkbZ$RS?|ItahPm7s(0D_lu+5HvkO{MM7ATzujAgZpdxtryb$
zM9^=&kP;|jtJSODqBwyc2x`K4ZoZQ0{LWJ8govePtVXib3ZjQXNzE5fGZEU+h=7cc
z%?waX2!*wZf#->s>dQc1=#yUXQGFyRWnW}O!^IWBfQkh-Sj12>6Vp1>xrtdFYPg=t
zM#1JBnZtYmNfSbBEg)$kXpRF&6Cr!Na5ND{blU=SCY1Vo0Xh?caV@wPBV=4x4zQHy
zL7qi+9ZFCjtt+Yic0Jb7-=-0Ov@(L`_b440vcBPojgY#Aw>Cod_kbD<5o-RsAOGgL
zi?)5Letzb*K6O7zt9i`vISc*UfBoY>|L8y3=fC>j|M1r*xHsC5zy1JCdgv0qBjrV8
z#>@`?PAC$#&pLO6DP3A$wI@PJ7`odJ7k;_do_jNW-#o^ZDi{pF9kJQI-ehRVt|7;<
zfwtjG-XYNWc)uMt(7^2@#svc`cx&$r95a#wkaT;D?|Di22BWhJM?hi<a2hD+$Qk@0
zN8Sj=)^_>PaiGnR1>v7JA-KdVrD^PPV*uWvl(-W)gOAcVPDe_eFZTlU_w@a%6Hfc0
zUu%aSt)96)TVj4z%^b%*r~l6qZT;;2?cynN{x9o?-tTw)(9V3<kkZ9ZY_G@=$9Mhk
zrlHmk&3mn%^WUtW;$wc7&zn&3%krrO^=0|gY-#!E5Q+8j6kT<_P%RjNtltGA8s#qw
zhJl@Hk+|Sx`_OuMgUG+G7r4FN^&)>@-$0-Wl!f&&f4NrP3u~;Ecb$Ck;6Gp2iT`q;
zytWM&3YT^*md|PKvsylDr0@HU`TS$e-hKa}#R3w_5EElS2Ya2!1Nzr_AdmVnK6ZgG
z4+$9Y*}mmkHc^h0D?okdSLZ4~YJ@AOMF6_a5FI1vJi~bk2jyot58+|x<*xAOkJ<|7
z@f&I_oMt?<UWk4XiZPsr?*RY6m7vK~)whfm2gX$=Z$P3$-&3Hb!-*FIvO1hc?}T25
z^W+Wg`*0q-qyCytUl@T>!XdZ9l^A}J-J=-~*m;PA5y<oa1!I7A>XvH-B3D2-j^oK=
z8_t`ofL?Z5@SwvDm$Ms`xgpxcaJ*_NvifL*^JETFFdRFyjKwDfXts2+_!hDBub{Sh
z1o}m%H4N8};QDyV_6_F|9M*B@s}2J?NT-MZid!zd$pDLw<WoBBGfW=8k?P_K>Z^!g
zjVq|;PJLZM^oezNcuLanlT$yr1)MK8@4o6h5}UR+0#j1ZGDZ!Q)v@WAMrx4Q*peqr
zv|B`jWyHnik@|o#J(33z$G8v+BC-_3#)k<>3S#px4W$r(kvu8M?YL=UpP2=;H__u=
zh3YL8(ZNx1FBr5q;9ddRn>8Ss+6TwNO~f{i&9QkIRT}Y0m5685zJ7Hi^4G-1hC(b=
zh~x0!gt%vpu#SfUWWx0j#AE(|dm_YJh(NIrZQ+4;G?KM2Bh5nKOoXC^u$hQfdyT?_
zLm}A;uPQ>9$$fI777xws6L^zWg?f$LNhk0c#b;dJo|4q8;V8K2=SI$@*i^(w%M>Ii
z{AkSjx(lUwCDjY=unq@VBuev^vLE6cyprt4A~SivO^9x=w{mla5SkrMxDY_IBa>AK
zq}dzbFR^H=^@_}l6>1qrLlPHucnm{0&0bE$APHDWa)65}vm-fJ2$|Utym}=I<!o7D
zO1(kB2zL3gT59$QyS##2Qj2QvO7bHP;=x<KlP}uAE7+(~y09ZbS_pI5+wF+#LL^vA
zNqy&g!{Ki&w1Tsr;FVY6^%S-OeYDm)Kxm{z4cOsjk2O^dDn;ajy_E_P&tPwe@CyMb
zdxLuu_{m<$2yPMfFp?1jc?Uag5@IQ%OK&*XEmQa4;1qna=dDEuK-qDx5dabY<w;SE
zz}VEm3Nj6;bkyo<2uf;oHFTgDMO1ig`g$)^d>xlU*UHC(k`y4sH`u`&5K9=3j@*eM
zw!vQ<7I1ukRwCH4SDHp0C!Um4m$j)oyq?KN*!!ot5S1ObZ!xuDc|{jfI~MnNA=1H)
zyS`AB`&MUYbWm(F-qF>;BBr)$<roN25MDv<2s8oBB@AZo^T}duxn8;_p_CmA86hgb
z4jPRh5n#_0r7@L${0j0F2qbwW`3A)A*FOio5Vc>&b#Rc`ulLQlS{l{HTrCZ2W3HCw
zvs9Mo|2h)BJ~1bs40ok?{jOwXx&96fBW}K4m*`OpvkxS>5~j9eho+fBPpKK_S*jyf
zKp-L|7Zg;@9GaCncgNI*><8V|hP;4+EVF6k)4rkwK~1))ZMZHck6GOsMyVZY<;!HU
z?~>FQ3SQBXkT}Ha*R5x%HVkqe$0YxEx6Yo?56}VUxDxCWKt8SnTM@XBnB0oRS`@SC
z!(~uEgC6A${-YR2t>XYSXt{PUDaAO1PIMbtWXsTDWCgr}RAJ+2nsAI72c^=lLp!t(
zI9I?{p~1)q*a7s3!LZ?u#MmE6b?Vl4O%RmRaCH+0qv3LOKwAyhBNuz-C}yv=x(Q`9
zw)zQOHE8p`4ivHeTv7FXfAO-^gV`_+QLonpIm%;Tb3YwCV==V34aX?JCOe>Ix6HK$
z@8;0nHhMP)6>cvaTa2l;p#=xGKlsu@(8>-{wJRyZ3&d+NrrJ&&IHa<{-xg!4VVuZ_
zt^Dk6!>MZwRl~VU(8)epx;U|7!TcXXdz*}RF|fCj_5YU8vjJ^4sCox<oq(2CQj`7e
z>;Yvrq<jlg8KbLZD7%5p4`gP%-kd9{;qVJEaKSgEuE#A&RfDiFhCT;_SAK$D_98=!
z!Oag?X^f_amU=Vo^nue`&F=$IcGskj!SQ${*hZj%yb?4uv%qF}>1Uw<;2<a1W(V73
zn6~@CQO-gw<I>MUEkmgqKM7dDVfrLsnTN5IOVV`r)N`j?0o#SrHGMch;CUr%cUKA1
zwmCq3HL$He5|r+%u&pQJ1So`NA2<S<Zj?J*pJDnW0I2<upmZO)G=(?@+R{+qR}Itm
z0Ys@Gz-9-VYM7LNePF|u+N}xy%=|*J-po|fbu~z=W>0YZbxPO2t6Q=I#$mSr=<21R
z!g&7eP-0;`0Cy<5ko)&aY9T6U>5A%286VuU@LqkS1~9sBJ7N{WOfC031qor<!Q&g&
z`An$Q@_o<Jsm7D>6;#)CG`^zhJ5kwJQhn!F;7Y3N{0PjE1rC33jdc{O-!j(`L=r~k
zkd8o;D`BgpQeXPO4&yA0UkO}}gt!BH(fUU+2X@5Kgus|rQZ6rX0`|GG#0iDk6&qlO
znHe3wu5R|%5-;mDMEloa;D(t0It<_|VLMQ=y|(^SqTDY%@PqqM8S4`Ymdt=xke_@J
z171mf>Z7|F#s#9d0y~KQBY~P76yhOPz&=yyU0CLmg=%zt`E#{Olf6R6LJ-U=$Q30j
zzCL-x6BS<vQG1AquY=b=I(H>l{X;m+4qE>w1jM|enlmZw46KVTrHvzF5RTb#s*FAu
zQq?PbFTlyy^MTxx3kSL`?YyARK%jTaWsrz2uj3pYLSA;9wL|F34u<~d(#CaWf3Ad0
zLB(~bV<Z@eE?ay-zX^PKCAl@b7`FTRXt*wYyr8_mtJe|q8A4w6iVKa-ZMML(7$nF`
zQT7DD%8skl5IbH6wSJHsudkg2bqa?+@#1yF&xSCS9YMAsRAomXZZzSbdpV7wNzcNs
z6peZozNct}L3iZBh$iBXj*J;0TxCxW)|YESB;5#6?OjQ})#hx8=oP^%ujnqWwlz$E
zSH!E=%Lf-?(Ccv1MH9HA!<82VT6SF4hLDz5QX|+X-DgVSE*==gpLa#MOxse!I5LV*
zuWuX~MW=TqxlEfhE&|s-5|nCbNa1eizDB@EhgUV4;u`y|D%jXy)Q>jREYK}t+PjkK
zKDYM9eVh36I->idNi)OC98H=Tj_7EFfb@+h_#lH`-y;k75W&$M;?C>vg-4TS-q3JO
zX}3CVfJ0<@SCTJYAB7DKM<Trrn*C^<Y*D@Z_|du=2T-QztFZ6i>8Hl!LFih(Z{$vh
zhEKpQ6($b6jynrK@>K6qVSZ$P?^0oY4*8Ed*eo1Gcs=PZTr_wcgcvRsypFpVKk`&>
ze?CQh6n5z=2MOLS=Qa9~3%YKD{DhwA=zQp7Q;Am-CBh$73x2dwGwat!ur<K?mN}v^
zo)WE`1$d#09mU08*Fm6iCACdKv+rWC>r7DVhj+3a)GU5@C)+bonjhZDcH~mK5<a#D
zBuMlX)rc0GE=}iWsp(!rlwaEGFy{bPb_W8*MT6IoFW5zK*ONZqg{$ni6?Ne%JIM3B
zF4P`~s&~R!-~tvug2d{{Y<u7hlsEfHNxcAV=;9H&5|nB^@w%z|%n}<#h=U(fBNHo3
zdl%URUF>-sv`VgAx4o#Bo)o>+Hmb323%#ko@6W$v0)qg`&+D;9YQ+>a{;2xa)b7Um
z*R4|}a&%nTJ|(F|m{u^*2OdXF*Dmlt;6w+6!9y2Mo@h=Nq23kbD-9XOAkFg7)&;G-
z3pmmpY2BQeaC@OMTzq<0keyYI+wKP)4n6pw!{WH_faf@Q^{!xLks~Nu#YL*uk(%9u
zfQ_dkfxCyk3rO<rqSfn_1KvX>GJqydn!V0c@-Cje4y=hIXKn}B#6w>SAoyG~dmZF#
z9-_$Z$=&A4nA<_`=1Q5{K>_E;nA<D;tBXUg2OyoURJa|e6OXCq8oDe07;q;J8oeGP
z|BVp44&;f8LazgQ;-L#IU{74&w+`T@$LmxFExs$^ZpY6(V2<N~9&)P3tTFPAD{`sA
z90#Jrl^VALQQ~3xeXT)R-oTW2D8Eeys>DOz0K6y<or3W)ojGxPzHJwQ-qV5K^^o-q
zjPI4OanI6=KC4Ni@g4AYddL-4Yu+<4ZpXfHaqM;EkA4wsS5k<!0_^m{jyQl&9lPAc
zo!9XpaB}DM`c$~6^LnM%{&b7nc|SVvh3>MTk*M2+nYxndn{4QWn7b>#Wd{n~$*|Xf
zRCh7#bs$UJWmE%R;sD7#CCWj{)qSAs$i;UB`7T_#`DCg7Ri9HA5nl&5-^Ih%6Ta_a
z;p+hSyIA--f&g4#sg6Ja7Yknp>#Nttq;#E&gs(##x=8ps)vAkxuS2c6OK$_I;w}sN
z%q+3h`qxMDpqQIPJbfK-6?bWD;8k2aeZ2rH4*rU#B)OHu+}B}#xS0DoIOyG_q)$zu
zgR1YN=+Dj)p8;hl621=5ii?D=BjClw!q+P(=1CDIw{)dQ_&U%nE)u>Dc#DgKufu5c
zBI0`>s-@7?y5~}8YTL0CXoiEU-bK~-^izLl!_c1M>ARBboGAA?%wz}UUQa{&aS`fu
zz*by@dL0J4lTYsoasi4^&l+^zMk;!1rSe3mXF#_2rjj-wTU>m4RtF9zo!*m@>OVgS
z2KH~?1r9MBS$w-%N{zP#q;2>l`*t-1l_v&1Lxh~~t!hwcqR+E762l9<V>l6hfraDL
z=pf275VQM!f#d^|3k&-(gbBXjU~tX5sPn8reeH!(&MbHL6_k2b`dULYqAPo?;o$7T
zbQuoUPEeP%dMZNe42N^iq_u{_yDM+40qEi);xj;9T);1Dg;R4OzYJIxClQ|k>EeQZ
zT}i#+fl{p-;|+$v?cpNcv*uO85^?n0^hihV4W-)DBH6P-!MMO&1{917&1HbWxN_AR
zP%w`xRjmOA^O2x*AKEl!fwzwxZSYfhr4f7}s@LDt@WF7J8a^0KQ@hZ=ThY$ep*aQf
zGPvhlAbm>*o(tn;z`!^`UQdd$i$r-D052}`JuAeE3({o(yj%$z>d-e!o4rGqilpyK
z^1Uu+Q}tzb<*GF}NNl}hlx0n`HCi^iY}>Z&F59+^F59+k+paF#wr%uR{XFk`?iu6U
z^&@s>WMoES?LF3>v2rFJIO{|&#`SL%%Tp!iqH>l4Mtl9CYT^<%3Ynzu0Rnko^wP5R
z1LuVDHUwV(47t;^{Rsgd?CXQ^F-2RL;>Wy|^292>ugy;fY~I;}VOc{?=2lKo%4c_u
zK@O+2YEiXM+}7Ih-ruHWSBJ&5E2(JdJI3y-4;C8<jbXyy`=UULE(H;ZG?#Q}vDB>u
zr6edu2z>!eZmI=AH-Ivdq_@3;IS6{gsFl?EV^(LZi~9420^m+$g2psJhJ9W?Ol?|C
zk{!9ym4?*H1l{=p?kV{q)*>mm$uJtM1JjP27CU3bI~iK!1r(`;vT2om;MzWzjOsEG
zyl@3b6S;u>o_`RA9g~itrZ0L<p3jXL*+dE;!v1egOMt=F_$f>PhUhslI$3RctSkDO
zP$c>pN8Bo!G9#~c%%C}`i&Tt$4Xqu9fz1kNOcM?SYgMhS_FVnockP@(Nlkrqtx`JR
z<RQ>^#@g17_->85RxZVEUW&0vF{9Mo?DZg+j`;MtGC)C7iv4rLqwnW)_NF+#>E6PF
zz3B#^GWJ}9<eeXAmsx;XdxCBly(DnHDXU|@_Jtt7T+mv_VK^qWxZPBhHqX*ku`d!g
z7Aa-&r>kA!-Us~vm<lzW2zp^+QP7mLVa-a)vXWC#atLGC@CC6Yv|-&4(O|Pt3J1dg
znD}M1PH3^jIrjtD<iRN2z=t+zT$K!*P#a-xwUcWx@!BI8`E9*sF0FizTO9^45h!T)
zxPWs<Lay>F`6;U>YQbW|k-$uROIzpqG4UyRozRSXOIuHFttO}$v=GIZjsjSA(z`)&
zVaf6F>N5mru7%zmzW+(M)mN^ZYDv3+0d-K7IfqZw&{A>>d8pwrb^{9B=E3sv{<aWD
zLsCEL^~UHmrQJwTj?t>66Dsi*e>JG&)lr77&4fNO23UCYtscT||EUu^(INZRIU>sA
zH@Txm`qfD_W}EPGUtPF0^0Nbw%6T-Cb|nnn`~VO|ES^WmtO%OI1enrhr6VeL9|XTa
z>y=mfd*^B734I3pHYCoImVA^zI2K3}Z((c1?A*|lDSnqzUSH%ysw{KrZo-aW00u7>
zFQ?>lnnLT#)r-`W=?iPyj6RrBL`3d1fTcaqaAhn_OXQ0OaN|%y-L$WTJ>nC_Pa4``
zUf}W}P`rjP075jM3Eu<fgstqKzxsVv2h-#ly;WKhM?}_LNmhCMda4WCM-`k!JAA4s
zm7Nj+%l8aUm`+5|R>pnPUG%$P08r&BQv|x&ttWr?>%B+-{OXLToeoD`1_fubJ8h@v
zX!NsN9-20#N7EXm2@u%bTWbI+;98;2jz5S;THcDPoRkrKSwdNWjswbJAMvxiPIio4
zyWgR7NdN+0+8Sy!U0u#o$+L+v0s-ro6lpT;{oqP{vS}M;Td+CRAYy%B=+)^Sgam%R
zlahdqMOy${i9q6T0p$?Xk;g(W(cWRuWQT&{Ht`*9oiS|o#b_gB)!|$<66jrXA)J7D
zcvS5j_Jmbz1Oxl>U`s=Qps}|s2Tg)*=AmMb#G)(08_*wqmp9Fo>7WJyFwlzh0^^T#
zMTfBDRo4@<L%!ft4e;ISkX>?DxTie_IPUt6rTG%&xn||7n$J}WJ@}KNpygD>C|s~Z
z(plkL2U=t9(96#8P~}EESJerUxs+MrYgY%7O5FD8Lgqk|NVxC<^L?Pyn$E;~j}fc?
zOwcwxK~e7?frJCSeh4Ipp6Eb!;Uu_1IKM7y;*@KJ25*oBZvxEPlc+cC@ctrsUbM-i
zeXZHiYy069v>Vv=<H9e>P`$))?RVO}TMDqH&=`qsj`hZzv*P?uJMA|Yp+4sXJhPHy
zB;9SAW&biUes|}xHK+qu#@kge=+p?~Y5un>?JLUI?toaJ!0WA3|8Hzsb)U`hxKD=I
zYfK_Gfz}m8!C4D(J;)_M?5rBpSE19<QlpJPd&3J%t|%d6dS}AP{$8Eqn>x16`GkA+
zezm&90N$FsHAM(8uRfL=;V>7|TL(Y>8Px()67IVaU0p=Rb)DqEp3J+ePyx$Z3xqZz
z|3s*aIb$tS#`l)vdB`BrWS#)<O@VsTn|99x9#|bW+utQN5E(9UXBa>g+Jzp?=hs$X
zm@t7J&F)%OjO}d5=n{`GXz;WOJit35l^#bwWnt}+MX99{*do{yNoB%1P|zZ>cfW?#
zV?9Aqm}OCUDm1Ze>!a=G_wyH-Ho&wYN2{t!IZHp!*x|!fr=eyEHF${fgBm?VDFJNn
zyb)*Sj0BKo2rYPkb44yZf;$>Vur7_i$w8YRK`R%aK|DLy)W^rtck(xx#7vNF>mzY=
zBpI$TLeV?NFhGmJ<o0;RJI3(d$+z=&zZ@dGrtL=BVx$c>{B7*7F>EBC<sF>wvqV@m
zukd*5AJ%#EW|KtP<UUS6WqcG`N}nrtXf-!HgQa%7jWm{x9USg&#)|f`y<0uIzNRq!
zvd3g;4}K@*D)Fp45c{bZC4^2xt=10>em}HWG2CLr(!5)-!0df`A7BnNeWD`ekTe=c
zgiZrkuj21X2~2*(gM}xHFvI+Kp%NIFrRT-i9zt!B7%&}@ye|ZS1#Y-IWGjMcDSd;%
zPlgpvBk?!JBM^f@NcJ}J1P-YaIW`@2YK^(DwX3)w^z@O8uTa550pMjF{ebb()(rGf
zNz~DF@<AOY_`MSCM{t$_6!`nQ1K+nqlKUc5+?~3PL&cD=?SX1U7!61Z=E;0BW4(?<
zmuOp!p>bFhb>~oVH_f+jQJr#CtiTUl`910(vgn<iWoYP-p&@zMBC=^J!j$sEhnU~E
zWvI<`RHc1C*U6O2i4tsJ49<N7Xf@JxhDYU_>Z!`&<rXg40ZxbuYr|Vr@DHFvw+-Th
z`U3pQnZQWXC!p`D#E>bdPg~bqS?dm+rjwV-O-f=eY_4vzLj|VJ?}nioQ#VJ7G7exh
zy9k|W0P>BzE~o{4UWj=INe-Xykj!(Vyqwr`t9(qJE07k}(mh;T8=&1P;bj9ztCjo{
z1^{h_yFw1~V(iHqSf+7A(KOUty~v!YZ=+S*!|I>ywZ)5#WUR$kpKvZ|`1Vzoq+b@{
z!m)b3z9xaGzCVZ)VIacYyrV0YG~S6%-w%&0+l#Kw+echh*Pk3#$CV2ku@Ox$$Y~rc
zZ45Y49hR2sjHEfw&zoj4tLL`3RPz&tDSgRj#QM{r7)!h!o#~B^RbubqFvk(|%Kc^9
z?$2|Zq(QVU@tdSUwRz&P3l-r$qf5ao6*uoEiPXSprQhz(d!xq=+k{!XwtW-}gt)wG
z)5!>1p45suU2Xt@mbBIe#3ply)F%>kh5NL*5L{?imP%f!8kYj*7*kws08ZPCG=WEt
zJwEaQ)l>YXA039cQl_>9qSA6}oe>O+Gu@r-CXUxQtpE`}L)F}K!`g?3lTE`1O;*HZ
z+8*0sbfQbp%~cLkDEM^1uErCI=sEziE1q6m0%VyFr^fk1(u_*g>-CFY%w2%F|0;sh
zq!v&IqMd#hr06em?#_){=yHiDGIbiITGkq@)GNw%RpJUsw>>g)=cV4AI}<M+8&#vf
z&@U(cp#>%|30E}{2~QhOgx;Y*(*cv6n80}imGCA{@b{gDfv|k0h*Rn4Bl*<QPTG^7
zPlTtFnm79$lG5jv?zCrITUBgk2KIhVLQ&*f=&)z}sAF1P>_Mh6r!*-nh3RdMPEO~z
z`Mdchh`p!^W|qizfUj2PXbz)wcW7Q3URMP^zqr#2V@p~F%)JTgg>rZ`ZXurKo5?i)
z!j$8!o{Mpa7qB}#$)xt?c!NER9vgU~O<7*x;-GuWuHBB999;|n3H4q%Ka&A!&tfdx
z-1R2I4<+FT4Dw6zuP}>ZBY~>96O7FILI_;|F$Ri$Ujd~+<im{p_$<^S7))Y=&UdFl
zs$S%}hyHBj-IJ-_6bX!BD0C(Y!P8H0<SCsqtDCF{6msUvC13#H5K@uKo?`j%mG;2P
z#9mT9LaCvaZl0-i1!34q%+3m<5~PJsr}&aN4^TT0yNEY0>yoV`Y^7K<!jwgQ!>}83
za1<>}u>h#wEG7kb6KexHv5UE*GPzCeU*stncFGC)>6C{R#l)4|bP|gF?POdYCJuG5
zLIciqYk9%fl3Und8O|LJ)+$#@rUld5Q5)z+nt(wtVrvuw8-s1GZ>7ekeX`8SxEDfQ
z=`5{{au^v{RxsAI=ifvLoK^D_=9eqgKNbU53whD2A$16KxYXi}C4Wu=Ym$oKGh@6k
zQeYwE{>eZ-yO<;`;`CJX`+`9uqr-@z8Mu@TFBKN6*;eRkSia^&VA47$4CF+A|44=#
zCY^_9=oGVX?UL7*U&Ov>scdB>(OcDVH1NCB!{6>Cem^Y*%tEbV8lce%uU+Zg_X_{H
zM4t3ee<i+??NXKl*4^I_auyKoc!xR4NwMdz>Xd~n9~721x(oo;Ei1Vqk3?iYSyDl&
zSw*9+n^Xt{4ZLe#8L_^IY(Ew-|CT5aFf@EKG5p)oJ3O}1W#_UtiICYy+;1{@RG%3;
z{Cmq(?P_eFA<Ov-q$PZ_5x)9>x-A5Za4vG4i&`5=$7=)jR0L_B->IXpxPkBu<#6SV
z%dNq}&Ka)=`LYH{9V14cvK&w}1SeL!yYq{rCA2As3il6jiL&*aaQgRTFI+S}2oZTe
zp!0?}CZO{(ag#BPUy-HhB{OKk=om7ONNSJSy^+1;;GiY|OUD9!eE~kdYv~7WXQT>o
zvJoXymSCxfwe#UJ5G75;-37~7Jw%zko1MYvv+B1eLW`M{@Ma%YH!)_FV&Enqil?Ke
zO-SlwF#(;EK~3?IivXn5gSVvtslbn)N#=c~A?iGg_3&Q{Lpgt#Jeu`Ve;Uitz>B74
zF|J0^bLlr={B)5;iHs;ok!HpC2rdc@0_Rj^O+z%g-ReEbp(eQiG`PS%12(A4Mo-0y
z%&H#`A9GBy;#W{KjR(>fxss5mvd{tGx&$X>2zMeflyxKdv)!p09*&@Cn!-4^q~35y
zsSf)@G3aVgp_R^+>-^L*XXzmK+Q>-ODr*gsxx<+u`JK9e?#yi>^k~3uOj&=r`%wL1
z!T*u9hRlxWMtRY~f$wIa3Q#W>Ub_%*nLtSWI3yth8L34k8}l=0@HFqT6O9u7aw993
zJG-g_DG8hnO!g;k9@vjWG5j=G3{CbUkb^!cOh>}I8I%67QK1Y-GW-&uNCk7{A5yhQ
zvET_T4#NsUXkb$_to^Fi77D{_kgGzXzDSlKH``%NLRc^9ECDS{M<7cCg|7bRsp5hK
z1SFu9z|Txay^9Rl>Ga9q)84RyImmfmfU1BL0YG|LB@mV~_<L{~zyYXN2+eo_9P^dY
z_}oSeF#fe03v2kfaDJ}{xqEeeagmY=1pbFR5>>GNhxi@?BvVO*6A1#f*f=6s%6qSu
zh<W23jm*yODRA_HkIa2wfX;d-=z;SD=lE&7s*-A~yG{^k;JZp+X4VK4A*`>4c09)o
z09b({%TB`?Nyz$u0pR<{b-D=9T*koh@)8qtt&+0x$8wS~%OAK2-dCEKGvtpnuqu<D
zXj%cxiG&mNepo4qd7}B1wu`B0M(*(bm2|KtK&w>77rRlmm24njyz=4nz5v73uUrV1
z6vo)cAco70xB!McVzmPFOBsPg2KVey;CZT7=GI$D!p3g%NrXyZI&(>kkrZ~3jP20S
z7TDmu7wT>wgTMMbTNGodom<)E<WJe-`du@GjXJq%CAev&JMo2V$7OQ{4c*Il^3QDa
z--+jN9WFs7Cdqk}YSn*MxI(dpHQotYCfuA{%Kt6{1at?&eH`8qpNUBiO$a@O$CVQ-
z=AK(CG>=$@V1*Vsj9DUOXv`+kBIyr|kKzr>yOXd?Krc6iX7wu|Rpk&<l3~qzA~w6r
z^OrFw=AK>SP7QN~Dnk-bq(gy;F<1OPbnLmALQfmIs-gr6&1jLESEW{>VaaGiF14BT
zXLh5NjA|__WQ&8DWr7`5Of#$b+8s`S%ttQD$SNry`{(K!@yqXmDjA?!tu;)z8bxM1
zS#G~xR%H&v6|-eJpxTW!jiD*_AB8Se{iOF^EW{PpX!467D-op@z+-cR&KGqM^`uTZ
z+;FUU_xZCH)%oU)>AK>kvy4+{ek)F^^$>#|X?k=STnRc_a+)C83Etfh?Q--4sm~Po
z;k{btoGRMG%}Ih&E~lm5h{>>Q6=MD-EcKh#Nm-Wl754DX!fAy9mQclwW+|AkC+DNN
z(bOj*AgnsUYlJ|qX)_T==BA}!nxK8!t|So%-{>cuf!#9TW`5tA(9s`4Fjw_OX!L)z
z+ZUxl=1VQn#%NL7a04EQi5)QKK?*Ct!s~D@3&ySHGKk3&?a?&yC@|=k{+A-?mwOVc
zd$aZ_MO|i#F6wI$Gi&<h*Bw7*+yZVg7)xQH6vJ%3U})kPy3OBRF!nnj>L>(1GeS4?
zqipx=Qy8Lw_mQ2yAlB<?4YA=2bto_nI#lcL5aPHX<HZ7l*<}h~YcJbbHyeE(cY0Z)
zwyVoJA;&%$*4YHw=B>7a#<YXqNl9J(-iu$?A6>RtFSn~L7i8XB&M{F`5hx6xv$l&W
zf(D<ft$V?GpCwTU=Z7k-f$Bdd)^NGu&y<<$RAh~;kxV*#z2~(qIaPscjwLb1NuP@8
z)C2fRUD(n#?J$!FpF{<&mFqM3upWsjAv2Cgs^URbo0S>)n@=CCka!LSmsn>N`!=lp
z2vGB{3r{yUUatiH?BuSM0kD<=&I0&d0^SUm<Lo!&KLeFj>c^K%Sc(AflSjTb_jB#0
zaHdyU3X&N@qtUBSPas022AP_1dParZ4Qrh~B!FyK#tsK$_DCTPe@*K>g&f~{j{(H5
z@l{hk<2AQHx%{C6M)pjHG3XbJV8s^WHy;S9D0p7em|r$%ZBrN$V&KxSJC5*jaoV@I
z&))sbtWgp0NN%<m00u2+xv#H<psl&QMQx|E!Rg~SO{piQbb?%W;3s+m^;wTk$c9Mh
zAG*Q*9N=5I437$OuoOE%(sdfo6FMxDav{KMqk->lw$aEB0_HwOFYY@mb1sAswH{>z
zyQg^$e4?QGyA-hRWvQ7DdKL=;I-6s=T~2O0Ma=G-A*Z#eE2LxM$8HC3rfn6PfL(Ws
zi|Myyi)XpCxx5PKop6Qs*-k1C|3GEj=C;1i81<UJdHzT8<zwPK3pyOGMr6yq$S8G_
zQISz^D?%|hI+ec-C!h_5I@{eSDs`arm_Pk)soG}tv|T&%akWCdx=lv3Xk#Wp-j<aK
z8*GtM+;`cnp6vbpwO;B!X7hV-q2R~w)`mi#=CDZsiyjKTvil^3<ICf*-Mg`-+;Vpz
zO=<N34t=ccw@sgM4LM@Yy{_&T%gUmtEZGjU;>ozl@TInG@<EDyCGU?wbWS=M3zh9D
zLS}e93i?14kV}6P8`SB^^CYO>l75k~eCaL&wBCJB1_EtR6&CmNzlv4Vq6=3(*$p&|
z7X^``UEu}dFWWx8Zh@+D$E#B|(|0-14h-N$sapgIqzLuBy}Ar`2!GUo>k^tK#J1D{
ziJ8ZNHVmXa#2GgQxpW!9#Hv$MKI~N*z{GiV>W^S`M$Ra2_I(pqvlj9cFL@%A!2zVA
zA$o=4$+o*G(D_kF-Go^V?q_OPnjPI7S>lcpwM&rQ6U+GUv;UUyMtp^L;22%}@FUD_
z(V(b<)TcrnbGN+U$RV&IJN-sAu!2x50=rDHw9MI=9;fd$nnos&of8gR1hF_ATr{X`
z&+jPp4CjS67#VYPz-vU5CZB3t`q1s|YUNs_v4y(`=X$!!C4~UIJ-Vev%pbIn#;dQ`
zAFW$YU_d$l&7Y0Sz|=phhe6Wju`l?IyW-hn6wAJ1FFjfSt!?WJ<O-s;+84>0ctWY+
z%OfHa#**OV&yw!apaef#DwY_~re5OUmXRkryCQ)_W&k6~U92au=_rNI9pXW3z^{#S
z5_2=Z+z#mq1m!8j9ijt*Wq~Lt`88T_Cdz}~OA(+bnxjxZltPb=@CAl&FTg7XVrCQ}
zz(FZ@elI2baZ;!(uDunX+1;G!ARKppR#m9o!1<I?x{7`>vvCn~1Q^3{L)XmJss<D6
zw!zUV!{?i_7e}}=IA>3Q;ANnccVWYEWgnFx*vl9g6YNc^N<j;r*$1r&NTL!^GRd=K
zd42Qu=zQahpQ|amO3I?T%G}Q-<Ii%u$rha80KcXX&UBo~_K!iUMm8n_oy%ng)xl+d
zktSfxe12Q^|KY(9PLjxT#m*?RXbBaZO~CFi8058sD{<ED1b78Of<ip({tCxoj?cXj
zG57;@090b<;+z@bp_r)O0p669fHq6h7|_A*3fXA34e`gJ?6Q3|hQTby6t5v<)wvh5
zaGql;Z@Zuu2VD-GK=X!#YC^IF5P7w*si*!X;fYQ(@V1)2Ht<T^=Mg&@T-<haA#;{^
z)+5gW+q1X>3&Q;*q5zGsmt$;}U?&?JH%250xoov!=<|^tr^uv0Y^Go(TgX6x8si1d
z$X%#$jN>~(#-(_<bLJ|93L0TU8!YqBRH$jOxD6KYIEq27`vV40b4#5ToI1`Q9Q;B`
zOe0wmGnQ2W)5v>iI1<k032+&P0(KSv-9@h!0K9P%(Fdgt6<1NTMbiKyT?!|=e)~@p
zs3y#`C4$kGU9`1=)J@|8Mo>Ryu$haAdWpd#C<X}~2NNU9vgkL%f<ld=*LwkCCeGXG
z2MM|SGlBBsa3oxAHvD02XXF6RV4-N0btslJJ#&1iG+hVXVPET=Z!!h9tZ<l15;s03
z(-!iJIIi?+0FEaFbiye*oddoy6TX0W>?bz>Jsi#KU3+m`P2iSY$f8bzGfr~JH0c->
zLXD3Og|C@siY(Ix#roU*BJWH*iHmrr=eSQL8MLXGP9z0r(*r7y=at=Y?uVEcVSR%}
z!YhPdPi36tnCF$)dKEyLh$y1CzFz=kR=6>u{A~At-VtwJLrnBxbi%<tO_eUT;l|<e
z$4r)4v+-Ig4)@D~mz&%zB^Ot$c)C@Z;F(DeR(kxb(wNtGn$S!F;v5omv{MwswZus*
zK-izyg}x6L_zDXMM7~oy&qWGKH4uw`qa1EcsmMj2wn2+5K%kr0wPglVEFltsa&)7D
z<;;F`F!Lx1T<pC<BDfH*#|x1y4K@x>0)iZAkF9Jzv4UbQ)SGYs7orp<yU)i5%~#8c
zV*&8mOW+WfAlPn#>z5Cub|Ef0cZ0%AD?H<8sT;)pg+>_0!8kH=<Tg`FWIYj4i%J;9
z;a?PDW(db4RLKCYO%a@(#-3k4G83jemt=6#2xV1-KByj>B*@(`E}#-lkPE7ODqf3>
zs(1=f+wTvGZjk*-jz=x9mo{K(AL?>+V~MSomGv-++yqVu#{<rrKbL~f;~QR3rnEzN
zVxrSnfUr6-HU(2RiH$w=odl0{geYKuH9T3c+)CTCfJaq;0bn+92+eRICYmorm0m>e
z1ah5I7gAywX-B3FK(ka0)jO&gq8%i1tc~e^F2I731lJ1iM5gTodn6yFyeGsBVmId1
zR}8XjfzcJ;6|{^^=nq=CF~o%%1f$GkR#oL6L3I8ieP07zxeschZOjHx$tfR-@W!cb
zpuUOe2c6Bu!+}g57CuVwxjR6+y(I@%auQ@76{8a<Cgs#b@{%PVdF3&c0bM@GYRV4M
zTIFQ_X6a5deE*T3^*R`55$kf)1`Xxj;e3(M&*EAa12rVd7q770Xy<E(Y>?%C8`aN}
zCBO!C>;$$<UfaT1LDVV=xZDPpFCUt8<kp3dU-Sy1@>}&P&d7AkWLSsgfa+PiTt0Pg
z2n}laLfdz01pW#!sXM*f?GP)!<kepS(j~p-jVF;Vem05FEJpiRXxb4ytl%JX$ScBL
z5srk6L)$!0K7VsL#*Ss)8nmy3!hOmjlDTMR_DDo_EVveU8o4;-J!6$%w>1uO9{uEk
z0i-rXzZZZM`5>-iZJ_@FgIxH}R1?ZA&Y;PXYrjHP<=0VUlU*S3cqA8)MN`G1{*MGM
zP4JQvaW!)OIp!__Sg5v|N0!xRWqH6f^OR0hC3_Y(0W_P0<??K$74Q(efE02?UzXdx
z@1+-Xq7NAeM8NvKtG$ao{CtXu46$Q7iPM0l(qOhY4It0!JNjUt=8G{+SqKEv1|;M|
zF^|}ZpcI`9rVR_})%)GtF$jY>bWDTC5Qg=YcJPlP6$j0rD)15~$!i*;(d7u_THrLM
zJ<EPd4i%RMtA6JG5s2#*oL|Cf%t_qo#MP0C4y^*j3?DcWfravDml5!O;8FzZ5X!dc
z0x}jUx$OERK9eg-6gPpplZ`cWanH&M=3eHERuuwa6l<&_>T3^ST05yPVf&x~kub?V
z?woCs0PiC^m{~%6q5hW76UetfBXa__P0=GO1h!2&@Xf%TjB>29PPjt0^oD{;wM6BT
z`c!BbWbH0<ZX@4^pq|@FA-n(d5{PeVm)tyI#%3b2&>5wu+Q%h0NPObV$NqCC=}BCo
zrrxKw3*t4!NzP7?(}4S!N`Bz9)Yl6++k-6|nh%X<Pl1#LM(d3bbfN*btTO970rRXn
z3z~LQi=Z6~$p)k9q-Wx80nrxh9B2Z=*b|-GuA0&Zaf1Ho_r2dWI@DRSSdA_g^2!(o
zO^?7Jb(v%}DSv8v!R$x*lCdVUA0;^(!LJ6mVVTAm9HM-4(S#=KrYStga?T=){mAiQ
zGsZ07nqM&xROB|)F@Z%uRck6`Mb*tydh5dW!;&1nNd{3|E3C6lb1?NX%)9oY{IDJs
zT?(-Uewhs5tE8C6q=HqVNb<mNFM@+LL}j)!#lcj1HDiLbWIlPN2Vy^~_8Q^v@vdp5
zl%o0@MFCb5Og7CQDQw#IC3(@~H{6Z!Wacr^K4+PQ1X3aGyTSU;a3#FAh|0!mhTrpv
z7>%&RW2BQDfW3n8mo0to5hh28(Dg)x&&x6Cm)px}OBLDgiAw9#Jr6B6_}ho)s{ya1
zW8qkLb{R33{lAY}P+osU!O{RmMjEk9WXr=Ju=KU~QB^i7SXJzby&nv?Y(oK$B<od8
zM4@fF2!d37i!;*7qgV-!?iR8D4z`u2GvHnpsuj?fh7f0oY)Og?<n4=#4CBYkPY}+f
z#9>$8stsJ3-YNl#BT)`1-vyTMI?|<lIe~29i+9@U?&Tu9h*_*K_GlCmFJ&<RM18je
zDqq&7L}`PZ(7_Tfj}&gk%U>GiDR~`qS)HE=k6^KvU5;_IEfYQhkR!@n4VWULYLs{n
z*sn=G^-A8-lSh6GJmoJWKQ#h-QH5`YCR|ioft~6?>;zkDiX7(^%M$?jpaBAY%9L*b
zTW>17fN3-xTfze8c~pGJjTzOEQGAbx;ZS>){3#=jm+H~ydkD<LbTU#QT=q+q)R#OU
z3SL1U-Rgs+PFfzmz+&(WupIhZ$EYpbgK5<6>%|gIgVnU99gBYVlPR|VC_ZNI$Y&Kw
z+=p0f6({d8FG{-JV30?Q{thsET!sBVQlN7sT#Oe=vH3+Ec(f5Q&I_QknJ_+vc;I4(
z>lpBC92Lp3F^Qs*)>>emWE0IvyA-&#RivLY|2~dYLQO0-eC~_Ke_oZVxSU39gCU1^
z-E2~66YFwTm`5{Oy5Wowf-N9Z7nm!h>U&~9(yQ=~fnom20#-iFhsxQTBL}A7SKo?1
zRp>{+w*bxlsdy4B0*-9YZd?!j7J68%C`(>?8E(YNiq<5Gz3G_9E`?La8-#kWwZ_eY
z>3Cz}n`Y8@5>c9pLlAY{0peSpq_w?$e6zB5ivWL2sIp%HK1~dvy^=~bmX)o=&I5Pd
zR_ag=y_^CpqG}GnUYIrYr^KG686t#QNUd?+Zm$`<ZJfiFOAjt@eHR-=MlfqDzrDcU
zSXR^2m;l3Me3NR)QgUg~PDT@J3iU4`8fl(PK8Bi*s#{wNJ)2OL%%k2V%e0McVB&;i
zYjRh{5vS9jE&+s?L<F<+=C8si^74Pnb1&f_4^PATfw?UMeb~XcRVYQ?vp!YH-cAhT
zI@=)%Jo+;>?POSPS}vf8M-TtxA74P$ndMwQr3&hfxgtW3AnAo+QB2XFH}zm}g3bA{
z@Rn%?$zU?AO}syZqWvDye&rkE2t2Zu)UuQoQ$*f~Y7&fs8{lhuTC(Y6rqNt20hpT*
z0loI-ElL=&60FQ^If-%Dy)?Cy*?1N;B8}{>qJDpc#T!~oXiAwf{C<NQ$X-@?yJUS@
z-?oB9gFhd!-1Q>vZOM%10P>);e~3$JU-eW;8ng6HZN~nN+S%fs#M~LP0;R>n|BVfq
zp*Y&sgw%q`xV)8qnmct7Y0S%?wJJ5wS;pjPz8*Dd<T*6oy5@|FXwqCIT?dtWzULWE
zG-g|OV@a)H;Dj?f>vfy%;cMHltb*e^*Q5*&^!sY)aW|*uV}G$b^VhHE99>K=aF)zI
zOhRJ<^rLH^$HV32RsF3RkFS?MH5cD|q8=rCzCL|^nV)OLbcS=%mAt9d)I99l*7UqR
zK7U^o^?1L$KhNoWKB`~ehOT}7R9t^uj`VbV9gUo?aP70i>jX`q-t!i{dwn)^f6Q<D
zyk4tzD|&oB^Z9tP&{3Pwq!exYn73B@<!U@fK|M#(zQ^_VyoCJvlXLC!QKR5gK&|QB
zY2gL<)zz$dpR<sdhfqX82<|O9>jeBzm;dMPxhFB-hjT$rOe52`vPS!66YhDh<bfNG
z=JT|7yZE})>*WSg1U`!KYXafr(ADr`@44r7GNqtiRKO0o(cR<mF=V$!fa90OacRge
zrL@R(TZLC;z4yDG<s8)TlpN~?#+$P+k4wou-327m=~kWXOBmk)=$F%)r>^q?Z{^h*
zs_^st`>`_=`FYT}*@ttC^Px*kUf#Y>cFos*@9|-JPCSziOTI6ojy8cm?3&u-CsZ3w
z#b0ePcHAk|kMnqaKEq<U@a-)}V^o_Xmsm|KUgPX$_FkEYDFe0`&e|XLqITKaj8C63
zEd3_l-6B}FYIk8V_7fd7UXfppykOXIJxw=9kblHz4zR!uJ#ksQQekO_bFA(-zVun$
zY&`47lGa035mIAy36Ni36!8esICRyMzPGpu;0vG5vky^!*4n#q-5Du@bi+67{=6A;
znLi&8TQ!5ES~tY}=BBZSd;x9VL;fJih*r&RUaOA!_?&Op8UK8xt3CcG7@mBkiNbnH
zHeShjcV}eChQT-SN<B0_;l+6SaO9gV`1Qy_3&guTf9!HtGV+%4P1lPiyS-3awBH(o
z*^HocI95zfg=Yc`el*s+*0KOrVl3BO*HgrL)3ovjO69AK&aS_HM76tjTJ09&{@FaU
z6cLXV&NNo8xp_<DdC>|2;MPcyxh<w%hCS?OGeycfo{6UOOg~-k16fZmWVwN^y0y<R
zn3;e03$x8y3o~5dG+BmPE}qHzKF#$<G0yeHFbz+=v*-HUFBU9X%?D7Y`=@W0w2a-1
z;6BMXH|W&yjWMi&>~C)4FXC^y-E~~>P0dj^s$W7(pT7bd!CEA3%e%vPt&B8(&9I33
z<hz&1u--%aY;@!CHpDu=47n>l$~@>pGs&Le!TGYyl4*GO1CFpYJtz*K>?&@LoD;p(
ze$#G)T&v^#E%UmKexjkt$}uYoxV<U9$~YNF_Gm-&o~9ThTT6@irh3hKXSy7moa$(f
zIT>()>wNVbe<OVpmb&*^{raGMNW0tuz`NC66??cH{X`;uEf9HU)BP%ZpghB?`2#$`
zU}6qsY-8l;<Y26C{WoQ6U;)K~Pmlli6CWR+g@c`)>A!lW|LD27{}$1SxH*X_I_WzZ
z<NvGptJA0d&fwDt3E(r}(;4c2OJ3f;#{Wt>QCl0Q|7C4LLr+7G&-&f0!heju?f%mV
z#{Y4KPp9N=XN*txQ{U7Wp9G)bALl>y9gM%*V)$=eIvHalbA3TuH+;=+75#U|Iq(@6
z>FM#c|1lT(cKmJch|l~#6~r8Do$dZtXa05akM?hs?~6|H+qHwfjicRPXNK<oRZHMI
zIXD~tHz)LMC2Z_sZfL9^CiqwRpRp<!JK8!s7#cg`|D87lsQ+(hY~T66^ZR$Eq>XJ%
zoy_pr|EF7`=2lL|4)}DUR^Kx#Y;0(2^pB_i7&73qF>|o~ZR<Zv=9YP>=IMqk(p+<<
zxX81~!!ys521%Soj1*4*SrZrt0GNm<oE?D=h_q2FU?7|b4RME{t|Nu-8*DmrgGqw#
zU(ZmFfO~#+_d`g<6>@7F1r6n=6H&bmG8<`<rw0&i$Ft*~uI<n6brxmqnrhCPw=6{=
zaspwZ2#DC;!ZM_iUoRg^d`JdW1j3kn=1-LX?$o>~v8AGdrQ~T}Ckq%nCUOLWA=dTJ
zvt&m}UROF9F^{T{40LinMh11eI9|cAC&zU)$3_?Q%~VAzK6vXC2_;kM??y!o=<95?
z+8=|B5=f97voWzQPnZcMvYA|2NxzwDKT(^3=X1P_Jai9h)U2Nw2)r2M#KTJUNIId)
zl*O$^$9(Yb;1~MPBqNQmZOtxZCxVBAhbPFX#-K>mB}gKfrvqD$sPYBvz5h%mIB@0_
zrs^c3N=n(oo&&5BGDxPn?@AxcPm~htD%2q_JBVm#1W_l*LFn(lawPsFKfnUeCk=Wv
z2ntjd%fA4R7k6&ZcWdIJ`-310_eg8Ty%i~J#B8!zJBH3n+LH^sc@4&v0Od)d&P|qT
zy$k0LheS6cwpBEcUh!0$CS(!9oV6}=@yR=AfQQIx4L+t2HXQpjVWr8~pxR9LI?!Mm
z)a$;kL04x`NR=%OLDHZ$M9H#mI1tWem5iZ~O3kW5r3`ubp#;n~E6veoRXk8pa38Gd
zd5<foF}c*@fwqyq-gqjynl@6C2ScmdJ!|IUGKoAgX_-vMMu>23lb$8wr4zr9XJ{b{
z#OiVMaFV(qpu+2)nrxTyK`X;7!W>#dhMmFvRW+jP`MkL-+LJmmeTjI!VPk(e-V<&M
z?ALyk2HtGN5j%(YnmFoE*psPC#%V4VFC_1<BGf<Cl)ZSV+`|R<(cStq`UtC;!^*SF
zXbwKc$g`@BJD#Y}5NaHM0OvwcwN~#;_0??i=~upY1kV?mp>$Xv+{GTymTh8qCeSco
zP)v?8J|z7{oh6o2JiS)mEfr}9t&V6vubk%>E~G%Sw?wT?G<aFRF=(wO8?Zu`l6RUu
zKj&=in^!?P`|9vgCB<ja4pUP6n;+ZeXh~-M2QzXV5uw2*Y6XpLhfT!$i+zQ5^(4Yt
zaFXR=zTGS@a>B2o)M(9Dm8@Tjw9v3*PTHg!1QmM1mX|Q|;;asld263*;)b1^IvM#i
zY^WILurZ>s5LsN#DOWaP-tlA7TeA0OI;NFWOIeZ%X5q+sfZ12#iUAto*?ZC~oNb(K
zz$$d{LXL&f$zz_DJdfE^TcXue%UR}|LW0c1LHL7$+{7V?v4*~!;@>ZLIKzIE8*($I
zM<;(D8pj$QlQ2TLj}2cAZ(;aYHwC2X=b5N1C{;MNW>`J4A+qE(qP48$ilJUcJD<Wa
z9?7Vh_73V?&^@buTJEHJsyx+I-F0Pg&U2o>Xu+c(4%HUnQp{my@JTVLV&2^7a}aF0
z#K%BL$0hN=BTDv@x!yIq8e1WKM3mLmmrVR%<6+2=6W+OO-Y@UHm4u41!I$DGf{9YT
zmN@JTb!vfHx!_4^895|h11^M-UlH9H?v9Igvs?mh)m<~|sxu^5HN!<;1et0(PmLpg
zC75;6<iT>n;u%TubELUy{g`FAQSE4+)55jxYEA7aH@+sxtl@Ots+m#BGnr;qM{j+V
z)HthIbX`POzsH0t2}eWi-m;fnm4ye@YolcN>~tm$d{Ne;_e97s5A8bdLCNt^+K_x>
z1iWnEAy%G$cowJ(09V)>CAWLH4D^lMFr6WVmYH=P_P35kkrLK523nK~5wLTv<QU};
z-tQcgh>_Fm`@LFruk3DuY;L)Eb51IYwv{{9DionYeTBwUfpK~8Dw)y%I)nsdM(Tt3
zq9`MV0)oLD1lLs9lnlCpKpSQgV+GC1*B%nMAA-*8p}@vwk7wEl;e-~13}qA~l*O0|
zB^B$+O$b&W63y{OPtM~_?a7v*lrqO|rkckgkbe4BymjIxqg3Zmbxvwm<;pRX>5=1G
z#|#-UY$m(a5CkJwQ!8f8zmyi9$iq<QY>;=yL!eFHt?VLfzz2SWxUAmY<q3Ji(M6mc
zg?!>xTumlpsx;OZ{WwOPSPMx_ig_17q&vmB3y|y;IXtAbY!Z#}u*?cRyE!8w0dJc&
z4N$dN-*VfCVbj26j{KbWvVFC?C#PD!6J5s-PddOxi=T_Ts_;Hai>g^%g7f+;YuV1b
zo*kI0P7Ygd=}{+{{6p|zF;;k9yI!mhHdl*aeiP5m$df4Or9|Ugxznvm&Ua8KwuX1N
zz^VGa?-f6Aj6XmU;~C2bR5%j%&Pv~9r8D3}1ay`6@O3-CKX7|Jq8oGkDe-Gf_w4!{
zZ={19BO0bDf;CFIV7}12+uYt_7bY>Cjsobb%S+s`H(1vRT2eR>N^?bPzmkvraA6=}
z>zCFBLW!BjeTh<8l1p_d_dz^q<ga_B7~FSG=e({m(Sj5H+u2*0_h;({_w-edu$-O&
zG^>Z$DC=(g;Vf7N-uWlcN!K@jO-;izOadYb1;I1WS;5_YP)U(<(6x{$6skc9dqL`w
z`xgj#s_M{bVHzAkLvw5#1rppJ>w_-02vzy;hHDtJxB7{;Nf#m-ABC>uU~n9pXL(QE
zi&tx{G7N+J7#mv@Tn5(>V&V1mHo_lw#tSv>cN#~2`GF#kyCD1=BAEqr`G%OcStm_D
z$I5sc*;?=J+MVgv+YZ}!Yo_^xG&H9tesxXf2`Pwf9_K9UC*zW5lShYNGvH*Ybz+s}
z8EKr8um^d_k>rHDVaSdZ#YjlomB!~sNk~hh=bl1_O^8XFW85dd{a(YXU&+&}YT~33
zm`B=2zT?jvC}Qu#0V`TH&Ck1Kw7|>JBt+TPVe08RYKzjYu0fbe6jz_g3oca9Ku<qg
z{%GG`g^kLO*cw_@y{vd#eCK=wfXsE3n4f!)mB-kE(JeV?3~U^H;P+6Fv?x<4PvMk;
zjft9xC$_AIlcnzkwV@{fGa!Kbpw^L@6u-{-ig*Y*jhI_544JPfX%T}+7x1<=UBJo`
zM=G7BBHPCBGTMQhI-Nz5qpiej^Yl_*9l(0S+jhU_8^-g@KR6g9slZ#sT6_N(`9;1u
z{dO%SH9igvE92nok!LmTcW}Vw=l~@OkB8z^Vx?7oxfsa$M?QcxHG0KZKNIaTmOASu
zs(O)9{lfmGX=_35N`Sd;6TqLhPT)_nfT$M-Z`uRDff9#5G_vTXefzp}L$S?v-S%|_
z658xnb!fzg*1h8L^!LuZiu7N!w4v~3Wa$R;c9@166me?z=Rea2_83*E)sOTTriddP
zS$q3P0PZZ6j}ph=3d2vE3G)BEl06Sx*>S;a%0vNM(Ny0{CQ6hOX-MvyN9!oaZ4EG}
zwa36aMJC}UnMgUlD42uNxmv}ta`C2kF_vm2?c<B?Vwy>MitlF~%1X*DB|IlOCQ2Xk
zpcBAYL?C3s3n6Aq;3*&7oK7j%hVzl7P#sQ5u29-4!}Z!GBH0PPy1wwYLFv|3d`P{L
zdQJZ!b*0GkYZr~1B~Buhr+R(pm}C8|vG;w3({lVLE#I;N>7+TvoR@@0O_66t^-o!9
zjKjkChgh+#QNrva7Vr`%PORc4i9y~p#Kuzl^HC4t$f(x%dHQbScINV;H*GF{ocfZY
zl&+(7wTXcQu)+a>dWn39J-*>hf`J19-f*<r(+|#+vZ~#K7E4Rx>upTy335@7@>tw3
zbR&E6Y)m}_07C#kZAeF`2<5YdP+b@LlJQRZPK}Y={?Nc5vg`4fZ+R)<<Tnn$<u@*B
zqp}5Wvg>hzWLZvxLgIk#krM<|VLxQJ5~3TK9tw$0Kd0WK>>C4lMRJ0T7izuPWc;n1
zEXSIcCjiyOl@3B3k7Zk=clwT`er{)WX$G3l)`e2H;BQR|U&sjA&PBcCH!85yF(aTn
zVdy(|UBH7ck<}!rzPl8Py%#{Z8GhgZ7vpt?m1o-Ig!F8aFEk^x00u?3>Jvc&?H`UR
z6UJM)3JF=*_YV$+`Rx&lLJ^gue-0$&)7*48w~W@sCG7Tvd|A4NJ`XKImJ}a!F+ENy
zhPYgD)!MH|ACGjt9!$)G=ExsAB1m(09~Id8_Ze<BQ2zeaWWStw%5+@fw1EflQFoNq
z#hQasTA)8#l4Av3G(0#g;K>ITOzcoTfmQ`8y3&yxS1T+nlb_y`1?kW^nM*fqa+kNR
zC8*iC{IaBp_zSb`c+>2I;b32P)}jZaPX_Zh=J@cf{qOk;b6zeR_sD*T2>m+h=y%h&
z)jP#HrhSvwl-Rjck~*oq<QLb3O?%XGx=_*d`Gkk|jIRcC<g^*a)5{}7x3ID7mxdIn
zU-m9n^RTa~Wv(+q412@bJf250P2R;en4BdBy}eAE4b@*?$6O^N5k0~m8XRYBgnNdH
z;y&aglBA+#34sNNwR|2W7%s`qYUjE*PA)$`86f3-#3du4^IwT<Q;2wh3R-$97!In4
zoEvq@Lp)SQ&W$?Fmx#rKPM&SJc!;}TyGdHTovk9!;_LH^%2C!^YI>y?5i`U(9hWv+
zj&9}1(U$p8X!bC1MD|6kg1bX>J#I(i&~!PeCo5!5$-5DC`P9g}zs61X#z#Tnx|~5;
z{3->zRYYDSNimG{$X9UNB$EapwFk1BAS)DIjhbDHo$lThK5S5IliZq|$cBv9WM`h%
zScO`wS?22fKHy0Gn-e4i$P6R+464U)6lN}kH?w`A;#I0v+Z-p;wYi3-NGv7JbLhgG
zB9<=^*lf3u*(!o7wcCw8-$<mECCMmL=xR2!+B+Sza!qEju6zCr=cn_BBpe>s=<w+J
z#LH$j8I4g-6vFQMuKfAU4w)dj#|2n(!mnjSU|wW+BFvfc6<?hoD~Se#1Dxi^>!+H)
z+1R}HCnc8N+ZT2B#b0w@o;~}0|3!`u`MH&!>J+sdR`ErJGwc-S4K8~8&z@9od_j;1
z5}s%gj3K+=+MkFnZoZ{TP22quTojJavJn)DtUoho&SKg`Hq?*en|`jbe|~+92sw(=
z^fg3m*}$&~y6RVebeQVNsg)Cqk1DP>MlKOdI1P1cA8>L+Fr_4Lt_(onh}PGo#NKNW
zvYFwo##kOG&`l0$vg#A9`aA(t80R#2%tcHZJywQJ7Ovj>z#DPZp9(^X2lsX*EGt4A
zlXgJw_O)XFePvARfOw`4-{#*zuhkQsm_W&hXMQ_pZj{HY>jB^?d+VVPW{w%XT#%G4
zat1eFbb#%So5~z$Rd5_z!+D3J4&^>42ohpd26D<5WVyKioMc2w^ntw?8p~;jrx4@G
zgH5rYN5zLGv3#32N#<TCDf(PZyieOa=rU{AD6b>ee?a|#ZPFX!gdt_pv5KIuMG8nx
zc-ZPv^ckfkcua8Zl5Sf=JE<??1pn%fLIJ<OMrIXlH~l#WJSq>#5$+ysMJVTe%1ACG
zc{%H*Py=I#@xoJ`OU+*mnFhvT1hsUO;9VH(6a=LZO(pV@<av92Gfs1XbkLT`OXV$g
zwyP8W{XRBJA`7ncIxw!1(G-7vp;T{WvcFJ7g;2pg@HH~A^W~k~q;DBW`B<rip-ygd
zld}@9N0q<DRZVbiK{{vx-)mW)T)PVfFD2j4O~#Wg%?dcmcC`251H(ldeYPj~b~Z*6
zTaC$p7c31WoK$9x+BvPX4b!4m@tkU6f8V*lH5o{>A-avvZj!L*P}m$EzPqE#=Slc<
zu~w)B=t16FYh7VU<ML3kUIaEiGt5iM*2O>1WMDLn!tKK0?p$|ajp1IQ*Vd^ihFP@*
z2ecF3t3^ws=%R3r@T()3V=(R@X=7an^ykvWx9}3MIw^7uk`5ZbNo@C9o-{P+RrP2`
zI?tALo(;02Uk!<2%o}HwFlUo7@`=SRe}|giF%bi)O9Iy`1ipHLG<r>pW*|)mBArjc
zLL?Q$)@%i~GGr8g=6D8nppOz|jTs4x!RU=bH#4Wog%7h;B%uar{6d&H2<iddeWz|!
z2i$Jk(F9}z`A|jZw(rxW+VMc>)^UgbqtV+0^->OmnXyABb5rC?_tv`zc+=)PUBC1D
zkl{lTRBJdaWu&)Aj_IX{^o1Fi7xAXfH$wf!l+H^D5DmoZ#P5$5z;R6PFNha_l3%p|
zQ!Fq?$Ef@RdhG8d>^>^JIeR-XKwD@x*}i-br8T}x&X6CGzU?4xY|ygM>}?Z!WS@3~
zn9<Peq&v?*Tc|h5zT1#)ioLd=*eG_wz538_Nno!8fKA{rHyVK8@W^)oVmmv8E<0=j
zKDqP@P~d_WYyvBEJ5f-jh&S!N7JxmdwKeEEj(ruL0UwJ7D;*;P&tUp7;5q{Ny5|0y
zKsu<kQoXY9N{}nJ@e$Xf{wZ2F1`L7rlC40^&@0W0V=a&?XMr>shA+tmD_Z7vlMFx2
z`=K$p>GTwX`q&^#>Gg<w8tZ^qD_w74&1<(n&(rlT(}}#Qd|3{Iye1LV8bXu!&<+lR
ze&QNTgYK#WR;W7fSAbTYfl<XxCOz}7LS?16>j%M&*BQDqB<2@N2GmaY>q4rv5AI2U
zQrGF#`HBFcLP0crIrIU2NdZEm_A(98^G%N&gYTLH-h)gy_hFMwEbUMLHl*vBAaSpP
zFs19Y`<erN$@C&g+_d^qECKKu!*G-8-2u5FW03&iBL1Y-i}wuymA(KLk)iK{3<ARa
zL9fFv&^-*Dj;|X4USRkVpiVE_tG3~O0Wf;shi-AlaJdUe7m15HBnFLMH1G)|`ZaMt
z1o|-%hzJzCKWYa!5S;F%h71$M_VN=c7@c0N*Bgbt6zB?t{^!|maMnIwBD-lj2*?w<
zovRM+4;#9T#p%iGJN}+-uxm66XCYnSH;7S`nU0i{XB&SV9+|CiXdXwWt@%J~91mjt
zW<d2#=WLSP4!AT7&S_?Rp%5Ew<*muUYD%Xu|EVnhPDchO$>$qc0r6*k4U5>4P2e(t
z6Z8dlF*Xoqal}~a+yJcj*lA*TkZ^)J$RDvmfd-*$y)i!?phGSFR{#+LqR;^^Bl2)0
z%d>pVKFB%2yns4^@<H6}{Kb5OIyHcMwE(UR>>%kgXEzXb23M!dW<bqIOM$T2Ckgm(
z{k33Vz%ev@;cL-A@_WXLs`+K`fy`)Vbe^a$KYr~J{8<P27$^Jc0ZfcZXaB#r_Fs_o
zzqmFtJ>!3oW{&?0$1?ndkpID?>Hh!l*#8Z`YR8Y;1kfXhJb#6&7e|DK085YrDivX&
zdY3lh0X)SLq8MV-?_6{3hbfdnrw+VqRm6oHY;d#LXc4%>H<;T8={vFRFzN;foZK>U
zCLQXDHEeb7txIRALZ+=-tJ_;_&{vfE9|XXquvpc4);q?)LjlCM=rKfI0d>?kQdK>j
zeZtG0sE8|T2Mqb`>2Us8lYx+6zQ&R|-fzDgdn$R^;1<N~VZs=jKt<cefXV8}EuU))
zwm`QCn)>1zhc`F{zuyE^K1?n&mlRRvjF1j`BlkY=A^7y?K#^4^%4EXBBT^*bh0F<!
z5Hg}%m@dj;k~)fGlG=@br57$1^qx(TuMw%?P<#+sc+S60`_^}fb_Sa!V=zzWl88A*
zCwoo4YILS|X&jaGqq%iZbW3i%dW#)l0#%WHq1)4S#?9`2Zr?VTs(SeVW)c^}|KBzH
zXC?l#XiQ8j|6MbNzrg>0G4y|t`@gXTVPi)_2Xi|oTZg|u{6FCaS$*s8*ny0+hO)W{
zm9VjezKXNrH>CeR<)Zr5=2q_b<o_1o|1G2Vx6n%8^c%Zp{2xoff1?XD4D^ij_%zI{
zjQ9*}98BL)1}4V;L>VNU^sUSd1#C>MjPdFJsVCrQ_%}?!!N~qk_HY0G=4lwehw`_F
zLi%>%#^&GDYX3Czk4n+W*jfdj{one3Gvfcv{J%QRsHZ^~io);wioPsvF_~>y3)`D+
zGclTIrp9O781w~}!V=@J_uO^}jE#l_4wshRd)k*Tfo2Fhrjijs=n@4&D8p>{?vCHJ
z!zUkL7L+NcJ|tD@V9d457+clLJh4pzUXs(jkRHJF)6HB#{EAr@fEK36@Dou}+!vK;
z1UK@R+0}UkN)rm2#pM=ietND$&90q5M|gU<2U1l;B+ECgn(HWT$JMY`6q1)NHysi$
z!Z@ON+sDbM?Sr!!Ca>TL`W|9EM4zDGbnpofsr)PqksL;QO}B7E8x!U7?tC^o$`gUG
z%|FIE67=e@B+=z$Z?@bWx1dMkZDMT6#8jv$rZ~>)`mneIkb|1p<dB<fH7#v6@m61g
z{?(=|Rs{3LtA*rJ@>s?&x|Hgc%Nx!o-9cLt*uc4E0`HfZE3uox3C*?C>&K@1fHN@*
z`2WFBmQb-h^P1N4ITB6>D;kXpj*Yvg0qz0s^)=j4k<R1D0zFOBkmni?B?{V)Q?VSx
zsdxs%_2aZu=ij2Wj8T_<T*QZQk%&6|)i%NEwvG$Fo8OdjMVrK?EKzjIxnE#U#U8bF
WzVIY4v9-&tj-;FiqtW{HG57;=iu(Zo

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-high_error.pdf
deleted file mode 100644
index 643e9787e7f41d39d88fbbd0a53b6714c8021ab4..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67633
zcmV)mK%T!PP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^b9?kEb|8_u!_35~YZk
z8fX|W;DPNsGdyUxVFSj=L3Izh`|W#+Tx(G~zs!^OW}#43DSk&gB#M$K{w&(Z`TC!~
z+3WvUJI{~*{{8ru<NVgf`P?5r{{R2{??3+S|8ai&&;R?dkN@ZOzyIO&zyIs_umA1!
z2j|ECdD!{!A3y%(!{R6N|Gs|C{o8%o#~A0g{`&vlKfHgtUq42|=f{8f_)o_#yY>F9
zzyA8wt$lm^5h1(%YNY?y|NQuOe?RV=-2Ktox8~<;<JEnB^ER&AKK}mw__zP#Z|C3E
zNB{mmj(_tv`!@c!zyGh}fB*Ye4EW_hZGIcu?4tSg-28dIO~0!X3BT!fw{O?>DYSpn
zX^wCAXj?B3e$&nG;JVmP!av9U=i7aC@2{^8`}SPFVE>;p-+TLJ=RP|Selt58-|Ts|
zZXkT!?InKiqD;bXy4^-mMmG?C(`|YRRxUs`|4{n-yuOWJNdNh-k^b)2yC{?Jo4NJ#
zO_b68O(*N`qD;cq-P$uL%Gr&C-*mfQhug4P022PGC3wxN*=6_Zt9So){(J{~oPWLm
zZT5FjCgC@;^Z72yB>bk^Ye&C{G6}!wW^F$sv-x!wdj<t7*-yehy937U{UuuV+N$$c
z?Ely70K4utQAYbWvzzuV$|U@z+w1?oi82Yl>DF$FGP;5An{H+lEi3^Df4Bq8{9F6^
zA@uRDxC0)4mt?fRp4)Z3%Q4ztcbexe#nJlBJ=1@<=lef!Hns_Q!m%?;oc?L4f9=le
z7efE9QhJ_u>3#kI+1>O&66~vk>a`&jud15}uN(fKJqN~XoIYOn#m9JEqy8&J<d0bL
z+V5i<CYoQ)?RAv(7sINP2w!%y*SWd=bM-6A*BxJSu=e}bQIxMc`bg!wI*RfK%V7S}
z0_W>Ac)nhTKUf8u?FTU{%GXo8o*x9QC|`Gc=G(%v{bi^2Qd!=Yz9?UJe4V53YhRQ<
zSc&#JBl`2(9r0&3V|(d<@8VXJuO~U*pNQW-it=^GJM_n`9|>P~dtS=w`L-IOeA%&^
zzpXvnf3OnW&TsSX<MFRn;*V6s-t7lrE6Uf?dp-8vg{>%GcYHlA-&ejUUw3>xiQZSf
zC|`Gc?)Q}!;ZN4$d3`IDl`q%g&#unb8}nV*it^<Y*PGVg4&kDF-O-=uuwT8TeBE)*
zVBXeIl&?G9eeV>lKUfEUoxt|{J@H3M<MaF=Xhr#QYRj<mCTJpj-L3Z@R=p@+cYJkt
zU-hDV-SPF-e_!>Y{E6x`Ubo@=?Vk8E-RY&K{vc>Y`Hg75>!I&D=I6(cKm3nOIi~x!
zHSzV%$$7T>wbOF;KTi4oTl3wH@%HV!+r2K-mkL;>#((qwiZ6DK`);qV&X=xmuFt==
z)r+@37u470X-gBy7g)3=Sh6gC@iw?<%PWfGA+sniu|9&7k3EoHlvFuDdHw4}d21P7
zl|fl=k{9JAv&RplHb7WUjq8jbe<Rdz*EHIEqU-0!v6Eb%T3Xklqy?`icu@!8^`91@
zCK=;eq?+VQcwUq%zVJ?|X^++3{yo>XI6;qx7cC-185>`E7+dlL2W9c@MR~F1*eSj-
zrpF7<V?ar1BM8N+AkeZEoU-6l|3)U5!_K2mC#4miEcnzmKE2p;1W9~)wXAp)E%L`;
zOFHpj4N6QV_R~Sqn$7EgAXkb)uH*;WxW$8f#x2Si`k`3Xaf=I<D>g34x8)MND5ep`
z5{$V%${z}jzeuhT1;<|$(};qdV~97F>>DF_1X7I1#UBg4Eed&b=8hX(JjxxgDB{tX
zY#U8HI>DnR9-ZJ(<AyrHqFjXoq!^G%a!#<w#I$9QcpYeB*$D=n-}tkyp&vmojX2oj
z+?b29<j-qc<{vMLX}s%SFE#((dIfi06m+{%C>90Xt_Oz33sQRJ>AeX3$*uPyt&;<<
zg(L)Td~zZ1I178_;135Ue6sbLqtjZr2*HLI1>1R1;=?qaElSMVxh6{id42C#q{h*P
zNWkQgl$>-|uN#x@>~v$!IEz6FmN%|s8VnZ!3;81C6loJ&l$@f)QXWBwCKmF#G0Brl
za@|;3tp2MVQ#`jWwobg(pRG^KsB87FJ6c@AE2q<WATPrDNWW_dV|f>aOPCIU*01Um
zlj*d%ElO<ej&(nR6l>IL;ZuoO6fXRgTe(lR)&liWJ&tJd&nHGd*ovQX2}*uyQ79-g
zcU|`b%^Y~&y5zw7)+NWS4gaDn#`oOsM^a)-^|tj&#_Qs}@~T-B3Rm9si?W342uiS8
z7w<JN-gE2JVWzLY>9FLd{2hxFd~6TJb|fp?UA>}3iFFwNbzr|J*V=aNQjg^8qExS7
zU%R$m!M--PUU^2fxpm9Y&8=GwPukDr(P9t!CSqO(NHGOhkB;H_)+>jnyZGv0US7rr
zNWs0nb<5%Pty?T+Yx)?JvzB}QNK!gfYS%*}YPNOD5$Vvspop|Q^zlO>aP8c><%rI$
zTQW=<88p0RkFJ;tH@rRShRfTYty_%9N-%IQ+g($`oohG630JONTd!b|m2lwhd{G*X
zI9!xg!hw6yro<bUpiO=Xcb-X8yViwv1f@C!H>@s%^VQO2FmW%LPKJqF$XpluOcm!v
zLMyq@w=T&9soG1gjnVgPg&S-_KIbjZ82>zP1(Uw^BIFmPv&|b{O-<-XQhwI9Zuwbw
zSYL!_;OLzfCVTRbPrdoYvGZY%w23VOu7!yM`+Rtt;ECBz=>#)1wPTU+Gx49<VdjTV
zsdy9T?<t{}IB?HP8+qb<JtY-0&xJ*)ZXsPKrDBCVEbg8u6-Sa5drwIPH2Fn=RJ<rT
zN&ZGou%u$(0zIV@&J?0WA^YLfIlER32jkhb2FrN3+J-0AbWD;8{mj?wB5(yfT4ZJi
zGj(>%&Q&yUzsE<UEzXW_==Ol)cu~lc9xc3QW}auSztK*~Bg+)NvM3|kWJt<0zuA&w
z;fy6ITI7V`6Ve*t^|9xYTv>b~B=7*ChsRh?gPD5KvdEJiC!EM7Bq#jLQ}fGtFGn-y
zmj;(|JugZdL7<T2zIjnrYdopv*`tTUh+VV@nB&Ovbx|<K@qkI4a~x1V7YRQc{~3H-
zuc_$JxOU?PoAjy}H^$y{W{n$+;veM5b)JkopBIH=y|BQhv0nLXvqzfdxG;QZns}nE
zHpiO*7j{bv$wymIXjd3{sxK0F`=YFIyeQdv{Y#QE^6p<0j%?%$-foFXzUW>Q9TvmU
zO;^as?YJoXtfy$bNNBDlzX$f>aQx`tUL5eM--7};a<|(ZpF2Pb=HGl!jC{Yp2+?Zz
z4V@DMo9os&F&YP^r+>Z~4K|r1<mmLg7}!%cpO*t$>JA;?04an8kMpF&50@wyez-*8
z#1E$=97)PGq$r$N!IR%U<zD*?YjlQCFo<MPLLThWqr<T~F5N7iw~k#>NIfn~dp!ZL
zbA8=8tIZ46A^URlJ6@)Scf+FORb-cr4Foe;YW@dE!KzF0;;GNRDA{`bOHUAooL>?a
z$4@O1qy<k|yJRTxiLvQH>I2awx@&yo<gDy_J}@>NBp%kNMHtzPf9F~#fTc+eJhfqi
zE}E1an@maW7@KY%MZTC`xrlVIOV5`VCC4TslXvh<x{CK#OXrHWcvCFOKzl^1v6(A+
zq7~u^Rc%oq_t4FbB!zfRDYTxWu_=WXZ|X&%l%5FDxus@#YNCro*}+vYrOx!cCatWF
zJ+FdUuiU==y9BA<2o4HC>K9rAtsJ^87QBOPcHM-1V(hvpI>ct`rs%n&ZRjZNm~ool
z@`o_xp$&y6r43nC+XKqnC^4cDA+Sdf41bbq)-b~{(TWv(9n<`;v4%spYrE36XE@1|
z^y1-gN=b_c!y*j+LA1d044+v9DpxJv>^5j(b-XMW1;W}=1y~d?sig|AC<Z%m8{njP
z+XgtP?SluW4JmHT!L~-dqhX6-Ft}b`=WX6Mt%GNJ1>*6!DCAR*N6w-^9@}dxl_{{{
zE*VnoS_2pK62ME;(mI$kG(?$6<7>D(T-&T+2fZi*?O1bv_>gPRwEWQ;=CjSpfY?&6
z@>}COqlK~AgR{={ez4ru<`PlEwcrv_JX05CpdGyTOFGeul*5<F(IADcTfndreey`K
z5JFG=WJ$W=4saPM3_4F*C2fLl)FKSJjmv6bGevZfAiS>^YJPZdS#5xGx+?H)U6g@#
zEVb8L)g0f_MPWF@U3&nbw5AZXMTsTpG&dQd06iYC29a{99@g*~>7dr|8C@P`*wAI|
zG{cm#3lw$N#bG#WU8)FPuZzM13(waVX|>KLmPf*VK3E+I`$@@=j(XluAN@o#<f4qD
zC*-2bxp9U?a}oHf(0qGdH)l$ab%{CNsEfkih@){4a6X(fT6tccBkiizb*-E!3yXq<
zI&qJ8Ncouttks6poVcL-)CGO!S!ZQmJ)xj>J(12HEePX@1;-_m6pU`7nIjvTu3=<)
zWyfoDwK-c{G`)N;cz#-!i02b@5pt*<FVIC9XorY&9{Wef6LgVsw2PAK=g~@yu~So8
zgg8%R++CD>t@e)L_6HiG?7fSUKa;Fp?PNafzx|n*VyZJq$r*B^EK2g88|6ibR?GR}
z^64}N^$ZwXV>57Rk#c^xIQru`Mcx~WkW(~$1?NE6lyhvjZMx}GJ!W|7J5bvgvfm%r
z1v>4G$0DVipZbzv$xd+!%9u>kFG{q?lM`otd&K@T7nO$UMTj{!z83nOI#y%0$|A&J
zk*dc5Qp~zh#q0O2K<R;YaH`!9s6~mb-EaXNFA{{I<xhklH15;Y4mLI3MjfwElSO<{
z@-5K#Dp{nKzmqe(hdObF1ALpBV(LqaqAB85Xj4<fJGV_t(bb7l^k^AI+i@PYNlCan
z*gy2;4*qk?clh<K4SkrWL>u^WQzw4ea?yr94kfh>eH&^;b3RsjhWITCzYQI{xxRg>
zSA6=ygR{{Zb1V`&HU3SmH0?9}qI7i5JKS&9czbsG(iRD;eNj5-DOi;31Zln~Av#R(
z@U-+L93W*U@BuL()~IxL_=SRkpMjFlGJayoDqK9)nnvRgEFC%U&jjV<->?^j{$d6}
z&KsI&(<zj%%OK!4VAyChE%bD296{n>8hddprd}M2=~Fn+GXP}~aCLMz5v-kBC}^7P
z)OhkTX(tzIKI#Mq-6F9U)@nZN1(C&r(Hfqki@-i9Hpe1mr}*zMu9=Rzndd-Ia%?l-
zGDZVQpSZA1PMHpyxS38x7{C{WgB$u52A2|Xn9*RrNaz(UNP`?Z9Wg3F!RR0jcGIfT
zVRts8KC>w7Hqd4#EG^B*hTOR$NFxZ?{<EnQwjd3|cB8fa{?b?t+s`fy7LN|o@f-OX
z(Z)}vC)_O6ram6^fG>NI;%u;sQaEsR7=4(1-0Ft0((-DT1e3N_)0sU|cQigS79oy2
zL%zo%#4(Ad!{XDJ?1VYcLW-o*)n*@Xd!#8UD3}6O2RhAOlxRRO5c9GqICJoteo?aZ
z`qv=q2d@d!6+la;4bFt=L%I_X{9?w}&!VhON05SG>cpv-Izi51q_n|_VE>yOzl)Ue
zIJ7(`ge$uE1Hq#Eug61nwXra1Z9I~cGxS@Xa)xPcl*6#&nHrS*s^bm00>uvyQc9fr
z*e?hPFQ@KUZw4fE=XyIHWs8z4POo)$uDI?mJSZ0hE9&v9@h|84F|MUMGy`Q<cJEjV
zY0I?lStkcN*H8Mhvc|fYz-8B+=s4$1x1t-5sxCGdR!kSA!}M&hWp?Lg?iAzB?JT!i
z@7&J1O*^-9kJb(D>TX38OHh&(9VX=<<zPDe9|mt-?|AH6BP%-edy~fB;fh=&@B*(S
zLw4k9hji0))H@I9oiZ>!o>`rzG(E|^^N`lP-aEL(M|kfI+-ll6h%pZmW`PHuF~_>+
zTf^j}?zAp~awG{nj6XObos4u@lw{vVi5AwNJ(N&7Hy0_{S(IBDiddBfThAM1S=<&S
z*9pqH$)n!WxcJsiMoD>TQ@N3d7wt4C8ci09V)!;GBN-))hsHxtjwB_c(qr43i&bos
zQCR-QUAR-i>SHEVsx>j9C@lvA34tQ^PDux(Ndbdmvr+8fq;eC|mbMX?Ga8JdZAWRO
zk^6G)J!q*Z!mTx;wg9tBjpMw;OAP;<VqH-<HfsLo5cj|s`2IJ3o~{8F1<cFwb!uou
zATP1hXV;uaX(f0mA7`WB;jDshf0H~KQ{E^NyyWL;C3s-^SsN~;{;d6mjd7k^tI?RE
z&9x{JDw4MS7Q9;&aw@m+qJUE*q{4ROQLvgkyz=yDG@fjfsk1AOoEBMjIFt?$-Vd|(
zjQubJg=bla)gtgH>*>2}Fqi1uY;f7*a0P|efn!Q=^pbJ}iPu4Xs?}|PDYUu`Jb#$V
z4jl*Wfhg!!Y0s(CpNnvcfn0=B3<S^b)NhWw;#O1lWDbU=58a%N#t)+xsohjxJIqAw
z#vbI2ya*i^Ihb`*f92KQZtlwTMjngM$F2{&D4V{}?jbD$jH0Q7ddG`EwIs*o>H#L*
zn>K@iQJZnJ=D90JixSQhDNqf06QyJ|xYwzO1;L<okt0UVyI5jU3$xQHrI0f|r4@3<
zr?kQ}A2u2>q>nb*Fr>7$>rpQVLPi;<*4r+`>y}#FE~+{-!n6y)A5^c~MMZ}S_>1xZ
z1wBVb#V2+6c1?A_`d;&+o&hU;g@2!`nZc?1Yhq=u@Ew5lyLcu~v|7GjuzVMncj}0^
zxW<z+>Fk8XqLo4qr*?6LC*}gps9s-<Mhd>rg2GOi5LMTyl{qOEQ%l2_DQ8eGQ!LKp
zD}~R_Mae#J^0fJ=6J{{$WjfI2yA%_cxBA4fb3~2|J7EFlrEXY&$%jg|@JP8e*oiO|
zJ?Iw+J;?Am*o&j3LUd!aLtStut}Ge!!67+aeK=U2(6<KLv(tk{r#%Iy-Gm8~wi0B~
zlr@D}G-YvN5)G^}IX1&)q3tHJX=w1l;7r{(I9$$QB8uFaw3MFWB@Ns#Gev4m_Tcaa
z4cs(VElMcgG--WCY7M)Ackut0Wo%LSEeIx@{ReDpAaxk#z(Cq5WU6b32q<%2gPr0i
zlV78$LUzGMQ-y4Y%+V?HB64)r59PE{B50q?^c-3>@f(l`**RBw4mxr1;O3XXG$?5}
zZW>EtFAfFoBiLq-BxNt%oCB6^-II*8k{P%SQ>T$(A(6uagELp_R5zR>Na87@G?RE_
zxITh3%Cz0QOxxfEEg3M7w=`tPfZiN2A!TK6jFM`)S{#a;to4l{QL^Z-be)@C00^#6
zbsK26v3U*}W1i$)h^(Gd9*6@Z`Z4(N@_q2*<@?~b%lk2sQ@%M%8qFJc?Ik6BA3C+2
zz7L(!-srKq$Z#AT^6xapDai@6l6bDM`H2=G*ZN}cU?lpSbTu)_N4_W|`INVcSw8e<
zMT$?@{N(alq~yNN&W^X2d}k|(Cl`S3wbpSO%LUgujNCdL`vvyXlh@#?UX;8QX)$RJ
z{n0Pd<{OM0pYWN|f4C^=sic!}CH7pS+>kAu%E#uaT%`2J>-g%3$3YTJ5XR;aZ8V>x
z*EEMl@44|y^quQi>hzuK;R63JeYi&^0KtjNZy`8Ze&B}w=_?LG3WvPOi-1{5gYOUy
zIi({bD2Ag$rk`+AbM^61=%qTt51an+#^^5j&l`;{a<acDa>1`upp<=i>04t61s(Z~
z0bX4PMT2soh=7(RmtzYWi1eVb2Np0pC<6~xE8+vDhKlg53|=@uO71hdq2VB^2#7`l
zOrIJsT<E#QkEEnXL8-!lT;Ui@4XTihmE)7cL0Cs?JSY_Q(QrLgWJqKNoqO~MvwkYz
zB$9qI0z;dvF?>R5N6RG73~X7g3~yrOOM@B5PwDZBt&;wr*eYoYhMU9L${-%ouijAQ
z6}Qvu-r{;16xEFTS*`ql-t17B5j=E&gis;<NG`pCkX{4?C`H0g1pUB9-1ty2*S5g(
zr=p%3o=_DTwI~d^g3#up??8xEQWSvI@B*$7t%j#{g>f~!;SuU}fRvxnTM4!a#f-fO
z2q$Z4%&BOzW;_;L4;aH^Q&DRx$0viH^cbQ2P0??W85B2#Uz!{x1|ok#&rqCQL%bCu
z@m3qre0+hOuoo$$Z&7l2B=9FRQbh$aTL_VZ`9sh?7+$yt^Q`#8)$WKk<mjNFDvI$~
znL!a1%4FC`9@>H-kvdfIl1v?{n94{UicPGb%XTs%RI2dFh*0UhCye-v?`$wJ9)_P)
zG$<#C7#)R>u1ukf2$i*nM#rH%<Hm5VA-m2B=Tbl`a*HbFwWSGCQL&L-l=G7v<b;_@
z;kApBfu*kbL3>ezZsZ)riLM}CCLL9zZzLW0tytjIPR1>HUkOF`U?A}U3Zst)+KfF;
zo<vsB*dvw~B|~c=sE5*uOwa>HtEA$iSKdvAmQ(eQyqgHkhMs>Y@dnY@@kb0TcYU9s
z<vC)^FrvLz)=Ox#6%M{gaojUrJQ86loP4Fej4j|il4D|2H$7g9ltb5KZbp?;5nPlU
zIiJjn(h)fi)BPfa5DKn?IW-k<A2~G<^M9h1@&0(ZE<(x^;`vv)%!9wUG2>L}ln}58
zV@nw@n*R!pWRYTumudJo!j+(~C^1DPF)T{#)JrLt2E-VoLj(nuBxX!7Ifv;Kt39@C
z3!~*w85za^DWz=~FjgwH!+>g1=^v($DdmV5Fg_}g1nE0lvWX##>Y8W_W~m$?B=4vJ
zF_owCT?}v)l@nvYqCnov0aC84Hr5SoQu#MV8>LcoBI_qUrZ_yinAyYUg)#O@2|)%(
zg-ROYPa>!2NJ{(;vW`|eGpi(604}KHB@Vt4oDR$QETuq^2}+zY00>lWl>suK@~?us
zdxn-}`hR6{8RNAg@5^WcWm?!G#NR7(Y*CnS24P_AmQv6{nqnZ(6&7J2gUv1^KUCJ6
zF^o%@af_0(y)|;EtxCGH%r!r@96fF_B=RL?OY~y`5R(IAFRu@0`rrXl<W$z$z)q$-
zM1#?^aup4^;F-%9N6NumM-Y(es9`ZtQ>XYu6tVIu7v&n2b!kZQuEfkm$>H-(WG+!9
zcrHo~-*vW3CTtG0GOLoe-=d5y%{0#I{CjSw$q2&-HtZK=OJ_COZI$x6D9oIN*wB(&
zxwD3}?MkmT8h4d~yKbc9ljLB+3I5zQL&P+LkvRO72)rn5Y?;DFld!UhZNjL7l;fmC
zk~Xz4Q<C<nMP!n;X%S-sMc(s)cBK0&H`<h?tqVd~+SIY));^VjeIzBnq^&(2DdF1N
z%G0Ld&LU4+*TKYdyHds%DbvASoXJe>fq!R~c8LnJw1=)hn6Rm%eo9qQ2E3(FyK>|g
zA?Jq!;0RJ+C!Cj9nP5~($X|ryrId~dAPFV*9|2{3CKSNHpX3a0$(Y3qAF&^}O#&EL
zlt67D2EigEXu~P)1Aj?a1~!Qpak3KuBNQTP5e3-f@?Y)vw0!7`l4uo8s|Iu<x`vl3
z3wR?rYz^Uq3Gc94`DMaCEXvpbA}o`>4<Jaa=3=$nhlWVQLZMh1X?~N2S3@2+kSq?6
z5~_mM6C1z|5+nvyTcKvyAZo;92y7_CesAa-2KRsvIt=OJ1>#{D)L1wlM=0O%Gk0|w
zG8be!$0F@>T*(RMXf8rrUxiHaA_=<WGj#r7gWydp10@Rq#gJSMl#~OcA)89JV<d7>
zAZ@V#Sr#FfBG8s&y-%8gs@Ll!k!PB^<Pj#1fMuHch9DD9p1@|4ao+}EdwlDbz%#ye
zOPCkmdL_u4%<k(ImdG<h-5kss>gGAbxpfLLC=i}_-)%TO20u$-`2^*(4eux3jWNKB
zk5Yp(rhtRidou@E5&<lWRuTd5o(HB>8wBrpwoVC^^K6|Gnu(Xmz)>o2q$A$O&$A&Y
z8T>v3Sz3e*gNdo0h0_$2IMD^>#AkVvS=SKmTA)yiGB((#)ee64&ako|#dsa9K#}sT
zM}kPz`Op9&l><k1e*s__kN^rH3r2_p&@$ix6u_1t;uauW2S}rUy3*9~+#8q|jUU4M
zG9c6yB-jxozlj@$Kgz-1?1kf9=wpWH-a;p{agzBoc80}feM~rKLGfEaXoiU3f=V+u
z*8rz>fE3dL;F=8r<<(h$YeEJ~T9btAb_6LQ;-qwrv*6*DMJi?_1UYkJ;xSrfQ36?u
zKy);06<D1)u!w|b7sjyouG9tq`W*#~w@5k1$<}Ebt{zNm1--WjIb{X5n-djJ%kMkr
zU)b{E8#HtqJdOn(2z%eLK@5gbFuwF`-EtM5ty@AOYNZ{Jl0-Z-e6=tUX@4x##Gs5F
zS<wI$0r<rOq{Rx_<d}wBAdZG97trIPBw}P|<YIP_2H?0qWlb}<Rtt905H{XqI<tUJ
zJU0AF14u<-Tn6RbaWD-oT7YGeLO9I>gk+6$I|l||8OLB026!hZ!I_&lVvCX!)r)YW
zJQ_}LYo3zNJW+@^8b35q07K@VjY9qa(@(IbG;T9$13wf@BtB{pq{?TcJuy}dGG8#P
zpd1@iD-G*~<{Ff9M|>^HpycG0dK7YOkTz^twq*zODLh(A4k;Js7b{n$!HrUkN-)}c
zV-zVHqY|I?E=DEc*%%f0w6!rsxHa6c^A-Lt{S*Ze9F)a7f(Y+~VoNyP3XPbgL@PF=
zJ`|d9QM@K8NaTY}DLyD=QMk&Y+`T@j5JI*F0`c^@dv4qzW#h&g@~v06D1zJ2<nMcv
zBvLkxEgs&_#xW28YR0vA&W#};Y+|q$^s!wGK%pUwlJVFk20>`sL_@%yw#fl0_b#^?
z5o_;)`_w)g(W+fGBFwe~CyuSh>5bQpdj7J<o^6lC#(efI7W?@bJFk+o@3SbGvv0FF
zCZ20QTtMk~HS@fAuI+FMM%){-LaLs7V-_jNtQXU-2(&ic4Iw1YvmM6kzpe1?I*duF
z!#G5$mwf~$_KFOz(|9drKW#gW*KAhId7Z|wbc<BC)%wbcX0O|7{bVm=2X3NX1`kKN
z%p%owb;pRtc3s^uqOo09cZ_Ik*VU6Fn%i}M#)#&2yIYLt+HUvc(Y4*~%WS+TWYG<V
z+}mZI47s<<d<|{oCv>SFagZ<4)PRB^c5WI=x7v-V)kM~Vh8Mip3>46hy4lt(m{BH*
zHIgz<09U0eP90j=5u}Ssqs6D|#*1^LD>|DBU{{hC6~tBCL`p)Q`yCO?R5ZIHkEx7y
z#Sv3s?Ti9GK2oU-N@=+{>-nx4cdIAp87=A2$+2GMh|~kS!dt1LFAASsC+2wT8I_9u
zu}FMJotPuL<P2rX#Dk(M)RT{n-p;h0<jbNfMw3sMuJB7fZ@MBY`2y-qXr6o~Ez;Xl
zsy7|Pcx`osH}XZcDADQ2H`_`Lsy?wqib3SluQ#oIz6^VFJ)<lwCyP|Qat^Lu4ResI
z0?*WrAV0igds-j%cWxw2sZY*es?W&GtFb?)`(}KA8?SHHhlWMCwr;ryoADu9WkZP5
zBMlD+Nx|>u-H6cNEDs?qZ<dFU7+4<4UeRTGfJvjj86IK-Y=(zq?q+;&i2P=K$eXeg
zDTG#-zS$n~;O(33VeQ?O0|-|-%ssvLt<RNzQeAR%WqxoB&&y<(Z<Ix1w}Ij5845F2
z?`57G7++n@X%JJ^<fn{gky)v3F~qrjD^|B(dTx!G`I_f$yz9MAgE(v=?enC;FUN9k
zoyHM_>XXcRwoWmUXX}&9(sO5Ak)cX{=iT1Dq#@3*MNo$vh)WvQYpuI&J;F}J1llC6
zad@jP!4NM|z=gS4BXB)>2}3etQ7GWJ49g^e*WXGM=0?KJ=B1~>HoZvPf62s^j?8Wk
zIKjgq?<A*&e!xl|Y0f+xp5Vk(j}Q!(!VNoo_iO8sssmE4KV{KpR`#c?{=G~W@C@`a
zU4-wT2i7Eg3HkA7>ysas{~BJ3?msv(I!r^yC!8HYVW+(N`_Od}9+N)kJ&Df_X$TXj
zT7AfQ4ZjTkpy8v^@Y1!@%YcFRGLrQVkV4i6?N#}J?ur?rpQ#VY27FN+CsX*9aEK~K
zh+eHeBpdPYUeE;e2;sy;IFKA?i@+80z&j{kTu5@6Jm8%JXu_u)cmP&7K*|})d<9Qn
zuc#q-3;UqIF*&J2BcAq0P{{j%59!pvW4{mHBk9@fL)QqN|9vPVnjX?VrSYc|wWIPV
zy{yE#_>>nGfEclZ;HzCEGA7T=MFC@QAe9jXZs9(gM2s(jDUTN%%zbvW@;kC=&-iZ=
z6&y9Q*94(>mq{i3;H-2_KY4(Y4E{(QDzgLyp@Dts@c@r}pNxfo)4tEC`9VpYGIplx
zzgHO`h6nViD+VD1fNA+eBvY>lECeO=S<X;IF7&BWBuyTD5)F|d5sQMszzDJ^j73?R
zmqMu!bU}2RPex`W0?uIcMjX-?MS<}g$08v}1RBq!g-3mZere$&)@ijl64c(lbY-9%
z1HpijlE0#deT1U~o{%C~Vrf~f>QGQizhwMG;7h+47!%TdNp(Q%Odufbu{B4+B;iZB
zXD*%s0jRXFmpJ2zk;r(4FrP)ChaI6n{nDc`f`t+X>Qm7~owc7CaMZ6_WklumtCkt^
z|CiXNepUPoE=|QYrHLTHul6Xae(NQHP^*6Hf<QP{zokIjrz$LdGJxv{Y%WtwSFrn*
zg$JQv{pO<*(PBga`&4|@5l~?#Ng)fjPJ)O`TWtoN<x}I9a3Hd6Q5dI!@V7uQ!}xGt
z-2<(hGHpNzvs(m4yLFrtx2}+g*9*)wM!SWu-#Qf#@YiqIgkTv2nA;vWNW`~KMHem#
zd54SUrj-amiv7-C9UL3|<cM_aWfF{7NFvpJGSrJ;cAtu;48%LUtup2^NE|=zjEd00
z-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNxa@|h?
z4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz6cH_a
zEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb#@^>6
zGjKu`wVmCRkbtP|033ab?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp;P*Ty
z{JcIYjD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z82<o}
z<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@=C<H-
zxrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix3uOZ1
zc2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^q;MC|
zfqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;6Dd)P
z0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUgh3AcK
z$Vc-^SZ|PpjLym*%8)^?ta4a52`~Ps3^}h9a-f<AC^^moq}q99j0ZG&qMPShA<Ak|
zG8r!=%9Z?mG?+MDVO&fW^h(=CLgAuRnqqv((TK@;s{~4{UaJI3ET4k9m=Ec#vM6J%
zk3f>gjBuYco!-c_T$HwDV+Mi4eTZStWY1iuN~y$k(<WNEM#`x~#;8{gb&sHHhn1E|
zr>l*jBQe!wxkdJBfc7&_HaB@wg(v2~dgV+bPu44E8o9LIxDh(n{bC#fgR53m0Vc|J
zOp$q*$n1?m1o)I=maqUG$PiwHiwVQIib9w`ma%VH(jzCOJk1Vlci)ntC&XDv(GzPX
zbclXM-34+gj{)yABr>nsw=C&A2Ykztj=6dl?gMO_Eb(xBD$U!sH0gXoM`;Lj%j?a%
z_G5=O(xKfk<Z2O^M!y~{tIZ^Oh)9ngKvMfEW)2y1WHGve>5v`Ig6E$~p!Z6eMv}cN
zY1(lv^vZ@qvc7jdRhZDfC`1Y9U?)AC3lw0r@<)NE@0COiSOFJ^I3uvU7brvO@!pk0
z=TNA;3rz?>2VSYw>9}`hSHlnPy?_~}x-fwopbOrA1ZG%OK=^U!5xsyJZuF{D)Bu54
zgn<^j@Y}cvIulbP_mZ_nJ{hESL_rebhEO<^vI;kw%gRsKi$!_E#>gKcl8LDsu`wVb
zI%NRE;c^ZTtK)EC;seiP5df^x(Mh*0awVOq-s!VJC6>euaYz-9AvjySa=+7+;yw5R
z56LR@0*N2UNp|Ii0|jLfIF6}a1MU2XGG~$W=$)o%g0e(O8T<+qgZ`kEJ#=QlIpF=#
z0^J;&pm1R4cZFaQYsNb*nZ%=66fO{|cX;Kb!vG(Yl$iv-i9$LM8Gz%sLOB7Ta|8)s
zJ*Hkn>oN7pzrcA>x$LlX2L*Rd8n(T%+hN9L?VnFV2d(-*XhjF<E7LhNB1-_Ah$V(T
ziC^SSODr*t+@;b01t}^O;i`ri*cEyTfTf^7z7vCqMUXxP(X=R*;dI1tayp0z^%RAa
z@WXghxK3M`Exlq|2`jZoL^^uZEw@2{Q>`WkjH|*0V{xI#jJpoxFs4RPs9YwPGFc|-
zQ(#)|0=fX+R#1pRmYUxp#aK`c)#cD4vX@uVKhVDxC0*tK2=hV#0EC#!3r3tV_t5te
zhK$9rK8aFxBnh8!_8<%yE(h1S50hq4@R`)N4p+P{Vb<Jr8(dekfH?+5!3!S_yFDQZ
zl1<p|z5~Ri=;>jU*33oV1Rh9L-X6!NpyynX#)PMHm9Zg&T~KmTFfKYAe+QB9ywDGT
zmFJ3ACZL`R58>w0>ScBV(~0HMK84-q&iKm2_lp{9nCH#4)q4(BzQg5rWDuY`G2{R>
z=&t+g9;)T`DX2ovz_<e>cFCWZSSj6ZfJpQLZ2*j-GYtC>)}lMDC}~yn!gW9rr@Nk(
zH#f5G#2aDPt76@!kRiRGAnx47x-oC=V!coSH|bv5J1{BTd9MPt(hE-_?St;RXi*8o
zT~T!e#B{lA37Y9dp#ZF=yB-Bk&w_n9+JxaeRKxF6V4YsT6#(>nr*sS#u$y^CAFK}e
zDKt@c8JvJP>IH!TRML0Kog0}UxWqekIh~1#`c6syNoPo0RrkA?4xQcwxCeYzcd8W+
z9(*nYKBQujawHI}yGot_DE6H)G2YzB1e|p_$pK1x{6M<#?eS6AwtGA0^A3;ejOQ;5
zT^CviadzJ+<P-sNot#2UIq`hmi6KbL-**Zb1H{}ZM&$KCd|_7-12Kr-DOY~{2KR1F
zixil%-Boshrn5H+mog=3!79JCG&&sa0A}8Pqn%nNe7cz!S`;$$hCC!t^fo78Nf&DX
zZ1+YW^N6AC+=x4g?88a{dg+})hGKmaL;Kh%Q_~`>HdUjY@+N$=xvci_LCo(>S`jd|
zQ?%hA^{w_>?u>%~<lAOxKkhgnneUWdTMP+>1V}Fu0o3aRAj*235&&Y~2@NkNoi+q?
zcl<{C;m9H?{5xgvm^(fSO1{oQ!p*xPX^2U$6O^#^JY)|++t;znc(6LG84p$`I>W(q
z;vYiV=cPa>e%&O*>)&o0V*1yG1l<3lE-lstsH={(1L`_tfq}X(S%l!o8<j;0>Jnxl
zgSx0$?Lb#K<GGyqCZCMxDwTi{U8Od#)B=jj2Bk~;$Rmr^4FN>4sza$Pto%?aP4`lA
zk~6+ce$t9qTB1}ZmY*o~iX|#a1M5_YN=-wli&EuS4MW-<qqk7^78ELtcr3B-M(L4R
znuCfaD|eJC+G)&?x*7#Qa%^P6qfXe8<CNwJMhxmbs#rCE%~mQl>Xo>V!C2CyRCSg;
zkv7keEq6Ke7_?O{0t9UZB|G(cSl~;&9u}izH5u1Cfs=5(6R?^ihMWJwU#m{Y0036K
zl30I64=EO?skauwvFbU-IyXT%KwuvZ{$d}j$e@1PwIbASJE8hmnWvtZtlm@aP*(V<
zw<^m3@iBX-P*6R1GXP6(Vg+E;yO{x4^|nR@qvL~5@=ujHs%Lu^LaKK?YbDj&pY@bH
z?4qo}l#-{q0JEzX2k7d>0lIp@?8h2VvS6@8R9QJ#M=FgVEHhO`5|pA!0}TWk^{QZP
z0fpTlz8O$OlMM@F!Kib9#6B3?%`P0;txjYn&DswkE>Om+>`<)qRmLio11p0T!mi5Z
zg|MsLFviMbWj#Z6vNEu-fLR*gSl|o>x~yK7=R7l@JM9#*^Rbp1ErBSuR;EIPU~T3^
z)@v)1Ba6DFNs>k1%3{gFaB0-cfk6%wOU(*%G>x(bT^UbVr%v|OBP-dJ0hYz?%1X<E
zcxB1Wl6ht7MNz%o9*oj^o6$IfvdXN?@_l7`W{E$Trw@?QtgIV}b_`m%Sxm4D;Vd{v
zQ~80Cgszl(mMtuMJ4+juO&-+`%WRJVi3g4QAa$7g`E5EmaOB_gaJarr4~O%ih@y_0
zH)0iiEN=yiLY7B^Wh2Y$fzpzPJR>YWS$-3is4U+K%UG8G1%)m*9}TKumLG=&Gt1S(
z5UX+rW!cU07agq1SzaZU?o6)}OM8}AiXm0yw?a(SA>S5@h?e&Ybw<lU#!{r^L}Rs5
zc-jt-a?x}cKK4=Gx)m6etlaCS(p{Gu`Z2O!2i=ng$5u!c*Tz;%71xGbk}ULkl-rWk
zV9T}1im~#3qNc3eqpCU!7wQ30ADf$%<!j3myQ<sLRr{&xxANwqK<=@5d|5@eyuz%s
z>&gPkTD;|3X0=}UpL1-G1v#lZk}~PW?pYYP+}x}iT&{2x7fxR}s}Gkio%M-bQ06FM
zT>f}eIX=o~&r-<c)^}i9mFqvtCs%L)3oIjm;P|L2%oSyTGR<2g0!uk(r~(T=S0n?9
zLmykX17psz()>qOnI2n&1glV27zLxtBGBUaP&Mly<ZgAwS1CGUmA|gw4OGWQfX9al
zXdhb?2&-&YqzKD!S2PK$c~=mM%6(U)3TuK_G>a?ziT6C~j8|9;ijf~%><q)U6kg+5
z&8h-$7>`v^Iw*|JNS<I9Y91-thXvMMfJ-dGULis((#|lVLxtQc%!sw#8Jfgu@UC(w
z45_LJCzO>xwlFAGp07wLR;O1W6${u`uoZvtsE8~_&6SGUauigl$Sy~*lnVcHltMWw
zJ}mfB@nen>CJZoJ%+6?~u4zInsz#url4%9Axlt@6*ouVWE#v^q_9~yZNVzoeBkin^
zJI`Vs6_kfas4a5O8<1@(yf38r+(Q5<@f9ZMD5g=dgxE{R7I5f5ugZYL)p7(hVsuS0
zj~rfCyyNl7BcNg;y)kT)wnT4?+f<$V21`2wFb|zj6{Q&m+qp+_I>4<E?im!uZNf8<
zM`*@vLf7QEn^C3S7_vDz!>OoM&Ja)q6}Y-c2wdeXuPyS`v%~|UV?h{<pFKcG9_T!0
z;Fbb$<JLTl(Ym1Apdja(7j%XF#w|Yf&|u#5h#y`Q<eDPJ_y8$`U>V;T>Ps++FHWav
zk@3t_h#B&nx_3rXPj#Az1?R2Gr$U8S#{(mRsbMn7M@o{ksrw$tz1~hM!d<c6-Wlu7
zfbjL&%d{j#jK{MwhR0Vm-=_*Y=Yy7k>2%R&<oW^1Joo5!KEW#jp3ioK$%B&N?57sb
zBX?QR_Ao0{K)!ot#D2CEu#Y)ABEl>3pT?BR4WLm*=>xRjWO@OOKAC-RfD(x&%21#Q
zs<If|hg9%rF;{{E9~{`!=!eoJIC@BraxQ2oti%l1ACF4jpcylBI~=*4mHV;mt4I#X
z7I@~m@?a~hBoi8zD-DG<>`GOk^_)+sBS~Y+fq|c+(q!m|sazU&X6Tr{^l*YY-@Q_F
zD5Ol$0eGb^yaQzYI8sBA7j%FWzo6tH2g+3?7<t+om6ha(onqRO4@8;7BRb~;jJV2l
za_013eEmCe_?0o`46mxRDhCLj@~)iO_ZQ#k&U}02YWZOH*{Eq|`k9W|!Su8IQODRM
z8pCsJ(i{eoh${JPkuq;g(!u<8rLg&6wwZ4IG03c@c@K2cQL|FcnO^5iCszudGkg3J
z45b5+t8)1kB}9tpem(&7GNqUfB;O!G@JLeZnOUokq%>t3I#a@@1OgJz?8GBTnfj?)
z8K%|Bb9AJ-(omO_Omn2U$H$&J>4Q0$IzE`$trW~fi4@Gi!9mz7wbLgvFll#Rls2{$
z(M8D7rd?#UGnZ0U5NDS5)P>3{ZKbO^47iofx+uw*j@H<-VVzmoN||-ktgp0MpU7fU
zF0M}?YFEathYh%LdL5r&)~~}RTxr4n8qt<F?8>*60;hayq#rxdt@UD=$a7N;^WiWe
zSE92k#ag=9#J!^QX%DW`q@V5FG|a+wC0OemP=d8?4J>aZdoN0;pG*jM<ye;_Fvq$?
z0ZG;_KHxSQn=DM^tCuVwXKs`%K)qoeyu+qVx66^F<Y3!+B?G0I%<F@qfgP=UeV?f0
zSXup!fW3~fL!%NVfCJpEa047Wv=ba>k?z7CaOPkOo?uZD?m_wnj)G2){vw1ipnwoO
z&yT`NaG2T)Pr>K2;Vn2K1Odu$fRtaJ)dgS1vy@5N@-{kZO$Z?32vWjKKrXIx1DJ4T
zYzu_K^H2p)1qkteFEk6sQCx@@&ctqct^6X=17!jpfTPeg960ucz~P8s6iCM+Bo}P!
zlw44W3y0@GXdsJ_e2{i};jEEQ#etgFohUSZ0R%$0B#zj~!Y*;<kqh2rQDQuVK*=9U
ze3pCb76THL%Ay2+gtp>HKNlj)`XQuK60;>JIU?O0%t)8TKPb;#@G$v9Iij(3OT?J5
zbqk!9v3)BMV`z9k{Bj}MtUrJfEz}#oh_@q~0}6W-c+R4v!qFufP__lZvnV;bw)Kk9
zwd#|DGueaUze}mS07TIx6a?Fmec&S4&bf6;VW&BHQN{*d<j}MV;Al~<Q4mNDU(W`U
zv`7gAr3cA{V^vs74lS?nm>ik;u<;&A31-Tq>(CYp{K-+igy2xCodcG6)|t{Ti0eg3
zFsPwU!Cm20`E_kLR(=6;yuhv;&Z$DgT9ky|>RY!Qf8TngFbI8Xk#YiXb1XuFZxO<4
zQG(@d>yzWB*VhR!pc<=w-5Z*iBfhr~#~hBbLM2<2KrV^uv#XWZXnIf}BDkQ>JRS}S
zjON5DAaL3dq(nxmV<2w|t5bl8cX~}+gtw#hCLs@w4eiY@Lfpw>gHU7v#s%SdHcYui
zX@jtH2Pm;VRu@D;+)-2lUkLbi(HcewJWx`jv08Ql+|{xJ->w#&_;y-!;@hdZ-6F*<
z60)D)fGHC4pTh@P=zu}-dxsG8tc+7IgNu+$dv3jw6DM11FoH5%lqDI;at^{8iXage
zB{p8!_y`bj(h70s2sW@qN1%5BGCENt1lkys7>+jmZ3KSI3F2Zca~%Av1tIB(A1|26
zMOkb)1qbWIrVw7G<Aq+BmJWYy;a+;;R|pyN2to`;njYT%g|X=<D^xg~4%iDpbuL0;
z90|}9qz&}b5d>erpbpE!q71YXTl6V@wGC>NE%FJd@q#N|l*AsT-yy*_j)FZUX@f>}
zm_!Ob)w6C=0j!Fk;=PNK;Iq1=Z=l{2%(Vz|g25LKP}p3^23%R`aH8mqe>Y&wj<=R+
zuyINhel18F#;pToq;PPHV#TX?kr$pWNrk!V@ZA?K?@s9&?n0wwUAQ-jI1^yB!U*0e
zLthGUxo^U873tdM9ug$f;+;|x4XI**siP>;j_$r8CufVM(f{)CpN_T9&)2WMrg*jS
zBEL?z^Sb?YxPJWSfB*3>ANFy+{wM$MfB*jaLZYtYjQ$>%UdU>@b<Ksjr^)g^Ss+d>
zk#700suGOLl)ad26|)NTYC9DGiV{txn31e;c}^~es+>z-Yz-yC6Uzc6oD{TXP_66|
zh@r{>6__h>dRGeZ24wjpnlS-iPvOWCUTK86sI$}?UQ!p~)m!=yU3G6-W2P$0C*O$v
z<pUNs+;THamb2^_l~2a^T?}B9o`(uH@Oge_^hRO})jRwG%uXHn1MdLrw6M%a?nq29
z#mC2eH-CwZ_h(@xyoP?-GwtWn^E6?7e_zs=qSGbO7i$^m9)~%PAXuO2G07sf+EHh|
zxvWAs@M1P&pb*{*b}IY=sT9W|F`qCb*P0+cQjxb_2rMk~DfG-R2ix6Hk4m*>Q%Yht
zD!f;fFm7ON19DWwc~D96$Y{}&BcvZ80x1Ni$+w0K8Hck{N_xBK8+Hkboec0s@UDN`
zQ-1ozOjO5THr<OIHUe(b&#(lJ4cknQlz!{30lw172i208pPVSqE)&n#(BOaGA%v)@
zLyM%iuR1_wqns_tn?Fe2FFH~{yE>BceAyA${1lh(dK#8w|Gc9%z^RU;%r85R_O?&H
z%lunA=NBEh!A^A~Wq#QazEp0*?}|{XjrsGAtb~qu@b4d@=sNgm$0dCGHvb;3)%T76
z^DpvzXqP(j#OPmjq?H@T$oDu~-_Dg^bmQsM&`pH<t8U%i&ZzG)!qlnti;g_praFRR
zU+%reTNg**cd68MDE|D5I6Mud>b~nZU0?j7V@q6B9<kpe<N58({YAGtne9?H9M%2H
zZW->z^ZR=sg}fc;Kkvq4zo{Dt_m|zy^X+o@u1#Cl#V<Nm@o07=<^HN8%cHI_qVVng
z%i-asx}NysytRHQi#AO++4prVZTH$QI=IUIeaA&OzwCh0-@F~a2bbRO%b$1DwW{HX
z@_hZpYrB2FCj|I*8~@^Kys}SpVtanwX}j0I3y@kD{V%#f9dLC^LOZ|gCYMi#yvAX^
zQGVGGwy|-tqbT#sj>2F}o#cDgntjt!e$kQ0o{u_Gy%}G1T&QQe&hx#%yQBsEyrYyQ
zS4W2IeR*jt+@4*h`W^!Ju4Vnaqm(gMM^O6tWygy!8OCEkAOZH}`2knE!_@!%LlpO~
zI`;G0RKoA^y4Y33pLe1j>Fkv4aemb)indYN{2pGXUHSY)r_@kgouWO?FFQpD_+op%
znc4A+Ka6aHxYZ*o=-2AQwX4J56}>6__~+fg7ep_9FSXjg?AGDZeaI^&)Rgl5i;kBt
zHqj9jKfmOdkGZMx-|6kX&M%ef)c@h#{I2&v|FYB7-X00x(>(q5Z1_b-zAlD3f}#|w
zU#Rf*_6S)j{PmALOHge1dDM~bnXz?z>5=Dp0>2)<Hkak(^^fs-XkYUmc>za@v9Z8c
zXcsTqqR3?Vq+#)>np`Bc3RZbwk5sWQQKk%zPg*e#mKrNk6)5wxpj8dCBA^jBVc~NZ
zX>0=y+lfl6?UcrO2d9zicD$2nPGR^HE_qR8O?*;0j}mgOA4*ayCWoPNwr$#^ocdOn
zH(Ao|cq0`nmX&MDs8xh67Kim!CH6o$wmN(c7~G~X5R_bJ^}eLUn^Oh;NI9ws;ES|X
z33LE_pp+mfqiw|ocM5}19~5h@s1H~}tFmEGV!#R?f70oI3W@xoSR0j5bOdBpsl`PJ
zz7JV;L{YheAjOE}l-(#`7>a%lx$6No%<_>3NN3w>OgeIdst%<CwYZ8``psIP58)U5
zW--u5251zSu5gXaLu!iFKwxPTSiupbGb?V={><{A+I@lb(sV`ot=gcnu&`dWmpvZ^
zLbU;J0FFR$zZM7`Td!b`lBpe$tw&WW4XccDnf+$TP(@!L^0ig;#eL_jyW)6mRt#0#
z{*C&e-eB=Z9c<;_24yShy4vB3W7XFn!~)pXC8n(CtiRe7m)*M$i6>3zeQf@KSk^u^
zf54T+eSdHVAeryjJPlC}SiT9R<;mfpn!@svRM^1{$lNMTEVqpU59rzHw)M&>?yjqd
zds3NXIidOw-mF9kl`|_RwL7z7PVG@RBz$R6+8OPbR#U<aTy#+%S{|?%a=R5;4i8~#
z3P`$5=&GM`F$MywoR=})R!$J$!?iZIZaLt&bqgl9T3#F)ZESAbJc=uE3x3>1QMYK(
zuYuE`$q$Ki)J0*20sPL3RNZoXZR<7?J6G=Q9Isj-5S3vCKYFWlD!AHTlxU#}{aau`
z$a6buWT@8r7E2K8`W8zNE30UN;F`*?`2~EVR%ufgitHK#9-3YHbJWhYiX~z-dNe|D
zXg0SVBP|CNz41iJd$wXgWBdCMGaGcY$RTBnDhbw@vN;fUvM8Ja%1)ZIm8I?b)+O1}
zw=N;@*3pXfv07pj6t!0ThjqhfE>G6fA`gtB7CCjMW)(q#`2JRL1lPbw&aGRH=G?jk
zOU_5VkTA@5b&`TFl|zI_<Z_!`d(c!9Vmkt>7J|H7)hIO5&Z~OG8VNAoQ44la*eNfT
z#AQD~S(0*UpCfu~QL57j^moR5pqjh_4i3hy5m`R}DDCMLSOn|Q$@mg@Y|n}>X%N&?
zy5<$W>a(j$i0RoC#FBpXvuz#nyRAZB{^IR|qF=v@1N)Ru{DSt(A3lOK0P>%IkW5fI
z1OgmasQ``zI_9Ztx9g-lD0B^HZ^c5uf7{LqT|48;(s<!Ru%{g42`ZVD6EK5Qr4>FE
zE6S+p6wp<SVTuy$iuw!>BTm=9Si>PH%RH;#2t?N}LPf{k(dSZDVaCwDNDOU-jsB_7
z*0df!3R#;e<cpGgJC@rt90`hz0D`AgYy_f&7lmQS7d|C7JwuIOBsB9wI)V_kZ;y^3
z6p>>6i=^a-8aEM8Nf(98n>i;%O90B$9_HRNBHLIZ1TovJ*pYuRg1^$8fstyDGz$Qg
zEQ-PaA{dI*K|V9?d@X)uUd=pm7NsKGN0c1-RBXH5w^TU<z}sEo;nCvsU`W3!3Oade
z_w|i&_i?6L1z#Y+Ad0RG{!DP`R<Ik&tl7<Aw|ruv;>!U_u<6!yg;!@(lEDwBx@D@g
z<48oX%#%7m3VFU2?0(|oQX>J(YqxS^CLGiF(!oRx)b{ygGDi@Y{`2G<DmmuC6tvO<
zZw|XFIp)C{C^;tekyX$rTk#v0u9|^3jO)>EMAbvPWT8OvjBQy@@K#+?Fz~*$>(Vtl
zCc0Hl(?mDLHlXaJsYsQ>^?-Pg1Ej@^ORpr9z+?%mq~tF<IhtNx!?hT>J9!S+CBp>}
zomjOiDI?lUsDk%SRn*~=J@z;V)Zeryyw2PxyQG4QIFam9q|_LyQg-A=VrN{s7EpB5
z%C-dTY`aWf#eTc8)l=A)!vP%V$u;F)qVlShF$xcUn+kA7)|t&mmL&SKx74YWY}-<&
za%xsqt&x{r)~pNew`eq`)~&Hk1-`;SU}f<_rbqZeFgC!Q+tl%Z%E2~uJfQqAYyEvH
zJ8)6RIlMSbCGS=`p((X0GeTCI%^aKJVo?kl#SagVl5v%W39tXuBL>intj3s>99x|*
zfK6o;$fSgnPF*iZ9f<;yCn?G926p?!Dwdxgz|VWN(a7m2-*;j*I($48Ih5x-K+3Vp
z%I4T%Q$`vfw?&ar484PL*ZlI$W@SSIE?AUxJxN&`rV^z*J-3zCylz!vwo@i?yqajl
z2|aicAhkN{B!2>x$tv%t&qGD2KM81LL#kE47nxig1S^XA+4ze*V~m-spF|bP%HoK$
z11khO8i+ukbWvhU7kF(T03jNW>Evmhurg1<J8r;v^hCFeHqs3h=pm-V@L)pQ1cr`P
z+EPDNeEu_Y=ws6ea&nP!-rAz=!L+qQftF)JRt|KWb+ni(AHFdf5DFl&AYN^>a;Q7J
zK(DwJ;t8DiBZ5Sv(0c(4tY0_53livHQF0sy!4MXS2oX5jiAqj51q<9i;w`K=Mvl#K
zKa@QVZYFbW>4s~?^_qZj!zw?j#rb`h>mEVkgb7G*QF030=?%J&K=X(=V~+UgBqh6b
zyEICS!g5h_$jZ0}Od0b!6dGc8TnY&69*aVx2pqqz?E<)6>y?ygczXzFZc*ZE!j)T;
zi2R^=-kxX>IR%QSsis5Vm#i;WA{GE;tZT;^B&}D3W^9_ny3|y=GVm0?!N67tJ)$eD
zOXvaP@}eZf48piNvpf?4#=4Sw0TyFjFCK$xqMWURcrQlCH6qiPqG26b7Zp{L@GjQ%
z=r$OIO?h38I3eqWIfEmnlD)E=SWq}?z_6JLwK!^)S!H`62G_bAX@+x0;Ail~9wzX!
zg`JYzDEOp&mRK+Nq|`=CSZ73BIZVddw3b*e_#`|mdqF5sA__x^5@Ez;!lO~>W{#S4
z)(b&tD*BD!NE0JIwe0|uZIy5a_!JYM*@8ofAya>c0mTSsb|hlT`sK<>17eCb?VdBu
zLsofeC!(|-Jwh0<SGHpSro1R<#c<1#eC7&SlNItr^ztGN5JE<qt`#6|SyRURUt)wE
zWf`rj=9$BkVZAV^&S(+M4EBkBqLrVe=CLTLEQ%?>E;HE932jy^A^e#&!Bhex?L|4z
z9AE%H1HG#Wy&F($rffgpwIxpov<8(+34r~<&7<Ib;=-9y0tp?5;7Op#MU!8`p|Qch
z;mp`z;BaVcKyW?PsU{?5Bz`Okf$UP#G#UFBWkee>%?}j*rbMI;U$+4W4)@0f1cwMj
zAx6SkYDh%v4`AS|2{JN`7>hvcL>v~a5F>F|2pF!zhH+Rc$jB%DfRKi_x(u|F(*+lK
zL-segNa*GAOLUZ;Sh0}&GSrgBlz=<65~9fgAO@X?+KB6;3DGz6O04aOktw`9G>=8f
zUQHjzyRr!~5{hao$VfaQQSL7wVZ!<)pGePW#@6)dt}dK5bkrtf-aCauDhDB9tQCr+
zsS~94rhrfh34BoW>inTo-3VZLvKw02MX0+-E?g93Wzdk>1hEUZ&Z6X>Kx<VtXorW!
z8j&Ue3S+6wBueVVUT8%R)0u=MS+j>D!C4_kP``lSw@Cbx2)7k7B`hUo4+k>z9b(uH
z^a-G6<Vu?fw-U~Sprm|V2<laR0a!!~r7xG9B8z;H2qoLui&(Nvy@(~-)G2r80U%$q
z{EneV0qjBwi0cQaV3RKkXu?O3AUcS+G1I{ZBZtZ1Md)HP9fh)Jn_ze6!)_m+!bmoy
z+7d@ODEQeuzvTcWHlloED>iFwUlZ&)&CW*uNT;3I27TIr{Ssdnj5;mE0t^HkjG54J
zY5rx(ZUV%_8Ds=ar)gK7xDFeInQMfuPVnG#z@V7ibsaVeGdzwK`pasNzfB#;UO3?_
z9DJ|l>t8x6fe~X$9qvf2S`=mzL3glD>tF|j%_4E^r@Dc=2>da*4Ljm~ECUFSPr|>L
z?V#zo`pi@Aw4a8ru_NTitnkt=N@fA3^AzA2JTCRZoJJb2Dnp=07~pCH@*PG}Au1C3
z#Z0Gk*g{r27XrX9reeiMr<Ku~rsGPEAOt*=1Jg+kE22?j?gPcd%mfiUpcfLtu@5f1
zPWyo;r<vxME$DlJ^@1*(qp1sl?(-X*F_cE8(naia++8NvVduINC$c-&T|mUnWv1@l
zSy{&fCfS{9E#!7sMixaC7;>eR`Ua!iVS=FSKGh4t>RepfX*;cNCYa*{lgl5%>}h>7
z-bc<YEX;T37Ctq3?qDI{bmtb1I}0HGm2=Vo+7}djIc396!Ne1c#fXyGfhlN8neQ+W
zY*~Mf6Iw``9W_%U4{(5B7!EiAP((YWw0E4pZ<Juo`ABQPW8F?^_8p4ZM#01W)IEy#
zc~EfJ^chXoj2U8AQNXTf;aM+O0KlglK>~-72(uAz_X;rdCn=MFSUKKF6VoO?^L`dL
zn-+y_E(yX8qb?430AcJ<)3znBZ{vry76~^F&5hfdoLT@T%br>QQ1DW-6PnHOqExHn
z)w!)09+^Akl5AoP1Bvu_qfD^@+k%F`jWRTAENmM3jyF==r&#LN^)K$BszEh>Ldl~l
zyWrZb7Kei`p(^`MY2q+N6X*Ii3q-VRb2ocyoj-E)M7Y2^iDH%OkpI})xA=*LJZ}jW
zH{f||PLK%NS>7mbf(4*zQI5pCI3=?2M^oFsDC9$qZ(y0!%=@eM$vGs7%t&@|t|&YU
zaH5^g7HhDPnK=G|9A2m5*(9AJkhgJ^9zg<kvG-3CdvQJ>R^**R?!s6Yz!`O}pC@j5
zq2iyX?hoWLKk4<-ZPC)Ga%@*h1KPU@F1gYVmAZ}ilKe6&>upyKtMBb!f@5s^(4|W`
zq>QEi;s(qBVAcn$OOZtc>*j1vYErygS$MGS--Fc&%~S&S8R8bQ&!4(&k>~x?b(^=~
z!E%Wv-~pCYEIk5s7dK^N)nzPY1a%vaO=DqcM>AE^ecGnuw8!4{p!S$Lz~0oJQ+f~?
zb4m{)Ytph}8EevRK9{Jm9SwoerPj5Z&n22q18xIaTk<8~HnN>e$$}HdrerpRgqSt7
z-qq3o<2X}81`A+DDMax`Gm5D=I?X6jk^#?AdURAFMW>Nd<XcJg({DbORM7W!<<|ln
z!c*hNXFHdWhL{Er-Fhj!DDke~{F+`qoL|!uMiaDp!{AG%Hw;$wHojpv!BcM-1mHK?
zOB7Vu?vuT+h}WZDnAG*C)17B=qs>GJ^GyC<?>$V6Ruch4HJVNMWIWn+sTbyzxwL|}
zZwM_lz)m&9jhZ0w7iAntzzn9ka0Wx2uqqd~c@_B`FdAD``E@?sIRV$xJ-6HCZ!h;x
z<`Lm>e}KZL{J`(_AB+SIk&C7h0u8{qi$YkHi_avL=e-QwRErnDibn9Sm3_ocur0KU
zIpV0bd!6b7mNEd)R7oBIAZ7bFUZjsQj;sWx37ZQBH(^IL6~&zwL|yf53A7RBoFv4*
zIgY6g9LLm;f>Cou3kZyV1rGs~txSLoNVZ`m#80HI+;Z3`yJJnK@WfT!bna$!g((tz
zWhCWSs)BiL(8H9UsH}S(n6zlLDqw!<Q;^FEqj#gS$4sU&%QBIv47X8g9_C++htXhZ
z|2;sOu;wOfkmqiyU9wV_vR6kdJE#=-V8kS=pS&n(yhi`29s}((uIm6Avn=F|h4ada
z-Wc5_OFMI(V2%%p%Noz`qO__Brmz7K+m!g(ka=#6^}z?Ws=Nmc=8e}X<{tpZNGHOe
z&r3zV2Yp^cA2xOp;}KlgSg^5Wd{a6|FoTm`7qqg6cKQI4ez{?q)7ni(&7zFWl@r-f
zaMa|C8K{&GqXVS0c55fo08+R%3{+~`$%qUIhg57t2cm>(Od|@!lz7s7st<(SH{Tc(
z51-LY{yY6*bmBLsc+ln6oZ>;ZTyrl^CAdqAN#h?R_xU_(S*Ef4gU#vrkk-$Hs&G7F
zLh1T=G#xytyL4Ni*@kN~wf=@kj78$A0p~(zn3va-Un;LDwEpHe*5#RgQPOjrT{^v{
zI-)u}rz-CSK%FDK<md*gi?W^?tuCq~);c}u(!V;&(Jj&dA$|W+r8-o2dHPqTSTd)h
zm3%2R2)MSUdTMRiWKeAlsbw3QOhYJy^{!8N`a3&RkjD5e1vfNgesAby=x&|o1dJ<v
z(A~*QG82Yw!$b`g@EQZPy7v5!uvSOwr~2SSr#g}OxU7{`$NVo-EkNXd9YMmpu?-2L
zmX!SIYx|r0>HP1hW%sJ3o-tI4pJ_CmD8^<bcHM}&f%G(l4)z>au>R2xFwW)C4{$ZK
zr2r~x9xuv<mGHAh)fJk=pUu?~;PcAyVyF^-6-H`jD<8YA3;r)bQEdx~;?IUL%(YWm
zuBYc24-I5RWAPUl4W%u>Xegy-ws8F!p|g*Mz$cedk6K!$va!qyGi8M~20y7-ZA%y2
z5v0PsOIAX$Hb&Y>kIrZ)Q#R_#7c(!JXEc<;?ua!*OsS;g@=>B04;A5kkwTW^VpKSC
z$btgCK_NF~+_v;)nTka>c&Y+ihVX2R!n`zNMqxtN#3RUvv%$nN#9JO9<q9!^rP2DP
z$jwDzI3*+_T``8s^$1GDgK})p<o(guOkt!0ZN`vdY;=6OZWo&H#wp%G!i0O@U}v$R
zyW~VhsSOz>U=6b&jTiPj6XZVg(Fz<4`Dn+YU;~^tqH9n6MMlfQGt~eRV}lAOlF_Vk
z%^NL$gTA;1bgM<dCSZV-(%2WJ<8P?P&=xrK{yZUj%7<?Nk+7k&{)G4qXVfxt)NB;~
zAZ)fna(==}uR!ItOoT%(wX>%wT8aOE#V|xpTKo-v6|vClv@*7W@G!W-XqB6^<wc4X
z0=U@=@hg+-YXGNRQQ~-280}}O(y=HVlv|Vx`=+geSy>UWo_sgPE=?|up|DlOzOR(4
zIK>nnZwz0Wf-f*Y)>iEOO3N~pJh7)UR6m5t0>IYh#J`gX^IO)fVuF@Ua@QUvHxzsE
z(3_W-*(wuZfKj*_CZDMW><?2J7^7WIrD6;a7&h->lqpSOVt&x`CY=R~5_5dSg2*SD
zc}&<tx95Dw1n38s<N;U-Cdg9*?12fZ!~kk=nBZm%_yl%IXl`6R7w<%5fMu$RlQN=>
z?Hn0lk>A3{sxg}CO3lzvmUgu-5^{KoZ!!i~DeuNmjH}XhRti`SuWJga!l=Aa<c%Fc
z-~=Gh_%PI$3+5fBjM*i~S;k(aMd<)3GJK}^g!}3e;OOnba>PpCO!CP=A4$qNUi>=b
z|GM;b&qOS+07*W#K8zaIcHR0iuC(jc3U#G;LB<ke!LCQ2$%E*y>(RGhle|xT4BOy7
z^(|w*nP!>y+-v;|%}i^<{7ji}T(C;0<BAd2HUFK$em6-0lj&G+-e|tOb!Y(#fD`|$
zgtx_EY!U{2-MkutW6_OQg9XHYtYyv@iTP{2p^O?T2`o}fF%#`gV9{JlyCoZ_j6ejo
zCGCtAyRZ0zsoY5p1TUjofVD`oGlE$M1$my-#hGVks-R~`cIWp0RG!`I7(px3h6_OX
z!pZ%d8cix=&#A#cwja}AAli?hV3>$!j}{;4=yAScouKUtX55f{p1HN_^=y%SUfH)i
zAu2<6QF0QxkC1AfS-zHu=Es%?YyilrTw&(#RX*{e<cD-SUARmmF*yjPtYpqHO+iX-
zW|H5caEhh`=!_{d1i=YVo=36?blxsp91jhpNCh<g=Tx(wTT_HV>A5w<G&DXs7f>Py
zO2=nhGWnH<p*u!+@P{ryWDiC@I{1R>MT^3pNoazTVQPjdNGtChjG37#52j22X`IwG
z<I?oZz=tre@Vp}kU<wS-i<0O2ype)0X_+@55F{=00<@Rv9Ppy2j+d025rgP#0u$rp
zV~L512Q|vi#P1Yr8S@rHE5(3;fN@STd;;lV7Q-hn4(8SiK=0%?P%l(S!T<!;;CDZg
zl)wVgQ04$fZ!FUYSOFa$6A%}QA%J3*@D*Gr0xaw1Kn=4dkFTN5S(9hhSPQK&pvofO
zyvY$tMX||=X=&(hj5`bE@@xc*PhNFmeW+6h-bd5o0)5m<Cf?A)nVs3JZ(RaCMVALW
z3Qb-s%WU?<J5i_bzcjg*4AtnGoJWTI_IMVf8&EL<d4)Nj&8D<b#921EY7F`AiSDvm
zIg(2sL1hU!RpJ!@JQ*|-y5&|E0AiRl)d@%pV=D*o)VNHjHq|BZicYi=3+UWFlJGj`
z)*}wo#MePa>W04)Pn^*<jGjfg1~7b>uS$%cBS~We0b1<@{poC-LJ|Tc0hIdIBjl?f
zi3|>zCiergU<=mBGN-?wj}~FZ`Jns;8;M9Xwmvzyxpm3`&aF>!ZR*`Lh)Q%-x3u@A
za3Z#~H3`4~jF=Ko76k}T_tq^Dl<uwD2>WAo%JDv1pB(SQ%M5|Dv}1y@epiW5hGLw{
zK#J`@E<k1(-KvIKi;I*8z`!xBl&?h@(Z(@@VvLIdCnocbTbFW(7~R%c9N@z6=nsEU
zWF-EK$9ZD5bVmoA>z##@06W~eGzECY8f?Rc;-{+(qeB=05<5*@a_oA(j)|e`CK!1W
zbUq*k(s7zH7-^AcDn9q3g#8{@)EHpB)B;#ETEF$COH78QN_Ykkgm5u{D*#Ojvu!48
z(?OB#1W<DAbr@Hc?}KuY_hyp`c2Qz!TuVN1$13I3;2dl+yROvm=2QWI0}<{V%+CQO
z*h{pW7<ycBKrnf&I&evyiw;aCl~X(n5!TIX*>Q<^RWNbPS~@^h>0OSn#vjhJ*;N|_
z2Cb&FYJ+RD$=3O^q8IRMH>F-1&>foBL6LBKDo<&M=58toV}oUUWD+&NLWbuM?PSKS
z9e`WNWygTyw0Y^0h!YPtrpCOOp?rJ;vc#f18elME7-Pc>9@wT5qPBi@$gVYTn+@Fp
z0Ij6A7nHd6N7WHY)YajV9Nc=t#Vx=>4Hvf%1<+KDH7uy%#J)A0#N@2KUX-EX1h<CV
zv^34OQEQGXb<}Q8Fw{|-onWYUajQsE15B2xOK|hq_(w|dFYm;%Laz0nb)w_yp49I|
zs3RV@gA=*8JAs_Sbw6cGf|I;Wz5h3gIF&lV?A%gnPklNTa(3~F6sr6OE$D4Z=NE;)
znqawgofl<lxFh*gH##s{=Pb@7*l+PA+peJ{mhM$|1xfeDg^-tdYb%lR6c<8%P)qjM
zNM$J;P>57Cswiz6;1V(-+#E&mZ8#xgmv0PC%KhWd+}lK#>2^h^Rj2s&Z9k6hwtZ2a
zy|zy-cELD_GKvu)G56TyAt`hFPDtJj7u2zlu5G<TVDGDzG70-6L+o$P^4Li_Gcvf6
zyD?g$_F2YfYA*)mkwaA5Qy^eF<$m6__(NOVMvye%V0i4u)8lE|k+T-<Y1`Qm3-a`8
z9SVKjj;*I}het@}<J;jI^8EOA_NKz{IC-08u-;D9VT#{<r@SA=2m~gxVh;m;PG|Zv
zH&!L(DpoD|dG=HG&ROo~YzRl$TX@Ah`!Smo_6RX}>IpS~d#(#}v1bKc*JZtyHNvoU
zUoLhm%Eg;F#3G`^b%nMOgu3F_7<<`Pa8<5&^t$20KhS}1$P2v-Sur7Yx}X=S1T4zX
zc;}fFBy}{W;PlhUT$D>beY^7SGb>Tnm4A;!fZwkC#mfMN*NC4OU_6{hkK6#R1&S-5
zQ-9r4BKmo;8KbDZ-IHteWJ2-fvz|;SC4ZKO2Oi5#=*~qLkwwA9Ky~IapunZsWk5Mt
zAf+opUKL7C)h`Q%RMk7wZ10K`f2oK^G^tbu1FWuA6m+(>DXYN)YrC?#rfl2Qikc_Z
zOI_{p;l63BS?{%U)tIt*b(vW<*0(-6W8Zp(6qt-@(A&G!k^_;er?CVtfo^kqcH|`I
z_Ugz<UO&7#dS(;zxs#K;>e&&?YIUv;OsZbX?=|I)ZIy0LoQqU%Ess{sIfwgfbI$E-
z&o=28Z(3Ej9_`$^#8}(8^@y=HJBs~TE?Ke=<!)qDA*-7nOb?1OldngnJ{42Xto2+>
z4K}yFJ>_!Py?B}@%w|@}0^Gj!iSwg*^$9T%`~x4Wy^VUz4GfoV;@5+>3#HlsvfmXm
zY0$&F;I3`J+!och_3BTyUR$?h>$P=D&fZ(E6*AG={bnkNg5l~D$5wlGd&G&d<7_|q
z7t&}@Zo8jbr`U%5RHqnRuM+~LwHYmV1nC;c@yovm#`QWRZe<BZD+ktjC4^k}4CkY*
zC#13WtxvE`#ue5b>Gh3VQz8o;9{`XG5<3NtHUkTaU~d){)V!931?gzLkF8UVWp164
zOH-Y4EOYA<@|CfRw6^7FE||?xnObpmVMC0cDN{SDPWM}VLR`B5tPFwROoIg_e&$i9
zWJ{UaEi-GO+u&`rNVKzOooB_tg%x(Kv6rDeN;tboKSgGKciTDz6TEGmf(K=EfepFK
z@Io7NFUt!eO}h83*HET%wu1>?ruO)~?!FtqLri@)wdc17TETtat?c<--5f8<I>LOS
zksp=5kOu#*_%lOJK`#poAQQS@@|2=RN*89HDuj6z8jZ`*c_ZL$*#*^i&{@(29Y}{t
zFIx(nF5REa;S&q3cfv&GV^>)X1AK5Fbj#s19VH#PSNbUFU}3Ue{Ev#Y<IP(ZKjUcS
zPn7TMjuttIgs?u!ah5uBAAFz%jA&P^6<vRQl;bSV&z?v30a9>jOgSBcM-@v2H)L0J
z7CI^yg-=<$j{D%<4~ORhfS^d?02sRa;W+JsmhuD6)jsH0&F|=9zp&d?k;VZ0P4tRS
z`go6kxM=h*$9JY)dO(Qnv+5t`PF`>to6C6_@cJ~lspC^qI~<PdKDEPvSld;whyHH>
zeH<W-zyZmB$0E%t@(i`T>@EoK>64MGb|KcgtH6*UeX38K{(z$CQ#Q6txmr*sTiif&
zDJ=krT3x|nz{l@pi9vE#pVAjEY)7OaA#5Qhp`Cwa{VlA>z+iRwBXp=&B-oW;F@56j
zM@53w#?U5sU2z&Yq&_Q71KLJm^)k4q&ytvY#P&-916`s5zfj8oxH>t-*w9zW3pVtn
z7bCLv`b9hZl~?~IjWDe^N01nFfn9qw4G;JF#m5865eC{2+OZ<Jcn3)NE7A%9@zgJ!
z|0p!v5!97CuVT7RJU3L|n6TRYQdkCxr1UL>E3eKif-5e{>pIX#PV1~kcvQb635Z(i
zmn7lN3U9Yg8x*(cmt1Us7VlTK(o5AZ9UO@7>X!}<27wX#>XU(D0gt5^u=rIKp=YdF
z-(t5M3OQo8P<E|sZ$KC$bl0Z>-})BNmG@A_b1_;j*7Vjva^v2)^?*PeUKg%91E~5<
z#Gb#_;|`d3^nw%uO1|Gs%)$MI(nH6m!m4_Ohan?*QOKPe6XR<oiyigb(HL38z41Th
z&}9Ea;U<EzeJZ+=z->thCv_JpJ>xXHkn0UquKKO35AmLX8|S37tRc_CFJeZ!0?Z8M
z#Cpb;Axx_SiQiC(tqZFk@vTQf<0(=$7esGYM9TJCD(nLbP{o@)2({`JaE8dOuHplW
z662Q_DB^niqj;hx7~LOX(Jo2|mCTulFYXUdC>RR+)6j}3K8=4ra40;oc03b*qYDgJ
zj*G&-!4v3_SN{RdBk>wPBQz@iNN-NyBJ_th4U2bFZAp~($Xf3VO@~VGC}Rg`5M4oB
ztS+)B{2N52^+)Lkh<0+742fW;GbtID@AwPi3Lw&H5r%@|pCllZKRLVz$WMSVZlQp>
zDC@rkbZB0vtSsZIt&+uO1VNe^0V6<6nVgV<>59i{X@on3eVU|>Kf?HKOp&cSCdf=~
z*yI4ZdVthpiptmm0EnMT#{%@lLUUz)NXn^aM#2G7&QW=o8RxVJOklBqmaY7dHiR|%
z$q1%nE3?ZGrbS^sNCS5(S0yW?o|UT7zh#@5sL1kn;SDjYiIBRVD$(RbeQ7Y%Ibc<e
zW)y};qoXubwn`rSUN|3!a&lpK94pMp1<%0(R4$y2MOpvNjjdQjp<e*Y&rM+>4XA)#
zxD|+da>1H4q>sDM(OTN*h<tn`CBNJ>x_orFpdbt)R7ej%ZggTh9EykX!fmhzU#DK&
zkeTj6(`(2@Ck*sw)+Ni|=39zUP)_*22!ry1GiWU*MUii?)Og_#v>d1x4gpMdUZ4ZO
zFL#v-YYo6wZk2E7n1W;)In%({PQuy)RvC%;3E*-w<uF9gZv9Mt)oDdtgk&FGY7J@1
zj>NblNm&E9QXO;cvcnDTKH~R{Sy!$i0-_d)%as2LOmlR@X`rCC29w;PKx{f}JuX0k
zo`-=@OIJu!Frp9$fIsc6vUyXU1DX8*A^6ZLnK#$Fzy$#M<w9?5fCY0v2`pB@Sm#Z7
zi(#yD;l?r&$^{$H^Jw-a!Ov{kBSGph8q~rTux;xjTFl)Ip(<Q}KEPdhZX-M@M(fd<
zIX!I>ghqLx0Kjm!DCGW?ny4!>Z;|3)s-*vZ<$`GE099^LkTneXXhVm5zcIfdK4l9$
zdN9Gt<fZs1leYtbYmt!ej#|}~(9f#omC}#HqEh+|3%I59N7-*xbZoHYdAsU6`LmVb
z&!4??IHMeZ3v;@`Oz4Uv+<%#w_6@wd(Sl&y`cg}7GupHPme2(?-e3`Q*~y!Gw3sxA
zwAQFWfhppSYP__N#_9@ATtQdC+=no?&4)UHmy|dmTp>}_6~EX}Q>DtvFU*2uo&d}n
z;2<3a`Id#(g$B>~D(^fL9ELGh-Oxn}Zg(L@Ij$fU8)fxd7he6M#52xe)^C|n>Xq|9
zawc9W|A-awO8G}r1*(e>!y>yC3JDIWUMM7{Zt-pWSAG~ZS6%U#4gO&7f=_}U*Hs~a
zm5N<n1ynOWvZ@Nc+|{k%KiG}%9}tl)^pO;i!wWAUjgTItWg8q&uHerG6Qm1HAVV;n
z=ijG-xE2Y!CWE+wLQY)lMLt~Wgm-F#JH}NTmu08D7a9qaltLjutgoZSZv4=rZXD2~
zZXD2~ZWs}q7>+aeNK$r_Y5=pNtCU4UP`7uUXow461Zpw}@N&3a7~Zwo#PDhAbn#Ev
zr7(QLa_Id+GkfUFL+HPE9dWQRE(*AXLg$`W!T}Pyfm=vN^@37>CEYs{$tT6)DrWKA
z$Q~4mTf?JJ=v<sUGHwm;O4E)P2E)A6Ex(+KYe6#1TVJ~P7wo}%HDkiO)AP)jFjt9{
zHYpH7NP)?EQ8r+y+;og)XqmdS2!y^e^&<3@sneCO30RiB(}2}39t%2#VMX+Wg+S7m
ztIkZjkVfn-jR^(gydWK5t#uT&ZdYogt`zrcstZA1U=ei2ATI(saj<xVxK7Ut8iw<~
zhY`f(KVuY}yUtP=1)arx8Y=QF0+GgYDGpajpg?MiKjHY3gNs5$JLsb-EEJG%(MCRN
zgEiC(lmbxvi$VxH>|*a|g>cBVw;=3R?4G;MXk=(Qp)DFraIV5gEsc9FcVM9D1zS3F
zT-YsL<&^@D@64Yqguaj!c@f*4KT3!`)F=)TK0MTgpnY>yG|PYGr6w0-gB{H?7(B;y
zK~AKLB4OECItoF7?$S+fu6aG_ZZ5hot8T8kE)N(ET~*;1g}o4)*kC5~!t!`dbps!s
zTz9<{A1=Gp;4};#K_Xx!*L|RsOQ<U;4QlSXk&sdEt{mA#%0;9y{c!i{)<UYL7qZCX
z*}}-+{&g3~7VrZWC4ZE=UANrB-7W?F!G0gw-LTOG35<h%N&qI$1aEaUJ{Nd91o!cT
zdZ(!V29w>QkdwH)69?tNDXmsq8>>2B0kj5V^;URrM7yrq2X+KOsdU))+zEovQEbPV
zUa*4xQoL!3>}k+*B@V0*zvSekpQ0njQly}uSN<&Q2+j!hMRAO-C^!dIX$G~PU7q$1
zgWfyk#<wS?8G>}YQ^*{E?GEt<gelel$Q;3dpd`1hY=SYDSVibvSduo%EnYof459(w
zNx`cqGjVeFMk^t2orp9YxU{bHi(|#?<;Y3uFm1W&^>v`0zEg6j3_UnHEKo&SlpGjG
z3dqWLN^(CtTs%wJ%z>zm5ll{Rgq%=xz)QVaxU=;+*oZa)H>d{PxF3sh@nY2U8~0yP
zxc|gPR4d#mPp!rQLW&XBr=MC3h+aRn7^L98=OnxF=-Nq`B(?!E*xo6S65+e&o9Wm|
z+;kT(-otLQwa5a(ySrF`$4c+61;_61F0SB!=!0Cz)4J1A1Im#kGAhrRKE)^;PJN0|
zq+HnoSFU1|feV*}m=x|e6||ydCihe4{W)nW=p9ew+K)Z8CT-&Ws1t+*<qC9K9I9zh
zCko0QY^M+nF?DtUJFHH;gB2CFa}iY+-YGnq@>6|3dcAWK>d5x44p_8hFHt}f!l(AD
z!d*uhl$!2CXBn2nhmL)4JJR1a*?>AB;W)Bb#j}fo*P-(Nv-USV*X=m67&u?Q;tcB!
zs#>BxNKFmc2HFF|cJ-*y6C1t_G_nT1hT-<V_ZAruYiHg%&pG+##Q`#3@!4AXSXv@Q
z1%qsSX^r8%VuJ7%`S!lv85;O{Yt!HT8=Z;o*Ap5t;3`+N|K|N14VhDaG~|Uc^c?VU
z1F2xY=9=!4cfKp+<kh+WRDDe?0~}rrKftS1Ho*Y2|Fs}S0`6ZMV*nNp!=w_cz?Vzo
zWvuZpGI&sC9qcq~stO=zV{ubZ!lE^0_+iDtPa+d;&{sk$Z>+_asFX%)%kaZ`THF*C
zN(YuL$H><%cCNAb-kITO!8%48A^V*p4B7AX`-96vTH*!Fg7waKdQ_=~1DNMjNa#Sc
z+w&e3#>RWEghzbo-${=qjx*3W8>(Pvk#18h^naUbVUdCsV2UMhY^nm`^u`{lh7k<a
z;s~Z{aR3vCLy(LPx<hn09CU{e={b@&Vv6K&07dv7OUK?kSSYCx9U?m34$x!F$zY>F
zhsZQ_m<|!e{|-7tbow5fn!c;cw6>YEXv^SM(jxdo<O@K;u#~XRM@^y6-dG9tHk~BG
z*Ai$olX(*P&E|X))=@(!*N_8zF%>I~ENWAkcZZv5p>MB$M132qgoD`dp<3+R`0}bC
zG2H8h89wE_sd=mPa?h7L2RN(O<8uY_6CM79z9hU^->gLC1B#>91I2uKua|1L({076
za#YgAAJg)se+<u&hm75MJ!I@ob`F1oi(2`3fMc6OSwH=JIoycNn&VBCcT|HPqr;Gt
zw{JvKHN1?VgH6V7(7)!|;R6mfS)0*S3j>a>S{QK{D^W=UAvKl8m<XwIrvi8Nx?4xk
zze@cYgG)iDxuAblrb<lJ!c+&{tFlC5@!~^PMzU$q^IYY+_Mln=_-PKQvB0r?2+nau
zti{IRsgnbJApOKgf|A26k5Ln6GN$Gm_NLtX1MsgYM&S!(YVhXQ)=R9{9LkOtP%wjm
zQscBNVQn9-4?4OsL23>f-Z228zHUK)hk9>H#^LJF4o@G>5F!q!s4J=2J@mdSN8O?O
zUHkWerNR8m36gqvVFUs1syINX8(lmN;JDt)sZsHsy1gROYKqo+(5)ld>v8sPQ-Ll_
zw>w9pmnW0*X2Zz%d0=Pgx^5h7Ey|~MxV1EtYO#Oi9EO%L?SuzskFOlVIC?0!=Slzu
zI4I&Ov?gRC*z>&#oyfT}m2?@az=DAX%&|PbvM$#;5YPG*)J3Nfog>vyUgfrQVrBN`
zQ@6Vl)eQH@wov3{Z@uJ1ap6w8zSV?r)l~6ZG#hVoX=TqgvsBYWT-P-23A6DscRwfw
zZr|B^7$LfRzmmGqUg|vTkh;Ww{vy!Ud(l6MMiUkwF<a++;RT4wn!v$4NE4n9nws&_
zG7N8<Nvbt%XvAC`L!$;M;Z&mENdQ`s6CqdnR62<SN);rex(c?enQTeV1XWhzN@|us
zJ3N*9cJ_j=@Bsjf@FIJ5A%u>eL4?rJGhkQ>D>LCo5}aoCnNXVtx$RpadRQNCQ?Zki
z;4!6=CHiRgcXf6`gIv`J4f3yQ^=Qu$aY0*y@!X`k7Gi~XPKAsTcr=w^Wr7uJb{@ny
zlxKG6qlt98Qz>6K7gO=8S5nhP1n{iXz?hF*=!VZ<G-4Bhol~h<`7$TtY3CPu>{h;W
zg@nmdIejMbl)Rv`DfAexUuL4mcsQ7bD;=TRu7r@d8aC2~Ok`A=NE1RB-Cwla=S$K?
z#LrYL@<i^Bsq9n4_)M|CO%TP;-f7Ox3Jaaet~ISn=-U#Okmc%pQ{NUBJE0wf=1c`+
z=PpI0Bl?C_r(AZ^=&le`9&t5Oi5|JBCKeN~w$@$?z1hG%Qo{>iIZ?>oH|OxMpNR8s
zf|lzAkwOtYUqI7I2%CVY)MzhOl}a!Ht&0+%QT0_o`_4v>z(kq}Zq0xBjYyHZePe`)
z3z-@GpJObKWy1-T*3U<fB?4247NHrLsO3dT9SB=fXJPh<H-UEVI7ihG9((i-i4%Jf
z*?9ywkp>56hRE)v-yj%8#GyD`Jt@L_z?p1_@Pa2f+DL!N17m|^NKz53Nv**XuORHW
zDIQ|$xOcNd6s)|79pnIc=w&F=vfde76N$A)_Yuz@TJMvAAcv=iiF~v}6ejcojewN`
zZ_<chZ&!t+RI@v6ZMZz>m83EL7rEO;@OVO>-3S>Pli?qm;AZ+0M`-0v#(!)L5U)OD
zOH77;EHYEgS&<s(I$}RqsGezuo^SLAdmjv+ka;i}{xQ`3gPv(ao{avGiLhFp%jz;>
zuEyA!g(3rM@XEnY!~<YSYK~}MKNGIVjO(eMfWl=2eHIf;DkErAPq3AYKxEkz(MU8D
zbJ;in;gjSaE-Qh=9<E*TvUIp$DU&Q5&a?X@pN8|OK1rA1cmM*qT+Pl>G{d!+ieYWI
z))FZaT$>;{5nP4=C=i~E2t(70fn{tf`3hVHC+P`%sU-w9`Fsb7$R?2`O?XA&eks9y
z?!>?A3DVNV5AdXj?~4(8?^1Xp_ORX%zdA(SJ}Z9zxe~57hU`&^G7{gL#>kMprZJ}D
zES+N<;>rHMiw9x#ib9<0=(#oI3UNhrBLo#txV1$yLVnXlG<U^WqHBnFeIqZgq{1i#
zFrR><!IKC{g;Da9gVb(s$mfJl_A4%QRzkQpcJvA=c9b?DoU}vv3+5i>J*}6vNkOB)
z*2zG1gudSL`U;Jm;I4h+XD2{zh_S5^P6gRw;W98i19c~ubrHu4NzDln;8#*1tEQ<2
z3CQjo9%BD?*YN85P~h?0432GdUtLkXLs(@sTVv}40_Nhej)sU2MxoNrEC%GU4&NBm
z#R|PKgl>uCZX)T!SlUW9%(i=haEnkLOM6MJh_Q6w*kIXMvZp{5Jr>EkujGzsZA}Yk
zHI`HmNT`Q$hfKJvGv>WU2qujsV+uj>bWKepk>F)bNf>&MY01I8YXv%JN#iIY{#`1J
zh?mh{(7-1}oXS%}w69t<#C)ov;mId684Rx+wO3LzNoe!L<}g<KszrVR%s;l2v6NqU
zdgmQo7HWi3I*0M`lQ{9o`1mQ?#XACMr?wJg-W;O5ypn8MV1emXs)i9QKb;Qk$#8jH
zPfq0g9JpG%<s7jtWv`@~MKsQnqH0$sOL+Qu&w3>TbP#f4l<$8CMfO}tQBlmVTE)Hb
z)+sIu`7C^Zih}mJ!{>W1s9B3V81xlRWZxJ>GEPR`&;C`ZLXDMMYeF54+22|<7dqZK
znK9Z|rJ9Py0|hXjV;t226_Ij|O{6>+x{jE*vKV!bzy}ri3ZoPz!pFx5l*j^uuL9Un
z;20n&8!3J26PCmf%y}Y<LxLq#1&lN(6=%<S`-N>xN#rJj{zpxlCxn9yARu~7{Te8X
zA;0p3r8MM5p14;TnU`;p4?sZviIgN`n0$~<@}PP^(FpP9fnIb?IH-f(cgrwZ<v^TH
z>Y(;js~DHgSG8hXdS7mUap`>3BInXut2meBk|GfS^G;6KsKb;QY~r40n19vE4_f}w
zgyW9a7m6VLq2Qfo!ayF3_?bw#GHiX-B7qe@L@<t+KKZ~7I7|uwNZ%`2C|l8Ky>*H!
zY<yKIQY+jjOr(n*isG8Ml)5-B?0aAg7|JwzB{c*^{ZAxz8P>n5)fi+ikaIy%Z&y-7
zNc;0CNe)6P0CWVy+E=AwpraNjqK4Ny8QkBy3`d-YhWPETB<b7qxd%v6I-il_Da6|Y
zQ4Xlf-vVlaOE-s=hP*aInU*I`YokJ4ABc*9ZhciN0=o58tr+NdC@m@p<+pw&ZuG7Q
zs|Jb2M}Jp9ktucU`2icXkFQF##rN@5s|IRXH=}3*>)$VtAeIbBD|(mNSJ#Q7zwaJw
ziv4}}P*8H<fsJ7x$K6$i$?-Z~cU`<}ihPaWa(bO}A$~=a(y(o^3j<27$u11o)J=cC
zZ@&3gjbfVg_Z7~>lk)X}d#33$2}i(SqK`@X4dnuvQBJYZ)>oyRqt~H^WJL*y#pqzn
zH-7YR)-)x3p1{YCW^da?x!J$k_M!-Vo32UeBxRepxE-y1wOupQ)OO8_j)t)krOX{*
zfi(IYEd!9ZADL(1$GDJaEQ1B2THO{@`la6<JE4V;pM@zK&J1wLzuvr8!qO^cSbfh6
zw6r?#gSzCx#*g}2B(z(-t+KJNt41hGtVAhU>g&!CzMm!7^v}C7L*d&Q|H3C1Deb#4
z7bpL*ujz&0o!n$KK8oRcMg41{A}6AMO>g8p^uH=eF9&d4cG}lO6{WEhbL=c}nyQ3J
zLPi2`q&$Bu;v^xZjq+Q)5}4e80GM2a&nwb>Pn2nG%D(kV<i&|fq97KQ5<Ch%DM_xK
z*H<Tref2n3)a#B5ut=J`SO3#*|HIRNyZ`;C|8M1Q{nS{F!yn+IxLx{B|Lbr6@wqCz
zeLDWP|Np7}U;XRzDS!U^=gRHY*Kg~Fc-ZH8{kMPpx99)yAOE@ibNjUQumAD+fB)0J
z{)ayOpZ?ST@xT6u|IfevKcD~lU!SW#SA>0@x%=7eKKyee-rIlsAOG9m{<lxP`|$eT
z|K;DF&&1|ztepRU6PMS*`?y2<lfAu>dGn{<{?mW|KmYIl;a~rM)yu%6hTHnI|JnPS
z$NVU@f47@fkPG(GfCl`9Uf#2x|Jcj_*MIllsF(9j<-Aik&Ly?@D6#gL)&B2x@){yb
zbN6q8?|%34Kd%I9Rh5vg`sYfc<3|&fP(JPNosYVX`EiZ?H~(R+fBHZE@|WN4%xIY%
zF0;PxoBRA@&E9?gyHhiv+BizYeE+Ez`0qZi6xjlA{O5tC&MEkvd1JLvUf0`?>c*fO
z_U~EmAH_S{zRU6=qyGKH^v@sNtJU=PkMG`Se~qs1-(M4`GEezhRf&Q>s8%-QTPtuG
z{9`3RLf=}Od?P<r!=9t*r{M3K{*M9T<Hq6UEr$Qj^#A(g6Z7<rP9UfsN7u`ad8>6A
zdOuYgpqN*+apF%bW#0F^)pP;$W3@f;9fGrP{@uI1R)6~3e`oc#e`NJD6yP13Vr_mL
zTX8SEwaCTrW2HX+dMQ)zb2S6xOw}m(gKD5Q)C-{C?^9(TdG{WX7EJs1zkuJ`ufG5U
z<A05Ak3X@L4FMBxHAPVTSPhIGZ#7YT{8%kdtZyY8V1KH@)Yh7Q3jW?N;G=&pJ7p%{
z{JrV_N4|hwZZ8cE<v$o5co^PV%DnSqHADx$)f6uLV>RTOd#fq=+>h0e(cparN^$T@
zUqHXGsegYH`t2Xk0RVewZ~}k)G&c9YUdQf#Vj1VnnX2se$BKUZjh-KWVs9*Rp?BNa
z?{fOPSN$c|`JF}o4;ek@uUGH+6KnU&4y2&}v{8Wz{jDYey<LCDjNF^Jxjy>hxAjq@
z^Y;vqUz(CkRsD7o#UIB85Yt;pf*-4OWDI%hy^^0R0-*L)QIel4A_VTMq9niY8v2bC
z+MnIv{QMq%;Vm#<>sL=D`FV&48TqOx$<GxtkI`2(lz*(0*>3;p)xVOTD}wUstD+>o
z@Fp@(>-obk;@31IlN^5aRg#|vx&Qiz_;0_xlAkL^+K*rLDEPS=LJhv^N%CXGboGB#
zWBC`}MDh;ASZDt9CVt68L;(DEKPCBjcr*THvAvR?D*~GGRZ)_kE8>>ttD+=7S1fP!
zS3L@T<y~A1XBjI$zKdT|ow!o^QiPKHI7Ej2e0x$T`MKh(d(&^#OUcg_ce!)FDoXNm
z#Teg}vh)k@A@6|y_?!48qw$=-S!l21$Dv)v&R;Dw34X2y4!o~=lKfl|Ak(jklKfn8
z``^6vSMn>S(*=L+Kl~<s&30P2o%`ymB!959|Jn}yYa8<~zy0lle|MwHSJC^seWXuK
zg1^ta`OH+gyLx7*`yGeN{FSYo9R<YxZsmE4BFP_((DEMmtDXT`^mDa#>NKKi?fh`O
zWwmzpU$+LqA627=6K|n?dpQ68m(cFL-0xU6;~#hlZ66$rHN1U()~BclnDSS}#mlgt
zD}t@=tD^Ypey)fN@?RB|Q~u|Q2n>7QMPI*Q@PECG8)5c4FT?(km(e;7*&1Q%KOM7C
z@kDTdRgZ!{sD?x}Z#AEPrZq59yw#MA`NwLYCE{CP`4?Zpxd_kSy9D|5cW@9|{SHpC
z);|so;dE~`1xx-|4Ix!;HN{x{R4tH7Le)aKC4Q_XH*mdy_!TekjV&y*GX4vDf!RxN
zdc1?%`_Bw+jjt+e{L#;oz3Huh?07#`vHexS_8<Kmj$+L9m!J6WpXnPA`d`r7h#vak
z#TW)f!OsJ809xK^!PtZ!tAVlgt>*pDw1(V|Z?zSFrZu3LIsYvG;v4WwCHFgT;2+rW
zeegPsgBw3yr?DE+!@kv+FZSnZZT?MbZT^YYHYh$-je<X@Rv2Nu0hWL94eX0M{hi(B
zA25LS9)B~q{o_R(t0Cw8TWz(k(fw|<zcqRHpR#y2k{`U)lnvp>YKTA98&Ev*uf2hb
z-29zy;2$~%e0gRl`SHLM1?Bvz_)31^RCvMibwKa^zp&S;gNx#;t6!o&@a6v1)S&n)
zj_Mn!wQ+0pqbKNBHnN)pr!LsOyucFup@;Nu7QmP2R~*5YEACH?^p}<^z`)<@^%ec>
z*jshp_^$eje#N<WBZm5)8R`BNzY>^WzPkG*`U79a{wtruzy0<~e#LoqL*@U}IOCW6
zX9c_b?(Hl316Nr5?PB;6{nD-8{FgQUco+H=bB_+B@6NuWKk%OattR=KP5Upu{bx`A
zGvm%N|MMOFy@#){#*I#>m;JZH{=e?1zpml;znrk><5T;__ed%I)Bj)7^Ajxf-gf_=
zzpGaQku#}Q?qaxtblo6kC7cj9M7D?5=^^U3h)zTp%9Yd%Bj_ZY0VGj@4B@2r01I0<
zqY5*g<VgWqteb@JVn{%`&~OHv6h~V)0nf;nc?F1d1lBm5tWF4`xB}D}=oa~zDt~1-
zZ55KXg);^%Dt_+@Ruy|r6eH3Qau5#JSprFK={E3WdFNaaBahI5D?pno3uta(YAetc
zp!{&9Rl<oRn7$Qg`CG=2Rt<@m6JW<f9*{uPT`0mn3ThQjwhi#WT|s%F!fWz*7zdkw
z_)xzblMjbwQN@K~@Wb(X890j+qT!61DJc7s60{naTY|`wJtLf9*b$gpL~ej?BV2J-
z5g1uEa4;&OcnWeKPOyI*jDbg$;-Gs<k~4D}rk|nu!2O3908T?E+FRwI3VL-qI?}3e
zJFyARK%l`DRIiX?AU4AVDmdXu3EHd?#b!|7sX}emr*`d+pbEL7Hu)PX9^y$!?ghwD
zaLZ_~&iNt|0JYsmP=)HQlSTy|o7kY@`E2~L83P82yDLEFCi+A75Ge0rD_hrj-6wcp
z^@lNI2quZmkaBS1T>)A}vW3_TB?guwl<oT54=y&tjeuhdvK5^ATBG9gpOWNj-Swp+
zQNk_O#(*%H*aWSfUEKyP@4@(D^TRxjZWo3$QzpbFC(d#7h{0*c(WSvKvg7Cy5ll$O
z8oQ!oPSjFk94kVGLSV$oy6~g~tp+?*{A`g&H8$gFkVQ2%qhHU#@~{e;1c%TqquG-K
zqiY<n>UeXjH>j&k;*DN}Mo)_JQ|~!)61nvTjkFnsb0q`6!SAuG8h5M?&c9Il_{#Kf
z%j`(`apKK6-=LP(A@O;yxUnl?)6h(dbV^rJ&bz~wYSX&{HZ?w@6F);ozKAQ~5TVSL
zQen4R30K00fZQckpm;mx>c&Jjh@<O>CWys+?X4;xVyGjB?MGC9L>Cyc-y5{iQYvL+
znuxX4YNdC-61KX~aekk@)pz-kpp+|SDIxid6wERxkvfu7ToIco9eyQ9Qr)1W#0hZ#
z%s?~0CDpn4KB)B6B0tp?1Zwd)&{S)xyMgZ3ZuXR@`aJQ2`_Q3=p{W-0WrOZ8#5Hjx
z88#M6S+<daH$*?tE92}HbgZ?5F%Fb+>s`jZvm^BLiqP`GD_0Ki-m-*7k&ZURUePNZ
z?UN!jo1}5Kj4aO`T5vIBvLi+9l~lWxlQvdoP-q8vUC2<slInlggFCw4^kC?^#Te+`
ztHjYj+bw+f;Mxnhv96>RtrBQ=M1#g^YPgi%RMPEUlny~MjoxdIyaIgqm0kD>)`N0(
zb%q`?tAvS#GMu3&KpW0L=Zj}1lrN+sqB)cSq$8hgh<T$UP9lWzzmj@|Amq4$l_kyz
z^qq1LTuHt_<skT+-aaMejrbI68bR055yKtg{qKdn2(tY5o*E4ai8@2YL!|i~{*@p{
zey^mqp(ITmoR}d#`;I)sQCuDmM7e0hU*Ew$8Dy*P2z9>#jt**TR#f9tqWq?n80$(_
zma*F*RdJ93q$BJ;l=<sQEMH-Mp?2G3l6A09hWOh%(%Hr|lxl`)uy*U5Guo^j3<4oy
z_A5E4hT$8umU6%K%0u(S>}ncXYx3_kt4&QqhlzE)gWWP_)6Cn*BDNC4aVy!=Z;AI)
zd}N)z#?cdb{1O>SM@F1bp1qFTwJ{D#b<GueDs);V_^V#6Eb)oZY2qXApu!9ho_CPs
zUI|-;;TMC&>^g5JI_N2aDGxi6H(vo8hLU@eDRyxDhB7W*Nj;bCLeUM{#~t~dgG}R3
z2i<UpY5YoRL|bEYj7VQ+(QAfS#jgOfzcebSJ`#&}WC;opi+7}{y%PRnWeLuL4yxuW
z!qx(A&QRvgjwr?$Q!PXHjmd4kk`IN*TRNgzu4JKH3u9`CP<~^oX|S-xpk3X^NBs>N
z)g5@<5Yc!C2}_6~ybqk;hG{dbgtMW<tsU20AySwtsqWQ%=`Ghfr6K(Efnv?<fF=_`
zcpuPZA_(um7>3AX`k*cYLwLtEtuo;D>UK(M9~uMW>1w((Sq=Sxq^1&T71@(wka?sJ
z9Ng@vbG%;02mYk!cE)5H<Bf+xlsZ;LFi~*_l~0JE=1T6CYWn7ps5JzexspI7wzRXv
zRthQ^Mn2gN^3*Vy)A)MASffVcYPIy6l0ElIrTU}@eRuR-A2jkAgvlHprQ}T3Fj6sG
z2|NZJ+gDxA_sU%wCi@svtXIOWK*5P5=St8yS;$CL8n)DQDmYu}Ee>ZGO}*MM(KU7u
zNrmXZJF;h_q~@`bc8AHLh7O6$Ti#2@+>S}l&Yq>(bD*`tWEf|D($H05N0ySXp$S9Y
z?MSNdj^rm{<mKwfH5$y>-b*WovbuL><_;10bYyI~61EJjX#9vf62XLW%J+}v59_kX
zkzVGC&@xVTA~NsDTNB~}>d1C;B}guNMY#xMJtNIdm~7=TcfuN5npjw}mT5IzQT?QT
z&#psPcA3E-vJJ8cbtFN$g3Y<d8L%Hdvw$MxoaxBX6e2|L$e<OXAbL7z-=fQUhGm%&
zOn++2F8diQxL2}JPTxp~x2Pj!R)|ZzBgI;D8QDmt6<tR5gqJzQrQQLyPYEV7RiD_@
zJM8-CTm6IPyYc4_1l1d<WiatwNquy)^j_a;26~TtNKcA#VfLlAq5Aq#+Xs^lMUAu0
zEn_2ENQDz*QR+A}g*e%J9;>3$yWGL4dnIUj;pErfLpJzwqYqWXxlX~sJ)5C_nKw-#
z^7YQ-=+S9w<IH*m>>ON|eV|kwv9}G(w!K}0?(3$eOZRnC%W!da+U*M-PEtBODXQ@p
zevo^BDBSy+S;7_xPeO>ky_dJ)DG}xor?}qKGbq9?3mfi_5NUg-k0d%-hC19RA4!%z
zYOu)!Ur>W$i0W|4L_73!c5rn@J8BoYupPBqx=;-79mKrRs)FPDY0}xNzNBdIJ6}N#
zugO$jd0-R){4MAEYqih7@fA&0cv1ESS>QVmRncUGuTq^NfqyzO!e0@-Y;gF7Ad4L-
z;-hV~1l8F#o61vvh$g<nAs9_IIGlzd;`k27Vl?`t`vyJw6`}F+Pll+lIuffzqg9T?
z^U-9LZ)n)Iu+bnB{S~0?T@~1F#|UMU?^LpFvJD<Rn+)&`9Sd@;UYx(tWLkqTH=4|A
zB(9Gpr*#L<?iKO5P@!$$xg-D0enWq@p}r&G;}x-GXwXK#bq4?=#Fl?0xfEof!?pfI
zgNeQ;7MQ8=(x^@99&EwUWVUbU%qBM1E2?jb7I$4MM3Vy>7Z1_oz{br)kjwu`QN1JC
z+@M#!5<EB+Vv`3OjLd%I!LBrNPm0*MX9*j?u9Ko4+TY;tb&-(uy4nG#@_{5Hw2waT
z9cWqR^e*M+=z2chkG#|Sl)ZIDL%+Fy^h0yHn05Wgng+A3Cu>>vQfYp+>{GAv+!bMb
zUOMec(DJ>^%QBkvhOWaRe^PXEQqunRIw<*(0bY6Qu7Iu7)_x^y1vHCSgbe{4xPD|j
z->c3l*POYbEAy*Ppbj0WxKs5*I{l7o*N+6H?3{Eh$kMN*KJL2MeNw`fiJX<y?N#5E
zf}#7&5*w}NuLL*pS5#|>R<;wMD>K_?y;2$3l|wHjn*D|Ms?QFrwO4{KzOKkW61kv#
zVfA!6N<dM2C2VYG317Ewj6gOuIBBnh?d;Ojeq?4NH{X?Dl)J_xGaDSV4qB=1jsZ38
z5dbM%5!-ewRGH&`^`VE1aW4n&m2iaRLA?^}BS1r3Ni|(AEe~1a9zZ|K(Drhjx$;+Z
z069ElY6I)x$Y{|MDdHg;8c-4sF~oLIxn2<;d(b&~s-w0p2cK0hmeyOW-aZ{*mMg+U
z0nOqeOB{F>50c1q09st!cb^A!j6mjj)O){@h4MfpYz=^=c*v}dN(1Df4;{!9kM&in
zI!L=Z#-|{Q8HAu7uf+`LipSJb>pS$2QyXl19#c=n{7#}zIym}VTzwsX^w4fl^{)V%
z5C||mU}--c<dz;XwIgfPzjCn$tz$4EddRB{2+BwDpm={Te|2m$Cu=x1nv*dco+UmI
zG~yQ=RmGYtIjfN=#Y4{OfD#K?(}hs+X!6E_OwluCM+f@EUB+@Qbyo_Hj*r1z-s(h@
zJXeBJ_ChGA4$4O-{Y<Yf*FC<TP*f+OZsGfP(Ij^45$<wNA1F1~_m^9ZyI>g|NR=z9
zwt-Y}mvIcJiYqrr2UO)sXfGFF#RaPBAj@>8DGWG@yKLc8B|a4R92bh}iUz9isi_HF
zR`7u)beX}R_Pi1}`VSPL%MLzJguqkXa&}%;Fz_qxw1l4y0E@d!;lsENxu>B^-Dw_w
zG_4C_)k_mUDZ-y?iMo8#(CAmf5i^`b_H!X!oV4;KspTQ}^jR38%x4%O?y`nqr?|fk
z>yIJhE>rkG@wsea*gozsg%5O`QmFJ(DIHRR$%d9w_)7<*<x1ER)SS|+^aIBAD_Rh&
zEMYeQ^2MFj^KlGE{_1SC>EaHIZ|<_DPhht7`2(inTV^nTDh}k;Q=*lEw^DXx%UcaA
z+Bd9agYE5`-fC-g1L%TW84P&ebXOa!eBX3eU&(#<n;z>c$kWLcp(!Y^O%vO|N9;RL
zssXtg?l~T%mNFn*oXK4b=NK12%Yaq!z15RZrB)q<)7AG@6=<)$QOda&r=j7fcO@J@
zRM%FHsVh3DHZhS<U3;nRQeAtg<%yYHD3w{er<#UtBMi#`fw_W>NnBZCqYJ&CcSRVE
z*e)2B;q30pCvzp$iJ@+7yxzeSgoZqtzU}Kl)e~daJPYhry%FE0u7P0tir6$1pU_nX
z*M}=rjg@!AcUQyCmDSmDU}bf+4&A79HU`9t3#Da=dhx9cgjSfAkErpv2V-b@?!i(i
z%h)P%-FH)OPi=m#j5h{?^DC*xcIZQ4u&hHLuCjV90V}=)VKyLEe9;AMK&<$p3)+x5
z(O0NtsKbI~JrLa`s6;vjr{0w;l=Iy$x}Xh?z$<~yF?b4ng&H>ul0N7wsV=)71Pw^|
zmZfj>&K0d(g9G(S*gvSZwf}{6syF(+;gr3Sx*M}TvxHp+xD{VZU4wd4#vVgH&MRTN
zvmA;p%$C7vd?jppV#*gs1ogI-T3<Ecle)~{!M-B4j-%h=!P+|X*&6EeMh^#_1y+C+
zUqc;)Mq5K2ghpF~9fU%IBl%-#T~RH*fgjvw(g}UbHQ%PbL7y#CyOAXz6|LjUwv3HJ
z!3mLdB{dpDsX|P<TE&r0NrwzqEmy*^K_xDl-G(%`uB1a&h?l2C^+K$UXbO_Jg6a!h
z(1r`Aj|8O*TvbLi!<Cg2TxAB;Hji3?YMXRI8}7m!bU9Cn>cMQctPEF$9F6c;2B?hB
zV7uUgzY;c_lkQ4>WWdI_k{=ncF)o;vAwkIF;sP+Fdc6`pXk>3)^9Hpj5Z0AckDV@+
zE2=JU4FYO$ZVsZf;@oN)S`ld@?-~V)#)Z~0+~B&>Eg6tBKDUN-AG_2rGSmB9Y`HYE
z&!wiJK7sl&B&5D&wp-`NxuiCLrMV)uyD`M6ws(z@Y8=<;PGH!Rq8j2v)1Lq4BcV=}
z;K=}*NlD{x%GV=KNJDm;E5Spn_d~;hCv*-?Ba~@j!XAifG1EP5fYDqD8&7RIO)cZJ
zISnmC2VDW%u1D4$VWmlD{}&dkU;5k!)M%xYdP;I@&?{|7HgqNE#DJ2Vw4)91m@BF0
zJ_a0#Pk5!RkS0FqmNuYcTxqBb=olYIjU&v#g%7);KsB~rcFvWcDI6rnQCoSC9P(8g
zAUQ6`n1Qw2hYaZfB{^!;AN4m}ZSrt8TvG}CH>ijKhH(M847erFTvxZ0^El+GzM`DS
zu{B)izOmJG>AoRVJ)rskUU^DX0rwj}$ZvSa`2NU!$nXXZ#s%oQk}|l4jAnq(eDG@<
zP<lf~Gv>mF3};N(<Ab>AE83{WS%K;sGfVdY`W^wkyOP`LlaiX|p=P1>#!$0ReM9DW
zp=GWBuyzAn#s%rJ0o6BXdjlHdL-uz<V|>W^9soS}koAql>w<I{mb?!c+p}Q|w6&40
z?eQVgdX|C|Wa|p5!(9)Cf*f>A8`5L=X!I6bQ4NCjcWwr^h%o^;<3M#8P&2p8mOJ$Q
zXlfcq#338K_8d1^=o2nbqdo_6<_drkF+gXoh(F1tU`K7&>$ws(U7M<d81=3R?7S{?
znB~^&M&Gqz^LCSojvd|&CVHWOpA@jA(xC!_8L%^Mvd57<@JiTHsnF+&*c5cAIhtDe
zZ;r4Iu1>s|0bb+g(iH&MxNS8I9cr@jO98vd$Oi$eTN(M!We)GCgRKLJ7u{r`PtOwe
z8o*+%gf)2HG+O7gw4cfFp3r`RgBffhx2Xq1`IS}jKvXYr^1-S6Y-;uci$&)940NA<
z?9UkM2W%MLS5l}MY{@I&Q%glAM$8h~;$}Sa0NLUu8ym=$k0eW_)Qo;?gCXrgZCyzn
zc}x~{#Y4DtJrp|4>d!d!8C}`7py8~^X|tf?1mn7rm1Q;zN2sN}jiZV8qle<0NEDZ?
zc?<QgdhLQ;T}d|ALqEQ)by>)j9r{TTI{^LGLj#9;>#~}0q;uh}tWJH;OZs9s8D0t6
z#>uYBt_C^Vm9TN>ysiXfwsscraRboeofb3jEUr9sR(KZgTMwmL6jaNQ=JrbX;QWrS
zfFpuh>@u1c)ncd7jD)(bY<7n1)DEbYt$G5Rg<kBh#f+rA-eoZZ`QplecO^AOeXNCr
zxq`dUpOWNa>@b<(3%O-B4n?V?c?KlRl>oYD>2-0Ty$ryYE5TN?Tb5S+8=aTMT*<BP
z9O+Xn7m|0G#~UiK%Rt^xi6EphKw55@ULW|XoKP-HkjpKy87Ra~7q$W9;+-z+=Zb16
zcQp-_*kNoJ62^t^G9Y2RcQ$NrO)A5m0SM#0scpj;Ws$>y=v@|h1#dnn!bY@lL=-EI
z0m$Nld07EjyvdRVkmd1q)M+TVM&lZ8RBzI?du0jR3jDBF!o3Q<+ACs1&}U7a?Oht^
zO3+TZk*)w2nTEXA-l_()S(9hGQeIyH2Z+;OlaanR4io}^8L=+PL}&!N2(@JZyR`jP
zsobSa4sT?v{zy>DRn}x>!>#WEXc=7pUhd@wqChpaR6k%NaGth>QcbL^^a=-mQsn#%
z>9N>sX}l&Yo%onGQL3Kn#>t3vX>w*G7~X}pGUSZ*CSSI9v}_39xRPvH_OwIsHCfaS
z<=13T<F?6(w|Y`kU6en&Ff+>5XvEAkTG)ilG<mam5#~+0nvj_$qZ_c9CYzg(m_~D&
zh?v%hm9z_qLBdDF)!r@hk*PVG3}@UJ?jy^&k~lvlYW&e%`dj&@3}g@cz;rG$h<#)^
z0}Qjzk%|BsW*@n?k-~Y48_$4`xe~U$v&420kZ?r{g8Qa!nJw3Mb0wU$4YD<v(sfb1
zkB}i(QbUv}ja(mF2`aCo20&Zc@1JD?*IoFNB6c^>J9xU0F?kE=Ww>|WB)+w}nBNu6
z|3H$7M3m&xfPC3U&TbH)Y-PW(B1=gL@3Rsha|LYs;N8=h2GC$1xw@l$N`zWlG>%Xj
zJQ_wQa~q(ReWZK=YT1H+StbD9XQ*pP_q&hW+{o^`4~=JJ^W8@p8Bmyy1f^?H?jt`p
zU@%w0z8Pj)e(s_Uz5=#eJIJ$-_JA1ZzoAqUE6;W&z1_;#X-H_hPk+ZZFdBXBz|~yB
zKUSNf0K_H{D@*Lg;_S<-4R)4~1f@@fkc|z9&?Y#`kX&?!kky97pgZK$MjFp6VZ*sL
zuYk?g^8H9q%3*H7w+w)qD?!V3)Vl(X&9lTtOCjzE#?KfKG+Tf!!@qXO&W@;_Nu5TZ
zXJu(We^JWPD|(+(y^{kw0^OrI9`$GT^<d^hIvKOGL$)|(aEEMhU~P8D7_T?+?2s`I
zw9O9M;=tN$;kyi2n;o#lfwbA72uDk(%?=_+48WQlvb_PU*}{C?e6l@P$Lp^?9fN}L
zUAV;^a#;h~xCQ1iz#n(WWnB=-Cq*2Ap~tYd6IruE9%~?LcF6t)vS!EYu?DnehdkEU
z33kXNugzkIEOP88I}Bb3Kx=l$WesS}CVVWD{GtvvnwuK<Q-*1MaM;{}iy8LA9W<_M
zOWh%}8N2S4uxn6<q2Of$Ze~Z*gP{+Dj_k9uz>byuw_RTBgRJG-rM(XnqF`eND9x2%
z8-y0S61I#u`zu1z1#Y|oHlK=cyVN&;(^rB$2qkzlPN2U!f&(b?k)Q-RQ}zqGPl>mz
ztcRyW7$B6N%he4#<Rd{TXWF-VRa0>#JSH6IKBpl*TFX*>@Hc06&EiI>W{^(pktW%b
zlA7fKxXcz7Y=Cim`&2DxIik3b1N@fZI2f=_x6@^f)ZtfxQqCE@)&n;1mEf6!Q#RBS
zs5BoMAJm%DYdtdf;g;Df)S3%jJ%EteZft5|jhI@RH6T+%6Kh21>d~MJ1??K`R_T1`
zLT9@ky3pDBBr_%ZXIphz&R0-<?e7yY({xu~Np-$y=0KWuMQFNIpI}@A$eQi#U-*OS
zdQ;QTecovK4&Z9GH?{rIe*381TDV(CumKd!l`ND~V_yN=$y4E0N`V0o&6Ti~GI+O;
zV51JWdkZ}>a0uQzG(;%O9cUZMafezuRl>`lcHFLJpdGhsK&2gfJErwi>hX$DykwT`
zC{T42@}^|<J^;K)3DyFjHz~pr1NJ6G{EQNRlM*x!2S$o8U%h;uACZ<s@9cMbAJy4$
z-bh?gbzX0{cl2Fg`2j#piV80}$}?0VcHXk1LdOsImr}&$O5>%7-(pAh#U?Xsz<HG-
z%wH<V6ma@VL#7CQDixU$c45@;l<a-L*Y**)TAO$gg|2@fL#JF5v)CzKCyWBrqy)<a
zfSMHHx@G`Uld=Uty)Kztqi+;3xYCcA;scSY12~+Nv9(=OPLpdOUN%Jwf?%bblX?)w
zhV#=vAZ|+71IN&&23roI6s>xYa~wq054g5JqM<$o-T|>e0}k>O;T~fEQ<E}u>hQG;
zb?R_-O}#ptTzg;MVNZF08gSsJ2)(dYMfBVnr`&L<e?^#aT2uoU1s@UJoC9|WDS~z^
zm`+NdrUyVcDXZ}Tgp(3{+5pvjL`}Ukc1!eY13~m9Yy8<{O+L)nuZCjw31{V}MD-qI
zVGSF24KlH=sCw@D)B(sz5jU5F<fMe{53EIJomz>qu?DWBQUscdfs3n>Va{hQMGv(<
z@q#^2te5L_YCgjj2ZH;LD_K?MoGo_H)#t@dI*Msae#$&@4FGCVga>c*Z>z@}>-06l
z42R8>u>+gK*y_OMP<Zwl=C`=iJ|Z|$h7LH^!)vjDv?fLDfnz=RQU|c%r3^a}Xg@xp
zshYul@-kx>itOW2r)19AVXtV<8Fi@;_g92Y)e&o0shAX~EiO|Yv&Nu06;gi;s#B*c
zbqvIam8|h+s|4u5XdGM}wXOiKfJdz{dKGCGjgF7fP0e?XRvW{h+I)>Uz#B?b=fg2d
zZ+cS~sW)HiZBTF0d>d4nt~j_cs5Kpjt}&oBod>T0v`1!iVmHCB-pY#OqjIy@M?FAl
z<wnbHP>~AJKL!=)J~%iHFbY)$DRg1xcwgHNh@KR&HLBkoJY)_aZ$2^^XM>7#^YUVh
zT}5nOgNk&!woec_r3~{_dUU(`NIkk8Mf7lMgBjGKd#i1#QDvtY18P(u00VHJ6hY4b
z?~@|z1B1#o0|CaMrd1@s$fQ#W0~iJHc}m8nf-hTN{GjR;u73dUl_EZ@-d~D15UO6`
z`^TW_-BXXJ=G{8<4PaHT?3U+MyGp1rCe`jH{9sI~-K}Haq}r|M^anDmTb=wS^sd4O
z2H-zel*P_PYtn*~nwil9V^T9KgkU86Cj}Th@IEPm=WooaQ~%_!c)4;#7#0r&6DoOk
z4FL3$DdP~RlDF*rNtL{1?@y{^Mhsj@y~CzKP$TcAVNfe?nG%y)dFzxwluydo2WVvl
z7YyKhQiLu{tdMoohl%|i@daa+T3)pDC$+NT0<Ne!iNJs{p>dZO%&!QI%dVfBt!u-W
z)VRy_aBAEOFQ`X(m9Y5(&66U|2Nmwp>0nafF7Z4Lut=ti9dJx8VhA$vY_8(9)nH(B
zTMB0eN2enKpxT*Yj}@tL83QmT&ZcW>YoFAni!pa&QJb#vpN>Ucx@6d|#vV-W?W=Kq
z2{syw%2dGuSA_Ycr*%}Np###QI#u|<6=6Dg99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_
zt_UwihW(<3g)&`Krh@$skjbWq-K08ID8N`$r-^dnv#Ou^rWds-9z$Ka2wu7(yn@D<
zy0NHCmyQRkl<8_}esXB~pcj>C#t>BIk?i3-Y7Gb3se{1cL3ZjOuy~H0N1O1X23F+2
zSQ~@E`=_>@p=X!6WuU;5lIpc$1;(PzouPqH<tlz)EUMhP2^b6dcDjZ}eLHy&SX8%)
zFc^#KcKSOs>Rg2xjD_d0@xZ#Bj$*A31sIHlSmczUb)JwFWH1&^$Wx~U&{?O5Z6EHz
zQ&vK;VyA>FiE3K024hi8GuB}2RwW+YHg)jSDPU6vE0SPr>R^Quj7=4cUA;s#76K>6
zrV2(h!Pr#7Q^$!-9XzM@yiF~v$b+#<3oG#83h>@|#@L;2?cHBCPr_42gALWIpn<V@
z7*^cC*wnlegzRJ2A$Q8`-&CnnX8)#2on6nSN}c`f6c4%xGZ-5Rb;=pMsZgg55L+2j
z-vdMiWPU_VU09q>92dZ?p8`I-^e!R|KA+BpQbpRsv8hpq4E#-v%AkR<udW=Sf$DHN
zq`kMJ?Li>Z6|EBR!PJx^^k5!M6<RPhmFJMdc2j*0eefIVbLdR40jf$F9v@gHLpJ}e
zC)Yn~M#tvQsWgX(C5KaMX1KtpL)WJy3*D(Q6*DlLDs$9c`jo8J@Q~r|)R{wuyQ3Dq
ze5cAB3q@G}3OyK36*^?sJ9X%gUGLDLiar=T=Uy4gcz-h5y^gFyCc9IiD!yPi73z3R
zb{|#dm<9(Sd)=vH$3PKdFtt7EMj>VO%{%m~A`XUAzbfcpICZRo4u(&SRL*^;jva<#
zK3P`0Q@=6_VK|SkqZ6GloGMq53B##%hpc^v)*Z47oLaYn6CTL0K4{s)8I%$Zm`ZoZ
zv<D$Xis&Nn(!7d47*55j2!!EOybM7YPQ7dA9U&Djf)K7C2csZ_;nci}LKsffYp?&`
zse4WSf2Zm-o(epwggwQnc@c;345#unIscu<U&SU2<V;EtXCOFS*ZqxC{VG6VI8U}F
zli%r6R(!#TRz(`yLCvc8f)UiL2r#&U`Y27e0Rbgy0#jX4y>nY?jC#~`ArRD~3QZV6
zHEJNV8{m&g38pHjM;V_mf_l_+B@kJh<cb(UpR+-+2lcG!*bqFanymleNwoqF9>`Wn
zuq_4ks*SHl;YIOC5LBV|9spu;dbMN3WIuHP2;~pgbwEIinu3Q1P$(%wi}Wg+4h}(G
zYb;`PT^@!gRcks);8rI^crd-n3U3&}gQ>lqf80iu4AbdsU!MP<#?2sx5v6Sz!|<e}
zX1B}U2eVX)I3rZIU5@{ty6vyyKcH{BP5{BvYG<WdZ(W}Mphp=A2cDAEcoiNo0zYBv
z^dI*?v0h@A?hks88TD`_7=(=d15Mp!*B@%?F5CVz`s=%+j2_FlKh)9;h8U+;i49Rn
z_bnB8=qK*7><<;Sq9MkiqE<Y_I8f9T55Z^E`eZ=FI6UhrB4Ql6oV#uU4mElg5^J1N
z>0Kv)LzS+`hyjG+N2C+Lp$aEQLCG*g><b6_S#b{IP(OE>@`w64?`$84&~@Dx9I9u8
zK#Wrgy6d*!P(k;hqr{<#?z%2G)X-gLf<q0hP>FG%q3bI9fe32__XTJ1UFp8yEDTt<
zkVBPScj@&c>THEfj6>bqW$_;>Uxho2165nW4G%=<mF^4<b#2EX;84+a9Rdy&ZEti|
z@F{GInzre};84{nN@66cIR${^jYCb_U>_XnSw%^VLp94ViE-$QMgpIwWI0-ePFzWK
zv+3Y*c*t$^GTii}=%&!pv+)e8@Q2x;Ya8zjW}~WA0K{xmwaqb4vlvNJQd4y$=$501
zE^W0%H4CiGQ?hymilmqgMK(@fa>H?CHoB4-NAaW#L)-XCt;)94I?lWbu9%Gn+{UBF
zGaEIwf+=R>@wH8Lak5W5H(U`qB@EbXRK1P&0kcu{X57SVP`hoYo7B2(ypu$|+jzd1
zje55Y^?<s!4RyU#FPWA~f`vIy#IiJXfZDm?fH51jGiLQES-pQ#^E@3l(_rauR?Ni&
z5%NbQywGe^>kPcOl2v66geqG>6<36=>##5zb#~*;z--jn48E8R8oM=3CN*{wr{8Q;
z+X}*%jcU6!b%I)3p&7HC-wwhua-zyExFR%PZt5#w^QG7iqB15BR!3nOv*B*?9G)d+
zZdo4zjtIAW$8Z#MF%j2w5OXnm{hM>uJ37W2g9!@pqhN{&7}Ythhj#SM3k5R^LUj~w
zF@c~u$JNz(`{(fNFrgXF;nCrlP#;Hu857LvM{yam=+{%SP!7~#<KxL9TOJrA?+qq2
z?m0_UCVB_kf2Q6(M|TDjagOIqb)+=vm0(8zV(Ln;ZvilMC3VqxB?GnCn}zx1eZhp~
zawVLGRTDf25}7cR4r44PB1?~AEM`KZ&M`f9V+i`pJ8p!ph?N`@UZwl<uJHxh>>6L7
z(XR1DHcAtIBE7;#f>O;{Qx^hr##oBk;pIK2so_)Wys6!Th0Zg;gc*M_oMOVzKOvT&
z`8f!jpshb~QaC|Vf8scCgyx&z6*@tieHuKDC!}KQ_;LiwyMlpQd`?Z^m7udY20bU}
z#h*AUeI!}B|I#-J0MrRs^b_c(176a*9)Ny23b2>}KOIF_%)&pNa5ZWeAwSAz0_t=a
zPB8&=Itr<n33ED%r<g!FT?rckE7lRZZ`#ZfzI~e*(b5<vhP2r3ME4crctzQNeYQ5y
z|D|S1OP*M2YGFWA+c6IPCnnokIijf%E{v$G_X+R9iK&(Wi#jpYbnP!kAs4eyQ7485
zxv@3|8{QbCJoOX&4kt{tJbOore1ae1C{$v?M{^J=F_D+(mf4j+%e1p6Ku#yRo?DCh
zMAvhJ@3G^-^=D23)LKX%1MrlR#^2n|D;Lxi<Od&RlF!jFZTh%@K03-LK1a_IzSQy+
zJ}F`qXe|aj%yLa0WelHiUmn+&3vAMr0AF)OR<-!t!bTnsJ{S7P>5;#ZoHZs6e^OKf
zkcB-)me_KcYsZ~WEtBpjwfG!$0z3)An~4`X%o0Aq26Tj(o4^m9jBuEM4jn}}JQHs7
zqY#G)zxwf|d4(eKrQt&n2`-lp%86ZSdSPO#Ya5d~HFPK{pK5v6k^3lz_)PTC5!`M9
zS#&Z?V&a10xD4dF#5gYZ*#xHOC{AMH^5ZBfVj|(*QC!3vf$k2J^0<72pSz;`8W|;V
z1uKhe1^P`v5))TJ$4zH|0VU_Mih(#fLeI^*PdeV!G;|zdDV~(n;_GT1TF<*$hvrk#
z@i|+T@P$rTw}){O6Ck21z*E8Db(EHT;$H12RALtI*Qpzz2a@csVk0K9N}f%#7l|j2
zvXM_@r#yhvJ#$uptw8fBQepx^bQCFZCAn;Os9j{SJIqQx3ubhLuA8_9JqVPTKp34J
zY8r}g2Yo0L0Hd=*Z4Zo4x*F*{j}UruPV~>;se*3XG<|1L(Otn?t2!vd7uV2dZ%!37
z+m_`EUc9rpQzWwJY+1fQ7M;D+@WQELFEw3%JbS5Ws5Yc4p9MZTg4s=6+g}NM1Gw71
z61Kf-h*M2F1|*Xj+=U02yQf6e8QH>s3mu{5W}$_y0NV+$LRXR<d{R_ziuN)nfR2)r
z*8pT2&x5|0ngIdq*`|h4yKU1v9L%q=mGTcA<tM+A8c>;~3+itZIe#TN8oJ6S;4g>i
z%O@Z*hXA?H@Bj@uTUxY`K}Vpr30%<Gbdpa%e?AhF(r8#mJ%RRHGMhm%dX$}f0#S4&
z*ei;xv>wE!N0!(u4rJ?~lppkxl?_DEDNM*yk{sQVm0ftEvt(ogEOb_&lplhSaFaAc
zSHx$Oj=B;)WMzrHhR#$<^DC*ozMnEOhM%?75|rkm1-(jTE*a1ZDszcZa{@7Rl+}DL
z=*=Y)8Ze@>WJV{7=qwr0Yjcpaq5&Z~YpHRlR;4<h01zFa=w?BP&Jst^1Yqc_skXdE
zMH?DZeUuD+f{yqAQg_R_zGNQ*-guS_WMr&AOm#ki0y>NC?}@DU&lN2Qva>_IhvHmA
zGY7@FhMI=re3P9|totL_-28kOXUWLMcXJkuY<yW~(dT_7IY7F+uVAAJzWxm*xnx9d
zD9OdId*43DtvxqX;A-j!R3MU+PatxS5O5P{pR<61e`bMw&T8ri6yT&!djjfn=F#|}
z0+pnEZbT~`LE<L1;WKG^1K51#QCpw0-wd^bv)_z&j5z!WA2&CYoideA0D6vKZ8Npe
zEoV=j6y$VIIjy18t^}QfZc}3N3BdVD0NdP%!9G(S>kZvDw>k&iHs!9~rQ4<)*1NWY
z=P-Zy+|YJ{u3bruXrq*0_ms0bAwsuI8y7akQO@%TIMA7LRD&$&Oqtst3p!KRQxnji
zGi7kYoVpS|2>NfzZ4I;RBSGmdcBMC;2$VR)p-qIuo+*<Y5f^95UyZPg=S*4Yg(5mr
zMmj)5CzGI0;D?TYY!m3AlSbYHNsUitx>pUhisPbkr%xErN3gc(fU=w^iyVn4uB1lj
zbzW3v^ed>Y%HDQp%=tQ~9V&CmKkYa$PTJ(3^T?U9$8lacN{&8#aGA;=2Ttfp*fg}}
zlv}z`LTAWA2T16-BD4%osFJ8p5D^`K;wIohXUIxVgwPqH3z|6VogpJVo2505!{ZS^
zZsLG>2F!6}WjQ0>2h@J0r0ElQpOj$sp)!X&)y|{la6C9Q=8&Tr;GZ+(s0Q}u2o*Ph
z{W(Lh_KAb~8M4>wEPsZ~b)>;L1Ab~G$~nrR{>+NYJA~Lx&$A_Rp-%vHjxcc(-i$No
zr7m~J=j}~(1G-O%&L{jPM|igh9M6^T!3c=FqIz<){5xg<7@jlaqK<||AhSIEIcK~l
z^1zvK(Bg(u=nQ$ND-iSync$%1IK;YrHg#lzI!bMRCAC;s%1M-$8jiCw<fSGP$zjs+
zSrN8JsIysNxL1Nw&6(WP$ZvH<d&dVoH{_;{nI*OgJvU^51BLUEpi~=-$>1)B<T2UX
za9SSI*N8ypqx9tyvCz*UQf$V~zq1AuoXJ*(qxMSJGw3)IhtGt+_gJ8mJ=50*0-j^^
zNyCSHO!jpkq4_Zx*ns66laZasoTCiq6S$lsjM)SR=h)`<4hYUMS=0r<xdJwX6QJ^<
zPe5=EAZAaAylSzjz@TJN2lS%Rphj%}Q6BVXW^%kEB-upzykqi82Q;C{D-BG}G1=1x
zxm%CXqArlmQ7ZI_`;P;#*~A6OEu(4NqFf30VqCRc5!ybticD@?)f{F_pMd8algVA^
zoF_&6$wnPE+%X<m*tk+UrjPrSwlqblPf&MV5u1X#G#J^qt2#=NKF_EUrUbXz$K==s
z_U4!z+sHzBOpa}2syqh2cENLwDeLM4Jm(OeHUZ8#Cf7EwImeoso)}L#(4G=){D_aK
z0coEAc;<9j*@c}sf}za=z|-mScmp|eI?e994?W6mK5=7ux@>CPs$K~l-ne_cB0d+I
zt<&Ru>QlV}jvJZ{3C^Dq)fi-)pVDnzPH%Afola96w0}n_(4U#N)F;tqvoJ4*nan2;
zFQ?0X2H@o*K`AG;%U)i%k3XF*?uASHBOutq&Hm}MpjQ$w-ZFeE3u$#fBK)~#ksj_V
zsY#^Cy&5!K=cl_`MM9lE)i8XaeWFyoA9`w)yc#Vfm#N8D1Jv^fx3$_pgT@M_;JT>;
zP;lMU0VugHKlK9K<S;jRN~&M9i&y(7x!%<<lw9v@7|55?yPAgD>s?L5|EYZCt1vJ}
zn6CwF%X50;li}R#O%Kikpc0xdpn8tLU90UZ!SY_f3Y~V;f2hKC*a|dZJ8A`r5Gbx^
zRo3oXRx7nvw4>fb8MdQo!(p$5nnvonBM8?@$jdG7$)DuPYh@NMz+FxYH4Ww1<fUE!
zyPOtkyR>8DS$YBMa+<5<z#yG;&I^4%N^QO{z9YQX$~if0>oHJ$jb`w(fRMYQg`ZT9
zX$LPL?GCYB3$T_(xAp3P|DHy_^&+sP(QSPt`Su&#)(f0Kr<Fy$di@?q;zjUFTWq(S
zGFQNcdya3aRh$5o#{5}8E*=5H77;3KsB6$-jV|l;`I1i?szEK*2=%_AT9|{KgUV7;
z@>RRT5o&7@*V0T|Ab~B-)Yh!YHMIn#)r>7oOf9tRlcE}u;RiLGu9jDpI5?c<T2~vm
z#6LoFEdp4WqC6!v{raE_!P44SomyUvX6gdF&qtIc|1Hi@uga<nr6*s&JBM&rt0UU+
zir8u?vnye{sm!hb+afsT15d3lElv<^vH+C{LbDc-GFQNs??)Xc)NFakusaY16M|+f
zKwRRu`gPC^n$OD`x<d2$N^)n2Ll5;8RbSwtUTK`fp*elaJ136z^nyhb<R~mr^_LFn
z1=A?bR^w?s#aU{)mPC|^bC(v-F>#h!?--|)G{7+-z}B)Vv0>v&oE(v11k%7|cBZ6$
zF{*1*eI4kU=&KikF+xDBg$xl_f=vb~B(9{MJM-V{C(`{~5j#7v28UWM1sQ^BE!g~V
zObzGAo;aq4Ctkjx;e}UkYJ6c4n%Z7?^Tw!}g`6F6x*Fg3Y`Pw_(PbFJE6-w|G6-9q
zlvHn;`se6RL;oDTq2;>(b&1pX*yJCGLof9L)FtAmbEUE(j%KFRS}1Gzs=O;tim<of
zsCy-Bygs~$!^Z2&yaKkKA8&-RKP|*(g>suOB$Ejt!mgxxD0K_S%aw3{7&+uCK?mVC
zxDs>_euXQk4uYm9h~Iirl#4Gse{g?Izx6`8p9uP`7g7R6Y_)pzTNEeo13^tV&&^j-
zo!?n1oe;6qjMYe%T0!(sD5?1ZY9>NoG$J4)WHSR46GCCFV&Hiqrus6_7y6_Zd{iF^
zO4%0~(Qt7^FrZ?=4Hhxf%*3<~b#7u-hZ?S@vQe-(N9HhJK+=Q|TMI~<2%6&n(nQD}
zFC0yT5#6=`oe8BrUx3bpU|b9C#RwVKl>;m#dXQ(4U564BNb5?fzg>@Y^tWjQAgzp`
z`8`SphOBRRVk4xk;jN93{XL)tLxh_D({KO7a~Ey<RQ>$SZGGx~lveYY<8v1JAOG9m
z{<q)yZ|(D6{qO(sZ%^>ss5SO)zkw<}-W<+Idl8EV&<;OOC<eMuOi?HZtFQVtLIFPA
z?KeL>3-<c<{N;RZnJ!=lmQ!ZmY?W%Vn0ApB>?_L{$Q#^96Aw-w$FU*v5`d@kDAms)
z8>_-~aNa2X%!+R@2KsyvmJY^gza&Vw$S&T7?9^~ZfxO|>!64i6>M&SDaR4uh*aVHf
zg4{!1a2jA9b-BM0>T^T{FhM?-p5p(^=VRZ;oH+DPE@WML-p{ty(OjR8V}91p9LM_p
z{KH#6yZ^Y15Zd}Kqpi&BT1Ir~yvvAZoOc-+O=vA6oYQI%@uaUsq!cSyM9i+mHKcpv
zcM-km!nlZ(;7+TE4DkmHMf)XF{9ZETyVH_U@ZGy&>}$0=xm*|`ujQgJbuAZtO<$`;
zzQ(?RL_L4AT;we!Ea>}syRISyS<sT{)KgkB@-Mw-WBanqN;mK~wPrrYyU(KeES0|R
zrt|s7n!Wq}b87}~F@!7)Xl3WAJ)o1l7DLpJ@kQa?1OcVkr$czs+Q&ZvzItr+SAYh4
zZa!Cl2Fn|B1^Gy*Xz^}`p+h{Bf7DixEBo`HfiCg#8fq{2Nf%l<oF{GInL}98LOeey
zsRaX6bO=fc<a9XB+KH?V=Rq4p_TkFQ46^$WkTg~n&>|G9<Gw1OU!7N01tWjLd1Hkw
zJcJ=lCfaZuuLFuz&`|K%Mj}I_Lf*o8iiVXI&Mg3jT#y<2x5Da&5T8Kve+1XLf^-O1
zfuT20l+Hsm2z*0W&&cDVfSxo;KayKIc;~#ZDyudK@;vSSJO5EHTOdtDP&`49=BZCT
zgwcdWADahcSpBhiK1PCq*oVjRgOi|8nsssrVKfm!5=3Ys$mEvMDtKeB1kK_QxTzIR
z6>85shHm3N>XfAwNXhi1<i3&3%cxW4T5Mhh<A@fUXJ=#}h|QBTv!2Ap$r%ATv3Ybx
zo|M4merEm?&!3ok9+;nlqu}O&8A>BI4Gx@Nub>*7H3<5+&aA^~0GfGl2;AIXaY&BM
z!!pj$v1#($WCp1N@#TGM#fBf$`=**iHk;TuZ6mTOHcfYW39bY`@M;51;;^`>&ET#G
zp*#^d7F&T42ri3V=j@C<y9Epr2gS`}HsaS}(|%&Ypb+2_IfbqOjYcg}YLF9n|8>GX
zfi<d>a3}EkskzGoRDzlb91k~7*T};Zn}_Rzu)ZL?^P@hi8)QShg6ao#WQWu2N?4^j
zBA$dRs;)FXwtf$Txj_*vo~%1ubFq%vrKPiu8iqC!0JK-UW-K18ub^zG!-k=dNZ(bW
zJH!=gyf)HUp~i7$Ts&BJgtT58ANNijfv;a?e=B9RT>XQ#TCNV(GK__T^|f?rZLO{T
zq<&gkkHsNzZS@9+#I@DZRS|2enS~kNoCll}MPS$))Y#f6)!Z(+39cwdv(zfgQPLZB
zxY1)VAfv-OA0#eJ^52?n9;7?Mx?|0+TGjYODcc<yKbT>zh+TmW6Jud-P-2TG>5hwv
zSVJwR8e0lR?zrvvh)~MUc9~j+TU6AA9f9#F!8{gO>y@x!_(~W5Uhj(P_G9R0DYvg{
z_1Bx~)D<09NU^AIdr}D8G6n*cfe@o%N20}8{Cn*;tLbzBt+*N+F0J^UHjwi%M1t6R
z{k~B39T#&~!bS~?s-bk>o6wmZSA<uBW!aGeB<9gj$`va9!j8lOflk2-I(2OBP<vCU
z8apm7V}_cZS>p6Tv!MZ~HGw&=B&}Lf6!uJC8i~rh|IWD<tKgO7T$59<e-3{kI>Fw-
zQ5ND8>>wKn(Ft~>XAL1TJ9tY%WP-hTO`Z^!U<dh0kV^1#bg1t@=ar6Ju`!n#hw^$E
z2d`+QpfpFvZF<bf=R!S+MzGhNd<eDK>)QTF(OCRVy_%^Zz-KASz>Y)%L8N9!o`EL>
z)x4tWajDx|URh#0&|`CG0PuTG<(Rpm8WTNZ-5Lf3&)5~@nDi|J7;z>1LD^iBe(i41
zc9UwiBja%hzS-^eq^ntIyV>Em=}4*^lg^Zm%*z2X!Va`Zh>WlUb`k_`J}JuXOIO1w
za3y>$6d8yJyN&!e`-z<}h7_?u&kZSJgPI%C!&WaU0Ltuz-idK&nsj&yVjN8p^xmL@
zyBm&aLwXocq8I{acjVp<p*1^l4+PMf9mxk`gl1}GsZ^8|m@|OE>_At=kVXaqE67dQ
zlNjvF=K}69NFIoCxe0OE!9jK<*n$kIa7ZZwcou`q<GlcEF_zlGNllc69ZYF4mL3dE
zM{MSkqMA8s=Hz9&MNT#p-I$teC_BM7yYW;f!oqIQcEWF7NzU)oplWjuqBpOgUfGnz
z1x#Tip<xH)FvMrrN6Qi#MJ9nOL8BvM8-ifYTdvXYz<eb&npETkwTxkU094x$xmX8g
zGek#tCDlvQQ*r7W)yw-YDe+<acDgzabtpJ!2mN7)hOmPpF~maHi$?JY;XykfsWIyB
z@FWQj+G`$SG&KyBIg}EvWAZ|Lgni(=CxB-M=VS=rc_nu}B9i(kNiIl}ejYgG*+D5^
zmLQ>5l53HO&?~raPoU5%$k!)OXa{L$2o&1K&Jx?it)SuEL7fT_dL=a!YVZMVDn#g&
z<k*~XPklgn3IN)H#0~*KI{@AxbZ3WO^h!p-gnR8aAuMMHvuX&-c_q~!YVHE0-!l6b
zuyU<V(;Wcz5V*5rI}L$5J8<wJaA(g=Ic)MCxntiBLOVOQ_Auf|I=24+wzE$tN?|*n
zUOcs7WE{AH8lrUl#JSMu_UedD2$P<^`t2z}jT$O2gw*Wt)`#(A+`;V|LTdJjE95UX
z_$(7WguJ|xT2%T#=g1O1P6T;`$+O!L2oeNdb_9!rfR`Os%144yzD0eTbMP(d>x4BF
z*3@!c6$*ygLERt5^D>zG!<sfx1l2^63f@u<j;w+o$;uKN#d%Ml%{~`zpk#Yb9O%02
z=7|%XNdK;6W%;d>FRTl#eMR}kdZ3hVOK{8%#_k{~U<adjh!e1r_dB|)VH^rY6WGf<
z50M03L2gb7+Wg3Bp36vnAgTe<QlC(iA_=^bm1Q=IBVPhL`y>*k>q`bldkD1ILFpe|
z$6zq}e_ib@B4NbccSY3~ewZ0k7s73JMBRmOn|(peby0kEoZq7B%Un3=iSDmgcwdO@
zuY)c>fbo1%k_)cO2nX^0m9TZFLy`S;l-MwlFhqiOoRULO(2fAd0DE7r`~o3}=M_}f
zM9<Z6$PeN?JNy7wfDHl8g6OcH*UW#jn*_oL;@RPjxDqxDZP;~WMl@-38Q2Rz7_t0y
z#H0pD{`!J;6b!U4Xvp5wHZ){^KW=dQhgkmZwO)QSLV9+D=LXsOdIk9gA)HT2vNu9;
zc4WxV?I4n9L?h_BBhyASn#`4m<GV(#Lg79;@_BsKDE%iyXGdss6r%HiC?~VQ5U&91
z5XavYRNrZbFX%rZKCh%cq9$M2f&vr_v}a<I5D2uxe;B}kcDNX$33$@shYW&1J6x3^
z6lgC`W(Wh?5$qnsfIcazmnh?XR|yXVCPoO)4nJ%N<9Q`H_q=$zg6jQzpNam<CWn7F
znvC*I{n%)g7b!rrskU)eOd7xrR)G)=U<dU;GzC?4@DqfvqkWGou~jHk!bUqX14Waa
z&ip}<?0+5i$RQZ%mE^LJ!wqiw5Qwycxj))#%olfmG}-c??hjD`cF;NmMi2EV+-To9
z@4WEp8xGVa%N<FaLMYNJsZ}n^eJ>za^n)CXtOH!F1gQW!E?+`afE^b!@iGB+T;hbV
zs6B6ZqR9~lqK-%)YDbnVKfGt_8;BYginP~Vl^<S`b<l|T3Dqiv>co+D5R~|dw{Lfs
z@T0u}EGK?=H`Xg>Y)aTtsaPkv^nN;Z(DXwSAyb%Tne$SHj34YDyN;PI-oL(!eAvbN
z*9)2Qkx>1ELdM1D*MZ`3p+v7FTV6Wtdq>mjt5!9>zAzVGFrJ)bKl-dm$Kyh-^yKh&
zG5U2-_&Xq?9sK=%<Xv;av`x*v5A<Hn^}18`Bj36Ybbg{#9oKhG8Y4eCfa99lk8A;-
zS;Ch9s-%wurNn|9)6GF;rS?NJ0ND+%fZbf^mA+40-}^C?&?~voKq%$R>3dNVu5`W~
zd{nM%z8xSFf0Oxk<b!lk1a>5ibS3lcl~>Z0%C{r;<dwi!a>s|EuhtzS)N$J#OHGDA
zLL^+df4k#S(Bp7Kb>MZONjqruJ>Y8d{1iR()p~uc9wBqd>yIv+=#^yeLS})N+Vmi3
z=sw?-xVIPm*^?r6xAdlmzGGyMcaa5lWSIAmB~S_I9}faXI#4Yh_>ci=@z941REvi`
zWWZWd0*eU%LRU864l+3x?_USuoGY<!ujI1Mu+@@Ocl2>1MXe);Z$}ne7xiBUsKuGU
zx5s$0#8w90qc#A*T0Hdq1M%sh9Uzcd!@>O5!MN{A?|UT&mC*3SgiEj2pS*tgKvLrw
zYH4CbQslt2xQPBbP%R#c=jerNai#F>z_qxt_;#=?dKf#nvCujh>Ux4-T-ka%Fv1?v
z#lR7J=&T-|CANYzH_l|f9XyjR?!OK$%8vx48jVzOVPrhoJ3Od6kpXrrepjB~jxXfJ
z)Ajs<ROd-SZsftUJibE@-G2uZpv&3^hQ^)8`KK3(#+4hmgB;XFM%a-e{7Ud-<PrDG
z`Fl%OA-azDfYZ2020QRHPE1$_p2l6yH{fX=cNVi>I^F|L<Kh_X0MxkaBD@eaDWUEH
zq{fvHxSuMqS!mH@A?ye&aM!K)u^Jq8I{-5-;=z8P?3k#xe{`UWPOw8qx-WS$phvF=
zdmKP9?mD&u72`hj)Lco>gLerOFeXLN2H>{861Ki-8g*<x3sc04v4g947p-7FJ4<{h
zRGw1xc3@jv6oDP!mMf{dr?j73)PEh|6&Lqk2PwTf744}%WAiw0{9F<Kj7igZ8*xQ0
z=D&`}qbp&%rOCWWZ^7_%;>J2`Q&%3|4)$qB8r}|qY8N%&)04y6U0U`)Z3%RCCAq>k
zuec0|78lc>rGfsGq>$7g^mgUVHIUN#4n3#F>!SL*lDrdhaQ$6DVYsWmx17_z@%>#v
z^*7WqwAdDpz5&(ZBKorewfJ_m4867;4MVGK9=IRFA<LPE*KiDTCE~TuG0jC3XaK>u
zcmb{9Jm*Tedqp)O-g_Bh5eYiBI+VJAXNH5T@AZxlN=wXuh7+(0er7l&JK$&5R{ona
zi_hAHJ~Mz|T)cn=5R8i$&;W#SA<(RFFprBW@JebeOf(Fwx2J}@u@WYyc4LUT6*J@|
z@ICZg&k`rHwn8V7U`ne0gHLrVQ&VSgiW7670V?An4m3bzT-1Tqg3HwS<Wy^dk{LWo
zE-abB?c^d4G@xaCcj{CF`MmG0#-YWCI5Px0Ujf@nd-x-`g<d+0NHT-#&BY{WaL;)%
z30lEgTo^F}ti=l?_CS=2OC*6;l8Z}3fmf1mCu0c={z(^6pmn5ab78~`4DwgPw)2oD
zqQG0u8Cul@PH#)0SypHmU#@3DtBE<#I@Ff%Vb-CwK>GKjB<GYQe<=z4hC`m{%hr&g
zq!JN!OBeX#V)(m~>I?L#f!n}E@Mj%LOay;dlJq{lmRjEV1GWk+wy1Lr&Uh!ipTS%2
zODtkmbbWJhCCt-qY}>YN+uqntHnwd$+1R#iY;4=+#=P10hx=81_vVkzbWhLp;8dMD
z&ok45=dGuFDeyp>ok}Z6C&$JQtht>UV8nH_*>_~dd$(N~JD*ni4%0$FN5wzD8{VVh
z6LK%978D{q56Nf>FvRiu9VQL~{a4Pzz)(>wjJ~0^lTS)1hTbaypj%sl7tIb`w+M})
zbI(EHTgPEIm0M}k8I8^s7?B4$=#CNCPzg(`S^{^3IzZKmj8Z_c(rq~K3``k^4vAk#
z1vffmuD|+_D3G~dU#o(tDn;5zFcY&jRJXmNKwqmmAZ*!h?eC9*m&qp+aC$UNy$Q}4
z2op2I%ri_=)SuNPUABww<B#%dQXiDPLvhuUqPXUMT^wb=u%+lZTmaa9^w|`w<K&j&
zwZYvstWb;OYXZz0;O$|+u&J|hTLKm9mN{B~z$Q~0{lS*pbAX~XLDOHfEip<u+MZ=f
zyUK6@T<`fnv6|XPTp59|s$X@Y{J`|1$cb|S0rwqCca7hj^2T5=Fwg;W0fG1TzL>c+
z43TGa9eF60aMF)3$D+cRfRp+`DI3Q2P7c1_qF|p>VoyH3dr2uf(_mXk$g@<wuXN<F
zWJmW&&|&cdpA1UwoAnm8es2WJ{r5%y!+to5ruiG3;L?6yXv1S;&9Rh~@oC9q=7tkS
z2JcKYykqv$tPYA6{(!aE1#0Hdhm)6dKq$Os{$8#iJf4QZP$6z8I8)#&CG?ye|J*C;
zL0Afk?;;@O;ohGHA?5FMpzJDc)aYpwexnWnqcF9!=mj}|YlrmT@^i00b9F_-a9klC
zC>8UDPVSYDx^p}ciA{ydfd&?dN{P||)(suKb%G&jWa!-tqZ(P;G|bYuZye^E=U>>i
z#ZDygV9ON;rS3?0j{~7*?i4_;p129XttI85057D~7l<dTp72Yx-yMU29u1~tHbl|c
zVUq5Rg2!C#9dErmz}jKV-eCgf7!G~k45=9jjk57Fq=QJ`Wp*+dY<g9~Ev+jdVa4+p
zg3ak92b%N)a~7PUxy|Q00c9s^bs?OBal=C2oA4{KC!Deps)&hEsy=&!L%>R=w5!Qo
z3SvXwvDNlt9$-7&A(#MUYE~KMCg{v=3<3+Qp~kM3<=_bBZvdI*q3k<`>Draj|LHf)
z!D!B=hW7meaxB>%5wPxXa@rC=u8aQ!48c$G-xE+FmxF1%l$@o58h$Y-=efx)&IPXP
zxka07IUNRR5ymronp^R8OHknZK?#`p4Aq4VU=&g4Nf(lWi#t0&vU0H1a%_}>{O8wR
zBzxyL1dPBz+n`7t3E@&Wm<xFVhH44ksh(?o+4d%-thr|0d(r4BWbQz)E12LYFO-VB
ztv&#xmc?dCNT`()00H)WV^;ny%Y6Xms73aX7({LtI!S)bc1$cD3ovXQskg5JDw~&<
zJU>b$0AW?O;gke`<%X*&EEsCqoSR@_shrYLGlz$u%>BkVC;(suFxg3qnpqpvJ-GuM
zHjGR61rBvwJRHhBQ<LR9JkcX}P)(lRUeNj2dZ7Det#)fA;RGv6iLRj*+7rA4b;P*z
zndpiIg`E;yS5KkG?oF^7r~Q|Pn9MnDxHQ0E%?#1UbH8a39kBj<pUZlLv)0Q9Aa;H0
z&T*Vl3VQO(TtcSr$Ccmg7kY@yt57upw$x{`byQyi9!a?KXthW5Ai)7He^IbeS4KZQ
zuqlqWj>~|r44+GU2_&7jjw1oA41;<%fULLr*@D$ZKLsmg7ioJ1H*2NLP-Sv#nLzlh
zYz4bFz@n~ziZBvbXzMpoYiNk|0A$?KY2npk%42;WmSWRk2?5hfMeZ~`gmyGohWTVd
zkIw5WIimlTw@3MmEVY{*3^pMGisZSI2vTP{g8C_W#dK>zfvGd1TIOMD&i-pK80hHK
zyN;rZxE{Z)YiR1I6@m>(S$4E_Z9*pl_gah#kV?Qbt0iUCurSae^ZM{FWZ4(NN^Vhi
z`?5jd5a4Feun2H+^U)hGFESTc@~gYrveU<VMuWvlr4v)g7J@s&NXJr1poECui`q2d
zVe~8PDVFvuyrdG|6cg#TAD+&%P6xzvVtzuQ$LBJR#|KKz+}#aiIB`~scS@#m^W@96
zZ`fBXlL5Mm9Y_cAfzx-fpE?e{=|P$T1Odp!M3akh0t9qV=6zzZ)CoVaaxOu=3MHkH
z8Xv~MOQnXP)`4ItQX4}yMv7a^6}1ZgS=#Osv|xS7N+jPJf^r*Y{i!oOSg81m?`TF-
z_6(&Eaq9q|S_#rN$P+t_vQx2$>-sj`sr-8TF`f_9$t03z=1j>E|4gj5_xcZ&__riJ
zRHwOl`z;EK6ytr6HynH+#`2<^|2E=Xh;QG}0sm02%)Ig>U<+Kd@$zWTs%6&ZU5L@u
zILpVyfgWRmZy~j#p6y*q4QRBwhtATg{(S~R%tbkZS&*hhhS#6OM{UprewfS}t4ivD
zO^~f8HgnJU$rrp;u`*A>5lwOtEjZWzw`HWzjNgw{@s};wD0MBKfRKd{Ee@vf!O*vp
z1~HpK+5El{0QXfxES4P_Hhp6-p%hw-U#Kib_}&YEIEQGsdHz&Z_!>JyWX<rfb~n-1
z_K2D=Fb)f{e^6Cm`J8g!l-dAVtr%gk0O&Gg0&`%&W>R3w1*!eU(dKgj@fwC$%mq5N
zA=k5;D4Ns2YQh@Tth`LZ_chd^YJV5p@A1`e^CAkV^}3*oQFwN)T=F56>D_Ew-@*Cl
z=6^MdDjE~4toQq2*3x2QFaXz^M9R$o-Au{y2~s<aqh;j+7BqcbFIDR=r);oYy-{B|
zm@-PbCMFG9`*8@=Lu7VV23R4j00Ma;f{Xd^iyQyQGV<K|#qMed{D^$57^x&pC8a}>
z+6+CT6Jl=Y3SN&dtItWmxX=$IRN7b9%1I!2slG<A^w|J&9PGINT@+Bl%(vMj7=i^w
z=%lvWSE%j9o=CohL3aymuNSR?Dy25ExD7aFr}Ei}7Elqs1-1oC#g8Cx3smGl5xBAG
z-$m1J?UTfjHf1Q@x<$xSmv$e$s2b%)vAY?5$CD1BU+Psibluvii7Gm$wqpq;ir-Yv
z69xpat=y}VVWV7nRY2*(UhgX<2ynGVGdk78u3YFt2w-<qgdala6tuyW9%kU6`$hm$
zP9RB@IXq$T_nit>a2Gb&n-}ZMG1(!DL9E<V!dp%ukhxV`IBp*09!&JLL1)64_y_;A
zHwe?f-gepm%&WJT0=e*#P$X*_nr*%<Ge3AU`6nnZZ|06#L1F_c$YD<Ajz*1Qy>WTV
z5OPs48O`Z~iJHpjga#5Z7grAoCU6cXnM9vF2$R%c8$^s4mvx92tRbMgvuK_Bl_nSY
zTgm>!PkgNNXJI~?aRdlX+%CTaxsvs%Xx{rBH98{-7Bi713=8;lq#(^P6OCyJH6#9-
z+Vs*o&a0|5lVv&XkqU09AK3!u!*5z@G4RZlV>y$fW&)<=CZjRx!beO+#<j}8=6-HM
z&}Rji1B{UY_RtACN}J2}0Rf^avhm7j+k~WWrOF(vG0DbHa5CF9E2VE`8||CR-;$1d
z5|i(w^)?mdUUuq_>Ac$p>=;4Tx+}moc+GU9F?^6}GEiqTq1=SF2Ii;PK^X0BiQ%W2
zb^AT75T(o-TFM77wVRZr0OCcruPj*PQL*|%-7#SrM&J&UFj7+v;@Cb>EAJ>g;ah2#
zYJ)%$h5-xjFc8y2y+?}u?T2A7#6>#oMZJ<Jf{toBLw|xDuVAAf%T_50M6p94f^M+a
z!6K1xpa5}jU0`k^a^dh5o_yPsD6U2actn0JEDmPUvj>&TUsOiPx@i@p18DXSUUZ12
zl&!3!`EXrKQX;6YweDHeMM633(jcf<-?%hs<r@s~#AEa#9TUbmnv<1u`~_@g29k48
z{{WS8mi~HT3lW&A?6}-#<-SgYm~HC>wIaWl6QJBFn6B(72OcoJmqlnb#S?trOd$rw
zaK6QIAeorGh4>ZpWWvpCA}(fn{g1&VDc9WueL;UY<@}7EGewsNF9XwXa$DI{PR)?y
z2m&V3z4=5e&YWx<_0*Wv$Q#1>DVWqVB*DnH3nG_@3`9xvD~9Gmx+|$5GxlUt>2fE7
z{74#G=jCl67Ds!y%|a4vK1?gj2shrs%~kI|qIya<N56GDr<!7vx0x#Q--gFj2ajki
zi%>^U^%R=T^)N8%X?Vv<SQuhHDPf~F7rCnCnMwWpf98%`t%`?+UWSvQb+W1zlXS84
zc~Finl8X$ORnb=DfHeMk$1{h>Qy}6Ym%?0?UBaJ^NwN0=GNK>1h}1kBm6imCE*4S$
z@zhKAhb8yQ|CEFL2S!?qqg1%RGhc}l#>N^suJJ{-P9YF7@(!jdx*oRl;1fq%6Mq$%
zSDROuF)QJ)cX;k`Kes~T5q4gVlo%<RC$h(@p{=&Oo|iXE&ecXm$ia(_shPHL+(ndh
z;Gi*@@0Jb5HfaIaYJ+<^ihifT+{L8a6dqpr#7?Ci69r(lT=)%^OKUQk0H}yDB_d0$
z2UB8TI$|(6Ki9Xk@Wb5sf#c2Gf1ae=>EEu*<P>y5Ro#s_n=F>b+8R*q+gSL76aO#?
zQEhmhfv8;)w+>OQ{1Q+F$wQhCHjM5p1iYVw?0{YSz#7+DHzH)?=;U^@w-5zDz1QvE
zJfF`O`3ulRbb+1tBBIPzYynhxI|_h%Nx90O=?Ie0MW&2}VK4tEgLN<=-8ad&R(FT|
z1cF{<GHk&3I0G?MaGGCpNe9^n+usd_l3|r~4sa5pOMa}&KTw&;st1e*uM>um7>}R0
zlekbV{7N6^8T)}lMZ}2lvIWAjZB3dccb6$9+Kwma(Z>Z5>Unfopb(s}gan6*+#G&H
z-UAPAE_ecPMOYwKrJeL_oy&3WS%JlYTqM%T*2gs-3OQf2jlX$99l9eOIe(<e3^|{h
zuN^oW+*W3ykB3gf7DO%xuakw5TnOI32RSeFI|b%hGl|s}hjJ4thoI+-q3hlw!ct(N
zGEwt!CSb{$;}pQJ3tazN607OezPQmVk@sAk9g$}V))fSNnA|#0zvmgB-Jow>A`E^N
zUM>uN4PGt?UIXD<ToB0l#gd{z+z|fh1HB=9>tpW?wE`#a1-Aw#?+%3n!4)zKw9r?(
z4Npa{$MLEoZjZO`^)&CX>+^)+&APz@hM%TWFzR=SvoV)jfoq$~KyD$vKNy6G-AVL>
z5|Q{B;4-3AMh<Gg-8kY$dXHcc3rN@{a-xG!$Q~UWdxk644ZI|O<buQl7<y$2L@)`^
zC?1|m+7^Tca=If(h~+2z#3=YK8ns$rl9se47yy97#Rme&VZ*n<u_sk$EC`TN;0H>m
zPG~_3(3eLn!U6tguR7*CRaR(cY#$WS&pxBt{NI`gR{LI-qK#EEb!dZ{%hoW(s^J`9
zz*KG8?%x}L95`cF;a86)qIDeTX@{!xSWB?-s`MtJb^AdJ(7gAig<$1<s)-VmO)HG3
zGjA<RfD47+QR_7L)zZ5!6=H*!mE*2b`(T9_@c?%SrVnASL)349P<05Y57?MO><2oV
zo(+Ho@)Msc9c;F}6VL^bH~E8Miq235++fv&Cn~W7Y55jN{SQK$B~ln_+>%&M_92nJ
z6E`*H7H{T!b7{nbJm4n*&G^q=FvZnq*B7mjyk!f0gp@<BT2bEjdT22DDVwHBaC;3n
z5Vo-KdxBa)^%Q9TXg-dPIabV4eo`Z&Ad}#{Cc#1HRlu+WJtAJ1xbu2o1gjnqfil6t
zWaI$Y>;@gaPBw@EC*j&z3L1J4VE0lH9NB={$Yk?C3L0?`Y!L%@BK3x-YUOSSwy=H&
zv06c#6!rkvJqE)SEW@KD01O6G^oj?gR7NeCVxT#89uX$gu|nIv(QPMR+3g?JH*wJv
z&1?YucZw@W_rj*V1Yj+x{eYNUM8f(vQPF8FY&WitkqWSnz7Nsr*6o-$L6-BYh6v?{
zrTW17o8sxf`PsZ+$_7Z~vgl#n?s^GZdZr(^XuX|o8Wi*(89Ze3uzh3%>WEg>NdAYG
z`pU~Q4s5lff%ToRR(H7*49#rVrLt<l-{#_qe#zXFX@A*sqIGhT@xI<-`*BY)mh_;5
zJH}c_j^?))br)GP7;Q%!+Q0-6>o&|45=-j2s!6fGMW=`8Siv4+LK(cu=n)vZJgNR8
z`?==hD<*emYxIbdP&y>C`0OoEEhHVAVEBwdJ9juML?<3atB(V2{X_(xKS>Pal`g@Z
zO_C5j&UR@$^xI{K#HHi#eMg0xbn+k>4+NK>iNEFezvtshja9wdeoKMLs(w=Kg$Bc!
zBNg;vhg5`mu*Ajod$!)vK1;_hB+~3q3*1jsrTELA7BBhwxLlWqegL`;O>VpejWtZ3
zG$0~UVXMv_{<lXA6<0MaUb$`i8@6Fj5(GB(Rf{x=*McE0l|K<G!Ql8)9~$AO>Kdk2
zkm(DZ72?7IS}j)CVVQp9$o_gZu&7lCbpS11EGpP?+>d%uw`RwQ>k?IwpPaN-im~li
z@aTP5a?sqISg-j2?ph&JH<h(v3*Xm}u*z+5QP3D$yH%`^O%VfZy@zx}rnFLho;y{D
zF4~?Ueh^WL-WNXkSAofM;;#_7jlK1v)iw0Y-$+)K0`08rNj}ZJ7yud{2I)r<c#^_%
ze#_H>E23dtF9%ok(PJw@bli2htDAeqTG5kEiMCqMlTLLZbSF6pzXR3>L~{4+<k&tm
zK?4sAYeW<>SBJ>l`wQ?NuvsVxPjji&5Q%=&dLY79O-S~>^4Zb!-d+*_e~N73CH3ii
zL8S2_F>!KDcm?TvTqO+eNc+XuDD;d~HSg}dDBFUa3EETYyeka95_uQJ!%4)Lk!nmz
ztY{&*MFF~<S|zq5^kRrSa%*5^8@Mz>#MvLmocj{UO+nY1NZ!Zt`j9+-jIQtjwt8XF
z0CqcA)E<mx@WFzmSW3Eeo;t0N8or4bb26&mUC`2lNdw(Hh`f<NQ9oCc%1uTz{*?Uv
zqf|#)=*oG{QeNn)s6hCRCfdBi11f`Pi)rafk*QM~7mMxfg)nY>0PUVSH*_GyX?v>J
z0FU;(JBx#vBz7)h_Gfs(eHrxdLEp>ilm2KRv+$GZ>zJ;lgY`{fnCIPjKu+(5GB^M~
zWIH)LfDe)r;?L!beci*Q`MyAUMO!Z)Bs)~wWqF|Ly-OR#9w5+-2V_xz+?*ioXO3sd
zUS9XU9rD-(n6`6r`GrZ^y~Os8yrb~>yV#pV4(~hS;GCcxWr%C?>5+)4^Acr6JoM(@
z>WMY}y<Sx8Zz+Nr^ArGS@<l1UkP|mSH;KJo-6U<K3^^=t?<7n)WVl$r<g2at-NX2<
zk7Won2jctX10KE;v+s9$ZCOSiAO7));g%n{tFv=!O$z%U9?L;rBOcC~)-EGw%=SU^
zVH+Nw?3Xv}+@N_U8O}Lw@Em+rUe%O0e0LWDCU|$Z%tzdvRz}W(p!bCV$D}z-+$9J!
zp>n-g^%X}z2`y1JwOo1tBsy){&Gj)UUOO!*%4B;75vNtw5)1{UhcrF>5h6flOVpzO
zM0MC$M|wCLf4_Ef6vXROu({t}9<&NCq&_A)&<8%A)U|uVFU@Jmv7#@@4{OWz*DMG&
z?l5n6*Q?}%1&5`6q%h7as2qc(RsWUju&|QQz9sGclLLWSnHs+~{jTc<Y)eJc8k`GX
zOC;K}j-Q00iD?Zr;v(6h-p;P;4l{hY??Fm*&v{TyD)_G)gBm)w%a;k>dw`B{k)($X
zJxq)kJh#Rz3b?%@8R1O}Q97@76M=hGrCO+F_oN<zb;3w2)9=_KGm}g&K3Dt7%F_B~
zM1!>EX!ShK$`!dEWHx+B%Y5M2w@{X+ch52mUpXgkP-dssjX0F807Jub_U<{S0O`we
z`p(vnIv3w6kxZw&AG4IlsthB~U}r1(``)D5esH+y!9z;D9o_@(`V}tq&uNC#xQrF`
zbFWI!RheW~A@QM!OST8{@Ngug^N>(DA2+sN)72?HmmJM;f#K4i%frHrsnXH5arLQc
z^pv{yd|ykCY(G>a^?j!<6rO%havVyz53}ssQWt7#G_)N_vmA9fOV`${h0uzt(39S`
zr1OpO9IzbQ@3$9@ldfo`&~MYeWb@%8`4NDbAbs9ognhVo22w<Q7`+>|9CtT-)2%#O
z!W^={M|v2w+nO~>1jV%{bbz$7ja<HM)yl+Dn910jt2a^Q5+AR9&`*1MWr5#{-cg#B
z+onqy3S(QYCOPxiuhO}|(d&4Mv6Jgw<QDAn1YfJMV@R9I7MjIcIc5%;z2DY|xB>am
zgs48Smv7JmT6D3%rynGW1c8fFl^Nt9ZdjFRz0{%eV9N%SmRWWQ7FCs576O=Ph{JUy
zqFlDtbuEjm<|!_1Nk*X25jdCZSa#c9C20?fduy!JDa78N@6gE2p+?CM1Aa<Xa`Akm
zeTYM!jD?n5w%OM@2Fbnk>X&ghv67JfYhtMz^g|^*0ir2MnT)6UT$yqcH?xY?VBB9Y
zm3SEKLEqwI&CdhwL9B^(0GFl$<z@O;AHC$Kqu06wrw)g@Dr5<?ZOD&^hhqYDllf1$
zu-B^J`r=`QnVN&oQHghhcEBNQ*Vhz+vBeV)uRKY29d?C+GK#>s+rN~2&~2VMvLi;$
z^)(L*VXxp%GMo%tZc3CYdBJ@xrPoY{TiTPbL-qr8=U@loLzoUj>quE!2`(-vuLbyD
z46H`+w(|~81o+zwtR!K{KImd-%Sfq5pr3RSend~_Qx4|@S|<w&OsM2h-em`pCOcHx
z#T7OmXjBb5$drZlqI_HTksT8{j<0^?)&mSPDq1dr(GTEgs455Xj<{Z{Wa`)!t58i;
za|_tRz#{wE-w;j3-#ritmU)u@rkh%zYtT?|RdV77=cNkWX_Ewk2ZX9>k6Ha4l_4*e
z<9f8AGUX!fuu0qJat$y<7`O%)RUm$CuISo(8~CBH%la(O*}8_9!Was$j;PETihzw$
zhEp7ZjUxK&h#;W!vWeRnPYlk8b&-Grbc%%v*hua{?Dr^QW@AmGTguV6h6v6q`sFw{
zCX?`mgUF^V(lfvfW=3`15r~>B>=&hwT}E>am##uI-T|&1)$A903dK8+fshP{0E$VK
zoW6<J%93I2(0Fh~rH;PCR;1Lx4WUrBaPi%O>EcQ;AIoxR^P!fi?$E~`lLsr1yb06_
zbK97?5z~(}nNZt0L4}H=CXhH;=IBaa!h}Mm1YMXad1F&BPAd3%GeK1^lD8d<J5XS$
z?EWf7y?yjsx^?_5r*&%dd36at9x-=x5Len#b#(;VCll`D1XaM$`pi@@Ic;7IwMY&9
zah|EdLrSvr326p~8A_=&h+0CcI~3CiesUI(lOm0NIubHHjB=f!Y&dlT7pW>&b-86y
zKHYI`V_obYW*Hv?zm8uxPbv3)RH4xud6zTsb!8}O4!R^^3ynL4tyX!Aivq`qj68;j
zNRmOk&XpxK5Az&bE|(z<+djlwutdmfR9^kgyiuxh<$|x%FRlTON~KfG%vS8AIkhr6
zr(CsUn!3^|RnzP`=l*rMLfit9fx#hv%9Mh*>m|)q8%zxKnxda8I3^cb7iG<-GkgaO
zGG{^wUnn7yS_We$DSGUzkoIi|>`kf$)dDGYBK37a_%=`k_9VdxV{R0wsJegym4N#&
zmg-1&1C-R)+e*T_NpuX$x;k6*TACfX;P=Y9T7Yjjt&9@T7Tq;_+NZeuY6bRDqO$H7
zkf4Gbh8y8ShX`;>s-|DzLt6WN7F;o$qQJj{mr#A}pc1}Dh^|O=*goJTbKLSXH2N1E
zH-?LO`&I3_3a^sIGVYNT(PjI<HAj|SOG}~WH!Hr^xRPS!>~MwE-jU70Kt<aT*xpFG
zB8DJNsdIGSsc+5+h}ykawsE0V&yHW<x`CGTTFhMq+1a?j#{rl|Mv~ntz2CLeNTqL<
z<|i$k<Wan))WD&aZe=l(+6;p2mQy<i(w}%NO<Xi2sOll1P;Q~m)P1g>O4gbclg)Eo
zLS8$6LVw&)Q45JfBHJ>5W9a$qGo5PzwEgHQZPZE!ZbE5Y3QJIQY6_DF8N>2xjf3?2
z>+v#lY-X6!Q`%#5kE9zk@DG%PMLQO7fra#n9dHq(&n{;g8bzM(8k1c|98|%%^H*GP
zAagav+(nTbwb?V*d4s=#paZUPA#ER#Xm&pBZlFE&&uAp^$XC!g8(lM0hR0m$q7$o_
z^Bk5-_zJi(i?#3HBylpV;;N-6ij(ouRI<>xUIoO_)VNLsDrwr_n-q~_M?b$JX<SE|
zG?}R16!Wt!jr%yRj+MTnxVlkRXFSpBMVz>B*Z?(z*}#GCcQ(N`qB~I4y`iaG4?6rg
z>~Om0*HWBaz_BVMk)F&jP9n<T<PaN;y6AA^(4x|>4m3)FN;}`dAO$}1V2o07V%59(
zEjcvqTxcpiH2%O^K9~xfMxtR2Z3%Ln7u<kF)~Dil6Q$(EOrNb7VRe*?S=4IUeG|+Z
zAHDg;#3xGZxUqaJYlb|M>_Zh)t>)&3bhGbveEJQ_p#hXpv}?@`oSZQMB#1N?h`hBG
z7X$k4WV!>r+vsSq{xXNQ`OKeoG)!>U{n4)tN=lJzxOw|RK1%3#<A3Ml!zH#7h7vx3
zs7-|WwuJco8{}gNS>1J9$2(F=k9G!Rg^~RY?cVNO+5zYc<MWY1k#<$fJX4jF2GvVK
zT4@F+XH5x*1ssz?RM64RUukq1cOwU7)k+$s#{j&OJN5g$p6C8n&=mtDHy3B_SU`l)
ziQ6uwK4xxB6<ZO=4P1Oa<y{-xq#P9}SKEGh-RYsIixPKd*xrmZbGS!&s-?@6g-jKw
zC)zT_IVrJ(MHKqUJ`4|U7ywzPW?Bo+Ktacr!VVG`an+T|&g(5sBV}VYaoyF<gNHo{
zzKp$kPNaq6y)&+amEtffU6DMJ=t~MgSBstLP24=L?(>rGs_u{DB4KB?MFvqr#~J@S
zs3Z@ln?amo$U}F-tprtFNc(&W1j=qrKhpU83Q$8;)4D|<<46<@S~>Mb$!bj&Gvc8i
z&@&-QDop@CDTY*_<3j4)Ex|=LNi~5Kg&itP^vNwO0f!Z+9&Ix1d?f1@fTHp`%^^kp
z1mES8)`D)1YQbXb>&83p4~{A&HF0!FRRZ;*Xwmi}NyRS$k>sJM(F!0+DJ<r{2vXK-
z`r##wLHmM02vL^*E$@|st_Vt&Yof4IphmFE6;8>{EHvxqfo0(R*dqW`#0+LfC}Wf7
ztOPOVDWm96WXV<;djg0g7Zrwnr|lDpBs#|VVR{Xam!E1a$<BMf5u$MD7>gV)gnVBw
z5Vosh`UQ}8tbh-gCv}3y%H=-x!7C>~(SHGE!9gy60*D2N+zyV(MjpFne;F+uz8Z*v
zO==21QD?0CNE=2aR0aL)P9^Y(_P}v>(nVTDwJEa)<VVH&mXcJ@&d+Wm8T%Lw2gHwR
z#!k0GzJFmO_;i!v)9fi>2Op=XEK=7i7B^OjXS^J?)kNxypk{baYq2?%s_CzJfjFad
zP~D5B0Uyw>=vz`RFd-F*N3cN?yb5d82aSDW6bjE^lVYwj8<jz;Um>w4m#wBPu~&U?
zHd~l!6sfRb>rKgGtFlr=8nR4RGiP0vyjsLtu2loplPqm5;}lvn=OA?nNgF<5U)6o7
zB`E+m<CgMU3lM9X>P{6U*etvaHLSiTo6!XrCp(#k9-M=RI#kmJLEF$qG(!N|z$G?C
z{gnIWsg$s26i@%Ya?sx$x;?PdIP&eF^p6`()=@6W3M3U`zf#<$-*UfF+NNJwE7gR}
z10vdyl&-iqcAm7NGqB5<lKLiqnVCPSPh;sD!33ziS^O=kD|&4XLF0VNPK`B=H6V63
zW2h|b_DTE<+7+>MylbEwnRK4(KHCZPeJAXh<-_(Tg+*E5c7u|A3ouAdu!8;UeKwV{
z-pF^xQheDfjfh{^>_B{#3nBi>%VWyc;HFn)bx@s_09Uvtu{d(g=DBl|+cbYOL>N`6
zbnx=0nj34)*$VK~19+QJHrnhowx=w4x*O5jcLN1wEuvHb=X*&0?0zprOOVi-jmk>M
z1@02AEQ(_Qq^~cEvjNm=C^~7MCI4s&d5xP%+m2}|3{k$_$fw}?8H|^40zA2GE;MDx
z(ZT@pf#gVShhDGxrT-;uXMvtH!_)vR#lg>Rt(fEo-<ca+un=fIciK+?MGafBNV=uU
zGHn{(jCxbAEjkL-YCtFY8@7Rpm7OVFrUC6U2<#=AZAZBMcV2`GlTN;ZD0e>IH*_82
zPZUhGv(S!`P8(<ZlXkVd8K2tqqPJ;>sD{eUz7-{z)~>Bpq!9`jgznHfqPu7V$qIHU
zWs#_gYG<vZ_+lo1pJu2B)&qhbw0AQ<Sjy|F63G*I2DysLuAzf$pUy_oqN3DVt3DYu
zl1iXUBVQ48qY|B{8JG49Z?^yAI93mTdF1mN|MSnj5J@5Qw1RQ2uBPwv<cMu7@5{9K
zBLCNy_(RW&1J79O*JmwXwIL)gUK4vcw@bh)eGmWVYYTrSe`f4(_xt1X@^!bD@5}oY
zyzl$u)7RtSb!^Xv!^H>XBZy~b3-w4_&ei^H&daU5@6+vetjF8wN6**o+ddHBVf$I}
z`4c{R_qM=H*PB={_3ngLaL?O_?^n)s&$}9R`wdNoE03lZj>%Np242Y&{(KTAS`noZ
zhPT*kgzCNStnW*xo}}V7@R=t8t*hMH2o@*4k>^Kgc1RG*-26?|K68YPkMZXq%JbqA
z;`Ya_YtP#X)lW1Mvp&|xQoc{b&$Oid5$CB#hQcwDbDzYqSa4nZFVFWw;oVmUQCs-f
zcyoGOD4!(>s|p*wt@Uhxw}JQAo+f;4`pb$jA00&y>Xn+xO-;IB`jvE_F2n8Q?uGrs
z(>F_RCf~B*g4cCRvlxDB*nph!C5plpy9AQ=w$xhTx~Z3a`aYjNY5kz?)GJEU?YB?=
zoI54OsN^Tq+otED{BHc78VJ5W(nFr!%8}n7_I5Ci0{;us<Lw1C{r)E@Jusg(J#UiQ
zatGerhrmPjCxmSUA=7I^x=>M16&TuhLpsx7Pt}n%!VPWh`)Fz{C(}N4$K1n<Yg{d4
zPL^_Rd`nhf&uGJ%clZ5O#iHHeV`VXStLq{fl0qpKD8C|XkXN@qX~5?+BNv`?wR_bM
z)t8t3ik<!UcWib2IX-T3%ggnt;4T%)?3MK#HLpA~&>(CNtwVbdZ`IZj`H#-MqMwyD
zZ)O>;)A3vQls;b7zV88Te78SDveF%Vy_V}BV{^?|+aS8Cz{uVk(o1i@2j9Kcpjl~a
z0jok2^M%5Cu57D+>^fc3>91G2FF%8morQe8Ykh1N`dsPKg%{JU3A?;GZQ1_iqh?JY
z5?ro$gS?1<mSL+;A@f+WC2;8XGG_A!8YUO8eXqeWzpUpH=Wc_qV(4YAqek`3G11j4
zafsWdKr+^{r7P`TuL`Wjw9B7a59{s4R^Qj@c?|1W^w{s%Uo_!7OEBzRfF3m`;q4gP
zB?GXTX6`#jHS)t3;v5}_wuj<_=zVkI@_S;Q;4Sjzx_7;z?Tz=>=NU8hYII`<eR+4-
z*5ge`%gE2gk`rX!P0Wx#86K}?rxEhWHGdu`J=T?hA-|f=l<&i{uORyEy`|+x$UV-U
z37+$>B2TR4cLnY>l@sLe9l3w&Y%fed{PGDXy)VC1zHiO}OzllAr_YzaZ>&zfEOE`7
zPV@Aaeo-^Y$$w&gqK`Y6X1m<>ejl2DQ|#gUgomXs$b>SnF?MuvFfp+HTe3B@gkmLN
zAo%;AfPjFNlaq<zKX&GS+j)5YR?&;PIf*Mf8912`{LApyX29^R5YP(?5-<|b8yS2{
zKEA)s|C01#wl+@x!`qaWftG=Q?Ymp0e>;8q{d*8h{|!b!ui|cJLO`!zU}i!<O2GI}
za0LSglkdJ5|I?OU*2LJtK*-jOK<nGY@OR(@j7$s+1Umn?3x5ax_ID&;`ELVp2U};m
z|1p?<1^LJNx5@V(z4CWx2Ll^NyT8GV-2Y>iBye(YHu;Yx{Ou)T;$mTBq9iW#*ZA+b
zDw#OiIy)GdI1>C_Hzlb5J2m!i{qOqzT`3t88#5<!0*?O<OU%N`$;5$xUd-xyWkpPk
zY>oek^lwK-0(KTow!eM-d&}H1FV#KWP(+(+&XgB<H+gyId4EBY{31b4AcU+53IYI3
zLKMl4BmhL-s1-C6NrHyBL(tHbCh!X}o4LUvB?zcztVh5*Kf6N`R&|Bk8b?J(Rd6D%
z*F|9`OZM~tqU(5a{Oa2N=w4_2p;J@MRr8vqEKETtLL3PZ*IQVIT;luuzQm7gSVbs;
z#c%Og3E)n{ml{_pCR9rC>+@s*lh;(9a4^)m{%Mx{DB0^uHzW2z4U&;w-pAOmZWq@p
zB<|$6uIAYIf}xqZXvGJAoiedxD*es4h!JC*y;kRauu&2jl5;jT&gBs+u|zJDJ1cpN
zx%LCC8F)U&%h*HjutwebiILEYDPAJHRG+jHs_ch^)$dUsf;;$yK6I%lV;o!a3%QAq
z;gI183hGfPG7U-6D3<A<)+6eCA$#wy$wUXPyuviyBs3{$d)RY;RU$^IH1}PZgZYV4
z5<R6llw}7|P0e7MM0p5<{TI$81&RY~00Xk%7sKG7AL98J;0Y4W4F+ya-1J`va&QlH
z<~&<bBE~GHo3*1Dd}KYjz?;`#?1@mGq#8WrY1X@N0dUClGvZrC1L+lywZDWdLs_!c
zg)ct%1`Y8M*{s1wmBNSP9w)4{m>SfY>0bsK%z}H}*EQ+u3=65VWgti!)Q6~8_l*W3
z*sW49mC|U~RH=VJUcRdU^Uum~_E{AVR22LPQS<zRC!{&K)Z&4@k-y$}Dz^G-q$UrB
zPOp2`+{a}SWn}Va3OPFw!nsX)mZ+C*!a|;rr5q5O$I<;s+J>MiUqD)lUFtiXEQ=^h
zSPeN&2G3{Jh@R)u=CW8%+Q{@J;`xS+{pEO1ge|at`_(V-W-HFPImDNw-wuU6nR?`0
z7UBuQiViEn{ZmcZ-!IAZa09+~w?6)UfYr)j<6UO503T)IUDd!FPf}_KGf6mrbD^wS
zt9PdUY_|FEFW)<Y=MT$JIV=$A;s|WZHZ?jEY#1;sra&DZl6j@c63;1~UaRkxjxvJQ
zK(wF#k>?*FtVFxFM59AIcv-(OXss?6xI&+rcbYyw=WOklS3x%W;_zH0&2QNbQ&K!8
zfMavCB)g8pf>K9JWVne|L2KJ#6Z!URU!hYyiLe%u{PQs1Zk7)v(YGiqM(ag2%Xg6u
z8kXEihirqeLSN+PCCt18n?qFI+Q*uNQ74yfMm{Y&8s<4{tXLdG7PoWim5sP}!l=xa
z+@CXDvr6ivEGZ@P2o!z5>?;Z7K+TBkJsDQ6Hm){cRr&;B$3mHuQO}>e57|>&V%5~k
zSr(hZLM$Y~1cO36B%w)hMt)op*j6yku;1Afd6?2;Qil5}*dk&RN2vC3;LG7HjUMWz
zfYkgwlYR(E7mltORgY|lE_sb;FKfGEYLwB<r*e)*F{%A}19dLwp4B)lcTzk3G1XPw
zb!B<Zd!D~&$*Uv*)fVYe%xP};K{=^v(cI{B5Ms8(&qzeiEqTu?My|k8@0wkWqm(`(
z#%AkBE^)ANKjg>-?_4(TpZC^EO3l>ZNBJ1ZOr=;$5`Km@wLtTu;8A)RB{W|XE|f_?
z8N&qbj+<_?ToP{8T`TLVGc-gk!^J=pg?c+roil$Wgl*FF{^x|{6SCCDNORTtG3#)n
z`q4a>rEA^Qn)+jILQS%H!|A+LGn2Gu3hk_}{`xAJNmjGix~QH(k12ODuBQ5*pS>Jv
zth{Jm8zsYMr!(>3i*g>lC&G?-=+}AoDvl2_Mid((;AI2%af$-Nvp{74cp~1Yx!uEM
zpsy50>5Qp#ENt_z-`rJ^3idT7dbBDruyd}|DAf@DSPp9B$Z7VUy;=^h>~6wr9{G6-
zE^5oRl{>a7RN+DcrN%VDaYgVd+0sCIghUi3nuCO*Xk*3#!oeH_*EHDF4Ell~8x~U&
zC9TSr9#S|YA!m*-U=#C)GaZBoB1<C1GD=daVl1VSiuE5&2v+Zs%?ZYj&f`t(DL=!g
zWRKm<w2ng|{SB=6>Lg5mQ=dcCIjLWj|A?hZj~d@PX3U6XH{Gp<ARNJ-S}||-RatnX
z2uGW<LD?M-g*JP$vWv6<A3zFqS-rc<6ZVFqk32gH{lKfZnoPk`ZLBdyI!2sW3r$Oo
zeG^5bKgGTal<E~dJf!>CBo^!OGb`lm=8TvWylvVnP|aq2%WWf;T@#Nb>SNx^_QmcG
z1@-!!*g8Q(@&OKd!d(1Sh4;~~=$gePIIoYgmhHUj*@3z0l<@VI9u3mTFT!`r(ZciE
z^<o3CxmpB^n*<If-XtL}6<X)Yoo+P>{)0mCHT=5;F15FPuY`ePf&tQ4&p3Xd!jbql
zHij-M-2o?JpsT$5&)fO^f!pg5z1ZUqN#8ZSv+HyGkq!#X7?`F=wrH7x`9h0s3wz65
zn51-iN}$g!FA2xq5IrYoDUl>7trhM4N`8*Rg@ME^U+oQq5_69~B`RgfF4d(x2MJ_R
zzJF9=@!q(c^Sa8!3Qh!WXK!WSo~*x*C#`yf=kyGqTiwS+TXz!-XTdV^%|C)py1oWz
zX&L>(A|$3%5;_B&7253wl@dJ%T??H;r5=>D7osWo^9-R#T^%+pLW?V8WPyXLM2h!)
z4c6rrp(-EVXbp4r)*#6?`9f6lz0j2c432a2Ebp;<@oKGAmT_<&b7PB=+weM4Jfgnd
zM&$j@WTD3WPV>k=KS&gE7es(lG_!y{-w5kA>!e9xw2ZHjz4h*{-I;#9?XZonW}07E
zQ)_y{w`)32SV?U2IA_@)1&<<|A|~RR5jRV{6T2+WSo55eBiKWpG$-^GQ*N{<R#L{U
zG$B7)Qbq<N_Y^XGLR`uM^H0j_*cyKQN}hgI6Bn)EJn}xuoj~S55l1I3SkbCke%>vU
zC4P<;5$d)sb5GY%TeMDf4Z>8CgvR%4oP|o780lxr@9o>Gu+jOETSKdAmlY3-Z(I)m
zkh!js^K<udikMq4dL<`~L5+j=0v<|ImSw8tsa(>qvC%ULBtPrn<QRHEZ5Rl_3<=@h
zX>?^LC9ZQmBkzMxBj=V2L+5KsTErpJ1--4!7O=A<kV~hj$+t1RjCUZXPG^zj=_;|>
zJiRnl2e4o9x848n595309~=ylR^YE<uf4sG_)@G+zg|mAkB>vc$~riE<XMgT9~`hd
zIzWlR<D)v2SZUW^E(WoEDF(8o#jKbZWTIcj(PZ63S1(d&T-ZN1Z7s-O39{5}0tE2Y
z34Wyrig|JJ{kj)0RN)MOMiJYzZ(o;bD7M+I+rF+qMxXtx4vT!({-eA+o!tdjk?u=J
z7Y1)mo^CjAhh?-u8L$55Tp@j6k4cS2<4B)ziX_sJt+$U9;O^&-qoh%|!idvm!u+on
z@~43-J8qaw*=S%Z+Uh@2Ns{Hnno|1~F}h0fTLX;h?XmDqQOS7U=L{X6l`KH%U9IBS
zxcO4Om`b&i_X)&yvCO4BCHAup<)q}75}%SBlVpy0F$iHSBM~y;g%L9*zEl3*oKF3y
zjo>Fwr9PaJTA{N20oQArgls4D;`%Jm2BlY9@h<&B<~99A=1Q6A-!2wEOOi~cNd0o(
zF~>Hhx%d4<)N;ZH9sjZt*`x*LoR_3WO_66twSpWC=3!yNeVq8#Z=&oYR`3!iF6`na
z$w9tfh>fN8=f6EjqM}<9<{7$8+F8nrUUj$yaO+EoQoD}U)h7lL!3qZi>m~Cc_V|Z4
z2?q`c`6AG7Pv5yx%c^z{T7LdCx!%UIo}du(D38Mn$1t|1$i~t~05Ado)PZz_iu`f5
z5T@tCP%_@h(5X3++aDH$B)6V`^_rI&L2=^%Tz=!C{#&l#Rc<|Ah&;=QNLT{UJ!*oG
zIvh!sJ29q_`M!|&^keER+P*P}Pc$dQWTDoZT{ghV>E~$k@&urUgvvpf<FQ<e%ue5t
zw8C~~msXI)Y+V>l3&GZ;$c3!1?OgP8exnj=9SZ{LBc_3K*9AQI5_wIs+M7$E_*(&l
zo6$Qia4~*oczLExPH4|I#X>Ve3t(_es{t`I(Ej1?A4CaOuEN5W_Wgr{;r@FhVo<~-
z=^q2h`Ls73&Mm*|;uClKLO*}HhCK}}LY5RCbTL0nDu=pUao5_f#~hDzz8p-<gXSn6
zJ0i&NbRQMi2J{(iHc*ZEHrX#{o-!YoIBnoVyw@H5>SD`5EiEwkU6Nx3T{Jv6Ea=G(
z7DD1sK7n2ZE4I>+5??DKBb%SzlLhI}Ihjj8ZF-ltt}Ue1x%|AOh3JdbcD!l+&Umn|
zH*490*(ZxNhBZEXYd<!BVZq03;~v!y5ou6I6Z2*kzj~)!$GmU)k{UOcMp`Gmm-6hI
zxM`18P9G+gKA(8sp7Gg$f%0pH>Gbjl(Jg#5`?(=i+SlIYY997Qt;}^sm~n47o7eMb
zrpde528*l2u(y|av!VL)^O(D2B(g{3U6b>yjcCtES;B{cREkWjEHS9yu$JGW1k)wO
zS^ZoO*U3fUgAr2EM?xwJI{$^(HkFtUsGy~%g7Kh=*tt=+Jk&#V<lMN^Vu?f|_~glk
zo0p^uwwtuo+u14-J)u6os2p{@rKVSA5ivu&({X9D<>*$P0)3eum39vcS9D*@Dx^D9
z&*S!YJh~ni&18k_DMdG;9=|$8_vg6T-uQ1&xGraq7XM12ZdK7|DKboBeTo&lHmT$R
zNS%S~Cddk9SL0^aVyC+|rFR=t+hn&UC-NbaHMyC`H8$ZEYu34X|93dDfaXL=L2{!=
ze#7cfT&0;yk<DyBs07uj)i%e;bRF)YDbk;k=Q;EdO_9r&2<*07DC`v>mEWo4KVC_t
zm!-(5Qt4|pwA(u!v~x{ov9Ei+hV#<}LK6><Yjk<_d=lg`n~X<kCJJG9{Z_ulI3N?n
z_P7CSP6V`#2`!3@PDHp;KNG4G<)qMoaDjjM^ZBbKay2%ueWk`Rc>AI4J_l&+D{^GN
z?LW)&qdc_=P@kf;!zw?ka)qDbzQV<ff9*;4CKLpVBIAn{!5DD}t$jsy@$fHIYT53O
z;GuGUl#QTLW_`_|JB#ZO+t55nZ2G&#effTl2s=v9_BBLq*}$&~xf)b}beQSOtCtgw
z|5jdcj9Ma`a2o2?IpE@qWKK=wS{Z=A6|1jHjr*fb#BPqa8vFA=iGFfOi_L&|)#nkQ
z!X&4`V=i*i_@OdvvT*eV34g@ZU@90n0o>b_sH_NmRK@|L+s}$)?8=1B0rAWL{`-L@
z2JN1hq(mwve2d#T3*$T%Jr4j+xmypVa0{%M<$~mF(KERDq5~Xvyfl^|tAgXW8m>EB
z4Jh|HA&^k3GLTdL;Gc{8Pszq)#P2wZVR2kW_)4*!yf~EmdDQ&qlFPSAljQD&Qescl
zB>QyDgD$g1jf%SR{RcGfIHtX!PMFfB9jgdRTV#L~M2D>|MIX`HLdS&HF6p*4bdv_6
zPVg@QsFd*gYvfijcGDkoz`qqCIV0R-tcc{jPnjr$r7maPlxkp%FrRs=b7=&sA%B5!
z8bd7|C3+WzI0Zu~#ZZerCwtyr-;C2<ARn}4@=<$>pY7@<$VsiRCb8nltOMhz7*7f0
z7fSb5rUVE_RtOjT0lr2dalX8hpY$sODIYDhG}6s&ZgN)P^Qa22ys8PwEl3AV<bNsa
zlW%vy<fGzO*kn4{(yD-?YDa$?J}_FeF<^g$Z)ayRwbh&qe8$#P!A)b~tew;TwP9BD
zB9T)~65ux%v?dFQK19Fq(M=j269${Z%YS!t`7{ZiF5U{Y06oZeYpo|DWl|m{-iyG_
zZ;o|I)w=lgL=HyVDAFzx;m&;*-WcH(c5R)OYLr!5a6mWVy;`(Hh9L&$2){alH45Vn
z@@ur~fZ<%G_!eFgRyS3?LCQgMjMR3&<xx|MK~0}-r1NY^_sK9j=EaBv#-edn1#311
zGoM8KaxBc^j+q2VLkhTFDd@!$q|s~QcLwrw5c2sHEJSiaT+LQcD`Q6SM~-Ju2gYyW
ztWjeTaTxvI(9JAq@)5)A70GD9n!X4#2f;m{yKgkD8i3nvJ6eG3An$4j-S&NY)H@ys
z-Ma4ZUz)v5P|xK+SQ$I?vNuJ3^sl{(fH!S^)Ac)Jhm7x1pxVRXsUy8b^32agWX~+X
ze26!7evukCX7pYvfaoAzC;ngB0LQVtz7Wp<CBC%)Q>-vY$7lir`W$a196qYOIeR;?
zKwIcH*?#;Gr8R!c&XDg>e(fM`?9g)19BmVO<R5lKSTWEXWIInlTWB{ae%p|4%DuLr
zIH-0ay#~;5$zU&pfKA}BH=2Op@F;hI;yXJ;E<5akKDi7FP~bur?1C%wJJC?3h&Szi
zmViBIwKW*Jj(ruLf$xikD;*;PPhbY$*tuZ7o<+bWkS<!Sbgvw|3gpUdLge-DfK=@p
zL&hL`saBw7=#}Qh(H6*+vmn|GqvsUE6>W>VNk#>WerPNndVS^KK6c1b27O|m#yTLj
zO4nOhi`p&F^K|{obYib6Ki0!wuSrDphOlIQ^n=4-1w6xP&|M9{3N`2b3ed_kFzWcp
z<R^husH{|XgJ8JvIwN<+r2Imuz}krbJxKNT!98hEnmYYDKT#kwD2S#{hd!WBX+UVS
zUgjYN{^^lp@LdbQKOhs%eK_P3OFNW+4e9!($ULhc%<1~=eilHVvc1TXH?4k@O8|T(
zFg#@XcR+66BqI<Wq5_S6f?p`8%muKhEJGh;Fc2ORgRX#J_b_xifnFeZfzflI27_F$
z`iA=j!0$hO7?yX8m%D)UQFv%W;?NjH10O(QpA!efpzjkwh(ICxzwH1ALejm|QDCCk
zpB0cpFc{Q(y-^uTfv!*)6wb!L+4}s5?WXM@AW!Ibt~z+$ZRj@^rzfxP1bVu`uF)->
zh4p}6A%3IIbfl&}*#zkF%5IHA^Ex_h%?IJ&dXNY-18QtKXOrf3!2QDHnr0yo4z<zw
zu{9Y~P31HiFqIY1>B#6L^>iaADDfnqX&G0t30x+4g0bK(&JN-%ffz@V8;G3{H%$T$
z5<yr8i4+$cWEjTY8;f)g9riO|1rQ-H8Uye$G7nd(Jj>7goq`L@3#bz)AH>ZrK-@35
zQxmvX8{o>&4w4~rb^~E&aCORj2GpFa6bOf7l2G6_KpW=!fTgA%d@VXie$Qx8wSX)E
zkU1@_?jz0RyYDXH*E-1iIQeG}U{Y*4$N$E)|AMUl!L?Z!nErz_bN+8Qmhmry{0}Bg
z|Np{c|0n#alQ3=*$bcaF^ckU192pi0EJ+%qQiP4>UD}8b@EAvgYJ^$8bIrXUu2cq{
zHt@Vv5g&T6!NYE&P3R8aU|}C@;Ka7Wq!%c7a?8Y(e5fzpu+_b{E|aAO`D@);!`^a(
zp`twCAP_E<)vDIB-Z2&)3Lv3HpE2qRsH4V_y6W-l177Y#RpN(E;E?~GF4xzZEQBP>
zHMaEee*5L<W6ARdj}TrDGv??78u~USOjbv3`CMa&C5C12)F<~iyx}SMpH0vohbe^?
zQldY&B4vVKDZCGS2tNWiQROs<Gnw)6iIoZYAalYZg^j5eri*fzrH|s7rFRov7(|MN
zyk}DtYeZ`}mG4Ctp7O7MecQXlIz!A-Fj=N^NyQywQoJT#G&|F~G>=O9(cL;IyQQ{X
zyv2{OfU3wpG3@C(<7an2wr?BE)VzEEGf9f!|M#B#vlIW`G-hVj|Lhs#U*P{g82Z1E
z`@h_Rh>4?-gN2=wt;1g+{vWzQ&cOPcJCK#p{GlOAEn;G6pz5sr4e9^4Ud+JS!pfb1
z;$Kw+f9oj!RcU2l_Kn>${nu0IU+e-cBLfoy0WAv~69FSTC-XPUz|8b-mO;|Vz{<i%
z(8kQlgn;3nc7l#Ze`yL%CXRp9zvKI>(=vTe<?jfE4eTULEX>TmnT+pl{xK;#nOLh5
zaQv(NUq#|S%HJ7&e;iGi2>vn%|C3SpOQHPl)%aI;&W29^&?hS2oW<Xj`o}6{;Arv>
z8T0>J8H@i@m-)3O3`0@;y`Lg4W6D62)ZA3xhB_D<Y&eF`#XoIc5=kqJefr&-SZ&lb
z6x!1?Y3@1c%g;CMye@rLfcNrrFJuHTX}MW2B<`4{MQCAc#l~x6pKW70A<Vos+qQ0y
z(&U0xalhrjPtPF-_TP!<2%p{`fmEf5WW@%myVk{JUch+ioU(MkK~B5~=Mml8v7gkJ
zF*uvx;uU6szK2*3(I-^!4DbmdlKZxXNDiZaP2afN7!&1+>3lO=suO{*)fr<Q33~Nd
zlIU}?Pw%$J4br2*rZnC$F%oKoOB~c~dzg(8$e~*K@=%*iGjhHf#;DJc{<X&01;M<*
zVkWtiypRP3T_||s@{#jlf6@yH?BLwI#O%8&SR9scLUR}D_2YN@j59IG`1xRHORm_S
zMGZ73Gw5Kp)3}&m@vk&a#wQxykV%OKs9}9l4b&7ZN;Mn~jZQUHU<hxt0+*il13A6^
z7Jyu!(`i4=Z~JK}dgHae#NF)!7yL56JE|4^Bv#I$=~VN$!Cvhiy$!jDB(U^ts4i#;
LkUcysKVGswZtkSr

diff --git a/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/alternative_model2-start_0-mod_101-low_error.pdf
deleted file mode 100644
index aa24b385b403d604fb3737e340d118a4ded0f878..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67431
zcmV)#K##vAP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_MozZ5~YZk
zHefVhz=Q6tnc;!aMmNydIVgKz`|Z6&uC=J0_vXpEU!hP{DSk&gB#M$K{w&(p`Tn1O
zviJY7cAj7V_2=;~$N8g;^SQr%{r~^@KYsoD|Kt4n@BjB<U;oehfB%>F|Nf8TfBWCx
ze{g>NpNE}a|LfPkd|CWt{@?e{x&OFN`x@i?(cl07=a=^%_xs04czyksum5!Xwp;H%
z`unfn-P(`G9}%+K??(E6{r9i`@XyDcle@oK`_cTIZM?hBAKu1w+t)w;JpTQE`=|4t
z)<^&Oza9VXpX|r@pZ@uO9RKq_f5(8|4%Ft4vCS@;-_OmT=g0KBI+5^)Zg=}}ZJ$E>
z51r=tagVn30^twc{0^>*{UrQj?0<gTSNHz@>aZWr^&9s8b>@3-KkVFR2f`m_XXA%G
z&(;lu@4LOl?^BdX_(QkbD9Y#t!XLU#Pr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>Z7+
z{rnJRwExh_`ll$9@O`)TOp0=LBjFF-?)Tv~tQLTTe`pEb^J;e4{r>9Rf1H1R2Yj7>
zeF56+pQ22{A7<zCQ<O>gL$~*i{t#sn{?N_Zenw{V`!4nj3Rbe8gnx7gjNAKLwCufA
z=kM76Z`lEM-5;Wi_8(?9?NgLV_(Qk%|NjtW68_Mw-4tbX1K|(d%qUt|0ucV<4lwf{
z?e8B#U;l<X;PFpMM*I7@UDu}^qy2rSdG1mitv}o|{g->b|0~YMHX%<qc4mpwKP>g{
z-Ff{+=>JVh&+{q0&%Z);H$9L9`|hB6Z-~XK>L$YbhW|&;f$<)vkN17?HQv{#|4tG4
zODuWs_puEV&2Q)SKFa!=Vbw{5Z@bz1++6>;`W5B-j&C_w`+e&u%J&_8r1D)IMfnTM
zVE)zu=le8xzF&vGunIQYFJe}d@27Y@zX)1UzVG<VkA-LZ+fMDRvV1OmQNHi^K1V;-
zz9@fTCEELp=+7T_#9zA^+gk_x6t|*$Kgs#|MEv<xl<zy<p+9c@Ncg_n^Hx^RkJS+6
z+m7A*W9`}g3oFs>{4wu79{+A7{*sE=yZs_;MfrYu@5kP!uodO|j_=3i=gJr5`;PA?
z(dWt+<@=7${kifY{FSwM-rq`P<=eIRYggy{jrl2TMfrA$>rLw)hj3B8@90l-*soqv
zzVA3^FmLN9%J&`bzITe&Uswl!pTPF#J@J>6#^?D((2DZy)RtlAL(oL{zFY6Vta?$t
z@A&TUx#~svzT^9?|GDZ#`75f^c;ANek9*>;=}vDo^%p@a${$4gQxE;rF<)Q5{_wwM
z$}!!4S`%OIoSbL7-#aa5|Lc_hzct_O7;it$yWQ(TeXD?FYW#QqulQo;xbOD<>U`@8
z=lcA6TfKSv_XYL6dD_xM@&y*H36?C&U%U-2+VYCxc*rcuTda>D<zo+|HzidLP~QJ~
zQ$AXTS7lJvo8(P-%k1$BsSOa;Q{y`0$3F-)+%=6hpXmDfI(CxlQ%mbwl(gU#1uyC#
zy#Lc8)FfkEi&T?*3(uQ!#TPy)HSMw5+rQ`f7ANTO@S;VeC}ZPG4`WN7;Gitty(w?D
z96QA~#`JjMc?>8iZ3LlM6$Dzgf>Rcp>OaT?bJ%(G>7=yclLepJ#-}%Xjv$Fo@0Jyh
zqDB4~Y)K~`tU-y%#C|$RTC;f{5adcx$d&v+8@G6n&$vYyLq8PDI&N{na>d3a`L<kw
zH^nrfSb{OvNBKj+@i)meqTu+OVj5Afa}4pul6_+&k3fnMx%gwjw?!e3&fIaMi$}Qw
z7DYTdlWn7kM<;mH#G?~DYTQsKSd^=9fD{8VNzMrtnV7Z=67K^|EIYxV^9O(SJ@g|8
zrV$5woEvjdmi&2b%lzX-F^zZq>#gSBTd&~Gn}Tjv3dN$J+x5WEctJ|9JiQm8Ke_eZ
zq;+!OwUC71jZZEF9%o^%9Q@(ngip5Kb97n@7a`d2reHfSN_?2cvqgznJJ)0>An)%T
zi_|#U5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?JaxoFZ+4i;`2cSjr;^(ZoVt
zHzs*<Nv<19i`9R(V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P
z(E3%KVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wpp
zEeZu?=C130pqT^jTbCSo-@4?uwc+2C#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi
z9YG0J>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgp-<yzaWUFwm1
zU6kq->}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8
z%*)I804ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1
zw;a*AbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5
zoo`CR5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2l*3?}X+)5$P#3z_R;
zpQ+-!NoXY(`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpE-h}+3bhdfptEmYcNy^XK
z)-68^59^x{4II7m!emb#@~Jn!Id(qmkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT4i
zJIws>DHU(x{5>TU69?{jX(LaZucxG9=DDya)h(p!q*SbshsE79rQ%4^V(%%bfF{2v
zkcu}YC&}N)36@k0T%f0P!kI#}C}cmJI%n6a;b1(w)?gVASKIK!nvO|Qp`ZDhT?DRx
zM~lqtV5ZKF*|~}a?)UhJw8h!+4c#7a94`ua(xZj<%*^xb{Wsbvd1RTwR~BVNn+!>L
z<~Lh%ES#|<MT?v;d_r0yygv3^k}Hc(gajTS^zaz#X)seSS{8Y-<Af8rgye*ud1`(+
z@8xLb{L<i3uIEK*BM20d+&6E^YK<rLJbUzT7_o~M0dpLAzAg&pI36&mbB+V*=OW>U
z<3EFs>opY}8rN>zV3S@I<Hp#V&a82RQT&4(xz3Z3=kua)tQQv8G}bGhZT3jh92bTU
zO%qSF)#i9J;KFWcA^B(v3hfFbPxVCtZ{L(PjyEM+?|(^BM&A94!jX-9!P_lS$rs(5
zqQhc1y6FlTxg8gUpY;^2Hwn$P<oCc{9F89y+=~NV^?OhNNA7mJ<8uc{!Tg&KijnX4
zHz8ULzoBztU~}C%Cr0DI^z_d+qroPVgdClo7Xy3h=JRr3OWmOZ93X|T;BlUm_~8--
z!w;7zocQ6Cgd<70h7^SpD|qtTr`&6=utsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+
zwD%JLJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bo06^fzw`ug
z$oVB<as1RGL0a&XwM&K~pBS4Sq&^T`qPxaNPR`1{=L2KYLE>SJT7;3!_;;>_0$7^l
zz*8GG=%Pu<vB{L=j<M<XQRIv1m5WFRyYzf{Q*vxFGI<Bzq^o#;w{)&}i#Nrh475kI
z8k@PICt4w%P}LR%au40?NK%OBltSw{8k<sR@uprBO6iFZom*;_rzW~clpS0ZQ|e65
zYtqW<*z+ow^~&w*ze|w%jo_dVq<*0_(8{6fV!=DuX4g&FC&sRuqC;$^Zi=2e+J=tO
zjv1%<Eq@489@<cNQreJJwLPHBjS?do5dwPz!SE-!W(_kO6RlXm_c6`?8f!RoyS6KB
zdxn!dNpBtwr<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7
zw*gLyw{3uv+CF%2+K}Sb9BgaUI~uka27~M6ectAM(>i#jS0Emri$Xs2c;qY!<gvZC
zQkeo9?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>zL(2h0thYz_1P0JsxVLsce
z42UiDD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNjZF(91T+Fx&;h7
z(I<}t3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn+q2`ANm(>P1r>g?*
z)<qd;$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%E
zh7DcTPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+lUD0|VtFL&=Y!Reu%DC+>8R%o_0dl>
zLoUiVdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)
zval#vs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe
z=^93+S9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV
z7&|qkMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixl!Jf
zXtkUlE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5
zA^ZJ-U7*w6cq~%N`Kd1%mh2R#pp3~h{iZ~VJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}
zt1Lns7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@g_kSTK+@`LgPMN?O;>mZPf7!
zHCe<LCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSR
zo0NpRgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SA
zo9o-Bdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{
z5~9Nd4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk
z=r3jv<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4
zg@UHpPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8dQF<C^KXn|Tfd
zCC4`NEn_s0^oa}G<do^KiJR$EgaLd}IJlv2VQ?uChZzm_i-ca$f;7mn(-ET*6pRki
zU^lHQ9d>6k>NAVNZUb$0!qU==Y{;EEf;57F?LV73VGGhQY&Tl#?=Owju>I`PVDacM
z9lw#U5pDcrdcw_8ZR+Du5BRbdDb5DFD1`%8htY@G$E|J{D=n{fNib<^HJ#Zbbw}eP
zV-e!WGvs?LLL8HLIxIeo$xfI9Eu=^~U2XOOw?~?yf`Tbfb)eJiO^F5s12Hd)f-?uN
z={F@??|%)le(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p
z@w-SVk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZ
zA*IB*kNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vk;xALClOLo-lz
zW%rJ?khV<wo^^7dbN!@0D{HKa30!vFiH>vLbSt{?sOn;aVa0S&I!w<7TV{7|=1wv0
z+|F{V_0H|A+q82#_h{YVuI^Suu>>Vq(P2^!QVyoW|6%af^^V8BHL{{Zzc*?89j?el
z0x$4NGGs@tc1Sl(N4@iq-YEm)<C)cYO4F0vI}d5y>%D_pe1!Mjz^$g8gBbH5VHSAc
z8FQ?AzBNov>Q3t-C`XdO!}x;}(#c4dMM?H;lxSfM+CvGYb90fBokh8op@>y!u=RXU
zmc?yRa-E>8n>^}0jf)@cWR#SbHkBKRc+pOSqS0irD28v7GLli!cxXHX<w#O8Dm}Kn
zxmd+E8HMF<+=V+OtUhK^rCJjsiqdj0kPs+hpOkb!niMc7HXFqrPAWGcZD|{UIitZS
z+IEyi8o4j$-h-B!BHUUdY6~#C)Hu#dyu|R&Db^K*W25GO4sj2Rf$x9g=jj??QNX+$
zU#Esv1o9F~eRj=>lvaY5@^Ll_9?mNG_BY9+G3A3I!ApLgR)PnnpS9sq>d)G5*cj)z
zwHl2n+FXkwp(1J9Z^64oA*XU1FA6wCLMm)W9tEq(!z)jZM&rpwnL4}j$Z3&fhePQA
z;qx$S&)5$$P<WPwSS<pNvYx)n26Ktd%?6h}4p&fk9XO^0M=vQyka!*Br&`?xm_n=D
z!1ITx?9g%09*BZ&mG+!E{kaII7|2C9#X#`<PW|S{D{eJ)Pv&4~`q0hUX#6mGk=jl5
zwZlx*ZtOwc$cxZ%k%L(`^;cf)?dGmbZ{)EEeeC+co3iN(?H<xHz$ltJsCT>xR7-MP
zt{!00y=gNT7_}KkYo5Duv?$?Bkpk6_H&IGfgL|EdSP%?a7dc|&yo)6!wJ<xKQVKca
zQ(7Tsd`c@!^I@YAL;7f=4MR$6yB_s|AY_zrYQ613yl$z*?V_qfBTTyx{6Y1)T~u_a
zfWIkUP|$N^RD4p0Z`V`@tnW3y>KU-oSNQk2ni-tBzb01p3f}=(zl&$`M62cd1<QAF
zd8dwui)%bNlg>_9ELth_aB3G<cw#QljOz8(Xr$l^Ehy}S2~l;OTA7n#F|{;&nQ{j8
zGR5LdzEb$?T$JnsCr_J?I$;L0UZw+WzDqHId8<zxJ4fWmuoD(wUh0Mgn0%;Y3y+jr
zgPjOd(Sv@G(1Q%0gS|LfDnvI%JJbbt;>wai9~_d?)rW)S34Lp@Jv%*UblOvJ+D(`+
zX)8e%O<7ZzMN<|RCegqulVdY%7TRtin}!A-49?VzgTv(<CZfo#NlWP|Uedq~GgGA2
zWDgE+(7;V&)uM#*O_SCuQft@^yo3M0EMtqpZ$U8O>_1>*1F6F>2L{qkAyZvLL_nGI
z8tfEDnfw|}6|xI9nkr;FWR6am7m=g0ekiAv5<&Z9rsvSAiQj-k$j-UabI^&42RFYA
zra?)=ano2DdvPduAHg<zBq@98<{YqW>z-t!mCV3xm^zIN3yB;a7@WCUr@G-BK@v|H
zrJ2Md!}SrQQKs$YW!eTWXvu(qyrm&S2K45L2`MXkW0X|W)#6a(WUX%uiIPQsrR&`E
z0zhzms@p)jjm>k=81p3WLS*%v@<1FQ(T~B8m+ylgFW(2hUEYt8obt_C(rDhmYcDD3
z`_QTF^nK`*_C}A@MTX<(kbkE!PDxInmBe$6%}=xlxz-nh2P4tvq^pTZKJrB&$)~(k
z%<`c>D^h&I<|mieA|>~Ac6PkI<U3nQJh=dLueFZTST4BMVdU1~*e|f3p1cNE^`hjh
zNQ+5(=#PGrHs4_6_=L}t{=-E{PbHm<E3xMq<%VqOR6aIW<szj&UdLBQJPwj*f-p9Z
zXruWgy{0)dde4ntqVHVCQm5}+4;T1<>BBuT0SHc9ehb0T@&h;YPhW8mQaI#IUIffi
z8hnRv$SEBeK`|U1GW~>`nyZh8LNC=Be%SPnH%52Kf8J<xk(2#RkqdsM0;TNBOWztp
zDCo#<4DjkYC>oRtMFg}oxg1;2K%@taJ+Oe;K^b_kS`i;GHB^LeW$?lQQgWZs4GjlT
zML;wfVEWX6;X=<Xek3JD3Q83Y<O;`NYEXr2tQ?;l4#GNG<3XXYkA~~1B10lG=-i`6
znDtWuCz14%5g6KRjo}kgJ6a}rW?;)|Wq1=KUmDCfeoBv5Y?br}#a2mMFx(u@RtE8y
ze)WbbuehCN_ZHXFpr~ft&uZld^k#?3jNqXIB!mj-M{?;Eg!CpLKq(S_BIpM;;>L%H
zxwZwKKNa=V@Pw+!s6}DO6@)e)eFs9UlA-{th8J*!Xf-^oD~zk*4UbT-1El<n-b%1d
zC}!+UKsZ@TV@^ezHRG}1dcYVSn~GXnIX)Tmq{j&DZ;F14%%Hd_{L<toF%bC^dWPcc
z8se=OiMQH_=Hm<OguO^1eT$OIBY{7mkt!;X*+PgM%pZdG!SKRGm}kWwu69SXAx8%V
zRZ)z`$_$FAP$t7h^3WCxiPWKrmt^Wt#Z*S>P;6oaUAB`Ep;CoUMubZ5Jz>OWd}o7+
z@i6?XqCq)9#ONr5bY%)<M5wGqG&&CD88?P=4cT>8IF|xiky}(TuPsfGii(ZwqMV=X
zAScXJ3a?$13@mlc588_&bR*{|PILwFGU=!yeIx0}Z^Z(yb~0|s`${Of2Lp)@P#AqY
z&}Qs$@+7i~#vZY}C>dG{K|PdKWP%<rS|t@9z4C4{w4ADc<lRJQHuU^Mi8qMGjz3~(
zx$FB3Ezc2Sh7s+(vR*=?t#I%~isPQ~;*khb;p8jzWo!ZGksK4Fy6N#+q#U{?b2F-(
zir}K;$oXVml#a-GnC=%TgivrD%&Dn>`^c$@nEw;4jQ7XObrDjY5YNBTWgh&+jTxs(
zr-Xn-7+cDK(fn6%B#RVNyiCK#5v~M<MTsdYiD6M<r(R0IG$6(x9U>^OBr#)x$vI4?
zSnaW8TNo{e%E&MVNGWZ@fU#1k9R^gBO8+p0Oesgifbmg@BuL-cl1&U@RM$jfFiYhC
zA$dm)h^ai4?_z+fsGJxB76tNV4v=zXwXtq!lghs_+9;Kx6Inm;F~#B8#mpW)FO0EQ
zN(eGQDpb-Ce-b%GM^fT<kae`$nOP;l0&qbkFLCgd;B;8VXDJ1WOi<#K0YIQ~s|=6<
zm46l7-7~Z-)Bh`r%NVZ}d0$2oDAU3gA^u*OV~fIsGYA7?x0Hew(i8)MuCNFL8EkeT
z`JuAjjA2~Lj9ZkP?X8hRZB^2pWv=<L<>+yfA(1aBTcRHmfS4Q@dwG30(+3ZbBB!#}
z26i&#AsURPm8)pT1<zc@I8qMgI)Z>yM-7XKnmWZNqKK7OxhU7DtV=_ZcO_;nN)DfQ
zB6Eo<!E;e^_^z{MGGTL|m06X%{T5|xX{K>r=ihTfO-2|#uwlO`TRN-JZmX2nMPcSF
z#D<pK%AGZ&ZC84&(YUJ=+;t-*pCktpPVnch86u_`jKtxuMBqhfW6KmanuL{2Y!gNu
zq#P$DlC-IXnUb_mEh3Y&O^X;CDDs{Uv?JYLxzVO9ZCwz`(x#3TxAv(N>?0}pC2j5L
zND0^8R-QHucNTftx(+6u+m$lDNSO}q;!I|05Bxi`v`bW&r9E^7!h}s7^(9qB8Ss`y
z?aGl~gq$A^fFnqOop4@aWr9&DA%78)mr^<=fFzXIe*~2EnNR=&f08r2C1Vyde8hg>
zHVI&0Q3ADr7zB%upbe+E5Bw!z8Q3IZ#K}$sj8KTEMHFC@%YU`w)AFG&N}^RXts2mc
z=o((CEZ~jgur-7aCcMLH<(CQnuqa~#h_FohK7b&xnv2zP9~vSJ3x#57r1?!6UJZHR
zK(aVMN~j82Piz1?NRSv*ZH1a)gQyXcA+Vtk`@NxW7~BIw=rE*<7l?;tP-EeI9HD&2
z&)n5%$Xt-^9E-HiaV001qqzuieHAjvn<VIxSLpn~2Em(H21*tJiXpiiC@BX>LpGIc
z$4KO&K-yvfvMfR{MW8LmdY?1}Rj=1eBF{8+$s<f20n0S?4M8TJJb}$7<Gu~T_W0H<
zfoFW{mM|~A^-7R8ncdebERko1x;dCN)Xj5<bL$jhP#`?<zT0qm41Siv@(Idm8{SX6
z8)JYMAEgFoOaTY2_ht^TBm!6#tt0~AJr7K&HVEGHY@HG+=h-?XG!rkAfumI5NJqSl
zpJzi*GWdN6va|>r1`|^~3#Tb4aiR;%iO=#Tv#ufBwLqa3Wo)ofs~!C8ond7`it##H
zfg<Hwj|7pb^PvGmDhH12{sO=<AORFY7K{)Hpk=@XD1a?P#4SL$4v<Cxb)~7}xi>H`
z8b5^hWk9GaNU$SFeiJtgf0Tp2*$c<J(8mnXy@gI@<0SKG><o*|`j~Leg5tM;&<qj5
z1(jxSt^rQ%04b&gz%?5L%B!;g*Mtm~v?dAJ?Fdpr#7XHKXTifQi&V@=2y*7c#ACF|
zq6D%Qf#_)1DzG|pU=az=E{tLEU8xNK^g9X|Z;^72ldaP>Ts@fB3VLr5a>@#9Hzz8d
zmfv^Kzp&-SH)!ZKcpM8n5ca-fgBT2>V0`J>y5%Z9TepNn)Ji)bC5d=w_-bJy(*9Ve
zi9s1VvZ4Vh0`Q9mNQ)J;$uSMNKpYKIE}+LnNyNy`$i?g;4Zv}K%9>_ytrqO0A#A+K
zbY=mccx?EU29S!vxD3j<<6s(Gv;fN_g>ae&2+11hb`A`_GLFG04De1+f-^U9#1<td
zsu$r#c{H5h);uMjd7=<;G=6BJ0EWyz8-@G<rk`L<Y20Si27V}*NPN^HNR`h>dt$5_
zWWHcnK{+<4RvOj|%{3_Jj`&)XLCMK0^(f@nAZ^&PY|9SlQ+TwL98xaMFIKKhgBzt7
zm0+~@#wb!YMkPM&U5rY?voR|0X=`JOaBH|>=PUeQ`Y8$`I4FyE1QFf|#g=fo6&f)~
ziB@b#eJC{JqIgYGkjMv{QhZR#qHvW(xqE$5A%tuV1mfv)_uRNc%EpZ~<Xf+BQ3SW4
z$=~-TNu+EXTRgm<jbk7H)QoHKoEt+x*u-Eh=wrJWfI>qUCF8M841&<MiH3kZZIc61
z?p<y(BGx_y_o;n0qE)+WM3`*}P8?g0(;KfH_595qd$v6m8}r$>SnTI#?7T|SzR#j$
z&c4m!n0T)JZ~>*`)y(texwgY47;$gR3aNVTjaj55v))X<BGB4&H-wNp&vqEE|F*)n
z>o6vz4&xB1UiJ~3*ef!;PUE$h{j}{gUb9&-=XDy#(k)WmR_iM(n!RqT^^?7f9k_{l
z89W^6GK*B#)g2=m+jVuvh{kqZ-7%uET~|+zXl~d286%q8?QSumYrEZ(N7r_{FSGHY
zkVQ8ba&MP;GUVPa^EI@UpU|a##6iADQv(Wy*tuye-D)?cRufqd8eZ^XGf+T3>SkNF
zU`ClJ)=0`c0bG@?ICW@cN02TmjTWD-8!yh0uIOwkfL%#mR1jBj6DbLK?sr5mQ_<{-
zJf<?*6-P{kwKEF%_)4WVD5d4*tmmg{+^wFVXSAe8C&zl3BT^6S3U8%~z9@WlotWdT
zXH+Ws$0G3^bz+X}k~5Sk6Ay~6P)|NOdOOp0k}r#{7)?H1y23B{yy=Rp<O`@bp?UI|
zv`8OMsor!D<F(Zl-pCi(qC}@7-)t*2sQSbbDF%^GzuvU=`7-Ry^^CH#oGeoH$~m}t
zHOxV-3OrLgg8cA~?P-13-?@=Ar9L@>sXik!ug3nI?wj!eZoIx(9~u_n+PdW;Y{rLZ
zl?@?Ik2E|SBn7{pPa{JAusnpcd{`brVqkeFdqtP&0Va+9VR(oQuo)hbxtsC9A@ZB`
zA#ch~q!3zR`eu8`gST(ChqZTC4j^3VF!%J{w?0??Np;E5mHELjJTH@BzEKv5-3ErI
zXDG~Ay_b1%V0?8or$J0vlP?*~BC}H6Vu*A5R;+Hn^xPUV^EJ=ic-MQK265O#+UH4w
zUykM8I*lU;)hC(tY@K2x&(<fIrRUDLB14t@&bz&PNkg1ri=YlU5SKKp*IIYmdW4;b
z3A9OC<M38pf+1d_fD3c8M&Nq%5{6{PqENtb8J0-`ufLTj%#DPb%}Y;%ZF-To|B{I-
z9hu!8aDs<J-bqdk{eYD`(wuoXJi&>n9w8Vmg&TJG?$_2MRR^S8zhu#8R`yF)|6ZmG
zcm{fzF2Z-v18b7Lg#7rk^~sORe+@51_g@?t9j2k<1!qT4*eUP+K6G7#$D|K>PvWyf
z8o~ssRv&U+!!N@>X!xi!ymamKGGO4njAZ=-q>%MNdsRN5yJCjuXX-<;0bf+d$rOGi
z9HNR5qF1XA$woZ97c>DqLO3xI4kX9fB5=h#@D9os7m{2i4|wMQn(&eX55NisNI659
zuiy#n6*UBJVITB2CMR`h#MAx=3VA>9A)Oj{?DxTYBt4sb=o-QEzYm2((?i;)H2!p=
zc2pjvmz7u-FL_}Bh!HyozS>11WAe;g6fgz{QW;U;7Vfi2#P}kZ@_50)+-FBCzayLW
zjQ=K4!BI1NO%RHAnN-3L&PvzxlLt7-;E%+iGD}bp8rY{E5AewM$yf+D?faaXAC%N7
zV`sYldzArVctD@JVh}<An3fkJnR-QFAt<5Ga)u&up--J6Y4YfkXow7nSQHEfMvz5e
zEXvZn6iS7l3!>Y+7@3g>ID^p}aY$bj1;%q6i-aH%Xgrq|9`z0SrG<}Jr`6_2P<#8*
zm4R{$1OrM+{)!&<5snggLW*FCrDeIQLqRS5lJOIPFa2U*Oi24B)d8_Hfq=Bf)*K0w
zgfHcuxp)c$pwhx#;*2LoBI6mtd=`Zsc7y`;OOM6~7D^nbm!gR}Yd<sKs9&|ph|23%
zEi>f*Z(^JJRq->pG!@&FCV~XN+M}rYt(OEst@^DC0^wNwmI85~s<8NC0M`-NT&9?=
zVD~Kx4?@BE%||7o#fSp-Qhe1BP+=!YAq%%of{098Z3dm?Q{$F!AhK;y7^i~pw?Hw&
z_;6p{1Ff7gZ9oXKTLebCb(|Epu8@e=3(Pe}yM?gdIu#J`*KgT`U>O9M+a5Sb#J88C
z3m1jF!$ot`N`xTAe&??aj*WhDL^}2|2}Ud=k?LLy^&*(vOYxL}c!#%D##{!8<Hwy*
z5n7mAf8<9&P}rh~|JVR!Nkow7qA*+%_MnGKD`HI-As?a$N9{5!B4l;p1yX|I2B<);
z`$>SoJtX!>5JJov$8;GHF_8c_%n2dzc0nW-C3w^yT^k4$3v|YZlpMcq0E7ZBl*gPR
zqJ@tIY<ZEgI(eDb5O(aR_7*~uy~2$UD78R1$#O(E2T~^nokkMEc~+EkKz=$Y6O_r=
z`+Q^uPN<@`vzrnU5VakEqaTsoUU5bY|8`mB5F;Kari|=fZ}rvg`ipA__%vegdo&UJ
zp67(0*H?wHFC5jz|D4R^Mq)JlqQE81SSpuAk0JH0pd?1!`&s!113akwVubHIFh>;Q
z9{{qP-vAFD%`h&Qz?@BeK9dQYp-V_M@URLp86f~`m7WkRFy-%_xOfPCTWJq&%5B5k
z7JM$(Fz4p793sc!5XNpLVz?>&AXHLMNRCM4@WRbNs)t*nSTY;L3%mjbPA^~zq?LG~
zOkmt@Dvihd6bBjvQdpvWkq~@Sf~&PeF2-k3*uo260XZ~YcnTPk7ghq2aTby?Q(ll1
z?gBb6&)U5BkSB+Rrsw#~)bt#mnKixKTTc7{;FtvxG;($zTrz5|<R!OD6U=0XMZtO^
zC2CQ?q6?Ez>J7507K$~021(q6x>jyh{1JZV#*CEuiS#b7M0xznP1g%^$rcISkZZQ^
zywMH$XkH2H4YH8YS@}a5GU%064htvY#b3&h^GYEHs(FBt<19d`oma+qK%*zRd9D?r
ztQIAc@lv8($=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2klreb
zGS>PCBzepT_es;~jZDi$X<IgC5IEe281_u|%yp`iN?bQ>qLpi;oJwSjdgV~}2)cGy
zX_<7o+88<#Q(cx@WUmHjKl5aBlQ&g(Vh*fV&NT95y>h0JOY4mrp>y3Y#vw4cYE>0r
zqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0JoRt(k
zv1USt=vUNTAgA&e@J>S_^QwKzlFoC$w=C(Ht9Ri(z_!T}564Ss-oB+t=My?gL!et;
zZ{D>ZJG7Aw?T#T=i@-Gc^=MgbCecGgdi(&A+E+1i$e1IG(G^UG?06PDe<^|9D`^@@
z_O7I9$GOle8xG0(-uYBvLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+845`O^
zR}!5=q4F*?ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$Dv2`0%o|;t5Q(|
z1Y!{eTI|Aa<0j}#OpV-2)*5*+Nb87#B*YD&a42OJZZ?;dpRgB;@_~(!KSU%GQ#WE`
zKty!P0EWZm93WQ5;ljiRp2s2pSf!(rZd>F^I#a#VXM;*Ci5udODjq{{ws_@!rz^#K
z@C6={Rp<p0Kai8`$_)n!$|7(aQ@sY-`4MH#BI(gPP16KriIOt-6(|P%K`VRc%z|^k
z`=bTAIW|Gzz|QXq!6ep<cUm%uN3$qgAXM-0%1MU-J}4<O34RlWbRaSS$8m*n0zl^o
z62N*)y@=Lh>Xm<i^P+OuVd)ME?wmAidu6x7jLq6VFG2^c`aoz!2k9%*IW!_m0Gx;=
zhF-)ka;GJh7)S0>X@G(hm5Ojx!wl>SJq5s0P$1ul!Nej+FF`adie)$*ah#kEB0@by
zAtn4U-W0CW7G_JYm{!6{EfSHA9(BuY5a3j+$pPc4aKTtyC^F-&138STQ4}hd38qYz
ziFyf4%UwVhz}pH6G00N$Tcj8Zs-e0ZT158pO8N)-*P^7$8~|ZnC;)&Eb9uptGv*%p
zUc!*EIM$0OWk-_m8D|f|kl}K0o%=9p1_hr<ed}<=`x0i&UAMt?MGKf?P!zoI;jr5i
zk|5cH?e053T#B9^MrqAl1Ww?ARORh)yaYYxiZmuXovVxuA?$*ZlY(*4;rKg<gy)5R
z0IWP$yfOjxTzCjKmsT&c8<<Wkm-Z5NpF86#6W=dttYMxv*H-U2Sosc@-;qIp?!=G-
z)S$cWuY0JL+e=V|o`G=(NbHh7F|ks*-2jp31=;`@MQ0fHA*@ArT2a!f=!NTmBu;ld
zEpKjQ-HA8Cu2;pnmyjX7pdjwt#kw(X?qa=A0XOMh+B+~Q-FdG9w$ckvBJG3jx@b`e
z#9dK!1jKZ?Yzdm_M4<qzrn?>mPtSsVIogEbJXFK)C9qB};0geGeo{Jy3)sy(qYqXG
zd<jj|T?Qv0j(S000G0HUa_2^72rltXT~23WqJC16f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E+#jOpG@-G682@PI7?K9>0)oe0zKqw(Z`|`Fz6TI^+2Z
zL)V2CLY&=C3OPl9TqmaxQ%*czcVY+<^Y@cN#sD#QiV=A|5MS7p#6S$<Ps)`azrnp*
z(;@}tY<HDipy}*`!lg_}TCmC=EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NZ^K$UI_bJ2&D^BKxpXfL{8fkfB)L#Lzx=%G9(7t4-Btr+f$>Z7!>Qd=c||lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3jawNJm!wCf|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR8ObU8NE*qN~&fmRdk@*`Rc3A9-Zax*>olR&^+qg_R#lrRiQu
zPIAVV$xm7lOG}jM#PSoRUa>?)X<(fyQK@Mtby2Dut6@mnWAqm4-hx7<5sxJn-Y7jX
zOLI`sWaW-hMLUfdQdgq@NREw6c+?47a-7mU!H7Y<M-{6Eu-Qt*M!gajG8jvml&a3M
zC(`B_vgIy^9)q^(MS!5Kpk$|B4-0&$*TZ78tR~}nCvXz3cLG*(#BlRp_-oY(834el
zR}$;b=pn@dHTBj)I95H!Sm!1v2MFxL!C&ly6&ciTyH<qyZ6{P8EA!M7lhu3b9m)zn
z^;TsWAU<Xf6$+{cZw6rLO{@T{dN(rwtKQbAV03)(N&Zrqqk6VyA*6cOvsO~Q{aH`R
z!!F7iOeuM)3oyHSae%H~9H6Tg%zmr^B?|^iM3t3;b)?b=!ZK53Bta>vG|)hxQLhTt
z7Ess?;+p|gG}*8)7K}OvNbG~L-R#1l-ReYU(yaXu;sRy7$_~X!UuCRfIj}NlA?&Jb
zUI@F|4P&f4R@O6ACo2OR3z($=js?zOpv&rIdCoHfy3<Y}J0EMQ(GrMaYh@}#2-ap!
zWWBaBIkKo*nj~5Dtt^%-43|dD92n$4vDB<EN7E>4(3SC&b?RhaJ+hKr8DLrLuB@~y
zh*y@}ESXoPUKG{a?ZGI$w;7EyD67oMEZ<kAXO{SbdHMh;&C0rwXvd(Ho5cjn5YB>w
zG?gDHN$5(sXW7ECx3jci+2m3Eu*~)-ka*Cz4^oG@pWmjF14sT%4~Og9^l&&IiYV&1
zc_UWQ$MRONC}epwST?e}9w;q&$TPz7ljS#IiOTY=u#9E-Ur^|B^U<IhX8CbgFtc1e
z46!PAP?p^+f6>9JoaI$w>CW^zv9xD-r5I9Gek;UO9rA6lh-i7gP-nCpWGqEmPBd04
zg{SQRDHlzL;bULrty_Un$;!QMD&2Ltp&ujrb<jO|aBPKCacykHRB>&{CCNgsN4YIo
z4YpjHtQafrCu+*dJ*uj+aG@R`^|85GS-!SBv8%c*U9~S&zm+!^1#*wg<I5_#<rQY7
zT~`)R*5WPSGOP8%|D0okEXYaSk(5a{cF)4V<>qGH;BtklxN!Q)S$(*C>8wxef-*-5
z<MPL&%JES?dzL~jx4r|@s$BnBKDmMeSYR0e1jkoZVXi0xlxf}~5m?GOLls!~xgr@*
z9QxS89T;<#mFB;)%JkSGBv^&I!YCMB7J(MWm#SF@A$O}YzDm&<tNe8ZZ=gCh0zAG{
zK>OIDKv-qFB1Kq+yP`>0&AWn7RPMVXRag_eqFG$wPrT<@XS~8<P>lT8VrLk(rSKZh
zYE~71!+5NU(m`Q#M)Cx^Q1eL9J}j{A0$gGd_6iYVk#>d=9V+BrVMeU=&d?-QgLjof
zVMtX)IH9ckv4ugg@_a=~u{ym1saU|ig01+AM@3{gYOYk&mZP9bMRqxgrBwKrqZG<f
z@nON2iXU^7Fkyh%Vs=I=bxjjuQ8fY`l}sy`&5dFq!B!*`Zy^U@wpaPQMard#A8BWW
z+<6xBsGvMVLT!<I-hgaV;e8>^=N<w`iLWq0M=_0xCB$AjwtzzidQ}D_u9hR95u<C0
zdF1fA;vJ6{kARAa^v1AF+7i7nZc}yc8!YV%z&vz9Rg`8NZ08=y=>WGvxMxrpw+YWc
z9-$ex30;%tZbp@QW60*@45y-2IYU4dRN(3&A#jzmytc?!&k_%ajs;;be)a$%d7$&0
zfm;g1ja&0HM(cudgMyrEUeFcx8@Kq_LxXwKBYt>MkZXz<;{&7&f@OSXs4u}NzBrwx
zMaDBzA!f*P>fRYmJ=JL<7M!;#p9&RT9S@8MriRHRA1O)FrtW(n_j)_62zSMLduOaS
z1H#v9FVm6~F&@v#7#?5Me4i@poDW(Crqe~Ak?RL2^W3A``2?>Bcs|<^CJ#!6v!7Z#
zkKAQN+rz9-0r~Eo5&PLvz&_^ehzPI9e;QLNH-JVNr4P`8lj#LC`egRO0ZJsAC_{lJ
zsLEn+A5y`i#asyvd~je>qaR9_;OHSe%DJGWuo5$1e>^IAgJ#Uk?QrCFR_@2LuOc}l
zTi}`N%7d-2l1yk=t~3<duq#!C)^k3kjwFpO2L^tQN|T`<rgCZAnW1C)(!&YreD_Mx
zp^!2~2jG>y@D7mm<46rfUeEzj{DP8)94J?nVB~3UR92EBc8Y0BJ`iORkLa8aFyboH
z$(hrC@%8V>;aA3#GrX$OsvIDA%DZxA-(P&EJM-<8tL1~)XQQT>>1R4-2h-2;M;&96
zXbjJ>Npl!TBC6!GMasM}NeA=WmBQwO*=D-+#~`zs<~`6&N6kt(XL_A8om?q+&g}6^
zFq95NuFB<Gln^PV`}qLS%amd|kbHv#!6QkrXJ)NFlG2oE=u8Qp5(r2<vlEXXW$LGH
zWtdhg&(V?UN<&>zGR=|Z9v^$^qz~p~>iA%0w^A?{B~ma42M1xV)J~twz@*)MQQFv2
zL>D1Pn|6`a&Rj}aL7Z9IQx__;w3V*vFyK}?>!KuMI$C4ThIM9TD`nPEv%b=5eIkoZ
zxwt-os9hPm9yZ|0>2-X9S-%dOaHR$Ndqi8_uq)qM3Y_w-k$&t*x7LegBF{}Z%!k8>
zT#3%E6l>{X6ZeYJr#-k%lYX{y(=ZF$m0+!NKnd2mHL$#u?7b+Velj84m1A9!z#Qum
z1teL!_<-AJY_c$suU@i%oVii50QH7>@D7_c-7ZIxl7nsQl?;?-GOsU+26nXa^?jm}
zV`cR_0`@w_4vk8f01j}s!VPfj&`xliMY;=nz?p+Bc!EVqxCiMQI0`yF`il_8fC57B
zJU<F6!C`7IJO!W6hPU8|5Cka00aAW>Ru_C3&r&97%iHLvH6ehABS;A|0lB!&4Pe5V
zu`Lh^&qEbJ6(Gd>z0fQiM{yxuI1{_&wepKd50nXb0FFY}aNyV%0*51lQ6L?QkX*2>
zQ*uEiE*zc%p@A$y@<H0^g|kLJ6$ffwccRev1rP|~k~m@`3%kUbM=p4iMTzkc0wsSa
z@mcPzTMS50DvJ{Q5!#9){alDF>xYm|Nz9g@<cM^0Fe6<S|DZf~!NcSa<%q`CEfHhJ
z)-7;a#`dj5jG^KE@XLj0v;F`|v`}ySBHoT{4k+wV;5mzu3P+b{K-m@q&!Xh$+SV&Z
z*Q!qr&SVdY|1PES0uV))P!McK_JNCFJLlFZg`MW)MHw4-kweoefTKmZMnNDsd_5aX
z(jp}glpZ7(j#XhTIkddOV{&BX!^V3gC73Cbu0vZa@Fz$45`sgmb`DtPS!YVWAg&iB
z!JvjZ1$Tv0<=3_0SosCW@dCSYIHw8`Yf%z<t8d+M{C(?{!XWgmMal`l&9MjxzC{SH
zMG2O-txt}hUSB7`fNHGzb#G{5j`-d}9CJ9z3YBb80=Xor&#qQtqv=6`h~R=g^LRKU
zFq#vqfWT=-kP;cKj)A->tWE(U-sv@Q5#Em0n}j?#Hncat2yrKi4MLFx7#D=+*)Zi6
zr47Q)9iYVeSX~eWaYs=Jd?Dc5MQa!#@IXn8#%kFKa97I?e7jn7;@fG_iEpRsc8e6d
zNXUME1ExsGe-0mHp#uiR?;S$WvocP>3@$=0?YZ?zPMmD5!3fH5QI=#V%Q*;ZD1t;>
zl-PJ><0C-CNh`#iBiO(e9f95j$mm3o5NKmiVmR9Lw-NX;Cy0x+%yICu7KEfDe!O5N
z7iF>K6dbG*n?iV%ju(1iS~~o-g?s6VUm;}7BM31ZX?l437sjTetWe=_I$$pZ)wu|X
zaU?)bkT%dyM-Y4ggE}k^i!#toY|*Fq)i$V6w#X--#tW`=Q4)KUeuo6#I12WZqzxL?
zVG=3$RL{Ce1+XfDiuW!`g3s!fzJYpAFxMi;2?k#{Kw)zs8*pW%!-=9d{@s8zJ3d;b
z!Nw_3__ZKy7`G0Tk;1_(iWRToMP7KiBo*ea!*^e}ygQ|9xC@Pzb>TiJ;!J?i3L|)@
z41FoY<-Q5WRita1dq|K_i+4&*G^C0JrjDXWJG%RZoSZG1M*qv#e>&DaKi|Llp5oQU
zoBTfA&g=H~;rjKT|Kr!ceA(Ce{-6B6|MlllqsSxfXWV-6O@-7sj2rEIWWhq|C!8yA
z5UhVLOhvkeQAoNg?hCI_)q!V_ugS~vUQ>TJD-A1Z>Q+^FC^A;{6I7H?AcR$li{MnM
z;UW-Cg3X%<X)0|6Tq6WbqaDc*(A8CU(I8Wd#&`u11u-v}kj;GatbC=+tPHkG&YaAA
zQ*5>~r=ud1T#12n6VZ1YHw>x*FVDCvcWF91rLkE2aMwMNCdHGHnkhm)?z{P0bl#s@
zcnRl^>$GRuZzQNog4S1lQYmOkor*W{lVyak9T1*v65fN3sVaQA1SmwRf?i-vvZlBU
zWZ|3CfFq8h^+%?(H$dQ9Q+^`KdRwKh;`p~R&jiv{46>@Wu;fsok%KY>{U*$Cp2>#*
zSp^1{2Gk*R<{KUhWoDg-s6SD0HOHCB?MyhUkV!-q5x1p+*qt%7JarJ6c2v;VlA(-%
zVAUrE5G{8UP8~v?PH846{&uWatW?U>C<X-S?}*CztEj;DLCSACLdIbGUL7fQ{o9WD
z{-G%T)cq*g{7pAVu(2Bn*SFme%t<-_DPu%Q{%<;BgCMHn=eA|~w;d5c&3*JUoC}{j
z>o*;-0rT;+I%-SyZ#y>o*rq?j3H!Nmf76ls+tiVi>${GOwBj-FGvbFn4~E}#<oR)`
zBPsLSj`RFDW_~K3who@(bmY-<sUuIUZ{>77lJ{fmXIddX4z}NP<oS29qbT#cj?5Y4
zDfu&#=RVHO-*n_0Pjw_^e%o<eAE)ro%=i8{m;Zi89^ZJ+{@f1q{%uE?9(c<COt_Sf
zbN@FTc|CM?6y^D@qak39x5&>dW%zNg{QWQL`Wfm7%Czq~8jOIvq<*sc>vnDZrXz2+
zu8yQU-*z1H;}ZOtAhsXZ;%_=u!9H{p<@vTFi%sB?{h7+y$F=*Lj`)3;)qigHwSV8S
ze_Y}}h3;S1`frDtf7aEpYKVN>@!52QpCJgl&hQ(Krecvna6b$A-M{NZDCD8#yFS&C
z-*ki0($o!v``d0X(?GTPS(u8{b^d-gYD7)lK)Ao_R$z8ZZ~9r_YS5#8(}~K~M5if4
zw%>Qc(LjalXMpwWl;3tlm>rTPe}0M5+qWI(^`Y?n40wc374YwOq^5`g{@irO@m<F~
z^ElO#Fd%)Xn7`>rO?0RuD8s((*sl+T^=CMLK2_Mi-%*-wS4UF5U5-w`i`0jIZW$6#
zkbl#S86M7VO#eB*>E_I_ZoIA?kLpstf720Kx?So>z5QDSfg$Wv=6?z>sMP!4bmS|*
z)e-3r=lN|%mdn6n;b(?Yd^{h1(~+-?p^gMOwr@KUN;}^oKR1Wg^W9?L4YQnF=mr8^
zhrj7I^w9Y!)8Kc{9=(iW-PEcF_j9fn_xqh~a~W&i{}^to#{9qX!L8>}8FNwK^MVIQ
z?XuLeO!DP4tL4@S7#3K}vMA`K_zV){QUiEzi@d7igQCb=B*YL}W~ZDQU0C>VEQJLP
zB-K1yl(5jKEZR<~NsTJ47R^J|*OCwxOI2tq%C${emEQE_@E^2_wL#ubn{(p?DUBZw
zyX%y*BtcQyEN4kkiZh`sRIJUNXMAI<&DN$b?nXh?**9K=#cuYESET%6ZJcz8l`*iQ
zX+*KjiW-tM?H4QRJU65C%sPIjSP0vz$`i_Bs}hE?^N!8<8pdZ<K9os$?6%ifK9x_D
z<ys{cW!+xUTOStjv0G=u9Jm{2V;w4jhSqpQ&>Wi)e~dCr2a{DdGW-ClD=D{uYER<y
zIJN?n@;(e_>$I(;C43qxc`3I?tEv+8ja2Q-bf}=*Cfdn3+x#HOI4d(Y%FL>^XLx*`
zXDbLwA5awyrRPY6MdOFI%A?BwaX^m043rjT?bH1I=J#frjA?sq)C6O1er+DNRPL|M
z;}+8nY=Cg5WocF4&7I8!AWNrQmS?34ugbT=%U2~{=?UD7<6#*(c5COw60Q}}zzVK?
z>y<pJkOp{UTSdFDu4{!f+~7*vdM#n7SQnOXRb5s3kef1<)5F|c$1!}+&9%(%Q?s5g
zz1UUpm!57SRKDa54;0I6C&r~5`7xP(6HAc}_eCmCew-3relqy&Rp^+WeHzt|7ybW1
zs$Q|<`>bAV2oE#~IeeNd4#XpDm77<*LR5A}7nmx$wlg9gTGw{ISiw{oqKuu$64Mb`
zkszt+5UiIaD=6`!J>C6yJ$A*&UZ`!Ue9Sjxwc=l>jjl9H&o})MB>wpTmn*VqV2tP1
zZA82J#5h~I$}Uz*ufV3%_6dBOl#q#5c4HPx7bJLu;fyRsuDF~f)a}|jg%q?3XvkXW
zSM|snx>Yy>Yo*VvPq4Dh>XoCba0XzK1@f>$nsRh>mO?#hl`#n1y4HN_G@=cq2<1})
z7g>E;)~v5C$vkcUo;B|A_sHRGt@eK2yG?r^H)^H!A&9Is+xp}>DhuPnW!TQGSB~V|
zdL^S2(FA|EsV-`e*6&z}gUPs~UL#PiE1)h0WB1l2&Y3N^1=q_K-C~KieKOWCU3(SY
z7Qy|^W=Sfp1=Ce<;VP(Xyen<Q%iWc&w7!q6M}&R^#yDa}bMkKrS~-6m29w4u-+GK_
zD{>U&!L4tdmRuNdIULGulU3I7ifTsm3<q3fQ+3J+D2;E+iw^9DrVKe~#l(b<c;xho
zRzBR{I_{u3hhaq_v>^+X%QjIyyZpr{W7JM5ax+R}pZC@$_^-H@dC4WBplj5xKDGKV
z%M;)Kr5NF5!=d*Y^=(g;9g1M%=%%>%)Y{(!G=k-)ZUVeW+gXdxbM@49Fb5{d2i1&2
zR8?6cz&hsW;xA6jv+GuzBbpVr9pZf|h+;Y>sN_j_rK2o_BElo$y;T+(&`DN(39bN6
zzlxSYIQpU}ggs)5mMyxX*z;q$DgfHrPK8w<IQ~sRYkg-q>L&xj^H>Yt{lkF#a9TVS
zBb~Fcim5@=zhztve<*C^j}j^Hbg@V3KT-r(MkFcuvA8~tq>Oi4mj@m<_UQ6J?toRK
z&0Jqec}ZpUu%`qj*|R8|VIDd5=mkzE#-or(q+T5MC?paOCae6tOyRH!x<L-YqA*h=
z`MM}L<;Ro7SDe`<$&$*lxiQ|#vbix{W!l`SHZKYXmwFm&zr2+Fvg*TdbXN|yQg3pn
zAFL|#Qu2*e#@@K1#nI(5tim-PSwD7{D2!B;?5>=e)a~r9oEo_Q?#ijjJ-a9ng|xd{
z<>2A@W|e}6xC*Pt9b`Khqel*<O+^u+hnZKwn_Fta$o*v%-V>=<tIbvDjAhZ0FyIco
zbtJ$U!g@?EC5y3S(~CK0M-+Zy8keD)qNw0avAfpOk{h+0`M5jmt_3~eHj=i8yt!2X
z>!rjxyNLhuOZ3M9l4Tc#h(MGs-86XmvG&$WIfzl83+HFz%e^UR#3Cp=52$d9z-&Xv
zR;A|=In63R4?Y~L{5)9BtrGMSM9nHa4<SW|T{0`sT~D)|=V5>XYA?Z-*`*+Ryem<N
zjftf>YaK4gtFSWfxo5REj4drgb}1#pfnvluaxX<Ay(wtr(3t9voQp-MRNNd|SE>)t
zxmX7;DLFKqKHjpH9)@noHYqCkPCcSRABT^ahO#NTVPW;E!Q<7g%Ju~Ohh0qfbV?$g
zwRp~&vH$^NWt9a8&?=jCdjX`%$`A=eDw}%l_9qJ|<{T4l$|haF0WNi@IAaoGhEp$J
z<Z|1T$aTcNm0>cWppGD6(n#T01t|GPI4ft|RVbuklS&FQGf=rRli?9TP)4<e%OL7=
zI(^}Tk8<FB+Ss!HLurfJzBw?w!=nE0NlHjqWuPgBurmH(E43lb3oxcuIcUf!uu&QQ
z>v_ns%&)IsV#^MYGHy`HSaXc0FaWS^%J>Et1{(rHcfhl<j&)GN6AKB-90VJTN{^a2
zS#SGApooL6+gG4T#DWZ6#Xy`eMJqZo5?E#YB^;K+#s|K|XsU3Ylw?D}TR;b?j5kEM
z94yiP3Yd+U0e6W#F@qET4$&|3AKrH?TYn@eCg6qfl8+B7qoCme5TI^gi;ScI)0C(z
zR%vp0_ZdN$--IusmxMH0<;z(ba}N{VX+WjK$O_ygjR7WD(!gGck?Bc+H(+@CFM_ay
zP<p|=#J6{}muwf-OY%)c+5<8szFb%@9eh*7z2S^@p}#=81}0`O2@xS)=r191Uf3@<
zlfAHCAaqL5I~FNF?)ZcJuzU=LBe+bM21P(&t&6hGIhU$(;(%ot14lZ93Ft9UP~uBc
zPJx1Qm|z`ObZs0+PVMx(F{Q#Rg8tw;W>GGrDQf@3;i%dceo`U|vxq@sg;_KZh5YE*
zcBa}`S$-$Z)vh-V07y*ug^sFv*4YZXfOS22&bWLRfp||HVMrABlfiK^l;as_{gPyz
zEe9vl`H8iyq`(vF+a>nrnctoaMnCa_sVqU1Ml{(~J5naBZ~&i25!<k|E>a9fIJ7`g
zw?h4UaAE-UucMlyDYLL=#m6H^h<43n3M-I5<WejOK+n>~Ysx<i%(Er4-3wc7?P2Rq
zWHso1ol1E`5k46mMs&4bBb6igFz4MhJW7P(;U8Co{M6sXan>8=?ME~?X*?JTc<<?$
zVnZwTWC8CzdHZzLI_XHYFyih#4U1^{ih(D>Bn=RkcN_oC8><U{l(B@eA9p<W7G<Cv
zOU`Z9@%UR5>_y_Wyh&(fh#%GeHziuYl)Is%D2Z}WQX47&J`_V;6oMqCj5OjkbQF59
z0^~y-*29FzholWFNIsN!wI%@b8|Ow7@c0d(NOkD|X?^_0zeBE+tl3eoc2PLV)Yq*r
z`tGzTTVeFwj4&mzHeBb6Kmf|HDO(c?D15(`F-QkU*-H@EceV;;GggPza{{ec6D;+;
zwqp|lH8RtzF#C`ZXTt33h+!}!jdr{dtqpBQqz@Vm@T~W20`UX*iZyL~c(e@ARxiM>
z#QbQV?bpR#1fj)ivI)@{KB1tTd3arv1tB_Llm$mC<v@o6!zvpAn=hdHSQFqUTqlc?
zf8y!`{)flI=p7)^iZ#Ki1=LFRL2LcJ&Kmd^j481JbQ_By<j*TW1Pw(SJNy8v%`up|
zU=)Ur6#j0?bfQDUIB!kR%JK3t1~qor*{v0>@}n*T?HChn6djf4gOXB(g7qdS!oVqx
zcA*q!pOZcT0<Bmp5ala66@>DoPT&vFCKd&b?Lb}*0uxlGIwgnZP#+F%pbG~#@_1NT
zPLLQ_eS?C*Ir5-5I4r-sEd-=ql)|izCK>lPxihfkn!p%|d>tRgz5x`98M2Bx4YSH&
zCdPJr8ozAn1m8kW6RXmk1B~U_bHV1RKI9aWzc}8LoKj&9Ac>o)#Kwrn31J}vjyxEp
z#413Rn^ol#+B!|AIW3!llU#T!>;}0TmwLhcu}JJjaCaz}CL~sxB~9mk#*Y{<D38Q}
zM<)(?s1qUG9bx`}heiO2nJ$L0bO-sxh)!?J0S^Fs^Z>(0SL(tmVOFw3LcKRc;j7dF
zaP-ZDC5`u}8A~m|ekjk|0m%L&fkme}4Ybh*i{X#DU@`J-c_b;PhxqJBd&oV4Is|4_
zNg>V!tEvewWZ2BY23+DQqQE8owPb>sF136E8Y&GRNntN0^G)@_q+u;I)=c1v4^0~7
z>dmT*0++n1CUDVtH#!$tN-+Ta4--BpD_NKgw37Y0Ju{kQ5wOrePO;43KS0V;fU31~
zKkI&_Mb3n$?YW_;d>^dlVWvB{b3+4io5nVyM}&1lOu(fbB^gbQ*4}UR0;l?|UdgEr
zy-%nEi;~Yw6LL3D(aog$BXj6Yi5A=krpq1=6ifWqEa<|lR{?(G`C)`n?fKX+xq(>(
zMwA1EV$7s6;9(IIj1~`nQ{4w(cpKnZRk5ZBFeJ&}%t|<B(mVj9{YmK<9n9`;QZ$j)
z`-m+fkSo}nf0MV_8`XDty5FSLiho`FMYQtgl==wO_LGv<Ut<hKPt|oN;2|d<+TQSL
z`=A5{t{J2Ad*k)IQ}Ty%IU8?h5uln`Q^gsCZG#k)e5wfpmtZBIloP|78HCtVrx7VB
zOsa+$*rRzCh4YNZeYaafjuG3X5o6yW-)p0sP}bS!%qX#HU%!49XcM25u@4?_6QCR*
zIcJz`0N%t-aq;e9F043(V;Oi8wJIksz#{C6dh-6;Dd_?&@i^^Q5jw3zD8=mL(O48<
z6K?W)o?t|^O%fka6uE)W;<k>RawHN3j+ER_EkV{l3Eb;>;<e}2UWe6hflX*%1}Ok3
zu-RiXzX{y=UoT-%d{V$A6?uM!j=(%-h(=+;a{(H~PRRS`;9*5DiaOtjMNwxUu_)@C
zOf(9#5B|yXkstna{jlk0?BjT9%tB4>9U$3$%rzQLHeQ%kimWg#6d+OpkOBkBpE<QG
znCJayRWMID$7`O)!k^$ugg7t4b{BnR5ldY~xeoWGbwDEgeR27s=<3arl~-WY&%{*<
z-rSQ40|e_HQW#K2{T|X6z#7^=bZa--KXkJ%%8)M5Zm0h5VoaC1K*n@k{dp9$yX)!)
zUvSV?S?{|^86aPH(yDgr&4k>67Bw$2!AfBx8%`-~*i5v5NQHY-vXv~j9_erJ#<h!g
zCu)UXH?=oT`67yj%D6_nZV+<D7lNotZEe@3PMC5A$(Hupt|`46OAlbMqjc(q0M*jF
z8^Fs-H*XP5YDOz@qqW0k&C=BgOPdA{y&M`X9;Tw?G<eu#)J40v`YOtLarK4tz>HbF
zblOEV>0<s#gFjlYrIv`Z^`2^%>5;~1Sv}Ie5}_gWQWZ?S&U)Bk4rjdv^LOW?haILc
zA8JM_bP7loGu1hrRH#(L6yD`U$tlcy2g3u}CUq*ldfU9z1B)=PuX;MSIn^WOYU-#L
z+R5Zme`~B%k{^wgO7f$zqTr3p0gICINdra{`$n()i!L-7uouv>u#+4hu@m{*)Q$Y5
z>GMRZjm==QGF@_PZL5fm4&1kyQ!C3*q`stu^%N^lb<*HY_QKd0?WJH`rpJ^q>sK(7
zC_8>eGuH$;)z%oZ6V>9;14}Z}fQFN6piYN1rUXP?df3z;?&FRYrZ*rvDiP8U)@4~o
z<VaGQ{_q1+T{sH7rJ72rkD1m)3<AaPOvOwZ!T_wPdiqEMBu9ZKa-$;1#G0^#;<RUI
zR#T~T24X3fvJLoEn)Dz58^I)-Kh)HXqiN~}nS>i(*58$1bEPF0CbmU^wHp7OHfIRn
zIBBRR7tUV{)sc@AuN_&lnUGTkZzkl(DxNtxes7lZ=E%<|>v~J83C-_~Mw6yW<4#+u
z;A{Ls7wTM2W2){SC!&U~8z9n`L!o6wOu8J7NW{rbx=MV=ZNYC3cH*?XoE_<$W3rC5
z3xAONLq)e&^i<PHPoqjxp=@}#4^u`$bBYIxT04b9=eScibZ9$nnO1eC5f9a9cx))7
z5Y8uz?vy)<>qt9#uID-vIt}Se#%QRvw<wrKrpKBxI3hbIM)>GP1puuz8i^ZYl{zz)
z-;`*jeDsTMJbi{?N&-o3u(d2oax2};rkoV!>Vy*#ePBfE%w1TiICNC<Q{xA`o#;aZ
z5aV~CXLO!IM?*1P>rG!ubBz41O!ha`L~E$kW<r;Z6rR{QO5<NSJSITeNZ|?Rt=?Z9
z0@3wez!(+<Q=~6e@0p&ySn2eFG>Oxr!|2u-$k93~DZ<4KQcD*%_DrKUmMStWI9&=c
z>Y-TH)H^`RMU*m|9@9l2UK<Q?^6dYLytPCX9?*(CD3~|ZuTSr$p%`L=mokDJFuqA4
zQ(5;0OFM%l8cKszJVhbIXe;4xJXV+nc4?!4(2Lv}-SkpU-e-3Of2<@Pgq7q3p@aIV
zA7G5msUOG~okA#Mj1G4Qs|=YCshQVfDjwPz!*ooHgB?M!GtD0U5FL9=+Nmg<$jOP%
zOIVE|H+sVx9NQHF)D*KtTW3?qmZQ}Xn*>foyq1D58npWgR%*r&9oJ7XM28mb2Kzk1
zqK>2t#6>|A@#L!Ts+G87Du&F&or=+FhLFe#<7#-~GR~{vX>G3C22b>g7HhBuSOK#$
znWw_ekjzt&X$>)3dKM^VD~B#&plmB#OWM3bwj}LH?5P;LW=vgBAl@P+=N^qMj|+b!
z9A~srE@=gfc)(*dGgMTvenQDmKq1qBBI+<l27ud&OgtLu$=T2aaKc=r5XVRkI+H@+
zJcyfOC6AURtBgG=)G|_no=3r$tL+HA#A*U$!z#CWCH&;zwKD*pSYe`#2FjsR`uv*+
z)JP0M*eVClcvA`X8OEzY-Rndw=|m&NbLi=P!bUL))({3L<+?8lqj#~7Px@8Iy^|0E
zoKr&jPCz!9C^>B&f<`!8;yS%DeFuM(oG_U6Z1#<kG1ji1Mnt*Ip&#ney78rC#1t~)
z)1sBLHX7pK!#|S5=;?t!31OP~d$=|yw$mbH95tW9i;^m~YQ5N9;o?9eMG;e*nl8Y!
z?4q``GF0+CdGYW!1~XmU5Q{RRed{kGt${BzV`x*>G6;Cm8@qwUahT^~S3@h~`yu{@
zKqtF+>f6n@?Tb1L6JhM?8b5Z))irCTM|2H;MhlsHz<e^52Qr!iFS_;YW@-eVD~poD
z%fZ6;xN;mCDa?%E@GCKbqi14-06TAw7B-<JqRFCg<gf)_5~iDZ5tn$++=!H=K&#5!
zh>M(uu6Ny%6=p^-e!voR!Y&4t8EX>Tb!*uXNO5V`0ouW?N1QX|*Wlv@msRB7yqjBY
zj%DpDyH9-;=e=@#j7CbP0Ub)qv0E^wKvJ)KBIftJr-4@H_)tN%>tQYveI=Y|<uX}d
z6JS+d;?`QVY-N&=)9=U}ol2@QfCyCLRW6g=G{PE+3M>lZc>WI5D{|r&WuToYXOlx4
z+ENKRobTqFF&iPt@e8!t87gKOOUSKMo7EsUdg1S-ifu?O=ehDy`i<R>_zus+qa{VI
zjXkQ0Y&3B`IzW*4Z79&k3>==FuS~#M!zC1V=Hz7RWYc(Xu0BoUVe({0D-$RA#(7hY
zXmYT4%|2c0g|k;k<90E5(lJ(8O&>i*3^nB|<I-qIRaT}=W=hha&67LQI){FUnVwk4
z`9uqgh-7PIkG_=FQwgRvk(O9lsD>gym8r^9pGC=^fp10$uQri7S>k|Xph}#LWT2R~
z#39lAGWj+xz_V@1xi)dcR|c;E#7KF+ru=BrjF2DA>|sMqCuA7s-~c{xHcTiE{YX^C
zd;l|{WadT557B^jEK-ixwMKx9P$D&wmqMq)oE^VB&<gffy0*b~94Xz--^kSKp@r@E
z4z+!o#K<}sth7j(<UPfSz<M|(4S;$$OB$FCt$=((PINn&VP!~(j*NJ;uS}39^MH<Y
z@+LS8$W2ta^N(Vgo~>8HCrJC4En4Ix(n1#r*wneho0<4;LJp{2gbv^WSRw~BLK`ef
z;ubWm!71DV_5#XJc(n~V(@oyfMF}(rsTK1SUIG^_5qjiSG~`e>c?1nc^`ps`XM<o3
z)FsA)S&yw(&RRO>AXvkM{mBNv8fbf@a@^#8dQ;-jTVL@H`0#;1wkGG;{+Vm+U!l9I
zzH(Kc#Kgc(6yCkGkC8Y*cB{t?OpKe0F#;7xPMX8u189obT$Gl7Q+<NjiYZ+gf=zA_
z8xZ-Xuv#Pywq|G~a*Ay|MjAHs=ZT!sa!h%+DJ0ntaoJ?>e^ZvhCH@6;2nA6iK`~HQ
z$SOd~hV7l{icN*x4e^^zR&*vXHZ1AP^KV&_staLd*ah$rQOn+th29ifZy5mE+N@#W
zs0;(OMM1u00;|8zL0#Jya!|G6g9E#_Zbai@H=^<ANizt>qZ?+#VSBXpY`qec>D+oH
zD$}|3N>C=AEAYd#t{OU)bwpdYty2g#t+fVEO_OPMy{KcvFr6-)1dr@RLa#(A?0xH$
z1LifeC^=x-sTL(KjqY2w9I|iSV#L1n$`RA&&-xcfL+TPUL20Z`N)C9c6N-xTsXhtO
zG<9VF%B^+1Lc(g%y6zeHo?4gEF@Sv6Rha~~k433oIRm{p;IV21&$Rf7M+YMz>y!^i
zW6N?w;1o_LSCcu@05;HMyrj+MXl`4tLfy}H0+aD4Vm4lzKW`mxwQq<<*Cm=J>^1dD
zmkzi{FgocQ1HoBM>5(=FN9Po=JkOe|gu@^j-H@=rK^tDHlRur1bX@m>q~p)#6sMMu
zm~@x)tN~EET6lueU0bi5wDgN{rXw$V_(QNctvZ6Nn{(Cu0VtnVK23hjweFwAFAkE{
zm$%9)0eUoOel~a^8;ov-LYZx}tw+Mw$ixP8>?V7f!E@P$-UzT@Hks2FCAZ?xQxK)3
zn=;I43vEMsAmYZGGSw}eqU(qBCO}ehQ|$tpS({3?8cMe;XF5a+D-ej5T_Z|%&;V;d
zL0lBqh(aue^g1AD1U9~DL~WpA&PVgs_!3%FFF<&5+caiE7+^RM^8iW$hqmHIhD`9Y
zE65`Lg~CBo4srvAN1NJikkK}^-8KqYk}3jT0>=l1905|`)Yd|2junzZh7@J6z1~r6
zYIk7|wW&jOqYRC2MEln05@QxhAaVrSlpSZIJQ{8+>3qb*qVVj3Gk_sMpOj)v90!E7
zD1z<GS}T9q#;lg8y~UXjg{z4(+3p(~!jjumt(yt)D-Nrv*OHaXw}~fZY|EWn@S5AC
zLZGgz#+MOl<cuN#x4%Z+`eUQiUi`J<PEjtj*8Iy@<Eg<%#jcZ-VB>vjP^8H6=BckO
z%Gle_siWDUEeh>ur%-;<e7XWb+xUe5k7&A=R(xsAC)+jSkkT}<RBM}HiuyxC8cQfV
zzD=2wnsRI^0aB52tl-?@LR^K<&=Qd%+ZnE}MJYB!EN>IW7D-KZ6nM-c1ex*_t*6A~
zf%SBggGVk3ir+565gFYjOQe)|#?q~5>k`kFB?GrDH?q#4NzB)O>*v11BA7SA!L`BH
ze_S!+wd)o)x{%xG?d#{h@783FMXG(bM!P6=0<DkqbKiJ(jM29f=gtw0?Z|mzL}R<e
z&XHvw>k_jV(cCUE%Mo4MEfy@gwmU3YbpLXP_4D5Du;hmTVB<E7EP}ehl0lEIur<&w
ztU=zoD;J^euoYw3t#%x%pPt*Lzy7t#cQ*cTaKfxqn`k|y#RMCyb|9*2TkSy>L+#XA
z;;Xd>p~ZBo%daY-o}-kbZgurlE!2zJQSiWqo=whDsAKDuQy$eT<l&=ESx$KpH+QLo
zouRW*8N0FpsaAG`vqJCec75umN7NsYnu!_Sn{pcKt_aakf=3p?tzI+hy*^vFoaCct
z396bh3X{I#-s+K&y8O}G{>lguZ}rIdr5GC?NmU7$52@ao)Y?#1RZh5S1NN;?jJMSj
z6V<s@y7=J3uj(7~ahM52FTEbSLiG5;tTM`YmL6N}WjtQ9K=Y#qZWeGJe5mG#=hi1j
zyuB<shJ0<^lE+eihDWMa<NG{>rqyzzzFcqho<tFc_EfLrZ@nq~N0z_ls^!U+CA4WP
zh|%_Q>l1_R=hiEj*=w!S;(?Ohw5$X_6#&LcJBs!q)>IcP$D#y(5zKYGWTEMb-Lec<
z%`)ZcmP72@w}PK2cOE}9Ga(RNP{O;@y43c1>V}Znu6U|2S*^50S+inLbL)_Unp=ku
z!hWHZJiFB6%9Eydd9nuTa(A|3JynRFp#)uVRbj>p#zU}Bep@B)4e8X2QeBcYB?Y*i
z{FJ+Ipuo1vc`;B@dowKH?%C`LxL8~$C=6^^r0NzU^0svg-Ux1eSzdEQ3I_>e?BWe!
z+YQmyT|rTXhg|m(gOvQ0zYDDv2I%g)**ezA^?03Uqy@vzfb-hr{hqm5x{vArPUu*e
zID36=y^;|+7}6?#WUjNiB`0tdz_{Pb;(%8rQ>v2^qUv{sGKL=^v$9Y674pl^)+Lvq
z92$lXD<Cyo8tdC*b7{mbQGAgBDYg$eHRAYIBoPXh9YLZ`1IP6!p9aom0kIj1XY^4%
zjac=gkMe0`c-+dR&sOkzlurZ4?kJ~58Z~;FHc@Cc6Z%g&z(VMUWFrB7vk<LZV(p`(
z=tN8%!317g`C6(8z!D}TK~i!o(g^2>)+{Gqtn;|g%5muQ2y}~H#ds0Gvnce~06Do2
z-Xe2Gqg;(STU{W)GVDVN!%QtEz#a||@-yZ6O3kL1fdt_}eU_Z0uCpjtgbfl~aiLR?
zBhce#NeT|LS(1XoY{J!>uo>hCj;yIu1c^C)Hq9_J;mIQe9%TS@93aKQRMgab1OxI)
zul17@PVT{1s7g-wn))mu!KpKMr+J*hQ%`sVF7?2V1XN~c;?GOI`L0qp^xv~+=Aszz
zRbC1R=u<EL3>Y{Prv*QOa_=hL!^nd^<-9<6La%tN3+e5>0<tpLsZU)qh>hsP{ABn<
zK-1u7I-zSAgAuH~7-bugPwUH<WCC#-{i<k~czO4W(IH_@=~qR=U<+Ro0+dD|j?YVQ
zuKm)ZJ&P_JLE@*Ob}%X>nW88uL_YP3l0t=vevO)9C=r)TXUP0p6#VRkU%Aj40gm($
za&rW!Vs7#m^fW;5P8alU1ow<a_@*QT&mI{Nk?hz7`O8SCMd7C)=(iq)7hX|O0Vcv$
z@IbnGA>eNbVwIFw(_3#sgh=(9K@SIGr25SqB}1{Bels(GAyQqHi5Vi*Z(ah2v1-^Y
zB>}~R`mGI)x<&o2sJVuDag$e_#EP2h3t9|+eeH!74X9rPCVMIFswa{)1LBeoa!6y0
z{oZ5bk_{Cj=U_uUCID)^NDS8-#9zziHH6TXgdAN3$iamfSa0Cc!07avym7&loetCM
z6*I-@^$MDTt*{G(JOaJe6ds9DhI$2-T{N%w_ca)784~muTCwPlbj}-Qn@2G;H@3uM
z8vBhqT0rcEsV)kqjFbP-L2<)6@yI=L1OJ+EfJw^f$olZG5};friOSc@0vJ<WZA|j9
zz&31*n9UgvMbPG)sZKnQ^9rwe5FOOZ5{Sq#0xu>d`649(6YFIOe0YF9_eP5C@kkU9
zZMEPo!A(S4Eed-f*D;VZMOxoq6n_5!MHzR9hh7xMY6H7`k#7Cbj6cd)Z4{O~k+;2q
zsiJkUd1d>_7{rz+oqiJchy@*7#yG}OxuTC62JJG&MGe$7Sy!117MyU|=NL=1D4d~V
z&eYG3h+>Z!<hKWA_b^yK(OVw|%E#c9B^JOQZi08Ls;WwPfkkmqIMB4U29hk|=2@Hd
z$)jAIPURn<&-Uq@xLc(l<kqWiM|wes#`f{NnD&pSuHlM>YG<~{v#kBKC`^Tj1!IjB
zm7g``ydn@QAb4Z%MljY$ijrXRP3D3{S(GQnrra`vcom98jKT><aiG$R7obK)XC<ug
zLrQ*Ico6uc7r29=@{ku$0}w>Ka2OJE!V4|IJV22-$J|J6qvq)NkYEe|zTkyXfFJNE
z%G1)i=>;ROV7t5k0)RK*f+K6d81u^XM_`sKtsmyjV^PSa3vzJjm#_Ttr60b*H)Y@4
z_>u}zEK+`|(r-}ewUXr<r9ml~jneQaceYU)9(Btb#GCSGT8fibDme<y11kIgDSlh!
zpjdv&D@z-&m0nre4TWv<69-5m2+T3dBhV`k8`;BNdDuu7c9yg{6d+X<Y*&C3@zh@#
zAQe9=2?mI~3ple8Y2KSsZ5j&rW;!)&nckFfhIB)(>}ljAdM5fEAcYV#WkiN<>TOSm
zOa?1a8Yz;C0w)#oD7{riB&$R#4K1@Vy;7rL<Map@i;T{kp)fZ(_P!#>GAVSm2U@uv
zx;PL(<xK%ajG$WJ{n#8CK;?~QpT>f}iacYTItN#emoi~p!Dv+)TgjO)cY0+$0|L!6
z^ErPA`@bm*spA5Yc{zisTmfti7}73l^TDVpS4>+~+!h8z)^_$Srx{nqmeUN#6ju>E
zhEe&J*_;FOEwMTGwpU^^QnI}Z(*c-vzNI$fp6JFTdmIdkjcdphT@=b_riLyGGu`u^
zS`;RR=ljMxTe0B;AKkni(PXZ9<DdUf4*TMzEa5ChS+&X=00zBRiX2Rzt_VC<zFZVc
zFzi*U&G|W43CCx~Uxh$a?z2N66t>r3{&bnx8!|ebaePMxTs<n*{X)EzS3)#g*j^dY
z@D+P6^n?ovpQ8U79I@Va_=H@y9X%lzd&5tNRjaEI-bP2nV1t{`D``3-uUsL73-2LU
zno&zf8x#<s^}vVb0%LE30-}RsP(Y}49&MPqePUQRvEbWi>P3u^hE9Q~FnSax;eCNX
zN|jV+HCyk>K^&e1PV(RSbId;@PLCjA1S3nNp!a|bvX#FsD4a2)g^$B_6-8Ijf2s%n
zB*j&CH!Pee<?<2&isyz0-U)gouW$5FW-WXU&cMnB2g4$8IUbHp8UcdFy|T*@(9YU4
zFJZ!XFO-{;94nX`=#b7>hp6Gax~bMdgH2vl?AvTvHiwu&O+E0R_4mTy$rc9I_4gbY
zfY^eBf%z)vlmE(<uY~sL_yAAFIkFy5@+%F{N05lTGt`5~J2P4ZV#IF<#3)49O)H6d
zIxg=Jp^;WOBQozoHyx&^jp&J=dc0J5+$+-_=1UezdI`$OEB78%Az5GPNYXk0ST=)|
z(p|NIvzEFm?zI7X+be<pLfMNT<?;l6x4Seh0DODp_+M%1ih5CK$9bDa`~gxN)2?G0
z7Slz+aJzcpytukL5e6ay%RGSs5L6bGtx~XH9`%9_Km}TN9_yL2cLW9eMj<WM%z6c2
z8G8-1Q(lBPa9!B~BFn|4rz&`H<%Oejapk2Q!nWx?(28I4f-JbW?0O_!Ty~+wU0C%E
zEH0z`f|Q>|RckMx1Jurr`eV^H$ckQCcP@Lu^W0o_TKyZ!ox5U}Ta;e+!b?CFr_<ed
zB+_0mCKT73i>?dl=AsK?;l`TlhRQt7BS^WZH`iSt3^&(Zx7f`+FWU*K^&KuxX9Nu9
z=)?zZbG;!^4Z>O2harL}9Cv`^7!bh%Z*W{`_pnBKR3cxk>>*YAM&%fH7HNnu!t6qU
zc({dmZNdWQE@&cH7Y{EaiO0ZX-L0@CI=r{5{a`r6(d03GX;(kEqFtBp!^4?(F!J`j
zKq{UAh9>1mQpa#0IB73reZN-*4q|*@-!s85{`Wf%`E25Sr`qrhnU^dgn3QCKRDkDB
zNmDV722-LdNWP&CjSE!cdBB&AkX%t5Vn5Gp#^gE@Ek7v}!_D<rL4qfSTa-`+UFaPh
z_Q8#SC!F6v*KOpHuykP^^g^~rs-?Rsmz*6!RTLLLbEP}1oS+;ak)e4)bQ%@K;zi+z
zioy{QA|JJrit8PK8e(!sw&e$b>msgiix5GDzjFN{`#_-Kt(b0;d$35C*u`!o5~P$&
z;Op(A60(!H=s>_WY=ez}0TL0r)|0$ywV+^VtMx3(*d)I<mz)RT=*`7W;%d7lMGBA9
z8!bqAv?jM^4r=Nc$lco8taBjw*seMUMA?pk10<dUVA`#7peQ^z0i?~77KEcWowO9p
zRS{@Aw>l~aZIpiM9K{|WNLHPR9q)CXnmym<dy|JMHYg&>aPTH7degZI>FG_!Dk)w3
z1TuXWJ7F5>s6AD8L&w{-?vI|>T{~fjoj{510OrbTspC0W*H)+PL|0pnj5JqpQ13d6
z>A&fn=P`>u^h*~%mZV?0__+i(FMeD&z4JJpT7g?PfBx>Hdmk+KQ=dk7P}CT}$5EKz
ztZ(ON-1O}njGI0Ud2qx6>)YP`=G#p=2Tl*~n@-Z5>#9(R?p+!PHodzv5G<^_G!U$#
zV_{Q`iUJcux+50Ohjd3QoDb@bSUKk{JGgaxN_8Y>rc_6==8_(WRf!Ei<+5`>yH}YC
zn8~E0c3e@V$aaKem#*70!|N!07)3t5N@r#vkW{KsC!}<477~G8et<;vUj<31{bSC<
ze$oG_?C0M%p6x0?F`7DHe#_k9Dm6iChaM_@bUhg0X79uGV!-4E7oL`^KCtk7G_eW{
z%lRHJMR&Op8WG*)3O`)YTe<M4`7pTbT{F^6s1gszt9FJpvf53(Cs`4v-kcrLneRpH
zXy%)h>jT@U3s8SNdd70}5BfyvWD?jZ#xc3&i9pil|Igan^jx>&+Cu&LD|YkT#wil#
z!%i0okf4EpLkrR2ii?EmG`I)>|DF|lj4@XgXFt2@t*b3nJ@LCT^D#3s9B0_(7q2vV
zyQxmSfrsga=2WgKgf*CxrCM4fdoZg}O7K`CNYLU+3fG*xQUQr8tq&+JSQ6OXp(@-L
z_GBF_m`%v;>MixJ>dC4KO`X-r7k1~dm#jVblq-hEoa8x?v2`U_2z#p%EIy;ciO3){
z5Q1dRrmi_FW$870v2TIC$vQRmYxrX4j;gVD2S((h-oa~iibi~CS~9ZL)Pa2Vn%%C1
z#yosj-d_tKJ}n0X4C%MtUmGAER2TFx5|Yc6W<*Suo9fhT`Ct`xhNkgAseZ3qP+k%9
zW#~-qR~c6MNE*ro^oX5aw%1H02lFj=!HmBy>n(_1Uk2XcTXitkzEK7HffM)N%$`mY
zx$-F`FYL8R52t-x$&ws5Z9}#P^1;&jz4#+m!#Crvg&dP`R0(d6!)YVG{~o+Qp^0V$
z&Ewkm1J@_YJ;Vt9Qx5+Fv9;#V?jE#`D{oNHIzCY<<Mo>WC}<nk9v$Po=qO$os$jf9
z`}k0^gKJ;=F9=p22}-rFl!%0elcCMEoG9~l2j|1!^@(;<q;9y9n(E-%(9Q{_)EshH
z%nX^U?yK;ogR4V3W7O*Cnp>_8@+qD{Ys;H?l*X3IJsP+>X&NJ}XhUiHiuG0ZcAVdX
z`B$30)3Stxd~jx0Jc}#YxI+wPg>AY-tgop2H|Lvw^k55l(~r^=L(i9I9Ds^xcRGd}
zP3)G)GcuKY6lAFRCLcWrRq@`Gj`H)Ibj%rW^PHxQ=S*GqvL%>r@*GxUT)NrK5-x3(
zQSK~V^`e=jn_kXbxz-{BJS24iFa7&qvB*0q^YZ3{wci}xw#lXGig2r)B`g&=K@H@$
zd2iN}EOzRy9Rmc)ys1MEQ0C1YO7a(P{wKL#I7dGvT3-Z$TduBA<(u#py^@-l*|3#}
zsPIgL>wM`96Xb?!*F<)x&StXbZw^JV*wV0UN~k@=#i*&AG}PFeJ)3Kx{(XrO@>C}4
znxn4KEwMy6I_wG7)U~2}5%ixax)(30rs!S=<0ILNXr7EUFkSdq*d1n9TKHBcM+Gjr
zf?{3K5SAP^&~rEkyoFbKjLb6*Dp0-o*_$%VSMKtn6DdbFsA5+FHJ)6tsen(H>IKdc
z`$rzun+v`wV2B+_rKTcHO_8vco?+rf<=lyZwe-*d){-1W=S#|}1vitFMOU*a1{SVQ
z_`}&N<2&+_PUWqe$WAzwhKN0!O6+vGTI}7QHR#zz4w#6RHJNpbe65MJVVGV{3?%ic
z2ti5LA~lbLgBseq28fkH#K{#>Z|JaG=bm289Ptr3;3GaFSH%&x5K9Yde)gtSftcIO
zc3+a5xkiO|(n6@<ZJ*Dp*6Bg1HqypYQ9*$UWNdNq|G7SIkUTMM*aATNd>|q>6w`*i
zgx}tuYrmQCMJXi#>q=mnyrP_KaZ@J@kF5+Qvp8Z6w>a2MZyDR6VV%xK<!~Z@#FWcA
zIZ?B5zn(}Ak*wQANuAK;4nIi~Q^Y{RQSOBpCDv5a-di~aiyF*V;-UugwZOR1c=0-E
zqim*`;B6lwAx>mmn62~em9E<AkT}5rt1)NFbRx>1OIs`A^D9VahND*xRgwr<k_O3;
zq};AV#h$P#7G|da?y{tOL*Kr7!JkvlFSa-e>-l1r<8%St1cK!AAI;q$NnSHG>MKsY
z2ybeTB`>rBO(XRyNs{w_$OGU(?iq(CW|As~!lIHvk@_Ac1%4rinjgs#&j=n?C!$&n
z#QiAl!z~$$>Bw+Upc6w4@gXxIb=w*>xCkStiqYyY6g-x8ilLw-4@m^fPhUSOe-N5y
zX<DI*ekG%PIWU${KBBQvns5lIbqOodU}W4fHD%A1dJk{Jim&@XL{AlV9}e6>8`(to
z{`6)+@3GoqFe1b(@757Ry<c*s!E7)3(x6nm(~6pM^)L+qKGUHU1rzh@*#m3w>-=*q
z<azjG$6WqGTqy8)rb`j87e+KSjHn!NHoD3cBW}oh2^T`c1q>Ax!;dB|<Vl5w5D#{E
z{E32c=z3QeoIm_sVW(WH-UWt$5bm^IOa^>#YV#BE$m9n$8N0!;%fr4pd`a;`2)5y*
z8%#LaUJ1s8JkeLemJCjI+@PPyFbqy|`efJzm;SNno2LZ;>+6*a_6XafQ+=2V&UsQE
z5P9%QYMm{*=h3ZvE|7zVg0#;v(54YekE!X<egcQwu@7euZc#g=5moeq9bb>7tK<9J
za&?Ta=jKA%ya=0&QLuSOG{J)#igz^`kYH<jK<)sV3-dwvUKD$OA}r?E?+dK&WiJ$}
zcT+FH>4+%=X4HVK?|;#=R{ABw1Z<pu7$jg1=^ZP+{ATA0^xm`}Uf)`5d363)NV6*`
zcf~D4fwS@0LKM3C%M*B399B3BS2@?`Zshz=1dV;2j<4iSl>CyfAX{2M6Z-MXx%rtD
z)An_Mp7i5iGyzN`lamkitX{ot*0b1tPx)e3U+A^3n02$l_LejEgoiV{y&<VqHg7bq
z$d~REN>Jk=hR8o(7()O2rB54?i^q}{w*h5q{)ta1*L0nz@z%%Ec2H52pA=y^Bi8a*
z#0!LD9!vUKF0Qe(Vi3`JEYog}70F4Ox+KaH+|#vE5L<en2NSO8O7k~i%^!>2N3(pg
z$I><d^ZsB~mAUbKGZey;q6)E~(=pxe6;olB`@KjblkWH83rxA+>y~{Ya5tknOvLtn
z<3CK~*?5CQOt2^sNaBHLeZ`uX^vTzq<fKo&E)yqx@)_3RvosuyPt^kU>Vj^9jLGmB
zDOg|eHRcA7=?%g$Yoi?EI!;9N8}nTmj5lI>*$jTAyQR4qZ^Tfl&>sD(3S*7DH7c}6
z-q=lg^6O$|ZpIlAj%;{%=9S8%Z@>7ylNmvWn8R0e<G}ErD-2A0Rk))c@%8hH0uwS9
zc&nH%RfBH-O2IX8*D^?7p7i|J#maQhD26UguBZag#9ON(zxY=z#-L%P4lSIw9+Oc6
z##XJ4?(DBx6^3TNl`0C&64p9&@3FpWdBxaKC5Gr>OI8tj@OuUspf|w;NA?Z#b0xVz
z$M~vMb2Z*d)i;wG&CmqODR(7ap@~$f`X<Ho#ww7BeO8i|hh!B<&JmlXBsFicX)v4t
zQ}|s$g=13B7(MEI)v4%FGFUi+N5xl572HaEwCOl<np9ONe8XgsC?0SIp+Yg|Qf^7l
zbOw;xUv;X3<WWrIkr{HUnvN5QEj>8L_lDM*cd~7&0(3Xyb<o7!S_bgKjMs_9-ZKoe
z+&2=~l~i=D@l`8dzO1&6ecB2bABeIoGR`NGlng~jpN#hK+G>4gi8VG5Qt{U(f;<cb
zX}^*jLPMeA*y%jt8zJ3}@Ug;0bUv@5xy4t73Rx#Zlp_e$Yie~c4n}{!d1#ScpZr$H
zIxZ++g97eP#HDzK(oavM=^1@#aa2ghzP@VZD^gzWl$?sphg-W@K`xMcJWHzr^Kq>p
zc;jmx1uuN`_su(^6TWXAXF^#&87QO60^*3%*xwf)*be*q<`GS!OAW!*>gcSJV;0CD
zlg{YveT@v;c=TErw(;n#Fh(O^C1W%O{njTE7>yQRl`3$f_IyBK(|HtkyhCX+o)l$w
zq;?=Z(B*&fRh}&I6+lOSO^D1fbVYmz2pIC(5cOF0t-@l;c;QvjG_jR;dj~wXcY9|e
z+TMZLxUzXllwmVX%Mj=GW*RVTR;|ASR;*DzHxC=5^{-i|fTiyoRQa8NdS$w-K{S=i
zX0DsR3G;&~vCKp^rz>gdZb_t7)RlV%WnIQGR^(TICsUH4{@p3Dv%lu^{&gk1h58cJ
zghs2Fv(>w32>z;X`b&bz3>f4yo^8!0(pbGQZ@(p&99U}<I+udS6kOwqZbacj=92_6
zLm=UnDYD0x<Y6)AMVjN61TzKBf*lzlz9isHPS~65G|f~A;(X1`DxU;(Zhgf%o&mM(
z4Tubp93o1RizfVQ&?VU{-I)wgJ6_RzyOv8R#@CB12?6SV`0c-Y`fvBY|M<WC*1>&S
zFl`M`q~LD<AOF|i{=;*J-98Wd>;L~$|Ih#B`IJBZ{c}|Oq4nFkAx`Y`y#Cw2{Oj|d
z{fB>U|J*)p{mXxN{-=NXmw(r%|I>f`zy8;M_doy3fBpOy|MJ`gv?A>D%-zp!_u-!-
z%ijLmfB#?o_J4fp-G|rz{`-G@7*}>B)8St;2GpIZg%CJ*Xn$jGubbTbski_1-~KQE
z=fC@x|Gjz{c+_xPpY}grLi3m(tok>*iS)+oC3C(1LN7=8vi{J^|M9>1FV)L=r*hsY
z9LM_p{Ne30tNq{XBtyZnmjm8q-@W|*R{}>um7ul%TnXy)$^b?GDs_4x?$6&bA9bVh
z;~M)f|J_>u^nd;N&%fQ7(K0(+W_{l`_xWSZ-aoqBzcn?y`{F3?ebc+_e(vzU`Mgqi
z7g9}p9#~%|1-~<ItOnN7?MHP(G^W32y?;(Pv+cVqF9+@4UQGY|!9cC1zkhsJYy28r
z-@m^mP-Vj1N0lh}gK8Cd>#Y?~_I|9iOJ99!Z7Q%oR>Pj7>8IfDoBj_Z`?#dUYnng)
zJJbK`lTY^8J37(HejFV%^tYN+_MfT^go#%*3jUxP*nV%d=wD0ucdPA*?-21N=ij~C
zYxQT8#NS!{?H^hF1J_gU*yIlL<Jc;W#aoMUEq<(otk`d@KK_QKOodR@UJdcbYS8@j
z0x0<VpzI^>-Xl^uY5(>Y@LT)!7ho_=zoXmZZ&=C(x7W9t{9u2q1`^_1O{~Npt0f2L
ztprNWPgOcdftr2_{@yR(gTFV1WkzWGz3Kl)z5qm*)ZjWVRDT>@B}n|Lwfo<&ly9>7
zzgWr?{6RIu$9bzMV9t-#z-W43fhbPD^ab?G2>Z7;q2K-i3^?;ISMr&E!$O8(MwQ(E
zhGm>NkW^*2KL+~oS2#cZhP}}?))Tg!{Vu1!d(~e;(C;kze@N*$f4O?k->`PS^gs&w
zPa733QQvA3kZ<vK%*egmo9pJ(Sob3B_Y{#|nvyhSz1>9d$FZHV<-V09__12=Wzl)-
zy^^0RB52iDMM-|H2v@+bijw@oYv|YiaesD$^YeT7g}1;!>t8*U<mVy6M)g%ulAkMH
z#@lx_lz*&bNaXTXdnG?tgkQl|MM-|)O=POm^M_x=uOXwsHTbKqlKec#{g+3?fBo&1
z{9Li<QeX8b__-P)!G6_~<j0C-zkjQ-{0na)ZRs)AnLoXWUs4e>W657Ewpa4=@Zf9v
zRZ)_kD}rC}RZ)_kD}pokRZ)_kE1vkvH!s1jyo*coEM?`#ckye`iIAjUKq$$NL%e6&
z`4^k;EBU!17<}K*OUcg_ku2e>q9i|8jPYG5OTX|Q@|xq1zlmQ`8sUfY)k{f!9NMbH
z*>61wey)bQ`mcJD{9F-vN4_db@^eKboA|0I$*-tRH&ERE!*Al(bf<+N^k03I<PVni
zU+STMsbl{6x4(Yy?{0MYDtdpnkF=>t@b{@VpP4FiSI=x(zhiKjzp|CHqocS^cPr1E
z4N3lJgqBx`U-b-kia%GYfHz;&7$Ez{YOU_q-fE2(Za-I}g%fX~eOoyH{+G}$0sVJ0
zoAD34ga+o+*YNiF8Bb9WxxBtAuJv_6_4^eOa^S0?f)M;%5ixDQDk{qD&lM3Q`+XM*
zyZwtV<GRTG&dacW<YlyuL$*fP`cKDfR6G$JVAZ4G532e6%jPKfgK8kjzSVaB$xzK|
z2qna~a1>hTmtMlT?9t!51o`!Ma1ays9h{Qg|2Q~gSbVD~<>HUk;PClYQwq_as>LZb
zuc}e-2i0T-t~U_BVg>$;tCd<A|B0=@>?N4@@8Cqm|8a0@d{xQRVn6=;M$!1HFwPIx
zpQvK{t3tY1|M+tliZRz;cH+N(rY|q+KcTe|J@mtiF${`=p9kh}eR`|O7wX4qh!*lz
z^ZvKAw&Jf^Tk*HF268m#pXFbC1Aarf{mvWs2X=fPyiVib#*f!&tk#`_L$&T-qx;=z
zaQ1ww$@}xCY8yc|RgHo_s0Iol-vG<M_y+dn_599m^A9LMdyl^w-2U+*j@97y^;TQ$
zYjnR`?XOkd{Wod68wnrYYRUldV>RSf(Hm&ztFgcT4O|cV-}wgqp>x2OWrmU;4@_Wq
zeN}uVzi=wN^xQh2_x_*QYSj^%<EyJ*qCc?Z{>9Xw_$!9$>wL3uYxScg=vOwfoA{+J
z*uJd568)it^sg4cm*`gv!Jh-j`I|=iOUtzt^YnYYzM`KEd+_V}uKJ38#khC<kow;;
z()}xTrPgpq`WlvA(I40{_Fvc>{`I$4@+-!(8=~xQ8fW~H{j7M#-@ScBe_#rWzg`Sq
zqF=hzn}1s4k9VP8QTJ#-`tIy2`UC6vUn9w1ZQ6hS?f>`mzh&Gx=6}AUzxVJp*0}!Y
z^|JqZ*#GYx_1880{?iGIK0dW?Y&3z=Km9+No}Xx`_qO~0{#{%Nu&)zV?qUdsod^uv
zkS98lU53}`A?mkq7DrI|aN1MKSw01I>_Q&QaQXwmxjvlUiqVsP9!}R0+$01X+mRA8
zoL*~@eo!Gl_b`k}PHf1K8BR|V<lGFWQ$Y-Li%}FJdEVjFRf?PZqy*h6r=@_?dz4G+
zEuvfHp%f0&SrSPDiC3R2@0=_8SVvhw!|AsWD+_3DVQR}y3DNFv5l*-`kpy$R#=^wX
z!=d6igp+d;8v~#Pq++@~DXG&ZQhA1w&mzi1I3s+7*W~js4rX|i_t;aCntT{6E7xZ@
zonH{|BAgzVNd6hlm~|2C7m4%{m|J>HMC9bsTP6Z?3l}+r;=g6Yd5^%zvVnt9k;PMC
zJVJSUL7ESx_O0M?Pf2oSPQ&!mfez8)!s&8x8amP5DhE~2E5s@JNUCr<u}RN3)p%?=
zd?L($Z2IL?s?8@QXtPEXo31*i3bk1yn#xB|g<Mga(JzmcQ^}R&UVw}NvFXxt>YTrM
zIz>>IkDv<GU7XXN-(ax`Mkn}e{ITf(Qn@@+fX+?yhvp%;XT;w0Ks>Mc1P`qK(D(Dy
z0XQ}TSRxZaY_jDJlF7!Vrx>^#u^E#n6Pw1SlL>fiS5R%%*BXqqnv#62yS`N9F$jf8
zI2!{aY4z;tHbToCj4w7n%;V^GaY%1sgDjwfjvmo{0s((w%l+^;x<m#O;^YNlDpVST
z*bMZGpm`xO;(@bfY&y5V-zPRdTVz~~%{adB5sFR6>2t6=tOD<ygQ=!B%sDwQn#Mt^
zj!jZ<Z-6TWWVjM^48E;BM^3k=4u`1Nba}gyf#2ZwSXPZY))m#dYI<h9p{9<M9VeC&
z1tSqdFs8$kqC2ZgS;iZXY0(F#BRo{B!<K5(y8<>fKBHTqb}A0nm2ijvv!xv9tyaR7
z@FBCX@FPO;cFfg{iEfZb*WpcYCFodHK&*z|07n@lq9Zm}EV|@%c-n=+Ms&mrjHRT%
znf3Nb30qz0IKR)1n1UY(O1WZ|a#d$wv8Zd92ZCHQO9`$Kb1)Qoq9cY`D9}Vla@bh&
zeNf@lqKkKjo8p!5IY6p4)!jgMYd3pJRDGWK!F{OGc{d={f&ipITfbjfN2c8?V7rJ3
zb46?zfVGsIxD{e8C4WXB!!iqZ<e>dD%DuBAOYaq-<%3tQw8*_>35{0P-jtxxj)2f1
z_5X@imXYfjuBNf*o8A#e?@FrOUO2ZDSLsTs?^M*Ur260W;EwJ$Js4QGk~?&#zE_E(
z0opBm_=qGJGGkpyEm|e}u9%BYir8?0-c+V}L}3g@>F7wldj<ILEB)>jR0eG@-(!Xz
zGOL7%1sE#%N=L5TK%SRd&TmJ_Iyw^NhB9#U4zyEDj}AYH5X=8c>J=i)N6%Q2p+pq7
zoG(yeKRPn;hH^@LPH&&mW;BIQv8EAO5;_v@hO!{^;$8%^IrW~1hU@{oBjjEvdq9VM
zB^VK;R}{yXQ$qt}&8eZ4Q*un@Z|w*V8guHwfmxe;Fi=Y=#yS%8#+#I^BLZY72!GG;
zrJ;EHx10dMNckN>QLg~cwTmuyl=+3)ZPWN;pq8@8T}i!vL#bw1N#m_^&Zx6?1cMBv
zyz5Bc8wxw$5gsxWm*h%r#)VL_y^iPuG5PN`t4&P<!<66eN@{sG&Ag2)Vk<!ugvdxH
z9r=dug%lrIr!R#z>Bi%i@*Q@=`Dz?>w2mz?4oY>+rA+V!Ov`MI)vJ{yJ`tEULj44;
zjnMP}*OW!_N@|N3EN0hvJ8=cM!Wg^#T0?V%DX<CcqcNN@qdH<9UlChQq#Lew0d#}<
z@s;H3Wk~m@8;)y=hH@n}qOCDHMx?K^Qt*T#xOa2T{?e!bePeM{Kt6>~xsn<JK5I+p
z8;iz*E2t4r5$;Ij6Jx1qoYTfs%fP<MZ1a>PU!=Z#c(q)~Lb(>k)DQuFW2)&>F&<)2
zukPame}hVO2VXaoW%f#{Z$mY3etWat_KLX@%8c7_-4)87+Xui6`E@%I_1-dKoAiNV
z%`7tY#^7yYM@pekr1cJt;gzr%V%g|ur;uz&nXYc9r1l}C>J8;2?iHyfMtcXy>tw*{
z0JaUrwdx3*AIh}cb-j!a{7KR6jAF@jyz!8WQpc(Y22Sq-XEl>{JTj*D72umkw%ibH
zrXx9YD1CGvJ4<Y(sFIOU(;rB3auqhc<LmiIP^!_mS}lB2^6NejBR3c%y(5Cs72tzL
zI*2f-!xbGVOxiGlo<;?<c_89VeU-9d>Bj^3W=mZGz?l@}N|W)V2%7>TNClIYr=%Xt
z-r{hE(bTIAQ>2tD%Ee@i|JRWmBupxG<qrvk(&@mE$Sm!>Fy?klI6HfmYR>^`g@Wqz
zOt2EVD(r~B6&1bsfvCDVP^w-sdSFM4)nF8!UZ@-<wYZYZJSk$kKt+>ojN~;}f*oc8
z6&1Rte~>?{OCv`ToiJ*~2ul{$)ii+9x>^Q!T4%V8UI|u1f!RCK357{lE_LS$(9*=h
zlD15(>5A$n^?P<5SgF|V9ci4d1kVIiR?wgaqT-1hKC_4-j91nX6)yTw-+`8$7UZWR
zm|Q6OdxvHjT^e-io}utV9cjIyLw}wKH57^l-;wa_O4znzkW#XdV>1-9s83j#uZYzE
zg<T4AYVFatdI#j|Tm1v_^^GF}9Ja53{R8lIYR#1#D-<-oBSrY-&L9j=N6gpgOKk)C
z`cm5mlMbN9S?89q5!Hd{Ns;k4HRH4{_dHfbr*-+3Ym8FS7fyctJ!CIHUmvQ5bDf-n
zdp1M+GH;qfvE@5MG)AYcjWcT~z*5JV_THaVsXAhB8<=f-y9Vs*rlt$~6q6}g!Z~r&
z+YxdyaMZjn09n31BK#ot00pS;Yi0>sBrFNhrJ<L#;VBX35vMrCpTClN8`7|0{)pbb
zYL#)gGYn~m8Ra9%(gy~cRPY5DY|_DDl!*!h^+1#pt#I{Mk`t}iP`!e}Mw6P3z_8J(
zg5&#X!t7OFQZTH2M`+SeEU7D5S!S~^aJJfKVE76}mg*G}H5!$0Fsh<S310=BjSBbE
z5o$FQda5J*YlyPg5ui2NR!e}+w%Jsk`lCq)he7a4*nPlf)5i|OVl>*N`$piRP_+DB
z_Q`0{$`KMa8ntp{L5n7>d;?({vY&LMMY{sDy{iJ-?HHkS@|_^tCfnfAQ?atr9XiJY
z1-xRtMw4odP_NOXUL(|NG#RZsqP>QK@uyE<_I2R7BmZW<fuD-Y-z(AllOnbZ1XZa1
z4gy9rspz`^v`IsUY5fVr?(c|Ke9LUS5LHpTI)WTWliI$4nXT&xv;mrp8h2eQgyME}
zTs&L}I|D>)`23#~)jN{TjYzClf(IucD%w{^99BQFU~eSzx*|62S;7Xe>!f%kc&39?
zDPwhA?SNGIK$0HXN1r!BTKkbYy$k#tUC+n+k#%|_dD9gQ{pSATm7pu98kRP_586!w
zH9~JYlSY@QCjnFzYDDaI<wCfUm1Q)GAm5HFoICXhQ~D9*59*-gM+$hw4!;7nQd_$#
zNLjCdq)&>lA$aMLexy9#tIjIdoFOczD`?r31nSU`iaS+5j8E8c?dqAYq1T<PA7L$m
zemcXP^}5)7Qo@$WoR!w?Ro{>FZl76Vqt(2h!5jH2s<lKd+ey%sn(eb*sg&#r&6yI-
z{=$3JXNO>%SAs9TuE;+UnV=D9^GaYSLGrsRVPiW>__`4v(~op&gv7iOwzCVV{YcIB
zjX_b*u8{ez>=PaFEgfN{I)YjHQLe=flEM|SZO1~DI-X%EJ*12yqW_g}gk?d!66_;j
zLpU;6bcBk$WsW+)ewL!`Wjgbaq75R4hg5BFJv^XlCsV{jIy9&x9?BklMb$Z3suAhW
zmHVP2d7mSmRj=TB{-(m{AhTQ%CJJm8S8|LFK8pu~$aD}|t|S2b$meiHY`ot4l`ND8
zDq(8?EyY7>b@Ec4l;A@LGv!L&TGc`7)iFK=Y0NS3N?wf_)RimZQ|mjt5<Yd{y-ht8
z^E=5t>6JS0Ba-Hgf4max237wGunAQ^Qc{7rucT&As&-_J`YRWEP&-BvL08I+4hqUg
z@}PKsFMD-tG$(BsIZZsI42Nfl5A-_cUvg9xYqDgl4q%uf3tmZ0mbB?&sCX!Xe@B*<
zj|ioF`7UKSm%6)<5+8%RtkuaVd9DPd?1flRS5h7W)OqX6b&sznRH&0sxA6VD%RG%e
z!d>QRq%m~Y_m^9ZyJ#65Oci%3$6%_sOF0Hr<w~$Wf~s;Q)R&8};v!Y`;-h>dRE0rD
zahEQ9s>FwapW|Xtb%e@vmm-|G5#6N)A0VN!ja*6ff6>r?0E9|E(hq<Te5zZ{&Pxjh
zf5n}e@Y6wHaV03}hkhM0PXkNcsUClj)<v=Eg~U&a@XxhGUAAc;y1Q)ChwdcOpNr|@
zK4d%s*TqHEx)GOZgi@cOgt$u^hMwa78mvExjJs6f1K@M%!q9!(p$a2BtGggL`7BRK
zFxfykxxaK!TCRjG0p?r=>w_dTSF|8lS;B4r=8H2w%N5jcWUtOvn=bAU@y(U3<w|O{
z_4$LQ;#+Dkh$;@|)l;ICg11t3Wy@L(E!sD<WrObRo7QS;bpz<4Tp1L2-!xYnw0z$*
zS6|6}_nQ{$E6CHy6`?5r*rtkoB{ir(sRra~xaWABIAdVA_;x-M04IW$fve(st0$vM
ztvU*$tM9EUK(D<~%DGoeL&H(;N;rN%*Iv9!G=yBfqKSzFbnT_K3%d4F%M&xZP%5={
zPc;o}BMr+yf$>e9+uF(!8(rxAyeq<R#CFlJ3}<)WL%rJQ#89_3UT=MpPl>7{_Vu9Z
ziLq;*1$L|6$d#~bUPk~|!ka6q-tsdwm_DwgE&e7~R#(H$mDSmDU}bf+4s6_Atpgv$
z(z0Z|cv%u22<jC!KKEb@P0u}8Dy11)d9L3gdy7m2zNq$E2Out}y;qQ(69>zXqS29Q
z$C9w(OB7}UW5tzv$G}+eMHBRuWcQVf$2#C}1<e;$yp}6r(>VF9K+~n@_@W8gU<mX@
z6ZB)S6kZV<Hw=<C=qsr%yB-7tBz?<zrFip2E!SW`y%P2h@V54!Sf_fU?;A$hE2+CN
z>oZH(Wx!kUwbV7h+gfTD@V1uPon=sTakdOb<11m)6H~r8BEZ{PYJJs&Phy$Df_+77
z9Y?>#gS8<Usjs0vZ}d>fx~&K+u9QNC^aH+zItWB#k|D!|fWwgd(X_6p7T>@R?lWnG
zHe@fo67~&vwoL6tmcUdrB(A+8Gzx$dBkM|PG=@^Sn0B>_Bi-t16$iN0H8w!vqS}2W
z^@7@0t(<lj<I1d#XmXM;Bs}#+6SU#N=_5fY9aoPg9#>XQa+M*C#TBp>KpT@Hr6i{r
z;c}i5)q~k?X&J5xIU4b?3{)AP!FG}0<x1FaPP!|vl7SoJ%By7H#<*x&hCHf|D;B^N
zRd-zv8rfUdya5(P!ZHIaPNzx5kbKqW)*t|jb8`@digT-JpyJ$2C}m*LxY$~T8(dcs
zCj*nl=hm?9W0x96mSCTYEf+HTTxuHd3D%bx@N+J;Tj$5Q1RLPe_*`mtV~A62?;0av
z9M|biV%U?S8sbFLo`3U^fYT`;2WciHjlU^dk77bzQT2cDq1F4L;lL6)ho%u=ItNqn
z8fY}G{8I)RjZahKiKfa&W#G|V$wE0X$fv38dSvYpm1ovx{}YSVFMaMvd4DCA6dOx&
zhfi9iZ@HSJ9(^UXAgM<i=rLD<oQnn?iBDLit(Yc0X_hvyV|>soZD7avIBFbj4laI}
zA@$Lfu=Ub&oO!9PAm?!$wUr0SAzQV9lH;O`8KRc^kRpw&x;|>uANU)tHhH)kuBin6
zF=ds34C5kl8F)({2}(JSLzZeo&Z#TnaDjbetLehNA*ddJK9E<Q5|zXK#t-rv9#XzP
zavxH>!Gm!Tx~`-Yt|6rv<TD@q+6F*RnXwFW;X{fuChYM+-n1dZn2)Jh0rZWTrTYMV
zk09S&$!+yXNlo)mvw*!Z)GVNHNF6V>%oTvvZlKG!C|x!HeS^9;s4=d5T$a=rAJV=D
z2oFA_ePi*uC|!mn?@HQb$S8az)zU0%e69qKuC&4~%GMQBhr1pOfE+YT8`5KVW&3&{
zszFfy&duN!F(wda9IP$_Yvz{OatGdzrlxU39MaKi&vBE6K4Ahi;yIWzR{)lXfjV<V
z{7EhaJ8HXLk1NlZVN-PkM!jnSJFkl!X1O)H(ROXvyxpXtV~2Nxie4<>Ck1S&FjQnP
z19!$v`uGHdnyaOP(8tZy6fhJS&1|mxn<K1)tCKHgpx3y$umS`dx2=YOp(ZWA0N71R
zJ_5kHm6HG11cHioX2|F0CJlXhmax}=7IP)6!Skk3JD-JqN}F~Cxllz1Gw4KaQx69C
zl~(dVR4;Mz!3lm!wRX$3SfswsK=*0K{*1AHz=mOcWe7EcF6m0eW~FX=a>Oi|EpEm$
z511`ig3SudmX9P$1!_h+wn340v9_#I9X~0;7E%5XZe0%rrdj<nPJKpGwjnvPn{tX?
zQO%aV<CPd^O%1~knt9y}M-%Ty55+l=EG}E~7V58h?V?>7(jj{f{rI-lr6I40ov=$s
z#!<|b2hNZl*}Jr69O+!VE2~rA^9Fq}oD8o7ZR2F8+;N8BY*)g@fqC6|MQUqj5g#`Q
zE#9dygU{k!Ds%B!yl*{}uqdjQEx@Ak&siPBuYe;0EOsf)i?G<KG%uiH7X&Y$BB)xn
z>IrNXxY%Efc>x%^G-fbgyh~$70$~?Z%Zdwg1$Uu8CCSBz%y$M`$St#R0A-&VGmx@V
zwSFwEE-tp0f%tMI*lKpm(yG7Fd1=g*Rr$`5KGiZId6#;;0f}7-GO{&00#X?$Ew@ao
z4{TLVDwie6<rdit0I}1AZ6LW^2`&x|*`%+CO#>1;l<i`|xcFTLCXDyah7G34-qkh$
zu{X7C7^5_D7!X~#{fzmsT|BWX%Kj-Tj)BPHqIp>nS-eS;29f3QcGPJAT%&RgGpaXX
z?Os{JwgNlsm2j_ut@eu85b&(YvW-N=&Xj>xd5Tkji%dg~@{cHg05of|Z0|Y`HrD`g
z`fF0s_r`%j<S!%FrAfmk*+r}^1KFkRuS#VuRWd?D_TY~MrCeoAS~kr3E`pZ9^zUU}
zejo}|V@ve|HUi^mTPW4UN=x5J59s7<8C=G%fXx=-HEHSO$Fzx3^;|bjMy^YfF&obC
zF1FQ`)HKSL?Hw%}+&8RJ?Op-8f?T^-!oC3fniOi>HaYoLPl~FGvS$}(rb)vlXQolZ
zCS|6{n$3$aZ^CL)W}1|4&}N!+Zc<_z)oC(fnlkd)rNlI7)41BZWj->Ivq^Erjp07h
zoGVf7Q=-Nn-KD>kf65T-VIQc@6%1k@Y0e<S>~jPWV8d+XbTlNH-HMH8;Ky7E+um7X
zyKqRjq6NWyQ~Suaja%L;;jC>0TazkX7sdOC8DdEHx{p+8<oei0x-zn`Zj!;w?>|cg
zuDkFjMeJ^%cd&HVoqCqBCE(tDGw`j|#r!UB{s)pwBywcz2J>Yf8M_e(Wh?uQA(`hs
z?|oJhWUhd1AG~`i(;yn`BU5*@Pl;4(i^dTO!I4*Ti$G=|wd^DC1*v6={&giQ%j{Zo
zbVX+FD74#$%5!wQAt5rTFdqp@SEJlVc5cvMw(??LNzJzG+!Z?b3fL}ErtYIXAO`wx
zDAmNuvK=EwBfEAC45q*18yJngcJOL$z&}=-3IT{sB372zjm6oQRU6S+J`$8Z6+${T
zC_<a$tSiV~gqYP=l(QN#YDXd4m9XJln^(YQYx#a8DCID>=vxLt&6S|#I_g~k$L3jL
zqXmdNg8nlG2F(_s%kb9@>Ddw0Gr?&DdRChDQ=)}h?{lhmGGIrbdsN4x{+WF}nE4PU
zV|K0ty8~u$hjejpZFWc*uQ&1RkTMRo%?|3~;M#2Qy9`{L9ni(Ww7F$!l}WX^0<;Wb
z%?|0_Al7VgzHXw|o~z@vS0nf94k+KnTihX&HK>hSWG(~!afeLSMUi|`#1R;J41GJ9
zH9KUn2D4^|^lvb0cDxpAP-}L`VvU{PO4#<O^&pKL`^lA*6#~?nD`4Y@`$+oO6$I*F
zqd7DC3)TAIu(?GSGwg>~f@c&ShSX;4x;vycgO|HQ&dUbg%#Nl90}q3S?6b4Lj+Oqm
zT~_R3%{(b$(*Q)##+d1NyL4}$*mkMj2Y&Y3se7LyH*S|<yMS=J;2Xs0?NZ25f<@y5
z`l};2h%z4uN(g7legXTGcncY!pAun!06&+h8+yn`f>O@3Z}qCCV*A!H;Q;%biuh<P
zOZCAsqxDCEQq3TZ+9Or6CnYt@19X`!F4#cC@$FN!fO2GUjf&-R%P<@aXs6q0vL4W2
zKN6I3&S<q}((fz5GY6+^s3(9l9~vKE&1tnB>HKiZY!<NQVplUM`F3Md6KllO(yRfQ
z8k$%mVpop_EEKitCP&}i`Ot;Vc0F{Vv-L^d^4(UQn)4M@U;Fz+%rwo_S5lpCnmGhb
zyCO7Q&?g$#0JCO$`xAdqU2kd{*yoL!FEhw*Z)*F4e*381TDV(GumKj$l`NDKv9Eyb
z<f(8gr2y00UkO_&g?EbyHtK-8x7Z^Chv2<KLj+*%K-&Pv9ct-R2`_`_xLwTv9k**h
zg^s-)(|Rg+ydo5DFw1u2s5**yQ?hy=Al{?|YXQ`o6k&;hdy^u5M#;ZP37UriBSo06
zUN+B<NK2x3_Pf20>g+ggB(A7BuQ%K~`Yy8k0HG#D#TOlA87dJwZ`o0?;|J_ZDPnVl
zcq!ty*pYp)Nevq?UZn{0mjIapPG2EpiqNNm$ds@PqlOn+0<g7xM6T8*UPQ6$AIQ)t
z*TgJ#iq{FF2sJ6easi<xMYygRpwy&nK~S$tD%a>6MGUU+F;jfNQ+0rclQOopYs#r|
z4fxBZXh9IHlyg!K!q{+r8gRr-347oe+SFjnK$N0Y4|0x!%=!V-_D3|-r@%WPH)y~>
zo+8|13~*{vhE5&6mZ44^&aSCfhm&jX%RB5T4^RUJ{1l-V)~bk}TjP`)F7>YnGfs_a
z;G*CoqM38xE+Iug$D-+^1TZ~7!bw?;4<wwF;L`@F<|AtArLkKIzc%1RU$VxZP1fYY
zjQwgTW}k3Yeo9pDK^oSuf!81v>x!!9u1_6=oD^|$NlH#i*#5v;bk?brC>?9yN-9MN
zb1`snRWi)^tflCo_9tGj2a5G_okq=P*y2EN|8XU&%AB*s4!Zih*hxn*b;(beN3H=v
zO^Wc~js9)*cw?QuYM9}$nKE`@a~NA4*c=MaUc>wrm)eI1N6OFv$9i}*HUzCn5qscR
z55Cj^Y<MZdPK2-@AJJ6JU_W`8F$_ia@u*W$=j^ao)aQ&?D#ra4p;L9l8deaK0=30u
z%460Tgi|r~#~_?KO{rtRN33LxKU*b04@TqQ>Zo-Ecm+IajnS(}y=ZiNlx}LibF|tR
z24VA6=0I;KQJoLRDBSd>E)q9i?QIY@slE+@rppg*45Fsv&@~27(|Pb3V0&anCw3F@
z)mv$Cd{k~0`=|#<t=y>D4Fahc{bLYF_rbwwAfixZkU|$`j`!8=!01U4TO<7L;30E>
zdGnD;IU5Ah&C821b``OC4Fc(QZJ!9_lrqdy;pletkvO^?Mf7lMgBe88z122hRM~09
z0F257V1VwEBH#@8J}JUJFbKBk2rvebR-OPOlTOJEU=+dUDH)pzzHEK*gU~Bp{{Y`B
zMSNJjzZ7vGgkJIc#~}3XsmBv}w+?*+T-7VP<#}OO2{pzf>~7Kz#w6@+9s4F>x4hFI
z$gpm8@|(b2xepA`f37Htor~6lf|JNh?}0Ii%yJ<ZN&iU!1`obZieUL0v+C5J92PHE
zt_Z{8p<n`%ch>+Aelleo0wH-z-=Bo!Eq#9ylIbyUCG`%Q20=vLO~W86Z>bWKsJwMb
zAj>CZ>;q6)&IJQJpA?}B6DwpL^<iRvhkwDC1<Q+?{v;~PFW`!*lW+_e6NtMM!TgHQ
zxb*tD*}682NyJ^QhZAuxy`UcDRl?>EHcyH;9|YW`)4?R*F2#8qh$5LXcEB;Y@FB>=
zv$=}bR)c}jZ2`^<j!s7eP_;9~9xD=Y=>sq(&ZcW>YoA2ZMW4H|h^DLTr(+RImlXTe
z*n`QveKpQ6$wp%lOyw+aMVMb&T1QnHIv_2=soV#y2-C^qz~bR`={T@(cwKVN8;hsc
zCB$EZVYv-l5nhZG`$dEWm@a~;X#WGjWK+a$5>Dj`Fc#r7Sx$Ub^;6&UBAVhc#L`9b
z(iPzqH2TzyMKE1D9;^b>)ztjt(DXqsf@%5?ROXTF;XG;$2id8Ez~Vu6>L9Rqj-5xF
z@FD`sb6~8E!QlN9ZD;7&1-En*cv4cmmao8A#M~Jg2q9Pg17i_#>n30<;O%q`jd(kG
z5Lkp;c^HgExSjqEjhHJpgR$@&HXc~F(^0JTAqRu8;ES9xw9XT<oD9ao33=+YfN<6+
zV%vv%@RXKNQL$6Pl|-19ufbS^Y5E$B-KxZ++a?B2odPy7Se^u96NBYSFg76=yLyRg
zEF?~hO$dfJ!Po@hspG^Z2G6NIZxe;(c`$aNupAGr0Pl@wjNSRx-u-3sBs_IA*nnO+
z4UEmhu>1zbCh|@MWFNZ@xl?NYCZtZO{hN?FyPi!*o&D_;54vzO7#n~(WenZ~)Tsl+
zR>su#08tK^A5l{m7N--(1;o}*0Uutt3r~a3r?Ua7NP9Ro5p_tx-$Yb84UB!Ua)bt|
z!|4!uZ%5mMM5ZfRCE$aJlq2+D9!=$1FgC$+$Y8q(pF<z~27C^k2{uSoDZ}Ff%VbFB
z-}U7Bvu1Q`{+ysW6j*XNQ8V2IMjg67C28nR$du2(a6;y&z4R$rt>GcX-HDk)io2s0
zzI-QSj)fw$f4LqECxi~^^-c^O((4@<D({2AbMBR)jQ1y{-RsCYq_R5!RsIFT38>>$
z*?m-*V;UTU^mQl3j)5Y^U}}5RjY7)mn|I)=JPw8vU*&W#oER&ogW*#nm2uyRvBOZz
zCrgWW;w!xnhV%G3I@t-s3Ayr27*5n3()JywJERvlQMa5E9>}mhsM*69loAe@pgW}6
zBOpYIXd>`JUilvkC-BMxVK{-8E(pVkyLR3Y5_sW+a0NLSIUx)u^2!TgIHA{G`@a)=
zP4<5$^cqhE9#z7g;zVBfAw0tgz9!?p^Y|;@gn^t%DdG$ShwHk(al)@06o&I;Yf|~0
zHf8x2jA&J)vK>TL`4@~JvckdO3hJXY-3A0e)I_GbqI&1H)EIHpbRiJLQMo3JAdDIU
z+6}~yNeQMZh@<pR7(pC0T?s@MCu2p7pv~C;>_MD09UFotRg?A~JgJt$!2{VU3AUvm
zuG;u|6kZgM1VIS3_W%%+)2kgLCi|%aKq!B>t^)!nYH}VPV4<W8Ez+uNIyeNe)>y>o
zx-1M)P-{9#;8rI^crdNXa&H*HgQ>lif80iu4AbdsUzYzM;-(YBh(cTXFgz)#+3nKz
z5m_oloDsrpm*GDMxBWHz2k^G*1Q0x}c2=tO)@At*T9lD+;3-*+SMCub@DsL9`*9Bx
z>m_z!f6#hNuZJtaAf)UcAa$2se~8pwy8UUi*LO!5J(hBRh|+Y17^hc>4H2aK76cyJ
ziMurWL!g#7#5e?M`9q8Ype}z1KC9Lz9U{izSyvtr<Iv>XbrW!i=v_>#aSGDAP5_6H
zF3*SohT=!06Tl&aGe$wlFhuMN2ly;MhjEC{U8?*cKIfh70};Be`+`Gwh6}_v1<+l$
z1&09LhmI155Z!fMaEQ=dXM#h7maD`#K<K*4ejvhH!F|D5d{??JI12+7FXRxi>n^>X
zM9h}U#5ly>E{*>XeC6&i4xqN28y<+zE8Q6!Vr|DE;1FoL4grTi+Z&A)d<xql(l%Wf
z973(UBu28DQvgcdI7He8{ooL1<s~r=VU}(Z<Ion31U^s6a<p=txRUB-)4}8LklScw
zxampJO|hkC;~7@&53>Pl8}AHeBh<<PVm3l;bIjAMh@>g0sk#z$%TYv^w%Q`hf@|}X
ztX_dUDP}{FjnkIga2%P9reyk2JSoG_Hhxm8vMsfaGq0R0X5#_3@#yi)M#Ppg#cVvj
zwy7>o_KD|)D?+El0h^7`+jt)^8=*J-CT0WdwxMnkb=!C+iMZQ%zL<@;+lG2T>}^9`
zFX&~YrIKJ_4ivF0O&uUQHyki#BRXSNpOV%4H#N`GaWf5;_GbB9Oawyyh{P9~jj&F~
ziz``G=0FJ9a;mr@bX|vq*@)SVHv_W~v*~;>8xXrSO(qe$DW>0Sgl#!t%tqL5O`RZW
z%Qa)R^V@-2Mov`e1y_XT%S?R*Y`%c~z$;^dVRht|F&pkC&*52O=9cvl;D~U`cML~P
z7ZZM62R;|G*WaA0-qA7M7)*o^KXRs+pi!OUdT2-AyjU=^C{#!8784Arb6j1mw|@@L
z4im_54v!Ac1biGhW=up@Kl00%6@EP>3*|r^Ha?y#vgLs>^4?$qanD(*GSNHe{xfm=
z9NigA_&J_4)saHfE5VKc#?+Ny-vVLkO6sEXN(O4NHw*L2`+^D0<w`gWt0s7mBr>5W
z9r{>Ic$OadSj?nGonw0J#t`(GciaeH5i2<+yh``yUE>S1*)_gEqg~^RY?LbeM0$mf
z1f`m@rY;2LjJ_1J!^(S3Q^Tj$c~iRw3!P_x2{rztJH>>ee?n1$=I0=Ag1Y|1N#O)l
z{fXnm5u0x!uFwhU?9*UzJRyj!<I52#?+ONL@i{etSAx#s81$T=6@TKa^pRxg{-tjc
z1gI0x=qK1u2XRU7dI0<B$iZTQ{B-1DF^m6n!quo@g#0L<398efJH-Ui>ByyGCe7){
zpJIaLbR}#EQL&ELebZ)^@a@~gh?d4UF{H(IC%P{m$1BSI>$A0q{x3CCD0yP3sf7Ve
zZO1tDpO|cG<%p(6xG<v9-Y2XJC#G5kE$YNn)3v`Gxm?U*MV%NL<i^?<Y<OdkveZw+
zcQ|3H<=H!G<P-5Bj$9=sY%~Y15)*leZkb&Pv`jsFg5-3f>$$b4Pjo#u_#QhRT>s2T
z0IY@Z7=)*kH2&sxUb&#IAV2shm3)qdY179I_R&#3@i}^y@THcm@JSJ?0JZ4wFv~P~
zlren5e0f}7F1Sfo0)EXES=HimiyL`7_*~$T(;|N*IcrQD{-me|APswrEV1QM*N!`%
zS}NU9YVkSh1bC8!H<K@Pm?eB78qg7EZh}8_(!*hbI&|dW@JyJ^k6auk?CQst<`qEX
zOTz~ci7uB9%86ZSdSPO#Ya5d~HFN-#Pqn=3$bFPUd?x$oh;BE*EIR2XF>yh0Tnchs
zVjP$GY=TpC<R>w4`EleGF_CcZ$S-1!Kz9d9d0al?&s|Y|jr5YZf|W(K0(_H`#Kcw5
zanl)K0OVX+F&IZj?73O@NyodI2FAgc;z>y@zOL4RdfwGKkWWd+=WJQR7doNc9{Nd4
zkch4TPelx`qqO7`_i9J360_odow@;fAj$s9H)0~I<k?hvk$Cbb8~H?b$^%N>GiMdp
z3Xo5p5)%}nBTtDd$z{7k?IMfaVOH{4G@~PS-NZHMfuqC(!|3c#(*VL9w4qE8jLr_V
zJupIHHPU+?G4$q~=%2q+1#H_?eP@NDyMnh?bx?{guA$G~oGKvOmgbANcxQ8`NM_O5
z(tN=zI(w<%g;T{|YP$aM?4_mwZAe!>i+prMvzxfKzY^F6aJ7FWY<t%br<!&QNGdgA
z7anl#o)T4Oqzi*Cbi|gM#TL2(Y$xCfT}gKENm0Ei>dOcLbd;RD1|Z#d9`wc33<AKO
zZE7gdZJXxdV1A9Qlzr$ZKlzo^fJ!Z0fWJ-V{FUTrXeytezZ|A7pP<Mb668L^12yPu
zp=dFKj!112yr8pbB%h%Ed?YBP(y)$t0`yx_n-OI6C_DKCqv%SoS5&aldJvl)Sz@y|
zkgbDKe$Y!=HW)>xI3Z6-a&${tcJYbMl9COw&{=^}eh6a1O@<k|B0i%q>Pq;Kl_mBX
zn5mTJS5kd_KV@VLKWnQcfaanGy$Ujy6zB!WT#BeU!5BKqYCacmb4i5;jp!_?(a9n@
zOG@<G93-`9P>9Z2Y8=q2ROb@}q9YdFEDF(CiV-wH7&>dJEw52ghsIPNB}1PGM|?o3
zyX9P8(vLxJJWC2PGS(laI-g(xokjEaMArM~iWUUf*`eM8IM>k30XWxC(*Vvl+4;n}
zKcdae&v$W_lx%!AXF<uvmvt6x-dB<Xq{;gVHmcz3-vG%aC3*uS7r*X(`yjLS+<?H<
z)Db`+l9W#{a*r5r6KtQez=D5fk$ui;>IeXE(xyE@^*Qrs{D43uDW4nON=KBqiEa2y
zs@@<rpLx{Q=j=B_?cnS;;~gUof8xi@4X{(D@(DuE5v^?|8r^dC<VitJ_mt5Zpmrtb
z9I#D^$tMWsCkbqG!w36JS*$m(ZEkfA*fwRZ-i2*b2J2nh!E>0ud~TqfsB2eJBibnC
z*F9ydPKwYiQ^$o)ag_6Xf(~@14Alr0bf(m81PeM-*HaVJpEIR!L!G)3J_z_XWwwS|
z_K~1;7rWA%PdG{(^3Wz+V$YOH4v&j7Wv_-?#&f2$^kNa6DJ2~wqLWF`C-_50M79a`
z&`BllfuzPKHQlQQTg7ovxzi^U=p$O&bWmB&ltzw36jxFs^g1spGx`-&SEX+|5Ocl;
zY6oOa*{2-`#z~$0a~?TU`Z&%jN6FEr4=z(F<lqTi37ZCLPMM{PC3J=~bdZFeD?-b#
zger;pL?EIAQrrYR=nQG;$q+h2;esa4dS^&U&t|EO<M4PykefJQo&j|nSy|4A_W`wE
zDQWry-zO!QeL&`rrP_Ja9F7MkVh$OqLH;>IhH7wsj#zOM+@CW<Yo9o%pCNs{&hlqS
zT}K+6GhnAiqMV}~>d!2{yhDoJ^gLT47y1NI=ZF(GVa+&$R_Zc$eBRzvH-LRgbUtA>
zIpVub@OZ9-4~9eJ71fiY<-cPFz~MPVChBNd1X9b>o^!@~A`hGy2Q_XOh0c(Lx*S2z
zkP42l9EV)D&!&z{P)DiFucQ_WOF4<MQp0d|hOE?#L~@w4e3pmp5$kN08}5~$RC6XX
zHS$}X(cbX^=Z4JGF|)*0fpbF|I9NCz2}-rWm=x|ZNFI~E4Ws2TeT{H*K1yFc;S2p7
zGR0=>{CCy>z?pPq7;3MCJp;y>V)#thdyfT5*)x582*7iUHfh+9k4e7{Bs4!J1sk-S
zV^Xq{nRArke1eyA#4(%T;2hiB-a)}RCXKoXI9I@iZ~|0b^a%>i0mbYokykA?6&RE>
z>Hsbp6>9kQALT)RW+ulwVv<dy&pRfobN~rWR%vi@j!B<B$lZF38g-F$j#8md+<zR9
z%_c5LZW&GE7UfE~7vrksiqQ7CRitv`s^&0b`UE}am{jg!=R7ImPd4hX;g0c0!^V};
zF@4;p(9-0kJ`uX>ir5t3(x7DHuIea7`aGjbm=fG-ACqAl+?!)EY$FThF&Vazsqz@?
z+C|SfrmU+I^qfO_+5|c0m`vN?<{WEkdSX0fKzmBG@gqK_2Bdug<eAf@Wfynmh=w)~
z2v4WW;tl4^=~TP(KJ+NN`NWOs>C&ljt9m6gc;oK%iuhb0Tc^eQ)Tep{95;{+3C^Dq
z)fl9lpTf2-qc>vuolaF8VgHU&pg%KjsZX-aW^rB)Gnr2?UQU<(48qGtf>KUwm%hAk
zAAdSc+zXfXM?|oNoBh+NL9YzJc+0S@ETq-_i15!fi?ncGNlhYE?$v;FouBS%<q38A
zRKu`^_K8yUe(0%H@@lj|E>n}Q2CC-~Z)>%I28|U8;JT>;0Jv`I06?zGPQ5@kIm}I-
zlIj=r;?+JN*Si`9$o0;K!F)Nrt7*Vq?`j(MPvt9L#eq5Ed@XQWp3@tj4C7{RdT<^9
zmC$^F)pJDdT5V?un)d=%=(MB$0}9(=D?q|_)CzzQEUsr&*6v$YE45d&quv7y+tIY)
zu-8IOBX!*og=;0{<(Bv4Pjcn8Qi~VpE~kZ>1~@iZsTasDr-j-sbZk6JFK}H>bF~~8
zq%)lJLf?;4n=g#-i0`#>PEOl;44|)34Sp6Fa#ytQlj<?`;031LA-8LR*3xLUULEw`
z(`dI|B(^k~t*<2CexuoXAtumirBSb5zXy|ek^IsY+byHa6|mu+<C|&~CqSh!e-@aF
zN5rs2hDsai8c?j!WW7FL@@Ydgh+>UY?<=Z>IoLTsmXeaM+8vHqTZ_DwX4(QtY-y&p
zW=*cCC4g2lwlp!dK-ninH6+6iYB*gjuPkwJIL)=LHgJi5#O7KgurNh=N^1J`K^KFi
zwXZt0yc*Tih3GyXQI`C-I7huItumCJe1Y#A;$5u{Z^tWQs|99P!gdqPt^nI2V$27g
zT3=e6AlqbtDifq;Eih%SfGyvTI!>tBvXEhSAPXi$&03(i#BufOpc_=5mo;>S>hqQ4
z&Jc$d>MN?gz(T!JIf+Ac`j&T29QEl1jV2hQute2g8mJdkqc~fQr}h+Qsp(o0Q7X<|
zT42Y-S!%swoC0Z(V?u<jWmRIs#+NubBEtxTz@>Jkq<%4~Yg2t4=$gV;FF0d_h*%35
zBCZ6R3{ps3Nj-Pw-|Q#S{ag_{JFy0bS}uSLQMDFy{y3(Fb7W5(Q^ON4-_Y>Ft2Z^i
zun0|UFT8o9SIt7sjyPS7Z+tdg58CK5l;M?Uu}>KRTb`6uZ<_k&=uboc9KE6DyFhh`
z)A-noKM;pj>IJGx#8Kx8vLcRVreH0UwR~0Hl_y2mTX5995;k5RUc_PJ^<`cGThEU-
zLfM}d{If#2%@>l%gcxC0Qau#hg7R`D+#f~``AX11*bS}(9fV!sN~(hh(-Y)xJt@k?
z7oI=3zoy-KA>B^|?bZt^fg-kAz4#Ut6ZnCkCY<NyE2+-!EEOh1EHz^_lBHJQJrqi6
zzQCG^&=(C4$O!4oAjO1OSgRuNJP}iU8R!db(hD}Kj|8Rci<D@XxFYCKv0w&^7;0u>
zT8BC}F{?uj*HhUjqB%$AFkfKOgcw^3OqvL);~>&RNFOgAO@xu%wm_W;r9NMv&V*=O
z3+BZLDc6+)EG2r7XOUe82#Tb2CDq@q$2$7kGy(*zjG+2G3IjvhH!QIcf@@f7Bcy*1
zz+fn#=Kt{9fA`!)+dfr4KXY53x*yPL9&>!oLjV1L_1pjPTmP+n{;U7}_y78U8Wu2R
z{_AfDl^$E^ypi@I7S9+RcAk($wogn^$lTCZeH$UIyu1D82UgHtpPs)#ds}7;s0c)N
zG?{&~ArEE_*^m~@VfQt}Zg5l9kXm`(7zQ6&!#+6e*<mDBg^a;jBZEdVOdXwkDyr?E
zd-i_4;&Fjp(HOFK!|DAo6i6)ST&q+%6DQjASrAoxlY>jbQtHOyn2FyZvkQ_2e_fn8
za_U?YFbzjA_{eqcJ>+~NbLka@B(;R*`g|AjvvlS-*7xTRZ~fEyAFZI<?q95++M~W#
zP)+)~g0KO9Eg&UF*8)0UiwE`J)w90VjxvFCxcB>CtsA8;(#la*DlHvGg-0O4Obmcz
zMO-}E0p7(UT>WYBz`5gV@hCjNyLc3P@_X^nO+$-^n=aQ*$cl}%qiYMU9bI{StsUON
zXzl3IPHX4;ILx&})#Y6~wccy>e9m~E<?~rIeczqu^T(RKe`e!vT0H?Ib{_8oIIM8m
z(X&v)Lv+h0oF{v{obcKMu$|vxbu!YN5@MM~8C=5U$Ax&DSAs?ghn;s{2<v$TtBQ$x
zipCu{BnDZiVHgA7_Xpj=$xs6phI2awTn2(}f0hiW(BV9igDxE+ohF|;#5hIx`ViqX
z;BOI*BYD)%(Vtq8;XIBbg+hpI3jHE*|M;Y&W|pV(;+Nktnp~J!?D^oR-!fW72&zaf
zDsl#dsHhpxHk_X*0^^3`*dC78r2LUk`NGL7D^`CvPw3$Nhx3Gv+zG*`+rLGyOZ*fN
z?)M|8!hIeO=Mk7?p3kAYUICaBfupBrq|kvwEYi}F!+Bu_J^CZ4LJg@A7Xee@^y)xn
zixA25v@BF}r{TS|D%93|cn-rcBgiAIV@PbC&*6^}n-~I@l@LkvAPQ}WB#IOuL5k?9
zztOpx*DF8=YwE9Hlwtpr9W@kL`;=-IB8Q$-{zBByQ|e)C+?XB2Vvo%mGn^4)^S%rz
z5MuMb`b>0;NA-il<RyhZRnA6v0zWt;N>e&GC2m}3;Se1ndmcDM2gsf`*FhH0gBLh4
z?uD1buNt{-V$0G7&#O=j#)I?ZCW{<~hL4~MHIw|TPu={5qBFvj5t~>G-?UIrMYykB
zK@Br%$qeG;2}~_N%oA8MqYAlxH&yyF?WCZdclh$C(Zee*6dw_ud$IZ1rfXkpezVBP
z6kG1l2j@gaN9?U(;-r(bIyY{qxeeH)0E$nCMJ+Zp{tl~KDCl8F>Z&WL_u9+vG8EnL
z3KDBV;SD=1g2Cv9y=;b|*oGZu#XxAo4!dKl!<)5U*2xsHdqAFb)b<B@mUMDt4+{oJ
z><zCm6d<v~1vU^LvBOLDmN~#&3Rl2pOTmn#s3%vHFHzwVuViI;p|tVud}{qG`^}T#
zB5rp05QhRF_6C$%I+-A|TOcChEoWEvJ86Ka1snNCRYT{gAYDoIeW_`H)mprc>}iF+
z0=A3;<ywE@WAnRNgybtJy?C)@WS5P#)U?+!m}=Rv45kJRqpCtK_DX_q1-Omu$bt|G
zx!7@s5sN3XJT!&kD0bYHTuE&WPsepiD3W4_+x(UAxxhDuR_x_|9}2A4%SHc=(ljW*
z+@is~BO_uctm2i_QnvS8ktJ+}_n1*@8OOnn%c>AZv}dpaw19{Qq2P+W*G=NrIR%L#
zzs|lL__w$zTuJqm0DdJ2)`4!`Mw*V(0KkRQfA0Xm)zm5ga3S4hiRv9UHCq_CsC;)s
zpNOeFrP3P2<d)KrSuEz!aA0(uym9M&W(i+i2P#hO7#*-U14odKi`QVp#gt@kCw7cp
z&^hC6q?Y64j`4H^0*M)F8~8b0ZNtXOV2eEyvBsoge#^<yz9Rl0SM1cT@;T4ObWIxI
zQb83vGRvl<@T?<2Z72}pl~hNxAzbI)EaU6xfK9lCd^EuhgGNkj2)OnS#YODJ3`hYc
z5>Ptz`IBLAMQjR)I`#b{1wtSuVn_OenELvW{vamftzJnDX{zxA)j8BOtgmyZ9iS?F
zb?zVy=Qo8u>`0j$Q(v<6Ea59gOrn@n%DW-nTugq+NZlM$Uor?Mp~#3Gq?DM{&O3-J
zPt2~S0kgBK`NG+$UBG~|v$Jsk?Hd%aBi7SLgi?*LspXL+HVObmG{h8?32@S3q=RS_
z3WwN{m^&qyNkHT{U$ttd8P(8dAS2WX9O_1>BLGarO6=fT#R%FsuP8s>5o)(EbA*}&
zWR5BUFBK#a=A9=+Y#M+${L2Qkviw>V^Nq?Tgf!|g{GE3o=8z6xI0cF>+ChN(vQB~|
zcO}F_1Z|6<4;GQ#Lg5s9Mt_STGZq5G1zDp{imHo5a0B`ceXv&Wr^ty{kn2l<6R)Jc
zX%R^~c#0t+X$O@t$Rq8eWdYv<5)^zSi5COVr>KfOQxk-OD&BHUC2@KH4;3!)O6q7g
z^sx?{?G*X2k1AoQz=9OABz64TNAjRpt4p6`1zL<D(1i&s6y30c)*A3deoACji|yb*
zH#$o7@#vGp$b)eX`xyLo1iYWg3xzoB2wEA*DZQoaxI!8B0W@NIiW03904D~HbP7J$
z5x_IZDD7isfjvM3&=95cigE%)DZP^Hm?95eNp()(Id<Lfh*o+f`O%VA+6QhCMJw%~
zYKK^*9dzz6m%f~Q?=V3q!lj07J{Pzq4r#BrtAUt=y&|(dDF7-D+z={CVJ}L1h(X$s
zTp+|C?cl&aK?-RffHegu?4Z(z0d$jUA7Yf=a=jrrWL;5y)S{GLNexk7^~CYfgu=DC
zhbd|MmE?*9r}UO{O^Q?60TE%0bkG4IVf?V4K6_fl*)YzVqLB8C@EhQd_6b}Rf3zb|
z@Dq$|*nyd0Qptg<U)J}6-Y}lhJK#B9j%f#?2N<QdT%9+yJ+j2X;jn3@R(RSJ$Fw6J
zbC{0Ul?x!m4((85LhR6vQ~*y{)B6BeTGK?~?h$;^K3D$Dt^zHMvC29;f3AcL11<Ye
z!vM>E)NX+#D5p<Ja^ZFy+@VH>7^hc~%a)AOE67#bkD5*^RP<2GK*z3g`UE(3p*w<!
zhd8Kx!qgumq4v_Hqw81>bvwi_?NG_1yB-YqWR#l{RhM<8lkh1D>MiHWOb%+FK+ewl
zvp&HExFR+TH0@gr7n=610Rc@(X6<mFi>_G89dYL)*{mJsqv*U|>kDAnbuv%?zYuY?
zmxth!BH+z}<us|Qy<7~V3&3%z46#x>;`&Ed0JDzh|Iw$O3VcoKYR|uf;0xH=h2hKi
zHhJZKMYTkS+6ChFq0xY^(}ncRaS%y^?KrDP*Kxc~^Fb19U-K5~FZ7DU)hj`-x_(`2
zOlM~Jx<(g#FC70mZ_fL|@vk@8kl;oeB(8QO4G0leuVkYZ#}CAXHQ;`cYiAMr3w(ux
zSAQMu#37<;FNfm*Pqi<g;n(GMnz3+KiS!?T`L8+Sji|p05nH@#0i>BGEgLS`A+~8R
zD_t~UIt+PH2A`{u!q68@pbleTG=cg8CN>?4)20}rquz3@helA}0K6tp-vxLepZ0wl
zB@V+r8X$~5C8|ajf1gbXh&O<%=`@V%?r6f{O}lBMZ%2pse@bd?Re*pHkF+C(Ks4Ym
zVhlvxWIhnpU9*4~(F#IW<$Zs!tO<uV&U6j9yLqH*0^Tx^M;m(Pz}ph;B20gXdD<&Z
z{}m8r5vTu(I3S!18*mrK`&(wyfI1RSpT6s%Y!_hH1iQFEh}Jca0K3-J?&26b8ZN98
z8MWgsBpT1oxGjk$@ZP|>rnp5NQ8uCpyfYBTEn}lYsE!b$wIf$nz({|W{;q?cAE7gD
zdtAKLUN=O3j-FHBk{^QcXR7LZ^FuVoMU)?*F=ClGdUuh|j}G1y3*|}C)=!ema)iyu
zQ07P2j3j1$2+f)3EXzbPWJ7aRSlLk>yz3gzkDwcA1pM%Bx-$W<i|cwt)fK^PC6G%A
z_6+aUm#s?m(jPzc8tJ(8{76uWoFg5m9i^H>+^{;hs85ON4GMTO7r-sEiTVgW5|nCI
zb+~o_*%w!&?u-3QJ#%0Zg}Oe_aeeH#b^eTw-dr8`(oQZ>_n8GYGcg<iZ)K}a2{(C!
zVRBJcuOxXVqOA5xdhJJ=w@)ll<0kJ5Z`IWL!V<-nfO~%zWAzd+oC$-wLpk!Jj~j_2
zuY^CzZU~Q&q|%iIxVxhp3aM~K)emXi?)X%obth@!me?=H8x<Zq**hXcbwmJjkySfl
z^t;Ha9Rc}00MbbD>G9r=dE%!lWAGK^m_$tNh>YgS^4pOz-pdj4PJgAH_mIjA7K?`r
z(MYlC0XsBkEiMjf58UWGNvIv9K@X|SAQrlE0(V4+bL9l?89&b7guop!=3G?Nj>vRZ
zf|d#hTq%KjQC$2@2;4z(anVsbSemXhz8%b!j|8Qfa2d8LsQ!~8_GO?iGHfBv{*|D2
zv-+aX6TkgP9u#YCr5U3|4{63xJAx}MaF3NGHj3Ls7ZJ6C;o`|W?O?ZfNChr>i!1AI
z2fxLO|5IJtc!e^LC5h!z#^2RVS*SrN_K-C!{HdadZZ+q!g(2poi-gt@m(rE#w+ASu
z9}$XPY&kXy&?5u2g9qcHpmyZ6_E5;)j!%NDyPjkiS8%}&HjD?&++f4JB+pL1x4S-M
ze0uKskc$xGic#1RH`EoUuw!R<T&%E;{lk?2xaW@J9$%HRe~Lla!G3WMp7{@;Q1q~V
z0EHeXW#5FjAjr5v5cXooJSk$!^?F?lu?~)mlOfhm74QPVlKDsy7qN@G>#&^r{4KLl
zAffAE437s_Lg1$(#;uDbb|uvfvd8<GS;Eo+M7m-U_JhNn*TMnJx<U~4qRF@mf5DS+
zg&^z*h422Jgey9*yS{k@!uO<x-BNz?;)Zo-70&d(S5W(@!W8z89^x)IhA!h7kg$UZ
z<BCVv5n|b0DK~pYVRi))?BK$<A_;b=UhYKJQ~%5!Ky`D`zdGXEyZB!neoC%Lf*qbr
zSHhMnV3)hV_W-&WY_Jz^CIxK$;FG`y3)+moS$%sFXWWIo(4C!pFauA<m8;jFgS!F;
zK31{6U7RpOd~g>h%n;+=H<_D;P~)!1fmf3Ka)b`FJZHE92O5qdE@qhFxZ<LQ8ICl*
z#pg7fdt8A7t<FWhT}=b+w!e(x>@JVUkAYm{+tqksgDbPIwUIRB+L8>!8An*bTds3~
z!U`H38Nay8IAXf8^;!c!ig|V=H#muldUhq%|HbzPklfU_4FntC{MN6e`u|d#TXFC?
zKtST2d@4{;>@ce%zbkLAH8|8?5eK>Prl$t5(cPf|Z1k5*eI_w*<>@t~I`BO(pPqlS
z6+q=4>OP=y57NL4Mi3YK%wQ;S($B1HDYwkE0kqtPW)bB53fMN#a+}%)SZ>pp6E2mp
z*TApwGIKl-)w}O#>0n55fj}&KSGHb*k;-?Y>Skrgx)Lt;gAq_Gw~lk+27?~fFc)df
zdgI3kIJYFv_?E{8l7aXlmRkp&E@HWX`hO+RPYt{q2anBqLF(cG+(5eVb=WY@mFuW!
z+)VlkwGBjF+F;;V?_#nU;^JRP0pOLCLLyq4^@08o(XDtizFf6%f?TdXm!A3fa&{Wf
zD!Q8WnWez|0$SHrGdM3UT~iyZ$5+IL0JvnU8DizT*lLDY`5#G^R^6WaT57t$b}h9G
zFeP+-19;`Xvv+N7?bB{;+qP}n*m`ShZQIz|wryi;+uFDL!~fp<-23+XoM|$d%p{Za
zw4KkH1bIRq=TT&xZ4d8;D24}V!=%xznw6ODhD8OIte-_;)J`y>mP$hodfHV?4r(p9
z8KW~e?FV%YG%nbZoBU4+=1BCb)+fKOpb2zJ<u0^==WpKyw}-m@z}7MKbP#3MwfVj4
zIFT1ms)Hd+nmh9>Ydg?tMGPAVi8|?4D<*tX3cPqI%5-B{4TEpDcNA6_FT%pXOaY_p
z8v3Toc9nsVpiBd>OjpL*?etVx5psE*exSEcaJ*P<<U}be!;0@zQPGBeSQq5pl)e7@
zEJfj<rp*V=4&892n;E$DeH$g=;18I#a(L9$T9ch^nh@GyP^S88PtGhnHAA5|rV!m3
z+}>KeNx~?gy9bi!qb-=l%S8~qky8~(ex-)V8aife!zRI0cG-sM*n&G;&n6V5$WWc|
zhceeA<Gi61J1JN<rL8GO5H}G49H#mp&7Z|aUpd^RiYKs1>I;(63j}ze!!eF|RwN~3
zMo{3P!|8`)xC|=&HQ#ZLWmee~C-cC^)S_>QV&;}l`hna-I5#S-CB_hpk>Qf2BU#rg
z3k|?mD0XL(WpvfvIGC)w7O$-G*4!3GtYNk%d68H<Wi2H}!OK>>7Ei25W?rl;5z2hB
z-%|-cI>U9peV#24tSEcWZpkqfk9Pa!2N3(po936ayOWPa&O*zX>Sw!0mpMK-PE-zb
z-%rvO=S2`usBO0sx5DrIi|&%AfA6-3Cg(_vS9@anj{TE>aiHogci-LQUgGTG5~L$;
zYINJG?qwwCr{jjMYzw_`eawXL+H-e@@LqXzB9>kr_3j3|a1C?t7IXz<>_QouLycVq
zsF}0cmil8ELw76;MJ{cF61XZ@+s3~4raFq#5ZDjei+p9ax2_DF0_R3J+8?QL;K;*f
zXXQ;`n(D5(W|(J{&2sep6!1D)%Y+A&@8uTSmL-s%L|&Z>alQ?EI~FSA@DFJ1#pi`s
zj6kGV)t_MB#nwbN^b#+HARG)yIDr<*K{Q`jHqwrTg-69AcvB|xRw`8e%GtR#1B^a%
zy-}bx)h{uZi@R2WBV!yqu>`MqXBP9B>5r}B*_@tWZhc#c6bhjkp;hulHr&>4CsQ}x
z5pKEl3j(&f$$TW0V-<>zq#`_*<a140y$L&Kn}k;IZo`^t-;%TCY=XddhXIQAIBlv%
zh0#RA*>I`CW{?Yid9L*&Y~VNw@!Z1iyO`=Z=}J?9u&ry#Q>TzmKglNDics#r1XEG1
zj!Y(F$VkdI<q~QSg(i0Tho%D{z^})4Q~j!S48W>NbTbnUcN&_%tYEv**cw~mw3B2l
z!FSCYs*wu_d3iNa0%uAeg;j6b>M%u5Z`tb5kO`+=q5ta3GysFIM^}qm8`?Iw`Ap2V
zuVn(ZozYwmY`QXP`N9h8(l3+7G0C<Go(&atIqGJGmC7>~*|l6EWE=<??FvlU?xl_Y
z3Lyr#ge+XsF==f87vsO2@97D3C~RTDz12>&g(nk8Hfr&X3fpv<u!iMd0xi^z)&YVW
zj9@~n^kdkS46rK4h3#n51ka;@tz6JpX;Ze%DAv)ihc~+zN(En1edpprh*5G}qbl8m
zvFZ7F&DK=mr@1R_V>R&8fuxaz-b(uy9Q-(T2+Al=^k>7Ul~vAS^X#f-8izKAjSVmy
zmyIRt2&4`nyiF5z#Y>yVAfh{HM?%A*KJ1O8=4(NYWe)6T2Y+nr5|&Es`bGz^Ge%Dv
zFh<9MyauAh<}WkYp)8fc^$?bkR7JUd8oM2^6Z)RFn+xoKs=f>G{4CcVhqSl$Tcxf2
z#vO59tL<SojA{R`yP5oLY7nma;l2$ItA*XZ*Q8KEg?EwAz;e164C67s2MkI*C5;!*
zi-DF&IhPZS55*zt&NaI8Ho22oR$4}EkTJ%GZIH3Xx6jTd?&q~R;hX$OMoR72G2>5&
zNK;}@iD*BGe|LCGH^}>vYnb?xY-b7~LMN4WE+JDan`K9|Uu7PDKronCC4Yb@2&}nL
zk}DRi<TB0DHGeEv6*)!|xq+yEIQu7oWj6?3!}Q@W2&TgM{GD!JwHvu-U2a8yK{Jjk
z4xzd11kU0)8yr5{yBz@G0n@B4>KNt^m4@Ogeo!mLjVw2YB)mB=#~2v<NP0F-f1}G?
z0qL(fqBGTBa9kaxj<lHu0ZDHelr8t8_7OxLtl(<!5<$VbU81K$Iw69>e1Ks^qTU10
zY-1Ay${aYpJ%_^3SfUz?vp`dnxKME#PZZS|5vHX~)%SkR`*P5Z->Z6BHL+5bZG&6^
zXB_`2<Y!wOjrz+l-Mas7VuiB(DfD~!?69o(SO><s#sL#7Rbww?8i6SDEEcn75<NnH
z{Fb4Kj)cqid}TZzP?}$}J_P;-Ga!v6n!(#DTJ6-JOeWbuvn9IF2mA~xL>d|j(v9q@
z5Wyqp1EWZNr|!EfDk)VoX^DhimeD6h^XzR2utJS;oG#s&APzKh+)@d%YXLPk!bM;*
zOFvx0jqfpssa{jC#l!*EKYuP$Y54)e?<L6GBo6FxonbGGD!$+LzMgpWz9_wOwRKJ}
zEOkeS-@hKY!B9@2ql|SwtmqqR%=k5ys7I^Rx1!b@3zpGPCi(T(iVQHusDHAvA>Gke
z>@B=-#;HMrOhO{Ya;mKv>LO5+Xe^V^B27YM%k?YHrorVL>c4gGMabW`rBERX!@5}d
zgsuIg_1VcOZ^eoVm;_-2g?U3y97FQ5h#zqQUs2kC75lY{9y>;#%e7}}opO)oFWsI-
zLz%qaww5bIyLmy{aLVx0m&P{PZ?0D8!5FM)i*Q@S_@zQUAR7|PgIs?gZ8LYyW>&s&
zStl4NP3w%73&3bM+XmO4fG4Q1r?QD<F->`XgWfiVRAv(LMPFN?V<0yPGN~|PU|IDW
zl10s}_0{rcK5{6;clo)BT{}_cjXW<bMdizB_Z0V^P2_qIwWH{zWBjTsJ1#3`OyB!L
zu~<*>bj0Y-j(nc;Uqs#7S-N{w>ji{xU+^v`ecA8QwdsT~UuY_q689obePJ7~q8?A6
zs~d&1K&x+qXN_2V^G@4nS4UOptA1BClpi<Hu$A4uQ*F{?6<mKy<g*MDj?wq^H4RMh
z{X(1o2Nm}8YOPk$FnKK7m7csttmvq7>DJcXbiQAkoLq&lI;x!p7tq9rLDrX3F<yv-
z-k%69Q-#k??+Hg;N_0t)S%onBSfl*wL7MYm$9V-ihOsKFMZXlg<`(BJjx3=Q&UJNa
z;JFs<-h@^*nGST$q_Q*)C@FkR6e4a^Td5P64uk91gk>vz_Kh?6#&oy~!3W}vs##m;
z;@6i(i4{64UnvV8ECh1tA3j*5<w}%}Nw+I488dM#-TOC}Ps`TsioY49!^rl#ekyn>
znBi1}QahzeR_5-htBZ7h-oo3Y%5f#1vBr(QNcPLo<r$$lfjWh7JLL-mQ%Uv|2?uh3
z=!<ry2%2tXr9V*eY0|5&6lI`}1?6wMM1=MN@ns{8)SYlp?aFlU-RVv3rZ5P7+C4F*
z?cO96IChdRrcfwm8`mmm>m~Y1BjDNPHTv6!JG`?s%HUc>li}I9mO$KQM}9zZ$3L*3
zsFnN;RePLyp+<I}*UMn4ogBmL09E57Se<^IjKvR`a6=sjd#GEEHQNOW^iNdL;H7Vr
z@lIZC*-Oq%+lNCHu+c$&NejSDuJ>XY{!%Oo^*?Zklr4nf`@=@sj>wZ#X8SeqoMk|D
z4<o&!>wC&A4=i#K@hD@{D6rUREDX=711gzkf=&!A41cJy>^YAB0<+PR4$HPhIqRqw
z0^(BA7_ro;EP4Ynb*<F8!`k9li9LBW(#qLuQb|<}tG_79)u$__rLkjS(wg*&r6wBR
zrpO;lyPLMvEIby3gk`JD<@S<UaVkHLq&bqz*antFPb50ch*W~Cc2G$?vc5aCH1EfM
z)uGHwCrmWJW0$e&R?ME)1;0*TEq_I&ERI9~!>JhY+kQ3EHc<!hk#1+2u9nRrMP1P%
zxfb;>+9)A*kXF5{U<zZBH^g77$Y9Id(aa?QC55+#Mok$iu!t3)A+@>J<@c9>?KpET
z7c4TOKM)i)D2&l#J^FZ<Oy1lRs%q*KA7{X=kVDZ$joK=P7LsP0w*%Lvk3dN?(TFph
z&A~7!$t==<NRv*z3d74jVG-#aTrm3Ly_gda!+L;wC#ggtPFY~lO;1_M#zG$1c2@*}
zmxyXh;GEDC=XVxIDl9dW6yT?<1h3^|flWUz4^VA4_)Rb4eI-zGlK^{491^By4ncAZ
z8zub#0xB@1f?**P4WU3Pg9)2colV-fB~z?}xQ2_LRA(bvxXk8{U_lO4v7Zw2Q?%u5
zVJ`q76+c|GG&e`7QoY?Bl!sI%2O0;8(INm;K0^WpTgf(n52CUL)A(U7kQC7`iMa=|
zjcVk^PF2+i)LDPFpA>O&%xG>|UwEakrUyn*<Y!af7u-23YkEV<mV47c<=E2+s8anU
zEs9y=G<f{pR|}y4wq3F5Y5nfy(%c@X+RuZ{#IY>|J=w(WNrNGry!=18FyV(*=JZ5W
z&CjNRy0Nztp?P_$>Bz!|q;q3u{6*%UYNe4+;awez{<us6gN%$N-U;}tX_$tcyqAYG
zHky5;dD>BTZ-J?$GLQ_Z3@C)MOuj#|*I@x<vmB9(Ghud~0<d)&a}D)Q6{=PRIg8rL
zQ%=rqSTl9mwX}$~sCgpuDT9H2O64JnZ7~Sl*L7J@-A&4%8v)oh{B#gHvUSPBg^aYl
z_zYmsHc}aTz%h$j>NXG*tA#%(*hMM%1oV0-jAvZw<W)f%E;%4OY%L>)r)~5kQJ4el
ztW=15C^*f9SfN~NAE}ZA!U~}|82e0xbY3zaTAeLgqR$`2z2|4s&ayFfKNINKfo+@*
z3)FIf1%sXk{ruL(ukKJqVpcLnL>D(QMk&yTlrmUJu*LRjck4)ZS!;Bk%?y6HUusUh
z)d_kNe!W7dx=y`U(?5Hm`;AIFkcB^Q-^w{mfChyV?})bP-2cf&y`t8qa$vDDwtDAs
zV`9_HxzAmbZ2V&6mw$4fbH`nji=`0jF)E62g@P^@82nPsaqTY7GnoO9+3esT{LEcE
z=r*V5UIhT6mmJ3d0K`bR<~m-PBkKGb4_qvWU#=;ZYF*Rx^r2mO=WBouNvOq~m^9ML
z95~VOdH)7KUk$@*R!sV6TnGq-jJJ0xo04=0{~rB6T$q&*(O>~%I-ccnX>-nm;yM9i
zF_RxBc`rB!_yrWumnP|NSmB^yQkW0w@(o&r$OBeiH$;1G&C9@rOfo^M1-g?S%HcsC
zrfqCkF{z@1jT^rqE(FxnT1^-r?ay4;bBHv!;z3mRsIN3cFp*O3XbxeaWJB-n18&+D
zaYYUI5aHC3eWQRW*h^SebH!7ge;fHTNqxLu(MI<0udtZ<qB<{l)0BYpXeO5|>sOyC
z5rECqTGi6q2Xok%FM>I5lp28g(thcJ2Wh3UPI>aO5E_&KJop(WR(<FBQMt2+gUPS9
zI$9{<<`M+eU1221Nboa?*Y3N!O+6+*qYd?Ev_WRrg$7kx@Fz}OOZQ^|_&LfGC3>e!
zZ+U`&4I}P1a8Q&mkZ76H()id4*iJJ3r3EZ9hEGyFM)y(RHA{Iyyu%6VC(-Xh_(8nW
z8a28`yx012Mm>y1vPFu_#_>$1v4P7rnDNWti(h1&zXTMkjy^MRPtgbGk8Y8LF8%UK
z+cXU6;D*NgpWt0Krv_B-tTwr;#H4HAJyA0-4&)4L-CkLLj1<u%L(3;opVf4`gTck8
zSi@kEGOQ#O;e8gRX!qpm;hBDn6g;jGlM7KjP-?O0t}~i^Hl?vk>({b>G=`3l#^o+B
zdZd=YQw!Ew<W)nB<lL_bg5a1oLUqL@G>AO0h`@$lQ8jka<k=1Ss%ebcWQ{k7+_9+1
zgm%v+HHZK;E)g3b`?=6}s}fdEf-e(+?CSf{?AT?(mq2P1S}kjWtu670hYQ>xN|$IJ
z`jKmO>zz_&J%!f+H->f=N%R`R*`yIui_UNo=$GrS)=$-ijudtHib%8KeW?|pUMTf5
z@>g0-)96>6W7bEOs<2>f2rcI3(l6gu7K5~Qcy6(JG+;=$5a^Aj8JyK&@*7asgoLsN
z&S+~SKnHG(uQmzqsYgItHl*Kp-aAR=RMNLni!-r8YqQ!iK+Y)iuxkEAA%iJcli)6$
zDn0HkFCT&&1x;(!2!s~Pd_4n~_d1&&01M<!-17jP>w@3Iit*D0(8KDd)!NjECGbdL
zz6_V^LfgYi-)VJefU<jA;%^f?#a?coSdj)bU}uA}^%?`pc3K8Lq|;Tx$MJr&XR~5j
zzuxlD47|V@rJpXp!P2xm$de=cJ=um<$Msy)npXE#+y7j%?LyOUeQ-agl4N)yr`0N|
z2KwdQWi6`?-U{5YEiDP1u<176`DOc!STkTf1=e|jyU~eI?5431`q$?_$ugLiB8Ro`
zZWo%4dzm@W6(bbAbzs&uPNkYKjg2kJ@X%UoQdJ!zr2|WqB11CjmzvJ&;HQeU4IS(i
zL9!J#z4sLhLGaC;EI*b5tt1vSZO9Me>yxT~OmaHu<G8NXfFozxk(T3awyrF&=4#B=
zH$qQxy6fX?|BQzW?pS7a;6)8Igr3G%@&?Ufspf~lhs?#)3Q$|wKJ1s<CeoNh?>E3_
ztp-9kt?zM>UMO_l?DprU#?piZsWCRE3GH*)+4iR)sFKA4GsNd)NB2UsVGCB772tz5
zvRSweIP$V;Me0|Ep43EAy2Kb2BP^LDR;Qm{$OVJ-r&KYG1}Bh({Gi4>+)?)jC(_B3
zs@5+k4}gZCwMx57gW&C>L4=y*Ow$)29$X1D>W1yoYoG#j+M$U7k}@j5{hmm(SN*r$
zPZ88$^A2g0<)WRPd;EXd%#G^XQ?!CvR@FyH-ew~4;G}{ITv=aJLSNzt60dY)t+Bcs
z@LR7n;sVBZ4pd<Mt=H1J!4w)}rIEBtZHZCbxY*a4rH>+WR?*FlHbcuI=`SOJR*D=q
z?c;#Ego>DDLhU+`0c&2K=<CMAKGIhx$X#p&7n&^BgXGN<FJ`S3T-rDRJA-(FcG|AC
z0m|TZ{A;Yr>@$t<=#$OO4wzS>KW#=p?nQHKXdz)N(#zfQES(ZXlx-Fc=f0XPXcuyn
zLt^qJIi>@hN7gv$FsRz4&p0s=|6(2jvV+UeI*g~XwKX*G{CdLbU&oebdrFyI<FpId
zj_h%o18l=zt=qPAAGK^a`)#j7-EKln$|MVM$@UdYTuow8vgvfKVp2Bs+S_%{FY3yo
zm52srlmVX9(Vg%hiP)iV$DU`A!MCP7%Y2Hcf~t^nmlTk2dTf9pIX*w&s2x*B)Yz&J
zDU7T|g3&3eeCP_NLl)V4in_?4pW&1-&q<2<olRLGlfdKG5J>VR4uWM!cX$9=u5HvW
zZhueUs5x_Fln<5gP<?(Mj_%zQP9LTi$ggu7*MlK%r*6AKCTocj=+<tBpx`)^1(Wde
z5&B!fai0Bd3)5x6m5%T%^CVp&J(94TY*4DmgR$#9)nVIV*#UZJ2BWOogvqbCC~-ir
zuatAbtn56aLUV1{SM;wOQHG+<Xc4gfQ9nrJy!<NTrVcqRI?G>j1Vpm}G|_S=I*rOW
zRT*IK+f=T~g5AoOgD$<wQ&f(SdIp5L<Vv4lWr~k~ytcKrrR&<ct&o%Mr9cqG<3q8v
zU>~LM@}U=aY@CcM+MDTy(z{6?KcAkM$yaSscbLEw`kSC>VJxz%t42eYzAYL;a|VV-
z6%J;8q2;tdQ*fAJFkl{(!5iw0yDURAdyO($uSqQ{J8BiL%HOsS?74?GqD$1KKwnje
zFJ$z9pQvdeItqm|k~5*&j+m(Fj+a66?A#wgY#kco2%rm?bSFJZ+2zS!`|9|4ZqzU5
zNU{*TFrcAc{|;T2;_E1Kp2oUmzZ3JX(>>#1=UdlgD;169XV*GBiQr2|XghEoL$YSp
zmFFDIDm5-`+^QUg>G;ZQk>N0IaHW=C(y3fGF}N>0Zv6YSn{HdJ$Z0^2V=1JYqH{Y#
zWAOURmbGiSlFkfXKhH6*Q1tK|N|?A&odMeP&NuI_91e;yDK|QPlNc->>aCsXVoQWg
z*^ns|R)u;(M2=q8JaIbm0!wu6NO}{*Zb1-<RmVoCcEdy+>6lIEq^;cMSXQm^N36uP
z$5k$mDXYY(+<_fA;jG-}L`T<|%Zr)6sL3b-6zb4L<`q-?oQMM+Rb0K-^p8}*I(xRd
zZt7Nm-ouA|(-b##PwNj5Kr{T{fKn#p(H=^3m51w)Ub%}qI&87WH+<$;Tol6P8v^kP
z-8pQK^eKcEihy^cYi7+k+cA8vnU`|m2}Np|hpqueZvC?16iwvJ+*=ckJf>`;zsE?u
z!kMC+3yOk3q*B0Gx%BQ?1GcCyA2cb~Y@o&J?At4l3!_tUvHS>~m2H0pA5^L8Y7OA2
z$or~skD{&RUmhi!;k+PfZo@z8;$$%-@FR>w8saOZGgYhS7^)@+>%QP2Zu`TzEIdx!
zN^fy%`Vyy(v_XYhbTk$v7(06d{2>VfI_LZLG-CJ&?#d6Bm!6sltaj-QyyUUqN@dr}
zRKrp<w1IW;#KZL<r%>nt)Tzyy7Efu+Rx8-2n(-#<XN1FouUXJ9Ko)66d0%~bN;mMO
zS_ZxAj3^$#ng%>u1y>spHkIVp76m+EEY>*H<@~}I@DhqsgmPjNienlpjEs0oY)+Tk
z_#m7|SGV{eK63cAMjMCfPcZJj_p13(fPov8;Rrcjagrv14F}X#6x$n!e<}<3OPT!j
zY@<tcjv<VVfIlaCl1?a@gBBztCBW8`gIu2QvkXc}Y<sHj+>g3$+TyPXxxsu;;qT{2
zG=(R%;497vvq!9Ts!u;)own&qfkL#7C*@w;2`{T8eQ&qNpNzwnZYji=UOMcCK&uoJ
zeh6R;qBVLXV#EW@_d!aH`cb&J#(|!s4Mm2Z6;OdHpWZT>z_J&4#!HRjMV=$?TEX=s
zLD-s!h`Sq_D~s4WTXR*a0z6UFqsociDF!$|3izE;oBgByP@We?XZ~WuA}rSrG@%F+
zlfBYt1d*B9BVtq`ONE|ec@5G~BK8z_FQ1CP@^&0sh{<dk$jJNzu2TPK(HSzAUYD4Y
zpu5KpLGP{r^W;LGd|-MH>qVG>9YkBViXEb~Axh4L8uZx1<YZH#8m@NFYyQC!PTIEz
z7sg>NsxXYCkynNzm=kC9rKZ~U2#&$+XgWRzo2Z(jKi6p8gLD&%tT9>0m^0Y42?djF
z-m08$X#1lvKn*pZZbbqLM|=0-nY&jAu>wmlwEaLIGRUeD#u4cWDk_#inAPbjwvR;)
z+=4^<R+&D%uR-#Bn=iyEkCO-Gs28OsQ}J2VyHr{9Tc<KL{bYl-P6~=)HHZFj4ImM|
zfcSzoMHKsK`~=RT=anDx@b*0Sxkg;llL#bqG(_D3;n(x@#6AKLBE=Y|Jg>b&%hc=x
zr$r-Pca{?tEYlC9stLk$g4WS>0oGQ*u=*_H{21Jd083QEE)H`MfxPqpWmLL%4LU^y
z@$ZX06fh%GoZ=$C(j<*W(LOW}d%Yn9S~P}Q!eY9A9?pb+>T=-x+Hb{`1ji=S-uU@8
zU&2TCGv%h&iS9!FsM873<)}tmJn45D<!*^xD8?Z>JZ|ghy4t>eZofdy9xij9ebGsq
zRgKk#x$((5`zvmx(?AsH>@UGR7+^tTcCiE`!#)n8AL5J|YFF3IrfK$kJrbdJ2kfq>
zL>(L{LWJ&`kPhT$4eQ`L@|blQwk0@ocoDhuhIE)hguxjY21k-8QV?L0`-|~(sI$#3
z>rr0@mA_+nR(zxRSt42WpgzmiLm4VW$eSL(hMH5SV}X@gM9?j8J&)_06N6q60EhY|
z|2}BoJ_oZx4S+wJ#{(fo+8G#xZ60ZbhLA?9`pujv&|wt*IhcMa00o**{!~2`>Uib_
zggMORKz$u*W)hbQ0KAxbndFn-secjZ;<(a|;8X;SIMI-blsI1V4MjgL)44-bCXTI=
z3GR5D6FpFno3TnHA1V3_bJRVkU;j+oKnEX`Pex0*nV&L(OS$cf+Yg*8i>eNaX%9h=
zrl`KAAweHx%GHWEPw(EM6^atR9<6zA9LiE?_u~pMW_xeGs}+ve&4@3B+NbQ>xI9m<
z)Jm=;T#I}{pEOB4f4++@rPjj5M$({$g_E_=k%6_fv7mbcS|{&9WTR!azxFVG_B*O-
zWIi4Dm*(YUe9dcp44QlO(bqyzAnCdNLxkttqjfLJG#P!9hdb+OYe9^3uD}QojC9Y6
z>1^WQ#|{NX26v&cXZ0hg?FQ(C+!55)<#nY7idK58R#}CxXAEhMU}t|uFl51{6apz#
zi4-^x+3k{>QesvGLF@*EL7Af>$DyKeBZ0EcP#|{t{m9KNe8nm?AY34tAIly<btML;
z4I`-U4Gn>jB}aIrH!4686+e$a^v_&_n5}sxKXQnz@lez2ncslW49l=nfSLnm^1!U<
z)K8eK8ekJLV)QElVo`K}aHB@+)!uPgEX4~i73=RY6MJ2|^A2c$5RL>x?yT|DJcB<e
zcSdvS{=BG1BLawQfvA8xcuaiOpYF4DE@!*J%_dn~9RiLkiNV(OkAr+>;ms`ApZSZn
zkq|Kwoak^6HR=LE3)2s<Fu(AH7NQ~b@zS>mWwfSjZkk;ZHfrMWAHBwu5r{}3pvj1x
zP6v7<Kn<Df?ROT}@rg5x1oR-l57pJbB#B;Pi$Z8X38bzuZw${r;|OI@dJ!iR+C~w9
zro|4$WjpYz-e8uUBidUEayI6xlxbcA<&)YfMNK~1ITu_>P&R@-k`GNx^4TvruInJu
zdbJkbIZ@vqaAt?|Utg2~Kn7k_(U8e@Hgiu?xZ|m@!ZT4Tc!Di)nzA(2U6b{o<wp{l
zV=9R_#P9(qJW0|#%k!9k=-}bXpwSS03GwNNl-a^TSuXobSLTNm1(?bi!9qujDis9b
zZ#L!Te-Uak)^Dq^{&i%L&?7(trwk@A0@_+0<^q5QYe))))+Mj`zAEM#)*wHdQpWD?
zMrE9SXB$G5N;%m9NOC6ulC{{3*6EHz(E2uWr2#{dy5q6|0ZHkvg`P2}bL_YHfB|tt
z*BF#OtNEeG97=4n&7p*fJck1wfVMMr$-TE(nP`{;s8Bjo9%$=muGKswRP>B?G`J{h
z<#+hIVDrh9i4y$VzAa@m?Ez47m)I9TY!Oy*Vt{nopv8MLjS?odc!A%~3qY)BS?lgW
zT5+WoLBTAu(nwHNtBrRITYlR@bm5X*8OA2RNX>9m;ri0HeKuSZHzcEEwClRC=z2Qu
za4E8ab&R4A&nB>B<enQO1xuCZ9Hcu-E1NeEK~#_lC{7P6j!4<BisRJE=P%%%kQyvs
z&hQ>zYF$cS$iKK~s*AdG%V=~OQQ~goMZ)W!Cn;WvAB-nSUjjLqDiu9S&P~>`W>Nvx
ziGD=pjap0GBA9=%k+_Y*`EFxziy&>)cp<`<6ltx3+I%zQOA9CX-k{Xw>g(85xWyHh
z^oQ~v@S!Kn!eY8g+d?CZW4PKQy6elf2zj@w!Mx+t3TrLpMI)H6GsOHv+`0L=yV2@(
zdKFpo*v*49)T@Afdr>hq7fqtqRBqmP`mI2;^V2o#(ygV(T-{kKU+(cXm<C2U+t~_C
zTc=qxedlWP$A0)3VlhXz_V3ovo8z-{)#diR)>rZ}iI9<Qp3sPqYQ9vg$~6z>xTC@!
zNTP(x?k%^HdHX^-QM-Y{%9NL01%1rwUVhI_;$C53yjcHoh_~JIHmyj2cF0}Hysx%F
z=n7-~h|sEZdqA_fT*J<IjiDkX@qj;9T8Qc?R@KE?YB&^w7Q=nnEz$74;~r_)Xiag2
zK(Ez^>IRuYg9FpvcVgFmuGz(28T-OhJzV1=@lq2ZeH+Wdddc%V>|v*c(Ev|9i;F@T
z>XJcYvY`->NMo>JG^`4Fu;c=_awPnYZJJufP~=91V_czdNW~O+4H80MCG)&)betF@
z%dVR;0y_kYl9tv-mwCopbR*4Vi<4?N!qRL#dWaCC`oNmVT~=dz-3E~a)kN$pMnhz4
zafCoEdNHxWYEI+nTDcv)*KoFR?dn~w6`f(P<7A_iYADiez5J?b1Eg7CgD2Erj}J+}
z?%&Rq9c#;G+XHu{@%i_ds<|6AHCA=8)XeYaF+SbL<l8O2x5MPN#l%Y-*xcFfQi~gc
z@3;F+OUDT3BQLwZeQJN-KQ6_8|9CBb-<M6SI8-p3D2R5Nd425a`Z#Iovh1>yGuZn5
z@Uo=m^?Ph>iSFZSXzT4}tMhl;sa<E6>?O`&1uskU=W!m+*;77?$v!V@bid#Cxa6vS
zzejKBv5^xzX7XG<>e*%;cg~>6op;XsYERx53h}u{{Qbe#_4d&<IumKOa<WTtjWxNt
zYTNX?pg7at{0<f4)oXAD_5OKz#^?D}Z%l!YZhk7f{^-%`L;c*n=~3>*f?bz{4_@ui
zdvK<YJA!Wx?ECu|!}sf<t@n#D2aO8AGR%eh=E?2QRk6Zk_Cre)?yyOmUf0O}q2J@@
z)qNj#x$F+^LUViWC@vTKNy8(0SEQ51wme(s%)WJ{A9H%=YL(FsDrQ|5<ZjM~@e3n}
znxk`7W<R0lv^t}J?{}?90$!6Mlc&8>Di)rD)EWmt;R(#jgT8x%7x29zN6jB=^1UOU
znR$T?FL$WPB~SZk^M$Uqo6PSI5t!Y5?0)I+QTnkB-DNWG_ZZDY<mKfJn|c4XH^iR1
zti~()n}Y!K`txJeXxHDBh44Y-JC{m*5$pV@UPno9&O%nY<=jouBTD$jgU5iM(NaG4
z#Kb>ua~3Upz1;%Pb9t%Arr{B&B7|`2u6THsZ>ZH7>|Z8EvI%;p*zA(W*4kv!ywKwm
zI6Z?m7C8TolNgFW)P1b9uzo$(y(;wnfVCbzX{Tg6Y*Mye)=E<5eZ4w#&pn|E7;yEm
z72lGxejSaW{6g@-ji_|0vul2TxOulC@pRnyv2Rv?A5=F|h6+!hW-Z|Inkd7#PGAaJ
zv7ab|{hPovplF$DZFx%(8*|d@x3td<YzEi(E|uQ4S;P};lTsI@*`rp%?Sl0(ji<@n
z!%E1CJ^6E@OmPC=D60d#+)9z`iFXP-hQ}3bJMGicJjQUiQYYi;TLknp7~8c9$B%~Z
z>Mb+s9L6~372otG9(E}%--@s<14YNE(uK8n$Ae{1y@8?ey)Ixg@PexD{Iby?+d<GZ
zE}}^T)uG+So@(#9ybN72b=O3n;(yD_{3akgzldpdYk4t!sg8Sm=_wbuL0RB(sZG_p
z+I{hUO!fP@#qRmr@qXgY0DkIo!7YL8isa_+w0m*3l;`AF)Xoe$o0gJ~`_hVHN`B`I
zbf)qu%;isVUD%Z#zX{9WDF?8*Zb=g?q87VuI*s1^@W@g!ePmm3@+ry!;C6VvGJ2~|
z`8m1RX>3Vnmsrr!uVoVi@iJ}TG;i!}tRx@rCcTo0-{cFty6S!G9p9Juw0|JNi-}Xh
znAjRSIXjvd*!(Hk8Ct@y0O$dKz5@UN77jKB_J8?I|M0oF|1{BwxH*d{IU6{e0RCqD
z;Th0>RseKD0ssa8osq#O<>mb&{5Pc&wX=2pZ_=Mhxis_u)=#yH{|J4`{WA#0{}=<%
zDZAU706y;?GBW{?02ux<E^pvy@~MmA-@bG*CdL*9f_82Itxp#H=fF7t42<;j0G+?Y
zg+2{`$~ys=|I<Ot(ay#GzYXSZBY$!Kbou<EQ~EURXkhDP|Hqh-`@d`nfU~2E$-gzB
zPbp!OZx%)-ieiF)nE%XG(ZtEl#nH&b3Gl~niZK5*HMY<CAOHUGl(dPhnX@^7{XfGJ
zwXk+JaRktbT7P<0*u==r_%BQU2r>ZJm^oPg==x{L+%nG9J>5`68mmr}7I-#zc;<Lg
zp@~z8QQ`=ps{#XofD@2~v%&$uDC^Y%hQbN3P&Y^#x>5k&V6*8fY!ZNfEki95{^`lh
z7a>(w=*=-S3^aM?ueG|UY@~^v9w4-Bk50ckw%$9}SX6YXDmklOGL?kL35CCgL&bC#
zl%f>-JiRUQp%_*W3S;wGJp2T5r{+zLDG?PcAy54{n#bZXl_TsAv8jEWAv;L)y3kFJ
zzE^{0pp*M<Y*_OP&nr0Q=&+{h(D;nLk*aX{JHZ-7eDP%3t8pO%<{DeI&Rc)I1PV0A
zOmxh*2kiJ_*$l4C#8IZ|cl1Wkxoj_E554^=b(=>9LNCTx@gF7nB<(PzD&p3|Bi{ix
zi1R%dk`czZcIIcY<H3W$gX82>BQT^I5+o7KQ-RF~RC$69-oGc}9XWFgQgjp0C8ZqT
zPk~m57$j5Ne@XAnjh7JXDb}DaIf`g%22sb$K^g2mb0o-<@8JL$kOn;)1_i2!<()ys
ziM!MpxHWLm{YH{SxTiJe-i#17W;WfZ9>L@#?aBe&xP)Mfhw&uQ;3iA4`Gw$*fI>Gd
zwprMhR{l_(Dr6bLoVg}+_RiaHNPx_0139AjV=(4n+**sVPOXvdxv$PFsM~!_ldi_F
zfGSHGilk0`fRbg`s4tAoItfcLg_>2BN(K7-O&OGLMw+9?x~Q)_|2A07^A=xFb7HZ{
z17kgJt^QbaC3UDO7mil1bH@Dpw+Ymt39BSBHX@``+q6s(FWtELTq8?a5LS<ayQ7qK
z0aafAlqCD)H(D8H5$4b;GTe0TkBT8Z&&Q1=(XN!Csn4S`)@>cm$GXDoK>b=TQXw0y
zIbvp!pA&{13%WA&$T%&;;)E0&mxX#K8?qM8Rl2x<-#VKghVS9EvRQeS7%d=27<pDS
z@W&Dq>q1T9_7J{NRIJvzP<=GozWbH!93b+ArYrB~3wN*wv}BnYoe0$R85WVFjSWb@
zP-lu|7fr3!c1lGU!D=8o%&Fx1g$XIr>?~62eC<E4UGKM1mkn5^OU^w`o11m9@y#tK
zoq2YAs*vKdY=tW>8s*2eJy?`k`@;O0ct>QofnH8y*Jd03`s7fqQ#paO8k}ggpJzYA
ziyH4!m=dM+teWYwKnn{`=Bz`yPFSulY;_JdC(h~^k-Pf7DsI%yshgfh!-kG^3Lh;R
z1C`0;l6+w+<{dX8y(xQpqHFe(YB5t%(L4-QA2{nmTq!^^ENe%ag|mgT1yq$TPROZ1
zI%&kyiswFSa#OUDYAMrVLr9RBI0(=$$W0uQ5M$)aDUM?e=K}8%@{^k}Eh=fSmz*^$
zI(~?97Z<S%(bDL?W)eir&oe<qP^w^L)u?i4U1ZT~NP9`!6-%R(b}pG?EP_!j^%dMD
zzjH?8xXfAYSY@)Kvg5+?l;<>W!IDQ&9Hu4wTM>u3;XB2Iszqb{_q|}VMLq^1IxdMj
z9#JxR=33XRN?gUXAyHO4Uo!E%^}7KlPDGc|IltW3W)dpKI$w&1a3)HHYT_R!=#%r*
zD)|pmOQ<1vng}6`{7RT62sd1`8)Xs*EACpE7wsXzYU$q$L{O==a@9HVmV;R*Oz*75
zEgw-N--jA2)(%+)>(vkDI4xakE>_haa^k8I&FhZmtQ#4nJd<c<boJL(NKG;uMb||1
z47yCY67e+EZ>_r7)mV7Yz1E8dPmZT!As1vlx{rjMaxpG*@06YHrH#nfhagM)?qU@9
z2WLP^f$)XB(Q-NmOTk~rjnWvBX_;B);74^e3zcy$u`nW4zk<5tNRChr5R7J{g%2HP
z-R@Mgdu4SJW^v2SS#VNWwk+SUR-g$L7%0}K2#hH}R>+hD&>_X6GE(ow6-F8}<P-L1
zBe|x)C#Tcp2ih{5nkZ`heC{Ga_#)`S9tvt=et)8a6h>r8#865>LRo~ZSX{oQ(tu?B
zCeavY{NOUy(3)fwN-1;bW~Ox*0_|sD&08aGI!tv6Q{$|DQKk}2nHDj&dB~6+&1U+m
z5{hsLXL8xR(MNgyf&2&htS#!Vu@G3ZS8MxlTgbjIA>USRZgPdZ5$M8C4np4X%P%I9
zuvP1;jK3TrkFSQLBu2lAAk!V=+yqE=i|p^yS~ZA9dst-#pIn`MC4p?2G7C_%UE6e9
zk7m=vXO4KE^Rj!kza^(yyAfRjgeC6bV#LkHUX*(uq()XPEFyTlmo{zXUe5H*Rwn&e
zYwFS<nfOikW;s%DTD?|e05MyQWN{V8&d8G>=%q~K@^iaWjht_<Kx~!ZW}Z{+b=NDd
z?-0;O673no2U0K;`^rk+VXfQe{1xOP_wM6*Zny9Ha!4=w@Lj@ZRqy2Tlwhch94iX0
zA)GZ*I)ARfqSL~`@)uk}8XX15M~9cVQ+KeQGpwX=0*uzO_U=zU_Wk+3_)Q<}b);f*
zkK1D9(!_6-CER;)q!B*1%F+0*oG!T?rK0&q{MR$rGOv#|b?#{^9zU|X`Y^2TVj^ui
z0fU+F47_s>;1jMd{#sf_sn~>HDHH`yz-I)1^@2-^oPw{0OrlZsOE?Hp7vDZXDNt30
zP6^ZC2^v}8;wh5ge_8AQc8ye#hiJ5lHFIr{V3&9%qWM<fN)Ca*v2l|7(7AB2+APD+
zzl*iLNx@}!87>x9TWc%)c4IPM<$j}i;FlLD0{sh&pF<=gpDxb``#STeL4Kr^x1O!}
z=BCw!Zmng%g|}*oPe@a1YTTz|DpyERbmK64$sh@zJc~Rk?2-X5Q@tIhG}l=3l!QIV
zLyjan<ONH1q%c}S+P)+%FH%BU8Z+k@`p3AKqy^S((#z;7LG5y`enkT(jldkrF6s?`
zMqeR&J03*gidkOnHKQd#wiXfEmM&9Q$3aV^PGuF+WP-THbZ&5gq9$hA$<kZv)(U)N
zUijv~irRVk{lY8fJrHz`tHj*wovZ@ZCY)aJQGH;2{~f=FqNHW1YFRR;6nu2#bR4l&
zErKk4H@Gc5A%r0z!W*@&%!K%5_DA?#&~f<eQbEXERdJITRGNUdjoCa-rZ`H;6cyPP
zmY4B1^yKjjiX81v>=sWijg>x}7lJMKTfRX8&%C|8ev)#66`a-Aw;><$m8q9YDXFnB
zSa=yn7mr-)F~7Y%HYZ0IQA7eX=VEK^+Vh1#*53*Nte?rVCI%T8=P}foSCN$qlp1Fa
zPYs*%au)*3H5)+wyfp&9lLSP)ICxX<_zjgg{9#c=Hym2mr0a@ow`#U7%TX|9J}N`Q
z-?VR)mZq{g5X#ehXlX+c&B@XX=j^eK)+u7uZ%^gZ`gR!As5K7s877ItomjhjNPupv
zR1OkG5DLPM8wvA%Ka)N7UD$KMZOBA|TGLeCN+w8@ebtoQwTRMHl-ulMP;ZS!bdE^G
zPc)TsdQ!9ir*pNAVddgY_F^p2PTU2E{=znw^c3IC+?SP<Ta159a7vIq<iR9_vkXVd
zKomkwA16>bxH_IxsSe{KOQzbNlw78?Q$gsqOF*#~e0F`}Z-LRPE`O7HCiR;7P3lUK
z;nyk}J42jEszCL8*EY*Ks<{JD^;(L1r{!BxB%QFpn)Q<Ks4DbKuauXi#@a84yNeOq
z945*-V1X=#;lwFwkm%=4MXoP#I34yNj)-iIo1^bEX=N@ee9__J$Ez(aOzt>XQy=e(
zhbZV1sFlcr+Tk1AAne;C<PF2PK7Qj&F0J^r*JNd7a=C?VGfpn*Q5J*$1Jl@nJPTVN
z3CIWtSO?k(CS2uYK2+};eeqa3eY@sRPH$-77umHq?3di+F!C!$(6Xy<>cg`6FS2W~
zf@GP_L_*@g?h)gJR6oARaK%T}Gu;(@J$|2jjdZ9F<Q2&dHkq&XW|Q%^cD5R6Tp9<~
z5Ley{bvl%7lHTq)kdoiZ=+FwZn5hY+ZUSsh2%pIa+08~i<<%>))G#BVJzyEQbethV
zE|OIxs=a<I5PQvsax;3v11%zG|527<n;p`%MLyq%)C3$9)okz;7G!sSScNFg+Eqx%
z(xJD%|A*fWu_(;f;<V2M#XOp;HkYR1n%MYXJs}@fuAz?u3(&<ydmT*o6G|c9F1V^c
z0ja~G_UFCvIq+<SLnkC@?#_dJJO3V|jXKIvp9Y7ejAN$5V&`=NsJEJf)DG5cw32*-
z;o@v-*uug7K><%bh+tyJvT=+Gc+usyq}Xa<X_>sVu1sjh_K6(2Dbt(WHElty_NAvq
zEo2|;mctG6H-^1ky&20ctR5NcQS7n7YlqRfGYeiWTla`wsBnWC>Zn(<*p(Zl8m3*-
z=j52#6p|XLount%_zeg2GP+RFw7K}Z*7T1$Ow`nA#^dt?WVat9Sx<GzQa%pfF6Q8$
z)k<Bbg&1}Qvv@oYrW?GAY_U0u4ZFLUHtH%rJ`TBxhr+vr-!wT+T8MUxl*GT2lSq<^
zmc|F>?^pAA6k~l$a#26k!*l*7|IPrd@LgOo0ygjYt6lO}UXc8zu5yOGimxv9x@93A
zszay7?G}r~;z37`wp={K9q^qb&E787;TUnXd4*+YYfV+%(hJDxV(m_g8%+n-a^x6G
zd}uT~*mxqlqSnEkA$lIy!?758oYWKLGRNed$a;M0<eeX5W;<iU;0PTqU`>8M1v^zm
zo+L@JjP=Qv@mnMl`=E9DvKpYvm0XP*U5lJ=UKQVL(d-i48l1@nOjc#5A68j~nrv8R
zYyI93Nc|h*B?QQf!ubp<NAMJ<&xJR#d|~2LD^^;ZCen1c1|~_YBu=yG!WzPt&XL&c
zHc{EigMaF@8o$4gNG(Z{Q6|$>t!uZoJ8I{c&fr{j{T|Fq;}417KdjQ_(fb}Jo6%rA
zLOosp|I2sz_b5Abyyy-WaMcmNwlSeaq0x~rXYxl}WxT8;1_&N#svobPT0Ccc<Ld9^
z7<zAC^j}Z@TDuDDS+BcKa(t+d&HPly=&kTdPpX_hj`3a)qQ-vjNOi~M2Z^8%h!(;b
zu?w#L4)5URTl}eIw>yN7#_?V{ghrA1dm6(<Oy{dD^}YCppKHu-pN}CSCvlpdy6{a~
z#1%nTgL1GoGkrPrGQzQ8rDdmxMZ$6Cfli%0PL6P<<ao~IJ}5lV+M48;TWumXbNrQP
zt35@!i2*HEgRd*!AArhDvg<r%!zYaIe}+yJtXzE|7;-h33_^*6^mZjGEyNg+cEs%T
zwPqi^FrjrsJ~2RS@o%Ho?utr?r(`6sxSq8z&Slo~0P>W*_E7v`fgQD!pO__bf-qOO
zhwF}?!W?Lwe;8B6d4s0`<31}07GhlrcFY%KwXpk`XiWO`4R;|lhSP{ZG1`*{mtr@U
ziVs6#={jM8%)LNT^s$n7m$vcq7CobS1zow`J?b}H)9w&wEGg5r6(q$?QebkT{pN3l
z?~&SqhlH2k((I~eCk#ZK5ug3hC=hp7$*iO7r`~5lhZUeX!rY^*iR8SG8Oent&u82e
ztKf{Vo_H#AsQD|QQz1BvVHOYKy$gb!gJ2Y+s6?I;J+CjX#%Rt^_F6J{sl3Hbe(A=2
z-eJL#z=AKm28yq2JjtI|Al3ad$zLeETqyq*^b(cW<@`o&!nYKxY^21}NH?dk!9|(Z
zqr%_vqAEBiKMg#d@42)`uJs!hFD0M+2IJADRyhJ?E5_^Kp3#D>0owy&D;uM!o#sTq
z6ON`bUJ5fu^{jU4x>@0~cy=YRzwd0|sth#70Nwg~C&`bfQ21;fzMF&d#|gwVv1XWg
z*nZw?8$Dr3ld@2;ZX`B7bL?}<=7rynWDqp<!mYw#?p!xN>chN3FKtqijWVnA_h`qx
zR|*$NF+~xa5Lbq<N8sGSQb#)W=uf4Kt`Q~Rb(7`lBpo$JN$hr;9yGP+)%0nH+D{gB
z9}Tmjo{fm%Eb3>Jv1gL7@`%OGM?)=cn213%BtdHx1D`#?>b=H?(@~}ZQBEh}p%U|B
zsx||g8Pbd1vpoabFo(Zpju;Dz!RZgfHZrHkg$=TmC!z;w`XEj31$BY{dZljG0N!fZ
z)&gb&ds9Q|bm-Be+V()|)OAPvt=ZiG^Hc_coxV*cb5-a|_tL!peAVJRRl7a9&+sM*
zu08l8d8oTkj_Ik8^obdi7x}8jH(cY&jLu6L7z51f$nUo{&|!4957ZM-u}?M7Bn#ZZ
zAv%AbKKpAi`*+pu?49jskWGxMEMGpTk}6*&7wESL-&Qa;Hdt9$_LlJ-vUhtT>?l}v
z((Ol(P4ufI-z{i2rEWWLTr_*(ZUb0^M2KfX;0DO(D@|ZXMAVxAvF&Z5Z`*7F-*f2a
zVIT$1*aVj8wj*Imkgr;OErGkxtE(_|oqEbW1Kt)4m)nN=9w7{(A$0}v^ep^0Ky=Zo
zrMhJim7$lf<H9e8{gbt?3>g9)B%47RVV4^hMw+0PPXcMujh>PWm$fZ!CK%)`dSS7-
z>GYL?df1>#==HyTude}N{porQZ&AGoewwC#p7zzN!k1+~$ZG;wy)HD74`XjXNFLvC
z3jCJ_aJibxZaMhR69}r<iNr_#6`0IqcY`2=u^J<HhJ?HV$$;u{e?4gR*8UwSaOxWU
z8eb6*bQq|H562#m4=G?+^lqjBdcLWlL&#qiz_(!IE<Lzp<BQuAz;$W*rYPJiU`%QH
zt-cl@A2Qu25?9T>6pKK-CUD%O`ZpkMs5m4b_{j3q`f<J?;L>NHA~N(n&_N*hU+8uD
z1v&>|(*Sw_koiVW0UGqO-RkS^XF$WZJ(!j^4ClXq=_2sa2gG183;W(dL_fy&zJkAv
z2O@(6?+)7o_XVeUsiVS0vOUS81Y^>xcYCAJmw;TL(aWEVLbCSwezl*nhk`z$+rDVy
zezT=pUznP>yy5Tagt)}8bP>`6eSsQAn{G=^ezf)1<&oJOgXM8@-kb}>#q%KMZv@uZ
zaLFRcX+ucG;+$dz2!+_{sBBIIR#G~T_)li~w>vR7OFmx73Wz`QYg)z>Z-ABx9AVD8
zi?M;Zh$F{P=LF!y#Y_<+f`t**K!1q|3N#F5>yG|%2ODbTzYL5N5QzzV9-fOQS(fQ*
z{zlFT;RVtTk_YBy?=R*X)UFBItqpWxXb(-FF|&@e-M=zvJ`HY8S^|R0K0(NT?XL|7
z2Z^QWi&%{Tme(~>SjjH~05PYb(S4vkfAjf8_<IfPZH(-r3pgP<?XRfy|BP$@39|kh
z*Jh??{5R6f@xQ~d41Yq%f5oKf{;zoKe-FRv#Esbo&?AXFeuQZhg@=ZKN{|F97vi9M
zm(&vgJ;V^98DZ6KUvlmKP%MQ_>3iBNj}6&d=Vr6jCUi%vvv3G9aAw_R)C&+ex@P1|
z+}9VY+w9y~lg?CwPF=InaIjpbFE8`|OmRtOv99*4b&5uW0g7wVXNb4}X{&Ogs(3hg
zN0dEM6<5&-81UQC<@~)W10}(Hi6eEm+j>6oQ2eycEr{R6gf%jbj<JOWm)Vw6Hd`NT
ziD?-$`N1`YXm|{Hy8*7UpHyHWDWbv|E*<nj?!EV&@ZFySO;+P;1``3nS0zGT=<LvN
zA!Ew<slsd~se@Q1sb6u=^uk4g-ZRMxRU%a!N_Qgjk9n7=pZpHd_F%IlEas^k5;3Q!
zB(I5Q&Gxho&4c1z47WClPRY$@Z?OYxkP5O7Ob5F5*qLANTi11FYF^)gGl+{2|18P>
zT(iGc;-5uhVq*Ds%^3a!{{M}k{~fvigDnV~I2k!w*gM-f{t3kY1vkhV*nDCKGSZqV
z8X{D}CYA=OE=r#v{r|L!8rWD^y93DoZUX#iqxieg+Q95HcF*`9Nx{F-1sVo=MtT4Z
zGb<y2fsKRd6J=mx{0C)_a5k{EFcPpevo-<H|J6^x$><ME!NJJ>SM|^M{?ut0Kd16%
zghB@P;wBbm=ATH$r<%W5O3o%WssQ%C`~Rtk|6BPp!_Vz#!U*_-ApCbk;SYrJzrFFd
zIu}Fdzu*()Pt4+vr~cv!8aSE!1;+gUJY(VL<Sb-v;P|ftqz(S5Gcf)Q!2C~l1O8f&
zzkgyxY(GH@3tKY)otlNMfUT3ozl^^ut63O3n>&4?G)xSCX7PVNOsw?(w6ij?0{(xm
zPw42g_5arJhs(nD2g&;TVP*NZ%*Os-c3D5S7aP-`z4U)StW1CKqE9;v|Mvb{j*;!Z
zbkGBsKPS)fxhMXN=MUEN2YveFe7^nypFTk(I~7}tKS&PX&wI^(U%3ChjsKurfA3By
z3*$e2`U8ahzp~6_H(?lvqWgS>H>g3C(y@sL!<L7{3PiuaN=e8jMy`>nemye|k2rXj
ztBD-Xz2hv-@rkjn47~;{Ne(&L!MmSpMf51IZ0ntnh13NdF+YcJS$+|aBen7Na&D{N
z!ue*}M}0-~FSM>(GtA4^O9e`SQHFvpL4Sh!0GJLpeUZQioLgDSzH6ez@d$S`_o7~Z
z{#0imWSPNp39@CTMJ;*_(J1N=FVWpK0(m8EH_{9nlW6q7CMB9)7`{Ie4RL1ZN04eD
zX_`lxM*UW&(U4>5y9kT%w;)Om_o&Xi*Uf?F=1~{CrRnyO3x2o%C+-zr5=ZCAbnbaS
bV7sm+Z(}Zc5@>yh-NiXznN22}{WiM+_yxK2

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error-dirty_hack.pdf
deleted file mode 100644
index cfa0646aa7a315504cbd4f24d74b949788b8922b..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 79390
zcmV)RK(oIkP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz00oVOp+wF=Tn^JXi+(g2oGMi
z0|*TW&|-ROCukvzFar$Ew`gf0>FvdEH!}}rCwZ#>Mxm-sSkgbnjdAgddHGte|NO07
z|5NI^e*M?a@-NH!tM>IgzJCAzfBvVh|M-8bU;q98Udq@1bN%;!x&He<mjCU4zaCh>
z{?DbXU;pdZzkC({$@t&v=gfW`Yx(MZ{nf7j|9n~dbzDD2;QQ;peEsL;QLMFJ?RxqW
ztG`Y=1%%jBP5-a|{`H^!z8ulG<Ez$R)z+={OMLrfweLsy`uk`3kN@p&>)*yp|Nh^W
z|M0i+tN%}b{~yc${P(vGc&upIe)Xw!UVLwxo#(I3juayBgV<4j?bEAJ{y}K#zm8rf
zDF8o++2Ose?kDhX>;CiCu{UeiTYLF+?hoDn*E`=@{Z-bvbpU>7UFpBdc}`*g-o>uz
zcc01xeh@nfr!vF<{2;bjOsp7yDE`IS-?sf%f0+I2zi0M0+wW7Ezz=O}>uoBd{DV+w
z_o+<aU96rPr*eo9_(ANr7Pnq<00{h>hTv*fEqghxw;t`+`sXj;YyIm3P`7rU$^?FB
zoo)B2OyCEx>x;fkWdc8ll{&AHQG6FEXXnI<?kDhX{Q~-7?V4KU`c${4?*I3E0cAgK
zQyJwSTDO(^R3`9)*!BOnsZ8Jpv3hVSLkz$VVx@3uVF&>H#V?=~`&IwE2z~uK_JGsw
zGa2Rgw(a|U9;5s&w5{_j_R<ggO#5x0Z~wsBSU1ckEIV6Hr+@RTzrN1>VbcG*4n606
z_MZR1+?~#W1j^e&b$t+{uTo6FwZs2g*MWZ3)B3eveD!M^wWou~U+R+Ud+$><QG9LN
zwUo81!%|4Vt5~_#&GFAEm&m)|H4n!3J_!nW7qlLS?-UgB7lxtObqd_B)!=*|hrcii
zWvjnUvqavTxSzjGv_#$o&+RtwEWZlX>&S8+`b6FZuXXf3_KEz3k*L=i(as;gh`+Wo
z*6R#-pKgh~H*&jQ5kFsvybB(Few^e8yo;UJVRgNYhLBgmR_r$REdPa(Xl4Di9j%}C
zHWGj7h}c^BZL%fu-n{Fwcb{yDybE5J%lpVD@-BE?iS8qx$h+Wq+(%x(Um1(@dRH7)
zUdQ6EZJpO0^FG-Ud2Qmj)7otjPUKzCP8XQBULx;;+vc4&2?}`^JlZVerN1x^cCEnW
z=WpUK9U9N`w~3a>Ytx2e=Qhy<yo<H=+o&h<E_eytM?H~u!RxMnAN553%F(G`yW#fZ
zH}TibPS-K@w~3a>4^#Vo4!xf-zrTL};eVvb-rT>9hL3wrw6h-9mlm!6y~+RIXz#R)
z*I(;VkFlX%N5E7y{)hip{ZiI`9QAtZcAXX0@%rnty88Cd6ZQId>NttS4a`d$x@2hn
z{BE#QmzRj)A~TR{S}zX8We?DW#E}EY_1A^mN(Hw{N5-AxLasTx{07wyU|co!)qng3
zWOYX~>UO&5_t!E*rdN$q*FZvpmk4gu4qX2<fNZ4KYe3n^Yw}#k?r*pw+3Y^b)8E^8
z7aM4P@uEf~kv{cHb7f1c;6O&-UC7lf%Z%96G0ksy<`oL0b_cSn9H3^)d#ZR(wO{On
zV$k#G)q&LPr{euor+&J+XK_gVbd^f>k(by%1-hga7gk5SG5$R*ghp$w1%kbj2zw=7
zQ2U`ih-=(Hde;y6u=Yc}P-4XTuK8VJ2ri_kMm_|68!zP#d5>R^sYc%87gAIs@6O)U
zHzm5S_vj-)UL#Zg6z{izu#eXG;(Ajb#TPIT_0byL)~otxMITl5(TYB*{Ge8JQH;U@
z$SYJdb5?XwQKt=s#I>NQ%T{#I`inn%Ref=wsK(ws#t(BKWByrwmhtdFit0Q5x{mqB
zB;~zxArRYRQVaxQ`w2zkj#;|L>OFvV#;12dW97hYApq|i+c*%ooVmWT^M}1BY-8za
zqfuKp0Plti!RI^>e=(J31MyZH$7CEpuJ<his;sR~38*{*iAFa`9cXl;(1A8%Ee7OW
zUOAGXFdP5|@&clX)CmqGnpk`&7YDqEf!q%?a^;Zh2Zk1-f0ez7>m*XfidWk?$#{#J
zMt?uN#39_HIgJbQ0LDw&kwfUiI}i?G7zAqDQ^*_BsB;^Lf7}h@zBuG#)N<hC5Hk=C
z{2rfj+gKU{)Ot!RUgYB&YTsG%pEFIAc-25SQMUN%nk^_s#oHtj6>pPB)LS3?g^Z4G
z@x3pB_$SrsBo!U6jdzc&W+0qgvDXh|Os>Td?`mzldq;iONvJ_hpU*UC@?-uj1M+^X
zC#P+XuB=B&d5JUDp#0Z@eIfh!?CLIw=+}Xyly_g<Cn@i~x=m8CM%8T+i`s3ISX57^
zpWVDf3EC#ST?-&@f=QyGdNxT#^|Tl74V@R8@dC(uuT5f6y*7#YVAiUa;c!;tn_mJ7
zgGzq&I1$w{iA9aH=<hg))L8WKLq6f^I*CP%)=4ZnOeZp&@M<}=#q8MO%PBEz-sPOc
zyhbG_2KME0WYe(cmV?s?TW;AWDet0^lLLF_g;XqY*eFX*4(y9%)AYtBST?>2dtT8=
zZ66!j;z$a4Z<O2+)~lq=V8gytv@&eig^Foo-{OdKK`2Epv`Hj7K}YRzuJzitD7hJI
z!~EP1S;qKy><UHawF`(h>ddwscx#-5mVn~5WfF_m!oqq1Ucl13?P%=EMLy2WSC6eH
zB|;}Q0Bj2z7VP!pZh|XjU3Dhd;-t0=2tVWhOo1(4yy}RzVf|e-DK;#)>#h%Z!}_{v
zR&22@3?#*TcCDNh!{uT0?i#aV321chs#$@P{6H`(E+iVs--rh0tmxQ4SDgvBm_!3%
z_rs{OHjNq<#<gh-hVpQf3$9q3p^-e$Z*iL)07t;Q#LjH!OsyST<0uyNe)E^;w750A
zL%RnI#{*%XG%w*kv&DLLJ)<urmaHQ8m4S3GvqNG&^PM$%%#E>xyu_X;c!f@lu=<p9
z*SsqJ3ZH=sfaVrsT@AK47Y&U(yJLkBIVZ^qJM*UYMZ1Tgne7XOOPZbsQo943B=Ox`
z$SCzQ&Uxk3#i9FGGyt@*$ND-Dw6UM)q{cRO96twyANGGnKaSg!3sjC>KhRCORrCXO
zuUfPEfsWz>QFE;)J=W)eu&z4>xTvmsT-(a2lV;yheVjCLMH^+-Hykd?p;Jg)+8m)?
zp~tE|AoT5pjCx#1l&-%tQ+n+E17Xd2+~CWhsS-E33(;cH4Px3tdVG!p;cG3X)&-$B
zhWzOG7Q5j`JHN#atNPJ70egJy<?z=nfV}e$UMPCp-!H&R6~Cc%qT}N_v`+NOis|Yf
zcg6ypOaM_kT`xMmse{+cj!)|FGr$7KCkrm;f%p&SR4Dl2oC+&`IA+2UP>dm`!io`G
z`R-NbwQtu(hYJOrNCx8bq3pVJ7`~2OJB!7xQ+6Fl%{R+(T><dr+SqeOnH#KO?#s|`
zxS1B*8wL_vQQ5U@z?rGU$$tUlUA1ezSe$1sBudv`x`G(y`L4-g_^AP5w%{sTb}5Q%
zL)~;CwGQtR?KRe;aV7P8)=@VtB<9+v0rV*P-!T?)V5yo17N_BYvuGeuH>r}$P&e&9
z@_Z?}<-*gU?7F^ONYqVACTr+7omH$|C9Nw~{Z28Ej&k=>Widu{Maicpj%owJyvNyW
z3CO4CrUR`-ZOWztE$-9<;VfO@qI2k&WpNT65a$lIicQCv7TaV=tz(O=V9Q%>8~?6}
z)DAcY`9x|vN*$%Bx;7TvgUi;m6SfU?*G|zeZ8q%`Exzc|wUjorIMi?PLuhi>2ZbwT
z>C&p!6Ua6pUZd_Vu!{o)kHnZ&w6Jd|`3PRiH2>Aduxod%d+7EGR`P(ZKJ3O>QvJd(
zfX)ZJggy`VnE~){RpZWHI#sNOo8>?-S!)~t27*qiaReAhfu6W_^rZT>cJ!n^A6z&~
z*TJnCx~=luQSphPGT2_O^)~jK+R$gZ1>*8K5cX5^OU^(rAM5ogr7EyuFX=kk)rwxw
zO#nC1657FNVS$&KPJ9)6hv_q`_<}B^qwHgDCoggpCoMZQhH-5xsX(l8uChb*TfKz3
zl@n{7>HbjSvo5A7TCgpcrYNqd1L-Jx-`lP;(FH~IrE)Bog{EDg;7hcPOG5EUXmLIn
zGreFBFexbt&OD)&EF1cbr-*{HjY(@!wwR&=!sNYfsPW>?VJ#g!r>z3_)`4`CeW)$(
zs>SdwZ4?D-xak{!D{YaB+CY3r8r4k&UV!Eo*n%l#I(n3f*XRsdDqf?_qZEA5sqHKU
zO$rel)J+>l!CGrNis1G-5H47_zFyEMt)~x<Ci{9~bTrvl&J3MV*8|5#TT%3Rk;>5(
z^P<VPvARZc0Q^;)d|PZcYs{e1G|h2G9SDEJm&O5LeONay#d^8+(5sfFZDozQFc1vX
zihaCcman0}8fDCy6&rNhv_Y@2)|J$+t~j7JU6I!2B}~Q@1CC855Y%o%F>2P;+=80v
zmhHFEQD$qg(X_O^;QCpbrg&UI2M|?lxPcC&qwG_paoJxQuAl>o+72Yf&%6{T#>SJ<
z0DL`>a(5tcTWt;1Z6{8M()SJ|ekQtll%w;h|83`nCdP3lkZ2)4lz~Lw^Fz51FV$!t
zHlIdiPz#5_QMZC#8c?(k8%H}Wn#g@)0MW#vw_qJ`opRI-yG<*4Rr40EdJm3mblGnw
z^a73g#$`Y;&sV*vV8~YW6b@rjO<#zY*e5I2{CcYU*BDePst4e0uDmU@BhFZr(JBM*
z#UhR#3m|WG<q@wPha9Cl%HC7;z=Rrzf7%rr&~ibT3^jhjCqm_SI?CQnmAg^HEwo4@
zK9INzRNhJkRO5G|g-4eVTiDTWo0=HsrGco4*cIxgCgPr3H#E^C#3q`T3ToT19@dRB
z;b`dot~WRIKR@{fyMC!%FXk#yJKkI+#5b21w62%qkXpOmjblYMURGMT_zi^b#u>bt
z-n~l7U%lhPS*eX#21KFCXJVwOpJ_X1M`OF){8lP=&qiC?fH2xSX9q0>0|_C_=AAP{
ziwQ2CC2R=`pb$bozz3vM9y%NBLXO~Pa7d`(KQZPiOgyDl)y6QfwB*1(<H*WqD8)&?
zGlC%6jgx5ADipU%2k;wEY*eZiT9`E!hgg|PDb}S(ighV^6&CbxKp6nGjs_z_sjCJG
zC(XL5KCzk9l>@b%5`uwlK$OB*Z6~ELWpQCF71z-LP$s6$GN2Ihe}{6dXt~>B9dIP-
zw#8khP(ji*Y}iFcnFgJBDOwew03Qe|*Yz$`E@s413KjMPf|Qpq8)VpN@KJFDwZm*E
z2em2<dgoGjo*4+mI?5En&{B<D5IeUx)E&U*zf}q06Qp9e94L+Fch$Av^DDb5i%Un*
z^6T*$UdB&`CA^e4Hno0A0=Db{`Pxu+&ccqZqtJ%g`XMpYm73SGYhqH@TC`^OI6D?z
zG6vvFUO~La0DPIm)nW8g-zbDOP(zBK(@~}jdb@`z$`LeyM+X|sF2oC%81Q)+2-Y0j
zrY|H)*I%7o-?>c`Z2{DDmd=(id`No&oL@@e?PnlEXmQAaA|W=VNC@*BO3KpN5Pbhd
zhTj3jeC!&Y6_d+F?8L;P`LFp!c9bzNp>13OiWb@-p=e>K8)YzTxTZQ1Z#CQ@hokrc
zAZCg2JGLE@gqu?{j5i$;nsK}hm$HGxh|_A_j3ci73m3|PU_{M-)&DY%AN^XI;bfrb
z%4Q8?q0=(;d!?}l8pluPXGM)QbpnT7d!k{TFWMEYaH(qQhJq2(Mrlwz7w9sZ@ndeB
z#*Lq|%xbOibJlL!_&GN(9q3){t?*)TB)XzOrR-2trosMEV6AHnm;F-N6%FV6q7#3E
zDRMyQ3*3?lq9aGyXE#+xt#Of_k&gOt&1zhwX-RI4i?sIj*3etLgtu1FTUB2Ue9Rp}
zD{#RpjInNU*C;YlH)<DwECHbp{ecy;lb$XEiSC;aFJTPo$r(!H=76F*6FC&2h*7D~
z_1uu5aT`dC6AtS|7WEd&#alT#N{5%aDK--RqKyj0LY2ip3f@hmM@Q+zL**fmC7|f2
zu-LY0>MEAmQ5gQpuW&|O>r;x3Qnjih5~)!c%n%&J?noFQiw<Bo*i1+{*{JvksY{yx
z#*BJLQMaQoQjdLEX9;R*5;!zQJS{-&lJ!`3^(CsmZtA*3ST~;h*RI|}$H4YK_2+7;
zU?S+es9)m=Edll=hI(yk6Ooz|FXqQuIq|So!L~omJStOeh$de2=UQ^&q0`s=;9}OV
z`Mu%8Sl6jksZ7zwH4sfILeux=eK!#HRD8w*K~E8g1KScy!6<U^iq)f1c`_lJ)~;A`
zsz=#jQCa}p7qfcyc`*aRwalm00JxO3uw7QDOSEoQnC!8*0^xRGXc7#)L>7m*9mK0@
z?gnT=&E3G_hk4kc;h>(F3ffibxoY+2Agt;@4#KJqM4umVzFA_68%6DtQ5mW}v~yM}
zKMJi#_2BWfK}}Q-e1qJP2hgyQqq7d4U%9o{gI{G>BbNcRKA#6JWI8X@qwAD`j-slA
z=Z*{Du_Wqcl0YXN(`g13<7viF+Sd7SG!QqY=m1p_H<5>|3iCP-Vh$9Xy4WLyJ#Xrg
zqGMqQtvVF4#j8$*Z1Jj7VW<x)l^8mYR_ZWxXs!DxDNKa$GLBPk-QlmB$Kty4s6!=8
z-QoPf<8|G6(BT36LcVZ7kDBq|6KD9kZxX=x?%P*h14j4?pO4WD=hXQ&F``#^55V~C
zT$4AHYTREid^?AC(-N_Bj5oHVQ3!)YErl*lb>|3gXbVn8dHbqVQt*c62!+rf9$hz$
z%*tu8X=r#eWef6Viow}<OX0P1ARz-IPu)%lp#@vsOgqZFm!bjNAsJtG7LSpk5C&k|
zC58dmcu|QGE-8m9yTMIG7y1D~f*rnfO0l*)5FMy(mk9R65hVi|ERvf^hLz<CeW<c6
zgiaJ1^(k2GHmESED?t=ZYEu|RlNuKW(LgH`bu0K-sJroK8Y+BHxgs%E4x6*9h&;9?
zG^MNhk_v99nLM;6Bv`#p1viyd1M$N*Ra)O3T0=4P9qj+985;=Sg^3Ac{{kHwpa#Vp
zI*@t_sp={`0#cn<p{H0<<yWbykY2D-RUzFWV{}rzh!~ymL(#055!6pccn-Ci_zlbm
z={ZMu4um*(F!M`c>PRS#tLjoI#j4<b1l{ZsP)KR#?9gm$pQNXi)WEeD3H5Lb@faQ`
zoH<&n#ITMah$ofO4C0aEdU2?yYP(vhw$T^VWI#b)Ly;i`dNufjq?WzXOR8#XF&yNi
zt*>;6l16`o>m0NKVB*>)v5s=>ljWe&=SkKDkLp=vfmi_1j=`6w?Sn5*+XvsB){h=N
zWs|X_QoVuOULaxn(5h{;eQ1@oN{iLb4#(0V`%a~wl8itjh-dGUooE0t);paCJ<w;R
zsfj^8vPB`tC#_YC@}WJ;LwsE4CzIEJqW86SHr%~rI~zefF#t5L)rQqrCb-(5<ksTY
zc62{2c@?JWfyAyzjY&OekG`PEHs~=vZZoC*a3Eo+q>*t1_Ut{)kTs0T%Veq?P}t+O
zd^PyvAc)3+K3PO7)hA&!jjGXlUic>3&b2Hx+Rk-xf&G^@+$92lV8rFS;2bSGaD{x>
ziXDi_A#3sg&`O=)8zzU0(jF1y)zKo;R+y<d`nV{xJUYV;8}{)^?=IQTE0r!XvR{Zy
z@FNr`=Dw`-wbF%xhWttgucn2f;&364fEp^7WpWzu@Sr|B7BD&}91ljx{R1{t74BQ%
zys!X@-lum%#X^)G5S0p;wyDA}p~ok_1QJsUhbk<{>5jqBpmf<7F+NcpxOLRZg+gv0
z728vKhInMqI(v^W>L(peJm@DpF!Zrix=-lXQ6tDR99u>y+?(k6QlZANRp)s5R_Xj8
z-zuFJ3U&@-DV%tUe)YgnUVb~Z9Ft#9#X&Xvenu%?pgTK`%y1rB0KrvAKN3SPC!`C2
zgOUgQxYG}G#FZD7V)`s_{YkH<iYrulMh%26SD3VM>097p6^I<LDsI5(qE&IVPB*TK
zJ3L&y7C`YD-Ibu5kk8l!z@4myGAF&wYT>eAy1*1%Hs!T8Vtm5sNtY4o-{k$~kwLyw
z*sjKL#$d{?IA_SuuEO7no_M1SZ$93@R_Kf5(l?M89!>ZaCsKI@GFk|pgYiQ+ebBvd
z0Na}Whoju!ZOGc;fGRJ>Wkd$KS15yFJ$PtxhD7L4`b#o&D19nDbjUwqIbGJ39-%r4
zuk;Ajxp##UpZ=W{D#oSYXXOpb2Es>2E~Fz;C_F-?Euzw~E6%vmovTZ)Gu*l4(2Cfi
z^m(nJf|OURM;Ar=qz74{rjmQ@K*F)q)IOYE<e}>^N4}!ViI+h~>FMi1M|Q{;c$A~#
z#(W<EMMtM2@dAY2#~o$*9!H;eR8gNjmIo59wV0@j!itKh2MV>4@{b;IH{n{&qrb=9
zxNA1f`HKQ?;EnAM(Y4(4e!7-NjnP8)_8w6$exglx@B#U9Pk(U_gh_Yu5&F_6hjR~(
z@md|Ucnv73uErenD(69PAW?H(nFrF~IS<wSfP4~)u7fc(>2U8cHSY7jq7?rAxVa7>
z<`ew+N4U(1Cl0hYj&uqL7(kyw1`5@GNk=juZ{l85eJtS$P#B0eQ9%p?@h^2(2xb9e
z48kECfhLI&6AaE_IK?RUDcYh?bEt@nLI){@Z4_{<WN1eLt4W4`6uC?(Mx=n_BLhhg
zzB2`z6u43C8w#CKDhq(<JDz|T%9HUf1#}e|6H~xNfw-9kP>ifTtOKV>#orX_C>5gP
zQ9u4N`QeqFkv+U#6#8B%AgF*+A%lkalZYu=0`cEL)X^wMWR)fshzl}!iIvX)r=^5{
zmO`M|2@0GlAP~sdsshS@jKA{Uog=hLg#Tw0SE0X_$9)y5Kp7S`0DoSQV*_Ep872dL
zw-kcrv&k!hv%&y6BG}4~;D?NQD|F*hWZXcawTEhsW2=JhO2nEkQ;Z%zG6eDkG6niE
z0EoeX{w<FeNBH0Z$YUyVY@jDo9AbgeG-DMDV!<Pp(U+8kv5o)`>ZoclP*bb;1}|d8
zRSsnD8Fg6@<eh<;1BvQ$Ph>1n26zr6s&86bHU?~Vlp?B<yWc?i6lUt{bv(}xYNLnY
z2_5!@OyR7BdRv9O4up}jm^RepX6$T1*mj237AkiYf;)Dk=qJsC4My<u$QHt<86Anm
zUxB~_seOtRE>sCCnz(FG>LBDe5D(JkDXb_+d(|K^NV{kd{R8s2=LKaC_g8FmQIxhe
z2t{f0jODxbsu1iYka&|m?adGpu5Vj$+Em;XkJHw6u;IF$A>#vzaBx%4M5K1d-w~yq
zQ-x95U0Wbj*gT_t>!_j#_!3I(jFBHev=0lw;*fJEth>50$fy*MKY-{<9Xd7;Nhq*?
zaVqOIr~o=1i54E3W5ru|s{6s)B!Yo~IBNqr2nG<O4Xb(|{7d38C>t3gRtk|YLN21k
zy#T9B{-f-#mJNL%!B$Z<YG5~_X?PrEL2o33ZGrn>&^wG$yqWY51L+e%M2Vp91q>3S
zIJ#Qq!vaskWT6-*(s(BouLW`7V6s>M1yu#LC#8csNR${n+KM%!bh1Wlbb<8)u^kip
zMuB-i3>^jG;z{CB!l^NNJ{CWG`_CLH)TJ(na@0kq&%Q@bFh+9#zI`P#$pwkJ<lE2u
z-VLHRDd8xY3@8P`<zPu!0Cnk9qU<%1i2`AZNyst)?-Y@?EaQGs<y1XxFTp%hB@#=R
zECMCM)F%cRzw$UYo0R*dleWhuu^^tYNi1kyY?2C+H>usnEi9O4y2K2f)g@+8#cdMu
zX^<p5e!rV|dJ60;$>rn7S|+|9zc+dXcV0>hj4??ZH13;G!JHA`vZy&DK;Cmgm0CK<
zd(KHHsB+FpD5#mZnRG0rB1c;MZhW2-gHnOrha^h_m^hdi>X|%Ej`)f$GACZktJJy$
z?ygA+HIP2hMvb!fXKQpTbI9v!C^?IiO%g#OmFq(ViBwb^(fvt)Rlo$03|UY@1c6oo
zFF+D(6?oi&glhrRlc+0H9p^ETc~SWxzOMp?x}*eK9I}JFVR$Gie^3g`yV%DHynB<K
ztn`(gPi3cTY{tvPbLNO0B0?+h2u`ZB0^=I!)D}SAED)}hPNKYA3$RT{VM%S0nB5kK
zf+9|b&b}r++|WpQi^L#TjGTD%RvCyhYmtbKimfE8D+Vqi@!7dD%-^eH0|@<=B*q(1
zv~go;EfcRERBTDTH-Koe9NUYL6;H!&GwGk}^86iCbQf40lROamzGb2qbfuub>72x3
z6wgU4C=oT%21-dX9u~YcIT5LUOx8q4`pm3YKotS{#Rbsl3hLw-hMXjh1x-$($AJW6
zWTWR|i0A}h*gvIBD=@7l?PP)5c$Mm`IDO(W@mCg*R3yixBkRnASzw|CStb$EX)XYw
zYjn0VaPXya3`${;cLMRAImjb6kZ7oGgcEYAI^J8`s`(i!3K>WJhc+a@kospr*gxR(
z6Rjzg+w|JN4|yk&A2k6T<-^mS9IFL$K51BiEE82L73<07>c~1Xz9!N+b7D(fk~!9)
ziCcD*$v?}PLS#qD2P!my%WqJ2OpwnWQ^yc#s$9^~9=ziSIj4?sKHB^cLAND#-x=Xm
z!f;R`NAL_}t9=THYdDdHQXFRXHnqv;NUGPar7IbaqoiXE5><dTd6}Uj*V|1Vf-Lo%
zB>uKzoBATEbmUirIv=`Z3pwWg8Erp~X`Tdg*l|n~#XIphryc{4{WFH*T&K?g0C#7O
zUusS`>SxJj1yHAE`Q$k(iBe`L8|qW=Y*RytXl8pUznHO3owx60^vwCMzK(PHI{cG5
z=a0i(km@;qAO3NkTaKH5z32SF_y>OO^RfVhdQ7eq=RPe9-s)rO8lN!dF-?CWAU(R4
zE_abGTGf60&vRNv$G;87>s&^O<TC1$w54VPYwhsq&UJJQU0chvj*f8}-r~8Ax^8Dc
zxzCKZ3_tYTXU0#qR8wFNX{o9(1iB0;H=4t1)TfQ+@EY}LqdB}recEWwsL?iU)T`HM
zoA%}6HQJ|rIr?ay_T{1Q9SFPVK!+UDHXI#tOxy6N+K4P@Iym?eJfKY#@(wBMbk=Ak
zzqB}yc)WtD=Y27$7I3m@rA%Vp8L3<tHA%$+7*U!$%yFJt9NKx@EB@--t9*%Q@~h_2
zttmW<N4t@hMB96;;0?aVJR&yv4D%S-<N?g1W~2Y^@)gHXNAi3ct={g3+E()NxOzz^
z;OMcIii9}9H94m8a6J%Sm{zp$&;=-t=*xgM9rdG)6p0o}35lyflanT|3$3o9^@uw`
zlXoRA9ZimtyqGlkMDp&^s(3hg!5Pr)64a`eUEGtJ920q$8i)%maoZX}Jt^ZuB=139
z+FI4v$DOWK(*>x6&SO9+6>Ts{RkT4y23#;3-1Be)ZJ{@qZ>S#bB$;TzCYc^FQ+>V&
zw@GaP16-T*1{H&_Phv3$liI*bdHeU(BUA<pA@A?=e*JGZoq^Amo6f*z40HymX=qX!
zKpD|)Dg*xjCY3>S?xZ#_O!-M~5ZhuS#|QN%ZPFUV!rLaT!T5GZ^d5}hP}H>6CYe1R
zNs*{sDh>?QvsCuQ?P5R_>!_YCkWfIimWsuW`iWH)sw~AjeoNiuF_9AUDsI!ee01Bc
zi&Ebr(sG^EZms2N;ERn1Y_3$*MO}_bs4otrOmx;c33*M<NhUf=XRf|`Y$^LY_V#8u
z8+;8LfCQo<rr9v=S<T8M;Tj%>z6LbvVKqg(LoBBPHq1$nfbG$8GDK$#gcBT_VJZ`F
zZyO=L{E)D-1@j+&$a}$3u^62=0*NVhq9?dG#GYh4eJ{{&dw?<*htqpvlY~zU(^(oC
z^k(}c5l06EOMgoj&v@!@>FZl69iY>1sdR9ye{+^dS^?ta=Ohy^m*pAug=W8*AR3f9
z%Qwsvj!-D}{?@f!xUHjg+CBWWT_=PMd|0i^><o(vAE<b#PIzIIX{ma^O&4MI3m~8C
zotmb&`Zjs{&_dL@<_4@t4J(sdgs_OpyNC9u)-^Z$$~;H~Xv@Kh2}d58yavD#GiNGD
zE1J*bR93*Q2D*c9nchH&umFk{O7R36UQ2%;*!fzgr7(I@i-upy7f0Cl9WT<Vfopo}
z+(*JD*}Aq7T-;liGc#?QZPSTA%%2T8Lunr+OU1YBr=YU%F9=rF0kLCZ%^V0i1`ATE
zKVZ;pTh$cfjbM|l3Z~(<HI(8#(nfFoZ<;DtYPOaQ#KAk2A#TBDj%r%ComQmtM|@G)
za-zVguWh<Kz?R-N-oasRZ`-E!;gGsXO&Lb}mI-`l*l(M*7#ROSu<{Kbq?W!@a3^S6
znla&X&^E0iq0ML;c?{{yFc4G*`i+6mi)5U<<OBtG3G&i>)2AZ1YdZZde39Nc73hhv
z3<&NWIPvTncw{DMy9VC9lt!5~LDuYDTLuy-kj5vF_!V8_-I2tZfaH7PLrb;GB6pOw
zOKl04mA2ER#b^7jqXWENoV#fDidll-2ycpSX6Gv4R7it0i7nnx6M4kJL1!Sejl+qj
z?YcC&n@=z}eajE1F>5njh1#B@41c<|=P+ab|0}Pgwx{O{HcfdYg^D0(t7iYFcIYMn
zC#iO5gMcGdJ9L0JR^>+grt8(>tXf6hSl-=-oEhN6)ec@N;pavEu5WopEl%>a67so_
z+A{Yk8)dqS#Z}|b<bY4wK<Hrt$2I34L;bK{9UY};GIc<3kQ)H~)EZWbLtBV@+BsVq
z{nUK2A6gaQs@D$bgy78w8n)Txk6dlv@(UaY`wkn;K`jy73)>OD+F3VRxZ$JNQr+iX
zjO3X6rjr(F=)UC%>0EWVTZOlzL##jcjP$KS+uA7$2;8{_qW;GRaOy+?_s)UP(GmKf
zlZRG#i4GtxqHrW_QX|6IbTIvK2Kf$<E?CDI)PS=y>k{;VXf>AUR2iZnPD>aKg3Ih6
zH%!F)sGZt2;N<1JiYJk%zjgpP@eY2*Xd?W4mqAIn6B$C5>NPkF+p2F1PQ{jvLU3^!
z^qK5(_$E8YCMq3D5)yHyf3uTy8j%giMz8s}WIDsA{H;Swp#<=^cB;^uPqw9p5FNKo
zS~+-kJO3zsvd3M0l$)N|yC_TDYrc6AZtJm5*t&nE1NvY<t^DWcOnyl8V;>0A)%1cg
zY4qp}Z*nK1zr3v(IndDu85s=6djngDyz`y<mF?^3gHtW^4aV7G<2)Z>07j=HgbA2y
z1sO)*RI>^!@GdBdyj`*JkhC@f7OW^L4Q(65w;aQ0n@Mws=!iw^xEVrWMS%l;B()&Z
z@DL13#tQ^#SgD+rjN`DRoq&SVl2QTzA(s3QsJ9g*wPR$7fyV*CCtltOc)uw$wbbAo
z#%qz1!jc&Q(Jz)v2&j`K%K^e@1_v^ORS?c?q9`a9S#|LuiyrD~p5Zl{nrC>;md%TA
z%NY3&1~TVxMzjqkmz0_#?8wTl21b~|Kro&NW*P{(Xh&ldG=q4k!9UHPLHIREsufk`
z58-zXv`9gl2+Xn!amQa)w7oD2Y(Nl0l-OY6h8QBrEJMvJ=0f;Y#SewEpJhBaG@K*`
z|5j|9W$-un$em6cYXO4fEMvW$)I4~}W31pGHIN9Siy37K+g>VEoF)e>hWS|rTq6{4
zAQ@ojZ!#3TaaJ?*5u;Z#^bx}+cPvISTFv-JAM3?A;L#%NCsnIAVk8Grr#MOnSlyHC
z^9<9BamrvwY&Ug7DaJ_AkcjoPjDBwJE^W}#GF)_&QFVlrnl!hFJ9WB!M!3dDUX`1P
z(W{ox&WLcejCMv8tW|ypjpM%4gMe;PBOd@mTpOCm2uj4{dI|x&%Fs$^02jpe4q#`f
zZ;Yb2ArK#IQ+#ueMk&IwftB5+aOMruS>enZ#!S2pZTE}`?5S7=tWlB3h-jPQn`0fY
zDZbg;YE6s{&}}j~!}6^FZJPp|;|lFb9UvCln>Brp4X2TY(;c0q2EYLLacLQ4hQDKq
zH2(pFqmMM?m}7?cLz5dE;@X+2{9B>#mf_9_k2i%o8`g!Eacl^)x5ldqL-7Z~`2L3O
zq=j>Y^N&*eD46gq!=FJ2V50w~@07KqQ;2iCHHE(!4pi2}0|bf!%b@5m${XXN;qPHB
zDHS$}F!UO93D$n6R2ca?_;Q>hT2d+;kjfxZr*9ZQM~NbQH+F)?kW!DDWR{R`x>qfp
zN`#CboE!=^g_+Hy<tJgqKyIuS@k8VwDH0>A1*V8r84zfgj00rZSWIm8VB#16C{Y@O
zwA&)e(HNv1HXGzn3C0h@tl}~RV~b_fc9>GEdB4CyGE%f)#&<*$o1(hGUorsJW0O=z
zIbNceSA;8CqiULTDxM4mzk-87J5dS=tywS*SUWX92kRyh8|e8>&XZ(`u|`cMnPdjS
z0Ycsl%V=^a;2nuM6SOs+0tZtDv^FLuOi<q}4uNK;NQyi=MN;tu){Bfnho;*R>^Y&>
zwv0=M8k<>rzDfEsGW($90y?j3#;TDM0<=O*4)jgtAv0=X$xdXZBMtbAJjW2WYN&xt
zPNSekas=}`*pryP=v(AU11aGMM+PRNfrunco&pI!j5~#CwT0T!(i@e8Py-@I(J8U`
z44hVK6j@<x6($0T9qD1rv>>}O)zdk}FhP~c1W(_h!7>v?1(>oNA$wSy{08K8K^{|+
zL5rMRmf`x~?HWj!%t7sC8NUzmFOwCF3}I$|-U|XTrnUMezt|EGUSpIXffzOi)4C6p
zrXzSwoVON}r!EQ7%(NTqyO+QghJ%77vm3tlAQOmg!sl)?wOdR*U5rATIRG}`#H@<l
zWBC?ooXJO+#B!ztG$fyMBpL<fqQUUDki*WBw*V}6CQoBh;hC5W4i2quW(U}qnCR?V
ztb1nk{0e41&yI$69voZU=b+_VOm;{5_nDFX4J3hP+P{vjENtH*8MN?%TL4iceqzH&
zX?Fv;p(Wh{2oQ}9)QeaW&8S5Qt)e9(1Hv!ObhSMAA!|=O;4nRM&3%j0(UQdBh_6^X
z=E1L6H&hTsn&s&oY?5Z&S3x*w$pjJlK{IW%$l+mh|6W98X)@W8?$XE~0YXeOT?)<?
zsrI6_L7=%P``))`HZ3V9K*f1S8mbGz%vhrr=Jop)52%?GPT&f)B(DIU=p8xYL#8t=
znMzGYXR?{zk?2328G;ejNUHTM)>J@1qW^fTIC0@Kapxh3lE@Miu4YPB0*co=vZ225
zA(JZBWF!Zj?D89Q;NATzS!w5TwC7H2YxKlV_FEIr2N`nj2z!duw#J@<H#nJi&B*>o
zw%$9!jse&0rjCg1fy}_B@B^|3-;q6DexUabHH!$;*=9<ZK-Jj|;ZVj*8idHVl4^&=
z9hAz`Z`4)8gjd(14o!p|3ZGO^JWp)`3v_l3DCuqhJCE$w#t(6Z*nJo&kS5&`b|}U-
z*sqrv+0-l&V)JM;Be%&%oy#aMUu5f^W-A=VW<(zxW_``?ExwF})Zx>|Qh)#Az(GDE
zEk7}Y0+QN1AyS{`3P67JTqQuEJ_8juC#^Q5VmJIo{cXu2pZgu@T;`UqB!SPhkVNq&
zPa3kxYXv3YJQvwTr1ZJ$(jP1rYx;xbicWVht@w*L^0_IHL|;1znf9mMhHU(~A%U@f
z$xVxl{<+nW^*^^mrUu9jlj#GN*io5YAU9#AAjplHc?z_Z)1S*2De_H^t~?UZqbrXM
zOp<`Ku#PmHK4QtDc0<%o%*T*N7UpcoBTchB<V4TdQ2FUp#H0{;bYkL&JYF%mM4rGJ
zk3@M)Lz0R-$}x|HPJ8s;LdIGkJT&66#FQC%j*O%lJZLiKMjk~Ql^Hs&dg_j-8$02Y
z5I)Ji>g0)z=sfo**Hj0qS{|{HX~e|o#bhLTRA<5xo#yGXWhR3jowo8u0H-ZSLa61%
z0&i-0vFJ7Oz?kj{Y=r5afYIz;-S`VnE5k<zbyePym^nrlDW;amyB6HB@;b&0HI6I*
zD8tI{l);E}o^P8*gy-8vl0D|s$tx!F?&Lj`xq0%g$^<^V%q~jtlNa7_z|x&q4p@0_
zrUO>qt&w|Z`QnxQTM3Ht+8!y4@?Os@M|t;WCM0vcD6=QU%oC&k)+EIWnxt4klN8i`
z%-$po29rCbmV+6fLJ7hIQK=+B5~)zoU_v9)6tpcsD2C}94pmgyFr^igItw7mpl%06
zShYh!>`bb)Pezm>0axmwn4>F|RZQfS3N5%@rOpd(SF>V_Im1$WhP+~_U}NgBP{1)Y
z85DGpcP!R<#x6JNDWvCP7Bp%CktQuwg>b=|)QQZrmMTZ4V+)le)3v3>k}2InsTmc+
zJdiInbHh<J%ItBeJY|MC=~tJ?L6-_xrm0IUEmPU0CO4AZrK%U{@Me85lIBfH<8aDK
zwK5a$rRtf<`JkR&0EJpvI}-I6)N(ToU@F3yDv+x31<3?W!SYNvnEG}mB}|<>@)oAr
z9;po%D)#|3sQdYD8ac4!AGC0o-c1XK@uG-yjFUBDq-#uT1=BgEMS}?+)9Qhwkc%uM
zOdOeZ6DF5T+X@p<ru_veDkmEa@>r%Fhp8^p)I%4mGzUe(%(NFR%%_=FB_`brs}qxQ
zrd5hARcW_^Pt_vZ7Sn&G^$Qt7(?G@~qG?29o>5rZ7C<p*S`5$fmDal97!_SPXFR33
zE<Wh9u=};pow0CCDNwO(OleTDZOA0a6s=2|Et$tPO`FX1D(fe*!OA?Ue6cX0E`VB}
z%&bg2o0iy-mzJj5Z{@9(H5aLEm&xMG{I_WpW{zA_6i{T*P1`c_?85#Wb;Deck-8x$
zlV<D|DSgw-&5XZk3Rha-u$41!aN5$DS=dBEj^x8>k4JvuC2jUhVw`4u0~=ME{v+{m
zItMT{G8_n&ugssEUIs|8Jb5B833IqAFlBRkG9az<GPyg@=PYu>e?@-iK6ywme{{N0
z(7VhXEtW6kp>`m?R-=EFyfa4P>U7>fUTZjbd@1$yGI@b8KX!VGFoAY@lQ0i=I-w|0
zcY3NYn|FG%nB1SZ&oe`Ky2T)k_%iv<&}~cZH5PfO(gBD5Sm~vMl;-s0@$N#lB6<5T
zHM)r^iRshRMTqIu=|;3D1$(*~F-tpLlbFZdl*oiGRq5e`gz(Gc2F0B5=_$p$@^YkN
z>iKlG;x8`gk;NqT>9xf?_vzVXNOO|zUxp+mOZta-zoh?|A^8X$%tmL2w^CCxF)cE?
zpCJcnI<r~fw9v$sClq%f1J$)<;=2LG(D;wkHC^s3(r~0x9z3BY&poT)q)GQapUvy+
z0>~MkZi0q180kxhZ)uqv4h_6h;gC2=28Tw}uFB_;)ob#1T)w#kq)(((x@}UIXqA4O
z%1~dSX{Q6`q7^E=G<{)PXHQN8Efw579iiVQECaEGhTkU6np}6otJEr8HaE6#lh-O+
zh-5SAxH=#>uCkT;<oRlmoB`gk06P6=7XZ-*TF>dYB}ZJ}HP=FKT_6V##9VWOPPbp*
z#ry0U%$*+o!vjIADSV6<K;Z;S|4u)?ct`QZX;dxJpP2_@x;)3(JG`kk32pEN=dQ}D
zLb_M`1;d@Gp)!d}N<jLk+w90a?oPwQUB2Gd=<7{~@NwIVuq1hm`?b=m$6Gb;r*b>z
zg_e%#G|`9W`T}HIXYY1i!P5ht*LJwc0||HbRfA_9yDV>es1?#7->lJNKT2}gN1F{E
z;pzELWlF{dP${GE0cvm}ynsrdh(1_=c%X?Q6sUsAC<e2xBe<6sE5V9)R%}!4yTT<{
zd(0liTu@V(ff>+0E*ZQ*HD<(i7-Bm!_G9Q*5gZaF^qFbPgRU@xOsH7SFcj*rGgO7z
zb6%yEfcg{z13O2C$<Pjyu{36k&?$P;$p&hDw+zwYBxQ&WXeVv(9U$t*5E_cOpaqcs
zf`W$({8SlWWT9_VRFc7WieXFE;br2N=x7hv-7?b27}LM=_HT&cSHzUjy(+`14D@x1
zyD~=K@4TlQ<LwozWu4JyJ)0TfXIf@E!_VSJ4RzDh=oWR;$)O{ND1*-i6mesk9gJ^R
z2%B|An`zhYot;(H?hY|6H6!Gl;dRDva)sa-qsMm<NE*1bGL~;3KBXA$XB|W@n+~QO
z!8ZsHTmtfMX3Nn>P?{nQjUnNiCIn_YqZ1d0BJ@+cGE}P>=V%CZrJ^p72y>*m$NC&P
zX`L~dT0R)rtq{zCcnD@^<uKVZw9__5U{dcsklLpZ(E&tlLoYJQ5lbm8h%rig(}v0@
zZH22E6u24AI*{m?hEkuSVU1DQ3Yj%zo6oRX+YrU3SX|q{g`E+*<~rbv={3B9QNISA
zaE1ljRii0x*c5NA1DxWm5q@k4x7LkiL!6spm=}W*IRl+dA=WyJZP-^7K5gFXROv@K
zJ{m@0n*yx04k*A{y9S0ggS`jh$4>@?n_{eUCNRc2rviekP5pq~s84fYL%e#<1;ott
zoC`SKFb>|J)27*F2`GB7PEyf<I+<+y7pDfkXvOQ>h8&C;)o*avYp6R;RN@3M(6l9Q
zfZ+>mB*z)hk=z5u7;MoK3?%3tbl$*H&}h*gfGY!%2*G0gNUj8fsy+D>Y&$2u1%rnm
zNEsGD@#ZZ>@Mc^~8Kf<1qajO#2qG4Tf@T8qVqYhM31h^zNGL28RS;DG@cVnRSs0e$
zWV|p2cFSsIJDDChCtv|sl3l~VK%Wd81`kG&bPOPRp-e*23rbF5upEdDWB}0*I-TxV
zYh+U~Fyb{M3ytj{fe<f=!8bCwON?>kqBj|c*M}4+@k7DSa!g`gAyKIe#QR5VD~9lM
zF|v#wLO3NkTO5fRY3E=>x-|ZdoJZ2b#1BP{`Xm;NF?|wqo|ZnnD;Q&_cwcNcG1`m=
zaEKP`jqT*yk<I}rIg&hQAaUSmni@E4i-Kn$QM)=xdF^V-MCFR~LH_SLRPG?6Xqprx
z+mU`?C)v(A3B_cmI(Z;{A}=zWw36UxAbU>=B!jJIqDdN15JBlevSV2l*OK9smwZfy
z$b9H{mq5HTrP4K=7L)wRka&dTP@^0bmU`A0(l2uAfdm;;myq|ac&cpQCmt)?K^C55
zR|ex$GGYxRsJGfA7WHqFR7?i3Zw)9K05it`f_#e<UIXziuaivFpH^QZ!GN-(+I~!I
zVg~=-WE?XX%953AAkJLkd1FT@xY2Z>fJbmrpP64Af*8%nRY2mj#i3wE%Vi*Tiju1U
z8SiwP*hz0k?M+Y~EEC(C?WDMq#s;p)B8+q3JSR@Mfz(dgxdn)iPst4;DegE`oL>n1
zc3$d*6nH@5L{oCuNpP3L4t~2Fbn@G2(8+J7ymSNduSm>(c7Ucx%zp+OWU>P~V#iD&
zXpz$<X$A)nL%U8=(Gx36qcWm09LSg%igI>fR7I4C1Mv?pb$ld<SgD0Lq6QP$qQTKS
z2^ozn5+ZGM#H*u^{wO4Vj0R$3O?4dXtVtnh@E=c_$$^Y+0TbmCNRVTidK{V{aatPe
zwaI&F!CxU}%*6q(j!t^G`zObyAt6xma2jYYMAbQf;5ZVYC!mS+)8GW3#GnSv!$3O9
z!7X}be^pV9W{Ld-zIV};4kWloX?F<njfJ$Q2~E_f29-$Cr&?q@N`h4ZO1nFdV4Bq~
zeSoi?WUdLw2nJjDK)7*0L6bDGiRg}hR4~i-TdAnBzDgunEg&)42C}U)>un+>`^s<R
zNuEn+AlX;JJ)2)>B2CpDY_!bic0<%NPDU&G-x=w8lTR1&2rm<~Pi^-ZBtqgD$%gu@
zBC+w3h)zdGQ{)6oRE_?Zum8M^?|i*}^=jf?`vqUC+qxfiEv{ex{7+y1@>Rap>p$_o
z|Mhdd0l5~iXMC>TG>>)p#$WSjdz*F{^Nu*XMPw8gjT+?K`6>C&=S3O|`G~<gwUGNf
z$E|GP9$59yK1Jl-W;@8&O-kX|0!NT7-vS#!Z9I*Hb<BgV^JqGLWjglwd{xSAzmbfp
zW-1cfA~%c-7PyfNasuAQnS4bCBV1CQO#<^n8H#icR!SdfJ)x5rWGB?ic`HY@s%XOE
ziliQCuc!n<vZiC75sMULXgL^8l`hQ~OImhaTabb?6UEUbxa_IjWsX0ceVGBaY}&94
z`Msoaf~U~{@ENx5EO+R@hV-gK*+!GfXm;1VH+&d^WAi(F0?tD;sNZ3@{$id{H!eng
zTk1z}ekqpbTBL}VA0thGMP6&Pm@S#G*APYFX@})4;6K#lujxNxbko>988t3v!x-Wt
zQRNzUBKeuTL71zt%4_>zf^%y3-6v{PyU4Gh#ql<i*AE40{0=wJhUs0(Nq;{OUKXY2
zp=z!ug^&Apj^8QrPlhI{(1zZ?=(?05KWNYMPzo0l`ZO1v`5F_j7q0t_In7Ij#i+sW
zs_3jnPyX>tL>?fsrp{$8d_T&{y?pV*x&JQp0gWk*i~6Rp-S}N*(#_vpJ+`5^>6y_s
zr6~CFMACMpl^VNkkMbI^L8huQU=Sbe^iZVL6ln?$00YRlKOfdYkL{)67MM~{FN^^~
zpx4eWP^22O!f`Ux4F{5<`%ZOQ(4r(uh`Sy$3L#n%?_J3H0Y~r>x{(SCS*aPr9=eqx
zS0|>2DM<x^HAaqO3$yi<Bu>DcxJZehMB@x&410P}Bzia#j5R?l4h31$rCX}-s3;jI
zTJRAWzxPUNBXZq;M^?7=miQP68>iI5OuZ{E=rb<5%V2N??G;9()1#$?V;FfmlRT?1
z8Acpi%65<;r-TP!*-ktV1Efv8z*JXuxWX5|n%%N`4o<Pm*2v9dCJ@}P;qaL_P!F0h
zQtrh)VVROVD$n9B9!j6tQ|iK)E`wUDqwE{&n*6s+HMfeN-0y_dKgvvuHgn;|-kdz+
zTkH*Ej|WXykF12ZJY0T&u1e4W-s{>LN`6Rd8}b+`;ggteVK%H52{Vv@?w0ds)LTJI
z;`E=B&>-hQPfmX%=-Gk`9~l=j`7sQ`;{rjtS=w<|k=QC#fKtriLOjv%!)yvRDbTOS
zwI5aSd#=(*K?$0a>TU|Dnam2;!#1b<Dp1yy+cQm$%7vD|iA$Q?#)ZB`$)qe6>y7$g
zrKy8AKdFAnHY>WyjmGlMJ$Iyjp4nYP>#-#PChWJH*l0x-T4)Ag_Tk2y#Bkr9c{Jm9
zlbMn?TG`K+K?q6W#-tmB9|9Twz}b0<mNfpU<>v=4jNwg!M&qVOm(OocY3lAbV!c1%
zfu)p~<Fp!q^DD#cR};M)`Q7LVBwC&o%r`~!GNs6?EQr0_@v(?msmv~e&Rb<cZiUqy
z9<$;#Aocyk=+uhXm`JVzudFJfjfOZz>R~IqS{6Dfdk(QRJfF!T(?!&R1{)}2v`J?C
zK=6j(Eh0RxjBRNmGuljq6s8S2!i|z}2Zp8Tp`B5{$rP}OngQDrP7Fq}od~mMgdCXx
zb|E}y96}f^PPPvBbXZ)yK_Cv4m>x#sSOx;i!#H^OzNRR^qTpsZFT)=aQI#cw3mJM_
z^<oCm8XZ&^e|n%I@O5qs3d~?g2Ik2#yNR2Dq0L6(6NNb-kaG@gJCY3J>zfu$4<rkb
zelTn_gTfB7mSlJl!<HB(6tAH*il=vk%tU+zLRB)@;}BH<y+A_04&HsNbNGcq6%-M8
zbOaZ*DiOqiHRf}5Kd>II@4Vx5A-Haw@W+7@-*<Rp!_%7n!5g^3WX_L`d~zYidD}{w
z-k}q|IlzX`sr1W}^C-Rf(tVPONqHzrk;Aa%Rq8bc3a?THhbf2->+WF}wwuW>4|bWG
zlii(yRnBB5ZA2c62oE&)IAJF{aLr|A8y&`sNm3?fqzX?Ss;Rrl#U}kqe5X}@FGEJS
z$@hdr{aYpR)$CT04i8~Em(mjsA`Ef-4rBQmMtnN|ZaWONQiREbD={o%O~G}B)MBme
z`k}q%0YP>(n(JC3Fo@Ae0Qb4-mdfQjtsIrw5LpB!)i^8y)M3c7z}v$jZU3slAiMKQ
zdjyo)v%WeMyz`4Zner(u5LLcPE+)0`vHhm^uF6~=n!sydk82&g{<tPy*{(nK^}1D*
z2Sp&1d3#K=PilqJcMMwxn0vlupQsy8EDH=Hyib11@G&U`!JS=uT0~>bblNQ$wftUH
z`)slE<E*TH{<9|AL%6{WHoF{s*BrKkE~jzLsV!w9VQm_Cp_HxrG#6`V1?e#1%WbA3
z<|MCaZUcE#P5*nQEl(>`xC1RyvTfG^u8|#_szanM)fA%k<&-x8c*&M=U!>Dt7~9J!
zr6e>mgSJ^-ivGwUqY=C%%b^(Pi1-I}__y}KvU8C)xO0^BH$+%%DhU?`i<Vv9Rzc<F
zS3dY0$7ec@;#@H+ueu%Uuz&WR{3D*g2wiu8uh0Q{O}bX$io0=_iWLMMWm=5D<XUtt
zFr@V^I$T&7{o*zStsj(3rWC+*S}&GSG*Ah(+$5nA$`DVOZA$aI*OC!qLz96ptyory
z{2C$}&-EeLpA8yEMD~WkZE>X{!%<_+FBu%RL;qH}3a5Th2bm3FvqeEm;~3(dUYnPE
z#hf&Xpsp)b!OBP~R3d9vLmsN3Wg?Zq35}LwXF(f~+A2Ek6wvxEaWo5+md-MW+AKws
z0u9<FWnpj7p_U@^B%Ke6B3#^>KRp!c!BB9DQvg=zf(!5h4dEH@M`+wiF~y~>O`16n
zADvKN!UnVisgWz<#8-7v7fEeuMW|%a4pqTRUy2-mz|%GLYz>QfDdH>iaN!(`v98BF
z5!2s}qy?oWZ6BIdlL#*kS7V-p>Tr#DA;#UlX>LIgQ9ETs!UevEq39;HCdG6uGE}hX
zR!t*NNv={T<6RqwyI<^WrRCjkmExY4AjC?Ryp|y_X6Oj<Lp2Uf1;=uz5nV%ggqu`F
zTorRxemnQI53(iAGi(c;7g(G@nULHm+@V*~`b8dh*I7k%z#dgP%?AasmqmGZ$G)H(
zJi)H-uh#xNQ~_a+(T{+pj44n;#W0lJyD}LcCi4(fT(GW|L+RGS%f853S#Y#i#?L|9
z2*vxMq_sH1jaotN<LZ*Jmr>z}`bJYjvl3^HHFNYt7U;D}nMfO4rY?d(a6K6;RdAxM
zic4dLr>dwu-+<iUmwC*g%|lF=Cq+Xx>nYtH(lOUr^H?LXJXL7XxkCv7tyx?Nsw_~R
zip~!4>ZabTTBdM>CEPM|qHo}fe{xawFOttghq}#a*aK0n8Rn!u$4wuZqr<5~*-ez+
zR7rW^>ZJ29=YOM><(8vz)4StfeW=a23smSC!)q&*vp7bznz`m9JfSI_j*{j{#ksln
zB?`*v#_7Zhktw+m+;B{pW|X!|(^Q$Sq%A1W50W?KJ90jq$8V~{@OW23Kcy-<;8c2j
z0i?S4jubxYJ?{^kpm**MlO7SX_9(brX3h_|d``(;pk6(cmFs}h+^M8#5s|-4*+Otr
zX-W)y!qfazuAg)F%Rfs@u#tMK6<j-0@(i&5t+G$8(6g+f1XltCDSs=YaAyln#FdKb
zy)ZX}C>KG%R!&;yUG=Y6(C>*1UcXE2QKi}wmPxB*u53GlsJTK`GE=2?v583>d!QJn
zQ@wan1BpAAD3YT<!gA4SZbf{_M8G)I4s{f1Y2|`k;eBm#Q?5JNjJQedWOXY%^wfj&
zTcRU(ZN<b}E0)Z(j3(zSblP+&nuuS|P*8@_kesACeyu)0sZm?8u|TKkCp1zLCo<8#
z#sQc47m|tzN7=<JkAt956HyZ5NlpA6jSN$w;%KDwYGT)E$6ccbrLF14(2V?SVz&Up
z-psD!gMC7?*riBL)#4rmFeD`c)m75FY@!wseHUqclK2F!?$*Qx<vz^G0Wz)>#<@%4
z6Mht8{y9STEeGXBqE!(=fY3u~`dC`dW1>YEx1>5}ml*UB@kr7NKqHwxu&Xg9TX#yt
zH(N0(4#^>)zyKvKp<0glL)JqoHLf75oZN9L9D%_ZtsRS;B91_Y0V)i{98dNavYcEu
zKrb~#xyA(;j_1cdU7|ZvZ7~pZRcs}ciij&X6ukmEv$h}7L`G`WT`7pDMW4g+5CE28
zkkkh5lZIjMnPzbDz`al+$^nl_TYJVm!kM{KmkX5;6oy|OB*pNJjHE)`1LIM^0`6Nl
zlq>xnP~j>W-vKi;VT*mgMW`8K>n4|cbf)u<C={jEbfmBDwav$IAjs(k6-X;{L_+ri
z(d3a9+19BEh2d_^@RkjysP!u~T&d}S&wUNU-a^RT3KdI$H1|h3t+|%HGRNG|7XCpW
zSpJnhaK9msf>b1S2?9CFt02_a)He>n{+kB!;f+*OHVG0rUj-2r0Db0=Yj*|b!~3WP
zT`5LjdlN%&FO{Wu-A#S^{66?uQV_^qUj;GHxa-9WZ_3%n_rZ&kVgSxpF=}L?=#AIi
zRlkq#i^o<864_n_5tl+m@+W<T`+JW{1Faq<vi;Db{idk?gcARzx_%I(hPzQv$oVb^
zw+`sRKXQCe&G_RR{V@b0e!hhC{w`?JvwsvQQ0-+HsF>gUEhzPunPNBH{WRdx=D$xd
znBhN@8Q^#qY_o0P!|0JT7CcTc_!UzOHU@hatCQgYJwE|2Lmf|biUD9y;)7V3jT#?@
zHl>y0aS;5e>`Idp^_$o_SxmA=+ItnF`>Xl`W*2)C!m3DHO!UXyI`i25@t8>vh&bUM
z-gu;~Cpu&@{XBNQKT{xr;{GB+>kuqRQN0;?>5$M*9TX%|?Oo7r7OIcVGikGW5Tt3#
zC`hEP?}F`S0h_8So7j8jfUD~>8PoQ6!E&>(O;s)L#}0PRs)LTY%iaYM9<Ux$RcGX-
zbK<csK_I2P3Sz6Ef$*c4{WKXqypfj0DnTO0t6<+}1LQ}<2eL>$c1_qDPm0ly+26z%
zssQWeM{Wmc?|kf-cuXf9Ak-~A3PLxJBXtPQ$V*k@u_i$x=euCJ8D~Gv7;-n)J_ypP
zTO>$ie;4FntQd^G-L1ioT@z6vJH=>3Zf|0^rqQxIRa3U+_l`MCg6yjGRS>S8uw1)f
zy&;c+G<g>a3fbQUEe+!zzaCF^@&^&O+D4qxN2Yaq6{$CS`{#?98`1**AV@>KCN&X}
zEIkO8n?3&{-lw$iKXynwrmsQBdsT5kr@uf5-aQB&s~V535+w3|xoP{&9pUpu?(%d{
zcz7fH7_hB;zS6Uyy$Uv)-5oyEsHXqJV@3Tb9qRz><z1}ad?`MnrB3gP2SGYvR0$F}
zUIin&X83A+=nqHNjmJv*Gb=<;++IZB!bJ~|PcR=($m6@{_OVM4$kyK5W%4lj$Q3aB
zO&+TlkN7=^rS0Vn_2#wmk*YNPSRMrF?$RVk<a`x`*^*Y}j~I2+&iq)_c&tc}$omlz
zh86||eB`EGq~m*d<Ek(k3UVahFE()8pi@r>-ram2s~V4O6eQB?yI{FF4MFhcM)X|O
zH6n~C2&BL7d7+P%Q&I@t-IN}y8jn>85_vzgLfs9gCkW2SOI72sm4ZUHcfoq|sS3fn
zm(^oc!-+~Kdbwx4p6J_o-h8$~@b1O+Sk-uJlOPZ!y?A)zcJm1f!Mm5(V^taQ7J@?T
z^=8)SO%%rPkeh&)ipEooVg$}tv32%m3$dGn+hZl;sX{RV`<vLY-<;(_?(RPKSj}*U
zJ0(cJyZ$QZ=1w}}ePFLi=e);i_6T|mA$at?&&`8@#j$6SRg`XjkJa;sTp#h7d<9=N
z=LV7*`VW4TvLHPQAFCLTZ4v~cL;(+P>^J|!5WIUVK328Bu?&Jl+UqHa{F3y448glc
z<YQIiu_nQ;x$`Et9XJ2VPY`O}JT4#JI0bG)kjU{Wi1QxZH$O7#rbFjrRpT+9trK}Y
zTa&4AxQB*NI*UG55e}m+z|!_85bTO{ISrYc59(vZYIr(Q46dvFRjjLe*q$5w>e9pY
zK@d$ZJP@R7Y<m~1@|XRHDzZ3v)N>WxrF3@zy4yZ?c@X8w>+_?mQ|Sl#ShaX;lOR8$
z*MnR`uoN9pL-6kO`&d;*yF-wOvJN~5l1pI6b+jRvCY_2O1nGNh5(HA$S3z+V@Fd@G
zq$Be9M*2242@-id$qz&J>;e6eM@jlbKUOs!s}vM+ybG3_hxI3D25&ys4}x^f)>kX!
zconSVLoja3AO%dH?uR$h^}9%r$o?u=Suumfr?ubR!5^y{kI}-E$o?+KQERMf-G6gQ
zf2?Xewn~u5_9|HR-`j|UqCd8A{a0;V|DiVWZc=#78G?70`p2rqV}*hx$wpoU*PDa>
z$D_Gs<WaEc>!4uM*YPH}Za4q`k2`+cBLW@-88}cWDCBq-WUqFZgGQ_G5eE-~?88by
zA;-JmI>#@3$QPFZ4G&@rd#Ds6aJ-0BL{v^24sz-!T;fTPQ56k>iM(!c6<H7%dl7>7
zXpG0I#$!!_L|zRS&P6uGc6>zTmeC%MRgK4*1e2=gP4L)mu_K?z`hANgc@SjKNu!{U
z*UNDQiCK~LaX5wEqE(&*yB2#20(rMS)}7=#JaJTHLipjtkuft}f<WF+95t-q46XUl
zxhi9A9xJ*BzYoL!h-2qLtW9w{A=Q7J+z9sBB;@7yvm43Y7!mZ5FIL6~Jyx-BXMiAs
zi`uK;28%<be!haQI75)0tI9Js1Q}8Es-LeQmSI3s2;M`S9;+Iw=1D=tM!hci!_g@N
zratcGGzU;U2r*)6g-}LNJqz`H4#f(oTWr>21#3)0iUHVP#XwerIIkhs&l~b6xap2d
z!A*DESHV@C5XwbHwq#)0V^!JZ6eM!K3eqBmvuOz41J@p_8jqO-fwc8i(AcYV<YH`3
z2F5)IvJbVn5NWTjV-*=+$*>iIGxAbZscj(0h`m=2l@Ts6NAZQ=J+AMus-fXJCCGrl
z{wjzHF-kB5?{R~VRgK4Z3Qpwp6kMT_ViY0-C*-ZFYbY@(NaR%mR6%=!C`T7;H{|h+
z439Jkt{DsYA_zx*22nzALf)$Ck7?;3qD;*Xg5?&Z3Bg;~=5tlq6%b^+XL}Vy`nm`L
z4Y4^W^s$;jT6aQ-k)-`ah<6sF7geqGhCB)~E|p$XiM)DId912s^lAv+<5?f88jtC8
zDCGTg2!<C%2SRW{-m2=4Z4w01U$xB@Jf4WY4Y^x5?qfw`KJFA_6z`iq%<y=cLwi3#
zc6AH(eGo)Uu$>fClyH9+thdPF4@nAtvhilfagiXA_k;Sn-XfDf9%p-xRelg;NOO}Q
zkyi)qg6Kk;yCHasg?_H8KekB_$o4uM<)kx2kzn~P*7`vZ7Ku)KPX=kfT71gc6u3Qv
z&MA!hL12r@KwxuUl~;lF77Xq}zlDcCRSl0d2@-j|?>Z;snZf2C1$Jln`NJC-rM^iJ
z$o@WV$94;5|3t{@gggqu7`$;|%DDLcF6g&2#L9<QmS3vbgEbIB8~nvyh3N9cD-UU(
zGcNx@kWN-6K|1NZUa|_<yBX#G39`Wnd3+;OH~TI@5(d0lL<)$E52{DUUpHEThxdVe
zV3invSKVmY*_tgD`GS}wQ5HOi9coL62{>QH>_&eOwY(D|Ja$SvMn^p%=c|WbL4G3A
zD@0B2gbR-y6TISw1j*E3?}F<@-|%twyqV77K`1yMiiD#4>h@n~Z#=2>DM(pJ<ne7}
zl;{#H@X&tM`jp7TN8X93=Z%Qsu}f++hhi(~D&EAx)Jal{sO632;;~y$Cx{VvRWQ;y
zj*J-}UkL9U8V`b`+Gr9a@;<3S0Z&GbsOgQP<GEwvu}y+N%IiJ1AdevlKccF43XsRn
z3I6_5f(&?gb+Rl-2S`GZkMHSsijjvml8K~AkjQKNSV6EY2}`1?cM6lo&WXo12?DA0
zRS^89Bt-dyOX-9>3W7<c=x`uzmDdw*K_byA$CCnrjbvbX9FBO5k)w&cUOti&`oxud
zbk3dO<#9OTv5kU6#QE?b*k-<%=$jjX%;RAAQ>(-PyqZu7Vhce=^AWGI*l8XIBA((t
zDByJ;?1*5?ao=a)Wf1mg3dI7jAEsHkvFOC>?z}pW?~BJ)2@=`f1=kx(PmIEyx94%t
zSuqL{d39wi&=68n7$b4#1$rF#4HcsxkX~N}BbQ~64CPSt7mYTDy{`~K@kO8QP4C%@
zHZd7Jy+fMa52%lR=(*#@hlD|1XNIKbY30$iy97zC)LsQ`zws?$kk^@k>3LeAViY9u
z-YLk;8GKG5mgSdf#zQ@XP#*LwFG6-Bii&sLsiPj>7Fnwf3W{^;)n$Om8bCya7oHO{
z)${w#gJi9riO}lJMqNO(O_r+|^gHj><1~xMv=0y|@B0AMT}{q3RCkG2>v>7=$5uMQ
zB_Y?V`wr6PkU!@m60Y(Zb0}^vh8zlbjX0#oJQ=_~QVu02*yGm_k97$GsqYFJ@|{#J
z>B%?t_@zfagcAcE0xz@VoLS3aF}~55J+8%j7w1TJyi$NZc7#*SRNX53c0*ovn|Mq|
zej@GtR@uwUxE34gje_lQKdq7Vbkj;(BYo@-Thv777H5+izuV*4B%W#%Bk<<Iesuw#
z@H5wsk8g9uwoF6(c7y@>9FCC_@N$ZD?i#74NMiS{nd*Hewu@u(jp^?3lpIghJPZc#
zx;8>-OxC=Q)P>2T_jvP&$2JK9>8}QP*Zr=^$`=>GJ5S%^)id5G?S=^c-nARJXVCHX
z<0{t~c@!jFpuQO)@9QHD6C@S<NI{u2gOB&}c&tzN@?dc)?}BzCEew6doyPD{J>ri|
zRVDwS{Z!SN6!8;^(RHRtd=Mm?BK<xSc{R>^%A`}Ii=jH2Ss0%+NAXmr7=Zna4x@|&
z>U*Kc_T%Giu2}QPf%i(y43QscgOfAzQ5_kNtr8^iYWyqsT{2L9JnZ+*N%<g1>dMq<
z5qVenAg}eVvrObNOv=kg^|e1G?F)e8{pf@Y%ZH9!5xD)67_!e!l?>o`KW{OU@FAV)
zvHeEY`Dl2E$D}tE@~$~WYEM4)k(&2ML2`y>Re_wZOe>7cC$;FugZ%GgqYr}MBt3Rn
zO2|_Bt_BSSKAB6y3^V~RRv;fTY0m(huVI#MDmq1r`U&0gIq{@ESh>iiS}8{0bs0L#
zjdS(my5&0y>w_T4T1|omcEeZqzUwhP;wIFe1@?ROoGtNHV4Hbj{Vnx|JPKmzIY|nZ
zl(Vma5#$&l4Q-mglbH68g2`W7BuHfcNpPmQ4NLu<`1V1N{J2emM9z0X4ll3O72yL(
ztotBH{@t$O08(Br@|6jmf~NNiZW<HvBuIYW^^hPLf9)s1i3K<uN^Z2k4`M+cyq*#R
zoAB$bsrXe=41b)S=}tQQAV_XvITQ$aU3AA|Glg+D6WvLT9|XyLZ0b=Ub$u5+XNu&H
z>*Ht6<OeY_D{m63Vsd>KOZw$cWcQrtm>-0kpSEbOfW!HHroc^?#Lge5F}qVeKL~;m
zx@fY9Bl>-|;OY+I=<wvbF-iYfOnlRYVg&Xd#3okia5%itR6mH3%(`VIncnMNjCF$3
z8Ir3e2lj*Du0DVuk@oKLO-|*C`*{WH%nub65jVSqKzqBZGg~d`y2C5>PT>6@2%c|5
zgncIF?^o)C3O;O0$4}6K+q<zyJmNA>CA0XutEnF2(Dyn6k7BIW${r=~I?=-6Zcv$r
z<F<IsA07wuxi^S~7Z-24aifP9`<*TQL6D^CiXRg49%2DS6uH+wUyLnCHugUYinLuT
zGZA}Vnc;f|ZuhSUL70(8L6XAvsj80H`$7wHJW|I;w8WiE{y~tO^SpcsvDa%<jkM&V
zrvD^0eR~hC5~sbwxro@iQ@I|ahv>fDx$qyvSS@;pibDU@Llj;>?D&t<>d(ldAPD($
z@I}%8zVGc!he_hIkvi^9<o{<u^8L3%f@Jf5rCO_=`i_idpU5vdr3rWt@>~M#lu+ar
zcvY-b(4jNoz=&@vzoj5}5M-W9a)4y+g7@H+gS|=DjC!^k@+7EC2&)8%ygGw;i_XlK
z@bMJS_Y4XTf=slqN|4CAqwd*}k6}b%7UgDmcsQo6e**sZ3md8%_<Ck{_=JIPLLLM&
zEreo&g}lcGuXV~E@o@{^oK50EC{j*{=mq81llpilmQ;pOv{G)!qu`;n7=l7x12=|o
zZ%%vhadX%`5yqbdl`lhY6!QK?*!P%L<0AuKCfaxqWIm1}K_ah8i_8Yh&9c>ULmmYW
z%^1dZADS_*f~Qh`Fx0-^kS9UVk}z%W=PQx-7=7H7jC#=))XDZ9nxbSStHc1js$u8W
zfYgTBvhCF+F>|5N12U0!8l8IFQl@|sVnUt-m1|{{Ady$Dc(PZRyne`DVeei)nagFB
zAdy$EpN5<rhB%?dTgF?QkkZ5;PAJpHyu=BSz++mT%zn!*^JhUOp%GJBrlomb4sn2D
zu9{$2xo59=5QIvt9TH^Pn^*c<PxjF>7tY6RdbjL2PlC*D!{8Jl_Ik;0HVs4XO1tyt
zhjFclhwBf6-0LlI&qqm=GnLPSAT$1S2?F_Hpu^#SiGhO1=$0wyK@9nX7(T2-<?Byk
zbJn4c>~@)l=+A;mS0pwZA@6KBdaSE~`we*%WW}lkiM)DQ43poSG%47%?rD@B1UVmh
z_)g@Nb(kbv%ncL_V)ryne->0Wr&WSPUeB3>B`uRa1xMPP1nNO3G;gBXLguJ<ilDvE
z>7>4b0d7Vf1+nxgNkC?%YCj3i*{Xu&?w-Hu&w@&GCF(dL?bVdjJh`_hUW3B#mLBUt
z3`w-a@&e#J6ni|CskS~-s;w9I%FNHzL^8OdOa1{No#4;*TUxI_3#v*w!3%jm!5`2r
zRfZV2Ic`E8-^k=*s|1O>1~rTpO*zPdHS?B~>_Kdko*ZJE2J=m<tC~n?1aHYqdG;Vk
z(*u1_GgsQH52}-Z_DrA_%%}I1YJU{W%xfk=AoZ2iKrIsYi6Ji6-a{ym*)7aD5G3->
zQ@ujLRiJw}gdQs)+=Cd?#xdiGfH&Q{KV_L*?&Hbj?&;?KEXb^MGSOw8y4TNXJT@h-
z`-I^ofk!dqyjypQF$vyl608zV_GBXdc=yl9qaai2bqRL$@DGA>;=PYA9QRaw4}#3t
z$BitJSN=Ieq(2k;eSAf`r~3P|pfUok5+t&{3$C}sfuGoBCgf2NE;tH)%N&IEli+qL
zF`)~dH{?-}84bGxH;nA7TiErO@*X<(`;-OoLEzMu@<H0fR|i7ws3Vu+CzR?ZGb{dC
zK*<+Z7hvg;hm=RD;QRgPAjN!*4?^jU6GBY#_ybk`ocR%a{^y(v@<EU(Bb9=O$oZb=
z0H=K>mi*|rpQ$Dv1Q8K%i0WO)kEsr(#Fdef;g-qr&tl4V$pufqYaYIK-m+pwdW?IX
z%!l_Oo#wtvkO?+l)iQoLTQlos<kh(6;d~Hex=yW?M2`2hGAs_r>iHF!O(x(`49P&N
z!~h)cV*QpeG*Y+RbBI0&!u5Wmjz5!+z9%%Yea=W4$!TsWO8+dzM5dd>0{E$#=Pljo
zCz6{^$m9E%CpDA(00G6=OGT%2s*$s2&ae6;hAgbgEJk2|7pu2atshU!dQaZ^Acz&E
zD@B{KzP{eRM!n`#u#tD^o*ec;kU3;COAwIlJ!1m=v5{(aq?Ri8+_Mj2%uoxDyaZlT
z`GNPOW!4KMmTW&{y<h^|%zB}exbKT^KW=GqBaPXNJP9hlZkHgC{>r>$2+oZ(ypfA+
zPRsl7Hs<cF5Mucy^vo-CW`f_y?RHQ3`ydD}?siI$xq@FQQb)Ds1i~NB5PVN5{2<88
z!`Yia-g&G>Vzs?1KXD|?n}A2LSQn(D5%7Mp-HgePBN?DFAwN8hc#{=<?}g{n5t!$h
zP5I+_5%2kx9|W0(Ss7S}wD$}w+pcWQA5Sltxtsqip!Ck{fhfI<&wk4Q9dDVDmp36=
zOoB`%{i>S0CcsUoPwA!~-c+6Dm;&|3s)4Mh<sBU7gZ9H6T-mO52N&{w2S>UtCdK}I
zF^6xa$$k(-=+Jsfu&JuAf<;NUKb{&jQ*b{BM3(MNIY1+b@kIdfXe$+hhErW;_I?mV
z0NUClNaR%oX*jMl`9^zc-wAnnqsMZ~H#$>}zxpkX&W><ZUjY!&5Lw9|1UAI)?il0{
zcwS<V5;hYtB17*Fc^H`zU5V!iyyu<6w~NH-c-@S=yw4vyl%i5O*x!%VJ6Jc4lR0qD
z8F+i2Kec7PT?fuLU&S$PBjvj8*~fZA9tD{#UiWPw?{{t_%RQJV6gk7+lguMQ`OY+<
z%uGLpBd)*BwI4_Qy6V5J`(f7~-O31?`saW8`qw|H^z)gwJ`>W9AI;?O<OWHEw7nLQ
zJ<C_!X$J))r>;P}_O!kT;8K=};m7S{A+pYy+h?Sll=4XXok5E;a?NV~P<J2>g)H+1
zJIYREqKihRkw5RRUL5Lr$ltV`zt=`t0P(8rKzFiqb>=d^d82+J)44PI#*AeBeGKCK
zvV3ROc~a5&6dtTh8?N^W^r=P85wUS=T{Q8xKD8(i%NBWw(_wY$1yp{I9mffnf3JO;
zeln0cbyBpas+)ZJL`GY7ls6EGL$f($8bl&Fh|xe?%$BJ+jKCR)(;sas8W3sUHSXX?
zPbv&Y76;HE<n0_Tt!NM;@&?jb9u4dy*W$J?yk(E^@dPxQ*fsF`iLCd$I6DGbkLZT|
zz#}kDE&=&7-0KarWdp(N*vG${niyt_fv|~wv0NNtBg1pA_NGSeGi}KzIuBTHYU6><
zbb_1(Q1oV1lSUWSPLsUBBsma_5VB2GJs+!0rz81*YH*`qZDFt2`Fj`GnO)#DaDQxy
zf&R(V;4wmW=snS3J0<~dvUvwCg#1OjUNnwTRX&3TjabszI5HYYubf4TyY;EFLy9-s
zlrqi*$e8AjYciH_^_NieLz7TY`Jis$X;rOhc)&*%JV6T~@0h9)LN0G($-AjczZ(Bs
zreBT4)K-oA=H0YTzv=V9R+PN4a&533+)Vyuv0gsvjsNZ~Z8?0KmpFE@>J20o$S|uf
z9#FxdA|unTp+XMvwx?9Qben|6i<bdODoCVI^Z4*;%fXGsbs!yO7wIv6cVwlA@0LxY
z51tw^au39Nu)$eqaVWa6sT+;VSSjVpN6RS?@`H3Mg#3W!^Q7ez00myl4?7O2t+1yW
zYP{;BbjqH^A$}~NhHGm|d5vo>$U*K^&q>B>?13x`5U+7PBve7ic4$n<v!?OqBk@r$
z0gWcqU9AMaQ_U4QZjH5W>d`7XHJ4f(0+AUW@F^prHUraSRd%~^6Y~y6)%<X?1bsF{
zg3qwpFFp}{ppAJi=!4vxNlDj!p_^88L9W<1gNe0nAkjW-%{vY(6{H)BL(#f22}KKo
z?r7YdLx^q|1Bqc}K4ObQ)Z!3^Xgkp@tHekNsM)X`;=!ZT5i3<y#GS!us48g}HB<vh
zF>giTe87=xsmi=!h_0x#W)C2Km>#NBwpAs;abzustXzQjVCgn~Azq>c)?9H7K~Yte
z$;&n_poI=pCOSsaog1hjYSE4W7K?!tNv-}37R?i!5C_sx_LpmxfG8x1AE~z+2$~o(
zxfUJNaikoK-V`zno%Vi&)znCuwE&79*4_cF<Op4jm2ZnBtmrtu;Sy624|L7Z4GY$K
zQV5q?@oWyn2X{Ty&d~vNJ=8G`GwTL<^;R78HY```p?1f)w<^4OAVI;o$MW|rh4+9c
z7E8~nZ3QGN1K~8mLbJvZe{sYIe9eiK2&YMWxOLT9vyESk+Lt(t)>Z2aH2(u(?-uVB
z(|8m#nMVp(R6uGP?JHhnzpmgo)he@L!B{JQ1E=zpWJ<7kEDqs!Kwn;0O(`7GD|psM
zIqIf`2d8$Yoy8REC*Gx92nYFr#COh&l&21q9sJe^gkRzzr-eSxl=4Kp=OHO1sXTQk
z0pH6&xLd$FF(7ntC+{#a`dSBd^~o$67NkZ4zyTo`g_fWxk6s3~Rgs#=dJqija^GXm
z8Vn5VQBZ;pCcEe@q?I~#MTA?elN+Nlpu#^*J&FvBr^V?#AkY7E>MYX1t9@#2fnaPr
zgN7r21aw$SK%QCa)cgu+ticDtMj(?1^+3ktJ16Z7Ze;_FGJXW)`ls$8%w2PG;pxo_
z?8_PxbU>^KGL#;tYJv<LM@|5eW*>Ubn7pIBVs(IRX|Q*&gJY|8K97|`-Z2LwPzK`t
za_lJi_Byyd*xf~>*xzp5ji1cPu;M3kG9Wj6WC&XTd8Zt(3>t1&WGx9Kq!{Bu!}XwC
z;V8l-en6O3OhbA|`(p>*MYW?@{5x9g*(Mf8Fn>In3RE)R3SB7&{eu|FRSum)Y!gSj
ze?I~F<UMr3G+%Nr00p1OJNFjc+RCoICH(dmhxlfspS?Zguem+r4c>Kbu^_rv&G3Ef
zy4HZMvdCG2p+z8v4<M-dBh+kRAY9qC`xvr=>^j#VTD<I<FbL-<QVr6RVz8aFGfD5y
z@xn*7>tutQW=VCT@jKdiwL$1(*>Tuq%34x887!M+Z>lcY{#*7{iOMz2LjTTo-E$Dm
zRd#JlxUiPJN<)U|odMz9_)7MQQgpV?G|UgR)6okt7>h$i55<e<ZR8KFfpnDPHQbUK
zaue_Cf}&4trG_x3+1)h3a1}18uWb0nwnMuiJf_N~6{=yg*_dDfLAwLMW)s(8rO;R$
z@fK}bj~YIcZ4-j;WZO{k7H&{zy9?IP{*_JhsUc<3rWw_k5<|xs+-;qTO^6>v%BGD4
zIqr*CV+Z1G!l4(}%aV#hc<B$MU`o|EIh3yTy<%nS^sOPELlIRS-R}oMVw9qC9Rz^`
zVG@)mV~wI0g&|!Vxf}xtkvvjXbZ*xG)J#xAv91I!tUtEkzUl0SJ15An1F(1orFb=m
ztujLp)yfum<Cb8!UJ1pU_1RbC6BUV|^NRF26OYBUbomYHUdGgnU_g>hJK)ruSQkKV
z3bM`xP&7v>Yviv4jrg~_XGfD7O40pVCnCS&;t<=sqB(S7F;K`C(JLD6te!(CDjVc6
zP7;dtlry-I<9mhMaEW&moE@2q$qLiw;0nFC<8@SBdl#;=<UbC?R{`;4lN_fY0lNRt
zhJ;_I#E?DEv^xcP&;YOomCZ}&*YI6l9Ey%D*z!y>8QDag+7`XUOk+ChlyKG&|E)vu
z0J<^uA(JK@ch`aNJxDklsk#<Gk!DOcEU*L@g@hUceTxDpha<MXYeT^gZN*4=W^qj|
zrWK3nmaXeYafXtg4T+ToXEKUWGhOXLOk7MK0-~A8>HO^u+sJ?BCoK4H7n4m6&iMn0
z;aHJbFx9^+)*{1MdU3Dp7>}yo!Ii*t?m{rP=TwVPTyaTY?A_u}cc9~e0ud~@2vrye
zzU7tK<D^1dZSf-J?TUfdqK(8F#dIcTKIPCW<1#r?&2bvwHd#{DydodE7)=HexgmA4
zV`i*&&?E<c_M+Ih;fXzJ*SL>17~V^xwqPLsO*QSLh@Q!Wi4E7uLLKw~B3~Y7_dtBC
z8y9w0rxZmLHl&9sEh3y6E|R0%Ai#W!Jl-{2Brjw^k?%k?HZQOWm;#OV#(_i^b=9Kd
zb5Y>oVAu0L>Z*q+MJ4+PJ5GzYGE1Xz1j9$XG}CJuDvkqXKERi@-?CY@lZQ~{;v7&6
zjj4&T*R-Y<;?ybidc%Ek84zEFW2RK@7vd%KA}10J;|%mFt<qFDg1Vw}`3*Mamlpf<
zK$Hp77meXr9{nJ*>VTqmD@xI`{A}C7te8bF@+(z~uhvUT{Btz;*!2@=@3HA8(B1<Z
zhobTZ61USvHQ(@`_piUvRdpaS&9U9JxN{a+4;mA5wUwtAXWN7jdw~;bMH4ukxM&Oy
z_2{RS_P7>#%G#>hF?s8$+TpZPPu9*)CNfjFr@yyR%;Li_-P>4CRjw$pF21@0(`81y
z1noeB-$aqIqrsd$5L9LL0xH71WR)9p+hIg2mG{U2MRsN_O-$2OxmP!2Tq}w|Y&$#~
zTnul+`L`Y@dFNMd?~Td0D(OKQ?2AaCya0-f%B=7vA=VeiT^ydj5ldTSscCy>|8J@;
zR-{T58G{Fk%sGvDu_~>3EsSXKL#&TUjP+>}V|^NWOG{*2Jr~dT%o-ulTkWb5F1xZ8
zjez7BaIKMh39VYG(864Z7dQr-A|0ieQKq-9UW&;QVF8OH_~t<jU0`jx%KkS#XWSGW
zi8{mm#S=!yRf%!iOxr!mk>OdZ;I>OB>IvgYk$GyNZ~lPLhp?3}8+ITe#^d=wLP`eA
zwsnc&tJtt#)rL~TzoU;f&Wy@_GMr|s7GYdDi(E-B#7mea8z%+LrVaLj;@6hws1}Ll
z@rzJ>D7*SVYUHA4XLAvusbwHN<`pj=0}3fG;5t)_8pqV&MSaE$+=UmV2A`OM@Vr1M
z)={Pq29=6)+@Qu%+7C3Dx{eF+5~ereBOJkNc1gr*cK;hDqNeocTEO8AGmw}{R9Y(}
zn3VGaaW{|~ga`aLWNK_wPb(MLKwP45&F@fem%{sh!`-vUKsgZKlFEtZM4I_>s?%^c
z2`ZfhkoR;s*`k<2rSMFOlK+JTqVROuIu{7J9Jh``Z8_8$XtI<$q~X$7l!l~*M@{??
znnQ(e33bINdvkQkHOz`a=O?BP7zlSUk7>97{OzlI(Y}IA%#K9$L$h0;(;UUvc*F<W
zz^da2UJE^L*;V&&5^==KaVHyP9v}?geW4RT1Ko=w(Q{O>(k|S<&oY1#z66abRq@U?
zaOn&L-!>JUGAB3C{SCw~gx?+;5wk;El;O~TEYjbi&nZQlmLVs3i39)AsFy6f+cv5k
zi|zo3{wvD2*QjPJJoNj0XK?_l4+wUOxPTit_lg|l8!j^giSfhLWhq7594;$GsdE}G
zCq<TWW<ME7M>)EyYy6t&5w^kf5Zb^`R9B3~Pqb_N8op9y4H;1u2ikxEZTv{7)M^Mw
zy$~<KjU$WW2Wiv)|5<yRp51aJTWG$2MGm_MRoIU3*A$711Oo&VBgEvQ+eqm2fQznx
zf6wEHwU+mrUHN9_saBP$j^lm29rm`pm%}R}%&-Z6kz{p!soTbDyr-RrH&J!#ZvcvK
z32=YqC%*9&y#!&?tct^IEp5Ew7Z@V49tkE4&{s(Ey|$dV&sR|nrO-i!l6?yR^%+}$
z&K@avAmK>h6)^$*7fC)AFNk)^3hUn!qMV63vbD4rd=cc-B+t<R8?Gc{m32G^eZc+O
z7fH(}V~oqc8Nb3^S)*0A#s-3=vB7B7sh4*pSUj31%nM&>O*Lr$Rl<de30xaXG3d2w
z>0n4RI>Ji;L)B}_7w+v{AJ&q4yPBby>5GIr1Rp%|y<EWrSiY;Y+#Mq4O&RY(|MkKz
zu654uDlJM?Sh_g7NP($~cyBZzVfT8{l>}P~-ad#6UnRfV1xsZgIj>69zK9oDa0T^}
z6!jY01Z_`}JjdJQvn7B2d7L{2J_R}04e?8A<<X?^?=h?m<OE0_i1-<b!EMNyaK8*k
zGVo=%k{C(x;2JZg>zi{V{B&Ijzc2&(_8cY(PJ~Si6F+!u^DE7dVq>oK3aWJ5u5K?V
z=+Bp;so(iNj^zFI{Slrd>~{_|e)D|k!u^rsM@@s1y1c&O=;W7g_yZ9?;_TD?h@(&U
zBMy~m2ZH4JA!n3VFPK^W_5$pK4;G0Mw|Zigmb8MzSC}-&4o-}dk^wY@DS%`w7d#zz
z6#z(@^Be6tf^H{x?E(zLyFt9E3jmKKkMlx_49uG-ve86SmpZ{!x}-6`*z(9|s|l^<
zR9{tKmA%Rj_fns#TFUpG!GF<IKBS-u`&?87Gk9**$akB>0ATiPI2i^P#J9<}P1{eS
z-6l=~EtBz_LjrJiqs^w$oYcS+sG>_Y(AulAB{y)*aYo4p%_w4mBk1!z<+L=}=y*a8
zqIWYLw|P9&G(<LwX3#+-PJgxJ>=GMtRf4ghO;;_<sA;Ulp)`#H$C4(!+)dBQ0TZCM
zqSmpk<0u-ANT`H2i;PnDK>NTG>2>0zE0T`I;d*owY!wB=NxO7P5}>uJ_r?>to{FU7
zucwZ{hK+ya;T#|MCOZucvFWH3=XX33M=_n~>8Zps|0(z9WfW**stN`lfgi3BBm9(L
z2w}s6MzyB4hpMsdu4)}+T2I(`r<o@^=&Ham@?RNtT9{}|n%NgS72K8{+Ok5_WT?uO
zI-2TWE{!HT6*kzByU25_WNa$7k>(l#?Dw*xH4r7Qtu4~mrXB7<v7wyLl#Pb4y&=zE
zZ9ERNOolD<-;<6@urWfnjw_``{MC|uAPZwd?1`{Krfy;!wmgls%xoE!OFV;?8UmF@
z!eJ9S=_5;cgPpIOhteZq6)ejBGTP!H*Jzu!aZGSfo4%BtHrx2*b(-e%$?Kd60vSC$
z6R)|L86RrXhm?jI*_~U5!A_saUU9iAzk){go-Ew0SJq;eV6SN~c{G}9+9Y?Uk&M?E
zhmN@=u05W~uq*u@8tgR<_L?UgoLC9ditN0m&y_FM!caI6VWZLMp$}ACU7+!)%M3Km
z8A0P0(}Pz<KWIK^Cf9cEoE6%=X}Ph2QeK(S-Ulx!TmwCjpa#brZc_I`srkJL%0YM2
z^%e{R4OipUcyWCsyx;05=k;RM=mGy3?X8h$B`>O~-d#=sYZ^V?LpP2duc4c|z$2w;
zOZ37kzL%t;TK3BD;V^BA5x=*Z2{#}r$Pr;0lV7HL%!Zrpd)Eo)D&B{l(IT15v{xdM
zYc)sd>s2g0tL}AeGdMroE8b?jjCS>4#GNq~Aq_>kMQ(O)qX}t@v!<&h-A1#WdmGJm
zIBB|IgK^eiA2d@XK8Dk%YZN$(csukonv>)?)(jWUI%ya$oQE{Vnca9qFq(elp>~|B
zvMu3snx0JiPdZ>#h1oscRcYEWfpR1xuErmb0ReSMk24|VypaSY;(>$|2#ihRCA2Ut
z?iVlHqG4OCnbh}zC})5`Ya3YLTMxq7(s_^DXjjUWln)}`i2fuEpV#Wz7aER=F5pB$
zThdqZLBNU%X43$7sxlTgnvD<wy8(GsZ=}h5M3;UOzEHt%5n#cU#*yIF0n%Qg51gZ(
z5aBs6G%1jHtHBh)#sau~2}cd*g&-t7=}8rBXg%R<b7@Vjl5j+GZL1_44V3bL<FqPN
zvW@g<7wb$PVVwCv+=3)l-eq^S$`?KP<m4J@Hm8;763FOUb(m;G$1r_X`TI7Q?kWN>
zH6(|t%<UZM`l5q8T}7(A97>&OL`KsW4vthu!r^Wt>7kTsxEBpKh-h73FA&k>7JUR+
z<~RXg_Im)RBsTK<hO~jTlVKHZRl&m4RIlKpfTVbKymGmXc-0X$=5ifRIe3{m0u->A
zy6}F1<6f{RA&BAb{7w~oU^*{y8%b@Q*S`%BRcpGTM=wj7vb#Q1B`%M;5Ix+ks(jlU
za!Lk|6h<dn8@u3n!3HD0`6EdJrc+~bZe4A`zFHNd?D$gU=yg3AR}`Jr!;b`n+v7(S
zBRODvJc9hOHh4r_JxpIVfs<?(<Sa>?6}~Ka1AQbMgZ82rr%P3El2y(z69Obnu3u{d
zEt8$dt<w0YV0lMU!L&~GkK<EHDv@nPsMb2Fs^QXL@Q76p|7>uaE3AgY^;FNBDh0qe
zk`6|CuGUJX*ckc^tiOt^Q8(GlgF6ttk?NRw5cdADUXqrad55}{BznXS2<M|Sq~nej
zEC;iolx_~V)~@?H2*4|;h8^L7pofn^zQ9vX_XZyBD~V;3TrD~(RYp^JLInQ?%%#ZJ
zd)~$5SM2yIrMCr7>XjD8sqa`N)l3mzj-;grMs{bdDCECkW|%l+A3={xj>%6}_&SBQ
zT#-i-GiPcVtN{-cDmLVSf)9RO^xx@Hj1D|RUX?b=IiMbn8xt@q(mUtNnNkm*lsTnd
z!pS+MU0hjBE;&?rl!g3NXT2VqWmBE((Rw{KM?qd4m8Mbo79Gh~|08;1$&ZP?Sn1~U
zDLpS2sBpr{KXR!g;cZooS<d)X)c~E}8aId|N)NfF=hAJhsXJ9}Uu>zSa_C8c9dVgj
z%Ehp>H;@vyTvHvmY4JX+PLi$_y0?-lw={nycB{o}4mxMmMGRiSlw%(4lyrFFRfHnB
zzIzpMN3MTgx@MjA(NW6J|5|(=9oZOXs!lqx5oS~p>y}<{PF5`Y2a?zUw_fX{2WXLY
zLvD}Mj_#e6gj6oD$ia<ju-xvd@r6}?Yu^ZmE+iNKkxM%pH+2i-%x&rxF6%eZEw+dw
zz{{r7*V*86XQ8!s>-Eoc_v8VxPP%*Y_w;%-_OQwCl>>us>ejx2z<zZPwhQteuDPBc
zbR1*K?i8dStUewS)`30s=I~{}XYfZlkM$7TpXAu_dt4C{f*;tB<Odk9vCv^v-y6n%
zh+uX3X^C$*9*95>rD*68VJScT4@50%E!7Hdd<A8%2&&Z-`@AB!;sGJJG(Mtm^Dp|Q
zFdRe##)He6&`(OjWnL3wtbjD}lT8U8frW(3H`krLX2i}wVEKOF)D}MR_+lV7S9;CU
z#jPo_K5+oiUr1hF`GFkL&z=*7As@=nkRWJI;T{5BV=MZ=jDaDVG+_jk31zdp9lg`X
z0&!;pYde2~um>n*5S+5rnGW}OO&nmVBf-4M5UHP&0SXx&qVOnuL>V7KGY0{8KZg>O
zGA@O%$?yyefnOV(|7+D48e&E0%Ym3<H!Q`GWFs_M9Z8%D7~J9`$j}$4fH({ykyONC
zsE(f_3IoVBPl~eH{;HF~FS=ePLcWL%P?3bG;kx`uQO3g%)MW4l-P6{jcHRgi74gp$
zq~r-v#KX|nWFR;UuQcnZI<Nmo;2r8NRY(xocriz8-gJK!lB2A$p$DQrt?06>#$`oo
zMPG@5$ZyI|Uh@K@wfd?Py0*$`U(#-pzwhv!Z6ehkQ3UD1SEM4;aueH^r;irY-pUve
zX|Z`A%J?+eIv6;jIZ7GNMw>!sXc|`y;P?#LQyD@+ByIS2Hr<9)gnnqEh*wZ!k0ddC
zUb-}0T2us(Yr0MNNTQUDPK7Yy?-5?EiN{~Tugz5PKj<@>!ID%d72B^m8RBQ(F`F0@
zZ2~xLHhD>WBvIl3AR4E#RD~q8liNo{jEW|2k&wh=>#JISMVhLe!NC+~4$i6#S*cSH
z182gBeITqA8Cw-B;V|iX7&hVn9*@TQPcPR~ymd0Fl~zB3Uoe<g_`yD}XkT&6k8#lH
z;w71^lRcW!zh{R;Osxp3-)!DW*`cLMjt&VWbVeFm+P@HEqnVBdxIJq~;z#2}Gp+uP
zaAf!0gACvNzI@d3I{_Ra-fpD~@m61TGNxU<Z!)9%IQIiYB#cWH^)h4H-7UfMT1Lv|
zp0DJU6?cEl?dlTuKhy&OXyr^9k~2!~yj-rCFMxMVDTuis6DUngM*{5)!2qc{T+^FO
zo-ka!;sb`HWPCtQA&a{-PM?OTeR7zo8H^-E*wfR9#+$qpq_(uGhooeXM1GTSof&Zx
zeSN9+mSjxF!cxX!>})1`*zbF9h>m&RJHiz8yXx`9?DsXpYpwPBo)I^#-*;W#F)8U;
zeS=ogLfJSeQq(gXrhXFBvUd$IKC*IYuZT{0B)CMcd1KqUzTPn=_aznt*_3Ii<D=U7
zE$;y2O;)*zs4T5dy`+*oq*1zJT$=(6&;<On&KlWe9Sz|h-mY0LZNfn);3k0hap@ZJ
zutV2M#}18p)u-U4{psPTFYU97qrLQxE{^un|8#NKm%>Z=RMoCxjNxi8<x=8OF4-Wd
z7y^T~L8^6i0*fIOkGu0W^u_ixkF^L`@hVX@*zZAac_0e)>Aiad@wx`LZ3(n(V`(vJ
zFv`y>tZ;?X#SK0DmSD!=e&NP2hU5wEP~)RB67n5}jFf!GAlAaHuQ5nT+;vt2_c=tU
zI|wP!As$yB<XpWa`B{A`wwyNo)x(tZm-Z1cdR*P3yk0G52*JtAM2LdbcY7FNv+dPI
z#L;&BB3fQuz*VC0R`2v+&DRT{<SHB^k-?sxFQWZYI>vMDm(C&C<u!mk%3x?vP+v19
zUiGf8PQ-M$#+H}l>#S0oEKR&^?^$)mZ`*5DQF6O^NH$H@7R>qW?{!lm?E8D&?EdO;
zth7C3nR<!%MJPcj=GP!gu5Bfj`<B_XgD}^&Ebtvii_K*P;QK1)0Nqta$tE9(SBP!j
zWd=OG?=s7zAJ=dK_a%ej<avwqgWiJeZEE^F?MOICiNUSZS37~mtu&52QoR%zPZ0y-
zNVotpt%JRkJ3X;tca|dKR`FMt?V3c;WmA|yby--*VUswb*}rHa@B>YRe548aRacRz
zueG$9_pOC4^Yzw37oB)C*1WuW?(pi&i(B5~(ZF8j#$wmZfskZYxiTL{H!($@%*$b`
z<y9&Apa_-~5v8rxSDpA^SS8G5Zm%l*1E;woxof<}bJ}Y!3tG|<-L=<_KK9z9j_b$Q
z-P)@CYWuP3@5LA|My@N|OpG2x+!jne9oPkoZWGU2@^xRhX-T;3O<n~2RGYZ|4_CVd
zS)F*m#4+bBxrtC-k-Dtv5~ag7WpY#GO}deQP4r^&hpatQ(-dLA0*MaA6>sDXtWL|V
zylTZfYnm`XmzLBHK*=5sMBMDs>SNbT0$^)0lQ4-~V}(F7CQsvvAcFQXiy#+^$gh<N
z*W{F4lf3vCxvmv{r`G&cDaNh&t5T1$s>EDr@+`t(<R<mudBx-j&qEEo#eT#oDAgUZ
zbm6FEqF*9p)A3AGrBwGKYJ<A-RVPr9wTr0@!+S9`QhzFV15bp;fDb%0KH;{<qiHzt
z-NSdxR4ebJ>3OQv*I_oMht+$~&ttNQEJ(tES$iMZkHYpk1II`pLI@7}F&2s}k_U2A
zMsyz8!~OA#DS$4LvHH?pKsU<#QM@X<#xUgOF&ZY~H7Pw;S~DK`Z@z2jb+ghvPjw8<
zecQRWJZAIO>fud#>*To1SDl$Tzf>buxhbmR;aS|&Wwaa}*H_dSUkZ4qTTPB!GNPT)
zK6PAfRjEgjvmbe#yu7L$ErS9|gH|jM*Ij*|@&%4k>Y*fWH6y~B-#G%Ju)Pc=nHG-I
zDxs43wVK5!nO~zBzJN)LrHwKsqmm3%IQ^S45s)Neu00`#*O1QO!EbhEo1-CD4%$(I
zau*OHvy#hd29FsN5sb!O^ZBZk%H59xvMDME*|9lWe*I~-&ZhMt7)Z_K`&P-(7J9%z
z+3;b6fj{PW8cIO-r;~k3VxIJSOA;Rfk+E<g@X(<jq8M6HuXwd^Qxfvl!bHcywZ>z;
zy)G?6-)mhN$P9O_D<gN;uK6+YLt#m+dLW7s@48~c&e`u38xvaIJ2uZ?3c5|o_t>>P
z;ONdk4nKJ1WL-CC4*l=#3AU89xI7R=2Xtr~9UWjufQoE5CLUCU*NI_yJU_%CvM$3a
zI7DA1F+CaAu_8dbA>Q<lq!7jS)bHKe!0WtsYq{Oo$XSzDizhzEy=;s-Y8$$;$Nl7y
zaI}D$WvpRR$Z>C8K(Mi)s~14)AxrxJY##Sg7U|oDV8zHiW7vaIw)4KGjaNBL>c$A!
zwca4izrlL*<ZbX7mTRy<SW_FFJ=*A^Kmd6_hQGxCyj1+q=Mbsv(!FqfZ9_+pnRZJX
zI)Wepf+_n_T#^S^zeXLTR<NN>WdhU<erG1~8V?y@XU%S3md<1fTo~SwH^PPt?=zs)
z6u<z#%9P8hW*UnpgZ_xy5DR&N`49nvz7Qj9UX}(@1wxnS2MHE7wKIT&!DvN4#M7{8
zD8(o$+gHu(Bu~agDx`zNQ}xy-fW?%tHvX=wSfpC9>4HX}oiIq#4{=irJel!I<4h)t
zU6axrIHg{u7jrDmJ16kzo%-@jtfu*e!V~9-%jIHX!zlv<QXAP6jRzmfneF6BZ7S*u
zxmh*^E+!`V+-e3VrX|bmx~aZ7PM~esDx`LutJxDtEdL!^EPYc}?i-9o_Ja|#pA1>n
zNy|F#=L>TyYc<uvd|t9Jtp>!l^bG;g>*fWo@Y6jKywzn<BAF{cLyOTNNc^&eTRK!^
zI`@?10Qi06U%Mj4W%=BB8v~h>Jaz<G23B9X!(Ygct2BWOdVVAX58#*C(sv2;vIvZa
z4g=XPQGmceJQ7-x7m((9^B8S$e*yjM2srwQA(se2Yd#Sc@X{x<L&7Wz-;JgDw(tp9
z0<()Ka^DGu<*>C0A#C803{gZw`>jvX0>H9;8H0e5*Nh3}ZS$K1^=*@idS=3Inh9s;
zG@3Y98XUF&%z`oD63jMi1zTIy#<DpgQhu>Qwst0v;UX3#euE8vUj{P4+P)m*ifXzo
z-bg3DIqkq4J_42pen7+x^DHB9rX(BJb<@V&-18;LzE91~jTx}@zV}op(;vYl`zUoH
zqVmuAf+9vLTE=d5BB`>W+?!naRY?Q)avAtJF<fLVCFJm8s+QK26ZVxf_KIqkPM@1j
z1dA21J&d(pF2O#xn6E!d9pxcbazpZRN%#P@5vW!_%JwfWKehFe-2B`loV>0ha8E&c
z?80Q~ML``(j}qM%x++{r)==byGM*@MEJwbjOXWYuOD~tmpJ2wzCG+P22{D1`B$4mv
zGW;h-jovMIqL+<Qj=cP|(&G9=EMkuQLU-i-l21DVHj{tmcqY*ETIg636Rs8xC?;3E
zelPjC^Lia$av$=lpmX8q64m6SSuwdPzj4Sq#E8y6l$gjXD+IyEmDA`j&CbYIIjGkL
zb(?g_y~jmL3o_a{@}8j7bXPJyhu%o%<K&g!NG4}GlIw~TZ?GbnS3}4kXS^Z0FL{*@
zI>H0F*li85bR3l*dP*GuN2R0b>k8KO7))Wrj&Vh<dKzM%xL9#5gO<1g>ogc_ok76J
zVRM;-!C}kj<9y6QTXG1G7#oa6p5>UBH+o6sESemwjZP`#NaHM$M_A)5lIt{_^}GtP
zw}u&@pcaiYKn~3aWA8U&1p-<+!UjGe$<bndp`fCjZYpBop`y7$90u|1=+fx9mG1nH
zg4O>Bs#(uy_Rt@%vH|_mAJS!4rq5)=$)`W$fF|<gYBR#>|BxT1-w+M()pUix1oP|(
z5me26$ZrgWmRBu)<1oPT>Wl{3;8*TVS*0@JU#1s82l1Yj^Nwi){RUz{Of}{$cv93u
zaJ^x3ocynJq0PtAJrePenF--XP|wgweVLB?Zj_;lH9eK8;FEKMEWnpK5;I_5Hco`D
zwy^YXTm{40SJc=mNn>P6@;TRexMwN}sGHwCZ*m;&c(?iz8DjVN4Uz!I<0E;wYe&oa
z9KogA6}bTEG#}>1NKw|xXJC!DrGbexE(1OJYo6}I@=y<b6{7&*3;hNuuvl@f7zL!O
zIYJaXDav=C7zGvDyaYY-fn=AR)8U3J09VOhAqyImkvB37uP(l1gW=UpZk|pIA{r%9
zw>rXCleBiq3@(s!{VmC<?ItR2L*f8eHqIl7rJ}ot!&*D*iy1smIbJronNKFDMWq|9
zAx2AdO%mB$QN>AQb5kk%*wn|FEyEEM7sIY_=j64yDX<HYLm{)v15sAfu7W#MzflZu
zV|pZP`y3%oxuX;ZdpGSexTAE2Y;SqH=r<4o_*H%bA>c02O_%Hq4z(`+X~Q+2>$0W6
zVC#xG-@uD=^BW>1HX5Tbwc#$!O}kUalu2zJlkA3eaZWN}-z0dt-QX@A(@a<xmoIKN
zyh~>#&N6Up{f0~E_`oR6K?CF0m1v;BNi`&JR0e6;c|FwNnCf=p!YtL|FIXjCT=3ys
zIS|N)bGsp7wyH2}Pf;qPAIcj3xG9(mZ2B&yE;EvU{Y^er&bP3r#)I&VU{ZDE8g4MD
z`i;SW%#nUWFu(vG4`Mtcd@wR9!{GKH6oZ&ZZ%J3$r{{;FD!FncGwzZra|L5FxsqFu
z1;->)&ksd;a^nF4fuJHa6$WCW*V>T>-?Xgc3_0aDv;*8~Ljr|x&;Vz-Aup`!UM{F|
zu_ueQoZ+!twB`motKWzbun>D>3u)mH6&bx4Xbi^+*M<!bs#m+SzMF)b)~nHp2;1*g
z^9L9aQ0x3gt$^LtmDPk~JC7^I2a*_B(XSB$&2L-_WMn=Pgq-szFd!O&S-aA$G-RE2
zPc?d^NMnFEOq&}MV`AE5Ae#uNhH0ZDFAYZ3BYB0AL#<S5;uWx^r-gf@D=$og(G?B-
z2m&DMu$_e}?EAvLu4eEd&;{#}bSV3Z(FbMmI#+J}E>Fm|igZCO_^-ZeRXv&U4Xd8K
z5I!W`XZ=PGfnC)j%X))1tcwTV(k$vXxX6MZr0Y_+!Kmr3s0(2;btUs@uvZ>QP6{|S
zySLlNPE8bzu}d4w;gwbiHxvSG+^{7XJ@N_Bml%^Nfi4r%jbB<=5l=HWaOIgd4;#X=
ze>Jo*6>dAR>Rk{3PVd=DM&863!FAl;_@c{&puqy@uCM;C=y7WFL-9J_&#Cvxcuu`f
z)^qq|J*a8?FgX!pG%_`2w_w5a8}?<JhL2nFb|rU=lC;5FgM%!SJEkPHiSSIjb4tl3
z2lrQ|mHd&M&Cuj6Nlg^&j#fx_9lNp>1W3il++~N@_?#=_)gfHwX5wUSG&r}02rVb#
zcg3|XIOu<oI69EWaf9<JCBeC@(4WzKfy`VXmkW@Y%LrnHD^?M`3s-GE7Auy8e8)GG
zva`fk#W^N7Y%)IOF9~3p-?+(P1YmEU<X>_iF#tnqqPq#d-{pZZWA_)o4Q~<Oac&A$
z?kh9=W^3?s`X8QTewDw7vhiFGhZBhzC`r?s$Ae*lgXDn-Z=TOxdaEx9ULwY?ZncH;
zptZumz-vK_rmqroJxcBVOG^@G5^MHaT!yGocL9=D_f=xp4lu4QBbmG<U7H-<M%sS9
zl(9Ks43P~II}wAdb5FqlwV@7Rpxe-%LdjGga3V3}^0|Ag(d47O-4Ji^R}wUa4-NTu
zNGuz{?Y|V%GG;Q4+jkE%L$HIdBDS16iDh`dyStK)_f^903{nkLjUW1mU~I1**?s?*
zUpT?y`;-X^3|~nz%?6YPzPp$$H2mlzYsR_J2pcRz*11?+WaYiys&$Q9hDx{o^?f}-
zvisEwvvFS-Ix{&+D7k;t7tW_|g_poYN0~^%^a~;hs=G1L%8>(Xd~uCs+{0fk_%Xyr
zy!glfW8D>g#GFf+Aj^P5FIY2xv<v7+sq+lk_&}6c4buh4=)zjV*j@-~m|Oy>PtxiD
z1M|($Oe3so-X+2A<6O2yA07wzQtmV-03*6T64uJq<b+?!#FJF}JOE&&_|jRVqs)^C
zdqty*^5!6%D2_ZiTxq#A=FI_}JkCkzCSI}5QRK<-gokuBd2YfOgDA(`$UnrByGKVR
z$8n>{p2xAyL^~Alp-l%;K9t9BCF8+a3(tIhkp9NB%s+zOmS&fY(${mZ(c*Fw^nfm{
z<Fg?em@8JIft$)hcS`!}SZ<xBHW^CEeshIo4E9@;(VeL}9HONvID=W|dtUg#g7pG#
zJ!x;(oI%>#HF<#b_Ph)uHh|7dY1|Mq;96lUsg~DBa|mmBqju9>g4X8rs5a0f!~BB>
zW4pddF*CK6GrVX@a$X`$=4h&e=?-3-n^NR}*Cu<`6Cze)A83(P5{H3pT7Kf>x*bWz
z$9YRIsPI<2hB||{;<e=&qJX$!pFRd|Vu*5jf{B<mLK`#8hg1YRgYsvBP3WeOC^oW~
zf9BM<3FJ6ElyY-y*)cI22AmUJ#Bv*3)i4ne^xRE|ZI)jdO>L4%pcu0@udNmDdR|*A
z_Lo^@8%Fb!mpZ18;A}7s<2_E=TJ?oP=%8zvwg@!@+w}thD`7N1a&yyXFgzpu=I#VJ
z&Pn-ykl^tBldi{7+o8u&-`pOQ_-!Hr!x81XrMcy1{6x-1XU@+_a~zE;q`2ix!2=2F
z@I6tY&&yo8$bfQN*B@cjOi`|WrSHt>WUk20htq}&5R`a(gLl6`*SvQzhxc|bYl8QN
z>l;i(+Gm<Fz0p3?w%#HVMZ|+pW+l8s(B5=$#H^vbZTgWsxc7w=bC2FTE9NJ?_gc(g
z>WJV$BAnk`od|Q5*J*}y8h(>*(x!8hZmzs5z9~1sK)W}4k)+l0G3XBN_;no^lr~%<
z?lfH(Lh|{|vAJLcZrD^8Y`_Zf4%S<ywa1RN@&}m4i}%IKinDlMto&h%7slEwgDv*t
z?J8;kcPMY>;(f6W;hQ&vI_QJu_QYLpwgrNiD-i$5>FYN|CUX9|g8efwus3<xF?(>_
zUZYym1vhGOj@@j+oMWanvzzX`F`u{bIoV5i^Bw_S9GGqQO8#M*WnJ4d6Z5^=N3!O7
z`yaeE@B!FQgxB_)!4iJImr!6CFU@bd%FSzKZB&St_PEkY7y_mp3H8BF)wDD1nHnn7
zFbzvLDv@nY9p0DP=F}+~L43e&0?8d#L}q?`PB|$h1guU=lc*rUtlR5F7jYzWa(NX#
z9uFZ3JWM--B$Xo@&y{WF5bcskLnkLs!rK#~(2rz1SMI||guas|V`wW`M^nlHvev<|
zI-=~sP%mMFQu-q=$;P=4$%ebSghae9N6<_K?~0e@=``%j<#pI_*+bVufLE#@h{I~d
zEOH(m!d_{mVY>S-KS-j`{YgfQb43Ir9qve|D~v|fq%FQ%)%f6z9U{DL50}j=J+eV%
zyQDD^*SvDFA4w{PZ}1cU%(uk@W&Av51`mQxvsmRJFB$<`4nC8lrnwxJNjp0dytB%w
zQCLEa>|P})L4ME<_u)(A`wVK7*lACWqLu;(W-)ene_)t-;m6S7Oe_W>$z$<WP)<H3
zuPPs}q)RU8HeO^%ufJkTk~nq=m74FDa!D@PrDby2Tq36<(P(fzQ3f>>sL07(D?_?r
zrxELvd&6a~I)br-z4|~DBuWD8&%UI!`6Fp!F_JXEA4ztSC|Mg|P;j#YV2b5F@I%|E
z7tU+!*j{+=!!27I&JTSJxGSY32c}6KOgY6eh)+>;Tf{Sdzg%G=$>Q=-)C+vK6kL+L
zE+?P(hrYwExRs8uZC;8V4R_PM_2>>F_9g|N;3D__AHpYw;T!m?Hs&^?gjJRNr^ghw
z;=nW8lY_hYA-o05l4Ri6rZv|y{YY@sQOuUpsz!Vd{P05un1f2Pl-zKosN$i=cKItS
zBon{fCj^x~b_7e`;)P*|bKfb!{_EhH5rX~D+0&NB#xT5#9IyMEsn3mmq^}m(Cbk$<
zncNbK=(;?08$<7cAo7HSf&upnycn1bY;~!d5cNo~HjpdBmePgLv|$PtOkT$IJ2}=7
zQ_NvlSQ4+JoUR7TQOsd8>JC3R1vYjBX|rWg9swLy(|m``?1(Vmoi0IK$xeqLLn(Vg
zf3CC&J|RKNo`1)?!X-b?ML%TeJQ8fIFqq<e^+1#(t#200v$p6H?;y(YB$tvL7ZERL
zQNDgqG*sK<xsC>Jo12}+q@Ek4=%RuJol6@YQ-A!zyUOdo#S5tG<HgHJn@VKO>n~FT
zZ%-Os9IVj}X7$v^1o?~%Y4n~HWe<5Oa`-~q)V|<w0-9ZIg=hIp-w_Yb=;!4E=dk)7
z36>AS$Q=ovI^|TC(-2Wu9(dkCl)ifU!o=8{X2Zf$O)bL_bQ*8yoRLwcp_Grjvo>7}
z+5L@2@|57d>AhFge@y+EwhHfs_Mj}`5wvF?Nou9MP>yhE7BTl7kwXRz)6Os<gXUmW
z7(CT`NBBY;Q%%$TQ@EqU{ZktmBXo?|$QX-bOieAu-Wc555Jp1|t&V(T*W=aUt1YkC
zCq(I0N_5ST7;>(4#=jT>7>J-p!{zyAq>1}TFt3s7{yOqHBVG)iS3N^cjHZ@=-%a7)
z9Fh2J=+*cBazb_x53lR8BT}D@qEEGcq+JBT`)FcLNw|;;voaP$&kx(Di&%1fYlKI7
zkn4cf>D9f|MSNiT;`jnjnxgnQ!#VUjLGa1xcY<JL_B%ru@TpG}(^Y+F=-{r`wQ0bX
zZ(W-Pn3ER0e;~<*y2c8jkCdat5na%_CJmM=f`6PXtEZPgb-|}f`BIz#8@i*E11J31
zH=`Sv)Q1aqH>nR7J|=~6yie;oP$3CoMmI?H2SNt*`l_`vNCGAi$eq>&B_n>Zby*4=
zA&!rT4@vEGa)QUbxxP!doG@nlc|z1ORs?GyCXhmLI_9=1T&E+dqWL}Qq@%t;Sztcp
zIC88Qa~<#zhWaBxDZ`Q|THz7(46&gK(P7u@8Su?@d}6SYO@tHAun|w(U2+W4VHe~c
zXVeI>fsQ1@jNA&@u3|hMQ8sL^O4&4RRt~bOIW1I2l1(*%(}CbQUey}lDyV>`oK00V
z1>Z?tpPrWpFJ47)3CYeMv06vOoh=PBKFxmBiF1<z%J={{usavv(r$My050&x&avMk
z%*_K)2IbLyG8n2x`^muhMOSGK7O&kqFlX2b-EcW_;g~M3Jikacz>gz=P6hz-aU73z
z8{`P3a3csENdzl$6jBF!RZyIw2Lc2tVkx@OUKMgY+N*`o(C(j~U)9Lrx;5ajY>lOz
zL6}%$DN>Wv0>&{uAfq&uSCx!LR9=llAS|6a2Y9L0?i|4>plOOE&^YWEPAgy|W$bhW
z%y>+f0*;Id*5<2P2FtpYGE&!k)yc3|L$(J-)qwfl5sczfW+^Jjwuh_{rby_X!75H4
z`G5=;b}OV7njQ#cVe;ZSl2k(e6wVkN%~UPoq5YdG+8n^%Hd(8EB9Dd1Htk5DWU?|l
z@@klj%03n3?N$m$0Yjc>pEt%Ew#h)Krhxj+_#n!3?K4Z^DiuY<xzlHZ;X<ypIFpMQ
zvW`2zvnk=ZPefxjB~tecDN?7Zq#81P0gqc9QZ->`x_CZcYW3GsvsTx05&Q2xHe>(s
zto--{daXKUoLD85SG^9ByV1qfao1{<thSJ3AVmQN1R;r#h!_NfIH`AT;Cpkew9^=o
zkv5cx570H!;vU!Pof`Ng)jKsj2#s7kNM4m3$1G<L?!3UU^IB5lD%i?ajf|vH_Nz*0
zU)HNiESRFxETXNHrNKl73oE=LKz<&(hR})6o>GqZ%z&L7NJLmF3U~1qQ5RU&6z9_!
z$VHJr9mml_R;6_X?gTfas597$qK-Q9#ox%JM-qE(dF>0Z7%3cq!!N<g-3js}Q0_(m
zf%2d^ZrANv8WBdul<LNjLCmgM@dThLI&e(Hw*@OXCE4-vDxE)bFGOmCy|t+!>C0B$
zI7g_Oph&Bs)3b<&yVtKI>@)HzWDp2G=(O9EoX9g})Dfsd2<1CookDP5(5D>%bK2H<
z0@<mKq^R|j+?Sak<VcKTK7+CT1OE~pK#sMx?KLW?M0*VZC9u9rt@;`iO8T$Vx(k?+
z*CM8-T*SA`sWH>70Lo?Q%UC=iYG3NF^-_!yDmK&m0ZPqqj>tnQM`PVBo09w5keg%O
z*LEemc?9*NU8|=g_fw3tAM1XKDdD9+JSakH^N4oK90TMNSvu5HGKqx#=U@KEr~Y#O
z^Pm5ZUzoVIPrxu|PPlm8|M@@t@-NRZ)RfQTfBpZT>i_lMo=^GnpTDfkzt(^0=jFA}
z^Xe~u``72c`j@|yzm!i~fBTo`fBmPw{d4vCPyhM9{HK5Z-~RUBJ^#($p0j}aTJ7`9
zQTHh4;U9=Q#{A`f`fq>vzdrTO!}EXt_kWF`z^4;EUeUisysXpBj#qZN_6M~+-hBR@
zw*T}${Kx<Mpa1rMrj`qjvf28l{m+@V%;ldi=-*Ydr5T@E(t+|Pw6sis`;C_W%YXkL
zq@|ys^fQFETOFT&%<>u4`gfHi0-}}%9`{?ze_N^Lyig_cSNXRpfzjQ=BkEtp@a|aV
ze_}k+U-#QN_8<Pa_ka2?KYsjjMn=<YbDGt0-rVOO-Rp^B_V<Q{;cVDTvWWi33;es!
zOGMB?wEa9V?RZ@gD*x`du^MibjvlFo{GtEMeE;m$UdEZ0pYx{w{mJx~&vvcZ^ym9`
zE_`3TtK+xl1gbbb$g1S}LVsH=H^5tq8{)T>aF)NdWX%1x8ulCwzss2PXNLdt&6;*@
zt-=~Te`EN6e(-~wSl+!e+UUOR9Rk(dYL#Tx@2Umc=RK7v_?>FVL3*pL`kKnWS#3Dh
zA<W?Zr+0hJ{$uw4jji-A<sX^-v=83C$zb?x-_k|q*0S>ZQ`tbHxwXWr`L5c*mYB*&
z!?ee1D*t9R5JB|<DEM=qvX8vZlZyC2obvZqz%S+JU%>gIf0@b@{7&z1*LSP=_ybe9
zfsJ~riJtmxwG+tdRjIb$-6JD0s=xMs3jXX0_<Vm)^v)A&Zv58p|064)Chu6Cs|?5a
zZSO|?I+ZE-ooev>yw&6i`fWA1%iU^iy{7VSR)g8$z5>}Herg5O!`k}$o6s-+z&Bv~
z*O|Qi4@~4azs}=1|G+ek3mjD$<@Z1I_N(u_{eitPBPQK#XWZ%Zr)T|1Ch!}R{vQH8
z`|Ir8e_-yua3BTsyNwFTN^dm@$Qt<*BXX{ry`QWl{X_%*Eg<q!LlU7Nu9_%*+qa#@
zs9Q;bZ>v>=3cU5M<ok*(`M|G=l6+qg&Va9qlKjMLsK+sKe0GEV{d@R{w@`7D_|jC8
z@4JW?$ghf$d|&af%HP#c{<cy>s+?QxO1`g%AYQMElKjM*XhEy|-4*e3U&e-n2`^nG
z`M#6m>k;u^f4P$HD`q6>S3L^8ueS5z?^REdZ!20PaK6=8{)smcshyVf?ccqLpMr=6
zm#UYZl6>Di@U31ICHcN0k|ew;O7eY0F#lc^CHcPMUSHq51V8gGj-58a%D3<0=RTda
z|7x;b$+ul}WZ`*RQYiVpBJvErKfRQEUlA0rS4By_uej`8DM~-_9{jlO{r;NxDbR?#
zdM_;{`L=641J2%h5`13`9-*&#l6+qg%)nPgNxrWL3gD}vBtHY44vlL3?wa^H?9}0n
z_|jF9-<jH9ap+f!`Qw*gKlnE{x_A|}-t8l7Y7+c8c=H*lG<Vg=6!sei7yp^9oQhiB
zL!GTWZdD}ty&k5w-m4zn_r9-IcAiF5t?X}(x2#su^Wau1bVc~S8ZDf73*~L${PQoN
zto~capTF2Y@Dd96F|Y0^aqjp1>v<LSs@Qos_I*W!CV5p<u#)d9w)N{4+xkN-f?9Fk
zg}4?!`7#b`<TqYM`$t{|g809BSn7AjY*gIv6j8k`*O70lfgN$HP5&dUfwy_9jryIT
zn$^IS=UZU;Ctt!o-16VL1o`=Qun|7tc24mWzU^Eq>>R4K^6K4hRs((HRuiA(yJ`zw
z%Br@Mg!tQPG6UxuSU+P0KIu9WR<3_%D=@Vj<5!&<<BxQ%+p9{q-}`yQ%DEK~I_KLe
zZM-T3r|;XJ!%&Q|e%Xot{74_F*uSH-5gN|Ti!pSHg6}&vkq`V<Q-bhstIhhW)@J=9
zts!mPt)@J3-&RBPL5@GmKlujcXS3SB@do~Z9e*0H)7Uxt_BxH#;6Hn-DL2En)!+tu
ztI03+yJ`cmI#rE=->Ei}tjssS@=v~jah%?MW4HMS0MHortImyYFXC7&vn0Q&_44Z7
zZ&v#?<Q;zq@eUAoZ#6M_zpVzMq~3stlRx(cjyL>otbu>%9PqNtQ1b183GR=tidXUz
zr^3Vk%L96?|ISvc3ODGNsxQ&+*mA!N4T?Wws6LJ!1GiS+T7rINBa1vVal!Vo0!#F}
z7Sdl$fS2fJ48bP_>L2RqPfb@OYI@JtEBfBBhm6hds#o+g#=VpFq5hGcj-RnBA&9_B
z-IwThY#HN=&Ea2vxssnTo*k#|Kh)3lQ}(lDIlr~NqTexvtzS=um*}T%_582het#GG
z8MsFS(p%Xp`W@@}ufHU}+O&WC@^7C0NBSLo{>$n8xrfibuH#XkFZ<Ws{{K#|U)S*C
zuY0vs?Nj@BrR$^gPyerm=Q~>Jx$XXce)GGs5X(M3D`zsS2|E$efv!o48zR~tLHs>`
z3&MXU1`SD$FtUgqK_0tSx-zawb~7RbgrMLT#}oAk&|+fdHPeq}B}MEM6MbZ8{58pk
z2C;ZuH+%$RTazBQNC3Lzg^!pDYchCQMqOBwSY=uAwAZA2?Mmm3HIp%jgrG|v`p5@*
z1Pwpv_&wqlApPi?^qfPq{Us0n)uVt0I|etMXpkoKS(C(ioJo$L;TJiy^xIuMJ4MzB
z*xqX@Y!bp?tjQ=95hvpm^N9l*(?GE1=f4a@0?PTKw@gTKoOxD9PSG{V23-?6!koEg
zs%UC}<4*USwV*T^<{-i^<sU{oxFbNTD>~8WPJ-}oYr>lcc>>ntE{0GgAHgYXbc-CH
zj1%{S1ijd)HFM@7aNL@74?*0x6-k$aLcAtjMIYovJ(4`-?E-zcyC6^Mn)E5y6^o!`
z;Vgi$>63u$qiZn6;l?5x48fEcRM((;84{0v1X+mnyarv#B9zP;phjf?xlb|wolWsH
z2D8i>Q$Jq$Fb2BWSU8GxfW!l9&}9KmA8XJubP^GSQ3OFvb{g##V;}6iKv;u;$dKN2
zDVH~5(XBzAT%=fiLXcYk0@1C30INHRwren4#vW0KzvWZbP!QE%53E6t7Nj^>gGcZ^
zpdrF&fW){IQ(@=M^DGcWGZN4#<#w_s2AXct@ZDL1@yhl@2Ta2>(FLy1cmP>UI}N65
zWPm4-VNVe)BALb#B@r$~YtWr;W8o-*!`@Je=IxA^l!Dy#YAK(hQpT17Eok*Ul2jxe
zuq*thP8peK3xYi_C9p3g=QFLcH3L3<B+4*cDyCgg(^xl!yWf!*YIT%5>f}N{lI%}m
z%N1ixzpf|dS>I|meTY}z>R?{~9!c&1718%rS9a!tK>VxI-d`gS*HUDOT4?xNQZCQ&
zi?JqZ@hE8I6SjOrD5YXbQjYwzt1EGRp`}rYgG;6xI1;v+bNooqYOaDKsOWJ=|0YVY
zyt~|pYlQq;eW>010<Nws>m@&uA;Az0^hTkTk0`q|@PjicdYA44n$mbzVS7FjJ{1md
zt1BxrlHq<ND4mD81}z!WM?&Q%lvgT}ir|7r#Fo?daw#B2jc|h@V7vKZS47A-rJVF#
zd8acH-s<pxt>G1#hT!w>REv&|6@YeStc>T!xed$~m9!mU0GHtWk;Dq<^vybwoOW=W
zdqR}s%Dmi&Lb$qeMT2{~6k($x`R?lcXg){OLy&t%tw4UAiRvq`UoU!Yf<MIIs2_a1
zd?S=eMXbUj!O{a;Yx(ByPm8Xc=Lqb$6pf=+<exYqjzD_5EhmPp@Je2;^_w9MkAN*F
z9DI(bLl7hDON|2$`cmTnguc}Fd8pz#R0PR9qK<N`S4H`#$k@Al>Y-Rk4y=1#;7DzU
z)X#NyB-DRE-GP<>1r;9TNb*bXK)j!mN))gq!-;%3;qH;da`moufe*cFPevZ#g%~3>
zgP5Kob_N)NmosU41wvFJoFj>kz4+EglHGB2aG^tlzO`<sXR5W+$$cp}NzLGkOSwTR
zlEy40SE&u)j~O<OAQpq0wr1q=U6DPbMxcPDgj%PZx)I`5L>E{JZc<xJ(xygn6!XSL
zaTHThjEY3R%Nt5L&PqCVMA5gZRvUU!)eL~6a}^&+PPo+h>@&@xNJY6S33n?@yUU9n
zg7cVi+SP{iWh;{Jo#Ii=wuUH~hD*uyDw5|cC5@;ExV&sLR>2X)xGN<@jXb~0wi*W3
zG(I$Xr_2mBGx$Cs%3Z1fYbr!b&4|*=mU@hJtE`Gg5*^A(k5JZ285AnQT^|Wr3B;-J
zEfu+VmXaleDK?cQj;;vBy=>^Y6Uq)gH-V=TW!8-O{e+0>1A8jpW<~7qBf&O<z#>a&
z4k~j$FXk|)$n?CdtFbt$8P<9RIay3KP~on!ZmNNb$S4cx2C9|#H=0CX_+<=2R*^b)
zDbebYoV`H-W-3CoEM$GH$N;^R6}BQz?o#I1iqQ7Ul**@OoX%y$#ub4%7ZTZ4q`+Ou
zbXzS;d?xY+FL}isQC{T=EhDqQLOlM8=9c2|S0t8RipO6wSM5?b{tD;JrTo7YAwQQ1
zE$iC2Fe+h1N`-~&!__?gjjh3eHjPjj5q^$<?K<{Tg}kY{dERO`-u_a+{v(K)rJy(!
znJb<pf2NA87)!zQEAkp036`#nDDfe{lbMU^fhaU?1k_jpN5C!&=(|t~UFU5A_6r5q
zuUL&sk#;JQ!!AYFugHP27+t?IOZJgqV=^qcHc^Uq(T18{QDUn&-XY`nlcMa5AT?6f
zEJew$$aAxlaJ&X>V6`sPhBQ4(iOVa}nXXj*vth3$xQrcrDO`TVuKz4$ORxAeETvSh
zNIJ9>2B>DLqSXYKk>BVeiFb#TNUP~njW7YL5icXx(o)X&8bQC7V&y*-xu8Cx_%raQ
z0^`^Gye@{tuZUNA1bk%615*>qMu@VdNJA9~Dwo3IR|Ga&ig{m|nr$_r>_|SgnlLu}
zlU5VPM#i_L5cm~XX0^&V9~If{j);vXcx^>(!<N|y!~v34Qz-F@41x<mj;eE&7PTFR
zJO;_HiSa^!z08p-`iSx;iAxm^{|G{nD(H=T;;RaJJCJDx$$ub<#eq;r)o1*hdI6X!
zFj574URAjJ0PLd}Ey&ezqC=>p6XhXBQ33RiB$OBMM$prh;loog*cPikq@Z}ON)YX7
zqdNj@IXKQN0Qo0H@uI7cG*V_Qh1EZI6{#UUt{Keq6tU@aMB-YEv|o|Bd{rUo4kTKI
zq&twPLO0c@;j{r)9QhU_?N^)%mtr~9JUFf@ppC=jqKoinej$A0s*DhMBrR)UvqI3v
zr3g?*k{uxQ&iq|ZNZ5Eo2V#kTPS1z9ge{{3t14VnMZDA?H{nB%h^b3K{EviuC^Tzi
zL}9b)fU7l|LEev5t6BzDtpeX2P*nk@jwE|0INqJz6CQ`LV^sn0jzeM<0MFQ`M{p}e
z(9ES!R24BpSEK=`h$*^?zRHnnY$?cpMI6#2A=vJ~qeWo5&nU48EX1-=ijgk*UiS&O
zz!U%#@ljV1)b4paRIICtc%~l-N~!mxk@SdSr4&Kwo+0&C(b7e*(j~59MZnTk#(mI+
zGKA7S&xS=%8nH;1qF+^nB3;O7aV9!~k**>rjbNlpnF4AUC|6;^n~GSZs}NZa#3?-z
zG!9efDp>z8maf83d^OFft8_IC`)8W?9*Ck(gye`cx|DsOBGTxQbd<9Kbw}>2RRqf6
z>lc#3AEmNF<pVGl`3P!;5nVKtrX-es5h_Qd;Ui(=K(R%r9OS1XL1foDJc?`>E3p8!
z!z90y(x8UPekop99nKyKxQ`Cq^d&|N=2d9J9v?KS=wTHeJF8slH0~~r2rC)a8><L(
z53ahRr($RebJ!ly>HAc6gNhiOa|?8549>Z=yb)IONaDdyMOe)vVJFv%PgzIaFB}Qh
zFA~2U32W^96i#TrvsJ-oM5&xx=s6R^g@l8!q1hB}&#SNy<tWS&1?)4pM*B!mI>R~@
z=d9*M+!G=+i!hXPlbCxXhh({Bp+?Bbxdo?@XzuxlP_)phtD%a{bhT5_86j|7J01!5
z(V0cI($E{>@7d6!j#8>F#61&|h9utuf-TN1z>O$XQ~vlhqbY`j?O^TA2+LL@wcXsp
z+lZrhB)L~0MB)*!U5^sc_H-z2Y9bXn60Bgv3!Gbc8o>eQ<^p_b+>sx_t(2+=PUDV!
zZldYDmk$AlAYSAXA}m@2*PDt6R}nbxNZ8iMi6QiipmEO;p{<F*l^q*Qgo*G{70l67
zX4CVp`BdU|uo>nepq{y`jsRQN%){+mGG}Laiz5hapOD0>SG>6jvc_D3)ZlZ>C3ALi
zK0?w_J~L_wRD&=w6{hY;V#Jp~HNv~iB~;C%4s$VK!V#T4VKFdG1!rX<uvG<R<&@Dj
zNGnIe!2)e%E)qQII#q@muIQmm;3w^0lsihX4Ics4`>N;<k$MtQ4mF&QXwXy`988oW
zA$mlbjk$!w5j*cl@L-Dq70<;nmmv5;Eaa(FBNc>}xwPmPR-+P-R7CBY%s^5X@|@2l
zWS)PU3h-A!YdI1ubMR7*gq3n{`bZuWW6sG`jnpbrApk2P5za-xoP#=*W8|qA_>TyG
z&w&(R1~=tM*yDk56kuNSbWUg)gq67jmcdUs+^Q@k`@g7>nO#w8ftm!B5V4Vk<s*2F
zHE<+sXQ4BN39stnS}iDr?o%J&wX=jFPSAWLY-D2+Orh(Qe>@Uwr$}))C##&^h>KOh
zTbZ#-gjOJ~90^*^9VjGd8GF=`pyAlXCUd1cA&AL0we~@%pHmiYY`k*{hl92<Nz-~l
z6e<gcV@ID;7H#bMa}tIppCts;xW#TIuGSHxe!|?lA<~R6_fE(-r%?CC{mq<&-H1Ut
zm1Cvi>o&pKs`&QJDb$^x$2q$;D-dEPbFNenVy2wcD)=l@NmgnQT2fGQXGg@<Iqg*|
z=GX*=&M2*O%CNmVMpF=aBTDU@`U39(^@O4KfPPGKo6$6;vbR(aVvYn8YhZkZqCtt7
zQ#cx&n5iT$H31#nXr7eNv!>%0Ij^+JH`e1M(B3O_6V%=?6de)OUC>Ue8n|{&L2cmP
zBf)bMy-p=2I+Az;Lr5D0nK^{C0kNmZT1OIHU=HLTzqC@Km@PMOX667EZ=lRfC7n5v
zk1B&;yzv+@#p!AwyUejv32<~|D@O&Q?1pr0M*@`Hz-*agQjIizP7%3U0rre6Hm7u^
z+Za-z<=xp4W#?PTugH`KT+4)WN5JkI6erMbpu#*K5sEp0T@87Z*oLDoU2On(BHzN3
zqF4&U^^oMXOmesy4$4O`3V&j#6kE*`qK;bBw&RVvhN(kgkJ9-3i|e{2&E*LZnjKKq
z)GT1>Ae3&fIm}^dHDT#6esLP;FjI7{27|{OjZFcDj;5vph7M)|dm8vJN5qz}1VsXC
zCI8M=a4;NIeO&l<jmm}>^snksB3H4%jv&>qY6ie{R9?azQTC{)Eg;uX*wl_574;Cv
z6(q2hyqPBiY#P9IFu6yoT$1!JZLqG*4tU;>cJrBHf;Dhpj(;Dt3ku8>53C{S=j`iM
zC$^?T1dA@Fk#Y8=mH|7JV5lLI{gLpwxfDB4^%IhXTB$A$fSs_qAra^#(TlN<jsQEz
zvBiEyst>gcjM)dCn#gjB*ww&snZ2urSZ7@zxgo&kR8pdb<e!r%h+3Gnr*afE7`|sG
zOnw@y<443{01_2>tHI1ZJ7IE5OZ*YA>5*ID5ut6M(e7#;XtbL~0%%n9tyX80fFv8(
zFh|6OVy$&!D_CjW)XGGMEK138nY~GMz)WRBYT&)h-uTc3MTxW<5=eaJX|{3xSfw*?
zXRjKt4YjLU1?<ekXR(<g5Aqb*tK~J&RDPu+$X5}6ZUwJ_(ECWTcg$0HB-uMHU65X;
z5-v5cUZ!&u=Iz;Zpyiar#CM|PhHJQ)FRtbK65FdGr|I;?XW}kkDnZi`#jrY2@{z>*
zSIVZ=EJ|z?$2ynWLc=}e@x(<#0FR0z(DE+x2-plFB05m?XJvy3GerSw!Eu>B_*jRs
zLyyIx^r7dTu@~8^;j;Hg_)Hx7lpU(!&Ukv)$RWYe5uxcspx)Io5Gd$g4ZN3AX48P5
zF2LN7EdGetcHmEWKsT^sj%4z=v2;WLdm6|w6Pc+RuG&wTP2)i5`Z{MC*XcA|w}y*_
zsc4Z6;X0=qp1Yu}Y3u@#y4H1D(6*83cSNagQ%gXk-qa8fsW&u~fYb@GAI5u~WQ85U
zKoz!~3)AVT&Omh&39(u-Xr2&YR{@h`IstS`^2-$KtHI0rNN%N|G#pVX147KSt+ufe
zjc~bv9y7)BYM{?dyKp%eHq!){k=bc7uT}$V<_OSj@MfkmZ9NUdnJKPUOXAG5rMBtA
zzW883PZOv%e@-#~nM=f`>c>Jfp=_kZIufdmh^IEe-Z_%gR45ztmyZOcP*Nz{07^|D
z+wf&QBDM@rYWgr6K&euFH5*Z4tNE{w<UuhzC(sSD%rpUSkY%R$UJcIR(`4Ol==(GQ
zZ;a0*53E`KnQ8$~n((v{Peu;02BOOp3#@^fH_i0KnDr(|Z9tc1S24g#6Q<7jG|kj7
z)|UxVW1i0RM?c#!IE&MSsl7xAJ1rP8Q_05~7&24Tu;xIxCwKy@!GbB`SBnLE%1{M7
z&S}EJ&IMOs?`fVTDuzQJ2wtb0iU<jV?=nqD*pdAEh}dv~&9>Dpux8^|83dRkzy^ZN
z@kpQ<z-HTOJMJ6WR?Dz(wylP9Tb?9=Jt2zK(*&^{r@<zO?O3O6q1y;1q3mhR(+gsX
z2iEYZnN6S@AEP5-OF*%0s-=#-v;lR;XYZ8QN1#{|!5X;Ivk7y9Pd)SVm16}E+lHD>
z5Zi`YhB+09+Zw+8vvK`L9MBwbA@iV_PqD)qqQxHxHVvc#o{g~F0ZN-NH)t?Z46q}K
z_1%QI9jLSkbSM1E2jR(Bj!mE&to^CXa1G4<DH2!<=Km=Zc7rH08Bnc(CvyaNZZc(N
zaKKtL$<HU?>vJU70y@rgt)X;k3O{$8=bG?y$9XPO$~_RJN?P0?zsx55oB)0{;b&m{
zj|8RM;gyE2bwJW401f8LRN$ueIY^umTLu1X<v}q+u?SsvtS@r9TAqkz-BJ_R1vodH
z6^N772_u|8$Z#%#*Kn;l5<Ij=fhu+kc@?yV_s)^9SwPP!cn#9a6s4;r=>>6Q9!O#h
zSK@7OUS<{E&Wyja3UA{eJL|>U9j8GtzZ$44vkFdkTr`OI)snb!1jxYDkPdiO;b)xj
zj|2+hW})hX3WCc7%d4fCU{=9rIFwE0%xFkoJgd-iKYtf?M(*C346g^GR3A_o)R$9c
zGYKQBs}<ZWR96RKESchcH8|(ZDrh`V%H9ne@RY2t4J6z=B5W|Q8664sEu_nxh)C7a
z%yf#-7N)3KnIEjdTs5nJG0a)B3K=73?yOZ!2k?Z^=FA1;%$*hB8BCWc%2or@<w$Z*
z0nz0M*s|pwT8mo7%B)2#b8!lSr@e5B_r+k$&#c1Wa2}nN5Im?XQ&Dpo{8OiRUJdzh
zkA(Xb65<{ap9@4<2)Hx7_$jkb0Hx)AnqiKeB78NNY>$MkV~LifUg0=c0KuPzw6#;|
z4UgnBo~q$eL5U3;xGv&<HQKn32-^n?;U7tqjs}9xB)W*zbtI|5kd<M?5w8e6Bm3(|
zf>I8uz%xwuvj{wkD<eu*17D_eH4L;_I!dvyi;(o;!GOB;oRWfMK`UH}d?YBP4#Le7
z2faevJkzP*2%r-#UXBDxk>yf^o5^x10?rd&M^jX-c33V-)7Z#zDKt%!<WdBqC$MN~
zg6!nJ6k+L1Jvv3!YNWmt*{2bFV3ynzo)l#l^hKVGCnmUkxGY6r8@W7Z5!g<0%M&7W
z0pymV@9$*TG63$p0X#)D0&T?uX-KkpL~J{^_OS)HaoadV@M_47Irb*MtRWNT5p|Ro
zDzWtuC5~K9<|ARlnD0X@u!fu3BVn}(?X*0D+A_9q@=REHB+@PactojN{+W6$XhM{X
ztLU+XlJmOys3zMq?zG1iN=|mn*h0y;8Xp@d8Pu4uhi<{ZjTsD)+dz#ON{ZPcR?662
z4R3U&%k~5+%n<LZCGTZy0%_0*#+HRUgXE7bWW7p4nIWoITNMfmT7&6wB-sB}g~CME
zL47$z++((6zkEdcP=ow3#P(_k({dziJ3pOcD{p&Ce#h7{af1RfHqkd&B4g{D4}#1`
zf)e`J)UrW;S-F=*2ejzHeK`{BH_M<uI_RmFY}lZ=46(r)cr!=Br#ckFAs|J$Wbz07
z6*%xD(#(Mu{$5;_TK|U^^viPuY_(%lOO$d-jU@!0JeffbSX=WH@?Uw;H$?1e2*+|H
z{B_Q$C3Fp%)sawxTzStCvEzBh9SXS{$w)&nq3g9$v8l%M*f)Yg^FR_Kx`eJ*e&@#$
zyao?uEPb3;{vDgi0=s-H8nZ!hIRZX424^V$X#>sWNU(wI0{w@!)t&248BvcQJ0Li|
z3pzkJj#oQK_<EQrHbnW8{5{*vsWX<qIHuQ;u-(co3Xy{tGsO35$%{Dx>|Ef*j0J=a
zR?I1bFWtbG97`A-OqsD<jbk~A0LC=CN1~xJOe3w?<g|<>OumtIX$g}f49t-vYy<1%
z2sk<pb$Hy4I51-gk|PexSc2pmXOyvo$#;(uo9!5J0CMnXhge}PiMAoZSzvbzw-9*}
zXHI}lwmZ-p!Edl+28dzL4`r?!Q(s|xpN42&M-uu>IyWAPqZY5zkmlrwFfcRYjS5~P
z*YlYA5Q7GDB*@I$@J&7<ww}OsOu_3Q%bYStCvoeMpy`DXpV|%Z_5Vnsw9!Yhx?2)u
zj)2W(XUDwcl1z#{L<VaBGh-5y8vxHog3|dtQMr-vGDQ1gZtgK@(Kf{R8*}KP71|Dz
zLeoy4cmr!@OyY6_Yi5Y^We5^8W>?E;02-OvJRg)rHjA|w`-s7{U`zt{$W9(*{J>H#
ze^5%Dh|`ZGb+TI_6)>sfQDXa!uZ3t{hG;NjHa-KZZ8mk(F?>w}3Qyc27S|Dlu1yc_
zP`C2Iz@oG2!GNOY=<q<0`V(&3=ioGERU-q+7Cv)eiEu$$5MZ8==n<GwMUUZnEK)Wg
z<rrH-o9D)7h{AP58AmsPvw;9}%4}&xiLC&x4rOh(0>C<!9-3d^F_t<2ygC+|Nwhl1
zxqb|km?L6S0IVW;85l8R&``~go=1{xN8rzh30XGloDP19Rl|@FBt$vlwPXpeu!7ne
zGR!$Rn1u)v1~i!vVJ?Cw6C%8Ynimuw5sy=bpfe$2lgI;pM0|YCmk?n{YRsvS@ag$=
zsAcIb!x1k;=pIUJE1~2QGIp<_d*a(0ST!HfQq5dpA?gtHc+iqUMuqrF3^uY5Wvw)O
zhXAvz;)EG8D&QF3HT87m>)=u7h-Oa-+k?wj$S?t6APf<k>=^Pj)MCewE4};?#gMPA
z20Odc(VfBWbUiz;ZAcn_69<Wp$n~HB&0U%g4!KM5NyQzl!80Hvw)rFI?QHK1b(GnU
z$@gMvf9B^eWYl1?b0!TIyGL(T3%X89r~x7mgbXSyEJR@|17j!Bt5Au>+1jMTjwwaI
z)ss2BvKAG{4eTSTdeElkys<FwZbF2LAl`%ss<%QtVa7CEGlT>SJMSX$Sy7G(MJ?qI
zLj<jH-w`4<UOAx)!NQRZ*2KbZl|3m@Y#9H!)m+Q*2ljeWlpPcLvWDomMNE4`xSEe>
zNl$}Pb1~+ZB{e5R)QM|YP{|rs@nkV|n)G`%T!DowcOqPqg#>#F?$Sa;Egf?rAyle_
zXR~nxWG;!Iz~K25$)z_?ctV86LE#AzTkq(pkQP`wA!1_)0$#+Zw>CK6#i>6sbgr|-
znI#V5q|!Vy9Z^J(2pOL}sk!UX6Z@WERI+zMz^+Vgd(+jK#m?|{!*CNEA}WDc$VWsS
zR&IM2m*I{%L{NcCS1f%4C+8z-s<-j|6T{wcn;s%m#EpB1Is`q7(8vIaKQgU(gm?)N
zo{cy#A>y+uCu+sBD?c_DlNs0M1!h*+86KXFC`Y|Wg~si87CgOiG=<iJ)Dwc-V3Ldz
z$(vZtg_1=12eO<^q{^FNRf;NaV1;}{OZqqlax7kX9a+Be3&_l&<lu41g3uEJY>Z&^
zgeZ@b21-wesDop`FDe76Cq#TL9X+1By*6-bLWT}@OsFySbgssr;h$nWg-505NTB49
z-h)aGK6p?^t!bOoaiEx=3K8!OWS$UVuLPSXL>#rrUUaoT`K=gQ`i2Lw^@W{abQE*@
z5@Y{}dI~gNT!6#X_+n4B;*Ickn6xGY9;O}MOO~M?h&v&IicY{g48>d@gT_nq!u^z_
zd&|f+A;7NWT#w@2n{z#icYj0}{-*XThrgkSehJ5e6ci#fpP&9GL{y;VFW5MN?$Ea#
zM4%91vjK(YJV>8q*CG`jcdgO#s+mf40dhCa2NLSdJxkOPLD`Q8e}|S`=P)N4?wi&t
zbES9NY9DY|ynF+_Cq!tSV7M#Jj5*P82efx$;l89o|0^EN{&!5tF6Qr%<s$A=8VnRM
zkb}J?ndpen-#8*XA<2FS`#Zt0DEj6E$6eqbOyLlzZ-mF7@<&33EV5@r$6aRu(1B9K
zRYP>#bsBK4<ld#i;+w(&0o>{kz=CPXzz$LFQNix{lmYV*DJKNjSDc`i<o(Bz-t&<N
zz;^=Nu8(r(p|lIYcdSzo_Ma3jR!oh0<>(5)cOFx_0DR{$wJQpR1$8JS*n&DCEy?@V
ziE4Y(!+~l$OI$UA>YeA$PN?3E3TZiaqe2zMcxaIwtn-K}KE7f6Ley0cDi<|R#GAPj
z9>^M=&-RIWdqFYx2r>Ju6Y~1S@12;}h2MM6B6hA$j4QUk^<0qpJC1WMaNl`W6}{g&
zj;12>8+bq=;)8WuRT&yjbz)Fqg8M$R#D<7=eezP<z$OYATPNCef%{Ih>l4M8tk?ja
z6ro=P_noIyc>-9+DOH{T)_ElLL02;CJd=w3Z=eW$MEZVr0$Ue!&&@m}-1|C#t=RiE
z2y98;w}Cb5LhgfW_R#kqNIGj_iyAzXx^Vj_d<DYoBPuD3x(yyoov3~ATq>5o4Psx=
z{B02Vx<b_00Q430-@r49jG*jo!*UeY-$r8JAof359{dTrW?5t(j5-VG51v~+f&P;+
zXf34AghT~|e;a_zUT<4`MG7NlgP7R`^amlc3+WF+W-sbnLS|Q>8ym#Tj?=&(Vs@Pd
z1`#v82W;>(>vF)gfs-k69UACEA;5k#2#)C-U?cG{aN+rm4&q}I_8-K@ChR{5kWJ`+
z5Fne-e**Q8aF~dZP2hiU@tU@Zfdy<A{12W&jo^Rq5NZPdBQbFJ23Q`0J|%*Bo|Qs`
zonsLF+CVWEh<N-qxgJdreik0#Oc)+#w-gortfv5t!9IUPC}LP$pPEVZYc2(deoZhw
z-Md4AjcO9wn#Ww9wCNg23pP>YV;iQB`~Yn7AexQ<`Jh~l@&hm&!9&D;HFm^ML?4L!
z9|O-QWVx+O9BJhmV3T-R{sA_Lm*F7rqzqjZ^hdCrBZ}ey%O==A36_npf691lg8h?l
zS#Ab4iIz<!{K?g6f)5ixkwb<Z35=tUsOVuly~?4$=Ex!|4c;Qid%z}fF5L$VhNqBF
z^#MH_mi`<tp~!*2Cc&_L2y7Az%ZcEK;-xel26#;wGHAd<t-J_q@=yym0)tU61k_+<
zk(=n`8MX=cPXb~25!j?Hw+YvSbo3F)3&3WAVL1WV<QZ0O05-X};Rj%=WC02;-QqNX
z`o%+SlYxKnVB3W07Xfn<reD0pkw<|o0_FyozlfKc?g19@GMx%68B2H)RY<tpbThCB
zmm5w4i>q5+1xJKQPqzYFNSNJp8d$u;Y1$|jF?7>ufP9FM@$p2_bS|)!Kw7>9wuqwu
zia>S0n+^lZh(Vjo1dBkr={T?mq?;`I3plzpX@CgJA%hA^F0Mnv!g;r4DFJcg@nG?Q
zng;p@vRv~m8wMV3LjH?*xC!|$ns!^!#<hrvo1p*FstoAAxFY3tV2j7odZGW~@w5v1
zuRNeuf&WFoTeC>CTSbYm1-M&<{=r*H5r%7HB2|5z7uR3<4m>I9DY(@Jt5GAKMysIw
z;uTDt8g0;%jts?AQg-@H@LLJxH^FZm4AE<w=vRISwuyeLI1wAQu-Z3qEu9V?+eEf<
zJ2)bAM4X4s^(Ws0+c=!oi}p9KT;y+HOh{NN(f%gft%CcY|Ai=l)wV3LEdpS<AlN1V
zmJfn$;@^7V{w4sfg!>x^xC-rWBH#+NzX^ZqMf)4eQQi!;d5*0@`<v%jIWXAftxIip
zoH~^fp5FksazC(5cw2?$H{oq1l>)(fLPE6?@yg@CHkYMb4s7$NT8m5+duEw!@vvHf
z+c!_DRp0l`lPX;f9@_-FwWxi7-Llm@v2MZld=u)@>);7l&cY&7e%2AIVsq)rrQnE+
zm15_3LY7(<LHW(YD;*7N<LoLw1KT{h7NuzMLabc4S$LASQ<O@0Ayh8(1@@9qxrh_x
zg;==&?|UI!F2wsvTUx?Z!3&Xc$@ll9EaqhyYMzT+UJXYy@guZV**Ts2z3}uJZVX-$
z7?-Yx5EvI83cL^)mrjo<FGR<M=K?PT$EBl~D!T@e$hh!S@OU9KE-np-j0?{NUbuD(
zU5LH#q#BM7&ne?|nA*!@YB7x&PpR^KaP;ycYIm>+d+E90Wn_tM(~?`7I?p9ar-UbD
z(LN#k5up952XknvG~$^QZ#XpKp|n)#0E}C>C3qovrMH3?!dIqWJF=B!jx6oCa#(PX
zmbQEm9E)*pp!dhITKC>kJ8$PUToF9|h_*Zt9E*O-8^P(1wB?TApe^ma)OKQsBgszH
z5{2Br98r9ZB=$-NVQFt7b_ZW+%b&qPSK6EO9S^qBM=)t>bC8v`d>kBm?cP(3S7<x+
zoC<9R!<~7}A|KMA@6baU6iztri2Sqnkh&TCb;~`$@h#eNP;gL`j)X1cCv3}Q!TFs#
zq7FevC61M$N5JilaPC_^3|{?Ha&4B$U<whNag4WCG$==Vo0Q8I_m)?$hx_B+_Np{u
zq=?NO!GJbB54?^jP%&(BdpC{BfO16T4ji>NLAe8M?cLOJAhKu6JHY|l_HJx>Vz`@H
zpXeh?**~Rb@}MRi0o$EeLY2>4m|r}Td-9F;t|-L0V9P(j)8BUQBFz`{EYf^KQQqe{
zXhqKvv7HTV3re4d%3;Bg?cqqMdSc)sft!efhO|YkbHoGMi=M?EyrdAIT^uy_Vujoe
z7QwxPk+c^-{f-P5TjV@HUf8FMf2XSQ5I&;R73O-+Q`MGxg5&75*OXp46*dWYPl!?z
z0(i$sZ_|yzn?-?YVfo32;Yf1%t)ZqZbk|A;-DuN2!9h0KtLwR*>MQz&<7~V|!*j5N
z_HxzAFZTwU&cPDe3*h?+(Lg0?gY_og0*9?&FViRtC}{jNw2=xDcst?~>}6<sV02CT
z4h*iTX=J9`%hdM#l$zR|=prGwgFdw3o#5aO?bV3xJ;_5y!e%CBQ&THggd*5^W)j-;
zPIy9+9jfZ$LYFGqUYHyDIJcc8ypD~nO6~|ply9i0LmM3`YG$KL1<ma2k7#ucliOZ^
z>JGcyUIglnxF35Gs5?w~8%_>SilReGB7P(T)v(#X!nl<O++l{?VA(w>Ix5OL!C}zc
z@=tI?4BGTha4?Csl7BxQOrkA+1V?zFEr$e0e4ssr#?7L{RuDyTPa<&`gSRq>I}FA<
z$aM~j@}5JjT6SjWqXml5X3B5}!Dx#`=U@eGCH;2T);Ab(Pl~eT{;HO(ca)-KVQK3a
zM%Mr!?CVx0a7SvlEn=J_{o9_x(LpWR)79?4$ohj~4y#Z#NJV=JR^#R(BpApT<2_}7
zcTkA7{1-ga;(Y`tWOuZ{ZDCdrgIgfHEyo4N&CXU1aL4`67JJSS8){EsaDz|wrZ0o%
zEz*`NgX5;@NH}a8+6#VzT(qaI(;QKPjtH&$2dYle-`%<J2+y7Cj&%4Vi9QORBRtm@
zr_R9-+DZ)Wpa^ZS>fBrW8)gVcM4&wcslf%>%nt5g0&Vf+91+Sk92XwP#paglf@h?&
zkYJBPG_)h(00dIoN;U3DCVEm-_?sBXF`+&X=a_2Aqr_Gm{h7Cmz@UQ+8OKHR9zzeo
zG9)?9Gx_K#*EF^{5|r*CRP7x@D^%?r+6q;J__L8{+<iPzz+wmMXAdH3aDMg>qQ*u2
z9<Fv1Mm&4C8V;DTm3`bn3)rH?IXFN^f~F=qB){MzO8o`JL2cL~&UvUS91eEG9>U>{
zSY3M%h=XRal~vr6=d;C{a|C1DL%<u+fR2PH65)W3h;0Fy4kGX13+*A?4Z_eKEG2Fj
zWW#$eQ9`2~he75ccd&%EcySJ9&mQ-)8pNJ0PMjkq(2?9qxjq6ygWR*bAalpH#a0UO
zBMMczAalpjuM09~=I7l7nUNg&`G}&3V_z3!1~X`r_2%FO9RW6spaz{X5hOT2yJr)?
zoFcM0xIDX0Y3iw$Ky-)m$yN$+?;X17blh<c>;lmp=fF-79n_vvq`d+`W{-$%1C}bU
zxP$Jq#bWagSlWj+i6j8+-qkj6X(!l56rkM&w!#0|Oh5jFD3(hX+U_$-Y#EENclCOr
z2SVc=9w-~EH&4pW?gHA#5Wl;CHaI++sly!vo}IL=2cpysNW15ssb@~2-G#C-&vqBc
z?r_fDN<!|4eZ0GncE?$-18EPO^g5X>o?M?J;KvbMpDo&(W5MlSRjWcBuFd4$>|O-D
zM@7@Z#Dhx>m^e3zE%usYFWH@tnETD{!o=8=whI$u<JwM_K_3<+Hk&wR`#l1Km~%vE
z2msQz+DQQEOU>l_-M(%Ya}sQ^*&L*t?E=vQM?M#b##dlFW9m3K)!U~U>rui+0rJgu
zL1@snkA&^ul(}6vdH|O?VRRC9whKjrv9p84<{;~AAF_lX{?B$9v+<eUE?agmdbSTW
z3s}lb<&PsK{dOU3P;j;qje9b1w)kugByuFI1Pbp*gkowUTpbW-i?!weN!tag;Q_kc
zNsn|mCTth3hWElpf>I8(VD-RhkAyW(fcJ!iP3L*f=@IO3gWZvX+yN4|cxevO&Gshy
zf0AytXlIV-Kili8R*oYPazf=(PDLIEo<1U~f>WH*iaY#?x9boLX3lmZ<i~@Uvt1w=
zyqxU>$zbJd7f1#%XDb`IPh|DjBAa>ga<&(>4VY=04+hRuvT=tS(2=Aq`JAMp$e~K`
zwM|eOM4HV^;+`~`5Fk*DPascAEPcvHH4~D?$?!<1EO4g@Nhj~-(?#VMcLe(h2}XQG
z30oA7phwbCjyac^iXVu22-q%GnYd_<1N2tjaK{0An^xjHe-}cAr`(ZHk%fkVkin1H
zqMbQ?@U{^pXI!6c0?7!AuuUKtp%b<VBWG}heRGXFA~0-`&K!)IBSA|zwi$g!eSHw4
z(OuNZr`gIs?x53b(a;<mn61>|4%5#Td(6}I@(Izc)=>@WAs5n-U~J&mc_gXu$^sER
zI5OKBN~xOg?*hy;Vc-RrX;rP_hQX>@#SMe;TMR?o7Gum|t@}t&inVPboO>AjwiUH&
zm|e10FRnp-t(RvB1MM7p0qupeo)wg$D@rx)NsQT|l{sRt?53=yjz}%L31=gk%WeYN
zu%><_D4mB2WhcSr2~jS5&})u>4Fi=n2IldF71@^BO;r2rwouIOXpw^?vz0{LgCn!W
zBXh+6*-dFp9X{ws1mzN6Ds8xfBC|yia~RY&{6G&9$)H2K2{9us(QZV{NJ_Vx5HtMf
zx3Z6W@@$?EVG9YK%_*~O0LljTh=V<|m0#SGKyw7SHRBRwHvwdX9@xwk?#TFe1lWj>
z6>v9$Rb$7wt_dP<oa>q(GFUQ4g7F4PW{dsh8;kLXutVfU(Gjp|pwI@)jN7JDX4}A^
z?Sf`pTW!(4e1AY_lW7|4nB8QE-m&Bw%+T97ONFs<1-D5R^JKj2CbKi5j2#Id3T)X5
z2j8KpmhA@EYy{ampGmcWHLLLTMp%_y1+c-P*~%{NV9;z4#5@T!N5F=WQTvF{GLC*#
zs5|4l?JCrb44_*X$Q?;Scaq4mlX<q?N+9ka!fbKKJV`G{K>dI(>!gE`<C6J^pkOY>
zs&DMZVhpO-DWxhhJ8vkps{k`HwC*aveBMVDTn1@oGbg!&GPCPtf`Bpe5uuc0-PLTO
z&Dzx{E*C1vB0ZThPl$54_u#;M%J_H8lS;Gok)+;)*FBVS65e{jsj#{ph*M#u$-09W
zaU{7XcCaTt5|rX=##H1XNzJi0bg(pzAUBwfa6U)EhI45?N5qx`tyWXJK&z36yn`pR
z#T4sc$!y%<9|_KlwW(p85|wGZXQ<9y3DG;~FS{zdWk+)6BSMb?t15|j2iIkbGIk`X
zUe$APjlXM=#sI6e@VSXrYmvS{tI9>*3zumju<Qlvw5V~M`O4;VapY6_@g8)U4YF8I
z%F9Q$vZPzyDu^1^5!mNQhVv(}c*@dKV!jm-wtK;PEK9?%pc_~Ek)(1{O~om&DEU%H
zo4ZW3ghODV*}9V>qnzZO92rr+daz_pCx@B_J}m>!1w3WC@n8BOz>wnA$$u&G*6d*J
z?Lsql4|3lrqch<D9SOz_QHeJ)jrSxGJ|W00rIY?rI-AauWFbWFh>*OCt6|{VqBzu@
zoEc>w@8ryg0oH4l*f0QYaW+g_YH>9UkXuYm1LP_}c?Vl_ix1W-!d!0U7Vjj$6vFm?
z_%5YMHQYXwCiMVF3j<Mi5@3`|ykmpgDxJkq>TM#|cd610blY93TF!-7sv5>Z6ep}>
ztKKT*xC)W?LzpQ=jR1}+J9#HxM*Of2qRUcR@y<XzOWdy>)Rwik^hlG^+C<YGpUj0v
ztk1s|<E3<jd|#w^bwq_f0=AGC`bel){_RMz)u$&N=1ACTZXMV@K!sVG;JSkfv-V`e
zz^ZFcwY;NmQ|%^RS;|e`0cw_5U>(f(wFSvL2=qskO|_EB5|Vc?Tb6iVy;UeINPa}A
zF)?`uv|GFL!8H^nBJTi)YwHu8l$a+(*i(QhkA#iq<UJDhDlqNZuBLO*Jx7GL8(xa5
z^_JaCLw5(%Ufc8#3w2E!1mODGgzX)E9cvpN;;D#9v)n6|h+j`f#GSPX$vXn>tljin
z$A~vPw`07UhNW|^H;qe2545<$4`ywm@(z;B+7*u-7|E*7V{&8`sb9U#Pod!F6O)JF
zx+Ay9+C@J<PNi!XsgU2L|G%|w>D6Ufj+*zc*h70@sCQ*fkpKw>$Z#1UCRi8=`3^8b
z{C&R4jEL%W9?Qr3;v-$J%KdfMqr0lJq9P;BT#d*tmzk^o`E@hp8lT|0JZAK-XOdlx
zfpw>EdMv0r-P2=W<q1@qNgHosqio7YK3o0(YY3<<X2!ebT4H9pD{?rRQjH%|_JIEP
z>?NB^|9b*RI2LpOV8e4vSr-5a6W?nlW^pW0I=x$}A{|mg*vpxOh@&%Gs<xs(OVw6%
zNb@_HFlL0Sp9w0=#}xmb?w;9H)j8pe4)_EpWF`l^<1E8Wvm3M)Qy%dNT8oJeHj~I=
zCYKtDI**xrYAEV_EGWgoqa@-JOcx{bYXW0C1{~f^gnydJsYZ$@Gx^kgMv1jf40lJV
z=Sv`$8cZ3p#%d=<S{`+hWz3o?UFeEn@Cj;+iTO3bbTO;CY)6Uh#Jm)z>sZh_dDMNQ
zb#kctM)T-UC-22f4mA*6%ZR*eouR?RvnR0OW69e8(~rM>&TCsfmwtY=+x*n~*^ZTM
zqknvs|M+iz{I4JNNBR7h|ND1;ehjk%`NseJ11vXFK5=N>*`_~=B=)xHOd7~fw&{H3
zB(@DQ0EnZ;<jtNAi-DfvJ^sv2B(m_i+2VZloE|1UB4mp;5g*`Yn1}=wn@U@Xy{X7+
zY)SxI%lPy~dDgLIF&$u6B#tm8HLV5PZkvoysvwt}6h11PSL2yw#s1Nza>;-8!Zw`l
zc?I9thSHzY|B+xr&Fnm;)1eAgJ;Tw?Nu%BJPaAX^YfHb=bW~CS<{6JCDoByW{B_UA
z1Sd$b;<cx1LM*<5k7ok6E0zlrN?m*CMVbPIYlq_~M71J=n>Bb_6^Ap{_^fN5I9U^b
zUy(!16rou`?XgyQo3m3gWlgFBlc(kjR|oPXnBw{>^ju7NdMZx0P2p-4Pu&!GR+DCM
zZdCQ7@O%}8RcC$`O`F!ba<63y9IAOjZAHT66=WPMsvP_wQ@V``Zj)(4P$6Mv<z_G6
zNQ5QFyFw0b%jvB-Pq#u6D$cMrfWPx@ZKOzYuF@4;%q=<D3L@y1Fl+_Cb(>;5E7UBv
zMCEG+yl&}{R($U^sL2(d?k$dSwUck0isBV)_iaiJk31tA&_YE%gT1-KuaFGiTXc|$
z;J7Uz!HT`b-pUMma=1%%Pr245g4YT-rCSSHLuk`U(cW<r=Ke-P3gz0C5_~~wrX?r1
z)tVW+;~^>;^nwC9HlbVeqLz`KdrB6(;@h;viD}pkz0x)}CcGxuOL=ss5-~J<&0pDq
z0o)@aZ&)%@`9StPrAy_GsDYQfuV_qz&$PA3HKbsCWj5_dt|B#()|pCHSX0Xn>ej(%
zq;#B_1`}7|e0g^b#>jl51SX#bEtz+YM<nu-xIzQLZtH-mfw!@B#`B!ib5VO!HUlMx
zQ!1gEc@ULv7CErD&J-GDypUurO!1vP$=-72M1HPPZ>F|Pt#$fYl@0}ryyumYEE7g)
zS!-ZG?y6)Q3rPZn9V%_n%^;<`L&{aLk<RX>Y1+u#c+($kCXBk7N;b1Q-84eTcP2PQ
znN^e>2Zy2yyZ=b!0ZDa_d{35%SmJerpT0a&BpEZ$X!NmOEf<$pIUR1E51hp;Q|cV7
zmrMJI<}0#K;CcDZ!CFQvyJ1~k@>P3b{t3qVBg$}@qU#aR_}t6@9qFT%sO!D#l(WYr
z&>g?xs+CHICMd2~#EZVvk{NDo9D1lq|9A`aR%&-xQLuBB;wtxIy-F1I%GXjC;wtYq
zh&Svj(%2ZvDY^N^DCvEbi5ZnlF;U2WeAU{dqQ#P;MyFI03AtBaR8i-h8i1>-gPj@&
zOEO5%s(k4gGH`e*26<5DcnS-m%3_G%UHL)?u^~8pFrIW?-ASqNF)p0ic~^stp~FMr
z)06SMBy35#EeX&eD@JLEASZ=dS=6nC_^5?JyXlHf6^cORs6BmA+wP@`M6C>^KJE*W
zs9l}E!c157b5X+~#dsDa7GAP8RK^r};L7tflb-BmuzuV68Kp0-?2&X{q*egt2o*h2
zLL=ofUMeF}$B<A5!s!)YZWPRc5;>JG3ZxgPAwf}L9elkMBCZ$#MF2`fDtBk}v<_ps
zQ&UTaB3BwfK4^EU)|9CscM8i0ntuhElj&VL!k+W!vQU`>G4m0uycCj)Yqo-G^R%_#
zFp`+%4Ys{Oq>a&zTq*~?Sd6g5p%Xzd1z?(vc@ZATv`YVw0f(nzNZ3bkpl8e*j!_{C
z?vi*PKn0yEbVRsiXpWAqAujFvMnC4^=@v}`NuFIB>4;bgKG0_5P=?I#g2e!sD1qgn
ztQHZ-5?p!ZX&q2#^Cb=##O6+v10zbn^_E6&1UUqwelutw58jsOLBm9MCr=o}!xzCF
zM2V@ejmdaN$d4Y5c#?O?dX57>IiCYshA$qmxX1d?j0OIps5^@ULA_pL$6kKv6djX6
z{zwn$gKxG7nu-J3IKCdFGlI5fq8MhZLFa+PW%4Nubnjr6k*J8XeI*+QyNookWbcpy
z_NGZi)ucQn)dF-vV2&;wr(q{P;0wEEf*5mYF3Ce8!BgB5F|Qn_TJ4U!<2*?jdf$Wy
zl4JZu7?{YC=*kv53lO-khub?(u1P8Y4Y?Nm1fecpj$@NI#bZ+Z*hAG~VuSuZ4#c^8
zVYv9~6fVDlJp3{V6wJDLex$=M0M{<)_jO2vRr!4iQgzZ$arSTz4R)RYTzEd=RA;Ec
zgnZdW$wM686jA&IG6vd+!;=^I%Oeb>qj)2oao>azKhw|J`0@GU^O>pZ^T)>l|11Lk
z6q0zl_ytMKm+XZk=6rb}iQ`vDVm@dhiCpquP$KZcizNabJZNG%yAR>SKob*se1VCH
zE?zJ(AD_TP;Ve8YHAN7;!NkB903}wSj~7a`UqFeAdsJYF0VM)L6O@<^-vtsmG2Tcb
zP96v)5{)F1xPJpl1gJqIk$iU`iBEuw#0`lga^1a1Vl+f3B2SJkjA&%MUl@_k`voI@
zMG-kG-Y8;@+!HY3$4~_;0!56a?;?nFZ7zg}Ck_PhF-h261abTdLF_*+d{}i$z=ur;
z0}#Z|J1$gD03vrg7eM4D{|z8w#{~rOV-lJP08tN}0HP$CE`W$P?zspe&%rK$$n&QQ
zAjYT&JnUb=!_R9V2^)fkM){bF9r83#*r9+mVTTIXy4WE<Ko>g{oGt8-M>N6?y$Z|}
zc1RyX*rELjJ0#L`(Zk6_p_&J{h{gy$<i1MyA%gb>A1Y+NlB~FuKIX!QIzSM7D4<1v
zp^_{LFx-MR2pB5D_X37W1SrT5sdNPxip-aQp%6s@hRWJX$Z!eH1Z22`a9qgHe+3x=
zvcHI-@^A_<%zsBt^Ba^Vw2%_$1PiCqtO_nf7Gr^hN>A94P;(C@{uNlL%$x!X`>()4
zVS0%bK3g#<7c5kUM}dV(s0y%9nTdrJPW4h?;Se-PuuzyD!NPtaJz#}h5dH-Vnei1^
zp|UCpD~vSci4%TG;|omq1iDDH5jY{;J;8+H@7|R5iS{Kzcyl=mA{2fqh){{j0TI@l
zL>vfVZS;%;5#E&df(V%xQwX7QPYNJpMrWMM9as@iT;hX~(tNz}!Cm;$VL!LaE4gpx
z&5jNVBK(pcci21Cv|z$_F4#l~16Xvp@Jm}(L4+iFBtj?@GZDgf>RthaTY}g^2ygmI
zLWF$Rlq>S)7b`a<>I{9n0}yIOy8t28a4$Z1v%+0?kceKV_NruAUije6BlyAxc`w0(
z67j2uZ)3WvAHTo{0kQ}myqTN?58lj5Gq=*2*$B25K)8Q_5K<5D3qF{4zln`rS!{?9
zN`?9&gc5oF0uUyw)R9d}5#BF^P!QQ0AtY!hfKUpXV^CpsN~`u_gc6v%7$Ni=0TJfE
zUU+Z=LA>bT%>qDpP>=n>gMr0ecre$o=L<flR}A>zOMm?Z5ArvH2dB_q;e$hnq3}T|
z>0Wq{lD9$#k$CHk5Wdu#g%Ik2Uw}}erveCdAooHDCEtG$LOpPU>MfqO0KzJ9$rnT@
zMb`@vCWt6>@G2Dx9aP-c3m#ND4~MuWMpx({Y0GbP@MeOz@Zk70JV+Jf3l3g2LxF>g
z3n@M2{k~v>E-vLo1|?)iXz(JA4sNfGo-a74n#uNcg?kbkROWQxgHOPJKwpFqUL8Fk
zgsNTu;Z>pn=UxI(FO0DK5+mFS6%|G(C=M9m<H}_$kZ=goBS@$S-`*sQLtHR%!lJly
z0);w+zF;9W&x94KYC(lVLWRN#6>lu8P~saCIv8)LF!d_(ISgc03h@YFc!UZSsv@XR
zLD<r$P>AJZXu?z=B;Z1+>kuv+7lQ;`$RK!ug*P-#XrbcMgcd6PQ)nR}QDKEuf=xsV
zyCRy17Ip;y5;45Nv<!EoF7pKpFGRTCQKSM4Z>S~#Lq#?xUif?oPfWnDDK1H%;f?nr
zY$!=7%fL4UNfI`^!DoaG712rD@CILvFF{k!8#WXsD%emEwEGv3kg(y6kr8Z2#w<|7
zLSIU#VG(Eig&H#20)fZ((BtBUiZ^;;hkzf29SW=?c37xyb-_au;z;oDO(iFI*htk*
z>=3BX^TG}<`}u_(!UF729K#oOm~-WMV~3<B5<I-rQG$o$GZH-1leplaNYlR!9)5=O
z^P3-^cXAy9;^&V!YTfG(f`<iIA(v02lYQ|LLGh!%YBm0b&wzZjw&_QMwP{M^3R34W
zWM|>6nm9t1L1VTFru`bx1S6h0b$K8Zw=DSg?3O<E`2NQ|vl$Kj;#UDE#4*Gzd;HnS
z#XP-wjEZ&O%$iR9L92aXtjX)$e8}KX*<L&kg_fgHunxe;DdV2t((jdp>;M^hHi+4B
zH-eSLHaW>Q-xx30y7|z6l<IqD07y;pa~5FS1%wyItKTcKHjs{O$KQ~p02AX_@*go?
zJotbsa13}0fMe>^EmcAvlMWq-YepG5%%>Md4Px%*MgZuPZRt)%)^OVlA;1Bpk=+12
zRFeQ56jKd(TQi^eW73tw2GS%ghrH-UWjXjoCLOtmEwC*_(}5{&endRo0oy!t@nl??
z&Knb$dqeM;yVAJ5dSUa~4dfiKMSnQ+&fDVA9UMAaPG8iqCN0lGjI4y~5SL-pt&6w~
z!v9f>PA#nqDHQxM<losm&Tn|fMkfjA<SC=M`4&DwPR<5nvgmvP2(R+CMwp99h7Rkx
zCH3z(GZ;he^n9WXJiGIW0}7p3OtcCvgRl6T9lQq|Xfr-T+Pj9T^eN&w0|;J-*m2+t
zL9Z_0TgRB`gk)pf_<;myaSW*99;)y$BHC*mTqG{$#u@mENo)=~4U^Le7}b_M5k!HR
z(zYUJz&*6VN7o`{D>fh|={a}2sN6jQ&$h*=K6i9UaCAWg*Xs}n=QT@;&J~}3le%1m
z=VCfKuL-8x(uqbvm=^@-&W;{lfE4Izo=JWTDCF=K-4jPeI*)23x|92!Z3i==0xz;9
zK$|C8liusG<SCXkU~8)1+tjH~!8sAKwN`jYL90jSa$!A|#-HR0|2i*=fUoIlOUKce
zsV$g^({!RXqC`@788~1w9?0P=O$P&T=WH4qGSEMMt)F9x{%zGe(fW<sBGgNih8p3q
zHn;i$060vAKZ$oysaY#_y*8Hy60;P<h*OT1Ty`>iSCd-ZIaJKS#zIgLR{RcFfE$SX
zt0%d7G<T}`2osZ9UB!vIiHTMb1pPXx%w!oE2f;4oLG2u>8ew9fc2s!brYx=%nL=zf
z?!{{66EO+P#hGZ_h2G||#LR@$Tm{x)qKG^d@PJKzUn>IK-$$u9uA5@7SA<PYMiFGP
z6`MK-L_!vu^&Zg1P*F>xBCm_hs+!><<|g%lDLPqHGu%X~+Jz-M$$eF=JxYowsrizT
z=T|GvG$Yk&jf6I)JgXHsZ%iBGV~Mt3wYrM!RvagzVYvZ*A24U2<<Q)%a1NnpcUFmt
zfUTjqhi#p47hWL_aSWIwAaCj9I*zu{L`H{HgiQ{9k86rq*wA!@-h~ZK$chB6ChB>G
zXvRC<22LcCsD3soUyjW8`w;zsi7`8T0vW|6*tBxHH#B2`c^}Kpl|J?SkAYQT+6av}
zmWhklNl*uLg#T1zzp|07KmR!N@Zn8L!0uS`dGM27u@QYt8g><AT^szWi#ed<`U<x*
zNTRjD=VX@eG{r1?F$>^`4xKx<@I;5szkwwfX;@E1Add~6n${N8<X>o|;*Ro6>rGv#
zA~P_&21k@8&AZy*S}N0O1*~g>d;A(oJx0Fk6Na2tSP-E0V@k4GTaOanMI6AHva22o
zxEB>g#%nRmtD}EBf=@A{cSIL<bVI>{hpds^BYCS5G8kGgaAxwcpfrQdfj5=$Rz`8W
zV~M`KC?D`;k(ae1jh}U`7MbhMx<dz{LIcXWzV$#Zx<2e6cAHKK-XUvv9}uaj6s;Ax
z4#7TwC2w1GlXz5}r3@ujYS!A|2X{qfwT=FW(UF`I>so(W{`j%T%vvGR^<un$mvSuZ
zFkIEh%X&C64UCvmMF!u+0zi^XgC{C!yb5Kr8;#dMijp*5?d1tt4TJOGyGj?YLg3%J
zzSju`Nfqyu7p?(Na7@|s!7xB<310*r><RloDS9WCM~C2@NhhxY$2=C+4EMHcNq}^n
zDOqdnS;Fq3B4errHM}CHs!3?CBJt|w6;%ZFSeIkb8{dg0dXnQJwxgqWj6CbPo$O5m
zk3D6tM0_ebc1)}r{%x0Mfe|u+y7e=FZ_*PsQl^Bh75K1qma;oqIC}cB(%L(Qd^wf*
zsdmoT8>5LCtAzuvok?!5;$0;H3&5!<wd*lOXPDWweqMEx`d&qjVr#BS;ruoicdX}8
z*gIAf)HdaGJ(dU!6$K0Dtp=jR^9niDVghAL16Q_oc*r^steEcB2n<$cYd$8{js0xX
zR-s#z_=vHqZCe#%TibBZT0thUCg<f94vW_-<x85j5|9}+ELPD)XqdFivIFm~Ej@Zi
zCzoEY&@gEthjm88w#B-kYNGtG_4B2$pqNyAMc$M;?1hms=1Eibk1$}xhtQgqA$%yU
z$u)^jsfoMtRD5pVWIeduO^yjZ+Q)*o1#v2ezM7@j?>8+($ZufE23x@hvPRgU=3$RD
zp1f5Y!at-5l18XyCbGs`YYan9XSp>LVj?wdI0i%AZ`?A(5nj~88`{i4#FmtDeHDJ;
zF_0%0hjNFmh<6iIB$K4yvE&$Pc^Gi6$pCu7)Fx?<_)YeKAYp|(vo)fG6%>1`To0Z)
z;9XZP2xCWqeS~+d=xj{MDnDW*CDP@;f!Y6}UxMaf67Z`~%eJaXJK!YWv-diZvB^u|
zDOb%}1QonkodZWUb?be6MU&%^VD3oJuR=!ra6$1*AT@3h^{ctPv#MM&727|fW?uzE
z?oBDhL5D>8jwPF{O-Al$O^0h0n_jEp07Hb`>O?78LR7xyk?TX|Dooin?C%kkW=h^#
zXO9xzlnLKA&*dMOvZY;vlFlviu~ul^zsa%iY-{I;48TcMQUu6Na4Z}W%&RJqhKVzZ
zO2DtqB;C^2!AZ1Le(ERouoC5~NCEJs>ZUVG1-_>OtTCl>trN~{#g-ueACmxI1tetB
z->Z|pYSrwW`%MR)oIe2npkQIj*IJRK!BTwhfoXwN%$jrms%))w;v56|dlgvPDHCZ4
zxJ^9d_(`&kFD)8CtR(v0f(YyYzWWA^zGH}{Xy#6AG^NK^5qR`wJY%m}6zo}{^<m1#
zS_2?8#UsD981gYAmeb1C-g?2yja;mC!NV<@w~5=D60ufby>IR{juI)-cMRDfeO(u}
zq!F%iO6QjPbRzQKQhe`$DO<{I02rI5{Huoqo^72dMLPuyETrBs(R?bByqJ{tDsXv|
z`d$TeZ_2z{*N76mafHoU<Y7Ifd<gpZ2AR|(x>q6O^5&w0+jdO&_%67eMRR!JWTf!m
zt*#X%whE4BX}4wYH2L$K7Lwho$SGjV##%u%GbLjMasCMtn}&^|WcO+w2U!t*4>cRp
zKU1fJ$mhb5iKzAq9%j)-e_51RDg4PI$9y4uixtgj9F%Pd^Hs1^w#)klOZQUxSN`>E
zCuYA$&eyhm<sNj4+)!}}xT)fIq6ebH$%v!J%^=W<Bv)Gu+nT49?_dHDul=HeIP=_8
z=sSjBOiPfjg5|eeOni{*j|HL0$7HySm9^AB$x%QKu}yitiZo*gY=9*>=q{Na90G5N
z_|-fn-mWh;4w65XD1o%@Q?CNfqBmn<D^9Do6#Qx&XK(5EopQ!y@Du-3FpJ(n7b8kH
zP9yuLk32HKZEE+`OcM8mg%yKQ5B0uNj^62`kCXiE`tU<>VEg^>Zv+5H^Y2))i#H%-
zMi;e6AWC+-U_lTRwkuK#Ji3nsrD&Tz@q3|dI@H_97<Noo)+XC_qhL1L)=-*XL~lTQ
z_X?6}1-E0n){K`_4l6bVx3J#S@_<D7la>sd5n2fD*LHdK$$r@`*I;wT7on8k&}_&F
zo^tk3{=r7X10$y+8YhaZ7%uLXoM1($^Ol@oMf%8hbWV}{4<13%@}DhUQU&#AQ%<lN
z!*R6OfcvwJH_Zqi6U=NiimWw<@K{(YmIxDI7$o?2*idB$wd)7FbBixk!T)(n7d3Q{
zi%~LwcCttqvy}bA5h55s+qCU}DI&4zhAt}GY_<L+rYS#*+i+ZnJPL0OrH<Cq<A_M9
zC&Hlcyuj<(rsG18d$w}RRz!_%i3!$Z_vDSJ@-(A_>4LvL7L;O2n!FC&YG+!8CoQq4
zNR6;&w%aY4l#0v=TLBIglwHMfJz;8j6<?es;V2H=LJzw}VWEel*F6=KqK)*l)pq>N
zk=^JYw;&)DZH3d;WEG`E)r~^SK5A2v@64uZVa1!bO-m78*L_6_E8gjk38ieiRwK~D
zx6y&I{AZ3Ucr}V_1F>kEPAm{@yd`RQEZKBzQj&kP?Yb`@AZ_KUJyCVp9jrQ7ZMFmq
zBknF^>aw0(vYsztc9`qROk2H1iIr3dec=_xf_f~u8e`4fTPqIM<-NJ$BnxS8EjU=+
zH|2Gn2nmcuRH<z%$Vl%9z&tV9N^M(%kF=H8wk9Dd!v-Z)7V~t=34&zp#}cJ{skRc`
zR?y)0zWW?UjGc&r#}Zw-v4|aA+NuX3YmwTvI`+|fYa0{a_$Xsk(oH`W%t}YBr}*m?
z{HDDXOi)2_+Cd+znMVGGL`EcKG>qO37*Jc<MKv6uCoK7kg>jba5}c;J1x`3(;I@u8
z5VUnHlWK3-Qn@aUsItxDjU+y8$y!!0pEg3&;=S04=w#g+;hSA`BUp25e*+KqSO~T`
zrawh9kD=o#R&UWuttoK6_r`&RLsD{YoqeVYzqh3F;J0rbMj(vi9e<h{ca-(Q24gGt
zZ3FRXE3&FZiia&Jrc=)G=f7G8%PQ2a6f_;%of8?GgRkJzq&#gg78`WV_a!a1a|PLk
z4J@Z)K+GTZf*XQRE%{4(Nw6zb-k&d#wU}^=6TM}`%T_AfV~B<<&hv)7?6Vn1*09?>
z21fdh2-jsbjJ{P+Bev7~id8jmmTr_Uyl*AKZOK^L%7uFjG0#Ond>TkhTZ&f=68?Kh
z6b?wkl_Z=HEmTx*nfUHAU2ZFj@y1y~ht`jG#PU@47WzV1@>sGr(t=CY(-wEJfzkA_
zpcFG=ao!)xSr}fziSWjy4f_^X%$wxDvR8&y4+*^$L(?UPhaiCyJI$wOil%18>4+nI
z?MX{MiLMasnDaLR8@SnK(%c4QZLb?1?%BbPLQER56dPhRx3c3lh)8S(=rrg+9fKmn
zi^L-t`JEeYaT^=p$1Ngb14Ox(Li`#yR9jTW1`gF`F5MO|=U&{wGytJ{Rg`jJSXvms
zpo$=LR16>c6_%b(_R`7#0@bsXkN3vA6CP<5lfR&lVeE>$t=Nc91`D=8p|=!*8%R{|
zV0bv$Qws{9>?6Agz@mXfwV8gmC5LJ&`)&h=YJ<FZ$}t&5UThU4`#nu{r$c=#tQ#9`
zW$8VZ476vke$8$6vnNkDjwxF#WlqqnPDDRnk94d>U~HgSZE8}cDI1Ly1SG4ME&xtC
z_T&OmcZ!i>6d=mA=TyD$tmjn4vHQMyr8ueCAUHOh<(x8b(uTmJV?wpqd(Ww=bMHO*
z&)JcoH<01w%GcYfM~QDno*NwtUpDyFbD%_3Rcu)s*j1a!ds`lkK_&qP$3^i2<j&ek
z-`hfD?g<NCiiW+ja`iSG@NH2lTZ7Lm!epZW%uA2~PP20JHt?*ru878Jy}+sFvGC(1
z8HlSAoAY*RxoFrMQ!4uyCa!^k*)e4Yc#C|8u2e*i5*`&8R(oo(NP5&0S`xejp6{UN
z0Cv<d@T&0(0gCX2hs*Q8iS-r}vLS444=n~Q1#s~)gZp$PalzT&;z_n7LxswP^O|4i
zUVsd>Rhl8HOJ@x<r!9(PYjAvr<RU;G*h4C%NHDP@KW}SP{TNFlw$XO20ANRK(H*a5
zho*0EEOs6>KQLtLuHG;NFvgV7N1GG{h9O>&!EgT4Kqc8jU;Sj790PAly%2o#d%>vb
z!{2cfc1+a$zz%ij!ylZew|WTN+Lu5veA3Y+*8vXC4t`<-btwc#Pz~nAOM;|Hlmrj0
zBU0#?@YI5pv<Fei2IA7kf>Mqnk$?vF(jLSm8`w)*a&|50OIs;>8|X`0DSI2(OO!`>
z(v+`$)i}Y~eTg!UC{dXO&hC)NM<0C03Z76-FiGBkn6@P*+CX00(i3PPxb2L%%|2qY
zd9_=T(R2(Pf4H`t`Xb;fZITk7BNG#1FE7!Uk@7Em>~Lngb^xF!y(D5f&TY3yi4F48
zyI&a_>^VD2?W=AzHk=_+Luu=H9)0T}V!tU?Vgos8cTM@8_h6-lFYVQ@L9=(iYC3Rn
z`_jOri`yk<3^vkpOjyyuM%qjT+;Wt+_>ZBk6J1&;Wp}2&jCfL8*@BNH`@`eVHcFIG
zDd<R>gvgd`q$eyC=z$w7Qe*>zc8e6*l4HBOKKyvYpWTP*g3tR>^$8a@2#*b!7q%FW
z$C7RDe1aoOczT%7yGtYoQ+|u=*sw0_F8!WdJ5C2XiqY_^E7YYlG*M1fA${|Ms<c65
ze4?DMX4Pn5(u$?nzyyD(6@e|j$y9v8l*7tz`p7M6*B$^%`R-aRu-xyi6=NXGc#FT-
zz;oIX!EEu-*b@7_ic5u6Psl4>F(rJRc5_t@ceh=+r*wCla0Kw4Hn_M?nij5N?bxd}
z0S6#5UE!wSF>U1oKIMc1+ZC3A1FM9<4a}xv;nRl$+gNHT2L&+pShBfv`v+XwrbPqf
zsNJ+^3~W~+D;0gjWLBo(25)C8*Kh-|X)BR%1F>m?rTwHSnkZjk;?M_*Rq$Gs^`pU|
zI~F|s2@%FEI$^^l7=E~nyKxafRL(I_^(y_(Hb6&jP?Ff<4IWE2C8qQ2A)3Yd;9Dy3
zNSk2q@20sraWeDL+5$MMe8CNx7Q4wypB*?9xr1$D*VyDGqzcb&auN_pbu6qL8^@b4
zxPhd!o4)81r!7r_XGvSyP2Y3SmNsN;;t|5{Yy|8kCW##F$w`7QI@CR0l429gwoP^H
zV~N#Kd4b#9k-Y$O6I7-xvS0(1Y1f-~0Q=po^u7&yVrZAewt826s*w_7S53N!qr_b`
z>t_Do>ZQe_uPkM&gxx{TY1fP0K?8n^OW2atv_&Os03Wufgbl2w4JP3emKiE*SW`e)
z+DiP}7Dd(cU0zw@JuANUFR3;hl2lE|g$-Yo^S-d*tJ-_76w*8v^aw1bV~NKJ4%4pE
zLtAid>r~x1B&kzta*&;lZXBy_zfzKe>ss|4PRwj81@O}rW}b2YH$)Kc$N_vxJJsm!
zO|$h~LkWt)RubR_F4IfI4&dQd4q%GoX%`L!ovj?dZNV*-eo0GBt6eplA<r2(Hzt1)
z6R0*Vq@X-eKrb!X31N8)GqvhVz94!C@a;)cb^`fh0{7jus&4Efsjkuh9&aT!Y9vDK
zs_!^J=PjmUOCr=u-48^l4YFbb6>4Xo=L1uAlB)zT@?Et`EDL==Rtpff=nK9K`=_FX
zW5p^^T$2QQ(V`DH5dSMYNUl^-8bf70(M|wlsa=$3hh(Xu1&3rQgv35+N;N{B7aX!w
z(OJQUM_UY~n657YM8tY+>GwCXsl;`>`B-lD6`Z;hZ47p$a-vob5~C!pn1AENAT6qB
zF(EIiC|0>a`Qpei;sZxslrj!C@S>D(xRDoygu_q6!PhQYO&~T~w3y&TZ5N#gY-~=8
zy!y?pX3<W6!);Zz;07L(QUf>gn67{%cudbO0OZJGD)I-&VxmUcm97+^50#Y7lczN0
zfD5AAD@v>w+fSt&Za9IxT9zAusats%8rV-o>jK$NVmr2^G8Im7GMP%%Ndc)$Xx10C
z%*|Oxj{wp-Ta3lFjjySo`i*U65mFBdlX#4c6s8hLJ=jYtGyOa;oq=CY{0{u3C7NRk
z0#k^2qI7z8%6yZMOLURrsDwiD-ZS}PSSTTy9a|0rFB3RM#v!x}NgfwDjt!iNw~A;*
z<5|j<Yie6WoiEqKPHIwE@c6+@T4Fplkc^fKu`{FreXEr=sFmu}4>>fKW2!^LbGfEF
zRPUB6HC+P}X1Sb);K>{jRJ>`R+uUqRIn7=&sURaQkrNxJM@w|X2I|pr&E(K$1)>Ly
zszu&Hn(_y1*2KUKlycDY{RgLLiDTFdDbttB=}%74F>t6Cn$=OV7>uU7?v#7Q7aMG$
zmjWy#hn6UZ$FlGnj>bk~)1ktRvb93^kQsM5MSN2%e~EY4Kp<M;9X<^NqUHM3gG6){
zX~7{{;vF{g$a}@d3lh=ttDNh2k@SVeUmpufr)4jl+uRf^(`g%2xR+@TJ7sQ3Rc@&8
zSkQRSD==&hQRpL|n?r)JI0oJ|M(ZuGn*(|*cpez_m5i(hrg-T^{cE6=E>iz)Ixx-3
z&nvP-^J|W9)g_)^1C<BbzOcm0A*x>kx93<e4U*gQ91G?#$UO^mz=k=nlzg~>j=M+)
zY+&pzzVd0BAu7z86M|i03^q)~D?HphufSwUEzu`Ttaze}+?G3Kh_x*Tt$7*$J)X}H
zAc)N7OBpO0mYyXY;)WFI%d|nj8U{(^2d2C;D_-c}Kq)(?1p*YIV`0S*M_Q%@0wnXL
zgvKqI=_~RTH!#<)4s!$d=U8|y0`AX}rd|X2=U67nGfI4!3{9s8kl(E*EPR&?&6f)R
z{{E71Y0J;wGGTlO19%`49fo|*wP56DcTw)|$Wdoo>E!pI11*yvX$K!@NguT*Cnzks
zOSbkZQdhLLpcJ2s&11X{KG3n`<LQvsUz=Wjhg8xM`>z+MH7(Nr`l(|x&iF`a*SrFy
z=-W2cdY;Ht$)+E-BrMqB>@6t^_Vfprlm$Cn#wBUNj@Xyym~dw(cyF#Jy^PH7hnuDo
zyY}J*n6FzZB^_SyG38HYHbm0SU;-_&?>dM;@63US@Lr(b^<)A?xnoRLl-RKJS6`_H
z!3J7;(CO_U|12@|dXj(ERrQAA(XsH(8zVa?Hq$e3Ymt!`hJ4~kn}<!)lH^}679~7<
zoQ14?h0+bJm6$jPK*z$yQZ2px3*IIguK>ah`p?=*;|ND~D}^5TKT8Q^I|x7v^t>lc
z`9P}PX{gTcs(0GaM^4FFqJVmmC3O18Z+HhyXl<n~1W#yfX-9)5v^D|vo;0E7SWq)~
zLThW*f+w_=t1fuF(h2N=I;<rKuLGG_OVbp|Z`R^0tyy3#xeZ;*QHnKwt*a%U{?=N`
zyO{i+r8K-99H6!6n|E-4p0!xahHo`IU!q#%s`X$ArJ?XQr!OB<<pSS93kqBICg0#N
z;I#yl6{f}??YMWjH=?$_Yq16GCrs>W&c!g{R#c~V9fkBj?P{_6ps4C@{<?WKTp=92
zLJHle>e7KVe#sP&a6*`hu8ZC%HPx|XXKca??8qAyCN^QCGf2^Q4A~dc0u;2MFu-B!
zAOdA}Q|FD)mz%!8@E8<n(31-kmd-(^w7gu04mA0gP_%4P*9+(<;;lgNde~T%vm;&a
zWQy~@k|{XeCTr>k_O4;eRl8E^ULHgTq#mXTLv~DZ^$nO?*zn-MAPN(j018p$b3hZI
z$dsmRdCL|l<pXF&VM2d#1`#GUfr{}8H|PzaIALQGD*Fepp*N-uu%a3pI*3FE4GwoL
zTlrWU)7fs<kK(PA(D1QjU6L9;`6Vh6Q)q!{NQxk`e}_Uvn7S^^(Inr$H!%6agqI1-
zp<{|-+*WH&qd@;wuFf{u3o(B>=tW`Uc&B6iC7s4ZcW(k-CDPsTy}=>fr>uMkILQkW
zTfix=@POWS6!TAw{LR|I90t+}?oBB`2>o}^io(R&kuqaz)`CX#B?Aa2;B^)nZo|jw
zYE##9b+)PVwQ`Q4W^Pl`Vt5otClLl#?;J!WX6?-DAtm7sf%bQrl3w_-i?iQx3Ld6>
zX*#oXTu-5ME{VzCnGz{%SOt)&JWRY*z5vRK(kt7pOv*`7$~&Q)3)OWFf?1G;9H!2^
zAtLN|kdng0wG<qMu(38~;MfJlm;p-C(wVekDG}n$zvAjfM>mx8p!b1CAj1DK<s-<*
z=m)m!9aV&TkddOy&JA>KnL5Y(%**&41h*tia0Wm?IVKddZ<^g;u`ow<OhNEm!iHDA
zGa<-Q&SKD(!i3j^Q+Fx9ZSS1BYomz1-t;yrJFB_f7dyMCO4d6Qt|)D62NNl>;_%AN
zRw|iyXO@&T?>k^w=JPi!a7!D8&TJ#1`ZKjQWs0BPnP5h;!yOE+FNwPyBd&#@GfB%5
z8@G4nG7&kykAh;}dN3Q3B!)XQkB$k&l^+So3io6br6tD$6uEbrpuyR_nrh3<ZkSkG
zWwRTK7=3+|K|TsozQ-URJz-)4TK<BSH+Dj^A9SO4+9GfjpRnQH$igIA{;^;NY6Tdb
zZzPF*$Yk`S4G#(8k72@7f?{N3N<xJl&*+t1eVit}aw!e8e6pB}-_)0U&<~#a`i^vi
z=S|219#Pn^whm4<5$F3@S<J>QydHCt2^Gnh3Nkx2{wl^yMEXAH0!s?G54ylp68(M9
z2PSvE4?4kfsUyntL_n?&POZy_KQ=T=*{p_f+%zeNaqMowDQ6?DYdq+}PR%%`px1;O
zbYW+I-71%pNm^VVbYZ8yypt~MO>i}t;%M?jtxsm`nmSTDwj5}EXrZ<nCJZ$4#)Jvu
zHJNQ}-i<tXL}AOZ5B=XLvk6MrrSCH`+JuRlw@EKnlEQt`jfJLgpKxNODcnI)3KMrX
zlWC-;Hu=zFiacLzL*q-UUH;^RoQ07aeJZyY9Oubh?$oTExyzlJvfwbCJYxEgPI}J6
zRUaK-@#OntcCEo;HgYJQzt5RvtfG@1@X!Z&(gPm)AkUn~c)iaAoSes^&%Y9vv4|Gy
zgN%TbFyTuxvEv<>?32!~bcg%oes^%L&*Kh@FW;wJ;-Q&7=@JjXbCU_`h7!L)rzuRl
zG2G8rf;P^4Ne%bOo$Vm9H?gr5`Tkh2{{#L0SkMh^t-+QG6Q3ZRZPE1mj9-lVDmWk6
z&<N1kex;G4w>^gXOK*FSrPuQd5Ej1cbhky#?~CsC;1Pab*zo43<besDA^x|xlg&(a
zD{i5!_Tna%iJ$sHtW22jGA?dnMd0s?ezyqxeZlh{+G{T*799LyFM8TTaNkN#dkF1Y
zoasZE?vQ6POc<k&Q*w&&C%soG^Y%sWl`Qza=)86pLbN#X#D(vR6Hki0eR1dcO6<p-
zXXZOh%SQ4)Hh~+@E}VSPf$egj7yZ|Mzt4+KY}faBr4!rrbzXF0J0|T-8Mw8yBQ3|5
z{DV7R8WG_;Jnk^@=A4wrcYa{mxQtI}vwNJli`!k1;g1Quo40qy-f8c=()aE1suy>_
zed>)f_U}5{i!O54cYV=C?i0m^)QVXD7Tx0%kUi@t7)@bf103(5(v<Z@A6nG-zBwtW
zUz;{`d7y~iDwF0$nn*!uyRf%i8<NdUvWW8?)TBrXiSgZ>PF)}7oztl+X-D7Ox%R3W
zxpNiOy>D(@rOJC#NA}9KYGd;%wtL_7ZAEwQn;Tm3-TS7y+wXUI)8Q54z3-7lHh`HU
z$$0OZAaYXPV>`L&6^rxUH$7u&^!CjKK|;NKb45r{B-_OOY|~P*v8QeN!f$R?Nqp~{
z?sHQnp1xO>^9S^UMN#jYesIGK-k6#a%<X&g1J-mbwz(}8N4;-uOJ6BImAsRuXWPzR
zq6yC0be)@ayqli0$nJg9b8d3OnS|`vP>!Xc>DvroF-)kOd1#xa_@=j=Nk|{qa3}VR
z)3C`)-<*b0+3i-c2tlZB+{?Bk(;NdjCO{4Br!Zk;jgEGcl2<o4+O6Np*g4H#qoXY@
zeK$JVt!p(lI@*mNXG=%B$=5eJ+D)f*Mn}6f&1j>e-Lw-oE)Gr3zHxPZ1ymf((l+iv
zg8SmmVqtN24<x~Lad(2d1r6>l0TMj8LxQ`zdvFpQ{v~<ed*6HS_s^Uirk}3v>aMC8
z&Z%ck_n{|t15tfjvZ$~1ULB@G_lmk!+j7HIVUiulW1**JGDNR?5pt(^+*Vl3;_3tP
zn3io7=3IF1LH)}c)G@B;X*XF*H(j1y<lVU3O%add)qEBy`?8IW+{QKJW!v(^VtL$;
zV=24l1LoyD8+B=RPgR#R+siu6lY{u8J=w$>yUY4-b0<>1+K~^o3R>EV<iwlRs);)D
z4WDIx)f2nTZXCF6{%X<-T0W1JwSGWfd6#n9bv`9K(7wEvK3k~VGR})%(N5grbavZ(
zHnpFKmvZc`tA!o;*tqvlvDC3Zp+Sp1b5Y=#McJvGHU?%9O&WYL_psbxfuGt=3_40J
zP6>_3uD(YO#n-cAG$dmWA70J$X}rD{Ox1P(9zA9{wK5{Jn|VwVtuLw0MjOreCL``f
zYk71mCnjqS22Ku_EB<s6ABNop9}1@g@kWqnx|57>(y^cOo9h{FY(V9y&(Wf>bAB5*
zQHo5jy+00WD4S}JVew=R?RMv&F?wXr?FOlHwLW-^hGic6u+U4zOXQy@0rdoKk1sbO
z9AR9FiS=va?LE#YC*72RdOEl2l$MiRmr<r4SXVQN_l@Xx_C7#1cqH?jck9@X!RN(L
z^3@?UYA!y}<x<ORbJIN0-i|<?@ET2L7UUVJrv!C2lCnln`Ytz;<2khPUv&q!1%UZ=
zxRf&&*E#k-MTyNe(-+$2?y@}I(_gls>V9}VamTta7$bJ2&C!`Zc9*1dN)J~@gCl_A
ze?-|~PrWFhz>8T?unsHfoI)G``Ix)N=oFjQxv>m7O7LB&wSA-Q#QEz63VM_|avC={
zNrog;5L{si^66oJ19`CR!&`hZ$@yvb7kVq{fK2QZm~J{6KCLfn8L!{Vymh4EL8wiW
z?_?k5I(<Fi4@6nu=N7;oxqH2rE>Hd5Z`9?y)(Pre!g<^-tpy#6@!GH}<`3zXU#uPv
zeI*}DR>uV-y4!0ycaIkfDFoOKb*S$@Ub5mN`T|n69b!)rH*}X26N{TqsMj%=VS77D
zS>nd{=^}CiwSN|ApN+hUQ5dIO#<1^Ly7F$WS!c~$_fMRl!4eQzb^Q1PaZkIq%k8{o
zsR`*P>=H9#u8&{pwo=*=6vkjC^hqE&oEhUj+cyJ8usxb!xoX{=*7%Zt8Y58|vk2@E
zvs>R*R2uxuB3qK~G<Rg7YNI+5U9+PW#_3m`p}UV>ELY`1lxM9MDz>o|+i_52Yu2Qw
zdUp18OW_Bk@~(07ONU`F*_4z>y3`fW^*yco<*+dlPR;0-IbDTBeaNgrk5Hb2-+IXb
zc8$({h#5?7vTJCu_0i#9M^o%1U6hCFyT}w<!X#ZP=svvPW!!aMSJT-u8jl}RpOM5Q
zmYI8Oknn}9;HDE<1+AJ)oP@yEr1PO2Hi#A9-`a0{JMNxTbkC8~g-zFnuFAK=(+%q`
z8=8Do@`yagt<l*>y1H41u^m<$C3)Z^EVIw-v&;{28IFy*X=&-~T0H7jCg#um`H1P-
z+t9Shi>k#W-Ws3#$6@m@VVPMGYn}-EHyn{4(1X;Q8{A-VSV3KpuxPCK^}bv(^-X;b
zu#i;bu&sgo!Nxg;efd(Y4)ykc%@{v%tg|E586x+RtqxG@38xm1OF@HuH=2eU#2WX&
zK1_d+MGBsu-jA-DYC(({RNR-8K5v)^T99_lDUpUfvLgugpJ8g<^Sg|X-~x%PIXaw3
zFV$MsPS&_qZA-z*cq;t()swC<Z8c<Bb^t1R)p!LvpDM&z{i!-p*T{YZN`3Ilr_x|0
z+_zuH=z`bL{Y;cX9?khteymGnqsUcxgk=g7amDIh-a}iDN{*73sH_|9Vi=D(#a&2u
z<E#uI`6#deH{wS!tL=DSvVaCyzpjA8(QV_?;Ya4!P2S#&W~lF1H*4I(TC=Y@QXxg&
zu9VJ?OE<nmuDYE$fUZultM-H};TK~Eg$%3prq{0t3g*t#c+8J$pel#a*!SWKj#&OK
z&F4>fY63+BYabh_y`(4lx&rJhd*3YuE`#F4cG4|LVbM77YwSce8JW#}l#;;fc<`UA
z!A8?&6PX-LBNqFOd;v;3aSx=e!moSU-JFA^U&5NfvSzKxtfWNX@rV##EPs{r<KCf$
zkIo6qq)g`>V|FJ61U5GKj6x9()i0sjcX~}8^~I;L*(X#Y{3v2oi1t?d$$6KvU95a5
zx`Lcyz}mLf;XdP}(1P|@4+AfCpxhV$gK$}_LjeW*8Mx|}yO+|VL&vvkKYmJ(rlxXx
z?`46tC$o8E^n^je+O!8*7cG|6brouUQ1Y1AJ?Z8;ZV{?HS$@b(M0Wt6Rxm}sjq6N0
z{N?F5G&G04BPKv~=j8<{h0#s~I;`=Cm(30Bn3xm&O|(FhpyUcp`E{I|ANCq}zJ=EG
zt9+fC-`aNU5h>Nv_Y_g>0h$SZd!i%hf~#<&7F(-Q)ghiwmmw6y<*5QhS#U9A!mWqz
zankzT+kDX8YvsIe<ne(e^z*jx?ds`d{kg&}m2g@l5_h0+n)iG?--g{CRG&R&h5rQk
z64nnY5!grqtLEhL)6o=>kD<6X&Q7VfeYelb1EXQk=<J2L1n<}P(x>fNYzE)`pSI&R
zNOOE4uLRB5_UPdJ04JdSIW7Ws>zfr)gW85#H|fZXB{+K{0VHn>X5J*ppB=n<@D=#3
zEk+ll@{ug=qS<cHZB+>_h@XTFMPt@bl%WwYcbzQ`g}_Pl8#bavPWXu@8hMRV(}E%9
zM>ra6qW#YFhtXTXjX^Gm=7y}g%h2yq<kj8$aCV%qMac}zc!OP}$LhUMSfIKGi(Qcb
zK{wR+PlRiMH`Ii_e(1ldauNim(%9G`TNeb)&xzX*njWVY3qe+s{8<tsq+y`My$-cG
zSZt0&MWEm7Ckt!10PZY+h98mykpTQ|GN?t-_cVB?-J}OJ8dE}GIo=7~j8-uY<$jP>
zO6x!I!fX|QOoU#K)pGr}b^?GqDQYWaY)f>wqH=|%Lbv}oA08Kp5@%|ta*EM}qG%{)
z?K#8N=>@$vcNF1HH6*<k*PJ>3#>LvFcm~T}DJB>kvJ5Qsi}CvACLPz>rFxzIBRU7s
zzSRrG18RDZqVQJ%!yVP0VHP>kd#KStI)B8<79E%t@PsTv>nQ<Vc_*_%QIcBBRYHE1
zxOOP~i5tDCz2BgV0s+Xr(W}o&!yQ@bg*B@HBS)jx>Aj&}-*z4u`e}m~+khE$)ZjOM
z5{)Ku@*d)<mb)=2igu`IQ?Fm`1<2@Q{kldiV3#_p{1lrBO23!{3|5#D>uqs)sDv-k
zG|8@&t1<rKSp*kV2J79@(~?XANhF43FUjPi*?5D%!}Jc!YwgkDs@!j!+)Z+_F-A;O
z8ol;-06K*DvvwWx4zC{&#P9`DedgOqC539E-q{~?VO@;7%wB4S(jEtRZLn8Wooe+z
z5U+DK5qQHgGbhuZ_+`5@2YGjNIx<|Kt5jwbv_k`DX@>YQ_cv5_yeDeyamz-dwm+4U
z5)T?YyojyvLPDD3`FYhjkMb)KV|WIje*=gx02p6`!&UjPeQ@2Rzmqh>xgmDNwW7XU
zN|7LqT^nJb=H6i6T8oe3sZ2a$mB3si#m9B<TiQ0Fj9zo)y~4H#qnlEEkngP}Mwx#T
zvW}rr({j<>wjVF2=VoxR7dK0a#OE}Q6tg`ASqh<RskLH}`v)Pvm)qDE9h@%c>cn_a
zo;b_x4Gc1Iz5v}mGU{TTAD#X-jc&J>bB)c{L7O#IS3Yh#P_R0+omen1#gT=E;CHS^
z-~7eioB54Exvu9SMF)Y}h^j4M3$2p{e%iba2t+xePewnMu}ze}c7=jDXAQ#8%p}q1
ziZ4o1H&jG?bY>>;AX#*7I{tMgRT#yOhV_$mU=1pC;2Qx+j!Gj^AS@c=Nm_S*wnvNA
z%Ru3uRT9W6=CjlYP6ITN{E^s79>lN&8|;P!{+wi}W#3n-Cf&%BXatN*Nu9<K5DC;+
zOO~L!66BfO{8(L>v9~Y6(h4pR8&p}l)}YLZle{RPe|St<BfcF-?}C$3DQwvXN8#A6
zTvml7MSv!$2sFhm5bw;1e1Fgr%a41Ax&WkGS$HZf(t8QR<c0BE>2zl5&fHq^6w#a3
znTsrT76UNGcz(WU9xOU}g^sLK+C(*qr6bYppO0V{w?@9kM>;9NyC~Q7gp@YPP($`U
z+lVyUm^X9A;t)M49^`!xKenZq?sl5mVsQ~&lTHWu0(rq5mmCpYUo6&*fIC@{39cu*
zMR%7>ffj$!zDIM4!HHunqww21GCDn0-j#JsVj<dESTnnoS{LaeCA)<t@xgTsHbJrD
zP9W?lfg_tkHHK7t#1p8)oG;1ie2tS-96l`}gVt_gC~(}F`7>cLtKuMBw4&}oQ?FwN
z<W)k}Th;3b<j@JK>S;W#T4U$S+l)b091+Zdb4Nsy(R-EIDa?mgN3dernr#=_%y6`_
z&MEhqaF;PL3$!Pvx9!f~X32`M=C?AXKInefgG9pP;f4hhdXXb}-r75L&d80ZEj0lh
zL&0AX3>8G%ZrlMqEQF75e;xgj92#A#bjfopGukANMDOdK4{WI#>vzb1vVNvaKV#{J
z9<NZaPgcz~Vo13BwXIR0M(_p2;zgBx-d1}J1y9`>qcn66UBwbCb#A}p12JTx^5vq~
z#))8meZfxC^8xQpxYT|ow@1zf1wB~~p6y^OOlh`Gq4Nc2td_SQVa?)PbT(SCgUFIS
zPB=S-Aj^~~#m2O7|AaxeqEQkK^w>(&4%Cb#KTk2Tr<D+m@lS;Hg;%u4`vH)|7D$S=
zI*)K>9uLe@G76<PTtTLc6Hjpq2--><M;L{B(a$i%9~iV1x1Fhy<0yNfR2df?tQ&+d
z#hx2s?^HO=pDVZhZJK6ieuHQzqo$<vvg4&UV^NbmnySLX$mnhrgm)H+pu{$<PDOFM
zj+ZEm!|(XQqCMRak@)$T*$+impi7etdQfWrjVQiBo?!2UgPJwXASKWwfPbG7ONotH
z7%yQYfwkucEl;Xmk)FvKonBGt_i&li17L^7YsB4LDqN+r@Xt=<gMmiTfc6K@6$*S^
z`wf<huIt=z&^U#Wt10DPDTg=noJ~@$>z1k7R;Mh2nmwY~mmj+7YHL?<`~*pmJ8*T6
z*7{b`2=;EcyN^OjLje=+EgCjz7=8{sC+|QsNy50eH7Md89LL8G@8H5dHuD5x2W%@1
ztZ`!KmW=hL7&GCLVJK85qSRByTNieH=~Jkiz%I%dGGM}OB7`7fAaL9lYQFU<2|Co)
z3h;izheWV6Bi0)7`NzgX_U-7&bM4cD?Th5b!}(%Pt7DIA_cunAm`a%8kzSp23Y=)x
zic0UCCRMiTCj0O+rt>-sMR@#g-n|N$v5gXE#iN~H2|tC$4z#E2S=Xp0ib-N=12*2L
zZn@K4iz2wMAde2~{CJv2k$QO-6mEdwWCVweMM2BAE-}?tC1PT0YTaLzb7KITs=U%*
zWL|8mlm8%IADn(SogfI<w(rvBevM8iU<tczPg~r_x@k|j9sJRO=Oa#c4_`(qs9S<B
z!+s~KpnEjk4~~Skbrt#eV|WNpyeCdlxZ?`mYA!XIpkZl~?621muqo0zieCu#@>?Py
z;Ev+k;uz}{6&H`bopX8-0luVCtLo(U#IznV;V0oX8Lz3{8)chO(u~X@FC-!fg;@J=
zJLm5A+?yTCwi8uv2Pb~k2~}it!G@!9YQQ(ZPbCPysNv@Z5=}?pH}Bm=HwednIF0NR
z!6rOQ0HcIQy=OkN?-TOs!dd40!YqP0R4e00WSsYMB<X2{X>EoKn_O~bM1neFERMqh
zK{+-sa;gg%u+2Wn2wnRPtqcx^S8=E-wKI#Ba2=Vx&l;K`-7jKj%ixlThS}XOJ<_oQ
zJ1ikp2enkzTY=tma$AS`MPC8Dfaond7J^xxnV}ylY|yZE=~?6J7xK{}c6-rDA6LdQ
zMM=QF$Rq_!0Rg=nuSbs2UTF1puMx#DG-Op)Ze$5gP{KHlEpm)W^Ae~ecqqVqM;2wk
z_C3>}W!)SzVAVGBM7aIb5j3CAeuICTFNmBXM!T~Cmu6+aIuhhbUQ@(J*EFfID`uA#
z0(bypyE%xl4}4y!(q})~vIDTK^yp+jwJ8pLn|Di4IoX-B@|NjX?vcsp*iww^#Ac?X
zqHqx7=}<V6d)n_^75dqGb3*>q8<U27XbB%&LFGo=HuQA8>U;m-WcyaA{%QN^N$0WR
z@zQG``|0t!&lJGb+twwig1dg2-1qk40{HZ3H?W$ZY~p)+x7&U{o&DGp{h<DI?fZDA
z|1>N7(7dbvw9oq`ExYPr$@#7R_LBGK(WfKwr?b_^YyIrQk!8rH;K!rNg&nV>N}hJf
zap9;4s@;4mJ6Y(_S6^LMJa+rutwJ^%e@cDvYN_mmTlkgF%u=<@Wla8!HjB-gRB0g#
zM!#=SF2&`gxA@aV`xD4=j|Y}-M8wt3#rtt?o3rjGXmNi1S7|2c4G}~xl=a}Lhw0Sr
z(PO0jR`}@@Ls%*PCmzpgK-0)4pU0HV3)S*fTh6ZLxvlZG7Ti_PjZ^pS=95r+8^eYV
z6Ax$h$37%eqDM_C2a@RrciUZf9<T6KA4^}(%Q2t&s`gbCX29-8lNQx!%>|476aAE`
z&5A<;g~taIWT_TbD!#KL6Po2?Pt9C%2;@$iR}3JX&Gtm1$Zqz%qquBeqfn7On-;7B
zwx5vmh*h9|Bf5PQGv91sP0$*-!tV<9)cpj`JpsbmyJrW-4rO~0m^EMXW8_2jf`whY
zQ^)wa{!|`{j`4Q3QD?>u*zNzbRYB}%RS%(Vy;b3|+YU&)|9H+&c^{8K(I?$r!#JJo
zi?F+NYqfiOO_ka0dZ$M_9byM$3Wp>sQTn@9bxo0SCQXXMn(TlzT?<5{Roe69E__0>
zQ@SjIJLiivYtlD2bOtKat(o}}kdK(tA6)u>JWY)T7CQo=Y_=EW7d&(^n}Dm2_n**~
zs>+YDk5-mH3hgb}wI2#U2Do{{s;L#%iPW9&)v?smTyap9-XEESsWl`s*sm`R7Cq$E
zS@;%kpSJTpg6i*;1^vC9LB6}l_wY<YPK>J~;nL?ey9cJb_L|ETD-XveVGHfa43SUG
zgDEg_$;%lkt9o_VLu=RuH+0z|1&KGA(>p+WKRikV+g%*7Q=8omtJdW3z1t&`c4zll
z^7HrjI7cTY1Co#t^d*+i<t(KNU%`#+_d*Ecc5`xj5Oej^35i$^d<AMn;ll-Kv$$uC
zkhfR4e)jOzQ?IgCVd<mI!QiD0-Qgn#7yYBel~VTY2fAzTr^j!j%*Ii?Jhp23MRuNj
zQ>`cR75j7^9;#Y*&pRKtmh*h_X|I^Qv{9z9y=%Hm^T{igM(~&so|ycJEtohoXmbqd
zRT*)rLSKF09Qz^ix?Olm`7YH*74u+v!Rody8~bH(g}i=I_MSyf??bj;u+R79bQy~a
z+aIsIpLQM(<j*4{@5p`b502f-+Pxpi&w9QYp_tejJ2^X=7}`AF*%?`)yaKQRp8o;>
z01!Jj2=q73`4=uA@LUCyeD5r+=4|L}0{8<wV}@*y0sts33Sb8S!G@5lkkGU6pDR$x
z&er)K(xxnIENlR7NVlqg2|?uk8U)9`lmUQm-0e*OKovtX695f>{kL)zLq`)xU+jOk
z1uB{tTNsMjy$5JRAU41&US0q@2OAqe_qVt>L@`9(3BdKQ2GWjpF82Qz%pWDc(dQ<R
z1E>a3?PzH0WdE!T?EW__3vhOHG5NbB4v~^DakT)Os7i}HgMZCc)x^op#Sv`c1bDWa
zD$2j727;8I?fYyg1ru8{XLA70zlJ4cVeM?<2mnf1Lo6#{0=6^$t?4g8b^wTrm;1S|
zzg+e{<4D8vJ&t5u#ev$i;Ig3Lq+lvCbt*M>90hVkP!JS!0+vKp1OOU)sZ!KPA^{cY
z98*(I9^e;ZHg-xx0|=;Quf`-hJUD+T{>}|~We^u1SH+pCS`P<Ao9O8Q!`gi1^whfg
z(6;#Mt!_m*U&U>vnm9d$1XTo5Y)3%}cCqjE{fscS(H9B{B4LYPpP}5Dg_2`GNr`=;
zPkr2*A`~=LrsxT^slFPg+e!2~)=Q81sgBGJRQ548s#+)Y3W?p@t*Y2H{=rtqR5<5D
zzQ_<?Jd$>2T*ywa2&&Y*@2Qo=M&=!liFN%&6kn{A!JnBpz*+f#R|h+p?Pcttzg?kW
zbHz^K#qm)l{F4Dq3rfjb8SB1&AHX@rR42Y%q%nz|`46R`knbVihv=F5QD`+~X(G8s
zgBo_2^28jxpN8Wd`Em<V^b+vo<Q-ldLd{dM%cZ!lD{M^;eWKP^t-_ggl+@A+W{y`z
zGTgl3O;DlVB8D=g4Zbl74tgt{_X9Cb#-+ya{a1eA6Q&aSPgZk*l}HI=F4N`8egYxd
z_8i#d69iB^iYJYx09}gBI(h&)HgHUOrLa4#>{n%~xMe6;=A!tI2caG#ax88e#D3NA
z@3FszthG66)a!sZ-8E*x9qx--z$&8xrYr>{ni`F7jITDq-5)^KNrb8?%-rvo-Xb5}
zzkwAVSK#fmF6u7JzX(zHydV?P8lI{5z+cK+tlgKIPwlP9MPt=(8#niH9meS$wo0M{
zQDPq2re#Wc>BUXuf-RL`xIK0*_fnQb-w6ezB-tn5vnp~)a)njUk)#Vee(BZsyjq@>
zYES7MJ;FL%vUNBbZ2w>f>)&*oidbjO8#{q@lhEf_(4L`B$7dlOC;r-TPP}X6Yu5D9
z+jf5F`?iK(eLr7lXLAeAa#$eta|q6Bk_{%P)`XeFZK1m|d|9Y=VS22yeef^c*ufAE
zOMkPSFVV^q*qCJsJ`k<xHY%dW9sH(n%bY2lT{OB--6kIiM%Bb}n0%Y-|3O@pWn+d}
zm#XKeda1`oLn&|$n4G(xHaX#9<Cj}TJAUJM{Y75bvI(uYXh4L-c4tO$@g)~d6&0n?
zGF};rU9)Y(-L*rRZuv0gLP(<3cAovX5Kg>rVM?_2&AUwBX;#!1bk4f8OB7`W5>`iO
zlQP_nk+};G3o_sqKE3oj77!lc;follSfosTm*itxY45mxg%zcX13k0POf#8ss^%YX
z44|`)Wz+(-K4fhuyy9!*YlM9Vj1zY%P)O?cv=aQ8HL@aA&NQ28u`DjeMI8+25fh*e
zO^5~i@yQTdqq)3r3H>a<krtiwy^EgvLri=x<0c74DTXEZXVnOdy1!?_TQT{9{snM(
z?~>$<SFg^jjvJw73F~As?_eZ{dg>j#OMct9=6<QO`u^LI*7DY4%R|A#ylG28RT-4V
z2-hNBbE5}_;dd5wwLV)RW;4R<lt6yjOF=0*6|QQxta1|7v|cH0J3l&^t)<IvPJ9?H
zC6oTScMUX595sFnzalspUsqCxAK;BlF~80KB|nQ3nx};x$|0ggV1j<m&$?VHi$3qJ
zoq6068ls-=YAA`rw3@5In>QE2J#2ajNy%Sf%RThgeOcUn^}SYOXOhp-t?GC|<5x~x
zMWT7l{-kvshrDMJ%ebDw;ykTMW}Vccq`qOhDSslVmd1ru2aozIK|HUe;_nChV;>Qx
zl{`B3#GP{SPjWBcIQ>)r(=YWRmULgnz83jD4pRa}CgF{n)Aqdt{+1q`#-7Z|#Xb3A
zKu@di4e<#fe$+cESeG2Re#UR)1KGF{z57`g8<jj>S#1<q0?LyXd`y;&bLZS&aK#G@
zRclj32VWz8QT!AL#Ei$`VBU%=j521=r|8MXbW3@WoDR$nvgI;0QPuu@(@ul_Qp|-X
z4A#W_=YcNf2TDsy_7Vmf#v&rs;<ClJUooxkW$WUMf4K~PZA!8VV^rLIZ>GH)itKM_
zEmS3A+Q)Q=Qsu01T>3VKF)ea%WtTlY24uQkjzrN*JThlq=lf>r7kxP1ge}hcU?{5D
zowa?0En@e}P}lkM^IUOnbYR56PUr(!+3|1^(Yx9T<CnWwLkpoPi7|JQSipVa^FX-{
z$?a`ctFKZq9#)wl2d4*AG>DC(W`XLqi!1M!VnAACT#*lxUUoP37xYYv=TeJ+4~bhO
z_;C{-kITGwQll!SXVASKO6pg0PsY0^%9Fwu>)SPHhMy?zE&B@&D;J9l5hf}zEl%Tj
zI0O^Kyxy?5d|qo)rx)HTkX|4^pW;)$+w_X--UW2i#CXOE!xZ#>yyIqTwbtu)rh+-n
zy?i{I-0VI(>D7<feUSBC&_6giB=2peCyYk>8o?c<kUv>q(PrUbxsH~Q24sMFZ1s|H
z>Il(yMwOFDK+&Gl+59Zbvpv-vzv8R2gjsCvaZ&uHB+<3}lfYISZKUtTn;5b?K9}6q
z5~=(>k+bnL#k(t;8uzq$kMQjFZhY&@*eIJe!1v4->_U^j;D_CA1GKflsYDc1460%W
z@Z)0ZUGQ>}hwuxbBe+aGvJPU*#TVB|ubIljMj>0xh=DCgNL6XbUM}{yo?(8;!vHT3
zj-MGO*d_ju)VeQlqenpJT|UVD)i!;+(4ffPvq`wL!oY8I5+VJey4qIa{@i4$!u?!p
z$3HJf5_ug?gjX^nAD9OwI?LSqs?uK~R10c2KW}mYE;epA3RR2>i)(3*4*9l@=8CII
zE$?Q}8YYp^XVFK0IAJHv)Mz0t$u-tGq~QtnP^QTay(LuYFN~2@u>Ta77bUBpK#;SK
z96ls1XF+(8bUUy>UOks<@Z~EXi|8cwCeFD?Mt31k3n@b3yjfoE8HXi#wl*d1svc*1
z>rP{oZg~afNP>*!SZ+vxsun@o!R&q0>imnSyoi-=^Xf-sKd0~benKJVxXDgVTq?aL
zTtU+>-m49&?YR{3P?fVRc~_duC;uWQYAlZ0sv2F1tpnbcjRL`l0{xy@PjOi0B>OSq
zGI&2?VzwZ3vZA<N8YxZG+s15)I8z4u(<l?&DxsJ08uG~gIJPqDXQD<=FU|RG;#=}n
z_Y2|g<eqt3TRk*o<nzP}clW)%^z);)C-U-xgQzbQ9bG(ftq1+Lwm?pfC{h^YxX#7a
zI@L$hLEKNT1G!V8=S&PU@Q-4dGf$(+rx`VWI9z{SnNmI$<*HhS3J|IieM%CQ^5PXr
zy%aHe!yAB#Bem?%w5U*1WV>3mdQygsKmJ%A7ICk0p*B03)rwx0=F7?&hG9;ZW;AI}
z1YTnJsBv+qlGeS!q0X$iW57N_9pS{?(Mbb!ZuNF2p&z~A!+sq_-qQ`;Rrj$yKiaZl
z6s$E%`Gs79Y$=tN+@?jeo~rUnH@ikt42E-LB3YuTywkO+1w7ErI+mMXDA|kSlTP9$
zKx&=HT+UNwGjm%>PI)H&D#0m1VONlV0?jf4GXp~$D}9Lk?at}`$lJ;f!gR?@+aq#w
zjCOC)JM0p$?Zs}~u0<MA^efBm<!@-cMxSWi7&82uq&|*QC(^!Vy18tg;2zN00KD^>
zjeB4fo>iqCwjiAFlJ%%4^h_^TQDP?CE{MB~m0szi%-VT{Sd79)T=Z48M<^8wvRdn5
zp9ghhR72b(TboG}S83s`F24wAb#Y;G>&~LaP<K2+LAPkNY#!2v@b_hk?kx(T5BO*M
z_k77EU)Hzkt*lH=R*7te=%qYLW68n^j2-B+hzu~Hz);Y-$WAB`Zx5!z^j+DC2V2-$
zw0d*8!h&8ZEyfYu<|cojKXrsHJ$2RSQ_8<pTKp(Rm+4F?E(7fzIYhw}{!)=YKDw6k
zvVdy;VdO5#p*BcJGCRa%s?r;z7+~#e)n7L|1g$CaW-H8TSE*iMt#e0SWi_K!JIG?Z
zDvY@vure(1Ls8srBI-J?R`pdC7bfm6LPM9<9~g);bQOu}cdiA}clk)~!S|%FMdU5v
zr5U!_q3x^mQ+1g2(819ShE%99o7;VFDdVi&#KkQgx_WxT{WqwkP^gO29=a3rSWcT=
z>ieob#;<pVK3chjU45HIE-u<?<@`CU7V3J;U+J(Iz1!Pzvo$mcpZ$8*2~$C!Z71I@
zpcA}Y!#Lpk)nPVcpL4g^d5Ik9zG^46l{*{vQ@&weake#T;rE{JqMpJCA=HkgL-=1_
zNX<1TeXNvFP|Qnf&qQ`?8O{NYnx5w_>WFE#%wErEWBC#_?k<}{7I@jzAGd5L>{KKg
zAR7FB<}fh%!$OGP);+QdDZ;RdIr`4*<NUc=73ZeuO>*o+3Qd*#M$)xg{IUaHDKJbb
zZ8H9{DgCjA04H^fWB+Ie>wS2C)^$y?ysv}n@#Kpe^%A!+arTYxS%RKBV_&_CY>D`a
zjXF9wmut!&A9wkSdn4K<?zMOi8YwrxYBE0bG;*|3CGkP|+m*r|#e}X&E*gjWq|UA?
z5A4XVePrY!QS)x7?2@U3VDjtR%h<QRP`T9Vm4<q}>pe7Xv6!Kj3EsQ1<rk!GebGkK
z;O$}^fge|$S6GU>SYOehFpZTi-QqN}T)%UsOpiY+jLWh?L@K!{WgXHMs_${u_Yq&8
zk9oLEai6{oOJ7)nzU^_)Y-6ww9=+8CuHOH%Slc_vYdKm%V*~m*vPQYYZe-o=tgpyr
zYHr4LZbi=LcdGZcxOR!}zdF->Gg(j?`?bI=UT^biqT2r+oi?B@URIP293gB}-cPDJ
zb|kT!<%bgY?#q0m({P$D|F;nuE7`+r;D@gfvqzX9yA>QzS;%MICgX=&8u?i{I>uyR
z#ga}_i=$4C={WI8`_uQlG?CEw?cEAJL4BV%rHrq}{merJFV_9$o(6c3<E1wEp)2-8
zbc`u13c-64e94b-<?%{#_%Nifss2L#>hXNFbqi0)v25Occ<a{z+MBO=vhFsom4$Jx
z8bp}(@tR(!UBBZC-zU9Aj~;y5knf1g50=CxmnuX9^N1}xMYIYC&wSRl+w3L7<$WmW
z#bwBR8pC&y)}^v#{wcHU?-u*y``9b)B*W5K6R~28F)!w3SO(W@W}vK5N-@}{Hs=&M
zLoww1txb1}k2iudIi7E>8;Mk^x+*#LLWdG$PBtH7wWSIi{-(`sNHy>C3#!Z{yT)T8
zV%YfS=dj^|`O}x=y>5mh!Ps$#-fom7h4}pnjs$If);t5pCajKF2Zk7p0nKbW?a>MG
zj2z?^XA>62xm@}lP@YO>9;)FMMA5VPiCK~d=#zz8B<^G>TtU|PyRj8~=cJk_?h|5g
zq1GjE`@+Fi)0<a`#<W!TB-3HBd|-0b7*9bGhRs|iVSL%yvxH$f_X0Vot8(g1*18_o
zad7QxJ>{+~=6e#;j!<VpdDG^3Ow|=yXnM-+2G_!eC>^m~iWAo~y9(A}LrG_hn*dw}
zjLii)>uCGYhY8re*T}pd+@q~2mA&^l=*8uZ#^0+}pn(am1<P}oMaq#=5qOPJW_IGe
z3qqWOQB<RuB(D=a&rVJUS$<$|HD(Agc}pLx>%}R_&Am!^MW(O_OZLWiL?o|3zT<OJ
zfOtfic>V?K2@bW((Yf-lUkO}k|0heZUQXRtmp4KlUji(TD?)Pe)8ONUZ%R6qn_LNn
z7==}qIrdhx%g`B{@bA8Ffv0T^LBBAXKpduaTEl_Y#9D7iQ@D65Cv;Mm%nEO0vdgIh
z{2-t6C?ey311>$Z(S%2by~q|6KHoXI8pcSIZa|qr?GZY&(U*`jDGihEzyt}K6CE)&
zOg~-GA+Xd+G)a7L=RXgx{ooaLVv~{#&aBMeVjc3HFPxzzkV1FDnC~U(M{|czX{}pq
zhYCe!7_u+)l9g-Z9JK~$>^AFvX=$^m8?g4a9L(rl8D&M^fT__eYRBIYjVBT2QA-~U
zgjt+(Qp0G<!B(pV-FU*)dJXlZV~+-5ACA00O3aU~SP5!iPcM4N_6%w!=%dQ)H<pk_
zGw4ID<4RHf@Euf^h!?Eoi#fIx+z!8f$K0R^z1p~@4Gn_3SI2B~=+tLg^T2G=bH{kn
z>iCLsT?#{#z6Ml0E%XE4c1%N`Hu{ZLuMKRo-^;=4d=F3V?I={{ye_1@=7JT%I<4}H
z&^$E*dcA?hhx6L=f6{^4jp^`3x`rzDt%MqRg|@ScC(>=eb63pc^R6R%V=V?|1^+b5
zPZ;S_g&(I2@_nRV6Wn_csuC(s<Io1(gFPitG%646+7-+S-f5EGD)M`^4m)@fTziQQ
zLsaxcgc}OzuZS_HTF{6XIOl=VYipFQYamgd9JVPGM6n+r(K+B+6v`*8(<VPl=ytry
z3IaW+&N9!y`)Q-O=HBir1j86aJ<&XUi-2VqJ-kZ!4ke5?$a80L5hr~C$vUS->_HB4
z4KQ`6b9K}G^~iGvK`iOu>m;K&9gFi}b`^^*R3ZVOfm(1U2>BD60hLc}6%6-hx3d=(
zl`HUvX$D7WR9;{FUTp_^4P$B4ge3~&Z*2#wkQt4_uWLe=sk>~J!GAtLVEQ<mcqKBA
zl9}vo7>qtx1$Jjo$SaTwtQ-o^N7iWS*^q~4t}>|dlZ3%TLHhdW*a`C}4~>e~!TF6%
zc(ivHaoqy?0&d8qlZ0+)W{m;5Ce6SUTVNiJGtHpM&jRLAu>)K7w84*I21>{TO@P+m
z9OgX^F%1kEmI|{$oL?xs!Vg$UMYc}lU>LHOY<eQ1ZQoJT0Q!N5`QYn7O*W+tjV1RV
zP<<Dj1eWLQN9)kQNHV-{(x?Q5-48HQk3(Bj@b^POSTG@*efH4ZA!%M3IA~FzYZdGe
z0yd2fZ(O!dFvqxTDhC6I+?{?@_M`Sl$a}!G<7R<-Tj0|4=<vz8NP8Q?3BIL^xIXMH
zQXlSEb8_;PZGfJj;>sYZpp)~;WDp6d2en8YwC1u)7EMkwdMY8`C>KCH)K>TH%5YFQ
zqjP`2NM=Bb6T7qA)v1!G%$10iWo+>>Y>DU|!IZl+2+l<YE0#GYkT@<DvO_xD2Z}1>
zm$AV?Mq!|in3tERVO9Zi(3pWy1kgtjxukNXnSSQ?^n3_jFfA~7aPRE{r2T?hv|u}Q
zppK2~k=ZiFmoV3Q=10uO;LT}2!I1C_Q;3`e=%Aq?5^DKjRN}+swf7g6izotM%vo6U
zelZ{2`>s<wEyCRo(ml3AC&Z-j{BK_SIm!B0Ui%dn8^_<7X5Rlz$Fe`Ckbmc-f&W)N
z_Mhoj-MB&9KsHRttH%$TMG;}4u(C8kZwiU=yg${FL;Z@S#03*pubuF3hO3sKrgUGg
zlzj}{S`q-+>QK02)L1wK8#;5Zap(t%?wxV)C2ku?*Q~T{EGlHGBd0FfXgXLfv6Ynu
zYz3kxzp}3MtaggQK!J*@H(-xEhH0*FV*2vy-~mHv@14wB-N0}D8+v?C3yMgxTqnfx
zyPHi%{lAK@mjuMf+BpgPhw$)M3DGi}b4n*_Lo5j_gGV0u2QiHH5igeE-)<)rSjb7f
z<%>`VzNPox@}YPL;Kfzaq{`qVC#O=Q5JJulix4+voEk06=9J(0$SJ=bcf%%8B<4My
z{JKK2f>-TQa_TDYBo%_UO0|TTB@uFs=FmtxMJIU;-)Oa@wQB7Ycj3QpW@wXJx$&0X
zA%gir_ekIXZ2368{;+yhW2Wxq1D!!#gz>*V`|XLpoW{xd>TjR1KPUeG&Y}Ow+&^;*
z5++VyM+<vrJICil{BOEJ$<PME9VjYjz15Utk}$C}eCMJDN$LNqUdqtM!rC1`|ECJ@
zT*vUI(%R4rlDp^lm!#Mqc7cVRje`xq!o|%2U<dJXLRbb)j=xw2S!Y9Q3$UoInY9Uk
z?RPs-C-5^(!OOw(yZAi5=Q0ZiWGc@i6gRY&F|jZ+hcFqCZhk{*&L%eR06c%%KNn>F
zE<Dc=5{@PufM*8bpNzsYh4R1F_|u(>k@Ii*<PC(gc(&AURLs!H<Tn}f|FevRqm#3^
zxuN6V22e2ktIW>vhk*G{a|3=m<j)f$X$v7OENsmHKy?dSQClaAzk%PH)h&#j&7B}D
z4JZ5aEdKA4lbh|YdTvf`!2j<Dp^hN6|9211=qu1OllAB1e)ab~i09vWxgp^N;(U&!
z|NG?TeCCTFdf5MN{YQ=i^zS~{09=sCzk<ZX^LU=Qo@e$6f<S)1$tMVjWcSwA;+e?-
zJilxH>A3$5<7bxZPjt##7(d(TnFv$;7meleOnUu;OJe^gPp0B%XY2xout)S@LkmYc
z06Q!DD^|!9>CK&;?fHNZLJoqOIU3rVTY#Nd?HtV*{)D<Xg#B~2u(OqTCiCbe_&C@&
zIM{eNc-YuExH!3(*f{9e*ckq)^xsV2-{hRQAtd(g%znH0_Z0r3=Kjrky>~P*MPUQ5
zbD^;P>i|I9!ubkd3iyLTT*Cu-Nk1O|+rKe(UN*=a{|kG5@ct8nl%AdR-*Vg#i~lFa
z!^s74-hW~okf{D|48;8$p#Lcc;^u<5_dhWnwpaf>77z~`2ojk8CCBrB$nk>y(Vw%U
zA>`?H{LKrhS$LQ{+v@oxp=xIbar(2(|2$x_wx$r@{*H@3OrW8o^Ka{dAg1C(p`npf
HmO}Y|mkAnx

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_10-low_error.pdf
deleted file mode 100644
index 3a16edf0b390d7664d6e3f452cbadbd0e8df0ae2..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 76832
zcmV)LK)JsqP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-klby^<WZuU~PN^5V9NpH;OL
zU<_cu3ytp1@WPNG0Yaa}*bCeL-iMhHk*vONv8CtEVCH=oeOM%uELJj^8JS-D=YRi}
zKL0P}eSiJu_x5kw{*~K)ov)w&{nvka{rmr8fBo10drPnX=ktI6%jf_8+xEZx@1Gy+
zum5vP`|E#w{o5<qBmMt>9#`sD-}9@r{j2Qh^?sH7bu^W~U;pX#A0J!%zy9m%Km2_=
zy_4rFU0?kuwVa>o<*Vd&oay!V_xA7q%is3DjW+-OU$%euxB5T*{l9Jh^WRs)c<g2A
zU#Iu7eD&)R;N5(zmJ0`mY5;zzwqHXOQOnEgO7-fWaYQAQf2nk4v}FH9@egHR&-Qg3
ze=Ym+=d!Q;x)03DzYMH3`*G9)@JqFtztXK5fM2TR^G9m{eyNrkTXXTF{HO9y=U0AM
z`}v=c|DJvf4#0YF<vhPqJ);_dU#cCS|K6$r_@!D;KUxFuOSO8iHJbsJ|8NG%XY=Y0
zZ$SF<87QCsrq6$4Z~%T8T;A=!Q4PQ^)%N2@YXH{O@>TAw5%{Ir`T0n+*#BAnADV&B
zxb}3U^YgE>eC>Zd1F!whXCU|f)!MX?6ZmCtpRdt=s|MhgYUTRT8h~G_<^H2J0KZgA
z`71sFUiwq%e>Sl8*E`VbpIHC59r^d&IDNiD)Az!Qzf?J<g*ytr{JfoCwa%Ra@JqE?
zzpfhlJ<ES6?ey8Ku7|b$Pwe-pq#uI=@XO%R!NH*#fM2TZ^+#&}*43{4>%6Az9_4kV
z<M=99Z1yPrq4YodRDD?L|AeyB%Y9rZ|E4c;T+|n*fjxgQzs@%A@?QRJXZk90C6s@e
zD>h_OzousX$CrHmIv-a2Kcn5p8H7Ndl!yP$UY5_t^|R*FNB;e@gdfy^Kj~&YP0G<t
z0coY2_H3W+s3u@p?PzwgiE09t)lUCJMKuA-YH9ZqQPd0M4<_NdzRK^D@Fy?m*v|Ib
z00UW%@Ut+cgYBmtfpxXd$Kh5B<#naccPQU#5m;9{=4IlgKM;QE=jTQJRr-JOZ5ki(
zyATPi2liPH<6|<_6SAzBQ?Wls#X!~-KRVZSYcY^@#k%|E9TkQA!Cd6eet!Hu7k{Fa
z<yP(cGWAr*dWhXmfKx>w>xyTx&)`&1$hzXy>^wJB6tb*X_Up$O1NozG!$$`_OS|f7
zHva5{^7#hexA{QUL&O(<swiY#vF$%Un?lwVKSRHN$O2hcJkB3`Zy<j%8%O=h<=5Hx
zqZ7-OetbOxSq`y|6>=M5AnS_h`tbn`WL>e8xssLE6>7il!2<qZ4u)av`h5=m<Xchu
ze*1E=ydK<G6SrCf*455=kMPp6LWA)vDh0Bx_&HnOKV^aZf&5$gwEDaJ|3p)2`TFtg
z3}ijTu_o?A6tb?^`j2fskafjl|FO*nvaWd6AD^;7{$w^jr^)jBZ2S{v938^$N1pH3
z&yoE1^xOLUx6%90DoWnjeCDs(?UeSj-~Zp}_Vg|M=tJk{1OC}?KD&4vqW|6htKp@+
zoo9ZH6V=uC(R}Tn|2h78g!mTZ<DvyZ2+g@4#7b^O^HPTuyBuby*bL$i+;)-2*~gBn
z0~rd(K%yFvghr0>>+zr##ZRf?JZ{LI9NE(iDN{qk4tLlId%GiU7#V<_zK=3J#*sWd
zW(<8Gqc__PnVvIF^&ez<4v<}vXeLTmxbPrCZs0Y<%JE<?7j>qZIQdcm8KR=)robLE
z5Xp}~mw<~&bpL8U$|;0ZOrZNT0z>)*d(=QaTl)Y`4I6+p<YP=`=e^Vt%UQsX<_Aa;
zf+OeD&gXBNLD5n&gYr3z$=2!ziN!}m>&8mCZBvQO`tc(7L(K-l#n64J_Ct%;kj)@A
z>)PKy*sNc28nUM!2-m#n03Y4{h|;i*N6WOAN6SJq0$Z3L#MZ<eik4}KkCts2_O6*G
z(tL1$48W3NF`Bl8+1nTYZcFY{E*d~_K{c)2?yK&DM8m$ssuuHvXaLy+RW<V+YpSYo
zmZNcBQkAQ&WBF8HSu<3o`S<lxqHQZ_2CT$sZ`l1l5a+#NxfC|rur!K<FN7r<ZT1b&
zAzKNVl2@6cZ&(Mh9W_ikx1-G<8(fy~1KBkIpY<f+H=E@YP5WN+LAtu{^PIlgk1|Ey
zFv%%o;4_*+^v$=8U6OB@!CjIMq-y{^r@M7~17u^`ry1}m+_nC_A&S4^72l)u8DP8g
z-uX%#2!v35!ae{ez?bGgI04n>=mQkaV#U4HCHedE9SG&m%dXh>s?SKXZEyPlbq%3e
zx#=<XDz@15{JWXmhGoma-;9BTAjTB5V;Z;#yv0`M3XUNfx$n#En1*fwZ?V-?D{<KV
zb`6BXE|73{;RCYnbxnVPjJt+iT*jel@M_Svo()j-M`P_3h&VRCV$uusq(FMw=?eC(
z7Mopx^qNNP3dBH)o|FB-G4S!PZ9p+{7iiUlyTxH3F>se>)ie|<eMarF$`D^DM;X!!
z<tRgXRm1j6%I34RIl`OOQ_pef6^bJ3Hn!_Az8cFHf6+E8MqhmCX$Q=ZUD0<pLv{rv
zliRcbW-P=U-EgtR7MLNV*aEYaI2noWb!>kLV$14Bg4mK~Be{^0Cc{sd+km>B<3dVW
zhY3;&EiOSyNfY9Kvj;_oTvAEPBSBRA)FBtuKJ^HzDs;O9@$6HNd{xD^m>{s&7QGRB
z5ZA~K5rqc0yNK$gHR3%nL=SQq)k{6{z73@5K_;VmsYgQ-wXz;#@8JjebY}x(5~|nK
zACpHtr~ZuPQ_rb8wtA}Xmm45!{G7UD;;6A@?q2eTbRX|PAe(;Sgi=p-23l~g2Rk#=
zU~BteZ=e`wxyKB|-sAx_J*Zi^=rJyeW9pBsjCxG{DQJAh#?UW}yifhHl~McD9~VWB
z{#c1!Iq~AuuHKwj1JWp=ln;cxIWcf)l&+?a2Q@C{0a@Eky*X{*IvDm718-A*eBezQ
zZa*>dHuc8`uDuu5aYOuN?>N}js*g@Tt%&bH$Dy=p-^D4wke$C7`$L7=>4$>NfTE}P
z7^!#SlrVs#hxi~XO1{R6G;bUl26XTlK0a;3I7JMEzwps<AKpHY7a<~?W2*E}oHPc)
zDf1%;EJqGt4zp$qhl!dcB|8|@tQo_>plWOG(E4kZcGSDSwc4FKH2A9BxkEdzEcpPF
z=8M{QrMB9kSyw5m9olt;vWnx&C{r#_fosyP(;Eh$eHmw(ajitjK&7qw)EytdF6%>w
za$0w-A1J34r|=GC^i$^gfwEb5YHm0O4TLiX)w1p^!S#u6z3GQV8+5PG;>)E;gE}bp
zsNx5u0dUr!4wh@`+ZfL_AS~``f9H%ruPYZz)`Yg|?h0JtR=o|xcE=*!7N@I$uw$mL
zl~eulB|Z@L%U1bj5SLRy=g+BgHW`J@*hG}rx_#9f0?oTattzp1yAoAm=Z3~qqz>bl
zHjvT1%^|M@p+Q3`hx!JEs2nJHPh->0zQ+%U6PVCl*#bJWnbOr2*JetWp!~(y286yq
zQ7N&LyP`4>u72n#B{p(sC8bGc>j?snz1+U<rQzTHh}dm+EWpZ_cQ+%=04Qu<@B^W=
z@zpMLbSmwF7_<R5ey0m}U_Z!>GKSdjO)ix~Y!}2JO8|~`1K|)GzQKjta=ZMMp||D$
zyvNv;anc)Qd`lZYuSGj^!{@aWF5VAv_;ay7aP<2iD0yeIz8G+#Ge}SM&T60bv!DTb
zs`u9Y7PkTHcrd#QV{Va|6UW7Yu($qAEZVr+fv-kk(Yq@n1I~_y=&9aYY1z%~ip5mx
z4TyIadwDzT-|Q*AZ$&#hj*<gmPdh%>C8@9YoE26XZEBat!Ezv2whhK9b42lObt`c_
z;uBP~q2qv<vkVN)Z68_tb8G(X84!o>Kj2KkB#~iK#bI%jIedH)^5t70pxqnh`0cxp
zwO_ZYuJJwak3gn9Vk<a64v5{yc|V_g4RFBE+Qb{q?pd37gH7Hb0@gbz;C7<4^3EzI
z{H#sgkCX;*O%(PHCGVN+xec3omXV`jPtON?pV>3*@;GJ=gx$9te3Vi0o=IVEeum9Q
zNFPVmEIUZc>K*r?q~1~f34#mD2o9bD;t-OYmbrkEbx$9MhI3@b$6+%l`)?Y4;oZ~6
zqIt7iwKxf8ekl9^x*5U&?dlm9lpjDp2uk*v=cX4Qn|_Y(M#E_>)B4hIR?AJ(v3tqe
zs23&>cISH8n>fmt3>-rZX{^(%oLR-^PuEX4g&KmTRk4?=icg*lH}%Bi>63;d=s<iZ
z_2kmhk)q-Vly#)2*t#>$6!1_S<*JrkL{;i@Js~6+e5|XLQ&X`^XB|4K@6uVHyvkiV
z>zh~Y?kUS0gafG|J1b@X2}X!xM=r8X;qYk?%e()C^Me}-xxf}2KL-M(x8e|y^-;v>
zGiQAjD~=3V2N;|_bI#hoaQYk&M};#%*0&Pp&w*fAI27c}HOS+qL1>;Ed;Vgjgr{)g
zp#Nu?rQo)12sR2FKnKK;R&|HVlUung_Z24J%*Wcw$XS-G3hh1Xyo3X&As9C|Zhdtt
zv>k)cHX|Zr?yB6n@gc4-pk|rBD$J!h#fmNJPf_da4+oyr9}b+mb=(}_;Q4`AvWMuK
zjbrCPIB*ysvutR7?A#2(j6>(nGOAT>&N{r|=s6Hdg4V$-1)wH%h|4{xLtF((9m4Jc
z<vGV?EDoOrp+mbm#1{ajxV)oef=Rlptvf7DNk_wqJvmAFsIaIdUUyXN$Vtjbb+vml
z$UB3>=0G3|95)R?+1~P`10~Ly11Zp33wGipE1(}O2ax%ggvVf&6z?0P;-^a=Bi@aI
zJvQl9rI?v1=^%=uqai*e#g*f9Qmw<maUhUFfi9e+<`nF*>EseAa3)Bn_QP_hH<Sa^
z-z3$iz~GZ~q%E-cq*EJ3!CsqAiUvDvl7fU2qao-b_S$sH>|eSI1Alh;OJnkr;Q%Nr
zT%;zcP(1Yw$d^p<8_J}MqXIiil1^1%R7tu@D%d~M5wgM-nsk~jFqkB%S_NBZIwUJ-
z!zr{c93lq<S>X~bNgXRyL#M1Nhn}D`;mDYi6tn`PM(Pq6_QxcnE6#(4G&~4fWRl8;
z^WQ)qLu`;qT3mrTn`o-tO2O4n(y1ROzJc&Xgh?Vn)hpQkk_@^f`%ybd-NWI{5cCh*
z-wol=Aye*tNh)E1IU&iMfD@V_=yB4>DOBI@$Ai3R;c%2MG|?n2(t`jDK<{z4Kx8w>
z1uj!FPGkdtz`4)KVo_jTNKFFIms*FwGxs@}s55uE8DU!$dPv5;CM^}mFhhJ8ICUA~
zea@%a3dB{)L}eCdtgHy=f+Lk7J_-3`<Cuetqkjs0H*+&<DEX?EzKg@q9dQ}Ub%W<0
zgD@zZ+LP`#^KmP26Qk0c-3Xnk%&0iU00P36vAtwyhe>)h&M5=o_JW{JK!!B6-cUy4
z*ne_U+nPypkx06H&D_Uig33)z2f~&)k(J*qnyE6ku?gr99cQ+p=_s>l8n1B%FbINx
z-Zvr8`;ra=(C|M9N`5p@u~`rY=N$+08<PDeTnNzZQe0|4CpQQ};nt<&MdsEuBfjeF
z#IZTT*0EqR8|UiCYMe+?+j_B+8s`$iK|9Humy;R~gpK<OvIn7guBoKvy??tJXW3sg
zIVI+uFZB$uX)d!}O$UOOxyp8yOycQMLs)cB>Fx;I@kN&|HIv=>F<op1t1ex)(y3Ok
z+dyTyBTz(jcuS|ADj;F*u_)7_CkKKrPC*fUMJam}HdbXiZY5lIB^?C)leztX{E2b~
z{d|(<Qj3Q`fGui3`S7iIAihAc8QuUFkZiMw?<kS&19=e=EPQ4FssRCJ{X~HK>LlIG
zrCq%ZBuDIe*<DkPQbEtThwfA;^@P2D-J0E-ei6v6?|XHV%?(i<m&gt)<AmULNn+f~
z7sb4xT<(*zXH^LVq57E7Jx3*6*X(dViDj{;c#e?cw%GRc^|S0pa$lS~j&mqcr_svZ
zslv?2^nPpxB)(RVEA<t=X!*MI;6RS~?cD}41EXB<n%NdG05&9m?fABlFP*w(=$Ln-
z0sJhp9pAtP!iI1l91xrGoiJaAhBP7Ax*N*;YOvh4X-6IaTMi`M_WFVBx4k}Ju))SB
zVnFwg#z5G1hdBFJ`%z}&zD@_i#*apTUrPwH#m7>JK9;^t8IKpA-GQ_pWww1mc8%L^
z0N5m|6?wX1i7Lqs!A&{|#8jmhLX{j)fmX#;h@(~2qMMWwAfc4_hi4!sv>U9$BBhjz
zuBdUYvZA&f*#?wnjcowbNx7uTt(4VpLmA)ass)tQa3Io2A(<RHDa4R*(IZv%1KmnV
zEn{gUDx_QoNeU^xHv^I$4k0A9%$1O&7INZ~R8m|u<V!~_lz6J*RQr}RmwC+LJi~w$
zr;!2iQ023DUO$dG1Gyh_2I3dhIvovYK0l2zPdS*jGfq^PlQT|K_<jut#~e=6Np*#%
zzJc&ag?TySNabp%A?Pz^=8Q8Hrs2Gobim@IoCm&xJnRkxrUR5{HNfk49y-fo4$ebn
z0~`ScM7sgz;OsIRU=F&h29$W0)nFi-L+uqtf>GvCo^#M;Ht@$b84WlCvK4j7yUAce
zc{f=NDDS3`AAGWPD=a7jO6V~q+%#}XxN6{(u)m&L*mMRonSHEG!xWbFS!I`^M7e(*
z2rU`(NwQ0!gC*=z=pZ++LlWc$cF?_TKr~EIh_n?Ql3|fyiZU#(u)mFnGJKy83NXte
zM``7++0Zx295!VIjS|Z$%OXm_@mO_AP~5*x35usG)Au(=8tj-9R0@MA`j)~Vdhy8#
zhD`ILb%+L03W^)pDM9VBh*D6yETVRnaEP{F{G#9~6xB}aFlDu?H;~mqw-ec+2Xwe8
z8`3#0%mHoL1DTB7qv%thTl@jh8V^Yv+~#Ol&j+_TH@%PYiN}~=HiLLM0684o<Y?v}
z2=4|CK8IHWaM&6Uy8}@$U{Kc%nGt|?Es+_fr)!IR&}&k68;mc+1qcwod)z4-*vNH_
zk`Xnw#a&Bg{Fm-yGUK;&X_Fa<rHh@6kf|+he;CiG3!=>MCS4+B#wqEdDKqBCPy8Do
z?~qr4xhW^ff|rp=qJUPXYq5Ob>lJrrnL#%>Nf>ZQ)Fm8)D|t<q85rYM4ewo5e>m={
z{%}=P^@jt8#^+ayd=UG?MNrY7jFR^y>*b&qN!Gw&D~g-Y%ovcIHE=i#>PmGWysPEF
z8NY#>Sq6K?-EBU28<{omqW)mQc^RpLeP&RF?vgV@D0JbR86TlbX$Fnr;+hZAUG~Ll
zyvxpP-Y+C|emZy|Ss3k-8Nh(M_I%J+L<gNCeNFfEj4O>B{ejqBfNuRWV+Z6H@IfZW
z0fwE1Zvnzi;eN0I>F`M4#L+cGnmV2P<>-*<-0!Xs9^snsn69Sihk^Bp*i?C4Fg7(D
zGqy~(e0gse;$9{w(NhIOqQAXdL_B=e{Y+Gejw%>Y_eWqa>L=vnjw+*kxEBgM+8D_i
zt}cvZl{X9nS>Z851g<J4mI2-0&Fv=B(OqsijBgFs9mcoHy(f35qVfRBbYz!@kj1;c
z=t0C-SNRwjlI4c90il->mK*)l<;^r=P}w=o4L4{-HZTS@e5V)#8~#<<{m`@2FM6HR
zOKUSIhaVRMV#Cji0kPo=hJe_Y{Kc}nl)JwehtSkJ4x!Pz4JEm)q3k_7^}_T<*EaT^
zySFqT`i{ecF4K2hPIenZX2TON(^Z_#dYRth^5^py+Hm=^7}^Woh<N4U8!pd53!<&=
zkVxrsKfg4Bg7_kNDQ3Ea!;dk;AzY4*7HJEgMZVtUOTLmDfC67g4ggj@`CMkYX-f-0
zq^!Gb`ci<lE7#6}<k|bvB4^#<6r~+*tP}!c%;aI3<%6v+HGQy?WRU1_3K`fA9e%D^
z?$-JQ%iUU^V0l~9rxvlb@VWhzw#g&cf@-gGa@u8>Z8-Ka%r=~V4KdRY9E3AGy7d*6
zS9exVv4hJG*#d9zSlk2|WL+&@nmnB?4EH)GXJ|w0k+L+li*CHKBqB7Ij@P3+J7!y4
zE*^XE2L(^14ue45@Bueu&y%0{2buiHEl3w$?Y@gLYB$``Eo%3=CYN<X@Ko$N%`ByI
zd}kc5`^IlXTAuvpGrhUJUAkDyU?CT4eK*|2dYjz%8L=C#{*2m<Z~#LPjDRs7j41G)
z(eGNH3He>?!_csMD|&%Jy$EsOgS^KFN<Ltn$~~f2Q4|d5Wt;^NU#~~>WeV1?nBVK1
z;yDblzA|1fgX|oEAsZoUiB%Y&!k)ocq39C^1xJWVHlJ^gP+`}aB2=P#h){{{y&_sB
z(+iv~Pk^kU3#G$Dc-S-O?u^$#6!9x!dJOT%AodHYydr}bRUFYnxhYmCy5>hQ1tBre
z*n^ZZeZ&>S#HeEhI%PVIdo0uj2!T#t{D}us>gd*>{nuT6gR2cAvm!V-!nX{uwvtvp
zP6Rbg9rO@8?ByOz?4!Wm-SFj6z?mU<@WG#SJeMzGR!|*^J_7C5?rg5mxJ-BRsxwc+
z`N4f1H$Zs~!^?C)SD+pPpCgzrw>(ArS=6(A_!SXoko`#aNzK1!HFjg1IcjXi2`0A6
z-53@hg)cHvS`m(!9_v-d5QI+WS~nDZest=f3wzb>n-t+mIVHtvX7^~{rf5!stWg~%
z+Rpe+P8Pn3;+xJO?As!=lyTP)ewyj}t`Jp5Vk3@~h?z7M>^h)4$HOu-J0fN?-Q#PU
zI^@IdQkN^vM2gR4{C33fGJZSad~<bs6`Zj*NBn)0skY)ntAJvLct_CjKp4He$Af(I
z$J8N)FGq*+90hHG;Fmv#W~|ES<zwoQk6t@C9rG2H&0ujwZhH{7PrXc+)sJTi0ne2o
z&C<XTQ66FB8~@2a`H$vs^i2PLMXYCf_$#U%jbeOyOrFEz+0zK1&kO=kkUa-DMdA-B
zxHPm^SH?MOt7f!-!u~1Ei5tK~KExpc0Zu}Y3>dQKiHLx6H?b8A$oV$*sYgzPp#8bx
zo<r0KTqhHMf-NTNQJQ+>L<lm1Rj4l_YtX6;Mu!hHQ9f`X2P=dj)*Efn3~FduCpc$x
z3<?T+X{>uPOjVp&MPtEtjZ7CFcJEI)^%R#@L5buV(G#+3_%2wxYZ_wY$c&Q!We0bK
zAoVb0_lF$(iL*t>f9nJ3oBplsC-_Bdi?XiC<WpO)l3e_aSs9vCUxr?Y?8K1j&pGuR
z7n}CrN{gtNRSbFs`3m>h;AgSD*gB{km=PQ;OfuN8MFukfu)3Ujj7zUiBX{XRMYbK?
z#TR>Pdj)X~zb3(LV_%%>d<FjvzCqgyEIEX%bGo{!pdFGCgs~$nw$%#bwitW(1q@mr
z`$#r_a@T|W!5nrl3h|z?2Bi>|9u&nEJ0>`W&S~Vn7EkiU%}@;8MSM;pcM)IH$X&#+
zK-hy`AYif|kakF#Z6)oH%ng;SL%i{*1qV3MK>-3^6cm=AlgbQ_>9H+BN%hn5Mrd@u
z$G!-?RpeGPa_T`XD6(8HbILWDAfR-KYAZAHMr>R&qF>k$Md>vlBjZXT1!vxpbpiTc
zP>0Qkc0jnKiG+-bWDu2okcr5QCA6B!rWTuDCY##5B;jX~t7SgJCo4RPs@sCZ+BN}{
zJXCa%z8O+anXtaM36lQF&?7R;QTGlKx*5?gwpZ}jks~9x?rzA%-;h{u*9iP5-($PW
zBG!wxopi0KZJT8IJp=$F15O+?dCo|mn)Ye$(;WD$cimY|5T_l+Gcgz55DwuL?1!I{
zF)Z3YlSmoaW*}T?Ni>bzdXhL9dEGTZY!hC<J@&akxcB&p2egsf4Z+0Y2-MH1aUxuG
zV2u)c<u*g7M&V29oEmpTXZni66zMbpY%daS`sq}RoKrbk@g;UmtvJc(9!H2I2GJy0
z5n(g7<c@u6h{(}6L|cTSDh(t}&mHUVh#gBnRrlPhNVKV$5pzeH9&9V~h%G9RSS4;D
zI`aJNA>c#X5KfUto|c3oC7wf0*=;IvO~Kz=ytILYY6OGq5vmc7r|1QareesQk!Z-4
z>d~f#9O<#<{X~28sg?n<iZO2Rh%*(C6L#O~WC!#iiHDr>$z;oCnSSEPZP3GYaX?eG
zF{rc6QaNvf1|qqbC{IO@2h`{3Ib-kfQoQjtnP<OG@8-@`^Ez=PRu_<XkgcwB-a6d7
z?>wiM)t2cwZ50G!V;HObJf{Z(plOuv%sFohj!c_?y?W<0^_WP!izdr?V<7TlBe?cy
z1VZ3I?EA^JPw#7kbKtZ;UGug;B;HlOS-8^lvf4&>&HI9FkJr305V`HUS6rS<kY4Ap
zQm=WRFks#$Y@uFx9wDLW`!b|?%^L@i*pqCrUei|M8qGEDCAL_v!cX2cX*2G=Dn-B+
z>Q(L^(M?{j)0g&|l^G(TMA<^U>ikK+!d-WQ@~kRcu{jBdc5VG#HNIxhK(1MpA#!O1
zw&1QdDN(+>TD0wf_E-C<MO|%Dn}|#rn+<!`UEIui&B}|fpFXKgzFhj$m@SW4bpg;r
zUOw}EYRhN-xR)j!$!9%wn6i11`n9{Qx0~909n;~!XZ4tlB|fW%e2oO1)A7LOE%XxD
zy|44@c3ik7tt6m0hxn|W({aFO?V64QO_2jA`&yk3WIk#0fy^guK9KngO$RcM__=-_
z$SfX0=NBSz@EE@~L|ry_35%;xpU13N>;(_K9-E<K=osBV?#Iv(&7qga&#DIL<UIa`
z2#_BL&&i)@8ATuV#-lU?P5d{b=SAo9YF(ALl%3BldPSWzfe+|@%pXXczPoicPsjXz
z`Ge!2KU|y#ayL7S_?o2dxOmGn=+nAera{~FzlZ4zpxK`}(+#4O!5@Z|vR9U@V>B>r
zFvScc3{1s3HXE2+j<bQu<v1IdY=;?8SeX35H~W$WE+uu>WjPy|T$WAORWN1^C@f4z
z^N=V#$0aw}mt1g)U8ZfV?B>o>yM<VVxzEMcXX{=)5r&1bbpqUt4w>M3Sod5?v4M3+
zDJ)AJD-N3&O_Kwl_&cO@Onq@F#a7lKlGw_+DU$=446eIB=WcKv@n_K;7nAN->%sUm
zALD_SRTr!<{SJh}KOm~mwGIgD40ZCrq6%f}fVkoec0gRQ-yIOwHTTHH!(-V2;apRH
zd<ki{J0LA?b{j46CGGfu2`24RS4=R8*QhY~Tc{u2#MAYL0W|<7nWSq}TrLdc;7`Vq
zN%D@ty+}z=N&OC^q%cLf;0KcVh-Ss;hRGu(^}-hD0HPZ<{*<B{hd(5`;Q~;}2A^X;
zJ~8~vZumE90PM(x;q!Rovse_cxZy6UBx!ONMjzXxE7~O$lzi~9MS|tGD2fhOXC)%y
za7$AdxaJpdB|^|}X;UJ043{<~m8l~>VB0ovg;OFv3m1kZBCY&RXETTwrMr(eoK$uU
zc)l$40neAE=89j^d|lem{QbIg1jX`BdB-Hrx1~1jCJPd7W=ooHOMT#RS(>aAH_AH@
z-jpT|Q#v8;j!Fd7;O?lTaCk{r*>ZSE9H#bM+$I&qz2L^XL`VxRmx=;d{N5Z<$h^_^
zF&-@0_`=~Od+Bz0Um}>KWsWc0U9wN3?D}vNC=nR~X95eZrW3%I*SW%#z(=Ru*IgDA
zqYcEyr|VL9J`@kx;DdZjr`#ocsfL3~!K~3e5l$CHu@@UXGe+3?x30BH#8ANDqliO@
zP9Y^CBwFEK6J9My-Ww4Sa6l<3+*%3-5MC|C#Z)}F0T*H=A{lTYRus43zA`1k7H~mU
zJVt?TJT|BZNieEL5CgD`hQj5hqoEV-t?vIb2naZD(9<Hi06s)uEf|1T2sb6$NDG4o
zaG_@82=aEyO>7C@x?w93Ab=Y-&@RkAR3+T~;b;Z=1_w<1;o1*>tpY#(ZMbulaN=*!
zg>rbfKo`p4;o_=Kc<eX0u9a}m$Gu#U?>(;NO8DNxgKZ#pFE>jf+4LOmt`6hv5Vgkl
zi>`DfT<vjhS8_GGGA`{(c-Dg#wdB~mp=g9>J)Hjv{OIu@A3(Sm9=<ff#}Jx?+~z^`
zS|+!7@WGaFn+Ihq`Aoif`B%bE9<GW;i?Z`4wj-4AjfX#`(Y6R_R%VCswal@lUYLW<
zk73`9UxrS~_|Q#0;yc7kpFwkAEt9)9JY37<?~Sih_<JX#%V8r4jc6x?E3R|w(1Ev!
zm*-m^zh&~u_K!h0WoL+0?jPMLn#$y0ja^y3)7X<I=jrTE4c}?(zc=sc7def-{U&Yn
ztn4g}krXMHPOL4er0=*`Gdd-B_zvx*OwQM?zLd%P+Ad88K#AaZUUr>PaMcEKr*B@X
z4Q{A#Lbo+DIbho+IeA|rCc4PCy5gbQy>N+Uh#dS)_Jum9yW)fHiq84Aq>DU4>{4y8
zX0dNL9u{qHhzTfkx!!cIRwfVYj^5D08vEDeV(t4^QJhle{#B@(THJ&2fHhWOUm~Ew
z`%+M{eYQkA5@Ik)cwHk-qlDKrZr=<+Lx=aRXy3u@+kiOJ$Cv+v-NzxQXpi)i3P!A^
zhE5-$_DNjEm2k~QkV^^IYy`oSaL?}Wsw(o&#s!^mzwNBm@SF(SvG=OfIcx_6atzx!
z@f42A+g1FLzf>|W_*I<&Xyf7}&f!NSyK}_FG>0Gg97=1(g`V-~@$JT0plG8-ycFs8
zz7<n75XOi>*Dp<PBVw~kIFuuP%gFzBR_k~W;~!m*hlBa{t$V)`9_B}KN<m-Vh&3|=
z?If2KweKTQR5H<8OdF{SzjZ6<#D?FBf-B*GjyO56A#Q+NR8-Ira7PZsZ^h)1XYpG%
zi38CHGv-d;Aw&R{a9u}~AW0p+6-ij&&Autzu!K81A`%Tj^W311TU=ua5BEdcvp#5u
zk0dqaw_+$uIK3mzl7yDu5sXRJ%Wp+&7I%Y3L}v*%c-(FpQu!NSMG@zO*imEPMBC6~
z!&e?Ls3m;m5vS@ro+d4B<Ff4>P5t4(oBG3nH}&U)M>jIy8Pxb7_J;$9Vp>$PheVt=
z9B;{0>X7#)BE36$qf-hZic9$7^V*iQs19{Jh+)X+%N)*($50g9yDtUe9f$gJ%+b^(
zT=<Ve-QjA7Vp*<O?J!W)IkcPnu#VU&4mW><hm%#-5nByKp8tq5FEv8DVN9wK*^Q05
zMr1bv_zR;05cXaoIsk$3hM+sxoFiTU0rsVm(VtQHrAA=4DW_HUmk8u1C9fl6>#GR`
z|AJMiD(CJc?*-@s$ou<EhJjLfECUBY@r&LKkpF^=2-ttC{3JkjP#B&7I)qZ?{CeW9
zn>5AWB32-m@wdnqieebR&rqsPc;Il@$cg+dqK8s-g#j`MGAVzHFrs+m0|+I+y-bb?
z6NA(!kW!S0hA^juQh92GPeQ4>2|1k*jI__+WW#U-T`MAr{uZ0YKpM&}0MVY2l!JWJ
z-(v0{AN9A`JxZl!1_F=*ue9x3EFmPe{uYx+sXC&9ZG?2#-(n;wwV-6<(*YKoCS=rh
z#FnG(mO+F<8t!kArEI10*bBFd60sd%T_K<Mw}@FvM0<d|1uWnjAQwatEsQS&sf8el
zA(i;IsALLbL^kow6a|SGAx){$6v0^o)^Z>xIy@ovA&bZo@Z*sF+!2>}MaiWt-4aAR
zpin2tj>}x?=IM%T)lnUuAw>Zy=jl}K=si4X?~uz|hFK5~l`8%8<VGl4?FmlU!cdp<
zRKs^7BofJgzetvJN3!>yIue{oNJ#$;XOdE>>cW+zRH?e4aw4n!up+>_Bp^~kl^XO^
zJ10Q&R68c2p=3*53Npy4?udzhW~cHcAM8|#OFr1CaC*NXJ_qzjxVZbtpaBjpWB?!s
z7g{F|88<(v;+L0#W6WQ+8S&#vZK54x!*|xPQgxqrLAAUgY?$+Sl^1gye9PhFj%4pV
zNXNL@N!Pz{oqvbeGN-kuWlk%1yFl;;F)zb6-A?X+H{Vh6G3y8cr;{=TJi+OtRGlo~
zbW$P&3Qi|?#9H>l2PpM?)#*H9lzOG|I07G(8^D&iI*^yHRGnC^uBIpC^6qhYbTu7_
zH_d(Z>S~;8rmOXaGDq!YZgsM&IrHK617gcThS+|T*)W;x4mGS*hMUMLU%Ts6>w$3C
zSZb%*MgWYtrZ8)W|Kj)wupKVEOYH=rQF7&7YAFzZFxTD1mICmW4(Au;wsoN7LlHOp
z?h4vm_H9CW-u9gzqks}0O0rz|jocA`u&>FoW3xGUtfJot^0Neo=?&mheVu{|HGqwD
zsilfqAMPA?1eLDy6|Af?QmJE##ee4;J0ob^d)L11CH}kx?QA3P3L4r{l}=zk)zv_}
z4oGH`XPCPq<+?p3Q74^|d}|tayxSehQ~y()|E&jN=(s=?vWX#h5@Kq6VgThnH>pJ>
z|I`k$;%S0Yk19eM78}@}yPg5yxUDPaRGyX|nCqs+nGOvn5Iz(h^Sn5m*1hw=O>av&
z)we+K<d=A+Hx;kxO$A5w9Vpx+AizuC5%A`a4m<V@Qf5y`-lx3>w|aNL4KCc#$lQGc
z*oyChWB|V-+_yW4+>^c;Sgn3%7uzz~$nQv-_WSKy7j?1U^P-L)39_R{Ijd!|k>fVv
zhOlWY(45tDApB}z$&yR!4zY18QgFxX6N`JfTbXTho#yftAM$T9*iYYjUc=oHX$ZS{
zUh(2BbPZm--4T38P?~iYT(E6Fpc4uumSV2bOo_mrC1naZ1ZItki3aY-q_;6yL1=c!
zX8>RW!nV1ry4vO{>QagWp;Fu;nS!)al-W4fNN3{#ux(!=+eiixN;9wS?g$&^@;KBk
zmctRcDX0ICZW;)6Q%*mQ1{mO}mUj;Dq+ZII=UJ?w#B&%Yn)_Ac!#KI#BOk{3<21xX
zAaRI7t`Hrwm`()eunmyTYAEw0#wm-F*o5FXhj@BsJmJZa7kzQK<h@=TKzXkhhg9TW
znNPB~#=8S-+^4O0vzVVkD^z5%C`pH5Oj1cYk77y+_q&P`?GBg{UgE{+pO<)HB4F~H
zJCbKh19RwXvPJMlPWFlyGx3B?gV}n*?!lBkhHL;5x=ewWu(_beC2TI}Uy;G5Fym3t
z*dgB{qYGtRUttmAJy{ry{F-bwEb&&%?M}?06m}`zfQ9XfmtL@MF&C3eUXUhtJ2Ls>
zQY&m}Ob$hR+xD$1tP+{VOOx%7k2%~nNLf-vQbOC(XUiayTZQ!y7f-S;@|r0Okbcbs
z6XgbgQlKPxEK><)SjvsZGNr^VI+iJ4UpZukrQ8nLVIemfp_IT6w>(=IczLN4R$$)g
z&`!)doUkM#9U6?y%!gL+6iVv+nk?45iV2(cK-?y-C3o`pqx`$Yy5axAR49{Q!8W){
zNL1<&NcOFJ5VzjrHyw|mNVpLywO`>zh>HThi{LedJ*ILajKqF>TvB*<DmTJN?6>n%
zq|AO){&@Ytq<wKk!V$+c3X}hBe$PUY@*>6&_ehAuey~zS*7wS5(F+$FTqY&bz*k<3
zD%Ei1y{HoVRbGr<e)+~%A#SPoLd8`U-@&-<;+w21u}!ag+?&xX9+zv}Z2a<#n^j!S
zVSC%A8$9lly5`gF8drhbq~p2}c`mo<PLUr3Ts!K!5*L&FHpS&7KWVt&WQI@nhijm!
zKOA^ffAD57GNbVCaEef-zDnm7CFWyHg)Vlf0LA66Y?g6DOa(2jk!f+{MKcx3xQeC@
zitFkP5c`9*Pwy6;9vPdUt8uFR+z~g2DsJXEQXE@#5zj+WT-NhQ#{2v*{cw98zv0EG
z&P$94fa?Ix!Qoqg1NiKI;3s=IDA1Y^E(}Pu8(t2~#tSb97nVCtaDdo=<x0Vvzu|7d
zyujg-fy}|%3yvFr=r_WtJmoi1)tLN7F4nsEAik}a{6;vcOMW9<vzPov__AJ<Rzq=i
zdtqYc@Qf+&crVJBjPrNVCB(@7Ttt<~?9lYiVfyIs-(imF@bN(&>d6m?d8)%#h`Fr8
zp9l%BU*U7aoY-49CKb3yVKiVQ3+E<e-46dJX6A;6)CMTLsJ@lnI~=W;0z90tm?vBg
zTbq)J7jbD8Bpi3QuL3@}a0@H&7MJH(ao_OCx2(8txV+Cw<0h`$PILr^3tMU2!Lw8c
zI(dtIlxf?;T@I<;!=sMb->I%|-$)S8G?d>;AurFpLYHni_c0NDH~<zoaKlFsDeuFJ
zZ~*l7qaf*L$iC4*g)ReyZq-FPMw=ZTOQUy+)Cssz%WbkWZOpr7nH#f|hsKRrIe_U{
zZ7!U}X^U{u+km*Auk-?QqLv0ACu(T`4VyF^O-K3Wi8_FeDxAF|oLNi5o+@|Ofn<5a
zZb00bmAP!?v3$le=_5<2(;FF{xm%GpvOZ<>M%I@M%tLYkE+8HXFX4fhzkoc63s{C=
zz;M7D(x;@kZYqD}0^%WfG}|Ei9-h#?U4Sq*e4`6IlC`IH+!@fpdUNQyCNJy)ilA`S
zE+F`oH+Sjj70%wJC%W}(BbD2-PWoUO4$txeCgSiuABb<IkyySbx}T#&*LiG_^mW!Q
z365mA$!~z%_gn{M5DkUH{XpnFk2j`64|V(C=174D{;ucD?*9ecLlGfR<VPK;_vlEi
zO%9Ai3`7`Z@2?J$9eW(38A>k{x%N1EQ%90^a9Ky_L~&>8NXQP_BE(;8fV{)lz~Ei2
zAdW)sYQ}gNfM(d0>M<Ua64cnNqgIC+8#&Xv;#k<V3Y$n|Nbk^VBOQ8Y91HsfJy)sE
zK~RnenhlUI@13PFn#f^JukOfUPOt9BPu>~G5(&ydmK0Gz1M%o69a8A&9ofcvV;mog
z9_gji1|7W_!c=-wAXIe5hj7B`)0+aJxHEJGLa{5@m?M{W$HtsasgZCGkM!Ljy^rv&
z0urVO0W0n>t{}0k&|^H(Zg=R{kz~8OF*ovOgQ_V4)(p8kAkB)0?w72D0dh~JKe=M&
z46*UKGQJhiJ4N7Kp@X?{P<NO_BH?sD6r0D@eZV{!DWt&w714qPZs-aqES;gYQl<L=
z{ZCPerJoF2^pau_DI~_#N=2rddZb+|ouRd{oin;t8IL=oYh}&t9$s5@iP)k0N7iAw
zvPZ(;&H&rkzHu7xRKJ~<Y>}n6GoY51&+Y|wgTb`OZrkyxobu3i#@Es`*%?hMRTb$r
zJes!9A3m~l4r;6IrFdK`o22v94<Bn*KYXOIMKhQ-BT&Z>Yc)^(KtS;*9iO9zLXQhw
z=^30n0PHc+F2R<?80S&W9=}}l5QI@f7WA}FqLdgABB@bouL#5*WuN9fy5S?=r(U=z
z0|DOyKoI%V4+fH}AB-bUdI|!`y;pElP;7dk^FG7Z4H!L9gnI$Y7h~YJ0eE!1EJfh`
zidcF>u5*gFFQ5X8n0$MXN7tWIcRapcMxF!8h!_A0Lj%MTU=K2ihI8r=$p@lCBp<+A
z%;*787L+5;oCXCfWWjqd5EqVgQ^psFKVcx*xHoiT&xnIv>goYoo2VKLvF^z{a+ub$
zGf=KDBw^QHdq58YYlM~SIq^yqCqxVCiLEeb!FVYO_|ZgM;fVEv_mM}Ls4oiR8TLkp
zrUCg1(tY27lc9Jv3WFZR#W4`@fbe9<KnO8<7-GHC4tf+3fl&Ui3W7ca4{8&`NMZ1V
zSV#uqf~zc9cctzg1@snW8aL@v8q3zTG7XyKDKThYUnO>h`U*~#!e9*XwhY8&sXG*g
zXo&yC5Zf3;5;GtZrY=Aj#v!U1L#)GW$K{xG#yp&hCU!ww6z$vvqg>Qkm!eMH2QSWd
z9lH;5)9llzZB0rkWvGZKd<-$IR6IY0(IX-Q8VH$xV$?)9YWPP7^U#2tg-IJ8xPY(N
z@Q~F(Bu6vC58~mR!dL8gU>z2pk|8ZmoJ)l%-@wbX-Jz~dJ24Y1)`zhoi~nhqopDKK
z=A)5{Ew(Z+FpF%efO9YisRm-KSh1N2;PIEK?XK9&KnQ&ulaPV1be$8iRyq1c>Mbu$
z%v^=J^+et^5T78~Vkd+;Gqd!GD$J1Un&`x4gpx(JzpKSG283@YxVW#_s=(JR3bYx~
zG=kz=WNHJM>DHoL)M2O6s?jp&w(8WhPjzL<1}(jALb_z-vmCa`2@0XxJj)arKvL&@
z-b<8b4m^XJGv^)bJ&E%)(L$nK+wFssk5CZzmE(8?v7eW8!^+f<U<TZ72%804{Kbtc
z%3NV!n7?A<I>7oUE<=N^>lK8DGr}qMWNFu~ma<3{Hz2;c_NgTy>aQ(05jf5W4d~3I
z2_ne3T+};TfMk;lVA8iN`P->0HI=(MXG>DVmNTNK`c`wE(*SIdp0U*+sla(mPbL!m
zHT^aiI{{6!o&zz8(mp*0K$WbVp;XMp0k!EdwpdRoH31||B}hu6w7r7mv@jv+S*Pwg
z5?aDJ(W!bV%jClxs~}{JGS|j`di}?3X!QH1AD<<3<o0>a=e)8XXB|hofBl!&zrE6H
z|NO82|Ns2n##4+5*1vCWd#p+NIHq-L^K<Af?(n=6M^jIV)7I9hjtS@}lhlti?Op!J
zeG*0^3o>^dk~zoQZ<TtRKS|YDv17xtm({Iz{(XD}89CL7!SIl&mY5XVH7P^(hP7B%
z)fxCh9k=zNyaUu~$x`FLv36RXYB_Od3&jP*x5}@<BW<Jr8HhbPJZn4d*CHPbEeuR^
zV@8U7&b4D^m3_|PLt~Q&MZaa2Q#Pj3nFi{d4W-vLrLdy0cVzLRx2Y4+=eYY+`nI^B
z!$6CDn85L$b$@htYCOLtU>30Xmc%M6&0t|3sjLGW*ou%$(I13Nk?0fhm1=8XQXNa6
z$-7r&6vc(^mctItlp0Dp3%|BVC`(s`$m2V_s4V%eUjQ>zwY1C1?5A21xa*H}){G8E
z7H@aVam6dldnJ;U(^Dt%htuzgxxAa)tKc1&!vdC>4_ap^h;ShEC1%EVWSRJun`#!B
z7=3&PlIdY=3oz+e1?zQA&_-an{QxrECuX{*83{?<bC`Hivp>^+oCyVz4nPUSzDd*M
zW|SOep8eEM7^1;E(@967J(~821-w3CkJ_2VJ?dojpXcA5X~YpId9iJ=V?g81!S{A`
z)q&;DVw76C{m6-5of8iF4d>`vYDf-Jw$lu3IVoE0#6FTbO7=Vj*qrSr0OnR-b&Q$y
z)#48XP4_B4dL$PorvR0!NCO^Ow-L$CMAMN9n>nH*hc)vgXT^Af`udjEm<ahzm=#!o
zi^_m&Lb@fC1;GgO#|B{#Q*0~BA6G?VQ}a6TQO!kR+PDRr(|bm$O;YVe8p+^Ua$yBW
z$dnk8)o^r}vNJaA>l25WC)gARLaX*|AQcnXmZxNSSYr`iJY{qf9~=|3DU#AWL~;#=
zW>1ubM<{jHoE1x7QdVIKr8!-be}IEao4<*iNIdpV8HAYehOINLPxL1g2GW}<Ba4`!
z_ats6M@$M`(cQ|+p}<?^c$gSlGgKnB%xoER8VEy<AGGU-0_7{1Q;d)VfT?bx`No<$
zCUSj$#+3WQnHOG0ipjJ9L8^=j=S<peLOV+|;*}z~3Y<zUx*X2|$^04lknqNy;^h!0
zdytl9p1l5%%f0*qqL-N2ZLU~_PF_7F3i(I6ZBjVz(_(OY8y^7^UMwBA0tUq}O`RN~
z)9D6<d6%g-mhB1CI0IdSs1+q#FK}^*9(Cd&1*a&sAJ;+sHcZr%ymt#ON54FonI(A(
z%QqhBoh{%A`-oqG@6*mwaBa?wgWf30`zT&IGL%6fETH1UMNcF|-{l1oWNNu7jN;qg
zHE=Y}S)@VxWhMGaicFE0tv8;n4qq;AUr?=Qsw%QaF;;w{QX)MIJ+(T0mS+~B;NKBP
z4?cYVNN3}2=OkWn>VS#9MI0*l*piF`)C0lJ@sFez<T*PThA8^Pi4p?Op=W!r9ME~Z
zGJ^L6Qv!4iwhVHDDKH)(z&}H*@U9~E$rtt&K}tj--jjjX7eflEgCzpE2Z;dJ*SF04
zQ?TF82nYW=gQ+9xl#F7^HfeWV6|t%>*C&5eO6eX}Jcoqxe3BS85pkIM4YgT1|I2=n
zu3Jp(Hk9aE=b+!ru;7UOn`7(YE;PrXk;*7y%8oAukiEX;Cl<j;3K^OMVHllqMsx}y
zGZ@^!V0<a!5muq24i{sBUk=WqQzS!W0Pj!N`N;#HzJ}psUg!@RUgY%OyE!HU314CV
z&FpPk|Iu%j{-_6CP2u56ce6ZiEI{0IQy0_WlgI;VBZDH{2gx<6<6}ej=ytccubcVS
zgzLvH{!Uz^)45DQlD8SH1<3Hmn9uLYXDa-b!h?wBgA1NOuqVJ%W%6C21BjORU%FiU
z^l1pDZF!FcId@!Lr=NG^?k}KqqKoJ=F8|ygb`R?pf*9sIOuuC0HPVkeJKbQ#eN|J4
z|MzrZbGt9XT}xb~xas?t?~B~feY;m^`F;Ul_G8-I{X$`%Za6H1(-q^V<@KB_du~*W
z>lRo{<D$g(+>N9~4*7HBP$wHIT^8IpS=)K$`uhB%T;o*vnVLOaJw4baFE>nn9^{5e
z)0q$XLeYqQC;))B0Y{sRh9_;4aY5u7F6HEpP1AH(-w)XcaY5CUb6t0AT{{CV4|9)e
zC)yh8Z7B>rgzh?@#p5imSUc9Q9tJ|FpgL>dLf(!eJMY`mjtrrb4@C7Gr|`&lMT%B>
zijarfksXJpA8%9S@TJpGWFDrYlM*V+F$*dyebWw4X3gioXcnQQ9q&U#Kf)c5d4bHN
zh$Nj6SjH2yM@Jz`WiH&|Myut}24`no`e`E*bkQ3PagJj&_gdJQCcl1|TuPRd8V-lk
z7LBB(B(N=w20%F_;)pt|1Ee58OhFh73Nv+QneUjsI?rJ%ZsBOUMC742M=(Z{K|=;e
zv=2`Nrcuhgi1P$nn;{Xd=GIdg@DafELHL=b)e`nc*y_{87*`qu<*I|2ikx^g1eGC+
za-Oli8H5wGP`Vk@6p<4@2)+T_D~9Kv#mDDx@^kIS?OZfO(&)+Xa-5^XhY!xISvd^~
z>{BqPktn0hCQqEDCJSeRAt))rB+)Dj=aFr)PwJZ1T)48F?{>EZQo+SN9i8uXZ*>a;
zB3)vpCluA;PqKzHG1<UAEAF8fGkJLY>yUzQ3m>IO>~O(K*uqp<ScwMC3`3$7XcQL*
z5*Ws^@+h26vz;R|!ig){$Y^lFBrby%`15ik9ytB8z2$Vp2?^Fn(!|jq7_5}nY<KkG
zL+9SU#nqX!4&U_a2!?ui>5Nwp-G?7lHvf4X7dJOLdOr@_R*2!NU%bA+BXA6z%#gSy
zm^jIy5=;!^_>4_#-+qNL@oCdinaNTMNByxk@-eVO1rc+*@SC87zx+lBrIXf0QRaf?
zejpfhGmnSK{@8Rs#X41=1&k3EiL7Amku;r2#=e;ygSoEV@L>}cq-HdZFyD|v{?!sc
zEsU0tMiEz7Q$l-O%FXHF4;dwCzG9C1Fa$EI{A?5Q2ZdE#dDgX-mBu{MI8q^*Q;_*(
zs680TvU}v-V$SNwyosF9VUc6P=QDotd4GCjbHn}M5n{ka+@V}NX4X6+0S@v3x;vPX
z5n3HjewCebHVl4tbu6PG9OB4@`u$2ByeW~aG$GoIyTCxOJIex@5K9vN18J8_4Znp6
z@qHxS8|^c-rDhdOK2!2Ua!{CA1JEH8Bp$?UsQ|Y?NWWK~jFRr164|w|8<R!Nr~YWK
zIi()+ZP6_3p;x<@TbUke&-6b>qNXXWn%hx!rDVM5_o?>^$L`4U)e=1mBex4IU%QrN
zgX?M%Z7y`A@!bmqK?Gs3gjFV085$eh?AbaFmolg^)kZpLQ)F~S+@2gBm=e2In<8YG
zs=Y`P+L+g&Om;?(cG0yPGbqI7tvH&FJ=g6=`M{=(NI7oWdwR`jB0xAJ4KjByAe6`*
zLvQg&i$IU+lJR|M5z)y!#iS7NPm+1825~+PJw-Zkh9lHWEPu*~iA8aU)Lzp-7ULot
z-I-));b)el=1Nj|dbs7qfS}Jy`I-o?&!D#^eQWSX)3|won<BVCLCd6%+m%UiK`zB$
z{hjQPK!R@(#0)YNUk3?8#Arw&78334vvq8zk*>-TvX|GyX|q>Q`|$d?$>PRekUk_3
zrdSEWojv$}$o`gOspWln{z<XpYT_35+i|Bp5$YsS@aj@tRKL(_NyZok8d0K2aTNub
zj9{5egLX2{K{XT9R?d$ikBdz6tj;Q#tl{3q^~2;nUXiS2;YSmiD&-nHNOFQ_gETZn
zE<z-G33H;KfNsPQg()C{nt^fZa%qAQbEYtW!&kghpc|S)^-21mSRrvL=(q~Dz72uj
zq7sn#PDaXzinbt=q9Bt-Hj#0{-W2wI^SWWYE|Dr@Bkh{J?CG*l%WNqdYCGo`RGiN(
zHZ=T)aEC-Q0;5}|h)3*rSw3aVsFT8*s=SKMo1Lk?y39I^OiVHjc#@aN^vH-jnfw$3
zmqj6`2(<{M<QF%B6VHfL*=f~exJYpYt+<vSA6<(SLP!J6al0Z36o5nD{VABm7U!<m
z&x5&}!)cURki(BW5*CMbv$!9xT)XIJG5Ia~3F4AjtI8005O7~k+6HJk3nx(+R?Y}j
zfqE-t4PNahH>FL^fM=czd5+NbI*gEiVP@>JneogjJyy76a~yWbYchO3RA@KT<!B}S
zFlIhfq|LLjB9Sw#E7qH7bhNnNkjIL&sTPfo$S*=EH`A*L=7%x%N&NU(Rz)J`x+0wZ
zVA=H+XJpZ$|17B@kz-x4$a3thg&p~^CI88eR=m_#EzH(vZ{=>Eer(A-N={XzVY{v?
z=GofqE9_?eeq7S-<#MnZt>$G}EzhQOHa8)w_F7i{tan)DkF>6sZ<cy*@ou|+Y|(#K
zRT0RsuPdh8O~5-my>&P6_|p2%iYgMh))mw3rr{l~@Va|=Y|(#~RFTNBu9&8qjJMpk
z%ld_N`@^nEUheBkiB}}nOx%||wPD9N{Jb)g+vCso+nvkwlIj*_y%n@W6?uJA))n{L
zoz6Ra)^*GC*rNZet74I}`>G;Lg}CJKb$q)-dVF#0S54I%=xJFE-f6s#ddJsXH&l=9
z`Ok_fW(j6h5fScw-}Mgt0{36fuMDhnUWw&%QK_H0NyF;Wz1s8Qg~8~Ji@0N1p&z%~
zxpyd7y03d&R&K_;RB@LWRu#d?z+}bmDVl-TT8}OA{*M)Tkyw`%d%s;SzC#<;b>rjG
zvY)}*<vra~mUYE;yS&77->x&CmzMpkvm%j}*A?6Ca@1SAUza|%NcUJ&B+}MeEMqll
zym$KzSu6nFzoMd$U*5Yi-|fD6T8Ycv$LY6UWmN-kuB(;X#qnE|5^<IM*q;9^sUneM
zT`}J-rhO{zSJjV`??2O*PRROO*SRXC3WK90%i{4k`R=}bsUq*t*UER_Z};kN9cSaF
z{c$?%XW+AZPgnGHU6I?yj@IH9|FI>%TsqK-S9n&sb-zzRglE8`*!?HnDxg%KSH3%}
z!oR>fHTxSp4%~iJS;@;Jt$k_<o(tX#3(sxXwHzC;1+jX1yLm!PgO_i_FCxyYDCAsM
zq{~F*M+53a_+C7=IQv?>C#Q{LU9sLgIb85}-;T#g_Mb^L6tX@-^Qy@`MXcg=Lmn&Q
zq7O#P_vCca))n)kaMs^&PDj=^{Ko`6R!p;_%Ugth@_c!ojOu<Zs78mGvaH6?Jhz^`
z#aI}AHP2IFKkKRpL{8p+U6I$hS?APNZ^%M0{xh9ZiInv@6`rMZ0(#$q8do2Fc@Ifr
zAX3&E1FpB}Wb}64&YRoOLq&QgRaPV-+RBHD?dHVf!nwOOJx+)JtgxbxYhAJ4oTOYh
zGqRWt`f;G5kaJzJ+<dTHICrnC$La8&WmP1yUI4s6hmV&F=kE3OI34~oef)(S>x%p2
zL-v+iJAKL?1>-;3QHkZgsDv9oc&B*}Z|-W3B5~iPi`D4m)>hRJXhF}n_bb*<UJC@L
zM^Fa7UqW(QR%9%1mU0T>^6<5LoC10?u_B%H*6MI!)N+Dc!jJE93OpdwT9M;leXdY%
z-hke<yMN%LFyPzAigGM0>xw134bjOcF9hK~>ZpV=_&pyg<(nJh`$g9GaBO_2NdL#C
zicJ%}tjLhr6GpAlXJ8=`|5al(zHVt%EmLy(3PBSLugpim_|LTM5y|VXkX$$qE@ZF-
z5P58o&Y?OG63P3rV(xMw^=^hk>7!8mCv{X{DL)@sK=w-)#;I#^YWzhQg%yRY4Ha-d
zq1)?QK_TG?`z#E^+_NH)Yh5u<ZnfUg+0FJ*FbL;IB`>ePsF|{ZeGiw*^xu7`#6<-A
zp2{oxUJCkyq7L4DgCB))qBT||axN<(;T_#&-|~702iixW_|NpI5^^ppCb|pjt{|5i
z^4KC>pmkRuWPMkV`s^tU;mpWlI{ase6@?t@igj|tej^|$9J3z<;~WsEgz~YjME7l3
zg~1~nPT!A0@t?^$EM#pVMw~AlwY{Tvr}9Uk_|K9m5;@it_nV9Q+|{x?(nvVFDiZ0-
zihEFC;A5HU4Ot0?EutckwGnhb!o&UzB3rr3KZ>PUOQ_<-rFmxWa@>C#zihbiKUBD^
z1yr!o`k=JeDHy<eH3tVg4&HwR&0OV`X1+(@0!#<{bwi$opjE+&U8`bQG2$W)_VX6j
z@F)_l2~?|E602$<x#;FSXyQ>YlqM?{$#YS0j;_E93cAzZ-fYEg=*<?ge6tyFIPH{s
zxgiVT_|LRk3R&)#bR1#?$=ubtQUXFa2^9l5))ng<q2fKgg{(Y^=5STTs|i?MnwtOU
z6#nui<>znT^N5?ts@Qd~SXRt)c+J}!xaN49r)r4G$*Klm>2m`oE{5)SFK@9tk79u|
zS*=i-t7^_gIO2k)4n8{1NEF3>j>6*U{BBZ9H)71+we*NkDykSnUaN}mXT#3poxDXh
zJ&M79g^e$Om33eAOovufnt{h^SU<ET5m+DIEgE==z;dD7W3nEn!GFdrK}cS@U<{|b
zDZ<M;dJFk_6bs*fRBH_4T2@PX9XskBH)J6gZUC%Ub@E?U+{J{IecJmBJXXU+si#MH
z%eg-1mE%kX5hRX4-pgAo+@n~ICWY>;5ISXBd1&pp#npK)?~!(oLXmL*6&a#emKBGW
zXWsb&<p|<?__?2J{O5<;HdjBdb0DDiY62EwIAYU%M?m57^Bd%5`Z^ugkFdihA%vY0
z6?@nzR~7Rui1Dr1j|gjgs0i2Bbg3faA=jS_Bo?6Q@2&WgUyOkfUAe1b)h*DfA~Hb?
z)8<?8FAGCwL~YuxrP8Az3G}9l>-4V8$U+$Yv!sedj%CGu%yFY{bI-g5l0LMz^Cf0A
z0L$Cm3{Q^SCHZ`hQhgM>{Yo=UVCnUkJFf!Zf|`*ILLsn^li<Iqs79cy9A0zhrhT%t
zeFhd2;J<2YjbW}UJ1jjZ8LIo9hzPIcXG$@?T@`^S&)!4Dd<zA3x!i+;AE&`vJXDcU
z#bsSF&7sC``VvR%@#92fUy7`TkmcoN7dgWa$NUbO#<Kh@(%&TWBP@56m0xKVqixYN
z)E`mPk3zX9bW|kLmlYA-$QW#I@g9}^*rNX|sUnf}>9O@&jQ5+QYg5$sLq!IMXI2!l
zR^3{c7_7D5g>svM<{nbZ3P{v|p}R0<WFdb4nZ!>-(drKs>n-g4?KGdaK=_A>+(`5>
zA);j24;9N4R{uuSYlPW9PIj}2WhE;soB2Z}QiSf4Q0^i8kJHfM+rx^C{V(f^X(9xG
zOeSD43G`+|wJK+}Rki&_HsE5p(+@mOfv@*V70Fw$ylD8eC^7?UZK5`KYRTz0QK5Kr
z_@aUbev=@<C4XZ~c%16&3xd@E9Ls9;ys<C1<nMe8j}z@b%c@9Zd7G3gxzTlEL4Mev
zdw85|lB%;Jk@XP?p_n9(c#9`K=p-InOz`1kMIbFLE7m@dQ@r8i9%L1d6Yn&<sO06g
z^pncS_f1i}MZp_H7>^V0>s{soF=#B^@{B_@Xf@E{j4WDA@Q_DEF?6g=b4bEY)()SB
zJCDcX#QV?m{t5Zz9jrH25O49$6Y|)i|13={I<gFQ%C+2BN8TcQ2p*EhrRG1=dnn|W
z_pr>YCTMX+7A^YEswx8MOYbw=Dy~zcDZT*iG%Alv&VMEg4w1gL;E?#aF(`v?e9*K!
zw&*|Ws@TLKy{yRCGln*j>mz7j9+#ZIecGhNAF~Xmv>jihGTz=qGV|P8^SB;V@<^~>
zmRb^9jkPmz*F3f2VO*$CP3K=$*l!FtZ*7OciSxLa{b$l>g{(DNXDB7ZjyHIt+<9y-
zd%Rs&a|Zmf#qT%zp83`JrJLmaY18<eqGxS2t-DUH*4it$f}UE^iPc(BT<}wca@`n*
z{8hPg5Iw$}jC5p0k{7MNK;@bljnH5KtM*KWJV}ZfX?c<?*F=}(jm`8)k8L$sDBj{+
z>dQ*ynu(aW=}gFKn?pP`D-v0Mb#NFPwpnj2Sf3tS@}Cs6;-%H<P$#T~U%O;vQz3xt
zv{Ju}VGlkkjAKGpW3it#RRnS_JpvOr8_0L{skpZv3|N2NB8jq)OzS;SXO&gOAjYCS
zFd-{JkS#n^#But#R1wIzG(aY#MB-J++vvLP1YQpn$@7&|k;pQ(KOs>B874->>jy#D
zLq+n4WmP0{t}9+Qy0KX}OJ|jsj-rZ0mJxf2xBC}$=d@op<gp@xqR&eenSF4nJ145x
z7w-)cBR;O>y@6=f&Px?ZytceINY{B|V;hUS{@`bOcsoerCT(5FT3d(v8`<98X34(u
zzx{PZ(ZnTHB(ijUwGf1%3|=z*fC?z+<sLRGm`5(%BM4a=o0w1P(#1c>jDDGpV7b%9
zk&yM>KV82;hUY5BogVK|$?=~RRU~r#R&gfVbM5F(zxSve`OmZfD$^V<J&~32<dQAB
z9yes6Kl{(*W&)(_YvZ|dX^|_?4<tA8z{m55{VEhQ=c3=&x*1|&oQTj*cr!8K<N3~s
zhz?XDo8iKR4R$)Zi1~r}#(DU7UN)|xb2_~st@JO)mx(_S&CST7J%7LBKuBV!Wt6^a
zeWYh}o5xJo_-OHP5%4|m@~_A1Abyk`PehO_qv05R=0s=Dr@pGxZ<La684-f->ajKd
zS(!`+q?ue+JZ_YgZi%~-SUy_f{AXbm-9_>Bi+$5r)^^z(TD>6)`=<X)HV0+s`NigN
z-WWGw%id=W&S%p(gwKjV(l3kpx-ojX$@tFk`Dim{7JF7CIcQl|WNL?`iv5Nx?CuGq
zYph7}(WUcyMo1+INxj7xS+sa!orLk%k@ab;rHSy=FEVBV)W>@a|55tlHHMduRi%8R
zQuSM!JGtuPEsg&yPj>~5EV&$p2qvo5HyL|^yY=x7Dtj6$Rs*nPCbKurrkJ;DEG=%<
z{3jH=XEj+0Vy2djE7Y=%3JXqJodJogqrx(B!Q_3qro3_4KDK9xz>euY?r=WaUv7GX
z7uWB3XP(@LN=CmL-gzL`U4}(yl`8^s*tqT-ynkJhRK1G84D#N!b>9eoNa*`EbLUL(
z`_P)R0EerDm;163QVcUz>n%r#AP;_MjU2<fDiT>96f>9(O86Ur`lS5gZzK+5ofCxo
z;%}5hb^JEdS`Z&UR3JBUf$+Vwm}t<|=EEwSDm_+c_(_GxowE2bde4Shoss$N)N7Ue
z%nubv;Y`00&o#Ahxu`dm=Xd0c%WJJb^w81@h?KQf00NpK1_dTREo%mapr4k7n#h_#
zVTfU3skRpL4SB2xdh2|!q6n{-v^&fcP7>_5SxN7-*neG-?AiHLMe=Fa^)_&dWcw}F
zNvGU?Xo(!P7pK4~EZmQ-Anty@Jmb1}ydT=|&G}*#r~Y2Wy&Iw76@1`tcMF}6$BHBp
zm(4`T+GcX3IV0Mej<3N#{!q<x)fIh-2rOgf=$cu?Iz!uRS<{>Z33{5mR~=ch&d}wQ
zq|I-$&EDD5A1ab$oz}!amexeN)si>*?IzF(d8|khcb%q$tWQ(8P9S;p+fASo@>mfE
z22t_^vex9_HBKt|x4g!KT>h^sii2JU=rfWA{vw>2s{ZZyF(>4)MRMHh(@W$R@2ry~
z;ipzkzaftm$)O)h4oF>6NsNw(YTv3IQ~9xy^YhCY&&ze~V|o^G_`f|xXjyVzI_ZB`
zg)SnGMYra>0B>cx3qJRUicBb=(=U;_KK-8UmUrOo=G+N+tjM=a-#Mi)SbyivKIJud
zn`w2<bMR2fKP39XAvwbO`*t44YbqDrtK5*MipVWr#11E9%?^i%FVgkD8TA$X{SWQA
zk*X+;f{7j0aTM2n%l7b=Z8`EkJX9>&Az6`$BbFpTW_aHto5b4<?-TM^5k?#_{6%7l
zUjqG#mN68#>$)M26}w&>R*d|+%ZhbMhT#F1b8?J_N^W>9R9l!)W2v{`?ty7G-e&B)
zC*F9d$ow2TzXw9rAIs}d8jm+}b}X+>J@3b^3cIs9t)$2N6%hqoZ^&ay%qbF4z>x}g
zS#iI$)_-rQ+*&EWw~(gI#sjy1-F%n=C8<(HrsHKL=JJT~oIf(BJXB<Yl^7S1U&dB%
zd05`cFZ*kY{JunsM1E-zXSpi+wUlniV?~_YYSQaMWKH<CN5XHmn13Xed8o+zGtnZE
zUs{ZW;zbM)_rx`ST~YaM#O*I+&Fzn?gK3qfc0(RpWd0njR3YoN>VyQ$vg5QG6Yy9K
zX|#hl1i&x6Az74bZ?k?zLZ62UmT6uU=IrH<9gDO;Z>1*xg(CzR?I&sxZ)sVn-VzQu
z!^=Gd(L=>U`+gI73ithGMSl9k1_7ErB99gMu@xJHkTu&yI&S%roTulWLFun6D$$a7
zLxilkLlQHq2l-UJA&)Imso7PL$S-tPyYf9b@l<4gdZ@qzQ9A_UrRRJaAVmsgBp);I
zSPl0kR7WBg)sjCDv9O`tm3-ci$BIy7g1?!_FZ|8$G$D_l^M2hkVm(wu;;bUZLZ#CB
zg?Oqdzn1fwMYgSn3Q%YY1>zMJQtY>!U7(VikjIK}FVHa{(toY#Ogw~h+QCbmfv0Ln
zC8k4_a*M4$7~t5OUYF8t$YXm@Zc0$)QQcX;pk+Q0f2#j>8ukQeT@~tYr(p6TP7Ao4
zH{`KmlgWq`f&B8ylyb|#_SQk=7t2K?Z|kZEWNp15uO(Bw1+QiKh4dP(OeJWxiPUvc
zpVDtB<iOWCA&(WAd#;LY5=h<G6^~nrI_D#uk*A8vZ6_)rB5O0qklmaD&pB7`N%0<9
zWbQl>dka}-sscM`SW4|cJ0XuP^8M3sQ^?X%TAbrOEOX<#cuVQ`Pz{OyvZ?`C8UhPq
zK&Hv3laUezK2&60!K8{r*2_(6B&OoJA&(Vl+7!pSkY6Uh^7*4u+f{n3z=gd-AZX>e
zLc>oaeLCQjb?Ohg{A48?QS!xKrkg`o?k_~NMUKXYiV${=jp@?cxU6_g86V%qI6h~9
z{Od}dCNgVFLfXhRF<+$;VB&9e$}IWN3KR>w=8aU8iwVAN=_%hvWq(gt`Op&cT53BW
zQkFryWD;lk%eS%8-xFd!RAk;v(Tox)X<aeh(rdnrcK@Dm^PwX1a*8XLNLi~KE#K02
zzCF>yggjPc-cKFTgsjtC(LG96+?M@wLLMtJt!P$7BFjtlPsfyf^gZ%XOu0xODx7x0
zL4_7~)hl6Kk<s+6JR6bY^r<EMOlLVE>$4nkZ82l&+mfN)bErO4M5@)K^khoDx=!n(
zl_<kYFE`|=V#m=vovOIUYF%wa=Plvu+j70!Q@}p7h<o>>#0Sb9yEGd!j|UUVzAdrO
zJ;m%pi_AnTos&pj>zsXO!rD=%NA}u>pBFP*Wu}WMYqoFXxGQ4svg|(-^4t!7CS#9~
zWh}g9INBq@?%OjQO~_+KX69AK86j)s+kMrN?1=rmCG>r$<XL}XDSLTsLF{xTRr*Hc
z!i!|V4;AUWD#Cmr>x7X=xm3hbS^9ND7A<<x;7b*m#dygB#w=qcD1DFphCEgb*K4jA
zCP`i!2s?f4mHXw`Z^)uW|Cw^X5J~IYFTLF|Grv7s+=M(<WJ>2)+(6P=fdds0UGv|T
z5$~1@`l%vQM$0fyB>l1l_BpZio5>x2@w`_)>M}KFz*@xu=M}S7zde)mggjMLy6ZGA
zH~5VIvfQSu*xukRP4;7Z{ws0?3s|S!!o@vOZoe%D<%~SGhcwV2iG5GmyW4uNp_hLo
zm#jBr(W1vfDHZiWzyI~M15+(tkzlgjkjEC8YFzdtAio65j27pN<lf>vNBLumouO%{
z2m|82^pYGc&Kb|W#d{9)#}*mz$BG%d&pPD^{65Kx{EoEE*V36-iK4Hfibd10thnD2
zwtI{B6z-2L`p?A1FJ#Tee=w*qvIX}WvS`tN78!$y{FXC#N<sg&?8I|Q`iDwRBX>sf
zV6U{!AIu0oZ5YQ4EZVYPoy>zq;974_pg1~_=LUh?US722KkE1NxYsJr4RctZXNYhD
z7H#>jS_qLLuIsGe9{8?L^>N;i$BGEGKg+a5II>m_4luJQ+IzG(Ba0UOXEF;3SzG1I
z4|jBwo8UQ>7p*n(Rg5jSnNWV&aDBq1Dj(+!S+wSa6qhOjSx4(fi*jX9i|gb+YBAE}
zvc=hX;xqoeoo9Z1Hq*WzXZ`%6)s&9@`qzJX{l#OQa)61sFKfUrTSw2F1c4z+g-o^w
zIZ%LX=6maU&49AAN5pTkb85KVtB}(8pyhH#J}YD+G#1N2#Xb<vW~06F;Kg4cu-<M4
zogn5oSc?Gr7f3+|k=W;;3*HtGmtjHgg9Bwoe0>k(a1N5(RNf5mFOQO_ALUlcl9dsZ
z9XWd6MD(&bVB6u5C4V6(k#XcypNQz0m_zE``m`Qtda6xgnxvMUIVGO!3>LeM@s7lE
zorh$fri=)M-ylVEhTA5jUy{8?S@%n#7r?~}1*p@8w#^Wyr_Dq&cYyN)HpR}To@0F)
zKe3)+3!_uhite6Y?MFF=XuUOS_jc><IX8Sc=}rvVJ9kW@Ci3|&A7r!N56L``st4H$
z=<&{yGs|Au?GCYIW9ZYki5wgz`Iyvj9*e#AsbO0Xy-O0L&Wg7@kR7{@oqRTDy+Y&2
z$I}}d2dhJGng#GhckUKZ))wPb<h@O8yUd$rfk@RXKq=_{yzLJ4c#y4{s;v{$8og@q
zIg?lA()$!QkL%I^e3pv#f<U4jC%3BVoX>Tc2gyn?N}t&>Ntl#rAz+_f^IqeFvh$UN
zgnc%%B+POQ(aEr~2D!~8=%_tQ+(m406n7w$g3H4q=qLv8UGyYzJ9&3c>I#yL_Sn$^
z(V8a}8GqnYw(ET}KG?oX0^pwR`_yjnwYpC&`vmMUY?t;v4cn!?qm;q<#yJEFX1k^l
zJGI}Xw+-of+couti1o=K<KJjkNWn^6b3yz^X@jfX!(Rc|*P@+j+Nm<ysbz>`Ws4n8
zKS`?NKe6p?BUDcj(E`~)$$0U}HYe@SC{0^z*xWV)Y*Je6Zs6Ez$23lIJ??spO#yB~
z@F168pZeqC>(L)4_{BrW=ovd+!rs-odIKJr7F!-H4K21jPYuyx!}GPi1<9n2I4!ok
zKpM+7fTpzwo}T7gGZ5$X)H7UGRfC4*rAdSGGouJL2Vmc^-0C!LQBU$Q&gg(<aMEp6
zLq=j4zt!3ZnWPF^20cwH8nUzPxAMgwkZzPCHr-=;A(Gw^mqF-YmXNF!{=PazDtDkA
zQq1u_@)23<06DN)mQavvqh-m2%%s`%EkJvk2w973Jp%~2xFplmAzzm%zCa-4Y1$HL
zplR9?J5n|_x`xpNZXCIIP$!ouqgG^FYCNA5P$!bf1&H-%SC61~<)+P&wES(KdgP;@
z5gYxkx4Dz*lvY|^6_DZgTbA5`u#4o(g~qrUWW%r089TV4s&>`x6hBp4X!pa=KwM_q
z3}K0NGIdjnWSWGkebrRKT-k_!BC2#qXojE|0x%>~rBsqeu0pBo<mf%MxkGmxkosYA
zsi)*}1eY+HMrtRp3vYm|@k5P!ZVWM0+f~%%&nbG23jw?CW{`_P+b&elEVq4LZ3LtA
z4Z#@>dTN#*a6$e9x#^aUL`YRTZ$}Q4N?mi9x}C-o&maLg&4;|%AyxCYF8Pebw(&RJ
z_B#5v;({R8CgFgVscPGWP8^iw1990jDId%}p}44mz;Kc%0kQs6E#gkjar-_v;-aWi
zhg=leo}q3VeX_d9T4V8SFJ84|IoXd})vQpB0&P6YZQYQTML*_<op<H>U7(<6xu5eA
zDJz!G?+~*BlL|ue@r#WRn!@*`gM6LaJQ)J3ws~mv*}SGdrR_zc<L?(Q&oaH82jGK|
zzT5q{pt#BceIFd2+Yg9?!BL=Q^%O^eN<FwkYlq9?=8zAWHGJCB)LkE4ithU0($wA0
zOl>bR&41g~vky{gF%B2G#(wXbbB*oZKeopD#${NPn}Dx{X~uPDZ=my5o&0-I#sybA
zx@);|<SihR0MV}lz5sVEKp|Gjt~w54QFa5`YPr}E*E`E4sX*^6vByKnETJabi6+Zc
zvEW3L%Oxp6fh;l<_^Bq6Lu~Y18O*BR<~U(nNs(%e^UFZcS?FsecKu|B!XgV?hZVg@
z*M>vJK-k;Fp0Km7jBU9{{Z`@<Z^pH#a<C&%f=YY=cBPqU&2^V<T9cez3r;)(;X;RY
zQx4APt_&gG4|A+Y{$T%sB`U!phdWc2ha>;)y+k&SPBRf$V<OYZKwLIbterk-Wao%B
zY}FO$)telLa-k`=fS`RK4P}1_1l*8%yvT0QXcsN0V8oMMKld?Dh?h_q-{ex!+<_xk
z(RPg!Q7()sE1<29<URvIvL8Lxds#OYZBW|38~7&Widw+vG!XXm@Dd)`al9!|z#Bf8
zMG831O1Wq|2c^HIo54dpWs2?88vyTWVQKgLL#H0<vnB<+HD$_aD7&RjKB&c+pt5`w
z3plteyAH;KFHKQt_k2G*k|^s<l8EqCDJi<*B|H+Qs*=#L>Yv1-J(zhs<kDC`Mi%*<
z=m(mM?61u})Z0jZgk70@vGPitk%Nu<YcH)_`Biqk*bUzVvCo*(<>f!ZtBrgP$^=%B
zDu-LOc_+FkrIeF5*nC+FGkfGqlL~u<cy>O>XMpm8G#AV9$b3PRnaR&6Nmvl%$6CPH
zh6HIFAf*Sx6k#*Z7fRl-Q-XydAZzRP!`S8!+QzXypIRB%-?MI1jEi!V8%myz@swKA
z5;JxcHRK6Csng>aW=XvuBpju|$zwYh&eB<mKNGNIS(BNWLo`(d$1p><74FJd#vw45
zn?4Q9w32l?0O?@PVU!u!c(OhWNCRVt%ZfQPGQ9^%Wu8WUD~cb>HslQ~m1*91$2SmL
zVB-3sclSX21*n%29CoY+W>b-$=s<ibJ*#(N@{9W~(2|XLGpM5}yfu~S^JMLYZ+Ffz
z1~JP8^Zsq}fzRSdGX$N+bedpvN~y@)lyyp}xDYT1E#Wk#WRj&av#1P6IJ{*!up(5}
zA5_)ajtAkjL$qtoI^Hm|Nrp=RLpV3fo>^Io9pX6gsmMA3={Gt7;efYA9>{_dUd}oc
z;gC0wgU!1HtA>j2MXqiiatL`WG3~g4k&iQ@U$We73wi%@jrn8NPJMVu*PnHE!WobB
z*WVUD;%ltP{#cpuQlI0BF9kEKG5}}*99LD2*A5j6k>>;QO4#zJvX5H_FdWw+Q7j^9
zH;2#}CSKHM9EUMO&>L>@I)qhx<Uf!XEq5k`z{H@s{;b@;c`U2ky|WIyb;`K9vz9lj
zqZ(LB2EsAIR-0Wv*c>|XAP$>bIFD*IsXrWaQip8No7b{wnt#;dCol30MH1RlvGcQl
zw@yaCk<umW_*c2XOAV>Yq6;}eh0iHAI#bxQG?U7$T$%`StjG=BBGY#KWcOQC#6wyV
zXdhf*HdyH<%ruf270O7mf$U8Wa=}S~DNxt5?vxAnZ>cmw5=wr?ogTvNJRZW$TK71G
zdo}eU9I%XN9=jt##|)`_PQi1qs*r@y5R`qD?fRmVoLxD=3l3F=;K8P-i;$F2s~-d<
zyGBjA{VvP{F4gICda@E^1Ur`4UQ6lBP|d{v);WXFi$EI6Hb2VLZb5%|Zh>j8M567Y
zrV<|GuM9FF=A^?j&RSWa02bWZ@f@xgDCZyn_*PJuC#q-gYZh;8@$=Z`(9SA0AxSD&
zft^RG$Qi7f<sEOaVD|cnoOeJC4{9iTUvv)lK<EKbT1@kP>MphvH4fPnwN2Sz>s4y@
zfv{;>hj6+Y5M=}1I<bm3Ep6{}kh1LZ=o+pv41(~GB3`})2$-JRFsn%76I}XneOIvQ
z-kNdgM=RKLr)IF{dIs^$k&e!D&amkw>6|z`8M5ae2)A>OG0%!cAh~5uQag)36_bJM
zrX(G->@fBwnXt>Qz64S+CN5prJ(A4aelD^HjbgqyXq0@)rO4vQlNDRS5J^L@m^{xe
z5CA^wGM6y>MUvqhXAwiHiwUui26_MUsm8FD{rHhZ#7zQFLvU8W(PBU@PXs<@g=Q2S
zBkl-C%B=tadIq6C2U~|YGdI9)rLK1Pceq*I5DXF}pE9Y?(8vcuiF0RbI{ZWb&PjT9
zh7CMP&CYIQNW2|D`fve83(<bm@K<T7!j=WFT~1@g`7=p(&)mjl#9t)Yu}rhg;wop5
zBajVH#&3T9;{IoBdzri3gm}NWbf8_PrnSQ@Zbljgh!-={kKzttfLLEeO>;G6O$RGw
zP6zJ0bJl#|DOqbFp2CI#;fy4{HCc0leE`~7R$NeVWo!Ukg-MO?I5y^_p|i0hk;juE
z^Z+z+DET?vTHYmeHoZ&efuLoSY~P%UCIcP3GPk)I;cxiP;I2B=cxP}ko#aoDJZ1e2
zaH;70mM*o$OGzjg1M-(5U1}=;JO(d7f+{FvBg?!&E-HNE?}$%;F3{4cN7I>*sf>_h
zprk_&X4wacw*p_Gf#AjPufukO;EAf3yMlfCj`)MI!V~wYDzAdnB`YkL&$c(0nwr6S
z!P|RB+<={QXvJXe2pY0d!Nj8Alj<tZ=8*qd2Is^#ctX5{vF7+Yk<E)3Jhg}T0Zwc;
z#3wjv!PfZ$va+wG9jA;5umV=dey9-|4|ZH_CmgEx{tsmi9*b)48eAZdxy<c*zm;I2
zh;B7KgFuXGQ+A%|@BAic<U1}7CxlumMYwrJp-HBD(dgK<m|V1!fA%#~nTnQhuXac7
z6T1Jy8rU;T2(b|Nq_+|4*N7DFWxjuS3-+X!npg1q9*@DWU^l%X+%NEIBXt#C{mmnp
z_GvHJ_i5`GQAgS-gmk>ZzQ8QX%|CxLl-snIF?uPs%@ORy?z^a%u4%hNJ@#lI?MIoS
z@}1s7;C3OKLEQfuN>Dyf!gnvB?}xs737tRugnWnYpIr+jyM5pX!mn=jrhLcTZU`DL
zkV;qMf$)=GAe1g04A%q}Rd!vs#(A<;Q#{#D0Cg~E#f+?*+oJv#Wwu=~0gd1L0I=ez
zWlg^cfW7m+RCSKaEHp%DdltxsL2{W@=_7$qAK}WA5(pEVMf0KY4q?@o6j;P+&3`SS
znhGfmL*#NUp@9pzE8rtEi=*V~rGM%TVryK`ew6L_cb*G8*T7CS0<w6n;c`xKuo0qz
z4P=z!U}GcPn7mL2B+_5s0G{BuRQ=CfDm$)Qbuu#u&)`CU<?n_R^p{J)V=Lm!HxLdS
zvwU6}cOYyFvxe9)dyr4{d8sW-(HZB|i;rPbL{2ru{pCETBl0M9*cN<R2BLGgkKjCI
z0l*ws1RhTB=<g}Rh)euDbmoVQ&qGZ?#Ha6Gmc9}aJrAAv`52z~A>s2-OOWt+$QpuR
zjrm7d;pg!Ra|yGXhDpVu{Lnir<+H;we}lYttOC=JWXG-Tl<d0fWQl#Fl6XpZINF|)
zZ<C2Aeo`j`*XBWjFw<d4pG~b(<YA?w$iqs98$`<{u!jY1lsn986nWU_DDtYtxrA%j
z2)Tx<TE`L&D;;Mg%ygU?Iz^>ZQxkSN&O@0DmZOy22Fq!n_IuIqfq4jIJT(B;REm!~
z-X-y6nNwl<vhYPbhbuPAoZ3)E-y|%mUbF~r17Z&;Ebj{hm1tF_2$D?56v0r#Hn(Im
z({Nb22a?_N&4mc1Oy+WibPmLi@B=yV7|Miq*}G%{f2F)@N$s-d!yG#xv`!)IH+#NC
zMxrGM>F~p=t_ctUy2V|>K-zTKz>FPnhcOV|YCuc}FC(m9$EjxdjFZjs5vRt-N1T4U
zgMa(SRM#yTL72Lc$&4G;Jx*reGMR7&z>6ImEs=aCXZnycN%%lm$N!F(l0lo9eu??O
zeMU}_;i0ZTgoj^kVXR%<z&b-%Wls8B98mId)_{9l!tH#H?(Qm|!)rMAA<GPW%ybgU
z3{cGUBO1v4F40om;5laF%MAI`m1Jh9Ue1z3yI*ZGFAc9Y9l<?d)=Fq<oZ_i!oJ&C$
z$0+gAc!%0|#I-Rc5!c3C4RLEsNx;;X6<o&TJ-2GNDsi=p7ZZV5xk#GR&2j_aKi~=~
zaid*XCHqe(r=p&nT&Ts1Xq6Ys6(wHmb7^E<>{B4wJTG(QyFeeIs<FA=n5#xYH=(L^
z0dE3|9Tvi@LmlFLa@9z91+CK<gL>csu{lJ~2`+YCLhCfes2%0>%O0ikqL&69<UQ75
zgmF1?_s9&wkxvM7U}c!Lw{OJ!3c+vc>|2sO$R_hh!0;IPtRS%)d{!>j@p<hi?eM3;
zv@ysfOYLU-O78qxFn&c|IJsjFr)HiR&?2`SPbOyN%fEz(84mBB+{4)ja$%@Smcq=y
zluU)$5}~onc%ysx5@Fa3F)=@<%xIEKomBxOa-YhK4$06*844nwEQS$>-&XG2-4A|u
z5ayAke=?{;K4Jqg|1|u&z~c=a<IXN!k6{^En%#)OfCF4+bcGz`GD9cwsXlSjmg>bg
z3Hj$SoOpQj;eF6=F6pz=k1|`&@E+V*Dbafno$W6=8(L(sX^#2Q%+Vd_Qs0`|W#51l
zsW=QkHt6Dy68$Un=mh^tuG%(vWHQv)Jv%ob4X&N+OjXmDYUMV$m1YJ6z&UkeuyOdW
zX2b(1YhtGJf8p2KegBKT*PVAaC8=S$e(Li~SN@VY9hu&_T(LN{d-lW)5FK_8R;uv&
z<(xoeEk*Li`5l+y+qZ&=2ZY9bA1?Y#b?mxIq{!IfT=-$y7+su;zD$TN9tb*^%mbT)
zrq_KSJ7XC1<@x_<dz)QbcUw!W|2@TO`ZjzbiTdpZNEMJYf~s;_K{{2a8z9(j)C~$r
z-ab?07(<%NK5K8UbFU59TU=8T_4A1oHAr?GxJJ=Kbbb|cgy&1pzyZ0~5jGv~H70{$
zhZ(>snG5|_v5ws%84bg2Zu<tu>`Ag9%H^g6e=W{alMrb*PfbFk5xQxTB0}p+LI|x-
z8F7L2)iA;ORQwu@2_~V?*5v|F1m>rWMOc2xgEsMHn-2E|BdO_dhjX*M59r%mOoomY
zDz=RWrQlTtiZ<o_kklxgA1-!dhYV_@@P<B)7MlWZ4Sb?)9CwYypENXsrvQ3L7iHrs
z@&`}}{hYst9|;QC0i5z7DRK_r`R~2~y4Ayz`nakTIR{Mb(iWP$JYEU{0~gcfTfP7~
z-CIA-H!wg(e(U41Q{*9_!yMk#?)ektkK-2vSL<*l!U98wmv@nSTKfX(bZ_)s(~Y(@
zI6_hG(4~NGO-%WIJfG-&eY~X#oeGc(#YfmKf2%^T0{LXoVf#34-4yf;*Mpk1Mz|X&
zT?F%>7scCmN|YCW5d+Fnw%hSfJKU7;l{?JD7<Kt-^jIs>N9l}Eb^D?(Le=f7!4^{s
zmeJ&KN3#W;6X?t5?%^%!aQ^Us<-UM)7eBs&C43daa}lzV4hwQQ+#cgaDQ4&~etaF_
zF&_SqxG=$GK?#NELVo-z=|WzV|Bq?s3xK@O4|$az2Tu1Y_c7>MsTDbka+4Q2ivqPy
z$Mg5!&{>opV38vzPX>t8Djb75qkH#9PGtGcV*6z}%9@&q-G?WOmT?uVM<$$~kee)D
z+QUuw0&@a!8LIt!gs?o-et4lv@nI%rqKg@N6l-5Wd{@bUe0eU@`~95~e$yz>XIg9}
zIZcDDB$sJZ6Lgv8FJhU;VGDA-4zd+;y^f0yIFG-Vw2>3um*8DaPkQ%1$L>xaa!)Vx
z->6c`>!L5cvqX1}N;oH-?Byh1=-*Lg$3$FucfUv3Pb;0#^!TXj@DY<C3uIMD0hAC<
zfHO{q5QP&Ui=5b?Fq{Csq`Iy^2JqW|wBSKn_|c(6v;`f|^chhg1<dDjf-Mv}k+dxK
zpou7IL!n!VB0I#YA@;)qLWEk#7dsJ+B46x8V1;sZ9y3v7-$CSn6U3q*LB<Jm!EJ`4
z4TM&7{5>G~*bP5G(2lGo7`CIZi3lj6vo?MbaXe1PF*SBNX054OyQ7MK$E4J=8-{|N
zsNV?Dp<|UUF|Gc_UoiMd<qs76gp++*Ijp|LP`R2poW^pro4c6&Chk5?ESEyBn<kYS
z2hWKJgCGje#|ax#=$i9JiP_hQiZky7q(P*Gh-1U;f}6P_+r-g%g5NM0Luq<t#BqxN
zIuA)cS<<7CSahqCKX{6NoNzu2*g*aD2haXcay1tpCu|TSI+Uh|Hi!?zA0ovWnR<?a
z)S>1c6vQ#&zHAD0)ZW^iI-jqGNBh()CmhX6#Z|L}$U`Q^jm$KL*zbDfK@f@)1S(|f
z2^>|BCGCnX<pQ}yGiNH^BUCYRMd|692@eMr!siJ}#Q#c~iirLtwYEa7?di;fZ}Fb4
znTVzA=a_5^(&Z(_hm#U}Q5wn&8P>Uw3=c<}1%0c!-V`c=!AWDS4E-j@o}0uaVCc7V
zKr-~33>h_ow8=yfVK^cX+EOLPZR3QWux*7LGiuuzx2uC;fH{QHWsj(c*=ASYu|{@{
zJ65Ucd7#$!AMlS}V$3#ar<D=fWEro<fPFGh(8sKwBat!NbR-@E4+4YJV3$%^8KLcs
z;`80E?nyblhkH*yXJv$P6aGZy(|4>$e=pGoqf~}<qe@Bdw=R`3Vv)E}Q@k?%VXVjF
zq#DgEF&h*a4sb1Tint{O!EH7vJ|!rMS6RK&#Cr-;oJODL{r@7Jd5uozHLs+cRgGTf
zIp7aTbNdnTH1RJjC2mk%I^rQ9GzV*l0WY!h^Yih!J_lN`HHU8OhylaL22l1&j-w<V
z3VSBZXr!xq-@qfC?)|tJM=Ly(rFH^HF!VADQW;qr30K0w6Yi9|SdPH4=Ta_G`J0Bz
znO_n<_Y{?%cM{j{w0uSp6gw@qD-f=iBkpa}tm6l#&3FvdfFg>moyiPB6+{n4ffKm*
zrl?lL46fG>U=-ns_cS_?j&?02DW{r$4x_)9uJObbY6u*Ka6a+i9R$6XvlMOPI<2tE
zpge*C+^zi$WoqLhO@N~xZp!1piWo`eV}n9m9}3@XGlD5iTE8y>w1(VpK1@#jO^NNE
zX)>9d{X=Oq>SspxP&o0M5>uIJ@tZuK52f>H$TSpAF3L?oLml>xNo_MDZqFPlJb~xJ
zY+)x%YL+(z!(=d^NnH|@Cje(L$qDN6;(hC;V3re53`<LssCO^MKFNtm2pGQgreOUN
zRC=Wi$c-+=t7uYT@mNKZN($AGjDQpi-}P12tTQo(Y1R*g`vB&bC9_w;YswOW{wBq@
zn_%f#y3UDGS@L1)=_DvmU{>SAO+aQYsUjBz-);)S)Y2>bAy7vy%*>#R;YC3++XY9N
zAy~q}A3&T(uw0P@-2EYNj#CzY<Db;h+e*<o!e~~wX1es@CC+<aqO52JLhqvRG^KCm
zk|Jfn3+4?aoL=<pTzsqvLNJEqLR_7)`g@7Xg%qmZYK-@yaOMpeDf(N1Q-)wu4&Yw%
z69wxM?$l2p!PT=1lciVqi$a+ObKW}l+l1TnI#*mc;;(bXJrsx_Zj^Ju-K~xgJy|gK
zIQC;w&s~>W;@ou)<*2fl`EhBUfBU1@N#oLZNts8%b5q6|mon-TJ}+G~KJIy`y&#xW
z=U9Omq28n_D;bUMJL_Dm{gQMwf_I2@5TLwSt)p!+LB~ATIug$HCcbv|;x8a;UDwH2
z<#k=@;`7nV5pL(}zGjD8#ah?ZmbK1Jn-s1)k{hOk(w<~^i_jM0DXCJrEE{{`-Rp$q
z>P=iGp55X7i#^2mUyQ~~O;O(5yKjqn*(`3Cm}Bn=R`a<KAnSQLw#nh8V;KzQk6m(r
zdA%LgK!|M0Wh+Zr9z38pGvzW5nlp1um2e+9S);<#x68DzwHAq!E^A?mX5XxZ?x?h6
zaqB+2G*iZakDBX$6I&Alws#Ba6W&mbKgy`qSoY;QW=y8UlBSDnjmZvU6Ejdzs?L}M
zpId;L+YIG~Y-fwV=)qdO%*HWV$vv2#={6RW5iP%4v7haFcFfqZd)hS*F>?}IC~>R!
z1#c4o(t_FED;z^U8of>Zo-t0Z0nvuu0{l_go#fO;tne{oBJp{W48ps_N#};wg~uss
zCq9__H!<XX4JkgDb0Y|Inm5D;!Gs-iFarsnh{R4jR=7hU-y*~2_Bcrm`2@;qp`B!J
zRqe!tNd(|2$-NiP15`A_$F+nRyPu9?#^gPKcdSi8$RoUSZHlR#n4fvE6Z11Kc4Ctd
z{iTNxC+YpKM9b&-&(QLD{)>Sgd_d;upkv<O2v71oz9Ks1?J;swnwp7$t}|cE0JkoF
zNZ|q^VQrT26pt>*T8VeyNIcm1bnLqz%e>H-2K7J!kl{KDdd@iFo={Q^8Ja%t%RW0<
z=7qoeo0zYBumh0`R1Z^lg7!q8dKLEh%K75i=PMj;`P}WZlk>&2?~E)7fOqpvAwTA>
zzhngwquzdi*|~qT_eqw7K(N70IZy(3kJzNDcKnOTveg19;E6BQknfZ%`z;U$-Vpa-
zq?^xn@e`ZifCZ|T4$Q(&g5yC<goNdTA3*AMxxNx;Vfo+(kjOVYUD;5K>HrApZ%y9X
zKlCtV@?j<H!{D-t_pQeX2L}?%TQB}%b?e371UHAj6?;q9oSjAbcvS-GV#hrbF*fb^
zHpUB>U5<-*^s?jK$Q<U!r4Vo(JN|<a0hIplfvN$+2R#6_?6~r^?j^j?pM0|iSL9!H
zc;*Mexz&~65H3g)dYx({)@%?K6<Kt}0tPn@8!@&c0Yb|=K57kbe|B8Z8dSJ^0mUM8
z0r-N#mT$-xq8~gU#r`{xFB~riOE55!bM!+OgQpfiZE<+a!w3d6FJ>nCI)JqJsEE<?
zYmXhTEMV@=4}yPz5E@i1g`z5m+>7uM1nxD3pg_4rrGo{GO|!0!_vFj5>CtZ#<!e)X
z@{ijRp8M=LDFMxBbU<ndTWZGx3D19aT#y=6qvIXqk&*5A1|ds~(F$>XqGvU{7%B}m
zL7XQiIdGnKe1G_c$hamygdnx!tAiIqEBt$KFXbN4Rm4~!bT!!3*{wY1I=X?qwd2C#
z&ws{9gAd>Tg0xsEnvsJFqH^2uN4fIN17iGK$>*7?$d2;~Op2y3jeH)oqBpdT2=NvU
zD0nTj<Di1qLQ_CU!k?`itZ*bAE(gD$O!a~aLzb3<6*la#gB6DG49AqfLx=P%2P%xD
z!$nYG!ysi-0;Jmt|BeCbnD<vnJN_rYjhmu`0$OegBuezThe&!ri1EnogqKKD7*l4<
zGKD(j+oXltNcY5Ab~$%I`pLb6XnI4y*NwHe%RvJYswnmr9~%uG8V!3<z+SvFGEh}e
zVmal-5vdVOQE~bBXhlbOhb+3>IA9^T+&F-8v%;snc#*WrjRQu5GVec2p@(OLmGk)5
zUH)8-9bOpp@<3~vAV`HGwY~Fxe%I=##SK1U^;w9q>#XiGO1NUc!^JM=3>@Y~Cw0eR
zt^m@Jf^U}x-C{zkxqLWqa_fZ<&y?m-s_Cv{m-_~eXgkV$4>pa#u<0#im%j#%SHr;$
zmm`lbm*N2z3Bpb1Iy2PUaRW_?QuiYsEWrsK|G?9ZbVtuHTnz0ve&QN<yg+V>eiN7J
zw;u(^@(vBQJo26x@}tv^cWC^*(fuu>h2#FVx1t?S&@67@Cgz9w@hyoTY{pm&&X1F4
z#zgBTfYezgPZPM|Z9=8{D3Zt{dc41x)~O(fKlo;9cHB2{v63%JcnrRk{g^qvDaahJ
zF!p>>-4w1M4sg4iH4V!w!xPfMnF8qZ9n}<MzaTZ8+2yQ>yUp=wK?*!mKz}-Hn%%yY
z<Y>T0wu+(Sf=Y&t3#xydR#6IOj>Bc;20I>?IE3Z*!aVJETrO)&;9V!!t+XWJ@2r5M
z+m4fFTqTa{4Dwtu!sidZ3<qzQ_b%EwuDRq^-n(Rlvl5i&z1FI4wYnHQ-p&~fA8+U2
zu+h~yCi8fI;&yO+bnpmmcDz4f;<a{sxp5mfjyrI~W~5b6(9m)C1~<pAb%-O**APd?
z$D16{$6E{`#v2{bP1!l<q|O+!pm;mFupue2N2g^&5Cq4^2RV%GxcDH?@uoDCCz_#u
z*Wlr=ccTG~-DJ`mOZ>?FpX?lWf9xk+_Yf1nl-VSr2E6|wW>AK~0SluI9St*m*zp|#
z4#4b$I|(zPDcT8af=bb{DSl|3U?<m4g0l$){jE|=-CfIJCw9D)5VyhXgha`hyb}@y
z_CDpA@emPgh#@C<##6sRlnD>5+}IAMhLI@ZKz}xgp(uE!^9Qj^Cn^dL^b_9%O1UXd
zF9U0se4Y?|!|cR2;Sqk~oA3mmCqM^}@DuWcN4W0IlSeoso<M=NDV<@427TP8CeQCH
zyor}Ebyb`&v`L(tW+${s)jV)A-F##+rXuu;DIF3aADhA;9TiJ*0+%!_{|Q_ILyw&(
zCD5zGN9$2Q8B@9@2AyF<@gIVT*m35X{jEla0r9F5I`CZsgFcZ?ItGoI>l!lwR<mo+
zCtlA2x1746L3118M6K!k{rU0-zAcW28DbAHHhWNfN-nRn2~&x@&Sn(27BH056EFp*
z=<!OMNMW=|T%M_}(WpA+T!%V+JlQ7H>4--kye)OEm{BDvaZ^HnexvxONDsItND(R@
zJwc^@qxb?<Sve-oP^CNDaj#+l<R!OYu&6S1BYu`0zqtjC`HkYi5E$A&NTVr1zz;>{
zdheYas`FLVdBkXo@!Wmo!y&rLheJ`=SA0n;lN-hW%bE*PLdU%r#*tWoJ6r`?+gly>
z!$@L9V>%QLiV@^!(?4#7i1zkQ;h+>ot|?2y58<7V+~EN!7Dg`v3#Vq)6(Imdc03Um
zjP;;IKs#lT_#uRmF=HR`MQ;T5%T0sCBBsQDgaa{$#Sfu@jLwVz=-lO)lyXA$L0_%9
znm7{Zz1+bqr@N`+4k-I-8Z)Q6t8YyAA+VjUd7yIx&@u1ra4HUkOQ4pq0xJ7Uw^iMh
z)=)Z-AA-odQ`j$~{EgVXg%J?|hq<~Lm?-t3i8>Tc)C8^?SeUzOD5Y1|lU=`u(6p+H
zU4UWU2`;si=F&kcUg=PllB)dpV8BmM9+13aSuYpQ$(zD{xapSq0Rna-QmiskZTveH
z*wHCIM<>#2VxNZ)^8mg;LBDL6dB>ihPsDyr>XLz8v)Vlrw2Kp-*b=LEoY&Y%cU;%l
z$A^NuJoA<YN`wt%46B@mFp9XGUj%#W*<fb7I<miE#?%J7;lXiJ{FZWe<m%PcN>wW&
zXpCs3{ic2%5IQ?TtL^i6n%L!-aAgJMiFm_z$6Y@lWoUBQ2-TIF5;mHv8o!4(3dR(h
zo$t{%B~v!TB*0f}t0x>bWY$gi+%Q!AswYxD?_T`m@-`O{oVvXaHNP$I^FvRp*UIF2
zcLvJ)a^|y~i~^tA=V{IHDa2u62nG92;fK!9*}zQRq<+39g#~}7wD;d*7YXKVh_889
z8v0H#zvH*hWwsJue@6bwHwq63#J<ivW)Eem=Y}%+jYB3+%}K?a%uh!hp9ary$e8e;
zL_@gLpA!x5gYOj19S%l35Q4&nIymlFYU-P!;EC`WXG!X;F$qIbZw+NG_GyMgJroWV
z&iy+lz}?R|aU06-o#fB+Su)kVn<S|f6N)%}pC~DRri6S~La|ab4~LT91fn4imno;S
z$JdLZk~v^VIOGaW@teREz!zFfJ@Ydz)HDr0XxG1~BH+U-(jJ-g;AoFZdQhb~;iD;4
zirk@4MZkAcjt&`?RzsjTX)t`Vdm~8K!+?*H30M`fg?t>fjjwb^X|%}H$9!u+Ab*Dv
zuO}zDb!ne8TE5GD`VAW5cIY3_ikVi0%y8j5nK=Zia@Yx76M+{ZD_v8;mG0v1P&gAf
zjBg4X8d^PWqM_AeLqoH}hNxWP059X{|A)jI7dI0iq$ja=;mtg2qaZz~RTew0gQt;>
zo6~7z;^xFgmYRi*Ru(UN+&D{@y+di>j{9b*D}?^LNnG%y-nroG+-id#yr=P!{R9aN
z#S&W*KO*45AMDw6oeuVlW=PopoP<`e3YOUqf0EVF`HBDHL7~H3feAMra3{rFmbnEJ
zZam)-?L~Z&lHJ3s$mW6>w;}@zX55NQEU+Eoh3VLC_@H#`J9s|&kokuh!Q4cIQ^8EV
zbNcL)Wr?}Rj`fKTLt&l56VPqG+AltDB^Vq}s=7+k8)vG@^ro4rx9tu2*e>H7bG97=
z9-m8&jql+D$*~0TIpi1|`S$Tnp~VrwANj6vESGr2IL1vgzWyld9j?l<nwoW3T2G2Q
z868myQ!c0OSR79a95oeLJQ$drEP1pzo`wbu-&%tq<2Us@;~UP&oi}9t#xe}qzPSv1
z!<jk`5OM4nscC^{j>R9cxzn%>`}$@2erQfV_Hq947~0u|Z1H4_?fp0dJVt%a%Q5_O
zLC$*uR*_@*p_PC12oV<Q^Gd;;cpf*feb4&`zX7KpA?L?=FyVK2-dXVVo~Iaoz3-Lq
z9?rKInrq*y@xde}s-6cNOcV|-A0T#TJr6jTC>)tP+vE=&#OKY5$2*?B9+3F%hN-N4
zj#o}P81&9F8)X~b;-VqG&@(4<QSY1zzUZ8E%Q#K#B&n-K{BYz&{9uPvKHQ%y&DU?B
zBvd}#-_^)8=Zo(?ouzfZZpx5jif~9xThF9a@Xt#sFD0hHiMUqb)%F1;wwh9`)#@dz
zKg<$(9>xvZ30VCKK$o3l%yBB8RLoV6;vA6P=egMDeI9BDf_0n+Z{|YQo48e;(p5v|
zvryGJgD7GlDx%!b3iks{B8r=7aN9cgfXC>PWipf0{&4^X%p}c3ok0m+l!Li*rcM&(
zE~EtxgUZ94IhT2q>yAW^s{`1u?O(+ZrO3qnaX=pyF@z2-#3~=_4JGiU8wS0iOxcui
zRTr$qA~usL467l$lT(7LD3EQw(4U;ilSmmb&eQ#_gGXK|_;hd*Y{$Z-Nx&YXw~|80
z8hn#XQQ(=l{osWRuqKY5Z}S<eumpVKrlA*+P)$rkFW?h%)gNpW6W&wV3`z+w7f-@)
zwGn#D=xQT$m(j6C2r#1?4N+o`lL$z2W*Q&W`EF;8Fe~YYaL5)u&BA5o`9NM$kb*r-
zZsV(aLMhOD$|y{~mvT}H)A2>{I|HH*JE;*COC6~Z1}hCGqKXAT4?BZiC8w5MC_+OJ
zF;jeKgDZ$aNE^L8iWCrfc_0w=E)$%{UI9&=QkNUCsnR62M~6_9M%N6&Fby%p4pehf
zfcR{x6G&9ab2?cRiE}zxDA>0(WLM<1bdv(_iBE+t6^>3dx>G2=_@)G_T^e^IgjG`6
z1DP^!YLsJ+Ab{yPq4?+45S7;yB;6X}s*=f#SX5?-g>!^LxEq}#O6RMd(L16jUu(k&
ztMKuLz_G>%^M+`%Fk86LKuB6sRC?R~4~lGWbZ;mWlyq-UT>VXH0dr2O6WvgJwfS+-
z)`k$j2a#=bQYgf%Sp*I?B_A+^7dzN*L-^r?4>!6c07L!+DW*VXOZp{94#_P6atI;F
z?q4h-xg}TND<Bh?+zDjNlCuB>3w;F?yW0>p+HH6k6ZBz$`mHA!{k(*!lT7GH5fIJ<
zUi1cJ`0&tUG(e&ZuZFHB=+;2hQqBeW>N(bwM?T_{9e)YyIEN9%VNX9Imf6WX-^0{!
zlFB1!*>UGE`7tE=xf>iAbbMcxZ~}B3&L^onqLZ64=@_G*S!9u?>%++sPuB;g^D%lp
zoRsjLj*II|7WD9w6~5C|QAhSg;cUe#O=NEGayQgnvxmE(E|wiC_({Ot>0GFU>u`s-
z(yP-Q;$%~&KZG(}S-0c8WC*urC)s*8I&-mD!l{ZY3QO@xVBYCNsAE1HA0idl0|LFb
z$h#f)Ej0u8EwXM{o=#^q>vSsYTrrcc8vCYSp-yGGN6=yI3DR165Q-leI%D_rE7WbK
z)2$GPa5O|OJZ>s_7Aog7eJhwjI^w<YMJovKQ{$=IVaquQk9*S_nU}C^x_BTQoJB6o
z2c!~CkDMAvy_43rH@ZcFc{&yHxv|sYee#HQIu%xwVv+3PB=#V$2lU~{=bfnccwLNt
zV=TG|&|4$x9pw5AS4TdFI;7#&kqw1dJ)O{qO1CM49f!j#{7(&;HryE&Wjel^+K91J
zweRpblv%vX=dfISy}S3?_9n^F&^vt&&k>EAPR@t7xa!E)*ywVS&zTL2ynL3e(-Sc>
zXrFm-yyN-om3&stk<DN5^QQBnEV7-3{hYLs=)5Q;9L_EI9NF|{l*Wzdd(S2%wG%G!
zvX*wnm{=D>{0$kJ;kEvtLIe~z=QATvP=Tf^O*+RjLr^T1d=ceiZ}hB5v;~G^jr{bj
zGvEX?YD5I|UvLc>ZsMHa3^y^gh?9W?xQ2`^G0z%8Wl2M;$Z!)f;PohRL&3nOPzctM
z7v{uEFy!iS^g_y?s^!yAokBqbr65?uQadr1vUqidvN)$SgIV;8A;;pJs1w#BzD2*-
zVKj@ZX2$2AFi-`7Azg7PP-0*Xtn79vVhjx%j87r`cqB$N!SOv9o<f$T0i$H%@jViw
zd*BG54^ld5;RmBr)YCO%nw+j1z%eK}Yf6?Lffpm9i8^LLlhZQ-nxN$KB`5=3n3Cxd
zI~cjb4r4Ka(vSxOSLjuIL>rtC!d4U*#t_``1dlN~Ln*k74F<oExhCAB9%Rl2B{r9o
z=!<f?XZ##Y3j<^nJsZ$(N>O(#9IcX$W%^MmcF(57{>uUw493jJXC^S=1kYNeI3wOG
z2r=oTJWg_!Sp#8`E@l`iiOiHJVKSoxZ!V)ZSJLT=7?_S`V*?7Lgim=OG~ilimm<{P
z(t8%uz%8A}7e%}w+||*V2ZC2BrqrgiE9#UX;O2=;Wz0#ZMiJUhhw>=z(XWho?G$Ir
z!sE=rhZ<yryPC2UGdCV1dffzWR)k1ZzY)+($L+A^iY)djDvTKy=uoOAl8tah>;w6|
zpSLP9Tig^(8pE9FWMwA6)dTiy@Rd6O;%*AYYwtnjHX)W>=7zy^An!kF<@1l$6x#Nk
za;C<2se^VKf7AljEB>M^?qXv|86JplyaFVmVm-^Dz=&sBNIAVS3L@W?FOs@O7{oK?
z*gf^FWLL)skZ0F`W9!(}GbvRQ7kl9o<@q=vEo~>3Tmtb7B<)@HRuU+Oi7A(`G#7=N
z5|OVJfAgmBFh#s<MD0XFzFl;@s+`qsY@c(u9tw9xMS#$C&Q}EZURg7R7~o4lii@Jo
zU2mY5z#(l{0{*0Z(1+nJXZ0H!ES+x;q`9v7^i4L`H3Cw)*2Fj2T>SPBdvC6*Z&FV0
zdyh@MUz0Gejv~_XoL5i2^XAkL{luE{>WGxnQN+fbG`oo+MbbOg%^oE#213;<G%P3)
zEtYeS0QVkE_LR=?gpl|OQF~J)oEeVyoGgcOs(IAfb}<t%XxsUoNvc;n5fAqq6^C*f
z^6fL@6nNe!S;L56z^C0PpEhFu@bPNES(N^BL5kgSzDH07rR{(E_zzG1*#G^P|MMdU
z4x!Nj6wl8{_Wdva_2ZwPt#_su2cQ4{Rr`PZ%kwI~{`=?okzJ5{wEcmUS9|&6FMoah
zhkyQa`g3}9^_PEs{`Wuq<)3mLfBKjI{$Ky;|M<)Q{QOUUdA1td<}9x^dtN>5#%q85
zXMFs}fB*5{UiEh4@xTA&uTKVCw(b4%@z;-xTU(T4WWUI5<eK<`+duuU|M~y^r@#DP
z!R16#FZtSD{k=ZvG-ln_ioeGu@?(lkgwgs2m;NgKC71u(|MKs|W!+O*_Y~SHxxfA~
z(rZ@p-(`|fs>mdPBsZ6TTgeUFs^UpJe^R0QPbw;S2}kHZFb{RVOntq#{@p*d_NV{;
z<HyII5pA!<?UnmpvDZIZ&3W{{KPAg=ejHvc_ip=|-@n^j9OVs3k@oPtc_m5u2PR+}
zkH>2_yf)Pixc2w=!k??Q!avR>pd@=E_*v3~E&2Nki)x7ZbE+u_(3jPc&-AI4U@iZu
zQVrEol`2)uFDuQ0p8Wq&{N~)(mlzo1@6Ww`f9`9TJI=tEso~3kAr9NA)u;}CSq%uE
zQ%!i>FRK9!d#WkB@R!vPkWSOD0CnG+|NX@9JA1$Uf%(U6{0vUl^REVHaQ9U;5`Iz*
z3f-wTc%k^R8gliVYD(VoWi?<?xB@JHa|Ikt@jG8Y{{9LO(0T@^m?mEi4iA2(nqC0E
ztcD=4r<$U|epQV=uc}7EPpZwZg>VH}{>RjnSDifaoUZ+)zrO+>>H90djNoT*oyzo=
zgKNgYp<1(RbiZ2-;NeqEXyPxc1$g1AR{F2>=5H^Wf4szeZ}#_l+uuKdKK{V|e>;(X
zej4X}W4S8K_Jsz9D&yL?yYQ2r0~v9uG`=r<Sq(Tu&Na*5ob9}0h5yc8{{!cJ1~Bam
zPDr&c2M1@mQ!S5cbiZ3I)la>p`U}0SFp#U(;#=BRl}6m6IsJo|>Tk{d>zt~;v(^8A
zvV+%ljY}EPzSb8xF6xWdz<yt1y83<zOkB^uKAHS>e;rJ)eSEoA?8s+*UETcSTfY1@
ze`m-45$*omK}aZ<^6;y-(S1vQvH6<+jav8}HQ+mJA~yeFQ-u7La*C*-r<w>~RvTeS
zKGj6{vKoS=oN6L`SuLly5uJL6@{L8<ZyP^fgztQy`#4K)13Z+kM`-E3*uLtK@O3pu
zzF)Oa{<>12`mS0ed|hqa+ayZgnEbqf13#br@5rVt#NQ{8gs%sN^eI<8QNFBL0DCzV
z59RBM@a?=Rit=?u_{UroMft{BlpP!H=WFpDt&E9^FHS}IdWb-UTopz6x*}q&T@^+7
zx+22TTopz6vLc}@muL{>Te9J$gHCI!ezh9kyP*IwdmGa1SI&6`3%n|d@^wXc5nL5T
z`MM(TeOE<MzOFdtr?dA^zOx$p^~`>{8sECH;I-}IRFp4=SX28XKM&>Wih#gg6-D{F
zqS;-^OJ7%roK9CA627qp+pxBNz6Rfs71aUR7n>-5J-B#Ly=sy0b+vh)5mEZGLWA+_
zR63NeD<U(+RZ*00%zxWJ$DhytcQmDj2-+8?qI^9>cr#uVMftiS{4lPHqI_Kukg%(w
zC|_5^yW~|-l<%y@j)3~})%XK<99_cRuRK3KK9A&QxBO4<H6nb|WSaB8&5KRWpPy_*
z`Pm4Iy}dV(@Uv>49&JeYnfc?>vkeJ9tM>kI!}50*A^qDt-Q<KQ_1EzF`cl%f;^+4p
zQGRMpDxZ7&r6-)1!Zbhk_)CvCIl*J#tc6?%zPT9NGvr_K?j%N$yY?Dk%D?covOd4$
ztY3P`S)X5W)-S!}te)SWA4vE~HDp$lnW+*7_^m})TciD*Q|S*_ve)OA91?yqxX&*+
z>z7_~79iu7m2~{VgTMrAPSvJxbYE8c^pZ3G*h|j*w|U8#pI>t3FTLc<W>=MFKl`~y
z>Npi5wDi|iO1~<27MU-9{`P7!|H!M&{I_|v8Ed{j2$1j-BR!&TpK7!H!h^s7T>DfT
z`B!@T{E{<%=_O~>N;`c#CDeM^>Hpys82csXcUIsJocIGlrq19j|H8|_fal?<CRfBS
ztHDd+RFm7pSJnDT?++0q{G=LELU09G{^knwt$_b4-hs#^l1rVzb^DdUA+zeK*3vIL
zwDiv^Z~rBYw|_<{^<P3Mb-0IV1>`RFy%pGRJHPV{{Gofm=f|BF<?DxxxBy-i59J$I
zyU}U+%lTi~^p{I`&R(ouq@P;+?`l!}md*e5k@t9<`*M80edi!6aCyF1y+}VXHrwY7
zaFM=aQQx5^ercrN+O8?^>i2#<q@UPh<GyiMJ*4m0M|a4c{3|2v-!adnaAmvLy-2@e
zfxK&q@*NxG4#M_J<DB0aXCy9o<Mxogwk{!!%T@IveaF7EBUahZPoeLqdo&>3%pTI$
zJNIuS$)`j6$H(8a{ww45G5>jwe!F4ESm!Li)mZG$!~XyFsIRx0{@a>mX4@~k^Fn$2
z>HpRAd<D$k*5?1`cjd}NN+lO7doyf;n{JTdXqV%fJVOzhBW@2fev7~pGw_Xb(4G=m
zjGPeHF61zpgU)-%VKfKbTxJAj-30U)uWFm%JqBQ47eo7)?te4~9bAyUXpTuY9;7dt
zgW#WOV2eI?$S^bqQH7CDXb$Qs)4~^WQ@~cZT5Up$V)lt*fS(z!NSjdbgJ=-$+sGX>
z2c27xI%p1h&CTWobk{Jo0USeqpg9!k4mXlH;4g>tKy%RhI3B0xAiisM41gApiC7AA
z&^ZoieCA-#H#qprLASO!V)A(zhf~lTiYgArp*di%oFmwv127Ww%t8O(Il&i0Hq1%B
z=raTNra9>S>;6x3Ft8dNq~?HY8hof`__{tpiII5+3!|dbZ{*>bgP3B#M&{sEWg^(u
z9CYtRBAhuG3jsN9=3vqwq`27xRavM4uHd`&qC{ac(Fsn1^V=o_SMZOUosnL{h3;_*
z`iv3HPWRdsg*dENoZ2r!6nsZ@#t&PFPBS~)YT+<AJ0qHgPvI`3w?HGj2vG=jaZh_b
zV6mAUfx%t}|LhDhfXp(pGm9HC%WOg%9mp)RZ6k0?UdMcb27@1l>RNFD-UKihu4|is
zUK_SnXS^3=m6@F|RZl82JL3f4seX2Z3V@I6E+f7J{9tE~FBOimyBG%p62)u+y6nL=
zA^<Q4%qGN#8P32?Xi<!xgTVog2+Kq6mKlL_o}dIv49p0R=Gi0oN_afaPUKuTMLPj3
z&Tw0somgRHZJC{)Et0luLYx(Afoq0TTnpO+0TkE5RMW|H`-yuIoh}TF4y73hR%U0g
zlT86*a0Jahaz-u5@U5SnQA;u$@@Eg1rVN+;88NgTkYZmYwHYgv#7Nk2W}}B*P7q5C
z7tY5?dsf?0*N{w&$mxuL2AhJO;?SFIsVjSpu1)n5p1+&IAwrlnz6@-N@B22@NDW!|
zBB8h$8)Bn^4WdssCHNR*EGi&SK~4}yZNwkJ0`Z!g;<MVin1VcNUA;!)=S^X+4UF^q
z%qhOh7X>BXF|Dbe?jvaoTagi4WRuuU$nZ_6m_rDuR@KY^bM-V7a;h=)=_X9nVmpvj
zt%}_Vc9j_=Bc{uXgdgliO&vp0HALCigy7cH?+h34*-RZnU^P?6A+Z|$!ZVOTVHVyc
zKYE)|Gi*|<d122BOHM!3oRgQ(DFXJ)##p7B;)>st`oBrd%W+C%L<^dYk?Arb3T;aC
zn?ueuC3@SG;GK&4rUd_44QH^Q)G%aSOYn5hIZ7N2q+P>@k8C(oW~@z#O`Fs&qC#yF
zI}V{&m--D~`%S@s;*6YCAAWY-XA|0kva?#J8mUpj#6lR>sTLp&>jd)=M|hXX7ld7<
zlA94HY*W~7h@2^pqD_e<tOE_ZxT`~R0(n=5<^&S2QdfT6-d?57;Ipq{Ok?e6GUV|t
zv(b=v6{>Oe#5uFJ-&pbpAG6Y_JHx)RDX0+=t5yvSBCA#nExcnl1<^+`;_A&>)$qiu
zRW=N%r7T4mIdCRY4n0BgZ(6y4Hl=wPr(F)gFqyF>BOc+b)O$Cj_!9aTT6Uj>KZev&
znvIMcHM16!Vuq=(ZVKj%I%`Jo$Eg&Bo3c<1!!M9pO7XZUJJilpE{RQvndRSOR+GAh
z3{&!kjBuE<Ce3^?FXAXExNdpwgp81zQ<)HQq?VaVbC3(KU&?Bb5l3_?D?mn0m}v{8
zc;=dF6*A2j5I65Fr1<<9u}!C<?{A9Fx<c)5igT_o`kN9*gt6$X^L1hqe1|b$eue|o
zRDgWiM`uK{e?W@S4fX7jPDze4vb;=1rO&|hPG(?!G9uw_3cDH@QP&s;Mx?JZ0{2dZ
zZ_kmgWe>4wR1kd(&z=z=cq;Yvro<5NS$mA(X^qB$O^6Xt5#AKvvI@1H5#M+!w0bU(
zeGw)735qYIzI-HbnFxuV5qWtk0D4BQmZ@mxIdZi;PD0=I5`RXedIRKRfV>NDO7Lc?
zf%{vev422v=89@TxGB>3rUZNOUYZfKdnyF@lMTg~S%V}qz9weG51)$gosmFgT2?od
zWeED6@l2}#-#OTJN}NN8s6H*L>yTtI^aqrfN{Cg1Y*QTWj7aoTF|)Itm+^r=PTI^U
zNOs1G&$84G<QW5CX9V@13WB{U`$$y`?2Oz1Q?Qwg6a!O1u(Ne9v6qM{w<!@GB_sX8
zrf?P@;R<WSXoh+X`BsKH9k^!}>eEPWu?hH~4R^94bvW{QI05qpAy*XEF5~!$$9aSX
znF<D-k?LfYCRQNe6zn-i_Ugw;I24fPW8we|N;FJvaXG_iVrgfo4D+6m`eqg;FUZKI
zGmBK}$m=l`BsxQe?3fr)if^(=&erUuICCJiW|3m-`FW?F3NsQmZ3-t0Nj6?2l!8kJ
zOv*@PH5tJ<hg9BWa$Vx4I2ErsBb&yiuxCg`#ca+<lrf8x<Co;0%n0X2>^y45NC3A9
z>>7fzWc3W;iI~k#kbDzJdqy(Fsd&se)SXR0PZb+W+A_7KO^Tny@5wr3WtJL@)D)9Z
zlsCb7jVQ_wNP!bsY%_o&42zVJg<|F<-XSeBEyzzsDvFt<Jwvmcildxe_uOS1en>m9
zDGg<}jm$jNH^ircCTC=t*c1*M;!|#<xx&gk6|guX&%?}8kX>t^xr;kUK7}jJ(ET?h
z4xI|YmnD`f1Yf4sTtn{Vu5KXrPGI6(A^LJt-w=JdsqckJhoHt?XDTvrjtkM_q{83C
zjMKWD{aQ6Mt;@R{W0Z>CaP!OOlHDNsvZ)&Gby=UhcSHL!Uz(=E1n0PqK28F2kbQ~?
zoN=d}9u#<&f{}9iz-*Vp8f0HC>N;d!F6tR3PKE)_NT)Cv2l#PPjHloSeg-J&Z*J8~
zI3i(5m{}TnSR0-oVIFadQ`p^2iPeyX4fDrT+}%tY$yDIo3^U4$;-!}uOj5y-o?s^F
z;4sQKB`lp8=?FH7{X!O|rG7&eD#mU`?tz)20s<Y*B$?gfOPY+ay9qwLBvrlng;4=?
zciGo3#W@4R*G$sF!{u-$D&as>%_Jo}G6YOTy>-9EU{qgrgX|P!aZ`fVuAU$|Q)gFx
z>)&Pe1kstKgTrVzlRkDB7H6VeI(G!1-6V7#_Q|Ojwi$T<Cga#<g#DjMS~+6;Z%Q0A
z9S?enW1D+aV80n7luqtp`6mO`?qXa$6|puWqW(n8+8j~uXOe2&ai>gDuRA1YlF>RN
z()}i}U5L<RXxIGT<Qwu+(PlR#j)o)^9Z~A1!p&v?Fs8!I<_JN*3G6r6d^RaMuGnBj
zorgqC689Y<HA!tpZ1$P5u0ROIJ`*+WcvhH625dY$YzmoyL`;d{XER<eW|Gd0xaTv`
zgzZtzcahA5=oyOWni;ZuD5Pud!%H{-5Jr3~>faFn+zD*ezb}9)A5b>`W9joo`0Jsl
zs++Pq9AMp>A4}Hhjzk<|$voXdtc^u=IwC;tGENzUdwx-N3GtlAQbM+jXw931@gX|%
zrl4n!ygU>!H6yO_SjwZ85d--}@*l)SX)Gz=5xRIN@M*>y;!xbvJdlB7lW-s)-tJgZ
zo;^(NSW=x4^LDIy)tRV6Ln_`>$6~<3jAz&3flG6|$qvOW&4|;wDe-X+BX6=t4<cu!
zbw{*Qr{K^Z)l2L&y5AJM$Y;dn9E)1^AV61YcErCN3QD>Ov83h9e#5%zvqOZ)O~DtB
z$c|&l1dXVSn*u}0Xc&R?>e0P~uX}WiKsxp4SRq-YM-NFo6!&A3Vo=nxM~^W{%^n?N
zf|fl729$J00HiP!s5ApsI+oP&vE|`Vl+s=H-7%L&7#7r_D5V)_h%upzk1%Ns1u5N>
zKtD^-9$`8g3QC#*<QR%cnt}Bgh)J3qDKe&XXh2CuL>qlT3g%>~M(E2;L9;WCu7S{g
zyS(@Aq^0`F0JCfoCJJblp}3?Oc$P64ralAEvMCdSe`bt8>iLXy-;{>3p%RV;z*06a
zoOOyD5QbuvW*}3Bf|X_<Q#K{ev1zY@H0EholA|#Ly0S@ZHNL~4$fcVS>sHk&=C=}k
zk`c3XD0XSaA2$W3LDb&_974f|Q%Y<r1W?@+&al^rfB9yg)Q)GvR*_X35R@0?L2>_H
z_UhTuowVWE(VdjxIlROMN8Ix_I4X)USu$2n$gnA6^@I?c(xwBUvI(@tB6#kLgpx1*
zkh1JseV5rLMBI?I+7Ttsrl90p2nDq%;W0p+H@@64=GB7F-k4$w-~T3IHgHCaA@elC
z9gm^!&ySih1k1=ks%%p94W!B@pmRV~HU;M+pema}eK`OtL!hdRkj`UJ6$Tt-4C%rv
zN^BJPoFNodMg;0jVXH0)hqT}YNjRhiFG#}CXy{)MghP7pf*=H*YL}gPX~Dp+j6qHK
z$pEm7Ays(MuS4c($kH*W9={~*5X35nBz~NPKgSjwvQ0yxk0IOiqC1K7=RmrQVKN>8
z>oNq@%Bx|7QlFuOj3I3pdde8bVEs~L#*iw!AozxKVdy?%Kowq)aYG{5@hneJFxilD
za(~Hyw2UExHR9ioA%pcAAp^&N!P<c@Lm;dS<jWY;o)L(D4B4x_*QAHLHNm{J=`}Ii
z`uqV?8C_~HfGPvXt0zd!38#{?(q*lN7Cjglv_SVBo!07-;stOBa#f(fk4|%SftEiy
z&DEQ-*S^zYy$OCh*(7uY0oJKvZ%Pbmq7(xf>Nxv&2IWiv!e#WqHX+~y&?>;HjNZkG
zMJWZNFuIQ3RRz+kca(hYdlMUmX>1xlL|1QoOWdS|Y84X+(bb#!4$;+{dajt+hEk}t
zy{c=-Ho~w9ATXm-=Ps#viJdlZU-ynExMB~%unO+(qno(uV8X;!$MPDp=WS9jQm%%A
zlS0;p7sytu$mm6^jkp4A61#@r6S}Iv^f5X$<r3DB(X%=p+*z4DPwcF$-XR-%R_~CH
zLTMF8y^OFVJRrmpCbqjUhNN~Ewn}KmB|O)6k=!CZ$!Ju23ld0;2DNt+oH=2zN`^da
zq4gFAtc)fIa{*#yG@76b5G$k61YM9fYqY7JAr1qU^?<auV4Lb1H@`N~btpQc(F9#!
z2;3CNoB~VXCb9E^LDB}jDZ%nkLy&-kZxy$V?zy6tTVOyPt&2a1x7L4So!~~_H;l5w
zQ<cUbtCw)f0Jkz)6KfD}t*Kv#x7O5e4TItkW~;zxJX%xN6;s|gB8a!v)O(8wuasp4
z7VOcgddJnT@nT(&`)@Q8&m9~ZjRhqDE2EhhghXp51|iX!kwFMF7?NL_)+WW~GyGt;
zNh9<w$9xy@26@(s`kh_^Qn4Uk<0hd~2sk0K3i3n_^noi~%jy+Zx|Y=|E^sYtY!Hc!
zYWJqZ0;Q{#Px}z!s+72*$w{Ihx96sSJ3KhOC@8t(>e9sH$!ZW>Rgh+M6W9wxTcr`Y
z;4N$*%k>kaXqf$mmN8VpM<YB|0aRwx$$pVDYE#&;Px>aXU)<*ER5!7dLolrpFOjb!
zRj~jH0#<Gc8#3p1Xx<<e1;W~t;8=Nr3Nqr3+BFD>#o9TDkczddYe>b~nRK-PMKgrf
zDtN&iwX1iC#@aQk-E33G4U)e$_8gLV)TXW>K7slw1@f~t^&9uc+9WoBrP(C*+cCtd
zzI%+3VjR!ugTS!INioEVu804dO+uVj337mDoRavPu=P|b*P9gl8ygMoO~ZjDw3?<7
z!Za{p4@j|@X`U{C(QFDkcWGLSdd6+D7W51mv<d7xnv64|ge0x`Hx`30eeOtpzA42a
zHpRgmqtYt9%h4tE=z{F+qf(D9fX8e~wEGm`NJfQKx&+c>RGOs=&@sbkmM%cY3|s0P
zZVp5EuuYn%#@<8E*%Wkzi=-{}<rhhlt-1h`GXxnc1|exuqzyvSV$?73XG4ARa%V$R
z3HfIf!~nw#0l5lrOD_saK943#^(Og5TGwzP`>d<$kbNdmZ4i9`uRK8thx?8n_&01)
zzF+iVQoMnK83J@|N+?_=r5WI}Vf@+*LeHc$V=jhCamIu_!-$*Sq>gHw6^K5oUfK=l
zdj$AyQ+BV9Q(~G;-9qe{sauFXlR6$~nN0w!y#OvV1nDXU(Pz}X0gV|Z{oA22!=!y1
z01v~YePi<uLAnaI{4gooHDL_YwQI=6XDHV7COOB_tSjWBWi<=|X*5h1BnTRoXf4>J
z7zFiiKMZyeV*+qy0M%81n%QOcoFVTmscT#jO*(p<IipBJuP}iY%5xxRHUTJ+0_e;r
zP|*RL*=6<}%QK2}bR4RilHyUU;N%@bhZR4XN1^Sy;P4(rDmqU1QJ|s+3ixpXdkPsU
zFjxV0W)$h;6(Y0@^%NrX*(7!a8CnLqYW{DIFfOixc(DR_%?L>61Cnp?($z6!Xpxp5
z0(cZD`88DYQ9{XoN`(X!>}*qlGim5`cnN0>U@@D*8oX~7YUeeiUy<TnA^ijgE6|BX
zscIO)FSL>eq*%nthF$oTs@b2|EK=X=1pBmOzs49pV8^h&GK5-zE;)*+)ew=65i5>t
z8Kv;f17ypl;IIO+<wfyQ2(>~xc7Y;2gxcDaxbhTf)Zq^?N>-zgX(j%QTVJ6mdsAYz
zl8iPDGEOkAO=(_c$1sEz*SB#s8F{Hu+!Kl7Dy{B9{417Suq%(SySvL%Ki<7%X~?bO
zBvi8cf~(lbQv-*1Q||eKE8P(8s>H4DIYD0vZibtJzHzh5(yI}iZ7AD(0pMli!6(wv
zx)<?r1JE*<SiS(yGO|?Wz_X0p)hNZHpjxFtEGmn9iHrD968QpGtC6KNH;TnfrMW>W
zDu?{0!~mc)w`hUgLN4Z`F*gWC<%};tz6|Az-;@}mKGwj(45W;Ig5sMoLuH07WGH8R
zfxTo?IA%!7Ox5}+Zgm+#dldj*MwS}glb2fj8_Y{%?y-@dA!t_#6Vk|1k2^$SmV(?N
z5)qK90Mardq5A_;@Jc1wK`ukt+e?Q)RQC1)kjtjv;c$~;D`#~Lk(i-u2NGro-&KHw
z89B4#0@Gy9>Kg)4>DmiygG1@r3k--u>Dfy-Z$3`KLDX?YR8*V-Aj=TUs|1i`Bx%wB
zvOGhX)Hlh$HD*#TFr$tnS=*bJaIC-%yD2=YV5{9Eb_98rWZCW^fi?yGgc)g^Ea;mQ
zV~QG(X3BuRDL$T|0pj+Tq@?$b3x&X6g;*CQCNBiL2(?uJc2U;x!bJ8%naK;%)(_7*
zUOJ>%l9mm#{t!T`!1O=Dy!?PPQH?#t57-Her>UV76Dut}+`%6w4gQAVvDj@$JS93Q
z#K(BX@Iq`%(u-3e)+Nc94QKcvv{gZR?U7{5M)K@U3HOZ>d9gPEtRU_6rjQp1za)hk
zuT6t^tH(*fqU_m$nMu;HiJ3{%unCz-vS#xkY$%g=A!H^==>}{jN#`acCQ+RxA|@qb
zCCi4yBxuuk+S_F|>5@}9xC>qk`;z9&?5|z$tb$MueaX6wU=Mvkb&g;VeMxf$7^bf!
z5dkzzUovlxhM;Hqnt_km6!zV{#D3wBut^Psy;8f(p5wdO6wX>lur;aD@lf2CkRh8A
zLzF6w3^{#CR~`ccpsqajpQQrFTlnK7vOB>YEZy;@?qwVacz5p%d|TpSzAt5`EqJ`|
z%6naaeCf)2T@VPRFR9WIEX65&&vJlFSKjLafJ|rR>jI!bUov&i^ePc*z0;Fngp%Mh
zVT4k*0cz<>!WW>HF8J4`G%u62nZb(8+%u$IUsRrF#tKOy0}9hUC3OJ|rZ3sK0fX5T
z@>Ve0vU5l1;7wq^ae_R3=?s_#{tHSmv9fGW^U=tzJq?4&XMBdy=xYbAW(WLZwW<(+
zI3#BC64_{+eOa{;o#jPA=~ZD$#|A{G6P&dP&czh6nkkR_lu<kKB0Gg0``+9Hb{pIG
zMM24j*#+M!0Mu*>dXB5!CU9)SOYAfRVxN=#GX)5mE<jhozxtG(?Wv`mKvpL>3r+h8
zQbVoNPH-m!_MBjk>iCR5lh=irpOVR#olU{%fEnylx;U^leM%XRm3aD;G7hv&pVY;H
zwdullF>!cDDmNw;-(_l*4z<|?^bBB4pVGYntm(phdH!<W9mih1G6n_ZJ8+AA%47{_
zV;7jK0RGsgOx6LBe4NA)6mSfE+mSVW%3=*<O`p=gfvoBCSgZl9=~EVKoCKS~zAg5H
zG;*9Ln-W$CKx;OEog?le;bWUHQ3nUjs?IM|>xIi^7hJ61Jlqtt5%O?KZN{m)DP#@e
zaLReP05{WTQp1pklZNcoy+Fo7|LaQNT>>@pIEh_DAPP2C0HxU!9D|Tzo5G&qXTM44
zI>3#a!0ufT_95{N;Pj^83_=MOjWxlquHXR5yeKFkoGJN&>{GhB657KPBn%M3Z^+aQ
zJ>*3}$!B_WaTQasDZC~u$iAUO@hN#JKKNG&v)ECJ8KhC$TqS#)60>Z8%XDGE3=zls
zP&W7kDMu8SMJ$(HhT*`Vo%W$*@X%mi6qJ0<Xtg%zz?*_LjZ<dg1R`yi#s{%BXtg$X
ze%NJp3$ZqYt~MZK`Y7zGVvi`td;nxNfgM%s5uvLsK^6+yWocK*Y_x&dtVSD{jZe}u
z484xkLCtv+g4cXn#7xs%y(z(b(##=f+9sjv5PgDi8IU!7q~G|1U_Gg8$i9)N`5JIF
zeI)h$l74-u-`KcaNH7D6W>Xr<F0nU({rIi0E2V$|M6)UEB^2H+B$&kow|AjO442^E
zr-lfD*(dsjaO_h(tteqJC>{GyH;|5fXh0zyb6Q3FDa7L@p}2!trX@#J3*=4EVm$!7
zaSHYVpf^s!76bOiN&Ji)f8!K%4+DmiFkd-ro-dNNM9$<pou)Dw=ZnN91@l_roWZ-m
z@&-VSlL9YlVHpY%nJ><$(D4TQl9Sk7NIWO;Tg)LBU$m(XLqIwS^XCH637o!=kWK<m
zAtIeZ7A%H0wFO{ndy$5Et5}FY*FT_vsiBE!WQxxT7JwS3V7mZN<0L%S7$7xHYaqmO
zN#(NKQN-XvK6;7|c&Zw3I8I}4J*J#0m%(4wNezU_N<Jsi5XOf4lfe<!Ddb>aXjOv^
z1Cf(jG&DF4BI^yN?H9?!)5IDO8)Pt$I|=U?22739z|`Whn3!6e-6F0QC%2r%TjZ1%
zD1!mtN#LTSD1!5nIOPS8`kRCqr$%LXD0q=*=45_uCqX&}Ovfn@(*_WZ(_(x8;W!1K
zHb6BmQWBSiY$^Pj!HGU-i9f5X$;Jx#N+>!{xGO(Figl2NwX@L0GDyYp#B|R2(5DVS
zj+1z}I3&j@?BB2#2kXR6l#XS1l5!HlTo@j%f`&P-u@%Qu{}l^7CW^7RgGSBAO5;HA
z{;?@7%AB)C28VcVWOAVBy5y_OE0+OK<0LfP!Cx209sBgCVFi~>r;&lqVRSLjITYT#
ztc+c3>K`5)P6Go2`{8J82wLMLaxkzTMiT=#@SKK|2w^{7q^g>eeDX2F3X0@$i7Bab
zWsxiDbA_^0i2F?fQ*p(z5+cS4>WkZy*DN!NQz7-uC{71Wsb=sI3tHmOS`fg2B@QmG
zTAP3+;8n{kN0EAwWqg#QsQb*(>R>R6&7;f#-Vmg?ADV^S97!xvZXWH;C^xCT8HMJM
zADkJb=D?-P3{rFO;$=X4ct$6(iTLU%v^X~9hecoFz_19^?2Lj`h<-B)(!OwUGDH-L
z3{qgB`go6S2SksP*c-)fpS)xmkT)-ylry6s?R>m2>ruqvWfY`+==ek+C#PYaLXP$!
z9w|rrKoJ~v9WX{I+PnIu7*%!}Gl)^S02tstPJ)~P-p5He2aLkj9RbWJY2^uEo^(oX
z02TnBCur<ya<TQr8%3{h{RX_3lh|0SpOZKcieBOS%_w?%Rr8d*U6(!sR&~>Mxo)wm
zgc?>Uc01t*Rw;J7u6>naH@wpy(6DcH^Q(}%avw0je>TaBnVYsq3RX&HdJkBoWR?qo
zIsC^77(DPkPJ-pnYSf8;a#(y^*(3~$mx2nB+_MIN@RLsC5Gazn^!-Ya+@<eVie!2W
zY)Y(Q(jX|2d(to{mAh1lN~zp+OCZX}Y2*P?S<VFpoR5>hLd6bgOFUGZ@9;0M8e+Lo
z)321u@(b9cU=of2Rv~elBA9OyI+tEwJA2oGQ7LiTP~()i8(t7ijVR&p2b#x8oDT}z
zrrSZKz-@~2Xow=|G%_$Sx$q&dI`Q?jt_~+g*ClZ3<mhxo094yk?6D#xE`0#3;%?fi
zj`m7v+URp<jncG*{nQ#|X_I2#5;>?m+gsxN5^Q9R!c@)zn}qqLrPZR6>4MZKPUSwZ
zNtjMv2O2N0P1k{j%WIQ!o;BWHn<Rdt7?#_>CShTu*f&a82-8MkD%igvn5>h?CdH{-
z0jyD+I?9P{1)ut+8>K0lp)73#FKrT*AknAJ8ii@o^`M0?ZAsl%4ox3)qcC+Jg2+7L
z9M+}YaFMOL2sB<~t1beK_t?602scV#c@9|X7!1~*(zZ^u9paXb0*_OIYxxRTqs*;S
z1EI*3|9~}$+;|DF26<bDhDLc?c@bz7xAHKsMsZum85(7-+zhOt9d<skZ|guY_J<q{
ztic!AY3Q9dWH}jF!wtFWwt#TfPGaASXK<C45K*z6!kt7hEnfp`6w~xIu%4pCt6QfG
zuDS(u%3ygCSf>n@D}i;2V4Uhfim?zlVVxov-UQYugsZL-oieyqoq3&7Se^&gLki3B
zU=y%zykqptRXgWP=S{fkYS1Bi<uqWOmtpx0Sf}Kz2*_?dF1b}|f2T;TQu{kaYRzh!
zBDLnj6fe4PGq4VUT4fCG6sT1fh^~yO=K>K9nJ-cj3ysr>>jGlyJAsXd+=ZvX>(l8F
zsz`fiof6fg;CD(?It^IgveKpos>`WKdiR08jX<VNYC&Mbl$18rFt4U^EwE1EX)@S$
zicixA-yuFtcY+R3mDAAt#5OVM{5@KZf5wbj=g%oLO@SqCP-?onfW@WjRg#82C^F?U
zV1pvl;w*iF7JJyFxDU!qlj1&53t#@A$h3wcw12rC*q{hC>Ggv$)TGxB$WVD781K28
zhBDSqO8bZ_t4U=a6sYnqut9-pM`a%tWsb=>2<hvCGS&=5jG?G+ix&l_#Wz17U*&ON
zgYs2Q2R0~U<#b@9YNRsm56W08D0<7%;s@m`y%22h`f8cz1RE5&@=UNnscX{q2c)h^
zFBp`%;hgY*hW$a!9>yT2aKIG0Ce<DRA)G`L!3fDK{{tHoyz)S>LBUHG1RIpQWt|aH
z@WKgU6MQgoLa;%}D=!2a6usrx{|9Ank^O&A^cLO<#*7lqltIZ0KZM5yg>RAZfAIP%
z-vmR>BqwnOCWkxpelsY3<)C1LH`^kWf6%5Z{{ovSid42IC9C`kY*Mnq!C({Oqbzz2
zm=K~xV5&`uH7`w_QH~Zp2u#XRxhB}87%d2BXNVu;6in5m9HoDPP0G=tCxPk3%2*LL
zX>%?R?2~e~=-M!OQ!Uc|CvU3ZaPWZEf`VgdQmz)en!-ZyN-!xx%eer|%IVdKF)R7h
z1z;+FxSj(hq-c@zumOeQH1tTTa?!<MQq~q0F}f@Z!wgYdbd$iVj+4+Zt;%w5u*r*Q
zIhKFCMg<MiIoQ7}|C18eofvF}w51Qj<CK`)EPWr5rJTeWp}5U5{7;J8d<_2+@;2)R
zFnL?etQ7k#%kn>IQAWanCulKVxkuQ<PuM%{$9bX{i<l+*C#}cyde{^ULdyPvq|Vao
z7bSI;Zod-k^?9HSj-}i$N@+Sn*ve62M-<YzO9U?3iL*5OML{iZ2wN1?@`tbmK^^`O
zY%BIB9U^S;t}BlSTQoUmy#y>u^eiNntq|#1H-JTvF3$)9Lh(h?4Pa4(Ge$wsFhraS
z3-Vch4z?(tvsC#-`Rs4D4@h8L?*)tE87>gELO^G|7Ay+rY`RJ;is-E8f<+0PbthPq
z&~lZq1qmHb*$+tAD|jzhjccX%g4Hl!;X)QgcD$uWOO)AinXpCKo2BtD3SYT9*n+4H
z=Y|I)aHThcMOmA130M@gS(kuCL7Nke6>NolQPL(o7%Ylfc}bX~nw<bho-In+1pQ!9
z&dN)|7R4;xBy7<ZjRZbV(0sIVo!FFMGwI^7c*#w)GVJuEU{h%6ns|qm`$J8TwTW*A
zHBr>c0iq^~+B7gvH6oHaC8laqz}7$!EOqroF$=8C6SP<Yc~aDbB0HxoIpI1|6HUqV
zqj;Q#p>_Nuc4cbn9d}+iSJcD{ZsOJBsfiL>&J;EA`kJa(tmKLJhD`!f!hqF8(VO@l
zP!mP3`%TmYv71b6QtBo<lSH|jc)zHLayOYcpzKX1)<g6%(o#^cF%3m*%OVCSof9q?
zHBmZaR-d57`WJQ2+i@xyEbYzmxu^(){2~c2R1?KI9WOSeMVSMk$d*&ZCV_Qb7HXo*
zPJ9`ti87nc7d1g*r=-cG#7>IoR};myoG@yl*iK1IP-@FHqo(z-;FjSN6?(xYq5CjX
zZvwjy!M@;?QGu{pa?7X*Z<A~BE>Zo+dJ%9%*yTNjC8vuDzpe$Ji<;x#oU5F{7+(x3
zLWnOpQ&hmH)*5OwgSQbVm>LkOC3lMo1l3wYtj6lE#k)g=WLS$=ho?e(EIDRWL{?w&
z%cv24-6;*_i8}1u9xt+I!x;H)P$6;GYN}Gf9d!Tda(gYk8C3W=u2scINYqWii2%gZ
zrr_KHU}{t1p>tCVwa87w{PMk^LUY*^PD6_cHiASd6s1KUiwe)uB_E6G(5SVFn(Y{Z
zKJ$zh;Z0(tfeDY&{(08;Ci=`8-$bWb<D1?oRrreZ3NH#uF=t6EOw1X5DQbq5cdew3
zSM2koeit@6?*J8Q{Bn1S3PpcSMG2~}i@=)H^($@)Yf{y(xK1pg`6}WHtx27|7FZnD
zl!%S%%MvJW6AZQ3PE6pYfLUCFo;7L3ued9{C|=tC(l-eJ)SA%fE6`61aY^@n0Qzak
z!J-2EwB%t?1OK$<P^SeW<VX2bK%ExdDJp<YOD+}FVNOf_6cs3^O<_lfinWC9tEGAg
z-+rkWQPUVJhSb<^1^e=G+$85;pKYn&zp0y$l4~|~)i9u{;~1CzH7omSKBB4-HjF5=
z_X_L6npHgm7PV$o*Kxiqxm?shMXhNXWXIkxcHA*YS?Vj|JFHn$YdCk*$SdMQEV)Wl
z*k~49B`Wd~?J`-J=$U$U1;}a5taf8lubI{E<T_?F9Dn8{K&(y4V*s9<lK7j=ymCQp
zf`9NcRPt&G)25Fb=%b~4;?=U3@TG>W@Np8WKx)z9p@wO4DPwqr`Em_?xxglE3h*_X
zRH7E!4Q%8ZlkGwt4O-+k#b=F)!yhNb0Hk4?d5JxTy0*q(tD({@r53LiH^Ai}yy|$N
z#Vp|!(SVjPa~1fZ<sJ?d(4i#{ho{19zU1OiVOL+HX<i|SM$_;ihy<7OhJ0e1x^9@*
zV69_PtA-9iHL7~<aphjhAzmGQv;?=SKo%``lc;#0SVIbOJYuXN^H~L^Xvt5a;_+k2
zE21Ld-jZKLwF!0&CBH5&;paBVzeajVY(n!Qdx3nDlSIW+&>BT|0E3Vl(u#pNT0+m&
zcu!g*t82(O_)<JhiOrYQJEY#o>K&3#NylqVUcwhzq1`U}NmPJ{HUX_7hSySB@``u0
zC0B_Walcl)06m~Mzw(W!$SS!y)m|i?T*^jXk)3h@Quovv1@;2TCr^nA2+@+K#HRSR
z?Nj|Ci``;Y@)|IsC3IcIGw6b&L<PcV^{K8Q2>YZBr2=5I`c&VB5lU7gz2_1_uht6w
z#+fR}wocWzMku;XIJJU7DZY4yUcGawAlbS!U&O^*ohOAOi&mHB3uMviO&vGfDtc4b
z@yFGhx`t>&y7C&}qa~PK#k2jUz&3!V{Y_!tJ%(7-^}v9nQX_WZ0_N@sQZOT37;vE_
zv|J6e&?ewG0aj>JoWaLQu~O8R5dvr_Ie82~x^Z3LrKlSOfL*<)BbRQyXdV{kx3HJ6
z4=v><-;@|osHF|!uM;`HDLxvS$}8Y6i|NZNATo;px!3Rj4O(4NG>}0{ptcHJ(CRdj
zS3rMW6qH<PXiJ<x`ZcM|2r{~qoxB23v?(|%B3NlO#IDUt>=qZYwovj9x=G6hqG$ys
z<Ozz8u1U)dJke@WvH=!aZKC8Kf{<{PVTLw|ZG?>46gJYlM6Mw-mC}4ug4gpYBV+h#
zT|Gf)Hfqo<L}rr$-5@fXB5GD3hL*CL*9N)Sq(TEmw3^gtM-i<iCAxJEl3Fw%M5{G*
z4$-Pq=M?~=B@|r^2+?Ya5mW&fTCJ+D5u>6Gjj3KrhF%elcmYzk%f7#)9|PXFniOPY
ztY1uZUV#Eyjppx)toP3*H4vOx6Za6D%`|fmoXylV1m{V1Ua{|&U~~2LU92W08{f@p
zP_pr5twx*oruYD9^4^4wD){<4gk+Nv-613!zwW+ykXgHSh`^S_2t*)~lvf~fmk@9j
zXrI-9f`4j&eO60i1Ol+qrd<K`S#@dr5P?ckUOT*%mLPEz$MC9Dy#Z`qb*Zn{-LFpd
zgS%gyXN<V~2_IKGgq<>#R{(mJU~Sc<(JnhDj}v^ltBlqVYMTP)AlsCfyaI5(9KcpP
ze6UxQ#kxbb)h^~B+p5gfJ!D&z!MewB@GRypuN~4((6vp85p|UO>#j0ZJ49%gspCSY
zSju@`0S8)DhH3;0T2<;cf(5Or=cx+l&#F?mp-ycI8-o0+GFw9}dr?r@n_cP6D;y;j
zacC7Tv8zfYhsVXLvRA_`<5^W&dZ36_m68q+(efnd75JegAX^1`Xt|R2fD+@Anm(ci
zd&PB8xzj5Y=p|TN9e}c|Dvcb8C^jWVIO4vj%;=jCtV-V=keKxts0T!5m3?~P!dR)3
zzwRTeN*~94Whps&9mZ`cg&a7cO<~uNnpI}$KnX3Ah7OR>vq|U~mQW>8uLwl60E(-C
z2Q8D9?g*h}3Kvvy*IOnf-MghWj?3c`K(69~xeV$!va&3jr-3-Hlr+5p@8cBAK18O;
zQayOp0D?e$zqEmdU1FLH)d2r2lc5^epCwdW1@>o|VC@wb^<~o6<1W8U>N?WkEQ6gI
ziE@^5s6RFQ@)jX>b@<&9xzH<sI!l<i3TwtPTB*a_@mjqqHX!?y=)A&ivV?c5!0~Jf
z8-_#VCPm9L`QI@E!0;@SiFzh%0;%P0&slbE<P&#Bqs9%R&@x%5!x40uRB(jlSj4)$
z4s~RLT1sucDY02t@=27H8iuoFvQje=$zsy-8XmSwsIwYwxSN7f%$dy8$ZxeQo$*1=
znatF)dWpS4&Y3iDpm1Ikl;VIXQn<q)xr+2{7%f-P*9b@FrS#<$zR=GiQmoGIe`gH{
zxFTH{hT2UbXOMA4F?=fQy{k-=oHKoW2*9%nZPKtIuOj_=BBA*zQm_HbSw%{=BXgEA
zoLAs-mM~@&7@So)k9R<DR*^;>0Gv%=N4NnhFM0(8X8~gN1ZhMqb~Q05Y19*Pu~4Cg
zZ~syr^rw1qyd@-AMf$u|WR;$fghf_qU~*QGKE05;brovV0n%AYg<kRgu>dx!cp%wj
zbd6V(P2pLLr<P4Z-)mQq%8jR*#f<3{@SIhoatAu+aT0&hQHLF8j7J(ao|IP6$Gt*Y
z7I~>xgznlTb_H=+pk(8%YAHo}T^1!w30}2VkzpIyn^k1kMi$CdWY|Wg%2i<34tUNg
z%DP$s&sl`0Re*C=k!c&)oK=##t{6`k(4HW5{D{rOfOJj(JhQU2?7+?}!O-dg;Av%9
zyn&oqnQFJchc0C|uXr(CSvoadRX2qOZ@j&365EAj%d~i}_*6H6<A!8Ig7YUxF$O8;
zD`Z=i(Hk-SR;DVBuzyP_(4XqB)XULkH83xWnanE?FDpxb2H@pILCGgJOJ8nyk6)Q4
z?uJMEB_LSC%l^vLpqmF^+-2BS8q(^%NceNiA}!pT5|c=kyCq1v%ulza@Pt~qs$<wf
zb44k*H?<n25uJvR^VH-m0qVJg+iJ<sVPS<3aJh&92)JCt0EAqYow@;TvY4CPDZv-@
z;+9@QE@yQNA(t~d2J&U)tga#Ua#q){e=1*j3k=K>=BokQ@~oWLGK`x!sbRkWDxrA;
zs%Ht@)l&BoH17ti&`L}ELlmaPULXn6QZEpMKyf`SvUcyXdWo|lEpZQFn3kpum%TLA
zHB#3tLAaVjUUs=x{=|1)3bnWa?y}NU*AR|LR_X?@%SuyyhjdK5OE+L$RvPMgVvvL3
zoEvywN^RaSz9qa@^Ep|ms~L#CL^b$nK*()U!%u=^>cI_2yG3kQ1FR*{Y~3>8zbnyh
z-3V++G+S?quYRK0x*;aeN}*A=9KQ#WxDou48v6~S%qFno?BlEI6*oYoF@GA6i%Y<;
zMubW-u?8uYXtHjvFL@<X4N9>@sP`tt#xybqk)@>MEl!6e)K(*|B^4ck1h%B2zG_Tv
zQBM$Bsj#PtsfCn%oD@SU_(2ROtLNq=4i2}ul+_0w@t4qCjQ|#=D0fOszdq<du%vX=
ziS3oBrZz<Pd6B#{KIU5DDzwU}^yCeA=PBG(%kXyGB=#D@Y*W~;3$snYv4|M+6RpOV
zHrFKDqyZ{33C(Ii%4`CA-XHZ`Q{9Gz45tH8FjLU128hdCLwqf;LG`(n1Xid%Z;GD`
zbJ0S*Nx=&&)XkNXxu{O>a`%a&KHZ?vOvWe-Qt(Ryb%Sa&S6An*J<ZkBb!>?lD$d?o
zK*!A0)O*G_C8Pn4nF4IJ5+!zAxQLY_Dj0zzaHyS5iC<W-R>iA<HHEKkaK@MdVl`xl
z*c2QxNFlK)(QfsBlTW1k*(5Ssu?I~(hk%@dYBlKma}{;$BYWm5>bPR@3p#FC`l8Mo
zHepfU4J%*hRnw5OW3H^uJ3gDNhB{b=GTi(w_9`P_%j1;bCW*fReiHZ_;D(xS1Jq@%
z#AZGIz+ALaH$YwHTw*Rn)|^W-6Jl*DYk7;jE02?Kw&1F}DeOExyg3&;k1ul**t>tc
zb1M5&gMZdkZu5p@GE<1KO$iPqZUK4O6rK;}L*5iH2)n_ifI-+5HYFHDn4U@e*5f4K
zd~^5@_OEHTZb<htC+*e^DS_tf>UGPv88Lw$5Msi4Z{Cz(zI!QT!kkUrlo&}<FYq3k
zN^0JKnwe8yG&~^Zl+FxL%oGZ%MFgH_&MICEywE1yV553bP;y?RM8m{2Cmkvp%wThx
zx~Z5}6LS@_YU(&zWv7VdJUxeb1CnM6vDJX2nUm@`fHZST9}gVOoQ3GN2I$OG>hlKZ
z%oL2P!Mr%9l<UX=<`gwFyhzp|1O?LCl;Ah3*#Ul&Mu4D|b5i}bkbzU$H!QJpN?gNQ
zJE!z-gBY9&sQI5h{=>63ZF*IG{cM!>s{0aJY0PS`yU>69_aFc5BY&jVf8&4u%U>Tr
z!zRp>fBl$o|Cowii?y4IY&Ku43diI@2j`%JK4MYN!Q&Rk#8g^oBrcx{8nt5Grf?|C
z(LFnRMELgEDaU|)o&r3qI3gw?2sy<e5KsS)Q~Vk=d*UzfnJCe0PGRbuddALBq$e|@
zda$q96nd@A@Hm-z&df*@GMn;k<7zk&9%VQ5T98?J*~p$zW>#JrGSZn&zH#NSEW8N(
zVsn92YwF1-m)N_Lxdt=RUCx@k6sq-94!#VF-899f%q7eU(`XFH#gFkRn{^IX;b}@!
z4yWhI{A#b^!FoN7kcey$kOfj98{}FUYB(-Wv#{?cBNO42AuiXr>(0VMBUgKsib`7x
znMDc3BYeecp0b9Ghs{Y#OvZ!i%yE;-NTND3)5s&C>x|qvK2dl#pU5qf8&m>ansW>B
zFm>z9%{!b)35GLL@Ju=6WW;NlN)D2NoS8|f<a^A<R7Q>`_fQ0<t^v6t$B{BtWJE<9
z@;Au9p$$O(^VnIjq}gSUoA)aFze5QciZPoJ6naQ8$-r)oxin1!xlV++&WK1kriKi-
z?U+pzr058DUT-Mi%R}dU4(UA<O*}(&7=zc83=sPmlkrJ25)=%Dz0Oc6$KcH~ulTq(
z1^gg2#c(uZW`>OSwDmrb!*dR#$o?LT?o92G-94imit*s_^?3SnpGpNKE3gFIImD4D
zieM#AuU+Sr8T)xlVIA!td()kI+BfwOCZ&WSa467{CqDLsa#!YKq_t_vx`I?_gGh*-
zZP(|qDuED8;g1sBMkd<jDQ~?LM$(}t^#a{-CuNOREqNwXT$eo`sb>*I7f2O3OtX#L
zmqSmLo=Y=Du1yRu{ua43W9mH9WPQs$SwktjGD0%tn-adngZwzo{X4;5iHv`!6VpEA
zeqRuA=uV;+`*kP4v(WhqKrEvujbua4DWr}=*262a8xk>P4ZAT*ZdQ)b78$~@ragA=
z&gO+ikc@t0rMbg~99dx=3UG%*rm_Mg<w#2Y){zVCO4k%u?2%4>a6o5ALIQ+90*}P~
zJ&+4a=>i6#mCH@545X6li;3tE0Jbj;8amTX#)2;iN>0~Rv*3~Px$~7Uy^j)Xy0UX;
z0GW|310}@McYpjR(n6#bc_Xk{q3d+%!v(%dUCsk#F+EA*6F`9tq6@WOpzn0T+zr<E
zegeCOzS9Ty{9|G7>VkS36rL-jJkkaYIRiu8L1=WREQURm_mW2lUkDlw@7qj=QTH0M
zOefDNZ~7e0lXEEMP2S;tl#0VLT?Ca9!wRF~Q2n<;U-o$-nH7a9UH%jLY>$B`ungOI
zh32LAvV_26g(0F(f&ha%uh8ZecQg;V%D|NhdI+nw89hgZWj15@1>%X#=p@;h^uQPv
zs58;7RXX#ZXp#)oN~z#s5kKA{C+?u7SKz|I*aMBbr!qWtQ;?v>xFNs-8h~~Y`z}_4
zLG}=h&Pk2I_T=N;=%rc}V5Ln)km_oSu@zh}SZ5%ED~cCG{!~TB==9fD@@$I`rXF>N
z->G%FubYCzbw(;RMpqbg-o64QWd>+g@?#qjOGKH3Z7_mQ^feU3N-;FXWLS-<fGdO1
zC5p#?0DdFlp+vir5fVxjiEh!wPJ9f;@44cC(1BlJF(*R6>A}(#-Pbdp{yp9UNFRu^
z&=8J+!2%cwTfqq!#EY+5PdNQAc=<B~1tV+F6TjkJ&t1&nwi^*5@RU(geZsH%cumXu
znGVsHTQmK}8T~FDmq*yMFK=I@hg?fAB<M&>*40X@{N+m;0d<$GjWtZyw?igfkD(D&
zn0DP2(#u5-fAXEgE1=teDzu|_N4N096C@uR(o$e|_<gxA*)F<@bbDiM4=Mj4EHsO;
zy(=`MHRL%!>%>CH><YbTF)>MawKzqS48>@5p=)km4S;|{Gjc}<ApGUEaQPObK=jig
z;b8m)=f+FY8`eJ1#RTa<IeJHz6BbTHbv&9h!MiRvG~uiMTCE7370S^K2F5!tpleW!
zRuxF@g0m8*IRQ8nM*ISI!qFFc(W-KWxNwbxDaKoq2~iwtx{O9n$G`=cOL*H0<wkVR
z0h<vegy(XjM)Dj4mtd37jaHH8fnZJt#x#Wp3RKR1q*v1F3hihqbkhw`A<(4)=pv*@
zF#ars7OGH=mh|2V7yS)q_*-lOAK&RFoMrDk@A`xZ;NhGY6uoF?8rAh^e5}uSx?V{y
zK2VNU(hExlHYdsY3iSw2hw;n>?}w!B`2vS0E531o+v|CXW_Tppn@WG!pc&0o_5N@@
zhv-FuZxnnv;6s5PZx(EidSR0R{n*H5yoQP0!pKQU`rO7{8nbC}rN$p7&DXa%OZ|BL
z!(LmVzy9&MBdnf(X3^XOd$VZ9iX4mPhpd^=ovfMu9m<%=Z{s#*hN<!xGh;e0V`gmO
z+n5OhD2<u?G%jOiOx<P7e6wZhVd=7Ec9<@YF%woY88gF1Nkb;gJlwFe@ryWSObVJ~
z#w@Z@!i?FH44c)Bny`=4j7j6eZN?n$W=wtzFk^1R=7%hpkDD-IjFAnKmWSJp3CoY{
zm{X?E5fAlKU}M=adHBhWS!s|wW=xodWX04IfXtYRa(L{RGV{rfIoL9-n2llEju|r^
zO~Z(3pNyEen8AkWR!v$#p~cTkL;W#g^5yH8F=fk@9aDzQxB@>j6CZI5ncfkNm<s(Q
zBc=@JvSI2NJVwl8)}#@WK+R*s)Q*!4Q<=eO#Qbc)<m=-xU^3i89>vX>s4+ZF{m_H=
zF=NV{Ei)$F5oN~Yqb!Y>&rllCW5v{#lNED(+!jo2HySV%z(^KM?KfI55fni7OXb};
z=1X44pJTry^#0f{`^Rm&q>&Bw%Wci%5-#Sb9?IY9c2i_bh6Ph84rReqT5lOJyX-`=
zU@G0FESM&<B21Wa;*<rm3l4rvn98F}6DHq*Wx`ax@GxPzl@m9UW5NXV?^rOE=9VVR
zXanZUQF)Pq_408WCybu7U@B{>ESN}4>IO{N`oex$3yl>rU@9>4F<>fvr3{!#)(+$5
zz!T(i8!(wORrX8Sy=cIcR{#x|Mw|Xa1E$_>js=rhYh}Px!dV$G2`hvB@^LFCc8Cm^
zeEO9UQvhQbG4*<L88Nl_8myertc;i^4?K;S+IKQyp47@TVhWEbBW9MlQASKzn`OlG
zQt0WATRE{oXu@otOqkSqXu=$+z~&iBx@R*-ieFhUm8(=1%=tGK%#*AaIbB0V_J(A^
zq>c*<rl2ow!IaHT7EGn<g9-DwGZf2)N$ldWVannv8zwX6!hm__t!1`hnJs9-)DyQ%
zn2Ov>3nuJ%i8<Ma@>a-#sm!4;V4j3eiCIujZo!0S3gvL6`Es4yWwKzNG+3_fbb*4x
zewpgAXVQRq(yhpVc@m<^f{Ew@$9&mOx&YZQ6_MarF}nio%8J=#vyl<An>R!YW|zf^
z7R=7%Pqbgkt^61;+sR=l3uZgXhm=P|k;G-g<e_^^nC*nZl@YVa@C+;FNg3f*Og)&x
ziuu9p2o({ZJ*5DaM<&c#X`Q4Evns=1yF%=rOcXiHnpHt>WyCaXMj0{T02e0AFe%bL
z`4%`G#>gvjxmS}B(-;T1Gwp?(q>Krsaw^)kvSAh_tdJ42$gIhve+4-k-LCV5SrL^G
zm>6Bjf?1SI^jI*Jw1*l|#NCY<krh)K=&@p+fV8q=p3tuojs*zM`f(dE^>xXJc_Ni6
z2ImPCnqz}{sLrra(vF!<^j+F9g>XKW%*3d&FkE?bM}-fC8B-21$Bub|9Ttz$CU24r
z>R&Sa(vZ2944*^s@mK?ZaUI(*Vk+R=a~m;F2ss)t<)um^rXY1NVy+37O}Ahome{)q
zQz_Dq4O6bhvSKn42W*%RVo`luhRh-FIvO%h1SlFZBM=jVSHVB^*fHfw>2}N$Ux>C$
z`69`fdBR=MnAv5g`u|%yo1IN|EGy6BDstF8=qCJcPmur#1_&rdhzY1033U%>gt&cP
zdp~PMe0lO@oz9|4s`|Y1jR@P}@c!}IYb%`Dm0YK2CcEzw%Ty+)Lz#wtIFy;c4`n`F
zK!h@z`FV(Bw(0nsBAG7p^h7dE593g#lgAy(JSp2xAkzt04rDriIRcq4nt*HufQNh_
z0-44jKfz3gh8@g&lFk*(bZpqc%!o;1Ag$tXog$gV36hFro>ibIrYFEb%!l^XQOqZ|
zRZ+|*Q&mw+e+&v@W>cRyh-pp(2Qgo1i|;H!(h=XOc}MHKQ{)uHG^d1um`^&HveFzX
z#Xh=La+alom`<2*5Yw4UN^^SW9c5B|!0;2p^alB4<$Ry_Vw}4pm`(Wln-sZQpW+k2
zG|<`+Os&Ir0Ml6i9l#Wbznxg60+Whf_OH>)9lZSZ4qQ6TBa`F%24yR9>5%Cwb}6*-
z6S@>;6GwB3m+=+46xPzQOYZxV(51-;B6j(i#?P<5ecoN)ILyx<?X!1(9P>XIyWEY>
z&4@Nk+rpqwx8QVoMo4f>eI~yRdx9@^q1)KMr?64qs8+lMF*Px|>qz1?Q}TF&LFooj
z9o4~|<^1hHYjir)%?0RpI#BU75*ypfG%zcu9H%Pb9%o|ikj4%V#(Q<)T2KR1CtF{`
zx{ZElSDC!NAn3b75<M}n6<F~=4Mgx}8cqSd=Jd(g6wGkcCz^bgn&U2$D6Gl(Uh(En
zW5nywVLx#7>2kIp+9xM-L0LNO*Z{Db4(iOQ9yx#wX854ksAE2dEWdfa$)PCNoXjzR
zyX&{{Z%ALKS@YI?8o+jMrd{3-_S*H4L@TCTMlLYIDf&E8Ag0;#_^zkO^R6ER;3F$W
zHELJH;^WWgjSI>yqP;FByNGT(%=O!7evY`iKEf3tjcIhuqAI|I{BDu>V(vTkuW6pU
zMUG2XC~MWzAo&9u@O6AZic61g3aIAn^2Q@gXBuo6p}^~$H}C+GSxksWvd=Uh9=Sjh
zlW3iw{u9{y?FmMFXj{ObB8)S;K2Hduw;*0EcE$_R-I@GwQ%IPa_HDyno?Z9|van{a
zI+gnEIm$Tw*2jjjnO#~89`5M^vx0R_*Ov{$eG8&-&SA=PP7^OzI%#pZfi-pg<|v2L
zy4_?{q_}i_vmo1!;N}-QZ^uXCYcUF)j}Rr=f)>q~dLP={9I*7vI{$j0gdj#@z&fde
z(_w-Hq+&vzcZDd1BeN^raS0*+8>J;^QUaU21$r_EEBh=<j|RlvwJ-eOxQoP@Zul(;
zmDhCf*%V2a(=2_7yv%9jKq7T>9+tjDw&x52vzVz8O*)G{Ga=uP&fQRHue1V6icQ0G
zw`dQj`RL}3c+I2)?QX|;of8C(Upkv}k+-08iRO~r8jk$h$z;$Jq5|9S98#h2o$i1V
zG;80MoOfa7z7$sBG_+z1PVnp_`W7dRXGJ%|t8dhxNc(<!7<sgyD%74jz_G@gk{`%|
zo~}>3C2=;{JcY62ZHW#>?$D_ArV=GLoX>G2ovXBHL#?XF?Kvtv8|dq(l!M{sqbvaZ
z@2n8Ct4RFPF}P<lQ&=J^V2d={lVLi?gQ_I6Rj(!v`GV^2LUe{%{OsQx<=$xSR{X9}
z-7rF4A&T{*0DVgLX)$b~5c7DR2_}GPIAA)JV6H9TtQY;=<e&WLL>UEcV!tgpqj^rd
z6N#;_bQ*kv=G}=?qiHvIOJX$VC~YU)M1$8%+<ywWm=flILy$i@?aum?opTVh5YrTb
z3Fe3ig<zs6(6l?gB{?o(KZcoNnhfxDtRAiCnycU@xGrY(mXaWpoGxga5^B6o&+Yfe
z^JsEY0dC28XZ1-4O8qp|GkmP-LuP!|DI&l`iK=NLzy!!}!vORg&djS1YJUqAK%W~s
zwIzE%*B0p~?fgJ9i;Az^BSy!&hHZjcWmZ?ZO7O2tm9R~b7c{Fk4oF-kXL>(?F(j&h
zPFJ~21V*Qe+@^%Oca7UEi9uG+17N=C!nEH*Btm<e9WcRnGsO;=I6a%Sc(ci9?^muE
z%G>OKDaR$s`a*dhYQWtJZDDS}EsFQ9?;Q@HH*_O0`(c|T!X&#*=s&?X^h#L^wQZ1Z
z%BXGEz)h6Zn<{~O9Z`(W-#-EE>9~H%<+RuUegG>e8e{Uzqs`4HxFxZ;Z;d*1xhVw`
zr^d6o*iC{UYMN3o0qUKm6ig(zO;ZYP$r)xb@G5bd`bNH>v&{#%C8vkQ)<rOEP1w_~
zkeoi6CNL55n$QIP2vLLDcI56#r^w_MB;O=}Icf!X#+hFnmd`RYd4n9rVj~3pvRQ0|
zKzlZeZH{0@dqaB$Mo94vLk-Sp9>GMR&S@gSL^aO|kzhLYK4-C~lYsP0@d$1~jLDWr
zMnxA}A{iB3+B4tZLys~l8b-q1j(7dwqEOJq`$?wa$`%QFbRYN<(@U^(OJaHpI@*+l
zTM`4R9%DgGKQO4!z~&!J(EV+RZi50Y#fh;64P1;PDrjJ_6s8glC3~WQ9mWNJb$tO~
zp@WODIh5g@MWMG8m3pU(@h0wgO&8-$baa;F`{0Qi`jDtVJY7{cm3ms9DV*`*Edyx9
zEZ#AwbiCnVdMmi-aq@bF<aF3u2Cr~SVxn--i}wpw!E`(u9NP5-h<4O_UY<|Xd-iTY
z`RM5kwhdl8Bgm#0-J(FIIbSxCBxatz&u<}bsBe|bP3Kf}x)N>zu`;u54cJAe%ity|
zZ_jLVqlj-J52hwmb2irLw^%#KCQN*opi`aMWDMyru1-@J?soL9zb=a2by{x#-$zoF
zel7mO6vfVG_D5b(%qBG4lCuo6DA5uioh>0|zeVwq;;!jn1X)ZKtt=+P1VQffAw@bB
z->(N(82VHkgsGxV%|V!enNKJPcRQZ%5|`hD6H%SH(25@Tqs7RWu85mtiA-0-O<}Ff
z?5`Gk=W8bS>3XIS{eDvVD+=;~Nd{(8Q;W~*qPGby=Z}O|#2&K0RloyVqB}+}{i#+o
zXLg+7D>m~&biP&}mnUr0nf<XI8+NAUN25CvCx%zTHlEJoN!ZU@61{_fB02m}p_@oH
z2dd~MUO>@MpC&Zif-|V(&$*&K6XpOu#0*3DLUe}oB+(!3X)?n^zSm6t;w#!S4g2Vv
zN>0P~e*j|*{_~l1PPYYTEr{?i1!wwoBzijfGua}5d|@VA1dUUtBp#P^yta9c$uHV5
zh6h25x;$A@3Eyx!#WvwTPF2lKE%*tii{>W0&}pi~EeS#b?+c`zOs6btNvQu6w+(s%
zR?ly7y|}Z<svkFeQaAV70+AfBdf?}uPWeh?!%SDw-IDV%Y#lU+>!<7JZcz+}9fd%|
z8)J;FO|lJIJq`K%4ON?L91s+lE}xqSoXq5Hh5`vQWu5D!h`-E~{bY1)lEXn1XA4+5
z-vOYdXjAe#hS*8ejH&h0(7VG&PTqK^J@Jto1AyujGkN2og2faiV~S|m8+DD!rQU8*
zp^Rxt#w`*9g<c;tP|4d)J8IeGb`ucVEn&su44Z@T2Y7GzolL=)BK2zXTCjIDeBT%K
z1->r_&$}I0=oV<;+ulN>D(7@L-7SjVI*i%zja^_j1;fj9dEG?emTTVHE{GdXA9^QZ
z%kvc1O@yAOYwM;SSoZVK>%iO3OuMRXB2Yd}qnHS$PnXC|QMzW{iauV6@;1{Iaub-6
zDFkVvNX|5K;*XH@<vM&JOk77l-wrBtG&1O>1R!?a{`4cqc;03=-jaBQjze@9q3+@_
zhK4pBW8!c{nEoq7F{0wR!izN}W8%za3Tu^m+*KnME7Yl~yPJ_*V2h*U1>fEZI9Qry
zXH0SSG@lf!@6rv9<S1p;$xWPyO@kV?BsvN}zmF>@SGXR9>@vCu5~F$BL+GgJTdnBl
z{p3!BdUg(L;;?Yux91CWY-~k3r<f-(BF7iVIp;95;+907!=km3%1$6l6c-yyiK9ss
z$i@=xe2Wf(d<n*sIC>q%Ca04$@J`5xJ#0M1akofBG%?dK4vghEz(_G5hXF=nKtn7U
zTNESG>1QH+VHg+veL6_!$>E~6Nwwr&6ga2*PFxwJbu7gIMrfens<#QctFhWcds7%t
z^P@`)$U((X7?4jRMqxb7LHVe|cSNkQQBRB2G%5q~*FQp04iPq{sQveq*M}4X7#mZ-
zrH9i3w;&dSErG9jGZ&&*4BiibPYkm<CUDLJ4#z~{#33HX{TBOaGP#|69;^A$>Fbl8
z)1$Zkv`3E!*;rQdW6)ixc|a$_WQ^&+QpU1YALLX71;~XcUbTaW)S?_l&7Wi;F5^k$
zM*vQ^LKLI&Q39}>v3!ycNS@(py*ueBrdOqgwj{=Id*y8{I?Umipa^;8DUC%+5q?FQ
zaqck8W0HU!Z3&<3B&lLr!$YqzrmzoNa(1jSr|ukk+;Fl$f*J3fBn7dJEB2<7>olgz
zBP5EXj%nKfc9fwiy$LMSnBFb|%rsP^_d1domCr6gYYnF^B=Ag1*$RC!rZ<m?-#Uzt
z-J+OJpC|we8?Lx}a=%XZ<O9q|1DVdvNRYyeNdRzG`sVK({>I@7yjv3e<LlppjD#{h
zw~>>kPamMunDznyIt@}YlDafpfcI;j8iKPKm>V)N_;I))6S$@^U7;i$WYaKaIKh-T
z%zTr`6dq=ROrMu9%mkUl3o{NAWa2HpbL9pj@xH)n_(~B5XP83qK%hP%TG8|5DV!`m
zhXudS$(xJs#~Piw*2D1UEs35y++?9{r|tPk4f{d0-bB{TaQ;gI$vvj+`GvB5<pUmN
zJMXj2fS@`AXiNVrO0-xJu}keXv(83#a$n9Zuf%S*MT`(uq+$5sZ}Sk-ik2wUGOur7
z?*r2`72A=t)7Icnv@QUgfKQRxcp-|u$(CO=xZLOj>Tp=U1DF~E^}eJHhc!HUai|J#
z3e`EBR`h*BCAnkcIYL~hIhXTI@K255&v*6H(v)_3>aSOzsG;Pg1SsmAxrs6~gfIm#
z>MK>9$m<AVfR)-3jVE@%af$%%R=gS?DIVz57{(7Q@udwL@oO+X8}a9%Pev(faoCDq
zla4*vz2Kk5kd}s}WejWSbu^sQQWF5EVG!b#fItny5ECe<VOFLL3Thagm;(hhj84oq
zRQO})-(#hj3+=vRs`1fxI|iiaV8+Tnd9xRSxPpW_Jc;2-zFTrS-<|CTx@mx=KlFg;
zJFtv7uua3&d^6alVHVYl<MU41g}Z)qMFKM()G&ZCe>|+=TD}>?(*Vwx!8`3XPE-c)
zv_)CJ>0F}+qaa<lcjphsc!u*}?@*CletZUPKDyIPsRJ-f44VN#jc(rN3<~NaIzMP9
zC0Q>J{n!=n%Qp(LJA?BkDm=QW>p(#b=icQ&K@B4yGa#oSfMX`{ee@?ClVHIB;+XGo
z{?^JE^zF%(M&<SDX;U(+>-uH@Ok2WDqi5A!jd;p%N?<1DGP*7K41Q_!;+27BbaCK(
z0yl@Ck|(1nyUzeKaHSy{-h7jjY&heV#Gssle4{;GANa~qGGsWvCR0^pxEydMqBT?w
zIG?!KFkUf7<m@^kdJG_GOLR$e*QwXQkzN#=p)Lckcp-@wD`lTSBW;PE{UwJTNvz7-
z8OYRq8Llh5C5g*e--JJhivs6_U)fB$kt2rs&W=ZI8iSY<TGJ53EfG=ZF+)NW>G0kR
zQavqAAG#HgVg{Bp3{uQVy0uL|8Qt2ZpIphzf0Fmnr_I!r=|sP-(YzZZJj*sbTQClY
z#cnghyjf1suaUWVA&L$^ECDE3=dfnLOGDVhoI<}6(>*)_DA;x=Ou;Q}q5*apfJ<AV
zw~vA~?r=-C4Qbe6CZT<_=68>RHSRE{d0LuB6l^mBdW&L!7!X@9g4tC!MF$&Dm^mpL
zsvR6e2{8a?t#iQiP$!%ds9`u^roz@}X0}X3Z-?Q8IiZzZJvf7G8m=Ck1Kl*5U`CmP
zwrdDim^q9aO=f<M<GNv>Vdg~d&Fp|?ZbCulQ=n`ZLYRRs4MPYs@TJk@{bvA7LpZ|g
zP)5WMv}FW<X&6VC0WgVF0=?X9R%GerCc}cG)X{8M<Z@aX9%{LHqaY`3OGG1Zj&nZ(
z{yt-?Hano*+7g}_`nQ_hG*@w5$TP?wk_Np%`PS)?pnI#RBF-Hn8gQLv^t+n1mV@wN
z)MDna{Kc?=_7!aLI->o)4O`6MnT83}GgK7A$i*$magknT*8shzWK^`Uj9U;R>VDMt
zLiT~yuA))Q;FpGBiy5AbHwiLIyPC5i5KV&$##cyUNZp?XN?I_*418%g<vkztg_%bJ
zopBujJ2ViEQAJRZ<Az$Q=xZl^Zb=NM3J{vfKtH6-OfBwi#R$ovzpIIFGx}SZ__-*w
z{9;DI+dU}94D@9f=9mvSW>onkyB*9cMPGD5dmF@<f%^<I>1|2$#5+Sl4+l`<3Q6KB
z-AB~cnN~Z5E$SJLYc+Rpp%CLR`Y;1Z8b%;ypipn-m(b*fBxXQL*AUz=15z4QfrJd=
zXc#z{fqT6PWYD=~`7M@s#iN*17<%kMHR4=gg0WozGwPOP{o+_N!xaU#C`f1QV}Lmt
z#b!n6!Pm`WQPjn?6Eg^;QM3mXw6dXwnX1B@0Oz5^iQdKkUm-f5bFsrvP_xDoZb@|S
z_zPv<!2UuZD7i&?v#8kO&l`l~DE_=bAdTYBJL)rE!$lP`JQ5$tX`zIRLWsGbgU#l{
zYZ&EmD9(!-rTMw|!NnE>D_|Hgm@67rsKM)qVo0(YVzIq>gHWf%L^42RU;OD+WH{!^
z%`EIuWHr<vZ@1L|T6Yv%4M2KFF~e;J_q#=W6<~wkRPCX2U%W<WSw77xMDgmq7XWk`
z#d|>&o4mY=dX%W?eRn&yR09dOD7u_HEc{&q2{XIgmS{?ASh%i}oY^f$(Z9z4Y$m{w
zKZ>@3ina|LA?)*~si&e!Pf_HImKd&yoI{a}EEAw|d^KDXIY<4Gk!=-J{8}@AZprCs
zUbIdxqny))DA=J)AT>^d?;jA;06DnZK`&*uqRQ>fb}K3x)cC?2pr&DXVFt1^Kn`Z`
zO3+qah~g3rZqj-04%jy1&@|^gnc2HT*hSY7X)T~FT|POJ#W7qzIm0G43_i?ZgI&Ym
z!;GEwCe%V7W*r~q163N?E(K7fA&#;T1$CFSeHf{ml#BI@A^WE3N_4N<t#2u&R*6cv
zsSrY?6<xEcZbw08tLi9?bA^cU;E@_5m;nhL3BReQ^{|D-I>|P1Tjk08{5<s`6GOvM
ziFlKXosTeE-<~9|>quBvIAp`6h%<iOFrh>K_<e7JGSpYTpJ~U>%&Lq5-e=_7cSWI5
z%^`fu<S(=7K+`<88J3XY(#1I(-{Hc=8Q*w_X(Ho34^=!2(V1nV0W(R0TcW2&VF^7L
z{U)5>7Q~T}p?*2=KOezq9JM5DUIy4Rl0Pc=BFCvlocnzp_BI|)cIGf9FB1+K=JU-Y
zc^=NU7<#|er-ueEw3v~5TW~(AWQ!UY&k$BG6A2pWQL-mkGz`_tgp-D$dYPEhNQ(65
z2ucls@p1=qGK|K{#I^=#ybR1|7>u_i(OtXhy_neU7L6U$h{=IFa*Kxndif+D52N!k
zAw1ad&KFMHZwQW;f%=T(z+FInh5>oGs{~2*tJ~j_aCN!k?7bNFaP|_v<|U@*dOGF<
z_$`XLwH@76=fujj<LViJm!qh{0DpIdBs!~qkI8?^oS?Q|<bUI|Vkq#ljO17yG3X&K
z=p3k>VWyQ#v4?Tnzy`-N?)A_RqNH9FgQzKS<!?dbD!qy+7DCZMZPEFNUGO;f_<_D5
z)X=SuxTA$`f5Sa0Fo@d_Z_K#5ETGTrczghTZmUlLeQuZZ*rK32JfFHyKDWPZj$_^o
ziiw`ad0ieb0uNU;&QY&q+>X8v^pPlQ@<1iIU~v|T=WgaF6^`d2Ys5t})GiCfb2nOt
z%uxgbc>sMKx7DX0Jg!-sh2SxJPUf6#-13Gur03xc+@z5)oJuRk@^DDv&D}PeVIkQP
z%@L~23_V%coZF$bK?L<yWKCe5+bS5i&h_wB_Vdqr3d--!eii7xJNvmPzdP9?6r|_2
zT@9qiK)WqiTouoSOx9StE5{M=FxKvHX`T_<rXDCj9)j+>Z_faX#p9MyJ?3d>_+kLH
zO)YSbk#||xo~Lqh7P#lOOCI2!Zu<7jN&1WA6Sz-bl#R)teYz`G<b(F<uj)s!we;n%
zKBdn#Qz+Z?ysy*bDIf>>vi&_{BwNyG@A16JM(^l+430{c-PMybNQkEf(}7BK7gNq4
zdb)9X*C8;y;~KgS$mdOI8h&0ES6&W~Pd9ikPZVnhyqAG~>^5^2m4doUDQ}|G=&gP2
zS(y3e=m;f;y3u-D(!{PxJH}+o0A$dX08q?8gSLnj2{fp$M(Yg7I|{I%F7RFsT+nqS
zdU9+wec2ud81$}i)xOZaHeUK;IDic5%e%@9HdFcPv(a^j?`Nm$<#~%e`tMDKntpwG
zlc6H+n{>9*|LnP?9!jU+a-QSGtD33G+lA%JfPwllYcyb>zLF4_88lE|-edv|bV_{j
z+`&?2lL2w|P~u)&l;fJLpA;_9<W2?{&xnd)?EN6>`g)uLV0V3a0|7qNmnoNl550(Z
z13uIR8VbqjyKsG(ANOhJeTh+*fF9_fQ^Bn17wtL%aruV6?uPkgAdB53lA9E`@Eg|O
zg2kmz`|K;YdyV1Sg6OZejg{%JwhfAD_c?5Rvj{qjmH8}?-O^)X4ZYcjGb8ZE60Dim
zsny1&xC)fTJ}wLZ>K3pzz#jF<&I0hL&xha~GN(Shx9~OfX}_H!=zTUnyE4iq#CHaF
z+g<57A7E}bcl>V0IKA5}inq;Yw^{H#PwzG$l|B+$XN*P|z&YB57tD)*Zg;8Z46^Cr
zat@228!wnwKP^o`m;`-3d(DEB+5CAK7*n5iN`PqhNi9H%Gj;anGrSSqw@X5)lRoW}
ztien2X0ry}SDfL>AeXwy`!YAdJOjDZ#c!I?gnfFuSyK!CsoOUhlHHjVI^PV}835Fl
z=)s}5uRiU~pzXWMJLRRqg1RJnFKj`%?`Xv#Te;EjE*@R5Ro=|n=y)Rw3pUS|oF0W}
z_upW`g5A^wCM>|6x>;Te##kS*<&>N3={}a9eT;*#{ABdLm<$VGr*7uL5^$$JrXqKR
zGGKkkNGaH?eV7b6%-U}9!h+@7VK2ObQ9MR4^l)qelNc6k>W6jw7y{-nEH@$HEz*#%
z1jg{AF$6~UWMT-2-mru>&;z-6Avx<C=wiXA*lj%<Q($yI8dE^n#p@%AGLVbK&={b(
zkME=S2mH{uOx;X~<;E=P;zHak>!+(GwFd3<qFqPpkLqbe>nj@}MA28*`1`nteVDr(
zPqPn^LIZZ{rbH}aXL|FyPbRkbKB2=$@!LR&kL<S*O8n|Wg%xj=*vx(wy!?aecX#}&
z9*e3EU-UwBzPpkAU{w9XJ%6L>U*E^lXO{vRSCWc*>I)&|@AZY8NJR&0TgV#h#@dzy
zSic)?TT&o=;nF5nG6w$!XjU=7Lbzp&so2aG1r}A=K_&7bhbf-7AP|y-9g09t`bw`O
z3M}g62LS+m>VzIb?H3V$hA4XJo}`Vg*Jy$W*G23Lkf`+<5R}KRlUIURcMYFI7P4N~
zYe1pSzf=K;^?F3S)Fevx;b=oiL1=F{@D}XOosy%x)&_t2^VI|p>PTA5R(zI6qIcVD
zVLuXC*m@XR8=LE_svfp614C`wS}sIVA9J~+s2-76WF50=2?$@vzE%+gL}vgemQj)_
zaXOe$l8F2dDIRqbqRGw<(CLVD*Vy)tNY4&y^i+r>&ah?u^yewSkW}i_*u0WlBH{M5
zFZ$U{;!_B`ADMc#s0v_8!9omwi*_^LQAmMBmx&R4ssA7r`=O(pl11bHY{FT^47>>+
z&=a>}*=N<^jr9cP>8urXAZf8yKOYqxi;NDWzh%|w@v#VAMJiM+^i`0;<x-7{Es!}J
z5ig1pom01hHIP*-xLYaZ66WKP>1IVQN+HOS#qMuRaLG}jRgmB#=rQRB6I^n6x~>kW
zxJQ>ZraJeLuqXl{btLsE%fUKvc>~VPzDz>ZGI{1oB?#hIakHkS`OH<*h@ZJ~G2y1J
zMj_<~X<RrYJTm=cYR=VzrXfG`+coAU+r0#8>dS>HmGI?4#_W;~Sp_p5g4U8<^jJGy
z9?@ch;oS9z_;;-p?RHlIPW7e8$<TLR{rsU3zkjuKp@%m$Wcemr6eBKPi!RM<yCb`_
zO9`a^mM}Qm9eL4Y{Va{n)kip2-@l?+`GRbjWK{}w$>&U+k)FLWT`5`!$RdE%k+C#E
zSRE1H1~985V&)FcDhk9b{ia8Cj;=!Cpc1~6k)hBH69lf|h#CThYC@$_T+UiC+)~nO
z%Z|~N#CV0cE&#NmX3d3!aj1$-)D!M@d5S8LbWUtaQ6&~Q1g?<98fnW9Q#qdIDkFi@
zIuZ@HFp{>^qryO%j&@4mV2*?y6yDpb)Q${{cAVbbK9|_WDyjt3rr&jCAkE%Tk#W(S
zS6Pb8i#BP-AZ%$B*%obhq^i5zoT*WY3J<m6SJavQ);(=KI_?VJ(5@YkOi0Mtj!fh0
z>iJVwNM=RzE?Y1w;`IGOMDIIIdfwavl}9o%yMX>WB3XTf5=NR`*&45^MzS@&h<M$N
zW+>-o)mv1qr&;v^n>!*6e=#tt-m)Tg7_wWxVkDI&qYwn6)cf1J=+doMW=hCXWp}8;
zd!;m#!PuqBo-iD{RM`{<j(s7Dud&%x0{L}B4MF>+nokH=4T4>kDwCqQz<WLSP>iKi
zSrbNWmnv(bnU}i2QTe5uR8hCzBD(E;rOKKJ;LL@rg+yah#V8nFOLf64Z#Gr-#36Z&
zPRXEXw|js=QN7nx*%Q@!O_e=SO-sFHg9}+UFp3_LW?1G#)pk>5It1y`g{*}{3rDs?
zwPRFeJyh>PRn|jwCRnL5A6`|uupUf7TdM4Ws)$RKRZz#XHb=DM2U7Ue;S^BauKp!u
zU%lJZA!Ag8vZYGb8=74zy57+2!l<{1CY^JxXQ@)!uHjv(N<$fGT`F4I?60LtOV`IF
zYN`iUWfC<h>1rpCg5yV|-!xq%UD|GS+||ycq>ZsIagj}(CjDDu3%E*?`mIXq{M=t%
ze2S(?|9%m%wz5B+7CP8`u%$@{LkL@%RB*NL+N6Q&6G&-N!DfXmWR;w{ZR&zFu1R1^
zL*v%u-MvZY8i-w*bZ$+WIyvywdqbljoq1ZegwfcQY|_M4M?j@X6W80%lOnF7fG!PX
z{Hi!7Wo%q`L2aeGC;;1BDQ@}OX`Rs&2bo&ueHGz2OOwVf4#c+5*k#!|Zc^E=s&~@Z
zUqms&qWDyk!Y=da78=`xvZYC37w;EMuD<zTOOyI71IwyW2(EZLfJpz8-qY)nYBm3B
zX{grnL|B{rd>CL$lapWUsx|4_Vu!9t-v$lrxmCYUJN~4Da@D)^sFB&bG$3!O(M(}u
z7aI&+O7vAcFx05|Tnp70jz~9};msEZh&nf+GnwA0{-Cs_1=5wJcz5YimPTQhE@f#L
zcIlxj4Z|*7dT^WLaU-e0;xE3V2A}$e(t>YE*HxZylwk1&(53N;H-Ih&+NHrtmo|$8
zk_#FAd@3%Yx{AN#F2}d{OYU-fi@)UVN|FAQyENPZVwb*^n^D-M%jwMyarU8*OtywU
z1z*y;{G)VWcIddvQOynvccPg`){sPRjHWJq(WJj}RI{4#1!mXxE?o*Q4|iIQYIgO<
zjt+E%wbG>n!?Qp48q$G=U6-ievn8|`meu=^2BgsCbwrHI%6#w(rf0|}&Hj>yyi%2X
zyN-;pIp{K^7De`222QEjUblpyHDa|xn$xv6r6jXMCnI!Zb_{PwM`m)c;zqG#4csoH
zM3Z$+iKioK2#PMz@Qb1gS$n~d%6wG=RX96~>Y)s2!(2SG^>2@R<6_QRLch!FR&=}2
zjF0S9YqZ7Z{GBXQk(8A+r1!G+1L}Sqi5}J!@W`3=xr@L1A!YWeYbp(t{n-z>jf7XX
zh+k-+(owHssM1lUcP&FMqWJtn7ClI|?uRrNl&)n+Z<*7z4D?nqMe`O#$6XbBi=yL3
zc9$W|^^|BG(p+h3c=L`XD{0DAg!;8i`H9JDdMZAhrcUR}RDe49ymg`nUFfh(DMB;A
zmMKM;hSl<vNBJrwD`jXF*upXT5yi5Y(uQeRO>iE+Wv6-m^gc4>Q5tT(MU2-m3GoL-
z8C#y7HQuhLqgY?1ZlzicLNC*C?L#12rWC6gWXqId6)e5X(5q&UEmJ;dYK}!uxuHg;
zmnrpY7TGeTe^aAbbdjvSS@m|S-<$NWAnj$MeUrVEDHk+Vbp4b*HmJQ!>0_hX%am7|
z9K4<3l*aL!ZpDCIAXsYrk)W}Y_oOL}or=RmQz|<Znk*TIIHuHfQp6Q3(UAyd0pjS$
z*c5>!eJNTTT08k5ZYl_U&Pt<4@=KG=mMJeZ`D|@UZ9nyo=lR8B#Y`z>aO-7CC7UC*
zOjNRP>jmz(BhfdrP`|Ib%2L5!L>$~X3cBQjJ_z@+q)iP?-=gT2@#$ruPH#sTmelDM
z#hs*1Z*N3Pj_7S$W=Y4ITDGjvvBC<3B$m^yD8$N4?>#&ksnFZNj-@c~199InMq__u
z;db6WU|RAzZ$%@PoX&v0U&t7aO_(L!dwW+|;fWglUY7Li{RAnNl<lj=wLHq(K?>lk
zN2HrI`re-9AZ>dqEqvF@ruVi;mYmGnR>_i+d235pp_N@_Ti)dD?O@59ydAYzIzx^f
z?h26)lJ&6HL2^UDYBV-vDcpN2Y20^-uVMLM**?s{MaQu+H<21Q+w4^USRa`duvGi)
zpy!fuzh%fQbi3-;g@{gNe!;Np=Pc=U<LAqgUcVg%t@j=6=uf?+*lz_s>g@vR1U~95
zEly?gk7lnoYW$XwRBx$qbJW&bYW!6RJux<)p;sP#WU-p-EiHb#RP!AgcrE!l6}Z<5
zaNLDxKj&R({cP7u6u1?**D?cc1ud|6%sIMSCbzAurDby4%8FaY!dHM?%k;KYi5paT
zM-+W?fo<wAui<A^I_Kik&^cdg4Gmzc!DaH=3N-6gJHFAq?&mbR*W-h$H$~A6h_3<O
zS_Z^duv*K2_zG5QEmyFqY-P)U_;=y@MmuqlMilyREtOKgN6dKhL=8rye~#f)FSNmM
zs@K_MJXIQ|2E1!a^xSxVTf%cEBdmUDlMz<okSg%5kLdhh|6}olP&HoY_zJXZE!RQ^
z+I6i}ylNNApm_CA1%A1VJxuJ&5c--pja<gi*HG4Lx!`%a>3+mfD~W8&5TKgUY2h$b
z;9bjz`3ib#8QxO^y|v7BTS0Fv;P87HfZtle!&gk5WoFx&sDN%}+X_Md61DAhM3c+(
zuyR_w!Z6s5gy$3{+`B{yywDN=z6z~1mq!#jb^(B|2ZOatYFkOiT+`<v6?Up+xO)Ys
zwdV9~WBsl<xosHSi`;-SK8l~uss2;+eR`7!>weAQiR<*%yG8;WvZnWq6yNaz5MK`_
zYZ(x~+cBi!dFqU4$ilDG#8@V}tsu9SYM|Hfsh08Z6~AkNhp*w9T}Pm2hr(UP!&f-0
zmg#eAI=6_wV!wEB@b$QyTcE*C2BU+PO3jib)ccXdSen0NoZ>a3qbo+@O$Bh*G7i21
z?OL<?rE}P}%$!?6b}fMLHQ(oN#vaJ7BVp`B4AujLui(0tf$$Yr*O~&G)ZnsOM#fh_
zT?;bZ{S}g(z5vVbc8+V*o5T={dy^QV_nDkDMDH_ETjxk(7365BCz&y_>wx6iZE0nY
zTua#bN;dy8c799F0HaaP8`o|ksMa$2y}~N6W^}rK{_<7>Bf)|~w^9UYL1?|#0&uA{
zyeXVu+%jan0+w3F<W|s9%b47nVa8a7tyjQO%Otrqpi;{mxfP_;5^lFb3$cceMQX$^
z7s%b+G~$#;qh^gk-IDX+2vl1$;o@cH+<Hha*6`j!MXhC6Z3Wb{#_%<0$uTaPXX1w<
zBQ>vR@pE+I=$<!};*hJdC3}k={`@ICwhobQr7+nV&Amb$4niNb+)Q)BU9KgRp#iv+
zaQrg<wi2^nLyk@@C`{nDSBPSKI-sp(U*b&x1k(~cw}N0=!&^cj?`aM81kg*%z{v``
z)EfTe<4|J@_~N0TS)(WbR^g~wrrWI)z+0x<trW>y1K*{VavHqNLdatc+ZqKOIts0`
z^0FTxv~%`6qCZt5Aw;qGvhP~?!ZNLWQzgMvj;fA?;Z}W1iAifrbn@Fmp$@^qDkMj1
zB#$rD=P**ELY}n7?e~L59qbRB;H_ahgJZrUi7cvmjsmwJ`6e-fo7P#feR+f^)2`#2
zT8KWbzC5>~PP_LQ;7P07IRTyYRdVuFKBCi%fX3?6k4A;|=|{)DaU{2X(@tAH7|dKB
z(P^P8yEle{dh9ks3hJ?AbJY7f4L%#rtXJ3JYXw@gCA{>C=Igd6DvTWqMDZ3(E>e4O
z3Cp6Q_Bs*Q8t3(^`xLfvsK0u1Ur>C87FTH6R<|nymD}o^+|(Kk774JUE#bK+zPI3f
z_r3bD0gqbUW(TOG)$PjwN?Kj$uL>q<b?+aQGuYMT%v2H=y5b`hPP~tVRt&~FPOYaU
zSFTouQ{0itc)Z<IG;8;E0~}?+?Ry=`{sIkft$>i0@vRl`%QClbr9ATLj-6C6Gs|?p
z^?;I=$$l%Cq$RT73L<F>^lWM9p8Rk$boXWyaHQ3f2i_T`eV#xIt)7SvRk$9PA*vM^
z((1`y02;ZASYS(HOwaao;7nVfMTbfTv04E!Ekjl-{FYmyM^Ei6x1Sx}ukot2qS%}K
zB2Zh)Xw?eHX$h=afjKR62%lLoe{ikw*D`<bmYe}LTRSy$z1f2+<;<5Ege$1F1%q$}
z__o`;X~1zSP#+hfGe8GifJ3dOR*cRY7)YqqbTnNXpq*tt;mRfK#tqfph944P>(#u?
zHN4^Gcx?r!xEfnlU>R5Qjs@OvHG4!2&EACZzqTm)>-bAUwKwlst(+F~*zk_cCtMq6
zyQ^tS0u8mAgDnAuTFrYDP^i`H_JD+10a3jW#f$cqbdXTXVAKi@YBfh!0KKk<Q@FN$
ziQ_5YW|sh}724xvM&SwocbQRmOG0CqQFx0++*s3#4PXpwWuiY4TCtFwBvg4@OZ>w1
zyv=2H;R*_BnO?X8f?7?``l|whS}nUPxYRAXD`5n*<Y~aCZb^@pQ*9FBEgEr=elfX3
zYYekM1jO}xUF(6cRzARG3~S{hT|ihX0IJn&7=fQ!!n9sTl;g%4A(le(W(0g{8PQrv
zmRePN$yLvWx2jIAD_i2K^L5ebUiDrA_J39HC8A_s2Bp?uZC};9Nyi!xmvCjDU)7Eh
zx?l+}8ltm$O(tA>wAf9^o>-<9uB2Ej5UaIwUcAgKTuIhgVivA-eRW(M%hEO;+%+U&
z2_Afb1%d?#?oQAk3oPyyJdoh-f#49_U4y&3Yj6wh-;$i1d+t5&H}l)s?ds~T?y8#k
z<9TMgVcTXc&Jb=|l-mdZlYv4dMCs)o`N=@`)4YW-FK_vJvQX&7X(ALye&5w07-j@*
z3P!zfM;<K;Mb%x1@l6qb`U!k={q{$Ch;Y7Z5I1Nt59CvaUu~UV=~QO~|9LMDyl$Gs
z)du9Vrjpy$FhVYh=&#JXz{hP;J^SiIP@h*F9m-V94=j2P)<J_l5H#7Rd-6>mQu{md
z76q?|i5vaopBqf<J^B3d;iW&PnHt)wk|AQY0p~)HwKYbSZxcgj+&q!8i_AGPEk&8>
z&x|ROjE^kQFR#Q+I$-4JOEgmWxub(VR0ca2wp6N~l@7g;AU)FfZnaOE{9|*oLzZy3
zP-V~1d;a<rcM36PKS6p=n7)OAno&YY4W_;GyNYuuTE|i(bYacR&D7Q)&ad7`%!@8a
zPa7_mx7O^7R}GT_)$Vad0>4lDqm)cWw0}X!s|*e<{0QS*N&@d__MB-A)qEGS@9iLv
zI%=%OQJ5LPWJfxM6SsB#ZT+KdA;NprW6X3{@%(8;5|gD?@)1EW;~0+Gn|JwKdqRvk
zD$-m!D{z{h8dZH%(Z<a%UX_5mcL|l5B0f={xD)VjBh18Zf8IrDD_k9bX`g%*n)bFa
zpRZGht<EU!3Cz^1bU?26k_OcWSjKFfO5|511uA<({WoJ}^zgK1Qt@Urys<9+)$0XF
z^}z9`bGWKh8{Jiu{7-~(^SKIubQ(31=`Pm?8A}0@jQm%KpDNL#3tLK5S$7o>{VD?o
z?Tpw<D5>=f6mZmrRr;jc9aiN@VKf6Ynb&mb$5}MfNuS`nsagUGYwOU@*(7X99pg>C
zll#c=W}+VKW{${SX}k62NRb|E2}hS3Yw6e|ea|Yc{Bz9RzATJ--}@O<byKN$_6kVV
zh;_Ik{hT2TO{MKc8tR)|aO~>q8_2drnq~QbUqIbJV7WB#YuuH8HSMQqzVb8+jKsnu
zCPqCYdX~JH<XkQ8Y>k;x&CoK{su`Qmx>)k^7`*ZrlzyEU;mVl&P0naKlWA13Da&1I
zHdoCBcjSDvs<>9cl~@)Sd*kyJbY%^CJ6t>2r)nVUCR^eF6RA~kJ8%NpGgnJk&JB5c
zsZ}E5chezWuI35bHLcy1WgiPti&W3gu{Rs0a5$Dsjx(Hxk}#Re$)-}ZG-t$^l-0Fo
zTv%dW7ieZ0r(q2wXnCtyNbu$+HFHn}s*oyba<l1*j;jt%sFhiLU%3G$Rdrt7Rz?ax
zPg-F<sw9}605(*?)oJL<6v3cOwk2x8Ta<|8oFzmUZeUd}#U9<gfvIVa*CL`Fh-vuj
z)u16!*!UD9y6`<~m9L7=OBvb7d;nLKztxlQE=hh&e&_rcH)8ZU)2t$^C+UST1*a<(
zT0Ma&dHsDXlTVey`jmSeV2d<+mL6JJ34$Ha(m&i!V^x_}PiUW7$kXZi51z+7>w;0Q
zjBG@=R?+lHgzisEh>U?~VjAR3w>3}6nISlJ6)_yR9TQYag%d=uZZ9<paa<z5CY$?i
zDYkib#tCiJiaaNy&O>K30>@p6E@82p9gCfdF+NUsYTfa)yEx|O(hdzP|JAeoP*wB%
z{mu{$Q02n2lY;04JbXLJ1Jp!rDhH}(Gts;#*r${qh(i<)G&5b0JCY*FLdm|Y+q0u~
z7Dt<ipff|hK%7Dd!$jnA=GGoB2BIo7c9kH#%263JtRFfao3y5DI;32Mj0ys?r48-V
z4Rf0^@ue<OgY`88t0qnYjC_dC-M(n&dS7UXwu9cJi3#1D-cELoA=Kc0I(wb&h){>J
zxWlJIl+59Z<v@1liq(wbmy8u+2XF1*<U}T?vOLM?U*yo7JY4PMIf>AFdQg$RJInu+
z>ze~w{i2uP!p|2Ptu0zk?%EE710goU2qASHv9pS|Y;8oq9o5?L&X?Lqsg^w+Md?@=
zspoZ#9F*fP(cFg`tmU(5O<M&MylYXAsE~eCDaco&ds9ze`?%MlAcB#8Fb0UM6vr=^
zKotbd&#+lI1+&lr7Cw^Da))RwI$*)4RpfF?bG+u&r0lHPd=p*X2+Iidw{iEIqS26x
zeKj9TcJT`Dm^v$F#M2BC=<Xj`P1<&h17MRj#`iccO2*j>Dqv%0artN)hH8_{#zwhh
z_^9~<d#r_21~-^VzztLj&D>8vJT;jW%9mS{CJpqIitidu9%C6p((1Lc2G*?546)U$
zY|0{W-ip$EBrTvuPlD+DAQT<eYLgQ1p|f*fzV|<tT~j1wSD#|XbO@r3OBU1XlxdSE
z&0dUXr+klPiK4q&O6c@u@V(q%*4P4L0687<2#X3$L)MK{ds4Dg7ZoGJBIKJXJPQY+
ziiLX5nEC{D!?@P<cizTA58Dd;V_4tBY(vZG3%u@ag7hu-jVB{^+yF+R*GwNM;<l=V
zk{F2`^1iM4c@Q`?cxcS9slIEOxx>WZQj4u$Y^_ZE6lE#cAZNu^qB5{yfrModS!)A*
z(J(g{v3H^$Y)0PoA#u2O|9l;nuU<DN_lXly`0etbn)8S7<b%Z~l&vnhw-6reT<*dt
zZ*iG6G16y>n&}RBc{WnKDk~ob>GtK;-^;FWRb_UnR1Dh79g=X{9{)J~D%hYedx-7J
z9_oAlsWZvW)o7Ar1b?x_yDIUAmL;Glw7oij+~o_5EeE{5>+|nA4oC?gY_&1KnCOvl
zqC+hXAdy<T>8U~{T{wh(oBedY9eajNQr~Nl&Cz_fqLNc7-b_{#qrLyf_y~l4V{Ft|
z0$}xYaz+_q?z3y|9h6w^O6jMm@etRGP9TukiBHm6NyREw1D6F9c0`l}e+o1%1qy}{
zD4c8G9m54Db{c}b6vhlYF^I?6SIY<#4K|hSmd0J5dyORp;(^lJ#ab^rAvTF~v?-jM
z`z~U5gPLq1FOxvS0a|jyiTl1)#bcAfsYo(X^DVps5I(FQki^(a0rwj$wd<;f8@Y!y
zO;pUlX#exXBwGGD&+B?CPtW}cH&3R!`v-xzhdu%Al=IDIPqyZ)Hlmx_3Cyl_kkR#d
zj%UMt$I`>V9p}ZSp6B(=Zu9L#%Kht!W3`7<&-;VohuxI>{j=hG`+d2beV6;-*M%O3
z^;7p(Lzm}d4+GT?XSJ3~eD@d44{I@8&63-0<`0*Q4nN`XU=I1}1g2NqP+1=e+C0w=
zp_`oF?+V-vZEdaVfY;AmR*iiQS<SAvngw=pB|p~X)ay*i9$xu{zCg`NaXJ-vsQ26t
zo#ab%kTZN&-+f~2w~$gRBd}*IVOX4(;%AVkyS>%fQY280aDS#-eXjPfNp`<7cTlGG
zee{*M`_Rs2n5sZf*+b2cURhmVEAK-Zlc!~T)7{c;H76CAQ-Si54KE^v;k$qtbyWZ-
z|Dgr57e@2tvF6Q}ow)P*<h#32xWf5jhM#khwVIA{o)4`hfjU#*;ItH7!nb|JeU`kR
zQ*<23PEH+2d<2}{z2CVbwA9=4+^3o+y90HG=?Yz;>9h_UADKC8f2I>4BU^u4j5bhq
zaf0@7bK6~Sz;i3W#p9u!_hA^%Mk>W=<@8e5jbx7VCOIzRAu`UJ?fz-n!bwWV5hY1u
zan$mV7E;MwZNK<MiVl*}rd>iVkEbgM74I40_<cv5b&E`MIenI{=MyxgLlUiAPebeV
zGv2t38;-iA#^9vhP2gtq!(N$$1+Fgj_mo=n3`whH*0OtU(XP!z_EB`Hi~D1>qy76c
zPL>sQSEQ*MG7>HNVkyka!yEyD%IFldZ{BxfQnsGZU5Qd|t^)c#6a|bv%t~8zUXT@^
zS$TffAbVEeERTEZ_Wt8u!zM6i_wE#!$~6S0xQoaU{BWaX^kN=5YLNCx@i}vocj<~x
z^9j<u&vQ?h31=kZy-v9&VwXp?{Z9e}8iN6sb_p4)0`=x<S+kS5%#ZUH?Z9vJ&hhDG
zZuC~_|Ka5LrMU%Wr_qhGM(4hJ*{g>?E&=U4C(hmK=edC4v7>tR*FNdCv#~y|wx6U&
z36sT*-tNxFJWDOQ>rZ$wgQ&KRk;rGh7Ne0#+;5UPlBR>CG|%kZAGo3($W%0ZoDU`@
z;<j==O0V^e58wK&?6byrEG`dqT~s%hMS%Sqb+p|BJYKgd#a-^gIR|*?W!BqYTnkg&
zWo`5ZY<y_sPfrQ02){pSI>otb73Z9@k@7Umydx6T_|DK!cY}LppP8xDSX{AA)ag=2
z@G#7^SsaW97^|-i+saupU)OG8g7&VLNu#B8f6H`A|3e3U<njReKd`IbyAbLt%dz{<
zR?W2^=63|N9<V--vihTfEe-ALZNYjLkH4(+O;I@jEP%&v0002u27);L$l3mq^YT7c
zF^f3ciz(Ub*@FSU1&=a47H9#$EG!6M1uz@vL9hJ$kIKKV%%WD7_W#f}Vq{@t0f3<0
zD*mMe)%$A@z`u<Fn3Y|u!2o7?J!3F{3c&iyxV)Y%7}^)>pSH|0U_*$Wkd-q)6Dnc>
zaBy=2SfQ(n1GIms3quV<_3Z%ce>V`bwQ{ij$6$UN`6Yd90zH_Opr&p0EbXixjTyN7
z5laB<Z5_aWO2SaBw_rzz0a#H?=u!CBTou7~Rt~lXU_0n5zK;|9&(t`f<wyTMdP*8>
zX>4x-;QD)5q7ZX?uq}XD)Ew&Bw_pP+!(W#EQe*{i0=Yqtef<?O=cIl04{rDqjRM9V
zoBezJdj>}3q(7%ANh7JSUZ9|$ASkP1Z>R+0hQBxX*zQjo_dYxa-!~Hb4LqDen^}w(
zF+&IrIjm_Vz@K~~c9~I4BhO2pG{RNETw3<}3x@jaP3gnp(4E^s|5vt6caNdN!z8L`
z?DPmQg1_f=0R&7|xNyxQ6pV!&ku96TIVJZZ0QydTIvKfgbSxjQ*<h**8_KbM@}A3O
zsb7{zZwq#;ZU=V{+lxfi)uVX_+#Am@i(0ml@1@%BB*Zhl&(=xGe=x;Yw%(&oKGAEu
zES(w4!LgnHd={e4oWNlrNTNwM^!>V8{UVO<UVesUqgZ{9Km<8OkW%rLsXAS;uqgp9
zUPbw#|Lyb2<1AbX60y12C%74fjfH${t<vo90Y>_C6v-Rdb1n+ww1Za7u3EAb(b2<p
zqlys3BE16|O-fM|w!yFHas$v^XQ^YwOSOrz2pnkP6oruU*K$hN0dk0I-{7Aiw6OYk
z75Q@c<tUp@`O8(Y){k-V6bUjDPc75dcuKOBIyG}-mh8u7?7uTwd=qJtwjX=W;H2}T
zCO`@QW3oKDM|ue-M)odcaxk^uIu0<UfLfArU+Q|eDO`$XxPIS>hk8u$8bKR@J~zW3
zKbIY+Y{1+qGQp7ghZh6oE8F(%F`Bv;%ie=0!?OvEn!YB-IQS$~nsr0vwjO?&k!8y;
zt0BX$#(hye-$Gx!&m}d~?QSNAG&W4uQ!tJa3AW(v@2+vWElbF6uxHq52~(D>qLim=
z6g(3-*0JFHutCl#dgGT*G#etvOu91lw#h`EF(4(DWk5HwTO21OM+Zx4Z-Iu2=BttM
z#t-zJvA7?n_>r!Cl7kl0y$vr&J{3dPX2*_u!Np&`yztKIh1FuM(?hle&)1a8A8Q*l
zr~+B%#(;2Z`vtNlRD@9U{=D4#nQZNozFs1li<!-fhpOWqKEf1^ZyBZCIbr5#*>Ahr
zg`$VngX5FRaXN#3h>CTWe~k!#i!PI%SR4myo79n7-J<{Vo>WUHzOU-MdQr$j-eCWo
zTExl=zhh?ndqj&PlJ4fLssagfsGAw|gDxAUdrkas2nY1l87>B>PS$Dkdkr?PW1|AM
zHdy-%;%*$H7D}n}n7uk<qNI?PL?2Yp1Eo!3P8~NdZLjUmE65tPj-!;&2rFf3-|}S~
zgb}Lk?(S}moe3NBaT<9H_(#w@G19(13v-I?2x#^_yJh_;KwzOv@jcZE!8aa%RgR7_
za~9W-EF2+^)MD+a7GgIA)pv5geKDT7;*%-DA6VS8n{Y%?fk-royfon!FVlQN37CgJ
zFJ>6<?C!j~+R7ezp0gXUffr+<HbHBZeEL%2J2Lk=HTjL}#VqZ_X5f<)PEhaG+n%%p
zt(sX&t-;JjsxfP0<60SE$)1<lf|0J8wG~EvlZBUab!R+zfo4nYG(`$An?b5JxJvW`
zole*Tm;ts5<gX9|KQUznZH*BQRR{K%)6r8i)lqXPmP+JFXeH*F`PL+52h}{wUJxt@
z8%x_xTo`w-@D*0WNI#Lh%u*6C=X&la6XQLt)t^Ng>&ss8L~|P7UP?MvTYcljnplS>
zdRl)!FWccKiVSVys@-kZ1kVxrK41hra0T=ZQ7m(^Pme3|8Fwh_?7}QUm$E}1NGac*
z!Oq;ehQsIW)_f6<gBtTr47$;gPNLYwv_TSU5q_j}6qUfq3A<+A)8WW7!w-QJ3ke55
zzkHOy9EbqEqb5t=*r`1y59KxfN<Y?+i~x~G6$(dmk;i-`IEU;I?HFeeY!^&#LKyyG
zi*J;&+xW_@j8`JTyk4$R?n|az8PRJr?JFZX#uy`$FfKA1f-gZ9Xh~>VDu$JHin@?u
zTV?KiE#_}uPG!zDj0^K+i^~sf4s1B$55H{oTb_`!TOVZdS@I{1n#UMPky4wx*|r(1
zp_Sovlu(?)UbjS$95UrS*H&nuwzu@{5})??oOZ|bR(r?Z@JQA&os9)AUf-Q70~b*#
z@|)$V_<%Bpsk^;QDP10<oQ{IsPr-<yd3E$G(lBbDb9}pOey#+_R-k@G-O<Z;znC$D
z{&rJGAa&fcNVCpe$3QwrPp2@<k)HIMjQ$0kQiY<$3+?tFbas_FGq(GPRmprgy!nM=
zjw5Q*%+s>q&xE6HPgw?4WWr#XFY;JjpPsJ3a%f-hd>Z8??tem8Yx?!;HZi=@PlX+I
zzAakHC`g(z@<mz`s)BCRgb?2n>s+Z9lY@CSX$)V5EX2CukZW_x(NLXLNK%pRUjDw|
zEwAM6kpIWkWs>VU=Ua4{3`jxEuGZ9Cg+y>{r(}daW})bFd#6-Pelc`~?&(yeSWrX`
zF@{eVLhXP_{jduxm3<{2eUyfN@=qy!3PI)1A=C1oek_yweMe5G#{T$J(MSKAV5Rgz
zQJ#nwi@wOK1os(-+N@omfcBD2;zgysM>sZdA0b|pArfC%5w_B2N#iJ2^$|m@bJ^;V
zfQYfcFKTmPRml}E`<rh4_i=C;)8T3LbBKrr&owSdX3#pRgSV?UHh%m_d!i<ae)OHc
zdgiB*8U_8L=Ii7W7NdQU{zRV}5o|0H!c%X_7KshXoLbe4&wMhDpG{A;@F+=Z$IQId
zbcPnU4#ehUIG=Vl%`8?o)VTO2Sh&6{eDldK^BGO#=;s3q*PlHy0#>F^uV(SAnx&R<
zo@8ljk5yTDmdk3~YHv-9ZmYeo7HNBysYf@uOkPSH5fu=ZM^L3Qe}lR);OI)5H?v@<
zyBl;S2`UZ=j+!r0XkrO}fzd^QCe7@-wm)Irf{~38MjwRM;g0P@6^cdEwrvfmadKuj
z%rTq>j(g0SLzlacHTq!Ol_z2+Z@SoSP5EL^B=L^$*2ox#ib2wkao@b6`bE6U?e}dm
z-d9C|YwU$5czNs+JZcjlo~$R?O)hT3sg2urTiAIc$gdS|SGMeK&MnKGUmfxf4b9`D
zfoglQzp7*J_kJ=d*6Z*Y{9^F^tdLa>B`Sh=kbI+HE8Y5>AuIic;khJ{zshR7vzYRz
zpId_oE>TBLdO&D4D|>8c5#B|Rg?@ca%H+tC;{}q*W5H;v<UK(RH$!ojr-}PamE67c
zlN0ziTI@FUhk<2%Rq;Hm=henwZH&(?Xy0_#rZ@WUI*$8Rg^#^#QN@g`)Vs!k%$c%6
zR5{CO^rTEpw|nKxnz_3PX~m5E5_R=*Odb{{cID9{KWB^?<1;@<We2paYPw;`(a(g8
z%LD6gc%O+i=7bOVRCDb`Dy76@TPabAe2EXo77!X+!;6no9)9&B_efQQ<4Xbeuwju*
z$keH?y5BshncXXp+@V5ltXxH<?wkG14ee@VVK?`g%j>cmBuDP%H(W}sE_#QekwOp!
z>sYyyZT=e=_COC;fg2Wwc#t%i(bQdg*a(%1)WjGCke6ifw0rz=+?U-`L*G`?Pc=<#
zn*Nz3S{jwaq~Y_uWf+>87B3TjZ}p>6E)FUR3+Gw6(b#N8Da|-S$@)k_KWz5Tt{>dS
z@e;84QF<jfQxMpOKiVN}q;Iw+qSWW8s_@m=T#h79c?g_!8)S85GwR+9e_j5%`EdGW
z)ZP4YaeUmzXF2|@@im%?<~a>jV?vaY^H9yL7ro2aPmAKti}o<litp_0On5^A5ul!N
zl%;j8{K%YnPzuQRx_jSpx5ijKRgPh}*)n`ZJyec*Aq86@WEoBbhttI=3<9d!<NLYW
z$hi7!c1gr0H08i;wKrEu?Y+!qSjW3#a+#bSLJXQC4<MTx(hV@)l&!X(Kq;0xKA4Tp
z4Y$$;#p_lmh8tXlk*i+^_9yndr@Afq(u&z;J!S$g6*S~Z*-JS=NSF0fdG0-399G!^
z)k2ThEVTrd)Jf)*n_oqs+8jvoi$#ir4vBJ6Zz*=6H3mBss-lZ7w{{P>mRD_10k~hi
zhN7oDg!26!fL~5>s|V(1E-&`xxFxC8$gP@cRdvZPBU_YT^mdAV@WqOeI^wQxe_+u4
zXmz!;?g72Yrf7kQ{zQ1D)XC0rv!d_R7~1`<>dKbZa_aLkue39GhNKRiF!n|WdIPA^
zl9VF}?fbr{bB*54cjo$h{{-Q~E#+kkCJbSE{;vAK(1<HK$tzbItmvTzU!=_}I^~2>
zHR(oL?zaVb<4Oh?lE4>Cg02KO-=EsHEckUO$c3c26>JLO+TPEmo;j&@G&>NB-=}J=
zLwf<Br+g}t-ju>a%&b9{{F(|uUy4ItN``ndvM2hzt*`Vm0!Q4yXyK;rWYKP&i4Tod
z7A=dKXChr<mjG6BkXIjoh^W;g5a*OkEh{z0uVPp=mq6nknpH$h-DRh9E^_H6(ot&E
zX-znS9`a9DaV#SmBN0i5{3<J5zks|o&M?o5XfyS-3^FCABDa@y?chW?gD$I2dQWs+
zkB8HUbYIglnoAx~G~wzls!=xG_T{V&tq8NfG@5quDiCa%^u3aNNn&Wog6*f3)tz>E
zPkwQISxLtO%-HMM=C>*v%3AGt5q443J}r&r&#+!WTxUauKE+^M7ZBjJvDLG+HAz6@
zMkT$I99%?ZV*umhTVb>?n7li=KTGGxq$^kV;4E9<xij;8b+*!MRbyf6j6T+Cy2P!+
zbvt>sw|91cAf__vE~HQAVfo`!9LMzsvV4BK?a_oC1N+(ejlNC&mwc*7?bm8;vhnP&
z&Bq99Xf}~qnO|fx$F|_Em97iyrC;wJt__`Hoi!&;*VoToH+%bTHC7Pc#AzLdwcIxx
z-gsW7)pWhnkg6WGxcpSq+;!w0*A#U3vpHeALyJ6#B~zi*HuKD>t9gcg^(OM>dg{tO
z=o9g!a2S0O&wcKIozgp+Nl*53>vtU)3l9PhYiZn>0jY;CSI46m?TIEOOI<Lld^1JM
zB6+<T#Z1t2Hf{{&m~8!$S|egI5qC(^3?x8RxVE39)?YCKZmdIichX#($H>j$=DH5R
zGJ9;3l1SyYlf8lOxCcJPT^cr_DZOZ*sKpV$6UXBd>+KP|d{(x?QvZ>=hug%@)fUG|
zuf_u{m)gOQb#yhYyhjmIYR_EtY_l+vaA{_GDNxlFHJ3+REqrX<<^8BhS;$w>CXH@R
zLqvRWDV%3zS&EqtTtyRsCuS1d6u0aX{^8g9q>5o5_=pGBQUwH_dlaX}F;XLD%8L4{
zL|PL`>DO=J%raR4$Zb(Q(CwBf>LRI17tGmn4<cajqfE8xCle{+6dN!;Ep<%pjJl~x
z@AhmKsJmcKd33EJU(C}i1U-w1Y>WTVhxC&@xXAZa=J-wsMPaXctoMlxA{fP1rrW%m
zoUODXevc|7Q(!#YREw^^m^a?@BU^PzSj493b;T(L#E(b(DIGXYVKO#j9NYFy1UGy@
zq=!d_AZjoj1bLCI<H1r-|H0!y@r*RE*?XOni}3nOUHwT;iMq~oi#rB(2}jAB(Jq1U
zE1L(8wVyecq;;YTHtrJ&9Zv7(+Ue9QOs9kQGY*h1-hBZb!Q6M^b6(~Q9TkIAX)v@c
zc-boiP$*JQ-;9x-><S6kEd1n<*s|GHGN#t5KW;qN+jKTgb0y4IrP*h-g>KM?^SR_@
zk^8hwSox9bjlfshiebfVUb>aWRtQ@5Q)x0Ovm^ZRAmy^QbyexM>8k@wVkt~p&Y8a1
zo@Xw+bek`1!_TP7uf#HOiWzCt8M(<fBC2f;#JH-TjwSBi%zNjeqwIVRPK9fc6xfw;
z9-wK!piA~a!I=ahjOig1IUxJ+OW$DkS~uLe_%>9B6EX0durj^@^jF{KW7-iQB4#ot
zcz>fIzixal;q8(oep^Njc~^471N;2Nr6x?%fR7o+Q3zfWp|whj=aXf6n%hdGB826>
ziRu$(M6DukX4BM0`1?^<Pr{=s`5JaOe!L?Hp;iM+gl>U18rM<lTdoHQB!MN^6vLJ-
zxO>WFEyCLoc+YR%<#7DAZJvzYY@e4e;P~5D$e6sxES!$Vq*C{pxX$X;JtSKW^;fFl
z__2?gyq1tn3caHkk8d-*Vx66t(PWXisz%ql+>T@^pAlHUZ7D`<U|eQ|ZN@#y_R>Y=
zVptCM`bf>LhTvT8l?~m2Im!$ECg{>z*!n%m+=HmsAv3CD+dbd|1<VaXgARNMoDSYF
zV3`Q+Jho*h`Do`WjAtdn`FQ=+SD5ko6#~lZ7|dzLWiV_#!k)cwve$EF?yFD+=N=U1
z*f+?ZeNErjds%4iyM6I0bet~ZPPC%)9;ifGdWKPn)R6l91nz6T&Cw>pIM;hT*;!?H
zQckX`PUY!kUt^y4cXh&Ujb08DB5n)h>eaz20(i?4BJ$4-hY*$_ux3-}%VvlLBry3A
z0~6K46R(ohT;9iE#!Sn<gCn5L4TLFRUonPLW#GI*h3%7ZmTUpSN+BZDd)67EJmh*&
zNiFx_s%tH81i_bxw+O+aC9y1Fp0GO$wajDE9(r~0K-VOVMu}%!7C_*QMGixahlDP(
z(X>*)88LW&E>(QBOb$y0myPBu-%^n#KM#vFohIIL2bYaXo0NXsiW#5&-92LDwuvF0
z;XUpFF9ZSKS??vsWjk%n6#PYS$nphp_tc6dES`tq5el4#VT&{DT8VLzSE&IyKM1a~
zo%@m)UX*8<3D#+{<=fL5;TG{+0kRob3e4~OYXI8!HC}U;4kvTG*1L>M9{Hq}BtMp`
z5$d&B`eB6;*HMUp(`}#aTb8vxVx7OS3>~z?=pNCN=QZR3n57PuBcP9yvk7k|V0I7d
zz445}Vo7aAy(>$#a`n1k^gd<hl*4+HNUEp=$9v`|j`AkOYw)H9kSbi}MG4!e9q#W&
zUH4rV4&^y^7(;v9n<RKQTEP^rX-t0-*b(&rLTnYdMtQ|Xgtx1i-6lt<N67xz%bl>6
zu+%?ILtzY1Y9w3eTJ*x!F<~8_S%e{Idl`AXYWdV=4u_A`P1RBom4@gHt0@TBA=TQ!
z8i#r51saKrksE7zAbRn$S*E4gef1u5)=l2(-(d11viTR7%mD<k{egG6|BZpNKH|2&
zfMDkT3k3Zq=BXXoXX(p=E^={&%A6B~Qw*DpE0mW_O6dNrf(#}gO`Phj_q(Hu%C!;Y
z9XPkhc{A;f0Hy&ugB*->r{*m}PGV{^-lDz<Gv60oJ$aOfY}@-)sGfXIvLc3-7Y=Q;
zrETeXsOea*wK$vGR(crt_-SGM7aIfxW^gcd<5a6=^X&w<G8O=;4j4#JOfN=jrz}PN
zeXgd7U#C>viB}19Y#v~bmdH{@>Yx`DjcxJpr01>Hd@?0A^_#rqkzy-7{dj-Skf$g-
z%9Wj-w}&5(YD1mGn$t>W_c94Pr_|YCk!Uc!ud7Abf2h@XRqJ|lzB&3U)dhpyN>U9r
zQ@ot;`&ZCEJH6bZ((IYB9oZCI3TiTD@<ls0JvJQ-j)d-7ZUUS%jEq9no!xi5ymlVE
zsNKrHV2?Z^Ze?&rjq14hU=w7ZcIg3&*p<=p?{NJJ!e8-XV`KRfF4jk&{SRjS8!3Op
z^525(3~V9R_Exr!!1phBUslfoiq(s0NK3tyrGE=H)l+p)f<owj*Nf^|K+IhLw7;tW
zk9BmvE6w$cp;$TaZ%v`!Xg(t=3y=lC$PNMmSUI`bpr}3@@Gn$f!d}lDVjyT~Yz_vn
z{Awp?XYfc1a09u16(7g<SY`yWar_bp>sgC~A;u<9<^bBwFOiZx*g_S+^}GFJLHtkQ
zafZ-L1Oow&i2Xki{71^--`@D$orAvpFS<e*$`L$z>X%eV&kp>H{P_QQ24ZVxFKnV`
z`^N#&dViH!fxiil|8_UvS3rK>EFzXrk^o|93}9A+SPEL&LH-DSSyqD>+MC!xSrInY
z$65T}CmV?6uX+$02=KojC`AL6{<;3&JwO>3&PU$p_X*<o^P7|FKUP7|<l<y|%%uPO
z1hGA`Gf+FMe_H?619JYS4;BDBbm|<?jCdT+BeU|z^*|-i&o8P6O4(ScSVA6o6Tss`
z=AU8vcM?BxO22bc3S#)^rAOLH@o&<|;gMqc2Xn*vPgY9a*2>Vq0Ls<S8t6f6tpKb{
ztQ<_xDbkwQ+grb8hSFb9sj;n|wF$()j>*c_nC^F?3q!d!dx(|g+ehk*_U&sR3lPY{
z1>|C31%jX}gR%f=SXk)(Y4kt5+aD@SSPz={R>r>q{A&t-5n=z~n4E3FMyM<RR(4dD
zzYhR3ENmPABfxJNCkV&}b>HIwu>4B~;%4Xmw~UPo>bd{YgBBix^j|U%HyZ~uQ2!<4
z<luw`=D%eiZcY|xWd28w1q4m8|CMq5TaTUl-!^`w!+*C00lEKoe4HTm$N2rxv$xfQ
z-rKgnSU4q!EBMh@j}I|LD=TQwe{*(^WeH0oXl#Gw#c$qC&({8zccJ}3xlt-A5jj!R
F{|7S2x0L_@

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error-dirty_hack.pdf
deleted file mode 100644
index 2b6a6085f88d032e3807c9c697596e17be2cad0d..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67390
zcmV)!K#;#BP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGb;Uf|AyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<Lx%w65`;KopSo?kJD9ZO8eWdbT9Yy&I
z%V7T20_XcQc)nkUzpx56+b?2Pl<%i_J--NAQNHi^%#Vd<``b?Kt+ISBeNn#e_&!HJ
z*S;u!VI|u8jOfpw?ufs3Gq$%5_$h8h`F@h~^NINLt0>=hyhDH7`jPN`x96>_o*%0r
z%C{Z6`N!I`{TEiE+xcVOeLVi%O8g}iv3L7L*oyM~^xluXPhl&{_Z{Dl%g>cB%J&`L
zPomG2FUt2FpZjy=MffXg@w~s4%F4HE@z<`-_Z#z5*oyM)6xW;9KMvudeBaTZ=&)bC
zq<r6T&S2iwQIzjH-hJ;Bt-r7i{yu^2&-cV%QW~G<7eOn^w^Lh&oex11;rnjA|FY^u
z`M%@3!{@3O<@=8BxBlm<7v-<0PUC$W&OhA~e@%CKtEs;TT2cN)v_JLGPaX61_3ID+
zYo;92{o9)OdgtUk+x^~YIs0Fy{Qs@_ZpV20ao+7-7wTIDEK}pZ`+vn3JI8&u_gCjz
zS2)+_-`ncV+dmf6_vUF!6Ui4?v?f@xEPwGfxM<5OisK=(C~vVof|QRvklvJ3IY4>;
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTrsi%^q{aV=6!@+~}X$`xPuq|~&>YH$BN*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>%ZP={=M}I?z}1JcBN1(3c6hn42>70^vctF5&Dx`
z?@d}K2VM(F2;TVQLf~;0_R7H@4o>)F>pe%OwQv!F4Q~pz^P<FuX*^q$n6-0FmICtr
z-myrHqYaUO$s;K_>8@TkCf(WT#+-2$gA^=pT*)*TE&>+vO~@(ICb%d$MT@08f)GtC
z<aJ|`Czs^9v9wtIcRQwdZe47hc&$HMpO{hC>R)%XxP(_ur}IEwg!Per*Am9^E((`0
z9RjUi)hQ;^X>(hY*xViKegrAjsMo@$60;~=_$#+^pKPrK>Z5ub(d3^`jDD~cKj#vZ
z{M4dQP-gDB?gyGV@V<4)f%mOTj$0f4O<9cZx!;eZ#Fpx9>y?bx#e3ydvnUj<yz3Wb
z3D*&nV6`sZYhb+R)~UlxUw_kK$xrz^7Ag4H9*XTqR<^r(MT-*aF#hYnep9Zs?b@Xt
z$=5}xUctV0ZM}khZEn5tjB0c1mZO_nw;Z0dpUb1g9`sGbybh3J3a%a<!}G0I4o`RS
z)xo^Hj1Q24dwuJc!|PkOSj^V+F(_v(_xzEhbg0y>hep(F>y{(Zp?^UUX?f`5heF`m
zxpm7Com;nLm^3nIc+DPNF&A!ld(;h=w>?|87?G7=;9j=7riMG$Zi*AGT)Vbj!6GZ+
zz}@+#G#qibD6ND8_o7XSH!eY&{1omylcsj93+)I>bqa1+T?ps9rOROAUNW5w6St7L
zF7}x!&YOf*a-nZsk_l3^mtGsA@7W4B*o1t}Tb?ogdEN>peeF%iFG^>dH@=#h(2=D4
ztZm)$v+%IK3DLmOJ1<Q3<RPDW^P6Mm!yai9TLfGS69@MB@HW8{vz^ijW@>83BH?G^
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxIKCahPbZA_=af3~IRg4>BZ#uKa4My<~a^yNsMxM`$!m(ahVAEKye74ymO><lr
zJ~T}{(N>$|&43HLrG@09Ehw}rj6BsB3A}w%);QjjY`y<Wk}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5h#3
z5Qm&!5*Ei#EfS;!Pg%QUDDsK1=|SoP(IvWTeB|V;?0Y^iHXS4$)~H1o*^K|rwNL;{
zlN@+z!v<Y6DLFQolH4&i-9CzZF}-pT>0p<hFK<eYO-3f~;G1+6@9&n*6>ssTSd@YG
zh*o1WSM)?H#1pF8qCoDUn;l6C@tjg<Jx60x3N7B$i$W<q5u$TT&GOVl7m2cit71x>
z>3L0BSsi;`1+!kcef_%xsow|=3PI`@S_7>dx-J&HgKc)*gneS{x+yxuX6mNsxub39
zDD9YWn&0w=Fy)~Qg(syASykHu%G@Y1q7fmmM-U8ul55s5!!gl{6?`Al{MT5+q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#JB(|l<8J0T
z5R@F-%(sluK+-2JY?D)_!zON~QxOL6Md9FvzJ<Z1L>y)`*e?=#MGMj($4*C#N>DI5
zNQ2$9s&v?$&8W{T3cC%o*$GQaGqNFf?g-Kd0=EBb>Vz#w!?4|Gt-rrCR>StQOM}Iu
z!*u*czDBh1lj#XJOSP$wM?K)nUZgl1?4lG7TpdOqW*@h@VXU;g+9koHt<`j9kJKHF
zkBmi#BhQfUu?TTY;_0yXG$uP?4z!RW>2$T(2izWMiV6y*K-Gaxvo|Fg5Ddh;EDFvX
zyr$ojY`y<$koAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^C?=lU_Or8_hO
zWmk6ZSPN;(wC`Cb2RheJ`m?gex|qOa*PZA%=S{bw8;`0kHW*e+7p24WY_Mf^=VtB{
z<Ie3Yw_5Mq&bm!Iw{wry4esi0MHEX=k`)~$<sju?I{Y67Z(Z+r>{}x%I`n&!#^2$J
zTqN)UuOvfu<Z6d>({$8359ysUFg~7Hou@QC$-VQC*1g_4xWz|!?+x5)+Bt|Z4-#g9
z2c9v<y60QN<fQJjE`o9-2|SEHI3b;kbXk;S-$scR)}TF<P&zjkDcM<+TN#R2l?GeS
z2W45@7A4mS%DTy;-qX1F(N0E5d1+I*k%$-VG$<NP7K>u|HYp<+C5?y1Lr{(+C8N?~
z+nbA3Y?Dz~{>ELnQ^M+FCRM66F`_6f2LlO#BKAp12c$^>gJQE$?BS$x6VjHp5tuU?
zjG}EvX{3?+a_&87sVTy(HKMivvrCQRyu?ck|D0l7Q8+eg{^t<)z!>=cH-4V30Tu<!
z%kgz;Xhk3|vD9bRoJeUUcqt!equ}AJf^UD5JQ`CzC=$Hn=V>K)VES1bE~Wmg{f3Qk
zo?ENYn4-<KC=x1?w*3~oTNH9CxACHYQzWFqcH~j8nmoMn^k_7mY?P_9E03HOS#~&-
z4iG*Mv-XVrFaw2WS%}pl@F?r)yKFF*=-g~@+2e2ph1Y>&N^ta&as-LjL4K;$ZGb7X
zx(z&kn92?v2kn6<=vHaZsnef}aEgIkgi{Oz&+pW4j=bVlQ}<*JhNchQoQ=j0qZg^&
zR9`#HMD4~N<c+)t9Tz#6byI)k)!uII%JfDai_pie54<UxzR>O=Edz|Ase^jQn?SWB
z$K~n)Cf%DhgMm?-akS>SD@ThG&J-z74S5r#WHq?gsfY!^pmmWWM$WrfVp0pU(<!Bp
zGd`sia>l2$!ZaT?8Zo4gHrg<xw6^O}F9<?L8K>6UF2w7WTHG$GIyAzx3&9^$uiHgM
zhYI+c@&yGwM@Gdbb@+Bob-?;w^Q)c#D}9B3pR1X{srzeUWv}oZfc3k0CQr0lzF)9>
z7ngVHh`6}MlQZe;gvFwjLJy~QafK)50?nviUyVizzR-fgPM8o?*Qu2`DHc;p!<Q*%
zP%l#~&g3hF&(1~3K5+81`KS|SFzaPH(B``o6PUO9#IbWkjto0t0p_J{Sb)igO1AJw
zxi#2{Fcm%M7YRMc@HyCvqoqQ0W3)qEa3`)T8T7#+IbD4?Sf0?g2HUgKgGQ%41*hGF
z36r)GWYLs0g;_LZabXe-tTH(^!)BrFCbDU0@WJ3r-8eX0&S4^o+?uqMp5i49+%Pjm
zYEAaw@CFUsG*&H2DBm<`y&|=S-M~Be|I0GADEt-#6VCnvHa3tt40B*0?G!TAHADoI
zIj_M^ag@og(NrP3V56x*wnOIVlz9<3I_rmWS}75<PiA@!t(y1^NQCU1D?JCDxOi~$
z%U~LmG#odLrLh->g7*<@vqzG$mu}7h%eL-GMq0@X+=i*s$gq&e;eo-Kt97ay&JiT>
zlu?>VJThD#K^kS+ZeFHs@Pd{M7|2^1GGst+j+l_LvNuLaHC-(ZMNZcG#*ipk^jEsh
zO)mfh*QdG-wA<J`2aPdL@-9SH&nXYY0TTTf{CN33`0?_6@Z0767|AK$oF$Fs4ZQY}
zlD-d}+D_kxPHAuSSY2c|jt=>E8sn7Y1X@Wv*Vz0-i;!!5F?cW%eNMWXnB*g06q0<(
zTg5CN`m-X%Cv1Llc`Z_MUuS2>+e^N)mBf<^K=)efIF03kYaK>z9gh71`{~JRa8)l#
z-ioxCw1@uaH)-<?MvhPTOzA&dl=M{6$+!}Gu2F8tmQLkkb5$-<`r~zcb;RQ!i6#hR
z^N2Q@Ptt3eL!<ZH_$B(zbu4xI&h>DC|Cc`8BNKq&#O1dT94$X^L;v&@2O)(+-sDBV
zETzGB2#1`~kr5Qb(IL}MxT(4NcqsHzo#BT~|9E3`m;C3AMi)8R-xRsvS1M4-zP$9U
zF@%DS{Kf#Uu7jdMxllwvOOwm71r0=c(AWbDm>raX2dfqF0aHUo_*Mol93Un48Qsuu
z5LE<3qXDK*4Hz!;+~P-4Qly|%;Xtl%45kKE$i~X?$>AWZqct8B3j1ido+>gVGK0=N
zdW2a&6>t(sKN*3c&DIz`A+@7rl4l0CtX76MG4iFsjN_;Dc*Rype^6|dv<1V>;cR6P
zkLg!$sPc;2X?AaMJq?O##{H~Ten4+_sLTi+IzU3GkbWeWUO`B20s@pG;U|KAU?XmP
zsF-V8;Q3QgPYq9~ii}zmhFn2t^U-%8#40HYz-o8_SBO@_)4IaA8s6{-^*TVx&*-fL
z+k|4q-UNh`wKV2bv{^GA3$6!@;jyWxwUy(OK~H*&(Eg_Ax5x~No5C+mjuHcrKcQzR
z&aNTeijjD$jc7i;z)skU6w<dSxjYj16B?<a0+}s@$ie&}XdetOT!eX6{NZYML>qE+
zP*4@cc&yBzhzeygY$OkD!H`HDs(4AJ4pmHLqz=U<R?uZT84)T~_+&(=^xhLje8zV+
zm>3Vk&ng;}6GV)TLP%GpP)3BxT12DcP@ZvPIM<L}XN7YqpcT1A74zEC1gWUl$S%tH
z$qsVDOr`MJMajTY*ZiQpC_*=Kj^adD5HFLCD$+NSj{H_E@M<UHmb|ZoqI)oq_yC2`
z#{+G~9w$#Ct7z;I%ZrkswGh-pX+<XJ0i#t?@zE>qCPT}q`bXYPgl0p}Ka_ZbXzchS
zhL*d&&(QK5F=iOi-Ye@RG};OWU!*wh8804*FcnU|QeVava30AqF{+y$uSLqCYce;Z
z%Bcu0N{*aQ=0)j<oQLUtkwORs*TI~c3b>D)nuz&7(aLy#yj&L{<q7fpD_!QnU)-2+
zs&q;SScI{q3>eLS1xK<-F~!R?d>r9QP*{|hqLLUEC3fni6ifqR4ALQj0!tDzCYYSV
zbc)p;TegMKa;S_9V}O*>HVhammD*uIHL3IuQ^=HZL<|@ol}Lj0oh{kK5Jq)PGzPO&
z4iJ)e)PR`EQ~53ixQfb&F<?<3Z{`3gS5_PAhBm4E8>5X<DLRq$6CYC?o?XoB;q$^6
zd!>XR1EfMF4e=+DQ*<OHeg|1ctDTuu5-b20RPquBUkOf!Wqg)WpvVLzP8k3MD!0l2
z8BqCG!QDMW%QF4Hvbc=#T9Nl<G=VZLY!Tw`l{vO3OgMuuFm_8RXdz885a<evFp$A!
z7m^<;>&+O(rOdcR$=Ti-In-7q-C5?EA6t$dHyIN7lCmZGF#(9lfw7m@hckWf04Z`R
zYi(dBQy!whXj-|7hFtK>WsD=`V6GzwNOjb(n5d~!d?Jcid6kQDjmo+-Bzae2=Az{A
zc_%WLs1iIEC5P`iTP71W2U?j`$=h#H#+GIp=XL%)H`HW=;R74?o3f>|8tt}9d0iA{
z&O&Tx$*tU3L)vzw*BXtxO2J(>Qu0Z1FyRD$?wTQDn!!jM{z?R1ls2|ZVWUY{*~B(s
z)IrK|QX)y4T9_$G`_v*bN!zrDv4JA*`9M3;{goSS%F@;ap)76cSaEBgO2Iyol3&u+
zo{p4o?QP|0({N{zr>*N?;<;TZ<BOE(;4aQ&ruM*pXO?z}3bV9_u0WWusiVH6swe~A
z(x_cI@{5r3!vSyvDX<gHORP*VDkbDELh@2d#{`gs68n#UvOW_EVBk-3hPPzQVup{{
z58NgJ3@l2ZHV}hg5fZfF6!(F@BrF4)M2tAuiGUFb5w(Z{Y;yUpc6?es^hHUuil$Wq
zx)EK&OO*w@ksP*$@WF(4Sgrgr;U5-dYyc6KN#6$$Bvx~=TJA$bq+y{@ER8h3NyDol
z4;)Aq2S^E3LF<VPU<U~jgQ~4iGi(qwVlo6a6k@+O^bLc1KnNX%bnyc5uncM}oR1@v
z@A#R!It`f%vYlg*_BpQP1amYOA+E1NCV7(tUGfT@KiD966U#u!LO?Mjmjfl`0BOjk
zlI<9YTog!KEI^h;2&M?M<yh~Nrl9KedP(G&rY?De$s=HyroJJ_#FHnm*<{?eLD(MO
zx+U<8Z`~5+#kXDw@+PzUdW9wO%uqK6vxd5P4smXsLJSIoC*F4(PLILQQdmAgIc>xH
ziFacR@ZzJ?;EXBYp!MF&0hUAn%c7M;0KDgcDb)tSd!DURLghSLr-WwWWioJ-3LNQ(
zxAF6A2ucRO4?&g|VZ&fzs%POe1tm^&fjRM6-elG_gu50f)S`?HHfptlpS?4zEJ!h4
zM=MaIeCv@QQguEwfJo)Qk=<VaSOz43Ldb#<A_24vxBvyPWr(;12-gA9D4?!1bv*Y5
z=0)R&@V*QPbp;7_1j%pWhT)HL@Hczmco+JZA-cEF$!wftK8>AWu~{Dz&RJ0W77&^t
zBDkQ^49+#csU0B2v;eqfgFtz87T}tY!IIV_A-f$xN{Bcqo#QNcxMh)w83{qooS1lw
zR#}ul)*=uc4O<0PXAUeP;n{^TEWRtX0f2r-0pl%F&T+DJ+J>tK6I(&=EkaINf$io*
z#nbZp4*D0iy!ZwU-3E_ifd|6gcWe-YVHAunJzKY2#b@i5kce7o2c#qs4-H=}Ohnor
z3pFt)V@FmrKt%w4@c?PDf;Ks(As2|FVaf&cxG0Gj*%`T*U8Dgx?oV0M46fCJoiv1v
zH<`{X;1iDxztR9wQ5cs&Id>dPgNqhmnWPX-^8g`PBi+t{!B@sH7=;1e2}*G0CXU#m
z<V5u%+$fKR6Wp4o<TFncB96unO%%Y8`Dde$Kfv@8tSOD#jM~5t1rv#nS_G-`8EH?9
zRfEhI3@a$d2GvT#dZD=n<=hcpi!vxVd8HnO92=w!Tb6Cv0euROmXbrt#reg`m1%IJ
z6r&Q1_TCsp%EqX~r@f0&Nq9C!1wL(UOc8DkH|%_c|4TnbK?Db7@s1$EJE7PTPPalM
zCMnU14XF=>W?U4nNeUAAU{i_@N?8=HvM6`2Pb!3vt${#1eeRwccSzZ|v4(u>6)uY4
zHZ=MB-Xw{Xjbn?4_p@;f1b~`xEuM2@2nd@PtOb2+7Xwge2%}^?wuwOy+BVS;u%~Tu
zK+3(#ZAQe}r{F%d&qlOrmyHOsEy0On>v4MHwWFSY*kjMO$6{kX`xcA+{EVGfN!s^W
zl+4+;SsWA3wI42^biA5*-aOZKxCA5ajaea8&%H5=lw{VM=~o0=o9>1XlIPhD<MnSV
ze7g=~QtB`ck?Lh1!HK;h!|OC&i`h@xPUAJ36?0yvaV*^;)or!DvZC4Rwpu^g%h-XN
zsF%URkuI}HbzR*tqOo09cZ_Ik*VP>(8ryaC<cQ{W-Jda{x!vv-Bf7TRJ$ZC(xBD_1
zFA7<7gCX~JnI}W;?J{3OTlooH>PH;pi!?Q$V2GWY#?q~JV`?>#^`PMeFE#@O^rLRJ
zbqi*ciDHeU%oD&>>55Z_R(1sGqS9#b>ALaa9O;VArUKZN<V6K>6*rNRkmr6!1Tz)Q
zuE=95qg`>tR9HKsfRC?KYJ*Z*Zq9mss>a>w33^6LdUSHEmpLN!z^?FCs_2WtXV-~2
z-g-u*qJJzB-%%&#$SyfUnKJR9=nD1ZqocPoZ72D%=!((g)1@o?lFys2$V$F|dJ~!_
zpGk}K@s#RK2Qgk-UEz&<ku6GeI`Yl7QiG~bERkXm`Sj~eYo9N}-dxWpOUub3Rj-_b
zt5?Gu<f_0kwIj$6@7SK!hy9%!NmJ^RGnnc#GV^Ne&*{DyAK=F8oAse#5w5LUF2ZJf
zh*sGU;`B(v!$DH;`}s5?^bgBJNXv)iAtVNthq706nI2%$=pTlM*Z`a1A(^`w9~>gT
zSs(JI>_iHo6{c^thdg-uW_wtBcjW-Wl@4=H?|tiY<)2iS99@|o9K-W68Ri>hk=Siu
zczTAyjMaOYCkMt?S92P~lr{O1(JV46)h&iNw{OMj_Dj#LF*9HD+>Lj=*J%)kO{9IE
zH2CFM?yb`}f>3>uS<lufM)GWZl39B0j4Lu!$?v?|yO%V?8MX-OkOOf^!+NcCx2;Fm
ziI_l}q%{t2)g>6>B?`DOH){m0M=xPWW-JN?9G794B=GuMiNf4SxY@k)G}xvWiTf{^
zxYCi??ExovIOLt=)X)!D$s^5~hr<(`nCcON;ZnF^hwpxEJyLZ*%JoYYeP(69WcBZ5
zx`1b(m+2yW2R*PR=}X9uKU<&txct}fQgr{tk<noqI$m&g1cjaQ?(aj_MR-j5p!Xy`
zJES2@plbCY=QaE?{DX#%O2bRnPA>xn-pfeVKR^muAGBBH1G+0_h<>I%BpdKWb(~D$
zSHdBx7$JJK`jBkI!+Sv!&?AHs6X8H|oGk)Z%meSBd~qSkW%7V`4xkAyIq(3iaDbFE
zl=%vtz+O>9@D}z#e`9h|hekZ@kD!qE10T|<fyaIyyhqZr*@vzXJpcPpNHjg9eM;j`
zCu&FKQF>X4b@7rH7JwMBgW#)OBr+z?%tZlXa3GZt1#aO!n?#H+f+>#|9L#-owDLQ$
zY0vmKi3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvV%mlN*WA@QVVMG-Ih;7Cna4yMmG!b?;~89}MuI@{19^@4y^U
zjDG;ga()9mcr?SfU;=YC_4!ODaE2}+*}%gp$Yg{7tW|nKu)vhRd*b3D^lha*xGA>{
zb6fDaT*I83%W{Yui$fT@m5AY{^n*}IJs~+Fk;4l&1F0Tvjbh1c5HIiw7&yIvDUep;
zg))J0yQwrD^HUsX5J+K(_C-SQO$n~n61f<kMPUmsd<Eptc;P8vOkP+CNXA)6%1n7d
zQn(A~z&va7;zOPs8k(NtGgH%Zd}h}4a&I~D1At=|NYKdHfpE#FxssRME=@3#9To-a
ziIk{C0gEn7MyWT*s#+-4{23&16Y5&IS@B2sof|V!>L=2>yb|T{Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|AoI+osa<l
zta>G}{)`?{EKpN#Eres$bBuLvf^vYsJ{<hTK3I`K{kCgGsNZ%%^|3NfJuz9mr{1Bg
z@KbM9mI2~p_E4dqdhlidmfpk)z^ZpM1F-6CjS5D`7oX%Wl{u<sdlo{fcRgz*)!U!-
zlsxRBtihC$r@8>Ms}~38>cs)Ndco|+8c?!eutZc@Iao(3jUX&DRYnq&qDlh|1RC|K
zU~K_~-5|ahP(_ms3uD2kbAZG?7~9P*9NMi;WG2np4<Rm4#;fd5tn^jJDwYE)gBHTB
z%I1ZztKBfh%420cLv^w;u(5zy8sJ#q3<kQaUY6%PGoU-|6teTNmKrUAD7IFnLWE##
z=0w(OE0ZIOx}`~yMc>L|$-;1H)XafF4irnx3Uf4#vIbolPg$o<_SGXR*_8p7#qP>V
z%Yt}i$<2~^W$Hyyz1<#+(tDfHID@jvtjzL#WqM|bKbWTvkkYKI8;N!dTDe(FungfW
zI7n0Zfs%x-lzWyfEPFdk8<tHT)ep;Tj{=DYjr$;VnEUx{IyrFU-}G>}zD*B@^Pz~M
zj+-}P6@4sk1&czKM}uV}%j<#Cl7~DaEI(O(6PBnf-wMlEmj4BXE;k<ys$rHNhXpgs
z)x!|0atCGE&GHu=tjbwlC6?|?uM<mqmRE`)RpqxrOw}RZ7K@0M_X~AK%R$Ccq~%0o
zwNiN64v=!ubQnJNRo=Q47?rHt>!#9OmmB&qvR?<?lLyCENEO${R!kMwhFp>?^m>%r
zlGR|#waJRH@_wSGtlXojItv%-0a72Eo0a8j%M-h*+tOA0QuSMTb5S7o*gU?hqFY{J
zR@!xC0c9=T@-4GkFZ|CrHpqgU)E!BgbYu4{3|ww*)(tLKxQYv>ubkC~%a_jj#4adv
zlrS!TJgOWY<+Eog<Z|mfFs;h<pXHM)IDiF~5kPQ!RTbunGC-N;EfRsHoHJB`g`X>u
z0mY$@E!=@IXIW|fE2~V8Ekc4-s4I+u(Pa^6aeS$obr5p5I^(Mpow3SaSMUa^V<W)h
zO9ix#EeeEHwkuMEWw<Mvgw?z&2u0<-D^i6u!7G}@75>C~o^{46EC$8Mk1ckFVOt8X
z@vLT50XU4uswf>4MrR~XunRSh6z#(T>n^}07GbXtAr@(87}23Z?iFUlTJH=^Vl{YI
zITVIeRfH4D${$-86f4hHq!g>uE0Br>>?_!czj#zcmZRoMMQu3>s#Ii`qgYCXe>qB_
z92FlHe5v>`M+p-Km@Q^!v{KhJAr@65&{4^>g4x_C77}blLh%-I0A_oY&s(Hin)s1+
zR>+-aF^>w$LnPD|x#tbYHWl6%(tPeAfRy+O6Lb{Qs8~YmrDF>?bf8ydK;mjS0va*8
zrkF<#uPfg1c<~6Rm`HC7+oUbg8{;-r=f1(x&H&6qCsajg#=&;(k(>^2D};Lng>jqk
z4CE1-ahuRJdG2OZsW*mfPR?*DYLzntR6zx<E)oJ)Im>H{eDy5xfaq8d2IFTB5RwNv
z&l$L-K-{=BPh+$$C^sm`x#k63VZU*Uk3BS)H$CEq7X`Vdh%r7u${<+AcZT{BjN*&a
zX<B4FGZkWnJg4rR(bQ9&CSt*PtMaK(;nnfLh+t}%O!ASEByH-x2Xe2s(~59cthaZ@
zdNUw=z4kIKNfG1mtc>CDRn7OQ!p`}iWnem8^clH+fHKcLx}8t(ih$>{9bxjIWH|e&
z#q-ErR<u3L3Kfv=-Wjo<Ed}gj&W?!iiu|WBrE&vklu`NsEjXE8K%-A)9~_`WqKPsT
zXo9LN2KONqJX*|^;J^n5HZ}U8bP0|g(xaRUS_&&M1NO(Gk~e6^%-jw~ZfE6wEc+^w
zL$U>)xvo6e3M<KkhUH2_p$)rIRcJluQ|d_4*m7Xt=cqIp`e7=U#+?~DrY}95pw4%%
z6dejFQ*;1c=?m`wSwD`{P~-(2AjK~zdB}lsRS8C(_C{qTIbx@nw&Vj*Ch>^Q`2ZuX
zGM$_`{TE;VjvRhvOgY1=Dy_-^f~UMIXZHQYce*p*Ub$L6n0+>Cnwfs4V|Fn8EPvE7
zHi^dY9Gf(Ufh3|zK3k;B8<TV}zg;P8KA3H$TYn5Pt7+Z?-E`Eflyj!nIn&9Ng6GU0
zzXU_+K;)`izC{U<V!EFX0KH5prUS`0NDw@d6nkdY>LV#lnTF1k@F{_S#4|hb2vVkg
z>Q;tnwelPtsjf8CB_-1wY3}i{r%w7{PNt3zW_BwDb5SA%b8v7F_Db#a$qY=|-4~^e
zEk$$@a<pj|S?$cFloiC8r9E|_GD}<OstyBgrL!(dGNz+7_H0;ZR<=@R9X0DKt=1>9
z*p!Rw6NuWCvFl+2uAE-SCz$o?unAXMu)jyN<qf;?t);*z-x}%1j&y6iSSIq^l*4>D
zjL4Pf>`JkgE;ezmD1F+4>on<SJ2wrpuw4n(ItP?sty=@jTgl#w66z-t!d*GmB?-*2
zE>S>|wTln9jm9Pm6Zz^T3&@!pB@0k*m<R8$Y18d;Bq=%AwqD6VX(sdfqG(`8D_`Fy
zDmhkGzawC;W9-nVgbCmPcPrcg#}4fT$62Jium_wu*n%fml!SYbzJa5l)1$u#VGJlB
z1kdxMuo4`m_QF%}`D}O#jtD`3G8`b~muGdsm+>rRlD52!j#?7}h&Y0jFcXlA>)Ze)
zoEh5!q3}FZ0aO7(yx$AW!f_NA;)OG@TV5-_i1a|2fCu0xbPWfNeIal-A{YhIu?Wcp
z+d3r|RN}(nIS?AiA|xNAonAO=<Wq5==5;3ujb8wP5H5)$HnOlwoO$GeH(8Vz4<S(U
zhZ3LV-nzwr1f{Yl!5^WmIMUCB$g+M2>6FB52}+JgHwQD)W$_Qna~C{J{!or+Y~2zu
zW^CO8r)6y4O2il%-VeWAh&JmFphOGx#xLUS$mW2;9tEDWD5-FCi3XHyLGUa}j;?LJ
zVsx$g<ls#9p!jzwl^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&-(Nt*hOmPD%%g5GNs)PcM6~jE1lFb9
zdJ;AG`D`e10tJzxUhc!Nrp5iLm%j9{#X&RWu0DtrF;o6j{Kr;gy`eTcQ%2M2YeS{I
zP=D!GZQ-ivBH%Wd4?n^D^X@3jy9X~cDALA@_g3ll)8uQ2v2=Qhl?pl;d#L)X30;zL
zuyDKgiW;q0Ek<I|L4L{qO+OA$v^L)dQ9dsTD=HAyLsRMoy&5SrKJL5uTUfk53nAhB
zah>)|`;E-xq0n%_{nSm{6yWKT^>3&;13|aS!yU`DZ$lxhaCKBE<Brrllg70a@wH5*
z;m64r<<bhmVxp#NQx0H9H9fsc*3yO85Xwm9?DQ0{c?Prvz-&gyS@VKVrY0dUyur70
z6>dXRcUP6XC9lMHVY2wCK!%GlpCN%tFn=!Qrzzf>!KVtao=jA)P!mR7c=_b$38QHy
zr}dVYSTk5tyq=1n$ep{y<qrhHeiexO`k?%_BP0n*{pv{B>fd(6<AMVBvyM}V;BPuo
zQrkbs?)_~?WQ{_gf2LVsm+;?o!#+rT?dP^J{JU<5=jLwtDHlQQpWk%EHiJO_+%}$n
z+p%?R#-GdAxoyqgbeI94%MLR(z&9P1k8$7NKNZ7MTmCm4c`}$fl5&095s;ibKz^ph
z{o_daO-GzO2xs`Yokjj_$98`lP(L#><KxKs<BmGnPIV+@e%BE>csl=nW*XW?`EAFE
zKReZtl=*GP@qC=GKQp8H<HY^rjy#y{R!1Jy{%yytg8lmQpMfg!d7}SuM;-i49Z9*r
z>u8z(hx_4YU|a3?#UFo-mr7$NwC`^^8Ei}h<oj7AV{iLz8FXa<z3}IDiTSr3qp(|E
zY(E$3>vqlkaffviqLAQE+>7Je4k%cI%kpQO6CbzdZw7`twy7Hk_qW}UZp)kaXRN^I
z-Ta%5yuv#>it>Cv(D`xG|120^-TlAmSmt(gBt;&K-z+vvl~5#pCNShi`E5snWM1q@
z%H6;1_*@@~%Fh6b`&3<ivkR!<G<789{<dSgc10*R`G;oo+dZCt)!2=M`@3%NmQu^g
zQ|wdk`t2#ksC#z&75?Bi2QG7gt{iA3|6bn>^eL!;oF56}{H9x^J#HG}&yU=`Z$zzB
zOIJrw#`$f>=^q;C&+x8)>ZHHvNY!<+BPrg#?Z_nY2G%$s7OC?7rW+Mw!$OGg-9k9?
za8rFwE$M^udrb*{X6i`F^=-#IN0)Z~Gomu2s{iqyQ<)D|pmG0Rfur|X5>k%7ZzZJO
z39gP)PSNi=A{d0viJzOz_WK8h-XW(tPCeMG<9p+u>m~bszrL@j>s~L~;kK%^|0^G|
zdXSXCHL7x6GPh<^?o#6CM#(FfXi&ts0%m|!+f<>xC<=YJk;2_Bd9acc6n#8QF_%1<
z8->=W&{Tlqa_khuHryx~dY!U6fimgCMwC~Z@?qZym24I0g7-w5_cl#ZYMNpAocBlT
zVw&ZflqJ>3gMitQaVzaMQ(nnCy@_qoA#nrfyiIu|5RTTSV&8Dl@qFJY@<=2IF-p(*
zU8Jl}N84K(8D|$;(j!SIBT<gH6sEowGF4G4H|nNNg(jeMeM10@C`Ujv6+=QE=D9Is
zE$w)=*~d~=T*{s1S6z4@omq3RrXMRa5VW?n#f_|5cpB}bu{Pt{?6$Es<J!!bu@VYP
zq3IMcTSwVj_0*J+c8uL@8>1bY*>+?BN7+_$4~{aE!hSu<R0<n+g`B`tKH6s5jd1rx
zD%)<ds%=K^WQ}dkf#ik4i{L;wh_+T<1|qV_HxZz1a#qCD6-ojRN6SzWdSybEDwZTX
zB~1oCxKf&c6zFbg0x3A?lW72fKz_f%1_)2ilVwNC1Cut=3$2*7m*-&>SoHEcpp>i<
z(CKpm7T==$qm>Z(f2(3Dnu{gET!JHzz<{KjS-h3r&M5lry+S!yb5*ec4>(X!BM)C1
zHME?6V{F~Us;d<>lI3gZ9EDZcO@2;RU1fcM^voVAiyOY%XD^)VxM!-kZn}R13KFe2
zDSA1YfN0<Py>(f$>GC(h4ZSGzjiPiaQ1rr&9If)9$I>Wul<x2anOQFMHTXU^7kZv`
zf*=gX`&RrIzWFSWtWG)nvGr+Lb{S|45eMK|cbS5M(xp+Td0qa&`z{Y6)Pbh_NWWko
zCywb$VGUJAnxPM^vr7)mwjMDw%fPXhLM-^mcqt4cYF<0zJCd2FzLUzq@?KP=NwTw5
zTu^Ql;>NxZIMSNj!52%G%PYb7lg32A2vPB@8eY9(fUUv-Sg~B;0G_e33qN-YpNa9!
ztyhk3R<Dso&at#CSUzemrtYBxJOl{0O1HaMuDn8maLYH>Uc`OfDp-uw$@|tT7FWr0
z7cSY>wob8(t+lOJ?EBWLR}QDPJ+8V|VL=V2R#RLMZmm{Q0mo)Lw_Z7(vpS_?Z4(MO
zcx?|Bi}6?q1+JUQg}ZRK*j;=_o$)P71UJVPCPD-DCBenLU{}dIt^vEU6#&`%a}*0V
zg%@8r+g9mn7m`N;n_GVr+sqi#ms6Iue4(JXY4-y!U{Mrv`C!gE0uZMSsBut6v>7Oi
zdw>BVhog*5t1L6<x6R~!{s&K1!Xh-&T2GW6Atw7PqC|6%bOZniav9Rt4F_sPgk-Gu
z5v1yt{sVSdpOzuTfkD|$soc<?7e%~6Mb%31LWp=fE2tPJ;i(G%#gPH6kNDe=g|otn
zXS6D$I1b@+4=K(mRzxu-xQ7(y1ox2QnB*Q(9BZOywgX1vXqB&(z@P1`h+-U9XGNFe
zVRq_;HS>7NIFkdEWN3w$;~8?YmAq8A5aQVvg}g*MQ9G4bh!FQ>3cDB`p5Ku^IC0LL
zQVu508LL1P*cpw1C^H3jwaJ?Fm_OwMh7;te(*cFcqDIEa!24@_(dd_i{E!X@z`z=v
zkx6RVi#sgUM0*s8o=3zYRC+-;@E?lJu}BdJ@RZ!-5wR%z8H-MO!p-+PzQR?;llRvm
zF^MI2)uLdIz@d3l&<fYXqXPuUHH$)Z8=(VM>2c#uMlr?=b^5FVSWwGvQJ92>;_j;=
z3bQ-%G%(h2@hmnNg;gs5B!^4A;_$3tXcfSMBmjGeQxK^x>+3fk5v#gl7Ijg2Oq}hj
z3JeD`;Wv=cW26?(+A&Fq6}fd{WLChTx;3vz@yS1uN`Mk|cI!eIo`rYt>D)ZaWr3he
zAVOQ^o}oY}YXAi$iUd{i)LN3tIvYs%c$3hKSd?2YasWVC<(wtHHA^5RVZhz0EF#0~
z^aj9-kM);cVRg%2X1>{{&lXUChw3^dDOsS1G`!vHrltU#x>Zo>^+gysyXskpU=miY
zN=gj&(kcUIjrFfyU&JZ3j7mK~irtw30g)xZ!duynJ#$q?BmC5t0-YS?!C2xeNg>;p
zR7pUC*|nuLMrE;!nUz<zKQbxp()P!L&@Q^Vn2l+d9*=;`vQ$eCka8rh1%V^6^3;$X
zYL%zvT}9ho$Sz&;>uBZBcpxA@HEP45o#U!>MmTn_3Oh$CtX+C}AYzDx>t0HzwaRou
zYJzQ<Za{#tOPWZ$Jy%<)yHR!z2QA*6HgTV1PQofE`JfqtFB>275u((fC^6Ehy8}2#
zw%PemM!}}!1aD895|f_Ba4UNsK#5SL@c?N=B}e8j&uBr45=Y3U-j)f1Xj8gGM-?!Z
zu6!k$Pw+qs-t$eeD7gWF17k|=YT(;=q-7y6--hyY8l1=q!)<q#oy9-LTinWE)~+M#
z<K|?5pJJ7>1>{ZE;e9FZo)vyyUn)RiV+$4Af;r+39{k8j3V(L!Zw!B<RD0K#IGWsP
zR>@#3AAl7HNIVo&NX{R^wj4Un@rbiB)-?n*3|-ExV+B;aD{xUxqjNb4xdI(6c;h+E
zmSwInMHIAQZR{i^AEf&O!8HnVgS}8_DyyuWWVkX85&q9o;z@~(l;1W=54AyiFmjda
zS)>@gHm*I<B34N5NCqw@B}VUhP9*Zlp(69I#OqkYcj=2r5-?{gMlO4zg(hbi9Cd(_
z1db$g`AkU73yCB|rOb<X51JRC1m1&2JWxk5Cll5u;Y&<Vo{p+erclYiI9YrW<R-C7
z7KKyn;MGJcgw!SfgeEZ|S_U*pd|F2f>Ry@PC>Lx<eu(jPNFg|^GT#ixco{GOHe$km
z46u>-mNXhmRp3}8g7QF}6?T81g#-g--#BqvyA+)>PwB(tNG0xvm0k0s1QY@gr2yCs
zCxpOs4C4uCf+h4!9S914B@bznKYdY>hXNg3q*%T}2*Rn-slcN2oCz$@QJ>BT4R|DO
z$Ks)|0ay4z%(D{cPQ0DUPKrmI5t#1?QY=`P?BWq;z~KuFsrZx*@-wd3uB+`trB5r^
zJ-pzI*3?A^RustIlN(;<)ed~|MM=brMM>UN(CiK72-6jn5KT7No;e040KI<<v_(FF
zbypvRf^|xAf1v5fCL8YeWFOz<0ZSI#bF`9k!Y+NVqh+{Vl%-4&=MKpQRycP^F0jrt
zf<*~N2~PBBn2?_F9mw^IG|-MaUZ&qSC0hJVF1tWLALRO2LDoHt9TP$w%3xX-dgqO!
zy&GC<q|(oN7S{|C7=UM(6+j&_3#=>pJ0V95<-v}G<V)!mKpiTBS|QZk7lP}a!ukt7
z(d2vxYGjdePY`LuWQBfHqD3%6#_<ar{YJv0HDQ=%t<|6uqG9l^2}cv&VpIAeB9iil
zI4h{<1!M<*rU}RnUPY66yN7>pwR6|Nt+xpLG&JynwZogv3fK-FF>5M9+YxeQjhh%x
zHj|CK=abD^0cAewgR`o`g=KBW%0w@G9L^<^ZN0-$WCFlDI+6)Z2zV>Vi`@p=xw^v2
zye{<tcInbNm9Wq+%7cJ1FUkY8yf-CUgbSrS2p(^d*o9o6Jn$MMnusaYvm-bH5w-_N
z*-d!J7p`*UgLY&pTN8LDO!(G%jVMh7P1z_{Q!fsvsTT)i>=dhV1SNYljRyv=)-;|o
zdkM%mli!1q8~o@9y|7kT#t(Zjoc~cT2+4fZsla#RCE5zh7;mvwSjH9bOz_>j4&=`0
zFfkvCG(cb<Chtu4NvWAr-yt;c+yko<PdFcA@`-eqdaV_3G3BCwi$8Nd)>#KMi~Waq
zn4Fp>4-;tA9d=q}4jn;aFa8PpaGH%H<|;IG;VJ<0-x^i%PQ$3_<fR$Z3IjQ%!U_WU
z1k>f}>8RJWC^5c)R3{UjD9V1BoIxES_lrXOS=0{;QvUFOk`Ot??^Z-$gOvapF;k6-
z#JxF!1c31?8U-#MM}(>T!<Zj&-9d>KqCEN->cVjkbs@Mo-j^l-(~-7Z2H_t`S_h?k
zScDW=6b>JcNg_G|QN&Dj5C-6IP5IG%Fcl40%Lw;aZO(|%__{<g3$9#c9j`qz-6}wf
z3JN}SqEi9b$8E-t`y-L?gEdvs0ETO0?jWH=%v91K&C>GCbq7{#kn-CI05Rma^$a^T
z1xa^QbTIkzI^JSdHFrBLgr?ieD{TOWfzNE=yIlQ=R$7>>N)>SFt5N}%UU09@g|5m3
zINpPVFTr$YRhgiv+dw-PdT7#3eF&~g1D#cM0@&V^)ZPKUZi<BO4(%}Cu?I+oX)u8;
z&w11J+PS5rjCXG7yl|tG2e-7asynwdOBm3=W=g@t`@{(Oc?j{tOj<pjABJ4~4kSVo
zD(IpN3<pAyINL{(FdQbiz-1o=N}>sNb=ZM63Jz!!2xDhbhY2~m<A^pF195RHxuv6)
zEhzazc-NWq2B_?2dW!VyLVo_5Shy%7(+ZicN*Pd9g-#jRDLDf?XF3HyR;%710mL!r
z?a_?D^7d#(V0pVWA^6@pU@c9NvmFs1pOlHu=dxtL$JU-a3WXw`MU{V{7(NbB2k6Hq
zC4ZNqk3>}yJOhzGO#XNRe|%EFuV{6iVQeN_R9T`mtm;OI7FN9(cvJxBwBHGPcIA59
z_>rQFY$qEH2W6A$Z9FLnqn^04A8q~teuM^`4@w)y{$ZGFcFI+Q%Q*pfd8bS~n~Dwa
z$?uc_u|op_7A==>@t&p4rB>$jeJufs`bnWULL}15e*8kBJVLh4R<Z?3?ZlMP(|%B7
z540&+5c9M4VNobq*g<FQM3|mdo*Z@}bF*tFB60Ysok&XU#IU9`T3~btwCDb4U1Akd
z*q=+Rsw8Hy>LagtJLle%bq;=IB|Mz<Xz`ps@k!^;sZ!?SI_C`^=sM{$)&A)^=tVHx
zI=K8BK=11^Sd_6{7Y$zTMIpyb2mL_XIXd#lbj*`SC+|t}<J3KgylMEn58Z(awc+!c
zZ1<yUGB?zlvfZ@{vVpfI?v8fzT+N@nq?&-aw6mC!{BInpD&cwSRAsIBdrIv<0{T5m
z?ZC)JX&o5dfEifY$|8MgI13tr-N3s$@7}8E=~7-0VA<|2?S-7`(q71^F6D*X%I6Uj
zw<9Uk7|EU{jgjoJUlhi6n-s=`O?y+mOqm=F7&m59oH(&4s#<-Y(E<|)7*yKsBC!kj
zK%)wkW+r)*UX3&lsNPw_6^1tD#5Q0{l@i|oTV<xAod`$8Q{VuJ-7w8-svAV$8tR5=
zUIXuifmS+n^m17#CApHSu6glRWp&Mqm#T_uBA)W7hg7?`{wkb#as5>$6IK+x*&3}V
zrT~IQGm0_(yupm3$6=!tMGweED~hRz<jPLryA-p4PfZWiHziy7nW@(@T6n~&`1Zt`
zIEOyD^ZAr+lN+DU?Ul8H$N0gdm9KiQGjF9H^~_zVcYm8xy<(h4kkSNq#vi~}CUZgq
z#%9?ZD!uyDSb4(BcF_>-M(ak)(6$XZ1#xU;YiWpFGXmi!sqHqKm9%oh(gV3*2%2m^
z0%?JD==cK!j+q^>-pG3?qZIRA!f=HtT3V#Iyf_nDLo5HhX$)ty^0;N}7xcr$btSE<
z?DlxlN|)RLDyud6&f2)u0|Ga~$gTR?4B2WbuRUm8RXOctI+2aB(R9-E9B8ziG${<r
zb|PbDqv=EjPv*gtQS?nYHedoK#*}HbjWVrrB%Uq&K>yW-yGZOpe)Kc~;|H3$kR4FQ
zo36@%8cWuO_<_qn7U@MvqoD4%L7S>>wDgl7CWw@AsuS0SCe>wRKnjfsuMjCTK}j`|
z88l&-PcFcQ(sZjJ@7z?#runT-c$+syV<~dJMWM{_E#&AKc*SV@27k7x&d#F58mi7R
zoY&#hz^8{gVF}=^Hbwe3=gVAGfEwx`8uJ4hO)E_YwBw}EaqK)PZYd1j)e8(?K~e1y
zf1CVBkT9n>(6jWW9AEN1MdC~@3C*U9a>DTi3G!3}yN*H_Sq@Y6rbZ)+9B53YDJNT|
z)4&ghHvD!myG|dRj<il699?~pOY@}jFTtMZfiprgHlVJW%3d|vU^*@IjV2hm9$TmL
z6}JD(r%CUt4y#V@E8Pmrv9aFtF*;uxZHcXy2bNze4=fg{Ltp56<Iq^cdSplB)zAye
zui?2MnAX<em({V;>4N96bF@w$JR!5_mzAR5^Iy48^w1MvD`z;QR&{#kb)fW9?rw-f
zp+6Pm(vBW-Bq`^dhQgJEbHlNYfi-&Ub>=jB?4v;tG&%5FqjO#-N~3e0Dkx&Wx@yP^
z>g1v+r8Q!yNpr;U!;pkVn@v|4_RP^yV8hB)fuhl+;K6TbUHTkOW$QW{aF|yV#nEWB
z>Dh&{qN9NET`Jtz;0voDkJcEWD}=KKx0WGSu4Qt5g_E@KPF283V{BGMr8F9M+{CF<
zu`T(l=N9?WvW9mB$25BwF_m!x4ccaf)HG<V6?U^I5yH~-D;cLlm6*mN1@koc158Pb
zD}^S%qs@cIjk(KUk?*C7E?P)!iau(1H&%dBQ$&?sl!iPnQ&MJA{8To!xGCn=EDBBr
z#ZFBr>agxqkXD2B%2dXAQ6@sWurAiN@UUhHxofJ5y(k%9bZatPZUzuE<7(fU3q$c#
zO}zn*)tq_j4dulaC2vGjAT!rZb;fn!kFLKnce?AUIuVSQV?#bp1ncG4PN)t;>i5ZD
zyir(imtqMqHilvi<Jc}m60)6PkXB=x2qx4WgPKb=bjM_kw+MB__-C{@wo$Q=Sj3Yt
zp_1y8F`>FSPUsdxy6fqTg+zg{b}A$ktqg;tjp?jlQ1YI^pk6bCZE;A~JQ)otSw9*3
zsq^}5glxLg4f!kRAChra`(itr{0g#826x0tvq{_4pti@%8ykH58{@WAvB4O(HF!Q-
zqP!jf4s|~yWvDD)tdSxULDQ!wPy#0f4GAwRo|*pq$asl>Yz6@sAXsg7{SdBZK^a7D
zN{ndwM#}JO*RZiIr)$*MmI7C>1YA9WG)2m&Z1U`km~P-EW~z!!+=-S!Q}e=qBOV>f
z^P*&IcHVu4l1(<L7c-4zg{bGYiZqsy6dcNnq{#MU2}7zTRb1w}n99A_%@Fm6k!E%?
zV}hr_qGZH9=a-xB;!U;)nKY4uLr&ZZ>>nUx>V|1XLpcPT5w@P{<QR&`E(+4Tm_oBi
zxBiH^4IHdzZbPo--81o`Yp8UxUc9OdwVdoC<SGq?mt*{pt;;ojC;-=Ba0pXx>>8Q?
zTmh;>^rl1$k_H3?yR;jL@oHDe5=@JigbDiLmEwde<KjhRHxnkVV%v$V7cwnlx~^M1
zJB6_bz5&L@F6K!b#wf4r!5?Hg$3wu;N4*k$H0E||rz1-TD7yzpnSUff!jMdmw8jXq
z+x`&PbRB~P03*X+Vh2|;DcOw<6sGeSKv0e(Wj87$u{P07OON%V2qz^to?(OeL&U(N
z37B|ic2E5@yj1rT)56Xzh~<M>J$A$LX~-mBn;rXx@niR`dG+`ehPT9K$PBGpOvUke
zYw?hAR_lk`=c)CBY4q9F&y@4WS;7wX=<G&i5}d}MWQt!)L!@0yschmgQ!2Hq1M6qC
zu`OskeL6XV>Urz30BcbB${zZ5m?ji=O#Uv)#n>a@<jEV6VB&@hYTi|^JW*rBG{-QX
zsM10WrR9%B!n6P*6c^*kAIdyR-K@(*`%sTG)aEgW6-~BEbInVG*KxM<6IyE|DA~ic
zo-07|VeGjfm%37NO}W%GQY^}VHjyo+{=&*?N~AW;Y;Fm}k=}G>l5sBA9QcMVfEl@Q
zm8NVk5;tMy8!9}#m8EDolC$ZD<h2f5zXPPmkXP=tO<+SQJ$q3y8(TL%fW(mHeFTAN
z-&{+eGn^#?Ks-821QN`MB}AdE99vGhDMz{lpeeT<y?_LNYR^ZpFJ#CcAml7>2@Y@<
zPPTG}y7wpW|COq5GoLJ#&QArbQvMAk$O;y~CIJ@CtycnT5nkX;NvLx40E&+3KtKX@
zGacU>QuPx1Ook3p{2<~8n<5VgI@#ozH{?b)Il2R@GRNAtZixj!xAL13Ei52(*+z$~
z4dCC%SGp(!h`<7(^4+4SQ=&A`r)Wr@KAIeYi<B@8G|evEIuRExbpzsp{A<*|k0x&!
zlk?V_{Uw#Xsfsky^_tyVkK{t$rh%p^K|%U;Q-K#t^s5%$9)km*sXmNFdUj(DSrQUN
z#n1};6kQnuM@O^zz%ri1e*t$UqlgcZ*6<aM%m-3y9WA1!@B_q{>01xLrZ}1jnc`a)
zLAam`0cHkTA&_m<xQH$@wk|-IL2HB+i=QC0%-sHdS@K)E&?4#$8B1Ily}6KH*cw|o
zs5%$m25HJ#Fa(pf_MkNqo(G@65!N2b1`%fZiDs~>pIev2VUi99tlDMBq}&2GEp5*S
zNY{`xGzqbay=}b&ZiGG32yO(-C#E_sOKtTEfTO;3N_-<~3cwu?qcHX`@|I~ieknh4
zQP2yJG<|Hn5<Y5dofdPCMdAq)U}jyH1e`;QQk`Ny_PO<mDX8q7AuYebJWBgYlQq<k
zrr%`xG=%Dg;h*hX$$RURGkCU6MDN0N8S%a0fB-x571*Le+yP3gfvU&}<yd#ZU=0pl
z32<&Tq=~=Mij;tCwE7UcxH)qOm>Wvx3@D3x-qDJe`tt5TKAnJTdI9<a#5pO7o`7q<
z^+~)nS!~RSxHh&<K!EPz%x6Ib%^K2hZ1XOG;IvC1&UC2Nlw&Ni#yFrs(k-|1K+@p2
zAYIZRHqa+#PTV<FWFsG_D8hW$oF1-X%(JagNUySb4>D$)+Zu)Rsz{~5RY~V*Q0QHa
z7K(W_+4szG6%Pa?ngg6p_B`51+t4c^9iWRqMb!aVr(A6sTid{69~^2*0uM@fsmaTm
z=!`?m1f-Jk*lE>mW0IRUI5ox1gk2g_+A7woDW#s~;#P(>cx>DFr6t}1CaDcw@bLqW
zm<zpPJmM{|^2S5nUVt1u>4`9Sh1--BXroY8LuGBMN^7W}-C(#oKw1NyQua2=&<Key
zdTWG(u^ea~3io&^4Vxh$Nr@E^D#A{g8eZH-ZSq%Rg@nGaQ>F&H)@;s=n+Y{L83D1A
ziZQVW^V&E=3cnreIF-0tq<iC3oE7ulI7Ny$6|q9((~4cG?F%HWS=$$st2Qh2y)@-j
zOE)*%BJHZZOG=Yy0H5oUf-XvD=IA0VX}Mg}1A*^uBxba-pNYb^krNZ~x^)UbBNaG~
zdfieIMDcBWD<C7n5yglooHe)M#T3edBg(aNZ$#y+<FmQ*YBBVFwy}`H?TAH5GxD)f
zo^A6*OY)T=r;@D@ipL~d5m(xT)+E___FYIy?Wqvar)_&Go@7y?<NOf+r*E4oDZcHO
zGQn_5J=@(%(%3dt9G=hEjwn)eM8$3f>ejIx0%e2QD76zu1T1eS)R|@L;8!lvzVAY$
zo_*hi06p8j3vqdB>*Y)Fc{YBAv^>wo&-KxO&DZeO?=6as`v?%%?n8ynvvwb<v7h_x
zNlIOw`9n<-m6Kah?sX5YLG-h4_g;_T`F8X57@msg;W7+T-F#zYoyEH7=9zUCA6?8d
zKF@$zT-A#(KW_6ysZPnR{dP=taRV;xBeD)Y6^&ko5hx=oSD_TSWJPU2_-MMx`spnB
zSvwGgr|sNSwGoLDrKrWU%`$JBO4uTNDr&t<AC4lRZPU|Y)<};yKzg#~8P(}5fF|`j
zWJHnnR6D!X3m1qE-Rg;p0-(P2iuG5F_aBuAJG0^{U%~v)wduFPZ$$v>J92O7J9k-p
zP+QdM@iL-SFPD%p`*^u{mYuDa%gib6kC%`sB9;c>$?~?vyqID;)d`8az3KIWDxu0a
zCN54_;xeCgT?x>9`t{bzG!jKYVYom&(9Ljx>Ytn80tLI9j#EBeyTTeR{$OnH;aCyH
zCmK>gdmG!^JI6ZZ&4S|H+uYvKA<YT{G(=2xMg0+)sAmw+0ZROi?&r~?MPcX|-YscB
zF>e7h$Oh3Bc}GJ<Z_n0kWO~|%p@Ru*FBwCS<VO2Qj8|cDHdx*pcjxd-rIXPnMypsi
z8>l?jJ8hFJ?JXB2A_02uTc=oRV1y7|s`pZk1}b~|)+YysXUZ5#Qha?8!wQ*<q~yQ`
zJ78dA>y!hVTc;e@RG(zotbq-%?Akiz$Y`8E74OYBfhyiKPGq>jIs{~#NHOc1ZDPiH
z*8ZO0(W4&geqHVA5#w;VEyfkC{QEqSy0FYGu_uuUdw>$7a8sY5<k@V;7`&E0Yi@f}
zhj>dzmhMSYZ*aqF^>G<HS05Lz_pMKk!)s``RDHKi$J)4W-C}8cH%`Z4mNtp}A>4>A
z>ol%EpX!Bz*Is)c7Z;R7*yLm8*Y-Ebe)%nM4SD%3PJD`P=7Vt`-OF>48@4-Jv5mbv
z7iWIB?9op;y0<cw9GrA74X&IU7~SAiFmX|(2@C}@b7h9^0uF9i^@{NglYc44M}V~>
zJs#`hqx>5vMLi%l6W52LmBO#G_%b9mGqi|a#*LXOU>}kjJhS_dWpieWJsPG+Y*IsB
zLm#>?01(lIzo$xIDqvxWDzPvTUi4rc37UYx<4_;6ZNoR#2ZLVVJ`1#llbzy6FPWnz
z&f+0O9G<#9?q9rlU6nr=?bC+}3=k}_58WTr!8_d_2mtC8ngl2h09za&#n+~c-9P{#
zKt@vHV^h{HSPyz8iSUPRbfY}t)SQhR$`f+xJqC!9POHfAMPSJQ{*b43adCFJYU2Qy
zB_p|oi7%3ryk09#YNoQ*C#~ObJoj00lImM8W68{a*A#KgRge_i-<`#7=ptVPE+-DP
zsdNPT+I!hf;E(T9DrFix00i@*4_{a@anL{+pB3VQ(`Z(8TO3AZF}a{;PO6Z{A_YrP
zeJIdN*AHKM2LN=wUvh>=AXFFfsa*(m>}5nj1*CpSA`lzZSuDw5U+ES7bfIo|uka`Q
zW4|g?qNAIXM${VULY6h=&-F{sIMhDqDg$LGm(VZW6bOh4NG0?dgj~u95p0-CkGKm;
z$HkN28W;>yMGQ%U9RW)S%t>BIjm$z8eT!Ivf`ITORMV>Pq$_pXMd5c?H?UR?FXy{f
z4wv(--5ljiR$Ft-m+M^%hg)|GN5Z4?#(9tWEkyd-qN{otsZdI$SH#kNMr$f)D|jp1
zXuDCGpx=72BlENie404T{pQ}rWC?Nh68iHIKxijPBcaj|$!0leDU+D~LR(`{8E%_<
z>ik4@ZNKH@MlB>Fxg{mXr})U^$Rb2C9^>@_G7h5)<-dZWGU~5aOcW|_^}B*2p<4x9
z9oPqn7qmD-5Eq5qbBs<N(i`X~i^M4;+ZLE!V*q3vBhRUT$Thw);N7$E`J$OiTY*(~
zzPNh@R)L4TjCwZ|;HSxIk65xm3&bR$<34hsA^*ESvbNu_OJ%<N9$nfi0t;#7{i)DO
z9Or5IgM~Bj5Yb)^!`0rRVtX0=o-<m5EwDhx4~(C{Z9G6q9!T{-^zNeEqU412Zbe3a
zPn+KXQvQ)bA|Gfh&$CgIPqGs|dHs4C+76Hw6TO0#Sm^$&z~l>mBa02phyfLfl|vM^
zSC~?UY6rk5gX>THjgsCYL~9|J0^ki1;SM_+BgUN}Nq<ni9W@>Otf+C|8@OVfSS(^u
z7=PcQ^%1JR2uv?%F|f)3I`ilwGHZpv6TP*<<OAUq^XuTaYJo7|-cRNOA|!ti_JIA>
zRs?^p$gLTADxCp13pSv3s;q)cAaI3DwS*v91m+mbfV$NjQ4~`FR7_+b9&RN&EXu`%
zh#0;xe<Do3Zl;kzpiH^QNV^EQUW_bNW>=6E@;8ov{bl|`Fk}%py4<oZ<0H$qIALHS
zUMxn}gfD^VyAV$zAtgpAAQDS^o)>0_<<@nR&7+wG9x}69Qc?xpVFuPA(asEvQ$DZZ
z-1CCNu!ipn+rk>Sr}VnCqB_I1S^%K{^7#NEzf^fd5V68@0Dg!UTmuZNUe?i;=ov0J
zwH6>=ZpxYkdWEZiQ3L9PTjjmsqh7!UK!kAP7O*Qnbn9m>Fi+X8hQn{ca`R_ye2aNR
zfIM&&k7m%AD;jJCjk!IwhL8_hSR0J5i-6x~kd8(lN5j84&<~F!E!m8iu?QAh%oThi
zgT-7H*ak347rbQ4H1{J&Ov&r`v;@5M{El+qk#)Y{*&#77wyIq2OL1X~GSH4wv?(Dj
z;YbM$pM=;Y&6%%_TyC$db%3n8Du=ZMX7$Qa2b?Rx>yMWr#JnkW2oYjlIq6#^>KyQ$
z!_%psxzb0FIN}>478DAyqg^<!RhgQbryGBmcq1MAwh2E4&}7cCYYpa97szZ2YpM%{
zHqvZkXAr5j0Z7d&OC2F!UU}*OWnPp@4L)<40we+avn#Bwb*`?iozC@DI$xGyI95dj
zFue~*{;iJ<h`xYAU}<&5<F&A~dRo5^5Ry5%oB+e^GKjOvp;vBtRzY+a$Rqt1o4L}{
zkpt^QPi_F=^Y-XdxB!6i7J1V7R9Pe}R&IT-eD$9Fz4Fx^rMeXqcrZF_k(eBx|K*Ak
zM0nUDFgYHwQ%UQNq%LRHy0dt>?!GX_dZny;J}A6W)?thFE=9SaYRV!3RRD*+q7NJJ
z?H7g9bah(OJd(5)Le_r<jCt>9#Tr!ly5|=3N?&*Aw_f?{0Hj<LVhv1nBb>q&Eq)e<
zLiYpBTr_3lqQ!6CSTJQR`mG)X9uYU93sk+q;_8*&4wI{Adb?9Hbp58eHLI8$AfSV=
zJ17^*cOS-1#1Nre<b8Q0iM<NGBPB!U7a~es4v#h{8&i4n@ISdCG#j!(UC8zgp|&jN
z^2&HJ^x_p30c9@4d<K-cDv~xNd%Aon5m6RxVu_&kkgKq1gEPgu)Z}oLxbXc~n;#;U
z$fZ71YQneSs;7!l$VtJ^+~}kOEs80-stvS(W6QgcHV{!CRdujd4>}QN<<W-<2`BsH
z$Y#7@D*YbuWs8zq6Y*tU`S{B=9&Lj27zb9^MopcF(9_U~_&k&a<wPS!&0R%I(8;B`
zu#;1Lhbh+OXKG=KbuR!SXuR%)Km_UWLLka*=au-6bQji9da?X>{?Gt{oj7Y;L8^p-
zO5;(o3BNnliB~o%7`f+fq%v8U0y8DgU8>f+*kQw-S{vM5x)<_N7lo^oR~#!&y%OYV
zEw$o%5xjPwNEImTCD<(WBKB9V&#HVy>@UkYSUB!4Xq2uu3o_T-bq-(o?*#p7>Os`6
zmPTB6Ws3u-omIJ#5(mCBeH{6EE^l80Cj8+lm(pN+b$7JZouYW<hU`KwYz0_V-KAZ^
zZ0oAi(opC(DEQ1&FV1PI7bPBr(A=ezMoDCM-2$-Fx_}!lyguFaXhHU;yPjqjY#yFn
zo)j|KHee6+0)NQD14okb%bCdPULb_0dJ%*W8mbrKAgr5<G(gCuF9^b>8gH+}1RS8?
zyA6vt;7DU^A&SL;l51FKgHRw6nF1DBm){l9h)0s}Y1|M6VQ~+20}>+_y3hu*`{7=2
zgSZlWV#*g*NI)((UWh70)NXESne*GtJxne9<`x#<;LR;8)6Wfs5kZXWYDB$9S7oFI
zOP&|RMw&xa<u578(Tj0HElr(40>oznd!+IstCaNvUkL;1`8z!wX$>`593l1X;ejmt
zs)q;iPPs80Vtfu9dU{GccoY;e$TPq(f*GRv=m&wU;G+N~a9AiYDdYv@?MZ8nidL;S
zL-K}r5i}tdED5qcJ%-z9P*f|Ytl}l-$t@^Mdl(cy2svfGj20!QT$IKwD71VSOm|9;
z7BF)=xU><HOF}?cA&4i&n`_@``V+*;3PCiCt|*St!HC;WZYesK`pL6X1p!X(sG@LB
z-I+8RVTkyd9P+Ix0$uxjGzn1b)ErW%dgehMzmSsUDP=wJKX<~VS+dKc!NJ1JNV)Cf
z?fi9sZ5uxDjP`b?Fn|RxntW0=?t=0QbDP%;u_(>OT~dZ7fW>V?<1dQDQ*hvrPPHYR
zDP`^YY)Q-zJkZ;vHG=fETa19rw_9>X3OC=4RvKT`<dH<k_ftnw?%qWizqENm!PeIC
zPOej-)7J7q;UNWB{j|*UKsqAotn+|Grw%#5soH5H(OKN_1}w_a`=|punSeK49rF=t
zh6{u<pSsWBVeftFM&sl!U4wbrF}O@O5o60(?=>lD(sI?1=yzRd7~-QFZJ^By4H8US
zhRcoF{nU*H>2&IoxRpB;?z*^FNZ5%B7BN(d)G-|J$GL&3lms_Wm6G5F8hmOZPz?IW
zR}${AD>2=<f2y_w_YW&cjMA?-_bL4f-=4qdR~;+4D46*LehJd9`}K=1*CF|(?{!)r
ze4sU<bdnFTeN?gu@nEj#x9&VkRmf@ZEL8=Gaq`Ggy@*8O3_>(bsx_vJBABl9z@DX*
zOV{qBl|GJ7H+8~Z7)_crW<02dRGEj7Peqk<pq)XFg-$zz(i!`pVj^tAPD_IxCVdQb
z!_tnSZk#CJik+~HePI2CWk0z7Lckwfe*x<cy%(``<El3tCwA!(hnhBbz5MVgiU0$k
zI-(g5N4RAl^<3l}9(BT5HqWnmsP;+4v*~=F)I6&SRlbHX`pK<b6{xtk0cO!BU}58#
zooty+y|4tcsTY=D^39;?d$UtMRhKIL6EY0+>FUJcQpwq?NnL4j;8iiH_NbcF|Igan
z^xT@`+F|qOSDazrL3bqTgVfZ3Z6Fy0wmYLB6C1t(g6e^9U?lnX*&^3kdsn&7d#X-f
z6wrOdcT1x5NFqg%i%XTr@nR)1yj2Hk^4L7A-}$6AYjK8MwXpKxrgif)S1E53%*6al
zxn!l`g%+W)X?$eDrhPt4N@E{YSWL}zR0Ff??Zb36;M(;zZw+9~yiH)k`$H316;VZ*
zm}nyy6sB$;cDO+k!C;;~xM#iXdBcZ(g6|1mtQRFqvrLFJ4GyHlsU(~5*qTEk%@<Ng
z|59n{S{W*_AK+Xy-x)W3m;Dp9H*26&zgF%|_-!E#^)F1f_mnXf!**G4`4iURsDt)f
z&V8r~EHX?GILA9rUzr4kPI#IG-bp=?i;za@%p=)Y3sZoUhHqmxvmU;U;Y^J<E6XQQ
zxZdV;=2v{1+v(i(Hp!QB*V|}6!c>Phl;FdIj?dt`!$66T4(#~-=ujV^%mz<AIyC+U
zZw~BvsS=0GcL(JMEf=I0p%~kErO+W4d~#5lz2K9Bj<oQ4n!!YCY4Gq0zB<sIZUonc
z&Z^+cgHq_h$nfOr5txPEHjwBpur%KJL~)l9uJQns)r*n?ggenR`f8Lf))dkOow26T
zKX4$Taw4D6Jpch0I1RSwOTfb$PU8bL&vcl<x9C#p6CN54P1mzC>fsPIa7qy3dLX)T
zDvIV(K3*hih_jwvc{m|M%6z90rNu&zpPA4WFQkQZpB`8rZ>aRYnx<3f@ZDOOfB9_v
z&iq@!8B@_i*Vn4y6&OR}tMxnc@B7u7Jq4erYk*iPretUb=g2!9C_SkJ&_3u$g>KJZ
zk})ZgC-mly(FC8|Ihdm-cMj&@i%zMy2im7V>t|~p&;Ju4o^KC<ODW#VhhWOKA~%Cc
zS1e`lyp;MHI1a9#Sv~XeG=MYOeVV3Ll+I|`4)vgUZ7WK<Iq7GmB%5?in<h8cOh|n~
zIpvYHI-A9Qzl2pO=E2GYw|w(`ChafE*>EWX4k8QXVpe(L;fXetQKH=0%6H{}7no!E
zJEu18jDj+{l>F5FXgY)5RiSEFQUXl6lz_hts~x%NpjMe}9;KTvQh5X^i*|4F2m;si
zaoTDpAF?W4;RAwvkI)LfxUvn-4=1Nu6dyiLxvA&d#R(G#A14~)ryQE<8Z_n31n;Za
zfrI;Y(3%JooytHrkxXzZ>C=RR6Ym&P4o>ncoj}E!nYs%@SGxM5)L=}Lgy*SlnrmdG
zncXx^{MgD0U+H6*)BX}Zo#-Y~dDb_1Kq;rGt|7xEMlru!OH+tw6WLbq{U4CZYf3rc
zv2drr)~3;ylLDzW#B3GsHq#-hJQVATAb-hJAoB#KRxa2^3f(2a9k%#06(c>7a%48G
zZ=4*n(fTxjww1n_;LdOvYZN9ENkV4hb9S9=uQLAaAD*YLlQIkVriPSUv+)^Y8ZNf<
zW|bRM`n!U694Cr3hbVaJT+xp<e#8O78B0Oylg?O;wgSkmCrLv;+V~L%2>tn2l<I6|
z2~w^x*&E%AW*Zt6oqxMN8x~dT8Wnwig#<utdK?WM=C;gPzeq{{^`ngspCsh1uZ9pf
zA>d3pF=VFt;s`zq<ItkOI}LKzKfmanbk&>s!T{zU1@x)g*bwLhy#mJ3p1eK))Utlz
zoBt5D#T?}{PJzPb{7c#TMY{T*_x_voC6@rfopuQDlow%YlE3i!oD}Hqb23yydk%N^
ztD)AQapBLL_b68s2XwhPGgg4N%xiYIBMfb<G;WNbPbe)SL$I*4tPEyl`$hJc)X_1*
zp->Af24p;;uK$Y+O{1O=t06?##RB`Y*jwa&CU;ZpBakkp_(vwE5!yGf`;C|y0)ml4
zvIBO>jBjbABv&J(5W!ITqM($#alOH2JAxM>8iR3JdqAq7AISySt23krJ^OEhe)#Hl
zDeyaoMg1K-L~DLtII|3hjo_VxPagN$TGRLNg=RP%YA10oTzboG)Q^_#Vc-+{1$6gt
z+BPO27Cca3fEB(6py7sVNde<vxB|T=?4HA+u}^??U7G?v{$k7;AI2xq23%0cli&ib
zGl;kWfY+YH2q6CUBq)F&x~CujT&hI{{5ylAZn=i3gB8}(;angE(tpb^{!PZ_yEI?M
z;=5J@tf|B4iZc-{JDjD8v=<)wMDT1{oiOEC-mW7E82s0A#jggnZwSrlk}CdC0(>FB
zGsFxQ^sWjF?{r?9CcwlliOghN`*yLy=uW=kUrLU7Z+s%eTclAC++um}C1$a_w<Hpy
z*7p*(c}_lK>jYtpx?s5`L)7=ww>=nwL=-}K9~elBQiGrYX2R1fqhqV(-70*xT4lud
z_33&*sQ6C_sPsh}TW1A~#Y4FXCg5xbfN+0#DGZG6-pMIrySF6NMnsZw9$ZSz6Z1sP
z%?MFqvQ04Y4q~1_^&QHuFv0j(Ivh4`gBdanLd8Psuz+EDEZ4+fLoVHKV5%<L{sT&N
zrOV772w9g5QjoWFI^ZZ*==h{3+)$2-xo3r*gAqn|FU<?!HP+;`q(CY()dz%J2MU6}
zlw1c2l%H6A?_l}~134aL9+2*7v2+vJ2wg?g{=_<e$Mw&$p^v50WaCZkjSnyx=uHTL
zi7oX;8Mu@hq%IY?4-2c{LAd}Kbbr9!ed8ib#(oPHVKVj`HE?Mf@*9{y4<CAVpSvJ1
z_*bGp;G9F4Hs1V-vx~XmY(Ia#KblX(js4Mj0bOkNwF<w2XIC9#NqSeQF5gQ6a#s(3
z6Jg(Deyob9u62NHVr=mI*csQW=dg)42tLUcr4$mrT202L%cpTNHeKG5a}!@f>OH(1
zpP{Fq$$<6QKdRMaw2x{v7ww}~Ugn1KP)&G84!N~XNSq<>*vY_mx!6v;jyywdx)a$x
zh|qG&g{KoAl?oijKkDSS;RDEIth}B(CcyuP&~7iKxPho)^gJIao+K47>!VTu)htyi
zbeQ$gQQ_3gk2<v%0iiS9J^*&6BPvu0;bsNi6QyV3d51VYPmxwZ{isGwlBr5fk$v<+
z#G!W`u%*=i73K{~G!frFWF@~8TOaU76PnO7hExnj{@eMeRUlL6qgsJXosU}g5VL@9
z<3!SlH)_-L`GM#(k)>kL@;m|Q_y&f$6hJunM=c^usn+@coSK9ikcD_6W5#&fgeMUQ
zY<*NKZr4Y(g7ne>;ZWdAsmP||j*^hzvoI*f+ggjPE{V=n2N8h`620q|^37-nmwXb~
zKnP$Hdh#13Y{E--2>g6HC58~vr|)#lVim{_L6%K8_6pT(0vn+p-47iSMY(<_AR7jQ
z{Vo9zYnVr1i^w$kOhPOuU-GQ1G(*ve6Ar`!37#jCth@o?ru#$4xGDmyj@utn<8AOn
zGV0OSN1Z$(x?qixv<j<^>kAkr#O|Nzwmg*Bed676$fB78EUdlpo_p|bAM;-rc(S-_
z2*#;InDclWA2kT+0R@0D6xaJ6RnufTl(*hAIm8@%S6b;u_^wh=i$^u`lQp5?B<U1N
z;(I;|YVp0niA)(E(@Chsf_9sD=N;|6%j@slc7&na+C+q*lmg%tCXiT>_}YY_)Rn>C
zFqHfRZx~8`0z@}o621XZD2F})Q7C1@a)|ggG@TU^_gr_>5Q{ZA?=ze@l<zZ~IF#=r
z9KI?;8Bs_Yt#LtCfs+T#q3I5QJHMUtKJEaeePkS{S8`JZn29v;rW`SEiqipm!nlyW
z#*OV<MlJ;tc;48l;&5eoiN8cR)s+y?DyBp^6HoSbD5u}$E_Qd0=xva6pqHPi*?d#F
z*iE?A_W=zMbiAEDzasGm3jnw3I+1seeauu*-Usvn61jjkKuSu@RJ6k4tyw||bA-%V
zhWF>^gY>pNB1x77Htk0lvlOM^S#ZxjpCrr)3{A#tQJ;jNp6+T1SK-Ov0E|EC&F#h%
zVEm%Y_xNh*C`T43Pli0O-&{*EKKL(+F2R930?|G?Pl^kW{y%;D4^RJg|NEE!^IM0t
za>2}%y7IZ1ukyqE%YXg$&(9rDd-e0%|9@5gH-CLz<=20Ij>7p_-`4$1_G+(x`|IDH
z|LLFq-2U8Nef{;Hpa1<&fBmOE{ZIe$-~a1B{U3k*pPzsG*XMqc6=AP7cR#z`#$WfJ
z{kre`$AACrzrE_+#_NCo%io?}(URX*qSpK^5ti;(UqG?BL;IcF-hi?B6}Nx-U;p#}
z{ZD`WzlzI1Q^Re&`hTsp<}qJF?(edBBb#3ff?N_t{wKH`1>pMym;c-U^6$juyi+;v
z6pnL~zP^sc_L|lHcbTN8I=LKhb^PS=f2;)O3RN2Oqx`)}qvJ;tl~4w7&mWkNnW5%i
zuCagjPiy_@zyI>fw>vXhW{1nH@B8Im|5&s4mk#*%riSn^93{iXf6oW}yX}=ay^zk~
z)nJKF623EUtcDQ$%SW-HG%SB)y}#6`+4fzQ*E#&}FQz}g^eC;SKR&+HHs7Oz^7+-+
z<|#p?N+kTCTD?xZYw@+>%SyWh=)2aYME$ZF&KylY34d(*Ut-B$TP)JPfBZYs|MQcN
zu=|hE4H`?n938w1-qkvNe7>qiuOU?%QjET=7M)9Z=)vf{l)qbTPwYb(wg2d8uhoAI
z^xrv3|J?qO)jtrQ_8yx8*1jBD<)MGq8tunRdB8j5T}$pFUsbzGC6@AlO13|i@^`C2
zx6%h7;g5;37rlFr(qP)(-vQs+&wl_0iN8lD0M9Q+hY-(qHN|{>Sq=V+?`m{t{JL63
znY}9^`QBGmZiY-OteSoj{^$;P$=~bPoOvz3H~s&}4ghAO28Z$wMhAG^cP-_k{<0ck
zSl-nX)beFDM47#-S$r(z?^c67;r$6@VECyW(60yB-#>)D{R1-K%wMnMGk?cIhB-u)
z^q~D!rF_9tmEC?U=*Ms5{P-PbV;M2u$IgB)r$4;vFFwzA7X3e@^qgO>-t#-w?uQ;o
zLjUTZDum;YY9i2h@&{(*KG)6lk{93BON`F%DIz~LB?;pCW)sCP#|E#ecO?<Ntk#j*
z<6ZAf`MM%}%0DWK@^wW74}Me><tIKvzoAh3bsC(nzr#;_1?IZ_;8c{ahX||DM@3P-
zu6V6ipVd(QveE?r{Pm}QQ@*Z<aD<PFqWr{{$TX<uhdbiuB%>in_k&kaz8>WM^%e1N
z-`<q3D@N*%AN5H1x*BYjAN54}vf@bR=65xgf8tAA1N@G$&iv|2{FI6~fOYo4rzl?!
z5B_E!6-D{FB0$|gDvI)TMflKtR21dwiWOt=QICY5`4-nXw3L-Ezs1jq&c1%L*xr;c
zhsbEGPfH3ZUsr^?#;52d<?D*b!TwQEl&>qs_^gzrpZE^>Hu2*<@l#6UIlozGZ_1ZL
zTZN4At|!9R)ezM8QBRbwD<V7YM@3P-u2@MJJ}ZjyGpf^dhTA{f6F;XrEx7T1@G8m=
zmiDjp&|mAAzkK^`!{0sV@>BHwK0eZ>Cc+<6Z(cK1=B}PurM_cunLl%slTkRk+@n07
zt3>(H2rZpFKI$1VzI|P-ow|*vT037{Z&|IK{p;R9_)#@lIPn$Qr-k#6e}r}eQ@^9x
zjDO%GH27hC3{Rf7Uyl!YZ$2t26VBHa0Xy(fQ9uM=SG4$Tj~2hH$6n8>?{Cr9PbmB!
zALDv@eCK1>Kk_kJ$0b`MZ2hZiHY%P74zTKx@Pldyn}1hR=94e0?G8gVtL^@kp_<hI
zcfzm0@=tz*bG<;n_XzUy-{6e-o579wdj<!$qjxp=A$?g5ZXxe#@)P;0S|Hv?)j|PC
zUsjVDxV}LAj1~Abu2yPg{3~05$t93C--A;gq%Q}z#z&Pke)RK<n0i-0{=6@%*#4+s
z`$s>Ap%`=hVJH6MGkxPl{}ru`;Lr~r#xN)nz8;tZYw=wzh>Y}QHKcHQS5r=>FRQKi
zO>ZlHPj5if<ovVzlV8AZ6w`OUz&~)}``~jL2RFWaPGhz192}~3{}|nOt083bT}?5Z
zUsc<uK{Z7+5`It(zK8q*EdS&e*w-WGJEzS*paAVXelxiJ<wG2+Avy26+G-!8`);-0
zs=WJmX}lZQ2k&YEL-?{90`m0*+WF}0kAHz1eEyw1@DJSsJ}fh&e0gDl*VISFH{~a8
zh1bKkF6h1gD_gBPQbK&N`a$}EE%#SbgW}H^s&8!2#;etrmY|<G$PD?aKUn=B{m?@C
zn+5Pe`WZv;>jH9q*GPYAxwdi+{amka($|JPAliRceUpC1xOW3@`|la){u#RxvR{3$
z`$77FEo1-6=J2;~Z_3XY&u%Qv?;2<Pl>MxN{yw>VlYU?di{CDW57JM)>dn8b@#9nI
zXVg6!kUp7xlYU@5|E(nX&7u9vxBsE_-!twU^PlhN?>l^rHEw`<eeB;3`~SP6{&<Gp
ze>q{%$E)^rahFi~)BmgK`N}QzzIOjV-<2x?cjpu<cQJ&+P81c|6^cqn(#Y_-Jw*K$
zu`^L&N|#bI421P?!X!lb#fLMx1hMv^DE7=J`6K~7)=NTo#h*pFh=nsUF*4X96!VVM
zl9zx8{V)uQSPQ@r2q!)Xz}LbVlvH^m!>OxOYRxApV5@>f!pmb2i8jL-(GV4%8jPAx
zN78U%z9OS!D2N^jB|~XeV`Tx|Elh3s&m*y9RCxVUlo|p68jztg6m4HPZ{hSg0s2G8
z0#dmqpQP076S+9U83`AT$)~q{<>n0MWgKV~;X`~m_<+H(e9~_bY&kwJ<7$w+GnCvm
zf_xDY6zM!K0o_JUE^)3RFt>=qfwO$P<NX0w|DxQ&!KmoPQ>b#GoV<Vn3FYk#1Y(4s
z08YaPVd#H43WwAGAFw3h4ATS3TvX1Arzph}V>nL-U#$w4r%i7SVBp6lOwa*XVJK-a
zz*J&0#t#`nLy3-070_KB;x9rKlC9WG6bC^4OUR?)7>pN0Bq+F-TSjl?=pI`T+6564
z2~dEvnz4D0gFz>lyZI#-ViSq_Oz`Gvs~m+crH&Q^iNt1@%6VH?&|vY$sPuzekFg2y
zj1;7ofNsmNGz4}4SC7~XMa+1XV03qu^E+=qZ~-+h1ch*R7V>Yq7(!ec;%j10LahNS
zFW@|S{4e!$bnWPhflbHJ7q{yHCg7#i9zPW$5=aYvqCN;?8IepN<b`+wA7$_`tq0oJ
z+^#^?i(S?p#3RKfB-h2+%OV;CMoCg~LOLR!;+-cQ`35ef(&px<lq0u6%oLEq1Jb~c
zP$7F|OjU<b`BK;-=1N)KD>=c7v!(RCz|@O(a`;MT8jIqv17z<~YNK~x>^+x+zUm|k
z!87zWUZqes6&(`-Yv{n?yA%X`b%d{75*vX8T7gn>#sJI?OUI?u0dXmHLI}>`lFEAM
znkk5(#jMM%TJ0Dw<k0d=$Bp2;Sjw`CEDD#xZXt=5lDk*B)Jp)I=B3o=xbu3eEf)z8
z(Ge&ZOKGMrVpx{h3zCz>Qs!V}RJ|0WDsG-7cHtPy(&!w+Sr3ZE`BX0@y%ysQJCM<0
zDXn&c{91KDJw>XqOmzeawkArq(V?+Hel0)}^aj9zOJT>5U_!3AZ+o>`hXz=3Y$+!^
za@am)ExyIvXG;m60Xlan==orL407#&GmIr++A}Kk5|F?d_=d3<_1b}x7Yj()y#Nny
z8NBvh8be4u?+B5N)zvU0nh-KBrIu@B!&TVGo(vqoOTwS=g=xIHlv=P&{TkSB%%0p4
z0I5J$zx5mQu$$6fLMR&@?(8v@M!e4|VSq?(5klFxq+|w(G<roShtjNc;4+5tL%gmW
zwYuIpVLGB8LcaT#GEi-yyikdQu6=VUIp`-z#lO;H_m`+reuh`6<_QTBIuhK5Ks<Uc
zu-9PjgPyV9fwTf0xoks81Uk$n!IS})P}3|p=nk;Wkgs$HK4S>+|5A#zsTl|`r}R~q
zl#@Hvdth=Wdq0@lsTqK9o4}uXl9bC|*!-8WvWznVkdBv9?E<be1R&BgK>yCvK&d_k
z)!7c5)DWJ12gqYgW1}6cy|*E<<Hj_UE?Y_p4`hK*2DnS9>F?^7GElkYx<Lji|J<cm
zwTx2*D3LD;O10PoI)6zuz^1Mt5(P5fZDa{&8M4JhLdD-wo$cdjG^OK&viMy}PP;Pw
zbt{oLjyRt<{sef^fi3x>pj2;Tp?)9^2|(YoMX0>bE!OfB-2A2F@)YF!rQ~3Qn9>16
z`J$kd`({uT?m#{c;>&kHUxYB`X;cm6gS?asc)ld|yfHe-Z`&9l)#i?zxS=$c9jMUH
zC1Gn9qDLr$<|Pz|OFTpF5h4B(io>PT*dX?R)^f`$OY8=MPXO`VaCI9?JtO;QjH#|6
z`Nm||2V>HK0GyKm<V#03+!zA>=#>ulQqcEk7!eih4yWA^G)xD6`K4s;zDvTjZBRw-
zg@Yb~hv|6px)ksSEcF0jOfUTPCkbT7z>YL${4JEw_EKtsySlQRV!=0e^cl#T+rd>R
zwQdLFLHPEL6w4v__UDpvNKHNSSs8*BkolqPz#S=NLm)K0Olwb)u#17x69QlF$O90H
zRq9A08^m7km4i8I89bom1S@%RM-tgEZS4UWD3_X!bO&KdC(*~wB6}`B${-$lN4nS$
z22RH|dQniq2&I=-3WqSM<w*J(gkJAJRJ{c3+Tmc{i>b?kv}qhGA;6rDqbE$-G>)gR
zttNw<Z4{F$>DS1?5y}kSkrO(Ex_&9ex!_kiQn7|f%T7OoP)_oWw9$dF9(?bqjsdg~
zLh0#9ArgXO@5noHDLAx{L^_1D-X|bB!>C4QdeqQMVn>#i5UhF!HdiE;Pe<;TFyr;U
z1I{amyWUG6hhWz`WcH<yHAqC_|2#>mwWr;UlsF+U_Krk4VbY?Je&<rM^XF1(y1Tj`
zImWKe2ga!F4Gk#duhXd|1)$gaT={P@0vXqj7=euIRELo%>JoU)0LL}@VVmU@a>Pej
zKBFJaL0Lzm(_H-Y(j`M^L>;LtlY*}Zk=CI_BR5zGxV_KUwh3Vsb)+i06pj!wuuIQ|
z4j$cAi)P3!1v&Nh5QNb!7bi3lUrO-;rFqt0DRSlkC)AkX;e8401A<E^?;V-7qbuii
zuWQMruwPu;0Q}x@m5DCh8`qsnG5#dk3Lz);yfj6Z<_!SZOTma2?sZ*zwa^TsGbdID
zd~9@S)eAQNKGbk8{<U{;bG(!^rd$%lU#G3P18y;dDt{@t9XeI-L}-jI#d{ev$po42
zfONdBO6(Z2ubT!0;V0PnOR@5Af{i=<g_B)s=g1Tuf}y{ZS{sH^tqZB=Yd%?IuXs-o
zOw^?eRN-jzNuf(I2V(7|@Jg^CPJ8{J<Ybr94S3p1!EpiW$)&JWV625e>pQG4FG`kP
zB2u_h9a+gk@bw)wouoiKF9^wY)Guz6P0D)V+eVYB4uH`YB};(TiY9?xCaX)RLup+$
zswzaJaO^wMj74)Er3FYEP0I6v1Qd#WUyy)uS-h0|Ol_-SyoLqw?R(}uzeSw33pSP}
zg?rWPh2XIIZdn3W^{a^aqHet#ri*6fOG);z;WH6>G%Ca!`d<jvzHf-S290=^AZs))
zcOb@wfU_>8dL1%8>@xbdp=J%UHqb1jSQ{D}q?o|Ao(=<a2n)ZbfjXL0=#AT5gMPg0
zG`VFqTPMz?;Bz4#S~Mxl8<MO^7;YH!8+F~Z%}0TCJs{++YEpGKZ2C<W=?ziVnx+Aw
ztSMuBuY~I%ps!0P{%Dkj+vg>a;SD#%BLf7WRxgRYdzP@>kY(*s(5l1tQRe4-VtGEC
zA3I)QE(Mzj(5aWghEwVFLm0pg<kZKH6y#lh^g{)Chx{zrd4T__aQ_C~_ztdiyB}%C
zc&oY;c6%^D*{t#6<%BGIF6FvF9%<0~V1O6!s(Xn;KQdbb3iVRZu|poZaLz7iWf}b<
zyL?g_e^G;zo(;%SKT8V%h~k%o1HgN+E2X(0N|VBN3@k5{z?=kcLXi5Aij16dF7UJt
z$Wd2}eaEA#pDBrfhuIeirTpd+%t&K@DRr{=z+hyVPT0^VDeQQHcj?&x2KA#2k9TPo
z23vO+0bOY#dOdFYk&X;_c|X#T3x6{yU~u7+bX`(>XAwsLP%|%u-PAekM~3Ho<#%Db
zb;oPNC83**$(2?Od`JgmREKkcADNyD`Oym!?g6Fzi>X)xf6+sBW}p{(NF^@J3MVAo
zlayROAyYFT1RdEZdZ7h+NJj?jpNG`s0`Ys2#A!HSPkJ)I^ezRbQM4?fUx3qHN~wc@
zd2>P0b-=xONX|yX5T$8XK(L20$9H7vyQCZtQZ(E$c4w4;b79!^C|7PW3d`vwky`_E
zy5b^*gohO8F!_Yn5m#YO9&ej<7^YvEbJRM&6!t#Azcz3TjNomvP8>Z~{)}7BJsmVz
zBTt}*l<O!#=|ScC>G-27$40OEm%zTu40<W-YSyTzNe5obFNIw#3~Hcse=jW=v+5xm
zHm2UwW9I>-n3b9w8@w7y$)~hreBDbS=bNiknlkbex`3K4rB<nQ<?t-ASH~*Fv^$nT
zQ@@^rll>YC+(W7~Hh^O_-(46GhA!D0kcKWBbySI5LHxOtUgn&6kx<O#DF3NTsaOMQ
zy>)cB$GZ!Fq=XK@1NrB&QJ>U7+-0IZrKY%R^PdLhOJ#nNlGEz4N}rx3ocqYu<1U^0
z)CX{RUiE{Nx$aVjao)Rpsd^?3a+mcP(4FqGJ|D<7UjVD_XJm<t4X^_J_zW;2+cU(~
zrI58z7Z!IJpG)ky%k+GRKtoL%$&*}eRhLr3nK%MZ-Q?V-`ksHOR@pOgZlro2h)23&
zJqf8)%WJ6GD()my&jNSSqt6C=v_&TpM)4<O^nv_yDBFpR;VxDCY)rod^VxMHNK)gE
zienk44+NmgI9&>xdsoi@I=-X@LJd-T8LHu>7=Kc$u&e9KTVp=V4xBf4Y3Emm%`!GG
zKyzJbS}r9}2P$Rh)4rv4Bl)At1M5<f*)8KW)bdMV!>0`Umy|7AYgs7XtwCUJ>gI-w
zkuFcHOUb3W<sM>4BI%pjxfQywZ|de&c_ovAj!V69sQRxpWk@vXJMe=Vp{r-h66zaR
zrIvju>GSX+p_nXe@dUxRx0r%pl*^UjTIhvY@PL%-ac`7vqf0zNC~jJ+twAd8rH+wW
z-8Xe^YZKfr^*k}H3#FRTsg6n{roUG4l_GCX{JXf|mc5kX0;;mLl4g6TLu8h7C8jYX
z!t>2NY(UNSZEAR97L5&;J>v0AE40CAaVZ?HV-ii>r%;n?)-C6b-CYC3B~V#zE+xm%
z)ofsmP@gtfY#cU<r%1JgOBFWQeO!reE@h(<xjC3V+Mypql0;uLL|d<$vNJi(C0zdG
zpmhn!-zqb-bzI1O(GYz}6=p|6v;leD7Y)(Ydxqh$TL`ulG=v!PM>^8$+%kjt*iBvX
zlyAoX3hyg4!j4<sqJnL}h`N+IcMMrReYwV1N|!H3-^eR`3GCc3B5vM3vVc>kLp&;p
zj{*7qQZz(J$hFlmE`MvI;}VZc+q*+NuFY;I#Qoap8}e~2^$h{Jmd2a{QrUs5vXCYP
zy0XDc?Q5~Cg)uGlv@n3Fb{7UPX=k=do_Z-bJ355uni>^^=$h;b0&_{}wzT-We7X#8
z0=}qo8{Q3k4fO<(xrTazmDAT?S0ysn(4ZX4VW3n?!PGJ2<uVBiWNEl0_8b_Ispr5~
zF?JjnqcQ7=bzCY}SFI9~a_cfALA?~5aKLc(#lM$0T-2@2T9s;e26?z>qBi6Mb_HKt
zN`2QRk%7mp7YU`D>Pa)TA&rL9q05l0*ymBtmH*Y}QO|YjaFucv<?v;A1iTas))0!T
zSOhbO!0D<55jdT!K-^7N$F)Qp?^I8biWh3qhL=yDv`(ANS81ys2)w!34|1_w3dal)
zIJdfHbTO52s|4AXz>Z5}eta&ryfA{LhEr6+70e8`JcTG5o~kbevd1=9p(1U_sOod7
z6~sA{GYG~>Mfx#wOzzaAKr&7VYUE~3O5<-<mf5qz+%pHd#%*s7^$p=Uho%L>Q*K{Y
zZUbJ}kPj&J6%FmeI66)39t?o{@OnnPie0=O^47&JMCa^(VU^-d`xL2xE~Q!>B{!$+
z-Ui1FpR{{lO07cLy)UKMr)GUAH2~SYZB!NZ4AD6od&ZS;(&%l-f8^t+=Z>40vRN5C
zTwD%dHXsFuH0NOmF_-2%MwY}H#NLpSJRtT4mE-}TH$v<|=nYm#Yv=HHAGHdHi!<B_
z2W{8}C!<SY$8bctB=iiMjGVVFrN-kZ<y4QYo>!JA$;QH1B#s9J;E=Wrk1iilo(Haj
z<+fD~r7Rokqf*K;CD}3rb-ySm<$4=Zod@L@U9_x*>4WxagCm;{+N%xDZkNK2^N92z
zbG5-|?nTNH#F#v`E~Q38B^)t}K88AuzvKrT>KAvvA*~!s%7?UaEIS|4rUxaNJhp7M
zETIaL4`09oFgF``fvx%yRu=J4YS>t=lwgL<=W^FFY|u+#zmR1^NouV&x{s#5aknFO
zx4{ea5->6F6m__C+3Xyl)b?pvV!tq!8ineFKs2f2l`-!U>XZjg?j^9vdU7zS-pIt~
z^5wdeWEIYVPmz*W3-ttXXi&)K%zv{N2t$)LJ}C|5%XLXL9%<tf($J)h&yt2FWgIf?
zaf3FF1ch!=#%Bpkr^lBetD!3?nx&+4+maNO3o%LTd1t8_z#E2qz=#NbDaN1VL1pXR
zK<yoqS`F2~<>F;fFI;KWtenWJA+(&*(xhg?5#4QS+8{1XiZ?vky_~#igpije&3l%-
zG%4OQ@Ik0}BWv;{(1cOxN8E-w$76^*!wgRQmqL~yG1KqMkY3YG`tgD=H0j3+!q6y}
zp}<}OP7P#NeyxP;BY#axwjs>Hjh5_7sYTG$YtM=0-hVEkX085gn6RcsttL#mH1v6w
zua_~esdwqZ2pDmCb6Lfm+%nF#1(DW|#)dbAUf-^6LM}Hg!)3{PuuVv_9^wSj4Bq?q
z+abfU_fXH(DtpD1PM%wa*q#dqgMQ#`d@1axZggGh^ump<ySjlGl)IPVlKXg<a*QA+
z?^2GJX9?RHQBs$}M(~hO7sdyqVt8q)Am%!?=T%a!OL<-pa`5IdCSkq=_6<3wR2a<Q
z<9%ta((2izb1zsuyE1MWg3`Q0#YV`Qcj?#_)#iPwAKdWX+4C-`Mx;Gh_L)n-{)Y+Y
zQgHUb&T}aX<vM4&H0m@TxxBdynUq~Q`3ymVmx7Kqq+>UFCK|xo8~{~TVTQMeF(NOs
z)1AwZmiZFcHPSMB@9G=(!7kN&SBV3JxwJzoM~I{|^68h#{*atWpWY=6<+61N#hWy0
zBv<w_ecf%eU!qRPH?|?_<dJnLxh&gJtB`c<s8#r8d!wDY;#9rKRK05@d6Qs9@?@7!
zmR0WLOW-jNGp#pj*s$cfQViPOw^aWEj+6A{4KXG^EknSsH|fcU34T#fx*W&|jqJr<
z{#Or3#e($WT|Z!hfhpW5)%3{(z45emNt|OyCV6OC1x|aD1sbrEFA7Sz94Y|w0cj<n
z&V_o5c$HDebs+C7Lt@@b(eG=jr0P1J0Gf1Nq~Y}@qcqa+dXx6+9XnC(S(eW;-ei)-
z3ywFMr18dc3G5rPtC^-9k44_3L|4SV%ZJMl^Y4u+GGGBN0Wmn{Ba0jn?sW3;x|I4}
zQjk5L5L(x85Mbm@`Y|5boJkrlq4<|5MY`KdStuv-jsCrc)V7zzo*@R6+|iKBb{`qF
zy`<nS53g!yWf6x0Qq=APo3_`@Y%3Y0At&uVGHE;H;w7=?6gXR6V1@_QtsIh8=oR}w
zhxXb;w+xS!ODguYd);3p>BmUpx{nlOyaw+B{kYzXpCpid2M!w*<a%@7$KRb)8V_Xy
zGCWl8^EOxm6J#G5tbrP`5A@~)71{FWGN6uZ0^XX#!hb33`nD)rH6HJ`65JT_W$q&-
z8tE7JJGG@DdE%D;)}^d0zbh3h(te|a+ojZ-q(w=xeI#h3*9ViX3nz%J1epd$i7f<8
z1Ln#;vO5EGWgnWI!!WxNzF`>DK&i%KI=!wdND|nufqm)FQF43B=gWe4d(eR^mt^e*
z?eLgcVwH&nCJS>+d=mbB5y0;Op(a*ZGQ4uOe76jqJD0*v7p7Wx9abJdm%@%0=DMMj
z^Q`oqmy)BSch@B(S36{Nj-4g;TB_!Yf>Le^xqjV*p7~iqz8zMOESJIwD%rV(kb5Z$
zwQv-KgR|OJPmyxonMBkQl2A%DTDuhTT0QQNWF}Wzu3eW@Ly(a=QY`L}of@ON6m)zr
z$Su1_)Va1ps(94dcPThTGKuOADdSP*#2wJHAH$d1asV^Hxa@$YUG9B5q(j36a4QX}
z9T-`*e7g*ugga!qhPUAk=+$?9X9>KXlApU^gdUJ`QHCtnNJhKm+I17w=AsPg)yL}V
zms<T4r9MCOYT$kCkm(v*bcYn}V;CiO`;!TFlS66AXMjO!$#pL6kp7FK>ryxm@NK&!
z)~UW_nm&+zLDTf9HgW90Bld!0(li3M*&VV=!?SiP%dFve-g4M79O1h%;pR+j%%&{S
zB?h+35DiJOUD`FggEyVLp3Fj${I~?`sZFw7dhscN=5p6K5NJ+Q^m7w8=el=l$_MgH
zURnmv>lX#3;zhRT1HF5@jL~rMz7%$S3aS+IUw8a1r>#pV?)^cr&`xD{KBoq=)yKhL
zsB|-#^@f+%Q>0u!PMvwc#eU0eYXItHJC)`Eq?Zky=lMm+wztz9J)j)!+~=co$L+L6
zUqZ15&HASFu08BiJwv?tRL>A`PIL6gV1!#{x8*_gqC6<p0I8x6#4~Ik?6@}A_Mv`9
zExAFX2-B2rAL<8EQjT6sZob{r)x?BDBY#E)dfYO(ha8j_*QFH0rgk9*y{lcgxo+<q
zLy1A}8Un;1e7J7820)E`;F`4SuJM3W%d)HQmn8J2em7P^W49X%fqQ)LLbtvBg+JM-
z!;VXV-215A5|?u8Vix;Lfx+OCasd0F-TE{6gd~*5)}<tCJJcv8;SO;NNw|ZJ<|^GG
zULgl}==(qrmc!NqQZCc&>KuY_yE?CHes9N6yp#Vb;-fxEyR)CPn%>^3gl~%AuOwkV
zAVe%lwWOYbK(eG^vG!7`l7t!S`3+wbecfLFN|NVkJbL{+Nn`?vzMIstOB%&Ey#Yqr
zSCYWB1shFoRJ;ZZIZ0vThT%y28i0mL60UTYmb{0)e>d<hwd|%gE#4#8;Q;FqRAL5l
zhb4_aT2;gnfORZMSOYMjB?&gg0Xy4^=Hg&-fLaC_l35fi!Cvw?N$UZnmWtf-2SPiO
zL>?wqi?p}_E8~l#CyRjq)ugfJBB#7gjf#EEbRT4NldYvK*f$wln5#{;mN?yH3ojF+
zdzGNXjP6*)^2{Hw0Vj$5J3sr>OgR>DDsWFxg7wDXj}Ggh|KL}c8g5{?<2_Hou?_VX
z933xdH}^TXGBJ9{m3(_f8S#_!u88%?i`PJGcan-zYg~(6d|4x3e6<*OSx6FuHeMf+
zgdPo*VAdSgIqjX@b<VoZ2|ROL5{eibUQvoxV{7W%IFP2X8F!ja1VaYY#*mgv8~8M?
z?G9joB(dfIQ}W2aq>YMfD4CLOcPTaD9^!L?Pr2n^Qt|or%fGbx3UbW9B(%={C(Z<C
zvDTq0if-WHEopW9;BhV~?0?lll)L@_)WapAn3vO6nRl}R9GWDd<z4)3F}%s&7RxZn
zBn<~fJ#AjnQsYi07aMo*D233xR#no-w_~095);m$@I7Pzfg?%ep&FWEAh1rQ7+P>i
zNHMhFl8|O-IMb7c!w7HFNg@XaqoMW(NRy;s;~Q3J((*^6RRKH?3gWk_Hz<hZ)PG4}
zQqLY^P!PkdA8EU@45kOg@LMMw6vJ+kH-mCmzWq#1m?ZL0a#+s&m#|rFv7ulsvVbDH
zHx8FKz)J#?GPI6CflGh=OS!$j^}0b>x{ny5EKSAkDN3zMIqZ)?NlJ(POEI)fmL{fq
zhfdFTzA0&e<@}NqaxgI#`Rxy2A0^2!O$(DtPyHliOH%vB;_xK!2j%Z}iHAYix?N3C
zw5HSk7*}S>Wq$yjCP|zTcmN~~Q{u&rw)}9ivrz;qd^5QuO!azmM|mmF{V^af_fq%4
zA!xe~ip!197+6<w-XG&s5eG65z>>tC4z>{<!=9qm7n}G6Sf+V(z-ui@Xu3SxiUPd@
z?r%xMnK3C`6%H^ag{#5=#-woFqZ-N@rrs%78455a1*<{<E(wd%)OqKDrD%XltD%}Y
z?_8YK4rT4uWe{o1o}_^R<670-A)OnO!0wF$?dshqY_>FlIjV@0Zw?Mt*M>=ny?HB~
zkj7hP+QGExO|b=IQXDI|U`&c*1s9A-X`HXu4@j#B92=!E;tK}TuQ$aPj7f1^0S46&
z1+qd6#)Lptn85(5PLeRZg+ry@?yIRyHl_W~63U7hxCF2%<$rE6O67k-+AeAJ)3I(9
z7m#@va_ZJr;}o`QznP-6MQFg7Xohn_QM+_En89&uI`fP~*vUM5>^?Y`xChL`iPSw{
zLe4T0V62u9vt@f7ixN~0{bNyr(xZPY$i_v>>L|?7r)ZeN)!Dh!^uoVM3LEd7#KFcp
zg}mJOFAbAOXNF6{97?XUh@)oVEj4Lq+qgnZP2<X1v$IMtE~?^-a&ZYZW*}^#V;QV@
z|4A>S0T|mPk&(#>Y?_EE-lUr^rBak`z9179Ur{cl_G|j?-?Ska+|--A_cN79PS!l)
zfHHC(aZoZ+{`;er(UY_+Z+yNf-F@LUI;FZVO3W$M9bh$2(x%#SROHAu#-VV4ft__p
zC}J4S*QtS!out*CUnN_WJa8<^Rs{%*MfqA00&J<a%5?Ql`8plN8m#pDMcIlVfhS3|
z;T0t?7R9Z?1TLvo%+y6-;TPHWZHOXw>Jor6@<q}mU{S_SN%u_|TYi%dXvMme`Ar$C
zpn^*R>(u8rMeLk1!)(e}#1)K<DmYFyg{;B~#-@~ISizIDI;<5~FgEY7lN$eqkX2~G
z*c7rAT5ubpZA!rfqp*3BLJo{W(=}jIs!roG^Vqz<PMLI>aHvfw?;Ao>K?P$|W=;V|
zj!mJ7u!2j#*OR)wOFm91>znd%>b+)cnvWDnF!rh<CuMQUVabK6mxO^^?xu8PD8bm2
zj*2B1g~Q*QVhIMY{F8(UrvM#N`ZuqlL#q0QbR5#uH>G1~qz`EIT^K+xDxX0T$dhAo
zhqU({nA`C_31Ih48qT6k5vfRmu}eZKkYM0)ktEz7Ht(WCO8=%D%~*o5DMb}bFgB#<
zJD^}}T8;<x{!P2_kmm1{r3xt+X^&3=tuHXzCk=diBa_<r-pHh0cAOG-)X*H_R-p#N
zDQ<_9eee7zQudwVc1&4cobpxy2g6Zh@4Ss>xWRCmjEC+6E{QyJA#jRh#T*QWNLJ9n
zaNb}Qbubcqr<y_$1C#!byemnn1IA~S$UjB(5KQ!N%IaY#);3aH!f=Xd1||%LlpgZB
z8cs2-*o5IU0uSl+PDwqa);lHjJ3L`{iE4!>4Ci&0@d?9un^l0q@Lff?M-Nz>l7^Gh
zDTGZbyHf}oRCX@`tB8Z=QmS{8F7A}DMqS(~UlnsOobt7T4xXgs`c&k>aEe%k9t@|5
zH9BOBg7bJ$oY12Km>)&M>>kW6Vhx5<peop4WTvJhP<A4jQ_|So;pn932Zg6eLk~*N
zir>q|B7Y*=eNb2`s9*$zr9ownG7Om%_JEK{n(;TmN;tBDuQ-Y;7(r2~z=8pAnIw?`
z<BUVV2Zg613r0|QGPK}Qa3eJt@8jM`6<IKXH&W9rA$TJ-ZT~>X^NS|cK6u+S?d9NO
zjM+y`@F`<{AYLMA<el=Au?QnpmB=>5sj&ziyM#?pm?|D&1f{705=KCpT36qTi?UPN
z1Z~8oEgzJ*)=|VN)tw^h#>&WrCn;C~x;_ML#-{5-@I}XTe+a(lSgVF0fV(aRK>^%#
zH3$k|1wD+Q{H>^m2ejh6vsSjO>qAiZcHJL>!k3W`Pts~2UH6Be1Xk?B2uNVXKU_+!
zk)9qRBlxo0T^vwGGa_OH-+vSlF-{5O?kHgQb=?CFg>k2y|3J`o>Gy|%R`Cww=wjQY
z;~z>|MLdi{LCcVbaZn<Eh%rwZCg@PuD(GPxzRxP^VE`E@No2ry>+8G*96tVZnf1%l
zF)8(vD@Z%__Cq<^hxFk?If{sdaUdkSjP-{yvP(-pl#%_dr5_5(P6(b$8mzfMSggn4
z^S!1pBG?qBRto>QQc__GuOcT6YW&&Q=XguM3-sVN+ojnb3eqm!{!mJGiQ7Xd*&C08
zLowN<lph*@nzZu6hZe;xTv9RG-kumIz-xo-K9G|NT)32Clz|Ha9?wak*gBM)3SJn8
zva`uxe@b>XZRW$<X`^v|Hr`GZzc3pvr;YmkY`mN{Zq!SvuUFnBY%BP)8qREde`)ZA
zo{g_B&D9}aUs|SRnyn;k+v=?2Q#JZ%%|;2U$cWh}VF^rgX%w+-vwvJh6&^7g1#HGg
z++r<N21q<f!)TWnFf7%!#K5Q`$4>c*G*j6SZ?tXUCs+_uW96$(o9c?sI&IRgcs9Q4
zG`{1_hKHR-{eLzJ<u)}~3gwK$cxI#YZA0BH6!CQ^eie2x8%40<E}q#af)#l&8%1y%
zDAr;(jg{h;ffuuFY8wi@n2qAMnHZo5R_w)Wd<SZ#{x`La#^Yo*dPlUbn)HrPgvD$S
zx{9%w&1pYXki~42x{R`zjRLkcv06g5@sOD<D6kY)F&m|<0xKqV_EBKPMCj5vhrIz^
z@0_E#DwW_Mwqh1)b(YzE);<cYn7z0-c@{mO+#eqWQcRqh=g>w!D+AV1q{IZU_rbCH
z6zP7FgHVYHxbRzM-}PP2p(;NC7<3dF@l1$}bGG`rQspQvVnXm7#6?WR&z(bq{p^sU
z=WO*oFedu)%)(tiijJ7TZ$D?D-GKotKHbhfvsh;f<ncLEoK0}TtNR4d&rx8+?C?oE
zjEtCtYJbb*Y+-VTSX-Fep-EX_cJM)RA}Q8Uti<d)OYFJMz{5C+3H9hGPGWX=C7xsI
zdSjH@$E9W+1xri>qMl=H*zpaGGHe3t=bUQdveCt6fUz!C1DtiX7-Wok`h<#l4%<kk
znz$^{dK5V^k*VQQD8rD>;hd(P4_K$xJ~Jo8QQ*X^v=NtrQffv=krNX+wNB99Kao`H
z1hx8^Nwt!Ig9ETY&k5@E6KS+ggxaYi>jbU)GZSYW#ZOEm&N`tyrW2X7UL=%?Iqhv+
zy$)k1X5Gw=!Y8I7dB9Qp#Ka}<D1Kt%CU}Ad{E6%0k>lO8@hWW^38oDUXS3%rBA?jm
zdgS=F`W+bGmMFq~_Q-K>A}IgFQnd-@sE*GZ;Syu3rt2tFVj?NbiAm<FwM!s#CGidd
zC1&Qv$|BDTTbS)B-Zo}?s_$LXJ=AkO;+)Fse8oTV=N$RmO{B&;2$Z<xn(LtfdY0HN
zo?1?rx^aw$4|Wqqo)eOvumqi;Mn2P6bjsrKfKZ%t@fP5vgSYxC`Kp(d6B55h!KT28
zi40gLn)-!kQ{2QX;EtoPiA%_Mpc7??pU8=I<Zm|t|8W9V_zC0NQ5eNc0FmQ|F94U2
z>q}|HClW~=*LJS#Q^yaREi>Z*lJ)(DWu83B9X?^gJaW97fL}QZw3vWrIqyJ=iL6<N
zffh59W*wJ8kDOUY8N?^DW*voE%s~OEP>YGYSx2E3v(jcAMO$1#E=;F(KT6UZcb)UF
zB%gH4o3J$>g<s4uv&2p(#wWFYB=GEECi01_Xh#lu6Ir)jlq{9-bgAVq(w}#>@riU=
zM=p00=KiB7jEQtwr}p}I2~LGz%mH-I<5JQAN_3Qdd?J_Dk*D1pkerIan3YcJIf}xV
zKp%QhvgG&%LtT3fPwG0}PL2=03C@wl`d95Ox!X--*E)=>n3X&0D6(Q!?yM(CWD0^(
zp%oL!vyMV5CUR#TMpn#xp*r5*Y(Y+X*MuC*v6S)IvV?;GDHRXHCN3dcJ5DqDB_;pT
zxRFciC~jf`TkI&e_{3Y`a}X3U3!v;ME@C1P*4eb7Prv~krVyWn26VQZStgz{527L_
zl3*Q$MNGVb9)(3ryptY0qTQ1rA5)KVi%-0_9y!NNr1U%+sx^{+-ZDF?gd&&1jwVJV
z={q47H<j&)WLalRbDq$35547Pg8Q5;wRtXZw?10Q4Y`;2h1lEcJy(!>NGCokSJsiI
z+(fRdv#DNB2)(`3HEwukPxTGCx2O8{Ea9kzJHe6X+=L&(*-ZL0;jD1B6!3CqI9vKR
z01%I|l}`Wwovox#vk-vJmij#dLy`(U17o5J4rh*|6y;AbCuJL1x6YQfjkH^5oBDyY
z+@^kzzUXYK<b@r1l*xP|>()tsxrv-xXVZIrBInj2cu0|I?Midcq+4f8Z%5Lt!(`|a
zjyOk-a?eCYt)qnJvodO(EtMM?wJrrm5)x{?C@9^<t~};*LFO&#({Mw&6gFB@eAZE;
z16Q$iP`ux7g{A=Vjvj3j8Lck?CrhCZT>>6vCz4^E6)5GD$=z)N;q@p@`7GD3BTu%u
zAiB=lAGLDfEUL<DXMtnG)lLp-6W(iQ3C(AwciUM@ZEj53Qk$5wrQtz5DJ%Kw^Fc<*
zg>4p0?^#QImr`*SRc9o6KT1VDR}K$)bItEz2Js1}!Xw|c3CF{;pzap1&n;5Z2C~m3
zk&A;V8=BVxz9b%z%<3%Jx94kxoki33#0osCEZY-n^eh^-C(>P=MKAQZDYfL)Hp}Jn
zEUD2OH@O8J8Hm(pNl(tCSZDF2Y9a;JSyG9&WeEooTw%|WJ`8u+gLL9^<GKIH$8Ey#
z_AKhd<(qrU<Qy_?9(4;TH_v;{Am)@{d?HEKk%QaJBw4r2t|8?nbmnK`a6R*=bI83J
z>Ku|!smf=b<4M5zxDmE}W~i@Rh-Xq|-U~yJio6#_AQd?U)tPU5H*#y8DSa3M?@WKU
zTl~t{4Y_&Jhi#@%y_`uMhNJqKQi<Wsex_7n<kdQJtK(g7p@-Sa=k_e%L;=YCi-J<F
zgSphJ=h$f7ekN3nqjcvJ&iY55Z4+MqXG#f1zN|C3tzQjQkyRkPru1E8$a+yw%Dtof
z<P$pEbLfROD?8RL<LE#*?4{tWM~193X`h}IS#jo&6$B7OC$pGOWK%eDNV}983l(K#
z$2wD%Y0pI^t2DIOGo?2}(>?NEn+Q!gN=QDL4C}}bZDxqenf;?uEi{>)5i4^h72}t>
zf2bU15%Vmq7%)O-N-IW?_L(w6BaZu0C?YD_=L}h)5e|L^t<Xr1b(Fb$B4+3e=++MN
z#~HFh-&<0a*)y!7OjJG{LQx)U6M^<;#GAPVUL;Eqp>>8dW#3@N)er<>Mtxj$JJVyG
zA=TL-28UE<q{lk)K$}R9b%s=DUU|=uow}~YXUI^EoAVhkRO4!Wl&XB<`hCXcF^@a?
zrLgbYf|TtFz)Q+PxwzNPB?{0P)TGNSafWnc<j*=vIX+>^IC46hz=*gM-lLH}>kL}1
zqh$e%B7N2wQkxOgc$9*CR>q+xNjOE2K<f<Y&6Pmw45`h5JKmt$959WJA;SagNk^H?
zCtx~`T+k*`HyvdqpGcy0221x*<P0geFqfSn6&KmD4ik<~7}<`T#wLt#&x?fO9gQs0
zu;QH|%QPTS&S>fvlCOZRYk(8XOHGc6wa`$?c{CZK%XE2^uzWHv){%qR1f0xKs_}`~
z=0o4HS&6NV$;gbvR>$5(=77|)Kq=RbX{Q1)=TgvUX}gy|PT=%)Ojc$Db{~_KIdfYb
zB^#fJ4?pq_n@IO|Z1aIDa8)x|m7{KICbM$jrlut16Zx<X9Lnzf4wm_2GAqM;f8-rD
zk^1hKl;Jp-PJ{*&saTY;`QU-Ts4-WHtD_|16E748Zef#;7{}=QJ@L|UOvYxsh8&Zz
z`CLw9X~tv9vB9|lJi;-l-oQ{e2Gtud3&&(>E*OSmN|8DN)^JR!H?kled6i8h&bkzw
z4FLbSl#RP0@P968;U_g9DcfgM39|%2Xi~H*ch-|6_5(?1vRES@<S}UDl{xDu4f#ao
ztRu&<iPTxgWV1%<tYcEpkvr>{l=RG<b<4Zr3?|+V50aTrB-1+bBb!L3b&M+dfvhy?
z=!Gft8e^A|e(*HWrIA;@ts}>>iF{k9OC?9Xt><*wvGa-bD1G_FBkYmK*u*pK>9Sel
zE%#D*bO8$QbSmJ5m3O*~*2txGl+=78nbx7V*psAO;9W**q|-WGMr+^@oh~gMKt!iA
z;p(Lf)MEGfs*x^cvvOx0ra7NToprj@YoyM4&C}JdS9?jpPW$shPOKwmu!Wphmr{qz
zg1^8))|aP9^}!Z?P_s%K^a9+_QS$QD@JcVYu+?gHUJASJn6Zgc&DKz>Rr2bz?tYnV
zd=*^gZHy}N0;1;W#tOLPbyI(M5a_0%!ajDCUHp;))f(n(zDiyFK+yHhekLYR#^nV+
znA5wuhWJy8@l{x)M{Z%O;gVO7F0U1JDK&zoIm~OHa*Qve$~tlzTMbvbcEs?;{%eOE
z<1wHewTs69_=2s<xP99BXg0TFQ{3f3s;twFCJHa@Ez~zer2N2EX39D(c*a~p4xt6Q
z#$~UC`i9JGp{at*Y@x2piR{QvY{Ap)G)KFzWj0s4Fxx0A`2qycX?ihQIU}cS@edK&
zs7Eij*<H#)x!9#1y~<thNmB0GRRF`MQH@@}AU=(%^a4)tX|!7}B-c7kcI$=gS_iqx
zSFZ|nwk+h<I&HCA$j`RaFH-rQHq|jiXq)P|M5q#;FStM+`hdMChK<yQYC#&xnQOiF
z?rB3+APw6Pzql5*0Xepi73(N_`Kt5a$Zu;QFV<<MZXo>NJogl-KCG!PNWW&Bn-qRZ
zaK3Pq9hJ(a(YiWbSz@PnkZ)Z*;6+}}T?^j5=bg!X0rLFFM{8xatJB&?rCM;bHZNqm
zdQq~3wHnG>zDkyaJh2vFc;X!OQi|=Ru%Fa@<H$q%Qtr$K8m+w+%4@!m*D4NF@rArr
zaY7wuLXbG2e#=&d;{jQ(Latm3Q2L>C<I7r>aLr!U&?$}23wS$mV0>Pwt;C@|y`a#<
zp+fyE=sclx;|qFG$R}$-cZx&*>y`S|i?Gx+fO+C9_FZ?gI7_|P5(%X!U&ve#hkE(4
zD)D4B!{?f8)$p|>Oe-5!oYJ=!6xTRYP1YWYGsS)Fvp7TS4=}4ei%^R=RIpd2dU%pl
zUCsPAyD4dSDV(+vhoOAr3z@LuC|T3O%^{Ad=UD?Xbv&{94E-*wKiamRg=<VGtNFrJ
zCyuspM#{vY#=U^d6Q`?Zyq|~im@izkf(~A*@?*tmAC-!`CVn0KwZZ^c$c`2A-dczx
ziqqJv|D{?bvn2~7s3|`S5lRt9U6+Up<uPAKvl4RPT9qCv;;3sp0Yx14U7IxGsQ28*
z5uv#%IUXVDjlix5fzU5x$O<JgU&xUaL2LD@lvokegBLPl1psxQBIRNXD8dT{h>*+H
zf|24y$<qDtRu>4lkD#r30Z1oetJ`~n3gtDw<(h9D1EYiYor8lZCSs`{tD!9QVi<~a
zY-G<0IC$mYO0tDglrMxUhWxcw<yDH9;$>j^Cj-A1%vmo|{$Lg_QkcscmXta;U@*G`
z_JXLVOTu}CfX|4bo~u<(d))&flanvRltvgm<rZ>bMNsud!m9{Vx2pyxT^!l6g89my
zB;|&YgV%zwGNP-U4PK>L56==gcP<0z)x*JXSF;d@K@;{ueyoVb5tK9xS+N)Fx)GAp
zNRbsG<r^uoB51|_Pv8E-a~ExU)qMTRZM~|tzqIBt$LrejAOHQg|MsnaYp?(6fB(zh
zp5Wf7X8-mLA}Q$f(EE#1z25aQT7?Y6y>dFe=D?_Hb)W-8%OAk6$OW{1(~sX}?{D1S
zx&ip6>DSW8;fq-b;JSm<ZOmcw&PueIl|-o}1K>nkl6kbkZdPPWCrFtBw}eI|2%rI{
zghH_ZO|kLg9SKR?E}2%w*$O71(=A+w>GFxYhx(s**m?VX=p~m14}|3&riOc9#*&`M
zyA+KQ3*M<A&+J+ybG=sne65Z-UbXk@AKv=e{mVrHJmp_4lG?UhB{dMO652F=wMvRp
zt&-k;vr6!Ht&(>RW2_SAHsLZ6Aima#fY`NG01U2`0vzl2Izc2ZR*4`SK2}Nmc9jT7
zZW2Xf>HX+etK=P;t5xFbH;Y96`n5>t(feK`wtlrn^p5z|B9W={`7q&Wkw|2|7l{_g
z>)Q5OA+L4O_dP#e|5&qk-@k8xAP6~xw~Y|wkmo4iA;ZfE5cOlYFd!N^=tPPmH|Rt9
z4JUF4svD~$^qG(wA)L=>NR1F)SAT>chuldkZumvubJ<G*1wBAt4GpkFV;Tfl&;t}w
zFP!gUB^N{fp5@j2B&9Yd9G^ojpYV;o1awj=cF+ej-K%d276TxiMmm5Zo;aL)C{`BG
z8RVwpa6y=G_~IQ5;l1Gu(8%E4kk4j7K+0tkp}vtGo25#H4_-H+ZUrH+zrl+>oT9(n
z>_Y(AaKw-F;3Q6NIB(ww><#DT8&SRCl>8aj8&0_o<?=<yFNph}^RO)KH0ZW@+WmL_
z1D~1_8vzi3#5_q@S*&iMmxnwtp}L1t9^o*%gpxi730uP%_f+bC2;mwLAhBUcLySns
zl@kHFQJw=&QE~xnTGCDx&?PQ<^x{0Y=WSk~Pm0?o;KPYKRmfqpf@Om4n%@vk6LQx?
zv`rLr%9Dg*k$VdHO#<GVuk$A4xQSTZkl!W(bz|#7esH<lypQ9KnuMC@y4h_S%n-?Y
z3EAPoqLP~@Vt8ZoDvpctC199&sgsW<^ccv#rzrWg6EgAa{B5nUvoR#x*kJ*P%?mrM
z1W}kcPf=<_w2+sjAvWE!VT*VXZUOhe&F8a&m&4e&&LcTbY^we#=t8m!acm)Zg1Fz<
zQ?nlUtlY?Dg9#xZB6K%4@8yWxjm>NMIb@3_bj0Na5fC$OFNA)Gq)8#{!-JdOHVO&E
z^j->dQH1nfN_E>SqBn$m*b&eh#65g^gQybjVMl~-?9vf#xfU%2Xm9m<cH7J59RfJ)
zsYS%5g4+?t8=E)yjxgTX4V~0gZ%cvbFdxR^{k+4*cqweRj>1b}yAWdwC`m8<BMaml
zVr(684>`6dTRXyCV}&|~hy5k7=aOzK)G;oQD=;7kw-xHUZjg&1*e`YIRdW0s_r68>
z+7W9T3j(%R7;Ol^uvZlAlO%G1o8F>G?Fgccwbd}>+~O4{jp?x@RXgnMA^gG)oBXA)
zbI;PoEaH|&?84rhQ?@j(CGOT#qmXxtPg@;N6|tr&Ay@8;l*N)+Qh7T9=tH=L9ccq%
zaeH=T4u~Zmu#Oj-7wMLI!>m!%cErYpFbg|geJ%xE_cT7m;ugJxnk3V;0CMkrHRzC9
ztE(BHnOqVZvMjNRVQKXDZ39b#f3LY$uBeW<*bvfTM`UbLYG#pr@>1As#r?z*2x+g#
z*bvI$CDeR3lya^Gao7<#8xvx?ciJ>{f$XolcnICF<B2j<%JYBnS*rsiBMPDL0V$af
zLSe_F>!sl6LsV=`|7a+WhDq_<Ul+d+K4HhJZU~;RBPuo~Wpqal)tE8>bYypm>FT;f
zmf#6H07?Srgf9Z*maqvs0%tF!4hICz#@y;VCD+{Q8Io!)wi*}!O$|>+^lZ$!|MiNE
z4Z#m~#Kwlu2RmY8W753PJEhm;CAuRvHh?|YGcq;=KG@-G5W*hp9Rh4hu6Fn+#H5#4
zha<zKpzrc^2mudvxI;wY4!(v6xc?CBU<Vpc2zKyN0+ndUfkc|JaCg`)V&avmSM+NL
zUa$kZC}tNo5J|um?1qd6G5Ivr5&Igmv)PdaG6IP-n<fDgsbB^lkZRd!Kf^00CjG=Z
z@STFNf*trz0aU@KNOwd+73@HgilGf`5JW@r5aF*c3QBpg6rSLv<m8UfkRgQ#CU^<C
zT!b9h5y$$395y=wSwjw+9iglt*uZX{CHCXsm5_lQ?qMN+%?=l`kiTY!pIOLVQ}!A`
z26n{11`z{0!e2wqm_5T^L)MKBIJFou;TUjRLLQmD0$h`Vb`RL2e%s-Y_oASbtSP%{
zM{H{dC$J;9HRQ3`5!@PsSJ{r}))-T#Xok0jPy%nc1~5^|-5`v>j#$@_zh)o2#mQl_
zmoH=pAg}{HKN1YE135qBh}jY8dMSA2=m>R9Qsa+SmLU=m*cwBU7J;oX`1^eQiqX{%
zgd4E|dwGz?klqU?(-1IV$FO4b_oP9-$;Go{f?^bBFWDwIz>dicq5*bJe+Uh*1B5>W
z2-pF^A9C;P@YjtYIXosu$P08wBx~4FHAp;@wmWu~SOXHzf>zm%Xx5<1XGbt=ScqX<
z(F~eyg|ddA0xzNTQb7gw0f8r^zz!37$T76T4?E}>+Oh4QFr5g%6b%3e_QD;_GCPkf
zv0unP+wTzu2Bhr|Z}hM&<{;ioyE|RlgMfig5^@O&Fz{0HBf-|%aqfm3KrdzB7c>mR
z2|5H0*vpweDd4Ys{X@ur9pL~0573T)fiS@hbi@<{aRD!(h9uQGW!8s98d5C`4_bX9
zv_FjR0UhAGVcOplhD4LPUGg)GX048h+Shj+DCVv*-i14W^}~!kLuQ&z00h*ADGhUn
zz`rDRG;&0`{z7XA)BP8UMVRitvqYjv-A1%*m@c@8mJRD_c!FW=^oaxdk}!sq1@aHE
z3h&O2V45(#XLX?FhbaMA2W)<r_IT-f(U1DA6&juTHlk~T?w(JQayGkk>giR&h#^M1
zF0&J2v}22>%KT)RjNtAjFU=0sJGun=gb?l8zJ-<lBx!-LvcyTKhnwi{2ett7lIS^H
zrR(arNkrdh67sW4ajv^a(2cWa6kK#{(*+#C=#tV1rHf7}U8wWXwIy*^yA%u!v8>T2
z4ZyvES))q`BbYThHzi_Oqia(lb}*0|?S4K47)F;;oFRzOC5I8u8hx-`2)izQcfmy^
zT{`>gG98_2F2YnpZkZjSsxJykw>L@BH928j3_w10-D+{mk1jnJhJcV)W-nvG6J4@&
z;bPbM_uO~AscVS1E<Jcb#P#-`_MJtXPYd#^-q`?wA5Hphh0(tMoLtwRtF>Bp(T=(-
zOTQdCJ8U-5bf;Y<xuSr&Qlms9>?LuqkX`joylw*_u5guW6vGR*-)NG<3xceLx`mrb
z3r%s|_nI!s2&jEtq%7jH*Cd5u8H+|KtmkZ9l+(5r&2<tZn)Z^|FI>yy?%8+C5{?f9
z(?-)BnVC<b@shkD2pe6=dd1F$oIN`%j?r`}M&6ZZ3U=<WR7P9s3$n2B=A5R^Xf#XT
zataQ(diG68*p|A6By5uI2&lglj<O_S)7^Sg61K^n@d_b-&yIN6XhXG9tjXE4BVP7W
z;G5bJFndYWY)Q2?#0sREoI5*k5Tfa|wIk0^G!rv;Q)`BHSN@xG0HM}og5Cg)2>EvQ
zjGm3w)h{Gg!<89vvC(8+F5io2jIikYC9WC-Cjwfd(bKCVs5KfdzV-g%M`q#;3_q9K
zW=BdYKXl{jnYStlY`5;Seh%BMEAJ)HQi`}&Ke83?+QTl_&A#jJ?6?kzOF^puXt)$k
z*{J~}8;L^ihgM)f(7T*AJHk_6lq~hz6dzr?cQ_XC(X}I3)sIZX2v+qY6EU${Tt1t<
zo(cWP<pBUNFG`k5l6^QZAmG)H@?>>nY;!qm_6&G+xoh5XdOe&P>%d3S1}ZT5CrNCg
zlv6)bjf`S-iuVClb=O7g>f>_R><C_Uxomc1#q&djID=RHNE`NvZ!vTfdPzb*Qil=Y
z>hjv`2yu0JZT5PUcH}RAic*V@DluS<{75Cn)3zTOpz-qUblZF>55BX=o;Oy5RAj`&
z`jLu^AXrxt-R{VP=m%T2-uzveaXY*MT$yn@JO}(x9Y%bs6SlcX#V)qCR|_}=kUG*&
z6Zdd$IZ}t2gVI9^F)~%Ud^mey(z{$ZI}qtFrTQ&Xm%r2H_VT>A6!u-mf-8S+N1Uw7
zg|j2Z)$vgO6e+h>Xm6L-n=8L<hhv;8zio%}oClQTK)PuUS-t?G=5*lfiLiEy?4~4`
zhs<7pruWz~D~4r}-Io66a^dXoAoQT-3?D;R8r+UJSr6Tm5hv?PjN1_>>+<95h;nu1
zv+c|)>!HV>N=NG<s}`W<U8!q3{^rbF+bho1D{t)sO0knxE#UmQ+&C{Kw|z*P1~Q;4
zhwY{081=@4P}xgCzY7D>r56+8>B!kJVNP`ZBIWS(!i0Hu<-6^0ul11O3;wx|)V5EN
zYSn4K=DKltZFa0I7xG?5kgEspr%y+es{=8wM|mh>u}5jG?%HPvfxQ$*1?)xnICW&H
zb~rip%46-W=U8l8ckMIm?MtElRvz5$y1l~5+vV)k5%217Zt943y=7YWPtPK|fmn21
zXc6w}!piG7Brk=v09fv>eU={c?y@Dpr`}!L3f^q)xSyVp|K>@9I8~>MQ-|bm*B(QZ
zs=M|WM35u7$Wx@8+qau3gq}l(g`{)WH5Xy3PM4^DU_Ww~fhvO@+_g^;mFg~i6;Y`!
z{JRd!cX#EA?iI7)LbL0L>u|x@b%cJnYumxi(vd;tDN^oD=f=yhRCnET5ti!dL)8(I
z>hhuL2ZjTe7ga|{>ZP#bl5eh!h?vw%LAMZZuKY9|A*t?$QmsH;o3p-d%m9ve*Zufp
z_>Kz^uLFhIUDx9i7*74YWR&X#2&$`llR5(R*5!%Sp#onDTRmX)UV*K(Z@zguwhDxL
zl2n`<qNQApScZ5i-*P)e2&-?JqOFj!AK$$G8sM~Flq^B!?NHZsZFBl-8KS*>D;2$E
zAJrO!mz=Q-2;sh+^&!o+i*bXR`zsQhY&jGNukB)dfHB@?4LI%3_2A}sC-~vb)DXJr
za;!2$uKHf$xwP8H=`m$>QFM7s87`B)mpFt>+q|0^?xemI=480I`d;e&o(nF|DMNUx
z({suY4C#W<dkhhizRU1zh^h2F)pbd=JvD4dwLR1ku=`vPdImFqZ$9%HOa;CNdP<ol
zhbluPt8c|Q8G>0aiOo9LH8qQC-!?Q`m%go6;7h4hW*Pw`qX6>^?&ZFDsWn(`eDkgN
z)lmI_9YcV^smfp(ayeBQtVd43JY)WdOF_pK%Ia{MG6b@^@be6TtiEv<w*D$C!E+f*
zZ7zo?gE`KHpl1lA_I1>1sTN*XYfn+`vXs-5A!gg<G-ZhCcKJ*hAl@B$7+=?uOB$%g
z-s@cU6&yjG-M&J7y(H*z^#iXSU-aj;id%JhP8q^hT|j$=u+<j@rTg<u6QaSa>vEbh
zn0{SAdj>prUt5jBiGOXB(xByQiLZs3r6O#|9ph_h{3R&`vu6loeO@FKb0f=X%F^(C
z%WM-OP!M|t1O#7$+NS{~!HKkIKvM8EK5Es(E4~2ce_s;FhPYH`l2}7rsw+jT<s*VC
zKdj-I!Id7?I&g|y?p6kH3Kve^r4)3%1yo$kvNnvnB{&3kcXxLQ?(QywOK=bF?(Xh^
z;O;KL39iBAA6_~4{OjJ2y{4G1uCD5?E;h63*<BNuSZYQmV}O*F=<O09hjmTIl`x2t
zyWnFfu^l|PAnvn&cMkp(pi_oWS6-c2r&d=^&&Vf|Ph~C}K%}yuUeIk2ruyf$kU6Nf
zmA7oXykDMZA}HP58}^2Z2tF1a6D%7vd>{#85oB>k8q^vp#YG)SL&TzdtatQM_BZ9k
z(vQXsl$4Li=`U)}tUz!qqd%k;(I{6?uOT~0z5gR6ZMWV(&LUdW{-pvzp+bI$T12*d
ztnOH;TB|6rCWJ!=Q#^Y+X(?%I0c7HQ^uh|t0J@|lNj0?`9(@X>_&5Q>P$ac{Y-9A2
z`ONv6Z}k#z1}rl6*nB2D%hKtq4;Km|Me(g-2&MGcsg)U`oZGpJe4k#K%(E*<r&x5k
z1A-PZ3k<}??LixRI`6|}-@sBjl1xK{b3z>awW~i#B9X){Q0zHCR<&<kBM4Pg+tkDm
zSuE_wn1*S&JQ`!?tKq$Aupi%VB|28n_w$L2N~DM+_rCV+$C^5Pa@_anO60Chd|p5q
zKbCy83Nv%*J=YX#;C^keiHe$+<}ej`8jqQ#3#!wD!@$b4qKBlxOylyY6<;+90a%DO
zanJm*5j;oCg6`41&$}_0FZcBR&Fg0#hnxj{$uBHPoUf(p?j2I9Vjg7?cOC)+VW7|b
zM4qvUwE0_eP#LB|gU$uZT?u9@wg>m&?wMOXAE(cQc~X(>Ho=tdcdkKA^FM#9`x^YK
zCL2AZnS)r-$Keo(*S=%=7Qqg{-*_ahy9N<tF8Rxg>O%VH!AWZ6(&o`T3c2+=y*E!E
z@eNU2`q=a~#UC`H`z=QHaLa;YYmH0(!bc<JR>5n08U}HK&ts@YHU>j-F!g!592F{&
z-GXdBgbwe?70M&>4;D{b{AmU4CVOvWdqG5ZuXZ_bwX&ZnK!{~y-JmRHfRA-&v&fvf
z?*MB1vWW&|t>`BWILg{MOLR*;)S%lke%>K|?)}bv7L>|-)OeJ8g7M&1M-R($Z_Sh%
zX`gyEG4KpkqT)exq4VGl754yqM4de4c|+n%d@Y?ZjA88<YX{y#Dw}vgu~EW&lp(=A
zD^|bx>!^$QYy`aLz0_x~Xt!l*Px=+I9=^c0{9!c<PCMxtfRvs~dwLZSy&Ml|Lhg-?
zFmtctaZ|H&xHFjy+iwqg6W&1T--3fIl#zCgSh!g?8>N)H_XZ}tt3)ci;BO7UaQ#fQ
zDi<9OwZEJuxPVf69?;v7XrlM*vOPGEdc-3*j1RhuZA7sSMA~9z-7xzja*t5VUr1pq
z6aVNv$}!||+fnXExg2%0_P8HCB1^Uz2dkLZ@WjFwO=8gNNc&o~vU><nCizID$ycFF
z>Xy1dp#U&}h&Bun85djs5^uG4QHn}s8_qSgA(Ub11<=Cj?Z%O;r_?|d`%%EW)JvPT
zv{{pcKi-9`y%qe|{LP|EddVXC@0diA)n7`Jg{0}Rcto(~BCm5(y#&h?5SKj750v{R
zekHxkk8*B7ba=(b>+4v!rPP0o<XcMco6Xh}MvMz78)DytNQM6M*-CIWY>s$Gw*$-H
zY_kZ--hIw1g};;NvfYG*mQJ3Km&Q2Ct*lSd!GVgbCl+-3^D+miQ3`*Q3S2cpMYH|L
zJYD6mJTG6M&}fq80(*ac&s8O}1Zkcb<_H-*q(Wr~0$RkqM0CWIlOwrhmwECq*Gm#Z
zBSc3q%;{{1p$GtU7yGk|yS-JZcULEe9H?GvlI$O)c+GvKu0)fT5uM=W*&+XIbFagk
z6(&++o@1=|I;jx*utDj@2jIb8rD=~8rzNtwoA}s32tao4(@DUj7eZXeCgs7WwG-(&
zE9{38ut^qCC@*K1Qxvp`1((;{^!|!g<|;jD#Mt~F2nU<Dlh%@^yFX`G3OgLhzOwa8
zc_oa%8_w&IZ<J6jFiL<QQ4x0ar%0M54=U#@B?<mvVvw6m5?p{Q+z2i<@3C;pKf(@}
z(6#Uku>fGEW)m4~Bq=ZOl9^@LK*a2fMtD*UT#Sd8-{WE0WpBd{2WObOlR23RvUQSj
z8OZ>1`OTv*B?mQ;*^IXc+i&y;eBgwB9Lg=~G447Z3RT&&=L+=@D#+Wry3)*>3*?2i
zsEWm(j0;CvgK0G;S&LI*Wh6M6LA2b!cDm$U2&=q^cQpC5?Z{}@3^;7aY1ndkY>4*K
z>;s~I*TW}<(S`9kPksKOEH&)&+t-n*<y`G<R;CTlhG<7OqK33KBR=Q(w^=0gmd{>;
zq2G9GETv6JG-N<wYR=R*b7k!|IR-LB=jYbNV=D0nSsQnWU(%*l?$*B~O|AUcRwWb$
zpkniVE>&zE)qW%m&Bub+)5Mj58e0&Y4-Lgi+QY{V$J*GFtR2xEaxB<Ect4qS&&f#g
z%<!*9!*X5|TX2ABTETk&tBFW@Q*|eLbFK*wG+-HoAor=sV`#U@BKl%!KguFj<2<8`
z&u(qiC3VdknZe2saO!K9$slSNJX>Ijljp7t%}?~dDE*2KKT7IGj7jz>Z)8lR@AIm}
z`R+>HX~ceYf$(6i{V0bh#mF&pmQA`3`0*)+T`dvKZmaxaT;6J*sxc{Jel+d3)Mw2y
z+yf-r1<F6JG(2UX7IrjTWnw1bX4#`0o>G+il_9K`r5o;4E`o%?M{3l{k*jk&jgH%4
zO(cq=-*d-{piq8Pkrsw{EMKt;8rC=0$LdL65yQ`08ie4ua@E=%5c$N%vs9@RLP@mJ
zS#-!y`I;7kZEY8s94f@yjVaYDgqO$&{UXb9l^lU;-cjRMHa6O*3My6`a}GW4(%8#@
zl|_sW(e`tP((l)`?uMa>%q#~zD5N!>vIE<~jz_cK2Y$OiS`<fof|e<_@2(7XJ(2xB
z1zRQ(Pa!Qq&u?2(+O9&aV3pLVQ84-RhRZ9%Q)-P{+8f5;sUsxK4hKRzp&e}biK@&J
zsFD@AluqJ>z2iG?z5Elzb0~?8s?)+0rS%>a?=7hxkap&=d>JcJ3`8l0UT#V`(?$H?
z7v9g$ZJ0`D@AhX_o~|R`kGsDO=uXm-FYB7NSVxM+8u<H-!PSA1Nm6Q}pk3Wts%JSr
zrHyn=t$T!uN>`uwtkZX#@xM{#u%O2`(S_K6ANk8Z3=^q%#Csoeej4Q!6L2~B)dUGO
zoxPLJ4SK44U9{*>VX2pSgp)W^5+p%q+*x8G;l}+dOtJ*Q=J(CccYSc&Cl$%XV#YBj
zOw=TQboYozEA7$VkqM}ZG^KP6Z=v+%(&oI?FCaFtDLGLK+_Nfj{8xeHyNV;`i;ks}
z6jrP%aKbpnqSA<slgdnLA#0$@I0aBY<EXmJZG|$NyF29eV@R5Om>!|Ll@*iyQ#|=`
z3PK+5&}xzl<@v>IOxbL6jGCFpPt8M2HRWDfj7uV*;FPiexaD(9n=7m1Xz*F?f!L6i
z8mqD+@i>$+<d0RA7?R4MY9Va%Dt-%fa%^9)R&BNzGL8C}F9+qU6123_ax-Fu)AIY6
z*N4&~eloAGq!ITsub%*EefzVs>{lb~)=dhoI)ut&<vNX!;0qPnWJ5>ZlKc!rG%Dr%
zl8`mI4~nalu&utRO|B?EBy<O%o$T-BBz-mS0Bs#1IM!1oAeLu3@I$~usDO4Ya5F%t
zCgd#4R@f=UfuilDZhcY`989M2PS7B5j7>@gwVf<Xr5SdFn6l9IC9YYs?V;T|fgEuv
zVY@-kgF?nAOm?7_D3P7ppi)M}NkDVvbWL$V!+k$=8^<7B!xz*(U8B38KD|V9gIgBf
zOf;k-+;SJU%yxOL5c9&oO=oJ2pmZaCwaCAO%$C+M*Y)HGtibBw)~^?*`_{jgTJP4d
zo;$?~=6u+ttWR$7fS4OtZps}^CbM!|g+)QlvA(B52|HSyH??a$^Y;a2`(!%xyYT%?
z<y0+ECONb5PQa-xF7^8k{2up2tw<I*w|x4<{(4(Iev(;rZibEvHv7;VtAU@w@)y3@
zWFOBf;_~f?D_dfo$ZZ^_bVYouow*=BiN2(RMno*Ao4hi?nfT%a0j=@iWgi}vxw31X
zwfp`+9_ycE=~)!;7oG1mQVHo8eiSCbv$uPFGDm>n<$bFV$3#Tim3c7n5-dWKR{9+B
zWD5)ZaChv+l-ZEaS!ZLK*+M;K9C9}Z5~`Lz^Jn8>2<ZU+rxnQdG!GE7LDitM{;Wi|
z6AmzLYph@UzUrnwyuhmGjNt6m%@%UYKY7+gH}EdloMqms%&{@D6iTsW0$fHz;Te9X
z)n%DfEF>aI6k7g_`gB-onU9J|!xtwS%x24@PNvD;?PV!4fw9@1xYq)UUZxMxIY)~W
zI%TPp0l6_Jie$cQxl<5Ge;_-#`c^{j1O<@C)q%>8Ov3?|bi7X+^G_j_quj76U;|Q^
zS+<;p$<5ry%ufw$c_M;6apc^Jt*_(9Js1h(7&)8sQwrW2R>^KXAy$sr<~@hz`R4uR
z6Sw#nyXi-GwY}yOf1(~LN3zjH1#b9AL<J1*&H8_v51IqX=m(iJ@A;j6gU7faGh2!L
z!f2U?s^{Wc>~m0hGuAm3)-=UC3DcB0gl+IAtpMBbk7=@5kgE7n#wS%VS1WN9$c?fU
zRoE}7Seyp4gY0e7TM^YQi6@<iPyARjpDT;+12MFeI*ZlTl`XdmFi-Lv?Ssa+vc-w@
z;zQOEwkS<K!2K6vIBRirQD7rgOV!i20#WbD+2xuczu(4I2L^V%Z8AL#qqWnyH>_VU
z_D>X9_ApY1i$e^I@;!+{Ss7?jDXWfG#d}xR`EX~;fK;~r0cQs&I*##ta<IbN7wj3S
z<#sk&6J?C$%CmJM>F<oSwVLLPvxOt|QDLEA==~aUElG3=MV-XDpj{<6$;vxb7J|o(
z%}Oy%6}6EmNO7&;ypy@J++vyNPvA;1%hc$jZFNc2?2}P$PSvxK$;m-)cbW?RI|O9~
z))4qTeH0Oh{<i1>*zBfZ7jn4#>tZuX<ouqhst^s`8VQf{(Hat3UjtR#v^0EcsZmGD
z2Y{8?!^0xtI4B6IB{wtuI2)~ZAo@+vrBcKzNckTL>(<FhD`;rqH=(W+dvDnZrQ_HW
z`EfjvF7oW)J);?Mi4H9D!8zI5Y=!rQdX(4swDd1|U_3=GwE_8m2n)AcF5Mhfq(8yp
z`VBbpL(W*oQLhlvN7Mr{rhh4L32KNM28ZXitkgK7ph16aJI7B9-uEKAf)raT3V&t_
z+~T+;!q)MMXa!_!8G1dcdi+L?kJj?y?t^d6>rB+@Lfpw)f+|DY%3Feaq*VU%HGBrw
z-E_7;bjr$pN!>`cv4z3=axl2P)m09PX{N~xzh898+z5@F8Bk5jw)(|@CoJ5Ep$SyB
zP`c~;xF7l%j64n*gFWFlDbxm)5uCYJX+Q?)Z4bPJrLi*#a}k?;0`Pe9GHMvrACC+T
zrlKmHR2>Cw1%j5ckhq%{$Bgp6w!!<;GL!sXzP4PzVL@9yfG#MK+Dkk3C(pbtPR6>1
z6XJ=HuN1tsYyDhmxobT>Z}U3&yhxzW=OX2r%>!|ZCC(gC3jx*UtCOt~X$tWUwb2Bu
zGn^w-EIK@|3>4etW?AR(<5jPWAjgYqKhAS4r>UQg7f-X2g#By^IqQ~A6LY=b-!d9I
zvqkSE?l#GL*4ch#LpU#)t&t{siPV3Aemwfxe4R;s&kjFC=47A1Sgq)j(SMcBgI}xq
zO}(*O4y+9_enmpot2!Z4wf}^`vYbCZ%%_417%FeV186z+%K$mlC5{9X+a(!!_p+FN
z2ud3HZ`xbQ8fYzuzK%mSpA+QbMG{gGR=hg2$XY>KVMgE%TOw;K-F;=CGS!K&9kvR?
z?U69c=0f7UT%I(7ODKe|B3r5BRXTzy=9^j~r>V15I$)}#60I;DR7K0ylyqx`g&Vr)
zcgjnZs?KXmg7<Mx2ycg;fRUdb^p&Y}bw8>9vIk!%UE_1yLOJ^*;m=abWxb%Uj`^#q
zv6eXbm_!L~mZKrQssd@xIa<Pj&g60n%GFYCjbYv7_sXJy?Y0)?h{y22gG2MSLfY_8
z45x3KU4DTN!~xQ0z8T`!8tcL7;Q|ZQk(}gEs(o<>wzHQs0cni}2>unsa^uj#k&QER
zf`O3`3-n<0nu=%CJ$wuv(O$ily9&pUVNeV7KdV|5Z9my5d_P_H9H+3P`JyFmNezv$
zeP>b|PxtdI+`kKDGaI9|Ha2v?t@Dra+Ga)bH+i|w7z(!XBj-5o*0XA+pxO$yQ4B^E
z8Y(TY@*Nm*kz3T{s@f3hie;<y(zQrIOE)Vt`a0l|(hC^df9A~|i93%s{pfm59#4}P
z?7(&p{OG_ctC5z8d#;cD=<wGvr}Q3)U9(rwH45S%;3|9DEs$!%s$BxNC{bU|%i(%d
z>vbb3J>W{zdr2vkV(PbakCkh~5=f<*#1hez%jvQkGpBr4cMQkM6nZ~smH$8=##PZO
znA)8=x?gTyV=wGa^Q9%jPy8L-$dT~7Z#Jb>TG(zrco<iWH@7y9BQ&n6+M=Ux1~)s7
zGD{_d?(4+js_^(NVM+@DC3Mf?_n>2?tlW+$^aJHqiWbtS>2Nr5EmG^{7&`rTRG6OM
zyQ^b_P&|5jtc2FjB6J(KxLZyF{dU)wRU0J8gKvZ`>8ck==t?6Rp#v#6OstzgY9p!_
z0(w?;MUbz8ERES)OJRjjY)6)@wv(tsk>T@gmxht^t6;S0TBFX2)pp74QjAg|T^&0H
zeH}1U=BqLKZ5=zbP+FcJJKK73a-586f2Pww)V1Y!V)eG|4uCp|ommMDqqkH*F4bj~
znD?66d^>;@LOaJB@n-CcYXN0YcYfW{qza>}M|LP$%NRZ6Pex-z6#B6iWWvUgrXSO2
zx*!VFux^*P3RO<-st*6tb`D(tey8d|v&)c<hF#6RU+t>Slccpd>dU>jNfLJ+haG)f
z`~vQjHvUHc;7xLIgS|aMBFaU1i?Gg2wI|6=yz2t)RkIv@&6m?GV5K9Vzv<QN{Y)K!
zN;aGQv25-8*9LzZ+e1jt6ngGnN$tYi4ellse>(ksNHMXEF0YV2Mn!Du?6Gg-7}sx$
z%ezl`C(erwRR2|qTb`G0c7cSB%{6@llwJ)Ns+I%HW*6iR%Fh<($7U-h<V`t;ksXPr
z*DjGP&*Q02&uqWY?stvV_D=Fdb|ee?pxMPg7Q$tc8eO2$+9_+Ivy1aqK;8#AUWK+P
zl}$i}EXsHJGbm?v-R`;j)D$%NP^b$K9S#Ot51R%lhxG}2T_Ac#Lr$pJHBy>KzB@d4
z<8Zri^W;Gl`i?sEr-U%3!i_Ol)WYE&Nj;VOUWBdo>NU!p)afKkbS4sy@k~J6VdC6i
zC)%L0A<&AVANC}7HGD5<qpW`$h2fO_yKKWAD*E2e2B<KRxO(WSa!`o#z3j~QpFnh%
z;|rZY?6tQ#&hMf-K;hAjeYvKtFXv`$1t?Vdg6ef?v5V37z;V9*i(`}^xcWBk+gxGq
z>P_=v4FohK5uNI2+{75+s@-H$2=fhKm8MTvtuE>;!g)hTT%}uVU_+#|fbTs_%8^^7
z>r7ej{Xqn#<@b5L-`7e(^VNoY7GMxhySMNP;*e{~j+<*67#>RMVB|_+kOt<x;2bMG
zhtgRAX+1;_jdb32-)C%lo%8O|;6t7CmO_pBc0VWb5v8jRDG>pRdaSwX5Giq25!aMb
zTJes55D_ohj_^KSp!(`upVCUO4qD9s3Sql&Wh&O<sXE>VNSL9o<bMOtR=HCw?&0Sh
z=G)^w^!!X-3s7Opg(6f-AtF{4@Hfn(0n@`=65)VoCgK^uku*&~nJPc5!NZNtev)5P
z{3h&=@Z`q03laF%LPU@&1dwM>6#onZA)J4Y6z`9sUmh4nh<0~z=u+Zah?%XA8S=u@
zm@WMC9;vECqeQxUTHPw<nNnFT*6}@>FI^)GS<hWr7g_Hyza2j^TpxJHnDPYkLFQbW
zcK{(O-{f)4HVQ{sspCO!#oB86hTe{`HSG&$xyjSqC9F~vD)K_rzi^E54Q}MCmz6+p
zH6&+a4%iadx`Q@1kRSUE&atT-bdw$`#&gCys2YlM7!a-aCEeKhD(;qEtT=0MxRKi!
z_G=xtX#UPDY-?Z<X`%X=0W)lHp@&mekR3ATZ^eKai_kzuGPIZjLRHw{0<OdYVbU7C
z*{^wutcT+Emu7y(9Gqyz2d>6NSUPx(Jb5q;w%BRp*MXws0G1viaP%lHXK?n2nuWS&
zyoI64$)CHk2BByx&C~Z<7$NzyUxby2h-_+n?mSVXv(tLEf@4)o7}Eo*DS-A+;^0or
zfMH{2K;7)8RA+&NpQA{bF7gTZY0k5-EOSA<N3A&3w6{rllD;)me~Df>tZcz?{&N)N
z4R>^Sg@9OY=y9Zh;INF6A(Cd9;&hsb8g+H_yl-hYiee&MNO~Kjc2<V*Ih`^kT8S<Z
zy}Da&5%K636?G;T)_uZ$I4NVVS<~QZa88&e;U&;7h1$I*AfX};mfFAN4U6qSIFWEg
zI6#_BiBTh|lWS2NPnu13nH$IRUeSy!T@=4Vf{lGKG5K0&3N1^5NQ=G9)iyZ*YcEN&
z=E(TP$b#>S`4G{g^?e+bH!R@^Fvf@dXuzw_-UWpBDv?|!Q$?x~8>_^bqGyfUBdRWj
zKfwv#aK|IhG;l|sfuC0LWEF^=R<0?r0jiI45z%LVxH8@j%=bV<>Pv#GMIJHa`uQXl
z>7|3<^}@A4mI0DW)YcRyomi~2ujeq8dR<YlLriM%oD|mrK+pfUCBtoH{e~3WDC<RR
zE6oLK7Ga<!^*bxVL=Qt+CP)L7%+lNe$&|iWh2C<u$_)^5(%$k={r;>RO_-93)1mnC
zy{s;BITcIz+W+K*sn+8R-2jzDg?ZXJNE*sBT5%g>>eDK1z^Dp>4}_8_bqGHw_-`(Z
zNGNwCI}bdh<S9S6=0Hf+!hka|G#rr}h}iJKX$nIunlgLguP6gs6rc#AYkrdgUy}MM
zh*T@`!EBJQMt#nFgqo-eOV1Rm;9#wIR4ST_4u;6In&v7|P+Tm2!8=+p6<a}wCgt93
zhk3wLSv{ww8TI<j`(MDoMdcw&wFCO6-5~TrNn7wnRhVue{g_n|z#f;svCCBu@}i5Z
z>3}<MAw<&xr0tY=HowJ!-(4OP6Cr6xFu>LIa6f5=K`zoTvxKP4qIY=|!sZZD$_;GI
zVhbxXH3G6ZL?hT1nL3+;Rr|4`dIRkx60H!<jENH2L?KSFL2*UarlToWP);gHqS%L@
zj&H^x@OZXIZw>?Y2;RwYmzuJIV+<*+CTLJN(Hfc&I~-#i=$a@%X4`5*%2nJ;OCcnK
zYq?rm`j+ODH2fnJ7Kw1stIIrQf<u=L@N5MA{pJyo2=RWAKXGj392|fQ8`z{%_=Q*-
z@jH@!k%Btu*>bS81TE-eqm#&WYfauKqeHK5U9cS?`U%ovTS{%E$?u=eA2*7BnBF#Z
zGE6En(5}K{lRcM+qFhNL%CCcKdLwKLmn0KOt)uK@@imy!0MAHedle!OLlrH?kd1em
z*?7tOT);{miTq7*Iz6yTK=kbxRfT*zz;~SsW~s3AoGgfV@e8IJ3Hag{<rxR59QT>m
zAZIdU$O^^vH2oyd9EI`RKJ51MOtVnbLF;;aICAH82qecYZr1XjO|qfls)@PBpvr$l
zCVwjDQ|k=-f<oy63AETB&j-^qlimf--dyG(^h`ySv=lQ{ti@kttmxu)xS{KV%?8sV
z7FOES65H{xVs$nMj`jFRh-I+{&AZ~tlFn<r52#RIAU6~!1#PsQW>Jbq*i;IInT)fo
zD2Qfkhn%=kU=K7LLXX0htyS^iAf0LVfR!hs;VlfoCg3eh0{x+*pKT4(d5v#~#`Wuy
zc+z<T*9j}hr$RB`g;H}-(O?a^r2`;Tu%-g>I4*wzqWiTyiGHf<1MfKQpm{xijuqqJ
z=CD7D7XHK{Kb}5=MeSK^Rto#Ph>3#WT@zgq&13r;sTBoVoKg2VPS*~s295AwS!@l%
zI|YMys0EgQ$7TqUO23Q!^e4a$0w;#CmyZ4QXL|Q1LI_xEYCIIP)zV4$VxnUW=qt%s
z?mLHd6~wq9?&^lkWZCWEoq5BrXF*V020s2}Jo1B%+;)4L7=?EiE-DbVrJOD*K{8#I
zp!LFdRv8b91`8we=iWws8zJ64C6f^tdvL;?wMbn+F|{C?Nk=OJuWgg<&e&0QzQego
zST!Smmr{u$NI4kB&%qVI5}uR28~*5NMtMEy%6_5NM|p(wLmPiMUAP<FOC7EOFwjVj
z#{igq0Y^A2aC5j4zdCuk9RQtcE+%?nyQ|IvGL^2^t?X5vV6Ji?Gxu|_S_Mi}1gZ#9
zyO(43Xb@tYa>kTFM#SeTego>m#+EP1RIF%d1;UQ1(ct9<8cE8r4%(M#y;SOgeyb-~
zw1om^(~)ok%3PC^`9I5$QtPEZ=ibdmQNyS6)Kyq}!hzNP?r9bj)dQT-1+vkiN$wM3
zL{{%pPGT2W4{G5kNu)mz=BgeZIL(#?6PJDovd#mchNjYH^c@9PTwvpXj9Y8oDuYy=
zEp&wu6<gY%4i#0Q1dKXP;=*M)WkO0UL7<cJgVG0jqfAni>USZA=+N>{QJ`_|$3{oc
zXGRT(FY%(UD$WEaa1zE$p6$$N6_2)oV)XoOui_O%$3lq3K?#H#kVFg<+Q29*Z#$y`
zhd%t=h#$rjW=GvFkAa5GhEjoo5QP(F4s+a_SaxhIscM`<-KIo~_IptwNeFPVZi@r_
zoDeL6*zYNNsCNnCV<LIv$(oHUdF+`n3Oob*>)q-azI2``8@jOo41!uBtvo9u!llt!
zxh~kWt4y(Sf|=YZ(P92fb=Lx4F?tmvG0HS;zFOi~JUBlOs+7NAVD4P7Ww4j02OGz>
zjP%QA#cfX&5G6*fV@Vm$wN`ajlwma6qh3E2SPkTUQOE*dh1>NqqSs?kvjvNkW54~B
zoiZp&EfGTv5>4Hh#>)wC=z#%lLUi;!BRs{3RjB9?t$4f^s)S`IOXdBo<y<)z*)O<Z
zl`f=@wvCSnBAIxNBLV)2w#OUbRBL(z(MX9l{g*Si$3w{dg5$bj$u5M93^;K<xl0mr
z68X-N^`GJ;%EZKOQgr-vE|EaPfd41?Rx{2u5D`W#p2Pu!<|HP_2>Z5%y=?OZ*yeh>
zZy2I1=<u|1`HNZQ{8HI%wq?hLW!&8N<ZER{@KR!n+&zqVXDUp76N6-D!?|-7c<`N|
zt63JhF;zbr1{|iRThs9j7NQsbjQdZiT3`S82^N4*QvlOh&{Tqj!0aQz&Di*`f|NS?
zUOZd3V=Y%?U#LqQfG5}{M!akc0-KU*0KMg;J=%do&hy<-BenyP7R$s#Mx}NQaQ5p`
zCIICaU56GKM!iad()_iU*+7p4C9_L7CvLWo8eXqApdkex*Wtc=V%t{I{tq^&`s-(&
zQ;?L`2$^%t<LWJ=M=XN@ec~uQ^D#8I!7sM{w5|piEdd>~Bqbh0aP-B{W&tubb>PIR
zG$G6`4<R@Ej_2mbU;~^LA`D;Kk%pD%zP3ll7fHkO<D?SS?D+DI#xuw&LzLoIZq<AE
z`Iv`exz3-3@+gygt4B{GgO;P?ETz8u!YHioRF>!V94=#^#2}VwGzM?~wDz+EiS;IY
z-j`A#c@Q@5hRklsAAJ^X0%J0b3Zcn4zwVNQHBqg%fPTBu!gD9+5T_?LRLjT}4@kEV
zI-X5oV`v@y5q0#mXjEEO`}K{$){=GaKAYrJ9IQpo8-UL$$c!6+V-_WsYPXQ#$~790
z?B}WJ)^QpPFDbOw`0qby{XEs0WtjPfSowr`^y6G>F{yElHL0S&CMsbsL(}MV^(g!c
z7P*S6)}E!Dvd55ZDJWm2SpMQy9!l%0TQh?c(<CPVwv$D8k;~TL=4ZK+o}_NF!5Tx?
z5}g4fvyT3IHbU5@o-;N=n5H?}!DG61=`xqi@(l6)%mRKKUzc~s@ZZ*3@q3?JPI}}<
zA(Ly21tF}$M_n}dzyjBy^rp&`;C?m-4}knkZq<QKEX0ufA#TZ8<x(C3j{cK<v1ek&
zRuFBwr+DXc!buO^d{g_VJP3)sMsbDn?XSx^F4`20J}CNG`Wb)3VR5=T|L^hNwRXU8
zmt*-Btvrz~!&QL(QIe50cz-z}h<USozgKvFEK?VhzCdYYKXoK&y;1n_eEV!HP`07)
ze)Rrp<^Ac#vE<_Yt(N~!XR4=wRp__uU9H!-LjnA6f1U|ek<aK)Z!TiKy`JCPZ`548
z-5&n(dAHAbKYz%W8gjK-pYRd@+@;zIY#hGkoXiQlo|U|J-<*{!y}u0+#6*jP>W%Jw
zdzq)Gb^u7OU#$8R^c9(1Pi|klZU1^de4ct&ji%=vt9D)|+iXa3rEBq`dm>X%u(=+Y
zYnWse*s+M;>U6u+e|u|jns*C)vXhK#n0h8qKjGQhlJUh6F55pO=NRn(A#ealunbNC
z{D1ih47z=L>m%T|O<8~s=*peiD8Cm7`IY75yK<NgGioaEZJq{L>0F@p+taUI27(A}
z6+9byH<@`C8yw%SGN)<FraXS9liz9}yI&T49l9E8xSw4lh}2v3H8;5Oig;f=2h-m>
z_jX;T?^mqI-s8W^Jh!Z9St9VR;D|wQnpbrBb_EX_Y{Ya0P55}|>ifdp(dY?_?5)ZC
zL4&{V_J!GVAEC_7zsG)ku?+Y1RSuv2<vrqFZBPA)X7Er~5^xmAU@Y_MyKkEL<G^&w
zZdL}-Mf*q>5nLF2RHARnr0?r-!r8Sw72>R-0(+U$kBN|FuI}Ji;`30wpV4S(`j6Cq
zVt#<*8}KL1g&(YqZj%ot$hEZoGV7z?Opv=r{bj1%T3cZw6G3R-K*XGFZ$PE=mLki2
z&ii^?LEdvVR<Nb~{D7+w#_d7PaoD0_w=9!P3hwoMgTUa<Ot`vbo9xy5WFiSW)FLqD
zWomWe`?hnmF*o}>d!O?BRH8q#R8wmEMKvPi9=*dM=U}85p54Ad_m!eZ_f=b3Bz7ag
zw$h%e%A{!FP4?R*q7B*k!zk_py8a7%9hkyC8t-MZ)AFKMeK_^DExQh=Z#~<4$Sk>h
zP}291oDryE>~7Fvfd?q1PkS`_8Tw41>9Ma~)EsBp)S*3x6l)d?P0v=%Ir1Kd924#o
z!_7H1C0(*dKhhB?2t2`+P+yjDmnC5IvB7^>;a$>dm>gY@2kq^9F!Lwhq$r%adN0=3
z9nn6K*S&rVYLq9x99qDfTa&&!k&p}AgD!75F=6?&_5AdDKtfQTfc6$s!BE`7#w*ov
zAODBRC%0I;hrPS3nBcgY)64s;Cg#Xi4spDqMw4I;+NvGaR^mN5eG++oUdZTj=R6YF
z+11#n?>u_#?|Cp#XJ3B!B+2IpcYS<j?5RCvcv6zJJ#g!vet=*9`l9}uWUkA9x?A0x
zVD35l8B_8)A?A*N|8-#Q<m<cp3&Ak3;24~#oryER$<)yH<DI>c6&xEOBjLwyLPA0|
zE_M!%fB7u`@OgPZx){XV0TRjpLx3sa-;58QAtSIs$RHv_2(0dBYzU<M{2#)9QwDK+
zJHUTQo6#}SF%q%^)hhiX1eE({63qWGM#!Mz;b2P0plE1rN=Qb?^p|l(Lnl+9E~bCS
zGRT>lSQ-l3yAx^yS&YDma}hEzGcpqD{v|E~Gz^q?CS?8300}317l;3v%-=@-;(iPP
z{xB#5O*<LdIXiq9GxqqGEky`$axwk4B?6QZHFdQ#HdT@k{$T#IRwYwsdlx5TQ)j{t
zzbV1}&(b)6?GOKccuLmP&KzJt$oZdXiCfwLOq~cB#BG3{6*V=sH~GubKY~nz9IRaI
zAG-e8GWX0g4KH^zvF4g%<psVCKE64=G+5F!Qq*`N*qWdq5YWU=qS=vzps4G$LPnyA
z@G#dXntC#Xej(=5mpEjE0rgDvDEKGG*Plhy++a7y&@s^!0VMT$XdL88UY=m|9rw=f
zUB6zt*Vt5bYpS_xp0bohD2YT#B4J{C3d>MSzCFAw3ZNQQ5sBgmSl(5Fc+m2v#FmN+
zmr|y^{hr6>GgBby54EkopP@KN@;=wgi20)q%fz7IYhqNljprQ_`}?r2=FsGnv6-f5
z*_U9ADxqXD{n@0532Tj`R`;d9Q3@57YbGYv^$sVYL_U)zD`}La_7$TUd@je^#8ZF2
zM#J`=iO8EdPBOgIfUFa)OjXimc*K|R8hO4KQ##7zi@n9E{CLP<$ly37%?KR1rW9Ee
z>r_zd0ZqQJqtE+9f)jUMVX9sthO~?$;t9wKF_Uzv$F}U=+;}OezEU09l9QO0RxoXX
z0*vAABUhp#<sL4GA$jnlQE-r|ME)ssyrfHmp?eb#!#j#R(jR&Y-pwdc6IQd0+7T>%
z@*lb28y8R<32<Iyn!FULw%bSnNT>|c5}QSR=@oaiX(CpktXXR!r?33|Mg*VOZJ|e$
z!UtpT#%;8j8`PT_9{U>1gL^#Iv>57)3Td)sVaOUZ2B_I~jr$@vY?85+Qfb-MXjEa(
zUR1yZW@Nc~ZHoIU3T{Hwy>9S@wI&u@JTcev*MN^*uA~js<RQ@Och6Y(x=x@CO;{&W
za1f)M*rjKQdF#c`=NVhcgRy%a-2P5o7gFO7NKJM~d7+nM6=Mynq4<))`&Koi?{&Yi
zB>p3HXzJ|K$-156+1QT=dvO2u^EBvY8?M;dPmhViPK7@*^(nY5CE`WCIxUO*oNUTo
zI8*(>1Nze4dN=$BQ9Fm7Z;9CwdW4y8MH7E4QK=!!G=2}sm8xpB-i79^+3wZ9eCGgJ
zAS^>=zd*E$Gq5e&%=lQSq0gw85`Any_K7x2BByw2wZ2;>${1erljEFfo_~ah65Y-s
ztu9IbS^avyt%iKyGDAw<QTp7hi>+T?1^LXQ(?gYvfK@v}N%5%Q7rTQ+xwX%%XmupS
zMjIFvboL!~k<Sl~6}r_ED61h!*8BMmGyG@?--=SBwI9{8zAezhBT@i#$=8W03`DKZ
z5auM=oucwqUsolKJGu2T^65A*uul+U#A9KycwAD>?Ie8SM`SnUZ;tiMD`^(9q?Ifp
z&<sGc&n1-uwIZ^2WZAgexZA+h7~(~o3uTi>ysY{DWKV92SJNzIS#F33vyuiA_6zfp
zh9<@u`*BO++90?fx`bBpGN(r;5B{WNkBCVaqTc<2T#jsI{HJabOx@orQB_!`aAeiE
zdT3p2(R)Z|NyiOavy6T&g=;K|Sv~C;(xsq#M)Rl~pnjw}*;U<jZgs+UlD}ZZrz8p2
z7U^2dWnuJ6HKAtN+~~U(V!kK<EDX;hb;~DCp~zbAmR<ctDSb$s-QJHva&P^1z?mD_
zrEJbW@41zXhPlCy>MoLn`fDv|_%X)hJgsWMoy-ziXucLwD6^n4mMPLT5B)~D6w-=^
zcGh`kXoz}-tDzVg&96KSuKeW?_6f6F>v5}lRO#2D=Bl+rw!ub?gE?+1x4QFHjl10V
znk0*cqdA*qW*M(!x*0u#wH0#HtY+~wF@3`yW;{uFS{gUjJ)G)nd>G#AC4<LD({a!X
z@}51vMV#|6FY<0xod3ugQ?3s|m-XGoeia;?0V@N+7xh8U?H(+He4;c?XG)=GWuHSF
z)zd0c!M(u7{0_`Rx#UWZP!AA{=AcIo9cAC_)N*=fcN1mvD$H4O(^$1FU$a-Cixe6v
zHKq!UeTA-)D-C2oNkC(!-HR{!Zo*VR)SrXmmWr5?!B7xn$7*J(q+R*=gAD1junT7x
zxT(dTV_lR8Vk=^%GAc6aVjQKCiZ#_H6q^^R=6I7km$9byWa}_$xkGnz?ZZ%5e?uGo
zI!Uu(niIG>fW~>bY7BLH)Y#@BQ$`Gj*>*Jy(Gc$BvPJVZmH9i$aEw_ywC%A_c=Kl)
zhe$i<zR#hqE7#X~B0fkAk;ez2ulN<`6UjJgjWs5p4?m5shNdRPJd1r|IKsUSl<pDR
z->0{35|8n;&I&ocJSHK7ZksX>RJU8(bYG9*(86bpdY$vOe{{H^q*=QbUn7i2+WUeT
zKO1*m;d7Aoy=Gw%$@{ge<yYRtOy6vEa`;-y4^6U(ccK@ok;0SOwPHi4*;*9K%Xm&^
zzC>Yf6*`y7t!{NnfxSYBRf6kzZuRF~@A$q$!alMXuUG-F!lAflcE&Cny*>a5*m>UV
z+tu7|-_^yCe$3&k)VEdr<BJo5p$<yyXoRLnAdXcqS7_O7>1ef$keJRu1@_kEE$Q47
zq7Q(V7EOfHUe?*I6yV&S?@QSHrn8PxV&QpHqEeRRT3yP!7f&Ab?M5XA|C!q*ud7VF
z;J4t_%$3~py={X>`if_G&W}D!o7>p$w%vq-S%^&hb9ayvZchQ)+Qw-(L?l#7!pD#^
z!rMO~rNvGlS3@V!Y5Jucg=tG}9$>!GREJH8(%}gkTYkY)BE$c@*6(_SQk9Qvyox<@
zWteE6bSkFxQs_nrg~YXSoOjo~aK73q$JD=zy}n7sV{{QI5m8@nC;D=2I$z^)t##m^
zA0!654I#)SmRZ1%Z;W%5^}9)Nq>R6jqxJf_-GyPTZNH7bW=cRrOM7bkTh~;ch?4lm
zVa}3aGCpNCWpu;^6JC}^CvI7uiPi}jXRxONSx)E^w){v@jFhZHX?*^7DOp*p+#}fV
zaS3Tl?3?7L(N%)_<vfF`CT=>RIn-UWYr)LEBF;`csG=3~{Jbk>D}o$tV)S2nEI+yq
z+P>>n*Pu)$N@`B$g%m1jVWl50y|n*YLHwQ{xjC?+epc~k;hFmn2yCvK)ZFZ?{8#Kv
z1pSiVjX{n5w}PHZ(pF_^<tf}Uh%w)%<4LXSk>nYBAnh25pp1x+UTF2?CL}L%-Xd><
zk0NK63Pa~=N?Igf(uI6%&F68mBvDJJXefSRdz);*P9DvmD$rNrw0U`JuJqwP5&ZJF
z5f~)!%HP}TC#xV>!Cid@e$PAQ%GA?^jLg^=JffVFi)WtAnE&1$hqDu$I5Gh`pu|R}
z{%j$L{rzhodusHusbMDOSuAbV<@f3ZYRyx}ho;SWg>xa+x($#3{yL%eWFc{HF8;Jz
zK_eBe0C+U<4afF1*@j}fUv<AODo`<J-m1eQUvzGim!`72kSfx@(bI<^TTrAM%{ky0
zuT#Zo+?*(;_w6vN(`p_VFinz1I<xoml7U=Xs~#kdAQeU&H528(KT_QHojdR#Y{-2F
zx1p=PkxrB<C()ALwT#wNQrPTc(rAxC21F$RAN!MWeo(T6WN@>IW#{2f@n$a7N!le8
z-^Q_!_LAJq+LxDBSWLK2bWW5#<ijFDu!=;<L>Bp!F;1X*aCtPTS{orikwUXSDZNZ>
zuZq-TpNQ%p{OI-|*aoLxTk#_ENbWuLPVPpP>EA9MH$$34{*~tOwqurkRBMM&&3h^S
zm0n;;iG0Emd)8aZv!=)^qgqj(7JI)i{x()(bC@{$fDO6?jvKeQNvfYe?Nei^<H@im
zY1H@D_&LUI({|SKq9<J*LA?5sqLi+KHI4DU1gOG3p?ax&m>q$^4Whn1BK`=>tD_h0
zl(MSry%uY0(~Dm?w&RrIp5?Ll;aDb)l-W22C?Lilpt`WmaFMFV^I`g~j3r~8jGbCT
zxj(~#KFhDg<2>c1L{MHjftO#pY7EO403q8rVTvpOv4|w7N7OhGP55Uyo`mQ|mfJ#-
zqu0sj?~aW@{9-vFrt`Hv9C86R0PB(FrEySANtL}Y=R^4x*{$9K8O2|jUD`pGGj(CK
zErgpBqNj2q_Oss~@*9=d>R3_G@30MBx=xXy7b$9z)Sq1oC7ugl+>KxGz>5hw!^<=6
zazcOnqMUC=X#ow6ZZ#x<2ix5rRwa(NaT5`-a{SrfAMU?HDh@|dlK$G4luvir;nFf(
z7niWz8~SGL7Ir_d09#VL*TwQ@LOIm+oTt`tE&6b%^Kox{4l?KKp)-msZ}&lgeL%1A
zMg#Tew<gD>%p;b=62LkE%uC%tS{Hi`dTD{-a7m60e9>V4ppcgUR0ye4`8Z}3qWE%0
za$K#btXzKjk1SZH&WT)xDYNUmH63B?&ZUP%?N8ru+734?UYPcF^=GVpVE4)a>#mOt
zUOA4=om%qq*m*?#go!k)qm6zxk6XD`u4CCXdrXO)O(m<7*-3tIOW1J4C}#*0PoGP;
zZO?dXz(Px#W<EMQ_~afwlKs$-BJ<7B^?VNTQN7G<T7+q5Fq_ZoV7ket*baxg#Hgo-
zWuu|`?d_1KWGM27=!+KDaU1cDv9hEuC7Cq2cv(VF!G5iPX9>1zvWv!vJ|4hT@s$bo
ztFNSV6ny?8iG2zQKUhJ_j|!%}DiW7Qz4A~`wV@M}PRm77$>87jc07EfU5MRetv)U`
zk(lxI`9<aEYb`ZBvJ0OwBs!fJH(Cy^6euy51kmYraPY)-#ce{mL-jqchT|~xxoIaV
z<c=u2Kj{l-P<FqKneU7ZLn3v#K(zQ*3U{lCJxG&dn;1|o<F`pC^}*`)WjDcAD7%?7
zyA=bjpOs$h(Cw4ln*bC8rmOPPcdP6oEw*g4_5LqN<N?hIQbH8Qkpf25BX~;FXQCU~
zesJ+>RV!`I6Y07<1CwOdQYSeK5lxXxXDA%@n`j&rA(guACa+IqGE34F)F})#>pJb7
zPCB_}Gq@K&-Usv31w#||4{P-J^nK&yGn-6CXvYf?xBZsiM>$~=#CLc=Ykmvrm=IYO
z8UGgLPI-&3PLP+z1j7SQ^XK<hPvCBBUVTrAW%TjG*nSAm-u=p%{k;32Ab@t?DoAsL
z(T=G6pvE13g!hCLJ@&pM(-U71EQU%TUW8!GDZKg~*~KfcSgCElJA{wU^;$NBPL=gO
zjp-txOJYa+M{>j8E%yD}+mMK}BwcSq<fa|+im;nu1w@Crfr3Uk(b%x^vUAiT(KukB
zTX&C}E0QH8fqS_R22Z@cE+zIxhnT|xe<j9xPl;h-K%3o=WX1Omq{1|(!E-ip!sJh7
z*hJyV<!6E+H^a$b)OctgH{!A)%n?~9tZqLW&e3yIdZ$mvhRAIJ9gI3Zq7xISnF%bf
zW-U$fSoJ+YyyUMumBKA?qL&Jivc-;(=8E>dc;Kh92H6xG#@29O<7vWq%nCz<+LS>Y
z2?Sd&?A|AtkdwT8SqO{eHYQMt@#6bJwVOvHfGM?fl{i7+Q7A2bUroA8-`wvyW8C;v
zPvPet?aLRlo=^a`j9JGDiqa-IC?)ZJt83BgcOBtFq6^n_`x^QQLoopIV*ol8^6n~y
zO|-+*>n!;2S6HqHk7yfW1)n2kN)hR^8F!@`1Y_(6zUo|B!D`qvC@vGY#e)Q&!Vo|(
zoKiH6*h7-n)y3r)-6`r`TP8n^kHqn|Uc9{YGFu`WzU&$}zKY4DV1A)YPi1m|NMwab
z!43EY8mY_KwZep78ASO=sg<!_ZgZ213cqJnfYo_TNNzzoWP-qBS+7F7D>gs1fZ_)8
z?@jFrB<gm|=fOSW1v^8IJLGl_W;1)OiNFV3Efu^}R<7DvowRlHqDRS`YSI9|*`QT9
zSj+*2_1A8)@aQna96o{TgR}by<aCKvxOw<~{wrI3QEAiiFo_-%4gm|CGwRlb_j?K`
zx<=7<(FhNo>+r@1@30Ho)D+{a+JZg$ai5i<MRF{0BxmH6A)FBe4+!9KjXlN_+2Si?
zDMY;#g$8LStx+=j-IhBoZANti`k~I_MZJ5Y?C3{hQUuG!85NwFWbAxWiL=o#%WD==
zFimOjdZnO8FNj9(@!<^AsUXyoNko{Wg4mkPpjM`g;@2Fnpbo5IlB^LEQ3(WtVfbd&
zRE3B^j*29VV6AT`(|f@`Ah(}sTQxy{wQXsGazMPOqjWp=>eFm_qIBzdAirz%G{HTT
zgW+UsG00sO`7u28EP!6N`AyYtjqWqONJHujhNlem6e+Mg6p=r$g7bg6tn-W1yfkO<
zRsqF?@c!-pt^;xy)AJ4H0i@(xEyyGr!oeYiV4nf!a|x%fT2Ic-Rt(rC=4G~@08D9(
zABzj@OO#(bggXbkJUnOH_zuOZ12IlCJSX|qJ=iA3WwPHdSa;<fd&n>74x&AV@JLBe
zk3^tN&@q=<pwP%@*MSmSTg0wg974XijPr2N!lxWU%M4rJ;YvSUw)<Iu{=lfM!P0Z?
zt?&wbSuk4e80x!+GK_)N6Ux`O4A=nE!>E<%kw;d6UA~HsyciBh(YZ8Y3UZWg1#5<1
zZeAE^fn7chqRTLTNH$v5vAmvOQndUDkHgDgpd8%G0b9ywK;qk22gY9Mc7<qJy9s%c
zZg7@P;$7v(wjb<0@kyg0EJ*-!Z$DTO-)IVQTNAWG-DS4|vho;;CT=3>UT_62E5*Yw
z7-_7|*n=rCzfd}`c052IR-?UtM+TC%&Y;du3=9Jfrs>V87wk<26dt38Wq?s&YUmJp
z+Y<B!V%(+o3&r^278Phix`7!g?+OG<x<R|2CD@x>531B<s~^=O2)`);FS)@rm^&IS
z85sU2MOuS+zfefoQ*bdk#$MQ9F#OMqdV)gTgYfBu`hm~|#t(s-jPgAi>mH{d!#BNH
zR@Y2t+n@|l_!t8c@K{BCuVCVD<9j5KFXKU<z(RJ19YFg+(!Dj%5WaIfD58d7F>3Vq
zpfi?&oue}<9*;t^_xh1IOgX^7{$|)Z@8Es0V_099nz*<Y{Lu|{fobI;q7VKAGmJjn
zk&<$67of){w>bvS=M31K3;KfRNh;V3s=48kO_tk%l!nbc#Y!j=YNxBZIT2J%4HyZS
z%nImqW&%jxU&;$f-V173#g=S<mkIsGn)i_4fN+ug6ib^Mh#Ma}MT!g&K~x9(IW{=R
zD2$^g=JPFln03H1C`#aWEYP#aJUr?0EI*4EN^U4`uuiai2zQ473BTY@E$|*4kaHsk
zSjNnmb(F3Cl}U?fNDJ~(urHhwM1ofVItU2R*jj$bwU`k3KSqkG1?33AEa>R;?r6_m
zzHJk|uR*+wQM~;CO^iwB{NH))k0k5Ad2Lok=6^HIT>m>A%k+^#{wpWV@PFlF|2zGv
z8$V_j$cQ3#{}!QH92pi0E=3lkQiO})Q`$%Xau-XCZj4>Ob-}Y6u2cq}+V`+o5f{3*
z&dXt^L*#+nVCfia2w>l0)(;f=eZ|b3v~M8Mu-Uz{CYz-Wo3>`F>1egiSWzCZ7l@R?
zW>f1`?;L{+2NK_6z!Y^3)=}e3Q+0RziY)(IO;S}iaKL{@kNbU94n~Ug0$1j6xBYD7
zuH<2zR~Y{X3--u32IenpgshI-^4Z1^D=e$v$v2)cWTPYKn+-_S{p3PRX)#sqNZH^g
zN}oMnqSpW}ba_pZOcnwH5@jNO*qpFP5fke9siGVfnS(eMneF&TM$uwnpP7`eHDWbf
z%C}<k_xTrTKz^5aXNY++HtSR_nS^t6viHQJR%d#b)<MZnO!p3|Zt2ZOABh7Tuqui-
zEJudUxS8$OUsnz0>fXMfnWV+Y|9j8=+KGQQjfI8n-#ugcNc{hsL;pK-|A8%tnmQXh
zSvmmhojwxrf58p%hPFWLKu%UmRa1;c)YQsQ%|#iQ(*IAtxS_43jRzs+-(7?seN=yU
z+8CMxbN9^ukre(LU7%xPWM(9!V`XP1Wa8jr0ip~n%>SSaQUF66OJgBBa~o4a#=pi1
zIU9e#6kN=le>Fem_tB<f1}^1eh9ZUzlBSmC7C<BesOB%0GQiYUjga&2@gEJze;Xew
z1csw2GvNn<@ZX5S2ZZv!z45m?7bC!5@QDf#v-t4TUtD2BXVbsHnE#h&ES;PIA{K^D
z|2ja{@Sipl^WOl>|KHt&e{IO$e=%ZqK+wX{&YX}z-O^6T&e`%`#$T4zElmIx&Onrg
zh3R7z|M$hh&iGG1I}1DE|LX;Wj)1-Yw}uZc8^;Hd_4mcj_V0TR&i}E?4h%02mXBEa
zzb|%{54;Fyhw0zZf6Fm*{ErSsLRR47*?=+eF`o~t=L3BLa)7VDz$YMxWUp#x`GMpR
ze%x#Rd*l9h7=NH#e@CZ`rOAh%K7cT#|G-!-AE4KNVM$E?jgu)l*_*f+1JNT&V?#?P
zdqO69CN_HD5-BYJ00(XcARq_inmZXfSOAat(AztiQ~e$4B0%&HU}<kB`T^!qigGhE
zGBY!BGIKJ11SJ~{BQpgfBh`N!{U0RoUvTdKYs-vr5QbqWy5|&Gx*OU!Wkw(|A;AeU
zG>D~<q7I1D_uHv}L}bg86~+FxmwycC{q#_YHHFQZ`?_AQJVirxHyHXH3t4(+qb-ct
zk66-j?7T4;d4wDrCWBWq+(e`{j#2T7F*JpEHAA9MqGpbzL0dLJ-kLGF_Akuj(U?u#
z_$Th*f8JYiz;tKz1@F)IB(;(yaZ3rJOU=uGUFHaFwJ(Yj81kakWl#IwblvHCHY-pI
Bn?C>m

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_100-low_error.pdf
deleted file mode 100644
index 8da253e7f6f68998d8c5d99491f7054a938f288c..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 60704
zcmV)hK%>7UP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58fy-lxWJB}SV-@oDvvj!R75+!Zz
zsR7%78;yqT?2+L?x7%f)aNnTHFl_((J|fpz)VcZM+{pV}naGR~<LHahrYMSBERXZ~
z-#?e<|CM^4kN^DJ@sG#(qxSQjkI#Sp`+xKJ7yr-s_^<!%D3AZ~{NKNQ{_h`-|M;Jt
zKR6%%-%-xT|M~dGNAV`(|DVlS`!UY?=>7a*XL<bgu=?ZbDt|ow!{gumw8ww?uaAHE
zmt)2t=cC*|#%0asv%3AT+OJt2fBEhB7k~ff^Utf#zx@62r$4v9`^!HZ|LQOArt#BJ
z+W0YJl=frXw+J!JpH{2J$)OquUsOBq#fq#I<@c4^J)ZN(N+^F(X;$>)f1>zJ-nZF*
zT-WdO-oDTKHtyGnMfr<~_3l5;S|EH;t<@jpr5XrdRIBq-Zy<b8t#tMl>__>#{4euI
z{mI_1e}MmI`7}8Y-cQcv{88G>Y9xG7?Rx(CQVoPJs*UogHxRz4)-LwuE5PzMSHPaa
zYy9L3DBoWJd;VFTf9B*s_+oPP^gpv22wzk?uTQ;!@V;8T?X@=&zNj{zheS{L&+^~2
z0?&D!<tp>}w`o7l-(P{p`TZ5BWBllS6XYa(F}deybiPyr;frc^f9ef{FRIn?sW%Y5
zs8;HaJOZNhUG6^xSpR(q^!Nk&|3xByEse|b9NNx{D1K4p+BWVgeDU)>f3&s_3WP7J
zwf5s~DeqbSCb!E|SlvI_>wiGr7b~A82f`PVD;Fn+Y9M@3?QEZV1L1wO`}{HQP28jW
zzS4F5usel4ir?h^Q%<#?Z1q2&><oLI7s_Ahi<}qr#cg6gKQVvIzDxNie<hiI*j@?c
zFV>13IoI#4o4<X_*B|pIJN}Po_jv~)p>E2<FOJflhwF3CmnZ+na|{1O4fxJ5+jK7H
zFhwZul+#iD*v@JqysdV1zu9Cp5#CmtaYSV`5#ClSXWWRgUQ)iX2>1QNzFvgye4tC5
zoi7ti%KI5UH^z3cebyu4eYNM|@KOuq_m!UKP<^RI!ux91zD=U^4d$0IpC9U%-2cwm
zv<~rCCX(=eV$c1s4wJ2(C~qs)V*bxrF)8mWK6S49rN^Yauh`BI-dRzUZ>&Xq%Jb{%
zwfK%!R(tdFWgDp|@25E82Dnue<$c9j{21ISit@hV-TgkdRTSlIMLX|Lb4<#&&W5KB
zI<4RB-D-UAhVndvU&VY<-cJ!H{#H?x_Z9p3`PdZYeZ}Y0Uk|dRysvo8PqH^D-&u{T
z{iyckYJBU)a+go1XHwoyv8^5QGR364uUPI+2WV2>S2WuzdFg$HHeO}02;W$PWmvnv
zUW4zP6>Xd^CnwAAC%5**ODz)KSDU+xh|=2%9mcb)l$7@spLgrmqbw=k;D0aAUccu5
zcQmD5?@woEQr=H-?TObZit@f<AD_g0Qr=g*&QD@KDeo)J_UR}~%6C@dd7HGaSK|-d
zadZiLz4ClKKF{P=#_ePN^BVng7nK-no%Kf>eoOm2?*Fxhy`6<meP})p@Tb6eO7Xlz
z|LK2fdgbhM*2lV0-Q!%{xAFYX_4_l#Sx~Q=76?&j&V5q66jrn-4Op@5azn-8B>o_5
z7j@lz{JOd*OW|0QtVT*fC)fJ*YN%)NS!%eCJLN1vIm-*hwvLt^?(!S<@k$B9$Rhad
z`?9T>pwz9IHT6YVqd8tETRZDk|D<f~fO3ix-B}q57aAfd47^V9ayA@g(_osjlOGi*
zi&eDT80;~NBL0yu#9(udo<I7ha!F>HGxXeM;FNL09<?Y>(Y^>%(+0siia8dy^WN%-
z<toDB=95swgrLl=pXa|FPRgE&8<giZC*P}2N^U+<v~Rpr`>~bSZCo$vxYTV@xEV%l
z)p2R_I^}Q@yAADcQP^!faysQKpD5h(t^+)E`zuS!I-Wh#UY<RRq8a$cd{TT*yppnK
zTH>>3--csorAg^AIgp%yEyZGX?HhCSAN+UUa?i490v3$w+Pfom-IJ0X#};ea%o{}$
zsLrUSl^@tsO`WrxoyV4H+;s!nr^U|NNw%$j>>ta%y`&ZJ5|_P0`aMZp_m1si?6zZT
zn3yjLOFr8g0x(Fv6Dm2cGFjiT4^kX;EIP%};Uu4274wsFY67w9Ma=KM$|buFS@Wa}
z4L{bo{OF&`WPQgXm*hdLXi3)h5F4jB-?4(HIG>cE3B;P7KI{V|pVPUmKrG>@{U05X
z{SBY^nWg6h`>pRTcH*Ld2`v`vN#Fv+)?5@WK=U<v5{#?Z@NRXB|FL}+h5YAZSIWH>
zE7D!;9iK=;Q|MmqYQ{gso>DK)%^Ef=-wyF*EJ`wBEkVDwi95r4in>s6oT8bBT<+I4
zb!T`_QP;f0X~);KD4e!|!y}jvk`Hfa`3*cCnzjXxQ`O+pV2GXrq!vwM?-^K}!q1$0
zsh$|PCrM|JTRnxHfqPxE4h3RSOzqTYI48dTb}UlPJQ&)v;9+rCl$?0*vuPR3OV3#c
zuPWG=%25UPQaP&NUemPWk+R2X9YNvC>Qp<yJtHfsUSo%viQQ;F_=|pcF~<^HPZF?#
zccyc<f_H|J^KBD=6&tbUFoJC<0xOu5BCvXii&6Mpr}!&iTh%xU*jBU}C74vS7;(cq
z7HO!RU{cXOEZ|aVaRpo|T9EiRZzu;8oGRKL1*|%^0R^khZA92rsoNE>=iEjVyDG(E
z0mD)(Mkn47_s9trr3QEgi`uO{5+iYn8VVk@TO*3GElO8I&ZBl~L`xI(vYPSl@JV?N
z=K#q$)b4FO&W|>?@vQCB<~AJPJuT$r0g`t<x8XQDT8hjwO3}!O`7R20Gj7~a+T>uM
z1=n_QFiQ>gzAugjigA^D%%b?0yhvRQbuXKm307R&czkEHYa5TD^Amz$+?e^;#^XDq
zjcq)^ijm{-5{EMJ;k2RAOzZ(^lu*hSg`=66xHQU8(^o^Cn|YDE@2=5IpSUiDV`Acc
z8&6EUOT!%#Gw<7YV&am$u#P(=KK6l&ZEHGo#`Gf2fq_eDlibBEz$qtxv*bgA+8LLE
z!wIHVVvf{1aZ6Z)qDEqp4W-!QCe0g{hDEyAM$AuQ7`KQ;;V)u#l*7l96h*KI_n0O<
z6gQ1U;gZD_1eT*9U=6EQ43~*k#U;NOw5k=u#h^(v4`}_ZN;?`OzFJA=0S&%MIuB^)
zjis1i(Rxw)Zq!x>H0vg1bwImrP*!n$S!MDCDsU^3I-_F(lFPW$tY;;11}bekx8cMD
zPFWuYl+$)<|3EoyxP=cWqt7z;50uSzQgg#SXi>OwP%YcZ5?r77)w_OZ640YTi?>^g
z26a&GQ5F}aMc}GI9khEJ+nUd@NZ8!X|D7uaz0PiyybFoy5el49R3D4t($S>b;&!zt
z9GL5CHZ`u;;)}v@`7S@4#O-7l{M-iTi(%}>7s66>$F6q@H17em%2IZR5@jj5p)r}%
zVO-M|Wex8LQd9!dpds0%u|XlS3#Axo3hf#)ev!C<1;dpsU_hI(p`nB}V?&IJ593%Q
zj0K8{r6dnUWl^~Mp{H01a%d&irL&C!hNmp|^W8fB9!;dQJ+T2BKi<=gG>brH$A(`N
zavP_%(b38J4K_#scb?Nm2^<%>RmK!M&SYzxV!y!#SpsmiTNF;Q;|w;6<$lK}LvPJR
zh!I07<EFRDI7>T^SCeG!I9|=Td7qRk+Qt6B)$d6`DF$10V!(;cNoq9)D>)r^K_{ry
z7;X419*c0IVGb9@T$7m-*TqHQXyZ&Y3GRO3)G!ufxH2-}?&uV?8l#n#-NUYEu38_U
z#Bd?Y`{jS<NO8WIBs;E>i^7o(9M@JfRvc%>DyvUPd0Z?P1>3g6IOUEgF|6Sw?nfL!
zCV`F%Vy!YT^ss$Y$>-kV>{%pEKYqZKf=Qynq>9VpDs%cc66zhI5Tr9Y=KTF!sFK&c
zX=wZo;t;5`M;wL=<RWqSxbN4=&j1(vDk0u+cdruS9X5F<k>I0~0`50TFQ2U9%&!va
zaiw$u_k?kDD8<NR&+QQERYr~unO-lBzH(%e^0;O$3Wx6!e3em(kx60iafhu}avxXL
zDmzH88Xe_O(dfwk0>-6f1Q*Xm;uMOUmbrn74^M|f$33#*a5$V)<2N0@h~eq5=+P~A
zEpCF92Sr>!52tWKr$)vN6&KJa1ttH?YuASlp<nad=(w#_T3<TuYPD-Q&L~A6?ZyJa
z?%Zzw5?2|EforH!I_q>VS5}Gj)AJK<p-#cpYLMls5{oCpO`BLe9cj3NE=o+LO>Qk+
zDH^UoRac4z(Oq$;fQRBLH}w=OYEqxu1e0X&@u4;@O@oxKx^%RV(p5)Zqm-^X^P0as
zRhffuA$7{hN;Q6h8RFVeP1Y$~KApt!89(9r;Dtgiu!igBqCn|wxI|PPinx8&s#CGy
z%20KI!R@owD*1)m=OS@dxD!;JmAHQ{3Z{iiL9N__ynZ?f-BYmFAFNc+3KtIgf0bDZ
zZtG5gpuh!mkvP+);c$CWl*@A8VDhbO)^|p&vSc-A?^X9DTtJ<Ic~fxf)NRmqoP@p^
z5g~I|qv*y#++aYhGJiFgOKZs;YZ{NKcaDb>uNn_0PHCMl2e^1XNi2CII<s-@Tog_m
z2FNNKT3kC1Ct<~*b5|MF8ilhiZ@79c3OPaRV3h*UiU!2(UNj)?f}#OIx<GlZ`524K
zr;{+CQv>1$08?B&QF6u<J=V4pmZqYsVS`LAQa&0iYK6}o4HCIX8EK(*A5MzF;Ig?W
z;03OmPC?nf@}dhR?wX5Y&|3|XxX20^SIb4HY^I<Y>=KKyfh%#lj5*@lFv!@VR~2(J
zQ_)2fS4XGBl2|CmWm2uf#c@%<1%obJq~;i;Y?<6524{jYB@gY=XvhbszeTE#!QfML
zr8QW5%9Nlm$l5Z=8c5nA1qnAsr(lSXwPnieZzGt2e-8djV~U&MB9K>jNG(#Kc<WoF
z*fJI`ltm9m20KfUPGvBv6g?#w<Y&2(R}i5^w`qgHq)62=h|qG0SI~w_YG1fSE)sZ!
zN3<e!%$lZ7UNug=Kxx92u@)(42BSt9Vi@FOk<k_RL8o*y1QA)Jvf=)>DBvLkWRVtU
zP-hEGwTBs=eu{4WxbZCtKSY=$3RFFV_$xB#T8*oAk-CS=n^Q18h`$#Krw*P{`W2~!
z26IA@IRQ5`r(ncIGbd9+-miwD=;3hWFEr62Ei!@toPg2eZGn`-Nx^WLnsFmr6fm4}
zP8JJ;d7*SMyx!^^46l@PGErAbx}Czl8uX9~xh5?Y*D$BVG;r&3N{qQq^_7%RDGQZZ
z+_9=6pbb|lr^F)E$<DC`6<7a~`fjB#>nO#pmcEP2&?_Z)EY}U*f1HF#;nrUCzFDuA
z5``F*<{C!m(qu-(Ee0e|*fYdSg?3n^SL2?tC=@RU>IBItUA=dd(K+N#?dn@A=`IpQ
zkFS+-OeUz>)pb(XGZ(V)+@hJPQjBec0oHM48@kRiyQc9PcK|1W5zzZK3iQ6B%K$X|
zCk3Ur8mQPkh=c2ni}?$s#!t8rpxc#v)PPRzBrt`dOV^7^(X~@z*ZGa(2nu`0hN<kF
zyQ8XeQi}T4hh5Y;w-7GcMdrL()Ok|adF&u>2;Fl}6?GruJJmVM@uA5nv7Y>>cM`ki
zHapdIQqVJZ*~yY~yxi&tn+_`7D~0{UrYpC)sp0%sZgzuRSMHb6R4<S=P?=sSP(*ck
zD^snCP_Xvcl;u*(Nx_L@C}ONA)ri8zt}NF}3C~?c7r{6(k58m%QO=;xBWW-7Yy=GK
zSp&*Ph~`C!4GLlSLI?)QHe2|Ol5#vrQ3MB#Z6-lAz`&}Xh!DOyMQ?NE)M%4ZGj`q1
z(3G=e7&&F=Nrh4^oa4t!w`bQclJYY4vxUj#g`zsakrP(Nje^%DvGKGYWb=Wty)MpK
zRV671)yImSH7nt{=7jr6Zi};IJEB}Ko9!$=K9}Q49-H&Tbq*!!G}_rGRhXT!eIJJt
z3O_6GmHG-lw0hraI4Rfu^&X3|6IR*qnYjp91a>3>`w6j8Z{50f(zQ#YMfhB1KOw*t
zg&pBSxJc|OBw@WTO=+V*ba#|_YOvgoO(HJ>drnGuk@bsmzR3D|!v>p2#3H>O8jHfd
z2iQ4&^iO4W9{Y4r*!k5-;AshF_B<>_(P0_;l<|0Z>@G_GRA%2dc-JX*lK>&nyvW-X
zOH@ftFmBUHz@{d>5US)N8MG?yLR_tyHr=L_fRai{96XCMq1|8~nv_y*I#cJ|Wv0G^
zax7BaHMT{dPRcE1FQuxEJIXkpn>J8Y$4QY+3eMEjNx_DShaRc2Ptr@NsAp`ALWPw3
zphzLbd9z5;!@-22p1Bi>)Iu(NkxGiEhI;F&g%WR7T<Q=>dzsf9t}_f+c^g?IUaDdh
z=l$uLvna3EoJEO;YTb?&X}>?MGH*FpwwX67tjWw970$0k!ZnA>G^wue*0(6UQej<Y
zUa3M2bqdCem6>^`!ZOU)k}g<WlzHJC<YjkJU^+mFRs(!~^U_@&YcMaF4R8fmB-#zI
z26M=4fHfGh8j#~dR)a-3g47>rBv@r$<+%n!W`k(9%V@wAkgaHl-(3b1^1I7wKz?`4
z{9?;KthAskQo)GH;jW33!%Y(>hvV}+(x$UWo7u<9G)!Sz&nCMRIZF9;A+%({C&?~_
z0b1InFhB~hOB|#CyXfAwNHk25iL@16;-SefMIPEC?Qbih4CnJj23A?*$gTQgH}tJC
zr%hf#qr|qVvWSv#yjD#yit=lUQM^^TzJCOz!;VQtl{AQAY$Xk%H(M?+WV#=1kZ2Gk
zqbR_p7<I}bN=BWsi27Y3NVNUp7lu~Is*~1X^6J!Rz^jXHC$d8?(iNs`aOb+Q2DD`_
z%4Y0d#aIHp;x7`d@!-ToF-OCCy(s3w^uEdy%{XHYC-HFre7Gp&Xy#uOz71S#hff1=
z*jgkG2drSgpq?EnBLMwbqB2ZR&ldHf*QDMy7+;775K!Xn@g#3xBiA!ZMby}lZ!MMa
zUwV(JjNj6uO=TdK9(F21rjC65VLYQAh$_RI^oUd$r=*9b%9x|L@gE??fT9Y_O|^&@
ze2gq&1++Rni`5IKSH7K92Hn&mX22m)k8ljG<TG7mU`$vwVsuU8;k=v1!(Gud9!?w@
zUpy_cA&!TepkX`}r5H=q$3ZWWs)@r^lrN!`F(9>S;&2$$lj@@It(FsK{03fT8SI&F
zxAo#{WYxq?<H3USF;W-%%Ag9pC0B+}=)t)%K0=Su3>wA5H5<}f_RVU1%dYG`9wc>t
zy7(YzjCQFEV8B~@z33~Vi_TSkZ144qE6o@EMe(-)z4}+i4#+RyN!c6+7<QVz1qeHZ
z`@sRqfJXusj;<ln)al$WM~6!1{&0ne2-kvUhPt932KFanQ{{ER*wl2)I4a%p<-OsQ
z@G?P(o+_9U{q5x<65*@iXQE1URKbi!Gyz#OCioPNDyw{j7YaPu7|EKhE{tTAHw*(=
z;W0xBTvaBv0o~u-?WWSvU2ZvyZ%x-7#<$A7rw*v1@&KxIWS57K$Gbl0LBv>B`4~B+
z$_?oNg<eM3ZuC=^H`9ti<>0tB6wr!nU<_>fPB8{H{i|yDp;xJ2^g5@P*5Ra@eq0QQ
zO+PON#HKG80%9NX7pvh?9{ysSLf7axg--7_l;pOCa*S;1gBhK!Z5%zNw=^L7j>Chl
z(sx`=b_YXd(-W`KRh-UxmEPj==ZhHHbouib+8f@8_~hXmF3&*^qHW=jNbXaf-<p9T
zzDQn*l`i4%W2|rpm!qRc+QMg%pSS&xujB!O!55MffR#@^mz8eX(gF}E8*ZDi6`<|P
zwR2JG?)~YJv*B=x(g`<KGJ!E>@-VIP!PZGlAM7F?6ndP32QH!0&$Y_kT1T+lt#t&;
z+nPSLh^>Xs?Xz@j9=RS=d(X{jmtnT)*vl~6bpCaUn}*;ZT;b8JQ&e8vRU?H2mmjhR
z-lAE&1UbovYEjxeojnZqo|`kYQ@lx88v9K*URe?mnoGy)Ro)%5JuVl`Ui^WfRq8MZ
z)J-37r<`^36Ms@RKXMP!g;#q>QAX{iJGw{h-uLFR?i92Nsngw3D#v%m@rG~wK}xTi
z|9qu4cl1jaYZ)x$Vy$x{T&$1Hjh_*_>FUp@-3$kC3W5<Z$BPjKF*5pH>zI(=wGM_3
z>8<Dm2K6GufepooFO*`!x|K&nuc9az(91XrP-4GcIhHM0!()E$xy5rh#mCBcy$Y~%
z1cn?Wc~7ju02Pi5#tKEBFeo@fRI2-YM}!K8))k?W!$X8h4)2lCGL>H7ba?{FJGxQ2
zB7}z{gYM3F9Yhg7GN#8V5gEjBL6uiz5TlASdZ>2A3gyt^DyASL1{z0@Ql*c$f|wX}
ztU#wqr}2n|IzU38(+~b6f+=-%>(Kt&sj<P;hLKqroSflXPVv5qc0O(dt!x8~5Ie~7
z2qunMKz4VWJPJ5-3L3unlYw^mAyx&|p%^oev<_!;g~nC7n>XEgI_?kQ>v(`v_b|Ll
z2XqDMG4MHq`D(9Qw4X;k`@ye>KqvW+^q$n?JZmY9ap!0$j0;R`jnWtvAB8V6Qd$v?
zl^*L&*ARqG*VYacV|{e%pbLAG^eu|;B%g|6HEVdZA6qo1le|-1Ci=<vPA(QsMd3|X
z0QMajTFSWV3_q=OeOHJoBe4<3N{X8_73{i5b&rQ-Xm&=-R=UTxz6~g*J)|x-+=&#Q
z%lPe#;br`G#`)G3_9{4IA3=%lO{Ut0gH{2>4DrsO<3(Zg@|g|A?5}M=3}4Ox)jbN@
z1HtcThi0tC=;do0P|RKuoR0a5%4V>*BDW)mJC<Ii%NEx&g@D(_kY;J%h$zo6@`Hcn
zKgEysaP&(5enqTTdiX1<9i3u+YNqbt@f>Le&{qZlD9D}@+#>N87lIp-)s1n^64i_r
zP}o1YxnTo1%NIKYAizaPkO8Nhbps;c+HGhBixhYp=Qg4MLXdoJc;^r_0{6*=pWvIx
zM^v^E1rUOaU=8Yvz#6nG6Vc&G+8`gekrNfdDLxvBXa+U(svBG&Iwk~#e>6Tk8KxTU
ztb(!Nw??Fk2)mC~rdkPZ8A=4#$dM3TBcxy(p=k(_qcTnckR6l?3F_gLGa9-0lR%4*
z|JIYFGyOy2C-FsGMETHU@@YL$NpAketqfhNFGDW`cH)#4?M$^3Y?BObw1^5>#Yv9@
zU!j~$d={6*K0rxeMsV~r$v|KW3}z94>N3?#aBplg5AH!lc8MPBOWE2V30%X|B(ZJ$
z#JT4q@o#Vj9S@-7kmQ5Y(^UiPkc=RV9qB1n8;sjR?BNNRus(iB_Go#ip=g-XPDCNT
zGq!{j!q$VL*i&KxV`y$OkG(jF7q^pg>cQf<%{*9qZ!-@T!vf(AJpjPuKOpRoG}}hl
zA(<N*QHS{A(F_+j!9jrpyeKFv2`5z<9y3xbLP?F=@j=oW{z$n9y;a~=J7ub&o)B4~
zmj&dSOb}4I1hrKec_TEgouXg(6b0$ENDjtTk_&;nCF=t8zl09kDUyJ2NfQVe70CoD
zdr~$aGnUY6C7N0aze+T<*OHiD1+G@vMl4o(6t%Dg3AJq_kn>Q{1^VWcHf6&4I5v{>
zPlg^5VUD_Yg3#?0{o;5ejvX;F66@}Ta`QI?);l$WxXO<dcU8c8*>`}hb@lCwEWd{&
zz{r3b2Th(kWo%u?vX5;IV%3M<EH@ID9mX>u7rsz9g-4<vK1+_U=zlE&Wn`a8;Z7@p
zX{6{W!er!g*G6KW@B$tw=aNF%6E_~fMjkH|EIh72V{V<3!d(Z{D4|y#J85bbv8CqL
zc~EqxZ@5emP7{RVLBP$poeGh2D`zjU#qO<_02w{=3Q>e0TEr_-*o|+w>)bjb<?5WG
zZ$d$pCZ%lcu6=l=#1f%tc;Qtf*wo61xvOjq`_8;lL?tD6Nmz)ky0^U;d`S%97J1ce
zO9aKT9b(EJTakMT{@%i+O-iapFvwo18u5CHQQ&GSgxsBy9r;$h`qoiUM(+8z(OzS#
z<pf#97&mz3oeGo*yKf7y1Nx9;BU3(^?0MSulc2mzdbutx(pGIvYWAHg^JUVYh%e5{
zsR;5UjeU7$%AP3Y7w?NX$LsPQ;as)vlc4180wo*r-8Fa75#D`sZXc^})47QX5>ha%
z-9G2mFbFh_@|&5vSP04{1pL#R_cmfu@>_IX?t+1oPlDh+w;6~62jY+?_qlzq9nOK9
ze7bkBKuUhA@v?B2?PGO8ckgn+#pAsT22x(+?wyY(8%dw@+Nt+0C!Da03E!x9-DgPB
zcD^ib-n-x+C1sLt)_W5rq0!vCEb+~H8;`tu(`LebRf>Rb)Z1PU(L-LZ+ev%x$_y!~
zMEOR&+kT|q>8`tx>aHr>DV#*eetrMlEl)FOAos4ykaBAVzTxh^DN(V#diEWG_ILlR
zMcsW<n@HI-HlOycyM&qb-j$cwKVwsyV!Mp3Gv6M&>H@+@e#Od<t*==5>$SA$NU`cE
zVeE(^_3Ln3?=NceeQlS6Sk-I0mc*)F@--4^Zr1}}x715u_rB+km+Qj4X(dU@dq}L>
z+^z$$YWH>>=!zUbIri#)A&W)ZFJ!T3`-Lo4XuFU_#LxZtLgw)hy1$T;7mxL8r)bFT
zF5z(%8uMBekG<ffH)1n%4PCQal-FzMissPA6L(c7>E^uth6s>P6yB4c%d(0w?Sofo
z2Aafg*2qow^X5a9x0K({J$glhb%rm}>otE-^7cJ^uywoUk2@O9i~e$PUX)j}!-}sd
z8cwj+wn<MPu5FX{=l=-PS%mKY%$4q7r40Tstk~ID@`2I7bifp|C~06aAJ}eS3O?=z
zrr_glU~&nwNNHh;hF|PU9=KFA+~DPIU<zJ#Jy*e)wMc1Ux_X2}sh!~5W?u@%DR!B*
zH9Os%rwtFWN^@VZZS2;)HW7w}vJV2-jX`q8jkN9smr{TYa49WI13L~vjHby&Ao~Zn
zbZuh^E~O|NU`dLy;mYKqYzEge+Icm&uK2SYPOwRDtnFfaTFmjn$EpWbn0^<9%)h{@
z)U_@!Yo<DRVN<2Db%9-Z2fM(oly?`{b?+kz_V8MEfjRd!p4dW?b{DusVRz6HZ{@@f
zoH6CxhT@DVd`5-A-$VWICC<<r7O8{aoGE%n#pA-FT>Qz}GDY4oco(q(l{DTktfVO_
z7{4f$O>{5jFq|KyXcWFd7a@n?^DiZbaYZ9Jj9`FDKKYvRcw+jM!-z9#5jc<=)93Xj
zR?!r&c;GF{iZr<!vrjP@inbL)DJGvH5-7i>C^|fySw_U+mBtvj77uWiA!vBCv5XzV
zqm32Y1`-o?v56-f%lIrj7+OYJ#hcFIBtDd$G2e7jIWgh=u{0*UKbE>HzLovCw4?ji
z=h77v%Qxi{i@d*<`n<a=NO+mGvcHzb#PhMVcqw0$Pf++$S~yMVgm^o$45-1|k(G3K
zDcIR^cqyEwWG-HljBzh`@wN<U!Q+xCfF<6|5rxbb?U>`mlFu(4UTTzH9`7xKNqXh{
z(%q%TGRm$GM*+*o5I7Tfa5bF(eng!+T?t}#lD^@xpcrjXe13W^h3A7s$OapVIZe4s
z#8yoQ7sIO2JrPb9rr3*vo*66b{6o)LmN67?_%LAz(J90-LZTaGO?tH;d2dEUzyZZd
zy0sW4kX|hoY_bS$z=N1&Bm*AAOmPe0D`Oe9fCn;*7zMiV_@pu<!J!%f48SrvN|&2~
zjwak&!~bUi5OCd~r)6{je29Qrun18h-IQFA8iNM#pyuER@^-3SXbB&BVY3VnzzZ8-
z7j_>iOLu=bS^>Tx2+sa=?T5dX!H@q~?p&5m{2jVbO%E67LNz^HLiI_H{SMbPO9y?t
z%b9%d@hoTQdk+t`MS1md^CXg8?Zj|(8Sj^%H9j76rL%Ok$Ge@?=5}Q~+F5$m0~gh5
z3U4SH=~)lwKZ74V8j1;|i{TYpBYg~^Nyu#;P_MSR%>xhC(rq4)vBWd^;NzdApFCU@
z9Tw%}Ph28c`o_Z_(_vdg>0ai5aaz_CsW;YO@Gu;w<IB)V83*0wBYuLt^ci#qR@>aY
z;o)kVzc)^&^!F|fm%~m9I*}xVD{f%y(1EuLm*+zszqWa0$6=68*%fS+`^N}~CfgjW
zA(iDj4Vk<-PuFNQeWxLRU%aOu#5DSdm$Wr9J6T#YF)5b;tSzXdk9=5jI3;-aF73rO
z=j%{kZ1cYMN7F?hM{qs2Q+E_RwE^7egU@OU8!Da9ea~zT*e)bD?`y<Fn|!Mq8kO|I
zBbrm>;P1RQ>YU+<54bBj=lhm6d4%|*+Ct6Z*l;~Gi8sUq7+tOpy{p;gVLdP!I#@$~
zZ7$X!zf5sTgYwI$n|j=X<A8Nm;aD=DBF17Uxtz6(M?wsSrPnp$G%UTY@%rWzbacho
zOmYXWZ;Qm0zJA0{IDA}!OfoW3Dmbv3I+`&<$w@rMS-NH;$i>n%8$mFZ?%4xgRVM#z
zJkUAz+sRrT?PS=Fe^=J_upI!%F>Gg|70xR9Rs2zWR5CBbQ=Jpg$IV6D!;c7d7nESr
z9)1*SD6JU}dXA&VuN!v(lb}Vs6yf(i6jQY*j1hybZ(Uy_VzVqA$`QZi;D0Bp4K&2~
z$I#>9V19h)-Otj){3-z{7~31MW==srC3r>c`zmCWOtc=;M(Dy1y$S}f;fJE&EFI7h
zCkHgd1EgRT6?6pL5kv7qF?qyU{Lo9{qG*N{Yo~Jv5rCGi>xdF0sN;ts2@T%thr$gl
z-PsY5=oEBM0e!v1HClSOUlPwc&=4O<Xvz=8P+B^@BhHe5mLD06Nz}^^MQmEQ!6Ty6
z(hVN3n@(x`P3)qKb3*K>BXFW`=&|W5j~G--UwOo-29Bq5i(*{1ovUj+oOsuGIPtFW
zOn7u71D=yQ8{&94aVVyyk~flZ-f+AnR%wu8G#TkVFdE%b5K(ODi_d3U!lDLgpdp4K
zV=Q|(GnyeQD7$Y3;$4@<bM4X8mM;9)rQvY5L$S0wcRLJJZ4d1xK5S5Y7pI#)!o!Iw
z8x-FSCeMGwnOn=yZWxnVMs`C`w~XvY0KYLh0AcTz(E$jIcM66B;hgaT2(Y(CM1Mx%
zTg$+1S5BMWFA>O3NZz0<(bozJae_6eD)Wp|i~{fh#Qpss!hkhi%YZ>(@z8sK6u%%M
z0_1O#p9H`TjNu7@L$D_2*NL}o!W4f9Sb<o^9|B)6#V`P$!J2M(z;HN-iToj;2Wxu5
z02l<3ls^O*VG;QNKnY+k6Jx^JAT<i06qeBt?v!ASw?_CRSkp_$3_vi#K7SAmBPbY}
z2`KtQXc~*sQ4R(O_Kct$#GC#QatHCKKZNdKjhYz%Knz}K$A?ft2yFc!BoS-6q5^G%
zaM&M0B(Y{F`TTT&1*QoRwS(f@QE$rtLLm(Ihrm(}YrOWt?ZPs)1E?#+^ZpPpi)FM2
zz*~R<et;B=Fu}saMvz(vpcq1le+Wv(7$b5BZ^jfP;(#>Pq$vWk2B_trObmFV_(7JD
zCBVla{CQA<;|-<YwscDX@c=@dAUnZxshcwt*`}*HJVQ(YDsu)@J4O#r+E-HWTZUNx
z4_T9bIw=TctDV4vHHNy(sg7TPkO(CI@gP{zE2YNxsUyLegn;xPa3--vRTr)#)}-nJ
z%897<%ZdQ+k|Yrl%38uxom>FHQ=M3Zj*@SADaZh)dZjq~cXX=Q@`+AWxaAX_3b*$c
zN~{4r5^hRA88m>wg$w}1;6m@jA*1k<Dt<>PF~;I!+bMBfX<e{m?D!RR%$nX4Z>W|p
z6n4yYyzRjp2On}cd8O1CJV3`N?4;}8c+P(%v1cx;sb?-LrCn0+1u-wf2i;Cy3DNyP
zDdwyz1e{K63wVOli8b9U;B;ac0tKg&SBm!>mk&Vd#jewR#3A*p@j3z@lotYf=I%gV
zI%~SI+(TV&lsksU?J?AKQle|h)qALO?wO(9JIb7Olqu?DR}19B;}eNJCm3S?RA$FS
zvb)r=b{SqGn|$r=sos;qX=AHR^^E`+cTHi|kod**nZSOy@ox2#6wQ)5?^aJqiH5oF
zZuXRf=;;c4QHre#rI?Da;m=Ue_Hu{`<#{_#9!5zjY?NTR@EduhM8mNs?S!zoc&(z}
z2=cQehUp7|t;RkD6lxL<!lhahv_9N9UMZ+_&qt!N?vzFyQz-r?zu29E&SP}_$7_i{
z?+H8GNq8g-tu>_+IH!i1l&Axc*%BG%UMY6Jv{I;(?v(n{HQsoSS5n=^U)uh6HHfL>
z0acVk2*Dc@OJ|Eou-COIJuAggyTFRK1ui42h|;myfc8Ap1_;;7z6wm`ZR-KKZrhyY
z(sYu-M&U8fhr?~(2Oiw^wUnu`B?T=%gfo4pcyC`SFsfe(Mj-(P-a1Esn?pG4lpBQ1
z-YE6lWDj2TUI}4vp+qBc_X~l&gcKwK_$!5Sdl1OI=*+-wjW@d#%S0o8rSwhSA0K+C
zOL@<SIvx^4N6&Iq&qO1~Ys3qMU1NjRs;-m5Qv+L;SX!?nc8*O7?06lqc$a%Avv2Ox
zYCrNI{~&_>cGmM5?v)}9;dIX{KD?!_!H2h33eFLfcHIRJY{w_kghGj}SerCcQee-L
zGKCxhyT-*t1Fw`#Z)388)a;PY0E7b+_RVcI)Hiq0kW!o!D#bmMDM&j-nVoZw40fIb
z_8nW~Sjiw#Y39@2D}^0%dtB-l+u=&xl*@lfH%$t4Q!YQQ2AJSf&nG81sh4u)c^B&_
z@gBy7ro7607?b-w^I^<Sw;?71$x9S+h3J~abRxKi9U$qhhB9wrT(Z20Z4_MR5KqsH
zC%ifGp)W6&eAmkhDBtz+l8XE*`%M<lc&`L@9?NFYE!M|qh0078R&*K0B3aRW6iZ^1
zcMT=l9k3*P#LL@1AMw&ez~nctl)76Qm_z4~ErKs{vR6Eqi6?Cu%+`~352o~S$^k;b
zkjZdMn+ry4X>-B&Oa>og#v{|*!C#Zng*<MLv<UH?ER9C-Otu@A_$n55C+1K}yA)r*
z(ssp1FW9%3i%BLgaFf!GNd9=#N?RI}L($%LeCP?wGSj$q+5Xtf6}Cb0k}8rC+S=GH
zgG_Ff)<Zlz$-c;ErZhmtGZRdd2MFW>Imv68N-)EcZ@iW%C9dgOrhI*N$qY-rU9!W1
zZ!|(FfgfIZjx_M{Q75gyeAA(wm~S{~Nk%#}7@L_7&Cm)tHGgatYd*!KO?y$oCax_v
zdHqrTUGrhY->?+Q<Yy3rr<g>g4uNDJdIt&XJ$^IL3|T@!sMLN&L5PQfc#GgOg*VeE
z2s5$YnU54PoJK*IiTzF<Mat|)<&V!FOxl-EB%E<RqcHj35$`NyDIa2j5*`Ve*bi2!
z%=+H=EPCT%gWJS14SeIns8S6#zKbfcU*p5*9glDP6!MjdA5=bN@f*zNE`G^+5<B#{
z=errr;`z8nVH1yU6ju2-2k~}nFL;!bdghaK&8I*L>3l9kp37r<Q{;hwXGfhY`7p_|
zDIYI+q~U>+89q54?t!N9aN<ql!I#0v4CBAUDMFe08l78|n2#|Pdf24`l#jo%S>_8d
z6|{Utrp1vD%~UA!DVjPco~sX#I3DbMdbjBI$k+rujZ^KXL_C7j@G{St;@YZ*cwUO~
zv7T2lzUQauhvIqth7Y5<FEJtjt^>FSr*8o+;Jf=l-0bC`Kx;y}Fd)@#dO0u~FT5av
zS>ZUr2|@tNm4Z2c)7^r3fzu@enS+l995+Cs-w2m-%5S8pGx?3&taY;?eyz9sMmVcm
zek0toxBN!<vEJlXM{#$1VPfX=j4^n;n=&Tj{%v}MSlORVP>IYAP4670k52y`=9o?&
zALOCl{D7FJI(>zh%R2puknsAEK1a-neWYWO!9@zQ0U}vCHzDhG`adx<H$0>ckkX6l
zL+QQK(TXX+(;16-!sW1aD4DnkOVf~WJlwtvcyQ?!X7Co5=a_|W_~u(?;TtaRGwT%M
z%I!o)aJaBprv$H39q8mO^iig5Pj@+_c2AEwW`C!;etaN7JkwBqD22Q{_lz#xa_(ay
z`g8y^IdH>A5Gn7|i*OO>?MFt^&yZuIg9=>+jBeE?9i#6KkJjm(B6R|8)N-4&F2Q_i
zl_{8|Jah_X<p8E*wYzXyz!u@AcYqRpzS0ZaiCP+foT#M%bO>oUny&JTC+Z>$RN?Af
z>C9>!GF9%bi&Etgdw>$otjuLAkL8(d(npqDr#CV@a}Sd@vW_x(BkLps@{nAB4ZuU`
zCA=u^FCb511IiE#7(s}Rbd>baP35m_03L!zvrlrI=?NX;0)V;c8*T7NmP{RZGoXX@
z5v2Rxys!-rLFuY(0Qi+Rw~g{hXKx#YZv7IZa$D9-A1K4=S#CfgPVe(Y2~nDf<wv3W
zIZAY$hlr%Fv!o<2lHn$QfE2#xx+nu^C>`z>h2Hb{Vg~fkun!(VF?isgYG-%<H((EC
zgn-G9I#ch_ky=6yh(ruTSmhY6E|LQ>j?oM@j4YRoqc?RXX$O{dhE7;GQ)fbUz!o9?
z;s7ZI3;_o3Y6Wo^y{j4H;RJNUp|ptcAeW%VR$a9Q)Y#0KJ`~5op*7e<GDG@+UYqIA
z2jf^cHt4xZeGY(fM9>@{#r8f~TC>R<=Je{$9Om@u&iv$qfh?Jz9AHTq6|^W39i>YO
zJ-svA_~?w|V=*GVblae#H$#|gbOl1?U}6drR-e%o2t~;-6bQwkKrm-6?*YMFrqoEd
zhiCe3fZk_#mjQ$+L%=K?#uX%X7(K=_?e>6vok_Mw7;`g!HlUg^V9hCa1f+TK()*H^
zFhR;x`jabW&M7{>P{t1fyi*3=86C`(gL=Ruk_o5BrPw^~?hEG0Od$;fsEiggxS=bc
z&;~<orAm(r`k$f_ZA^wOMoBS<WD?_Qr6SW!J=3n)U}$ZMb4J%H<MCj0t*p5t!fTrz
z5eIbt%sNb0_DmQ&7+{;?8@GW-^*i{;mRWiS18Qmc98usf7)*=owgX4ymWOsQzLuuR
z!Dw2ksz|pH(X>W?_{`F|pskLF;&Hv~oUYqAVy;!=h?%B{W-x6<ppH|#*Sd`Z0mZ9y
zJ+B@LJvO@1GdOt>AY-Im0xgR%&Z}G_e%aIr!l=OudfFF3N-Pp0sZr{W48&gLSmrZ_
z5i>uxQG_W20pE*&Ao6V-3?$b$7)M^z3IfSvRB%*KY`W2TpW*9HSR+w{y8-2kG4RJC
zM0C9@MZo>aSbC@2bBnh(K!IgUzBd%n^>Z6e#MjHnb3qvq0)R0zKqvv;kV7=gZ9oJc
z$N>?20ADeq2LxGQSKToU3@BuYd$1_M9O<TvFA#phqEyG;(2G4I4o<177i?{UYH*4V
zPv()!wVsoKa>kH^Q?mAg9t6|~FSohjN>~7*CG^B$3|eqp3IjfxfGdLH<KTPbWgGN`
zF`nV<bZA<n*g<;lyKplU&W17QL0BA%0vr(D3>gR^L=UI<=p;ce6A%db533;HL(ov)
z5Jrr_6G9<blwe$A$%iX-_cFj+*fwv%r*xKmXtqt7;3+xj*k6`Xp*<3l#Tbks+?GWN
zUg`~nAsWJeaf%BDfy6A5GgA*B4C4^gj8lBT>?inGbjQ2`izcNY9*Ry%!7Q5w8(h?_
z`{Kj-scZK|Y?^bMweLwOr3@7jgpX5PD;3U<F?vK`K#M};pPV%*oHhKT6M1Nn0)<He
z4_Lr=3Or<W5XjL^;emJsrtqB-52(Y!Q*uhL8|IQR<r{FBj#tvqpaYl*7VFDVk%j-X
z%7M5fGxOC6#g?KB2+RVTGGGoSAl0HcDpm?J5qSM&YP&my833X0YhyAfEZuVh*0O6H
zgx-qchRkKmttarVMTrHHEq0?&XJ(c@L4`TxzBf3rokGqc+uz-D8Iy!F6j<DMiYnlB
z3j%GYXc+<VEiko3+2Pi*Y#MMtX|?Pba9eHbI+nVz<dc?Ow^4?86|0=K$&Hju_jQ&j
zG6_Y4k9D^!?HG7Y>Vcehar6Yv(?W}q{kpVIOg@qlxX-TZk-&aY(hDn7LjoD_c%iUc
zpvB)5Tv_H01H$~Bg6jh6qp%E}bl;BzJlrW<;z*WupX#X!RPg{McGtP}B#OrC8%_X@
zJB0>xX3_)@<X$$7&Nm>@B$Ke|Tb}%F>Pb!Ip~3l<6tLw^QL7<p=G-RWn{=kAK~jNv
zZ7q|M<8}Qu5j#QJU_BSbAxg*A4hT)W3WQQ27bmH2&G=@WQfiV=w3GlT&C>Bmlv86u
z)Y-P-1|_wGxxuMMsmkQT9IF6i%`*4Ke|Y@6V`=o~a~#htbk+WB=XqZ_ui4hs?%)5L
z$3H&G<9z-%{{KJ!b{NyUUU4z{jdEt_T?&eCrX!%aCiD1Mhf`8!TZ4~JCIel*KFU39
zg-N5;=*eX2yqWpFT5F!rJy&pZHHt86fFvf&z?MLW;Z{m@kl;^1|4s-<q68<vAh9Id
z4t+*6G$LU%q0S`A0Rb8^aFnmZaJce~&X5{8chi5C9>;XZleTV*7gTT*{js*!-_GaO
zGp&4nb<|h=*EfejfKnbCv5{Jzv$p33YId(&<j<?-S?*DOx{n-D*tMeH^5hwPyPEk<
z>$<<^Qt{ORfgx)>`PlC3QspFsEITD#dT{_3nT^lLX`RRh6Uo*R@d*mzmd|zo@zQqm
z9p9o&m-0QEM?#KbCpmk|$_+Pp1~7C$x0YMDGwb$LsyxhMi3@Fng!_NY@@O^R+kI$l
zaJQ{>`kj^NuPZUjR{m)vEZ^YrMS0e@mF#7WSGD`os{f=SH%C=PQs&!=%zGMp=r>(d
zw5fj5AJa%_cXBWGch#655gYWkux`F=*`HLz&W3B&Z`)qCw-q}RIIjKwTRfww{L@O<
zsGiaEw};BegZTTE+PQyOzdh&^txxSI)tGahoYWWkmXmmk<7fLD-@dmG`S&a8dpA`i
z<$hbS*o#>BO$PoH6hEm*d2*^EDdSzmh$Mp8S=Bt8rOLed`@KO{ovIY&@vf4G)^76b
zH)*da;eJw)g3wq|l>2Q(<(Mwe5-K$yNzk8EgrF@`6)Ae#+lqKMr9A%ap;W&1_S=&n
zua_!Pw7>oKD!)DWCH^L?t}0K(pH$@cHdT>FM|)e5X=8Al{1#x4F9*y|D&ib!w<_{v
z>TfFs^aGBo-v~{s<Lf8ADOU<Ap?troR94bW9E86;54O4;i$AGw3n$_?oTKesg?qdl
zuFpDW{dC;^emx$_74<}zZ>t%f_M-|5KObHE!q(4O`01ft7`qgzz;iOSzv>3RUyT~X
zscKc>L2s(@DI0pmTA=w!^Y}?cC@8>*`)yNM>|Mp@Rfc-ZZ;#nFrRH~k?rKlt&z}W5
zx1T?UcrM-asgahkE;rA=^j69>eo-|=`Ql{`IsTOUA}K>xt$>lg(#nL($<_BtXXNJS
zFXc4*AWz`c2*tLOc(3);ftQRrQIz8ZKv9U_Bg)|<)$z;yrKdGf(*A<{gI8LLgL2fX
zZexkdVcl8|0!p<DSm}iz+Yz$TUuA2Pl%fg5<*U4u&TU|EE4cD;3t11ZGcU_=6TH%z
zD+({uBR!%})NS4`;^W?IK%{JTf;%eZ^*!$R<KB!jezuK!vjPQWW?!xdj=A;aH&urr
zd!&tG%+1~eLiXePbIh%upa{WLCX;b(<{DDc02ONYrLKKD4m|lEFC<xTdLY4R{9WjA
zo84%Pt>4(8V{9G!h8$zF6p@k^9^axoooM?y>KI$+z9GkWqycTabN=-$6jsxb(QrFS
zmd9u&?T%4Sqhn05Z}v`$&Cs*>$OK+83lBPH(QrK4)+;G`8;g9`N+u?o^k}<r8<f1z
z`xgX{A6S?Ddl|MHw?UD;S*lW&Dqj%7L@-jKz)U~t_F@oQJ!MQ%^2Hzw!J~e9GZ=M$
zp706P?a6?Yd@@+0e(r?r{o+wa*}9H3)jNF>@|7m?-HF+FHyLT@#oNj#`y)+{o<2R&
zj5CD`UUEi0QN?4=IJY;NST&k{@rX2d&>ebc8fUHo3AqR^;(D5X`<Av44_b#{Q-c)N
zJh?<sA@BG09OyEtr>u*75Vhaidm#Ec)l6uh`B;U-<6W|kDJN$dHJNjgvM(}Drs#vk
zug~p`(AT7={kVlyh3K^(n^_=bACgdB8zX!L`n55lG$hH)H$rE5zcx+;%dd?SphQU+
zz<5gzcIWdI(@j#hfMuYkY7yxr``8|W!@Am2?!olZ(@cvCbx%>}=~%i#1@P33<n?@e
z4`!yQ!)2+burt|8^7*?)%M91R`#h1QL1~k4)F7Nykkvs6#x-){cx0YfdJ^z51&WWP
zq2z4J$1LRW=>*EBLqqLpVTW0_r<EOc=boa^@8CVX>H+VV33q8lC73xVFhr&IM~y7L
zbSZ_e2eH-HZ$8^Z1NkzO1JijX69~h>=Gg4nbizR<;-EY-Q!%}GGMh0yeSkktkE7U_
z@;imcQ07gBQ_&-HE7S1^82W4|c$`ubHk+PO6S>j*xs52c;+e`ZYykb-Mil%yw-E(@
z@?9U6t;k-$hJru&uzx->)3ptzN>BGvrb<uuQsDVzT5TK1m7d<Ex9;VpcAPyey-VZQ
zN2d99(jzm0)AcR0h0`@IGm6uFP6;%ERQn?nlhX|^lb6#`FB6>GVCwWxyWN4BxznXx
z4(3k3G@uE4X1bUnb^4{(iNW0IlCV&EGrhYFrcRfD9ZZ$3oHGW*-kPW&gW1!^HlW&-
zM&?64mb8qxD=BlOk8MCPd%Xt^rb-tS#bBy*%47FQjoI(+r9OL!V>p-AwmX-`<Ry@q
zm9!?t0$f>Z;w8Y_wI&<_JYs7C8-#9t)PypCV{L76vxPlMp16-HXaVT%%oXJ<$MZZf
z0c7}=cpkJt@ums~VkW~13g*{PjJai40Mz7+u^-TZGon7Uf8`PjO3cl+vBdo3knp?@
z)C_tD=yuJZ_R;w@OM;J3L|Z;{Lha0ebVvNIj5NpnK$&<y<T_pzIUYFTOurX|*p}>q
z7DloJ*b_A)zTxW5%!fgV)sbL^yL`>)?ZGG64A#a~qh@sWfcllO*zn%38G${hUI_}-
zNq7di=)hm_BFrKF)#Kh^7B_}h<LXf}m>RFARgu%fG@31b;*Lu4e}{sSanJy<uNeo8
zi%ZR@XFVO?8B~D`eU`xip<@_dPjQo}8LW(0l4|_@%8_a*xRLBI!;lA5hYUj=p(td?
zG444>%@|_@$5f*q1=4cYj2<4yS7|Kuc!0|A8fT^Hi5d5t$^hTUA6_lp{qZWUVBWzj
zsV40g2E%G8o1t1{=q}&UGEg^?G8|6gR>ZMwV{0f@NJ16&oSGrBou{(VH6zlv*9?d4
zID#`A7I&YT;jp;-R7=M$#B$XPevNQ1C!Fj&hOGE7-wD!zyU$SWs2%5_!d7t_Zego#
z?AwA?afVqtSj59#KKIAg&yYz7N2Mt+ToGzSNFE;w2drC&WXL{~JV8X^qGYUMFb$Tx
zL!pV)Bw>&Srfz|hApo~H%FY3zgdHU}Dcm8Pf>t5iOnP9)Wz%-of$`!x;J1n@!?EFF
zQMbrSNU<%lk}o;u4~BHUG+`PUn=p+mqgpw#jB4$iV#c+`qp4KMZeAkyarII3B`!Vy
z%0M;0_0D)&NTMpm5_g8W#c29PrpkjJ7lvB-uglS<R>3GBI(Shs7}!6-jO&Eh+2T42
z%$Le_!cb+Wu<Rp~9_r!FUOrhPMkbJWL`~N%7PM$|r}~M}>E4g%><Xl(1Ee#4bTRHb
zMkiAM(v$JYFeu?@bSc6-&cJlWh-_(2=&ZwMcm|kzAp_+(G<tL6a`7ag<eywkfCI>>
zng9ooQwmCrd&S|Dp^jW=WLPS4-8sd}Q1ELa985gQrWagf-CLB(N&}5>MlP+Y<Tb7t
z)nCP|O>8fD*y4)el#?}L0V%w3!B~WZYrytOGy|yCwF|GIqm=|~2sTM)20mi-XSD;A
zf>w&U3N}f=w`-OBZ$q!viAUl2&@=uP2z*uXw~nQ^io|Mwx?5%P4LG}6l~*L)FyuJc
zhL<+X4YWa&2Dn&ffG$ygozz$@cqA(^@YiaD>;hV?X2>pX7fwlVk6127fdPG_D%lnB
z%bbEKLR2HH_Xtu)JLxRg&=BX@G$78iX+V)KgTO0`!fBcY#3h8etr|)(7-{|CkaIXG
zp<`k&GUYHGvfR*cwWw8~2mqxyY6c85;WGn<nKHV{l*7!^8A43A!&>u0{Okj_@<eYP
z^Q_qW^)ENO#ctU9jUQ~#J!m6=dTRWnvJnn~5xOmgNj?`1Bk_x_7Y9&gcdxqatozFm
zgw9qBUL}}op%-a_6%{l>1{5#p13KlH(ox1R62pnZ*btkdjLA#dGe8f>O*Mn3+o^E~
z#R|(UBbS9C{<$YujMd(;tYRp-Ss4Yqlpla6EefofMghNLS;dDbb;u~<Whlc9#3=#$
zH#HpMqQMxGk=jO)E{z8{TPkC>58@Y9r9WI04u`y<T$c)DVK9mC?tmdW+zlzw(fa1(
z#gsTT<Gtfn0#CFL;R)5Ej3-Z06frEw@S<m4gAF6&!+{D^Gd|n^y<LlpdPavZ#V_I-
zQ!|Jh*O)5DTP8%R8CDKlAE#i5P`itCHr!fjVGUo8GWE=Bp<owXIf2bnGdkVU2@9->
z$D1-`8iQ|X&3JW#NG`gTTEh}Z(KCo-<n{z`&f$baGQ81DA{oZ4^~eKcoSJd(M8>Iw
z_gyp1oZK@`oXo==zvyMi%u6&B0OaOLLMaws+9LpM7KOZo<-f?m+8~%~2G;}9W>EwS
z8EY>M(;yv-Uf$z2R?8*p18!rBMD{`&W=Ot;I4sgaaj&X~(RVaF+{lYes<=tjLd_Hx
zsTV@Wh-u@*wZ}<vKu70fFRtuGcmKb3&$g4FkAgCAeR7Hh7!6UawbKg(u!ZUz6hfa~
z;V8LbpTYwY+qFWJmc%^9m0s8axGF6I(P<$`H_BA!gfxaEEqt*%2y;_Q0vJy?asr=r
zs%sG{JUwsr6J9QfVt{*1x`R4`ExJw$dnQ6Ht;%Jf80(l=#1Nc2AvRG$5noZlma3GT
z2|7&4xl>~41w=g5@xVh`rQl3#VyL?bx$wL_cnQ<%>NzQ4*Gx=?N`F|Q5W_C9mDw#9
zwX0iRsKFAhF^mu;L5LwU6N9*^*Q8*t3zoR4XD%~E=1w`mxDBRyy&u1l&^y=N)H~PR
zpL<`*vE@3^vC%O~(P;t~Lyvr+c%O-6Oil8Igr9&*Ffo+GF{X6fDeM~>O)cshdk416
z#J;GMjyol~j*W8={3c0`b%VaSdy4udh2oNdmVsr1zPQ6q^wm*fM=Y}&?yr*{vq(^F
z7KLd3w<ehsc8pzD5HS2osxcUBJ17e~WvVZPTTL~L>u;Hu5q4pjY&8jN6??E;8gBv1
z%cXX)FUuv~Bn2&FW0s-OB_-T~0)PZkJxiYgd<umIg6SbnUdq9JT`)^m6;ZrI&Nsyw
zBqfAMVweCA1td_|Gg)shrK%cO2)wtyP}l@Gf8wp}g)%VusC4#?aDdYHo`Hh!N?{$0
z{>1&6lt3)FIqTrVX+Qd>vSCW#BmfCsDOgXe$XQj1<-!$H(AL@ChH>qUU~6s7V2_@Z
zBs=BmV&?GyM1q~WMeTySMPmWsRI6lW+{Ruh<9yj1=c#s+!ts)uCpBi}QoC<;hM>ax
z*2*QNi<``9<K^R_%r_e|2`aEtrn*7E+db6{bkcwja6+4p%+&KrVOJrSnea!HLs@|;
z;e(ht=!L+(5m|R%=sL^BF9$K2_ocp*!oCqQdJk>Rq-b*@M)S_^D=8FX2pPP`s~BTG
zrz1rjvOYatDX%h<XacVkN!|klyD6<7%2D-FewFyd7D&oLaDhBI99!Vtk07E8yi(XV
zz;OUDkQ4@r^88!q0(n*vUEq}hl}&l(Zd1qHNT!ZA%8L>Je1Rhsg@rG$6{>pXrm31S
zcL?uzjqaMn7f7v!@B*m|F;iP;PlOj>2_Pt`djVe{)wK-J+Vjv+Nli*P;7d0o!hjS?
z;tQnGNqm9SRGk8))0ml#8cimmqi|xLxs#Uy7I`JWA_lxb%o2+@Z*_zvo45MGlFj?|
zT0q2s<AtK@M@PetE$SPY4D-T5!~wtI9KRReJ9+y8`)6Li!0b77^#iZxq$p-ux0&}Z
zFneB~u6_<tz?+{a(Kl`u#4N}=rKg(2fXUtKkylp&807U92nI1Ya(3vh4L%NCc(MIw
zMlO=G1Fi+Sp)V4zyku{uwE`trD#+X}Lxm!&Lxf%8ZkOeP-0d_TfVVvj7Z@y^m4!Fx
z2}@zPz_y)DmJ9N-$#l_Crrn}5Z!2$Mml)h+xgdkvBkeVwv=xnjw}$gx>9VJNG8TC<
z*hiX^JYB5JO{)ZR)tTvJU+q;Z+?vKRGEychF_I!}0`SxUAvz3d7+aO?j(np;Q#$Qg
zWhQiE$ReC*hMSVgloD(smRwdsPxy;g$hxrUmnlXSS?;(A%d5%K(+`6a<XxCNeR`+N
zwq#S7^kp{nEXc6hl1q5NrTO*nWXfoUT%tCnMB9^6Pk0U&Z*5GyeN%bJ+}pQ|$Y9Dv
znMY@%Md5HRwiBT&vS%{~b=tfag*Ie@Nle<&S%NK|dx~LcGR8A!cCCBvZ5s9CTfEYy
z4<ll|(x?yKTxrxNZ_=nwR?w(VKSIXT<y%FKaG`pV5tjx-KE!=dZz5ITIyEzGuZP+A
zH9&&&>H-Xde5zsk^a^Xh@qxfTJ?}6Jdp-$O1m097+GbD<o|T?uf7j8>yM}>J1#vBU
zxniVXf|tC4P#hqk66fCZSjDNgc)P>j`7W8j7V+w?<k<{is7ju_LKO7UR~e6>H^_?k
zgLp1HK;f%oN4ak=j`hm-QLeJ_{qSOqqGwii93}8KpD{U6JYy=uHNE+3B720ZepNo}
ziw~JhXALKO;YHVr51G1e1xn))FVs%pQ>N}pSIJjx%&%xHT;8HbZLMa}t2URj=vAAu
zgodYw`Fhc-CG$+ve_v1hmCpK=R|0zGS84ln!-prq@u6@@_cy>#46Se_PdX%UqI~D1
zl6{@K(?g}Be3kMHulN`i{okup<3XpE&X;75sf5>uY6Y95<qp1iN`a;0I=nzUeDa3V
z2bOKnt3~=LUDD}r!Z6JAN%1Jm-ED<&nBmq^;b$(dmpUjZrCN?Cg_A<1`*@XtNbhmE
z-!LGP4mx$vqeU9wU<jrBd>ErCU!XeZ(IRb+e&1E9-SYdcmv4qa$;tPeIv_cvv<*s5
zDQSq;l-pATb<$UgAV^R<g}_gwr7DnqhH%OY%Nz0{*8!IQD*b9ufJ$E)^lFj5G+@xL
zOe(;r&044UPtO+VLUhBH3)>3gbRRc-fONR7Qga3*wbY!^G&+u#ZZ50<rvfP{^qQ_W
z$4Xg!Ypl&ni7rK_zp$JWZ)#Dv=JZ~X8j;XOuO;oRFe0XV<qoUGHXxp@uymHqtFy{6
zy2y$l&*-Af<I>u6$jUjoXo65v>4+MUq6IB;>r{AY3I!|*WI&O3D>r=!<y~H~6&VVu
za*tGGFsN3!7Vw6y+7k4Ju8g>06li6tlogukezZEX5b?Pv><CY!X4Fh0z_Xf;8@WR3
zxREO~?Pc_G)~V5f^;eb7rpnEkXM|juWyzsSv*f>Anw4deA)e{Tyh1O-qgXP(L(*DD
z>DnEoYbSn!oT)2va#Up-S`_(Ut5v#Svt2k~^ShLTH08Nmq-9I!bMqi){AXq6CMSg7
zu;g=h4b^m8M>uFz#wdn^R?}rXvYWue{Q!mj>|_#*ljhgzjyt{*V=c<H``>%eXs}J9
z6>+3hX}Thgv?`I8$C3JId3BYK_$7-MLQ5l5pvq-ja#b$lx>3qyTr$&L#v|5&Bcac@
zZigKYvo<*vw-YE!n@5@YV6oM@A~|v-H3BfmB)X5^+t3)uK|QB81#)m~bSl>+O-|*!
zlF6qWqBMe0BVgvl4;Y=o(Pgj<hX;*Z=>ThoM&1&lFoR`sbP)!0=I8`r_~C)4H~P^M
z8bg3y8Ynq5FJY6jzC>>~#y?5+_E7tkGqTc^U5O<bN1L%p)zdN6$QQ_QF(`_X$rKYs
z!DI}IGPQ!BD1vY^)|SCmbvej4T`v%KTbVqR;FKA?g+SajLqjo!uDb%FaH}$^GRC$l
z4{PmJ0ctcR^_mfCY6uZ(WJ*<l8b5v5R*<yTCs?;oxk|r!<;q25?iO*kD84{Y-owlO
zh_F4i!VtWRzv<|Asu2VjqQu}r-ZeV0@~Di%5nu6#m5%tWYalT>8HN?q2nON$(o!hn
z`qEM`6KhX4+kSF>GSPONrY&VPPScjs+Mntb;>o~Z#DN|pdG9im!kJ&G<113iWyooz
zdq4cfj}HY9XYguWF8@u!nlAqefUQVvrzqJ+KoTC045SqXn1XE?ahw6U3^``hE+`Mg
z^&TL^yk!Gy8AP1J*@B2ciFr>QWG$nJb3DO{JIC|Lc;?FZ0tG#z?(xXTXofOp^mIkU
zf#R!cV*s&iWC%hyGE$qf$!P8xaS4j`CI=7@PRim$?2Ut@vuu&&wS~5!;BzvYTNRYE
zYJ(piTB8hgU+c)=d!o%=3clxnF2&yS48w-V;QJaWB{M#syQp@FW8lXs(ErfpOEdtd
zJQ6E_(bzja?j?8wZsiMZk3uG>ktQ?o4ftgwP;g~LMK_d!HEF+D0T!LMn%_ZJg|^dW
zCc<}JyEN?Pndt=AAW`7wj+%)HO0GkI)GnR74Ng#U9daiTCK5?l<{OBs1gStw_@QIo
zNm2|xB=ZP+Q5n(ErG!IH26o0lif;zVaUl0~HW3>^Z;6n_(4T@3UV&ZewaagyfuKx$
zkfBxx55g7cf(PM=&(M)BlSmvL31GrV^~5-FijR2YhQ}pbP$`x1CS7WFi)OhTQ1cvl
z1!r8qz;G=HZNpb5hNlSO1xID*{85ZOc<GYY2xF5Hnm9Hop%cc2JRpz_Ktz&YYJ|u(
z+?0uIGc^9-w#*Kp9~=+fxPlbSP5F!0t$ydUgSGcIZC6AR2Z$uxB!l85&KgRjz=o*b
z;C6bDv_?Fn5koB^pl47V@#zH1RphJ<*PbEsLnG2KM?x$o&e(wEWEyMVv7M;W@tPkL
zVml3ul-N#FBPHd|h639u#VM3mAz1Ac&M?58DzPyt!i8u_i61%p1*nyjlyw#mTo`Xn
zR4%d>W|{$0_Esiyp(qbp5*lndffjbWkYrsT<frsiMlKEMs~bgMGz|8mZN0}j%B5qY
zB=UNHB(&O*gvtREe2x5umOfIHB_;a_^V>*S27fX^-SbA0_;R1|y>pgBz7-ouKk-@1
zQoB*I>zMV(bGiy=FPTnCu6UQ>cQ0>@36pd3J9u^FY6oLdbdfT*e!~w%fP=}Zxh;3F
zD#ce)vUf*4n>xls$j;+SxnE1$Hj6Lk-ujKlKtVHB<fc#f#+{OzD#0MPlHMRzG~1O5
zB1#w~z!$F64U@tS=md0?EXMQBsUIvBUc8iVglyHnyQ}D`vXQt)0q0(~hC#^T26`#Q
z4=;*W3LDrzuevoGloT(xOkOEnkbgAcNQppFFWVXlO53V+yj$)iNgLcqFFg@$l%Y8W
zektvIB5e8t+&HhX*K$hU$Z)y6uKhPoxf$&Mvq_!jV=rJ!z9RfbiHc^SsWftU94{o=
zTnlj`CZ%Fh`qq%|``Pz~f;3oKYdlAeOO(#B#n7oe1tIcJWF?>dgo3mavXV1V*;z<A
zGKEWlVxcrIJ0VBoi>hofJLS$vb~%LY<=EPVCT*m#*~?R$i#@7zI3R5)a|$6rlvZb_
zuwnm(!g22SM9RL_m!}LrB5d0uK3`@EI$lWZ$;E&Y5bcypKUvIF9wShWEzwaSHi{A<
z?G$XQac<d^Sb{CR@Qr~PnRWuY1@dHMb=peYP6P5ZGeZ@=Whi-6foez>&{qn!Mm&ie
znW<_~d}DehtF5$k?c0>uuyz9O_yypanNw@0WY4}SZ@zXE*He|e>-g)e9_2hEdtopM
zr5=BG7SdloD65udObi3dPQs2w0=nh*kJa5MSY7y%d$PvRL>8%brE}bhgX46TWRA$B
zTw6!Zu1q$$NQ)(zkaAJFmz%~L<?N_;CBEd?#u+_fMMYsJqXC6o-HtobbXLwMvMSDG
z_1db7&^7wCYMK7iDLoQ-P7U6pt1^)&NttZ4Al+alBrWHju(X_+_LTBrBgOY~W+qg!
z8<|kcDR%qu;t5ydX0RxW%buq7<ZnnJzmYCg*<PJ;BmXM|&53-e${Jfd@F6nF`rmtD
z%2`l+J(!gigh*{`nt-oTDdIRX7nPzN9=TLY5yOEHvq-ll;Hy&V#t2`6Qj_7a1WMlP
z+%57-Vv!s`vQ?%BE&%w?1i}T`EF-~iiQth)bIdIl==qHMC`gED3eG5qK{3TqIOUF9
z$Jz-MoHwz+bFnJCpdi_mDVktWg8NM;#ffyRa^NpW>#2m#PPzJ)5xShn&q}BG63Ic2
zEwglCqJ+X91fRRuU|s?bkg*l6<42H!vt3L;#@3Q@4jEe&Ai5|ul56|da5yE{n_>?6
zSxbsJ<Y$!+cJY8DlQXrKBRP8tI^<`Sv$RuMG)yKKcsaBvekDFKnfamwGp}Su?AuFA
zf+VeQKQ3o`SO#?$gjkupgbT9BT2bkabnaw+<YFz7dhi>`Jn>2=F;G|>tGu!zHKq}`
z=k`SJ@;*9{NYmhJgwPk0tI-`f-i1OG;W8c)90l*~;>8K^HAd8<`%=j9D#YFaj1p3Q
zn!JDzz+;ZhbOd2dUOqoa8*0LQx{>=`9zQp7zY9xh#SI-%W)uFY$+rigMkWX=Bs4Yo
z^4yUIzE0jzkOY;{;X&|W+&PS3123wGg0f28^+tTR3FhlYUU;E^-7{uSW%fo+c)9W*
z{K`xQw;L(p1vlmqTPB3EJ7#SHF+-3SBlUyeV$jYU#?^%y;N^*4H4LA<Wumh{B4{oj
z5Nl>~{JD`Hp3rd*#HX3?=I%&;A|D^-$#viawqfXVvW+gNg(!Nbd}T&DUNhzsypasv
zYL4QHCVG@&mNmx^v($ld280B(N$PfHk4-@{+f;~{q^17i%V{RzadMg_l`WRjc2&yD
z90O)$yBdX#d5eNtWNjOYf5X-`?J*|Twz2pQHrekA;vg3(Py1L&>C04U<Q+tn#-uPy
z6R|vDToaM+k8}^~pEV7mCLKOpW_{B$Vp2Wzt(a5KgKhz_?An1LXm8U7=n4ddAmCke
zP{xXl?Yxa`IOyW8)86v1!Rao%OC9AlHVq(lBQ)<Lk8Zm*eI#ad<q%_$F7XM+v+?{v
zh@9EAorVQnUHpxq**yAU4!Y65<R&~oap5CBhXMd8lb=I@OE{6aKxvcdK#!oT-PyGB
zfV@Qzu%P%fn>JoGA&Ge@UO~*g7z(_*t!aM&S<L9fP~f?3!c{Kt+_olfvQlx}%X6Us
ziGdhvi_(O_=B4-^+F;3f-(;1k$a*e+gaTh{6E1ZDK%B`Pp;ROYGT~bn_*XATx>f3e
ztMd{@!EI9Gy^W}M$4BOq(wz-%($=^u;3aMHJ179(u*O|+6u3n@38No@{D+Yb3`KXe
zIxv=qGb)4_B%mNjX!PQ5x<Cn|JkTmOEbvDxTo4YBV)bq@AKFU0$(Jh-6VWQPlXi<I
z7Z>o>a)m}Br-TB}XKTFX!SC7Rl2G9HZ2de?bjEhsp8|{0y39||Z>+=o1oei<l+O83
z4&;tdpwJk`iF3W{J{OpsCbxr9!K*;u3_?L2u0))}axo}SR>-j%om9Ty7bq(xcY*?K
z#k$N+c19_<V=#C0ICqNy3)tjZP@uk;d<zQn7n5&5ahz9^XF!2JvvoUITpL6=8w&Ip
zlczv|LSyn2D9~t}f@2<fjmdeS1PGJKcc8$d*|A?^lfa|d!l!Nt_i$ET2(!5A{8g^k
zf_ErWZkaNW&36=ifbkM#dg?5|P<INfboe&(vRUx(WXy(B!uS6O&}bOgF7?InKwTfY
zqzBHtDGyJ<Q`7+r>!A3|M;aaDATqs=7GUEW-bc%bPG}E9M1?7lP>G-m)6;0dtCPce
zV<Z#32<M?7*n{}sK?y$SK98p;!-Hu-REg=q^eA|ZB3ya=$k%(Mb<&kl<-jX=in7sI
z@*O^OEDn4&%Hvd!gJMyFlgML1ME0O~&>&&kLAs})-GkDJ{*E$+!Y}6v^)Oys4^Uz+
zGTyx);s|i`PJ!w-WcEZblSPEZ0a8OXhzz`L5iCC_E=2TNTM%AlBah-Mdg6$osws_E
ziMTG)(`{j1>mggh<yh>dx7>o<FQ&BLB|^+h*_-hk#!Ll^0#nBr0j*K+KE`YZK?yeS
zy|*CIjtxZS6y)Y%7KI~71MNV7;Zbd+W<bdoR+d@h8DeUOpu};d7vh4%N6Zlc3L4^)
zKqnc}1tL>ZG}J+G#z==m+9*@%xPpJj1UnY!(pMZQuS^fk1<ACSVIwH(7gICrSfJE5
z;=#}K5?wBeP1;AU@nAX-FJZl;e|RKkBoV>yu~B3+_Fz!YP10C{!{9eGI10^fXc*j)
z*Mpf;yo7PE<h-~wQ-GP6p1NN$eIp*aDWobQrket)W}G+;h}DNv;s*oG`Cl4QuOo1~
zDZC1y-L29bKch8VArTzj>WqSS&Q+Nq$eV01D*!!;&aPR}x13QUjd)WC)~x8At2E6E
zK2l@XoU5^W2#0CvKi0<s?;A17r>T3)H9o8+Sn~;2mnP_Qq?&CNg%|;s3-|#|)*fIC
zv<T%og3_ab*p|R4XtD<Z%Am;}6mSPlz#0PzzXA1qh7#XoFT(S1lf5Wjhl6mViQ)T(
z@nN%T7~n;GK27mrvuhY&MSMZcqs3-?JWbH`Grpc?)MeLma};ApAq1NtwtV`R(@eRT
zX2?6I!~m`>y(?a(oAIe*h8$}^^#_#3(G<Nl<CAEzUg71sDVhzK9gA?G4WF?o(NrLR
z1SQ54Te->N1^kfa;cqjPk0$fi#MW$zhnq8|O$RkVm^9@@m^UU$J#PBOX`xCULGV2$
zqZyD?nxf?Zwz3F4iZM?b)ri=#D6s9Gn5gV*Cnic&5wI|gv32*Uxk6dEgYzv7aVO^*
z8|XeUSMRZ4o^)5akteLBp{`(}yg}Rr6NOHB7p!QOW1_;yz6+L=PepgdCYG(QVxoNg
zzAGjQ>mP#pn(-16&)_Z1fsk3oJIQTeChUW^sSE5Yyn;8QB8x}xX1ulB24+&T#S{1o
z!5QD&%y_r;7sBR+&etx^`u9`J<5!bO#(@S*!n2(o1#bg3x)*{goo#Z^*0V(tu4n_u
zk>jO+1}zHydZ$t}lxdlwq0cj%RJPU(%VYibpZ@FfPUT-&M@C^oS|gy9{L_DV{Qa?{
z(D@wW=Rcpd|K(qf={)-LbZzT=wzRxI>a)G__{(p{zxew<pMPGA{L9}T|M5?M`Mc7t
zKmF5x|1W>{pZ@Z1kAL--V+lZHp&sQP=W4u-=YOu>%|cz^8QUEm=r_LvEe1uIiLHNW
zv=JBiX0(6$zy9C<_IH2zhZyBVQ+Cz<?C&W7R?2KE?RSS+amI0&@Xr6nDBX1Uc9j43
z|M9Oi%C=a!5_vbf7p&7$rkqc%mfz3ljrUIulECHrDF3>W!#k*oAF^Lm82*!n3SNSL
z(BHrZS2Eu3t$+P@z5nUIe|$U^N3^~Ewj}5An8E3_y6?94<Ne*{;=}6*nOW2K<`qKo
zH!xtK;9Sq$@Z40(tn&MN;m=K5;cp)$?CfhJxb*BYyuXu(9jPU<nsQCNt#&exJZjP3
z<E``!^gvZY`D>9KJypur>u=nA$@{ioysqEpy?vkeEs{>=#K!##6GKkgtfeHiZ>zyS
zIIA_P3~#I9o{-gaad=w|D12hSQ2D;c|Mj5%lf7U60RQ2Clao8kFHFv6+}%`-gfFTg
zrE^xh7<>A*8Ui)4nj$yeRzrLnSHKiC`K=Xj)A>)nfb#tn;4^DZPVcU7CkK$Mtfu50
zZ>ycxr{2!%7kaBuG*yj+FRIPBFmMG}{@c`*XPt7DIo&V%{QVVpoZnvog3{#V24CCW
zP7X1ISxrHOZ>s@RAgc*w;B7S^24yut2)(UV>W@4EqV!$vFL$lqmq3p{u>W5q^4HS1
zI8<a-nEj0ghAP*#aaZAspCh6!t0=_oZ8by_lGiMMliOv5{r+UH{{eZ=m!+JX%mHsF
z2UN<eCYZ{%)z0>*x3m31Z*YiLEjh@)s{|lGvj3tj^jq9t@Q**)>VH7li4eJ**RWrh
z7w`u*eQ}%E&reKO-?sx3xAFIq$?X7}VEP5Sz|D@F>-W~p-@fJRkNJ}w|3|d@yn~QX
zH|611Z=>s${v76$|LZ;NCu+cVh6yZz9Ht26opOr!(X1xI+iF+5iDfkr-d2O{Fsq61
zwi-QjvtClZu?WkD@9RbQ&Iek6PP`3Nl=m|XtMFEjg!k1vntQ8-^7~4GU$xaD;eEAh
z-zHJ|2J_cb_xUyVzjHQ~fQa4(Ny7Vy-SPCX)f44yMdohEib;825kQDrMN!^YZ1I|~
zRTSkLYq3DVuCLePJ6c&qp5tw#qP(9X+%C3?qP(w&x5TZYDDNvG6~b0gl(!W<4(FxE
zq<rgac<P|j`rY2G#`kV0NJP3D((G5{Jd+h}6-9Yp5iVm}MN!^Y41mhLqA2ex0vUR%
zD9U$MV?h|(m#guu8w*~JwvmeRc8cxnpU%&uysrqf@vWjL?<<<^mAv%6g6AXN>yYq`
zHCTqV`|CCM&RNksoN^l`%I_!Vu-1Dm65dyvyNrm^+X@}Vv#gYq_Z5*^ZmTHDH~8OI
zG~L(y|Bj~A0YAHqRFwBqL^|WGqA2ex28`uiQIz);;oP=W6y<$IcyMeLMfuKZtkeNt
zuf`v^<LDChdgb|ee4fcyxBO4<H6nb|WcsZC&+=kZ%I7B=QNEgCAiHn%2=)HH+NVbw
z623Bje0sJa;j3z|4>v4-cM;Bio~N5~0#tpQ-nieM^sM;#{YI28%}MohkH7SU^HiAT
z=N^CQ5vQDpYR$D!nCmweV?}EIZ@fEcpa^){W_Xrgcw4zYzvSG%^pbObe#yCi=_Tie
zCwf+sYx>)2z$KKKsnN0YTZ?cnjrJ!}=?_@4@6RteBz!Ts&o4RmFTLd4z+Bj@q}MMz
z2u#3csM-{c#@lM2UUKFid&!yqJTE!(^GnYBrI(!9ZL8v7lW%{%9&EM>c7OQ<G3(eW
zc;NNhpTE4?%s=vKGyi#BZLWL1J_wNTg^?aEr&(?GUw9C>0AH2WglF}(+UJ*?>z7_~
zE}$LjDM9GR-&%odz2y941^$4<zu?%Jlar_C+sOe*Agc*l;BB?Ded_IOztG!&GiN?|
z+~+U6M2zrn*9x%w%@r6+0sr542jVCZzmt<wK+oIB0X{mb_45}VTE=IUcl?sZJ3f0U
zjbHLo8t2X4Vg=57>+Ek|f%UfYlW*V;-2*;9?mQ{)A2Q+sxK&KbH?DRo^dl^PrTlL;
z{W0)$8|p^-(&E2Yi{iIz{?Ctm#N*uC`Th8gAY(GbZKxaR3uCi=-T)ivI~Mf?Nc>AP
z{nmB`@YB9ulk|l>HtrjH)g*n#KDyw$%dgCIe8)To7>I4S8|hapkb6y0zGH)2IX`}B
zp7T5NyaS_QA8nG}TbFEp-V7V*JNBi8uVG(Hq3@`BG$8GRP15_F`&TE)C!ziE_^Z}`
zW!^sLKd;#@?6H{ZTp3Gau|H4yf2~<>Z#Cn`J?kvCUU=u`<?*NgDfYZ`%wN{#|MAmv
zWnMS5s~Pw>ix5#m@!Yq{h%*XBXb~d7&i~5bo$zm*7wsuC;(X?%n6hx&nHRBeX9VfY
zYi5Yv3gVjA%$UCEV?>}_I1H?!qUvh*vf}UzzXwJFGR4k|&Od-IT?EuI42xccp7{1z
z9$PToik+Jm!(9<OH?IJcni0`FFQTZ-ctx5QOlR&;KQ95X%rHF6t7kCY^g(q6t$9H~
zZv{U`l$_zmh}g%CWM07jKv3K&V@f@y)H32NCO`|w91+$xFUDEVcqN_!zC{M-c@eTQ
z5LD;I%Qzy{7J=isz<d}i=M}>sK*7AQyo{VdSlS}&VQGg`(CY+mnWfAVUr%8H&k5cl
zbZSnpwi3T9z*iUL5m9MAE208KRNB1gQw+C}MNm-Mh#?8==>+=)Fm+-KjOhb_>J;4a
zePRrPW4;Rpaz<edLSW7a7@LD(j|do>0)W1OcsvCXeaDQZfTZsz6vlS>o*Ik{Tf<Xm
z?+wVoIS^rr9P(30*AXi=g@uh!uqPo3G2Dy5cd*z@hEG2Q|5U&>AWf&jyzhqb&^&a9
z58fn*gHvceL4z?KVY<Zycq*>_j<EhYh^lvYY%K-H-x0z;6;OY#4{i=(-{7f!5u(rd
zT4x6F-|;~&3XtY}O@$3`4@``X^#MIM2cQdY%x?~Un81@;1mMZV&jrdBBcfa0ePKvS
z$qJaZDJ+LTWphG*5P@w9Q2(A-J7R_ep4#D*bHh)25)`pFvDFw~2RyVnHe|7aDnuqT
z)IhhlPfP)kHzvj)N}#kpDNN`E$koG1gztP7gjEbM(m5C>OIXo~JPbtXnnOu(2+K7C
zj`xGuo^uGv1|XeNNg)WkIhi=(Agtz8VhN&XO(mZo9M)vY3cyx6L12u}+4aP1jX3c|
zNq|Y8P*3pJ*a@=>*6M6=7CuQRu7O<|M#C@?U#nppg5Zh@NKQ~r97mpmWR+qF2{Vb)
zs3$rY&Z90!s54UO%|6s?$G{WyGQP_v1ts4xJ)zEq&!mUo3xaQ&o*<oZhA#@y%y3Bc
zga*AZxRwpYIi>V8i!f1(?ck*9O~aiSZX+t-BE^^+ey|!%7(1L)T}XF0s(M1<0VjMW
z6b}G<XCnBVaboqvbiFZ0L&-&N-*EhHthsRhZY;U*h|1|DbPBNEnE*!xIDS*={~~oS
z1M#8Y6zszAE;t4|L3sjrclIJU6#(zf#Bc)e?o@iIMTy}Hg}mUb>+Z?8SYM*V+2FJz
z*i^xRCo@(FkX@&+U*LpKrP(S0v^x{_szf~S6f#x`895U?E0A>;A<$Gxtp8MQu~J%;
zz*roHN>H{aK3KwumB^7al^bnQVi>|1DLCzvW33>TYbv5>QDO-jAW(`QcTK1%fVQ1Y
zSSx_Goe9KN#<Mhp!w8JpMd~Q~$EEaji{d;a0F9%_P9)Y_B@arUO|XctuS@~k1y1a2
zLiYho>{M33Me#ioXnF@ozG;+Pa8V|zp<$d_3FTLCY#|ZQ5hVYno4(`XN0*W#uCgBx
zjVPEk&W_mx%vIOvvS#UDXkC30O{(J5Qtrq_iS@521&0M=RSS8R7-j`L6KHkCsnvv;
zRdH%H;c5i{;;|^~8mCs{zXw+ZuU&D5wS;KHA=XZDzM2;kgfPZ`qQv(pHW{}syVWAE
zUq)TGAmjU@yn+rsDJaD=SHkJxOfx2CS$Kl0#1?U;DcNg5BKBzs^oMiJ1YBI9_)TNc
zhyH>lxY#EcN(4a7M5=^+blN45ZvYoBQbG(yyNUAWAEpT@2|m5kpbj4eInJk2_!guz
zp9$>=u$`Ikp8=k;2yFNw_Y(mUN1sqg0fRHGt1BFQgfexYn^huiKd}3zvLhE@*DMOV
z#yw3rmmR&&=hP_X1AJx?h*gNQ&zb=LVq+xsCJw(uh7Dwx!%67dp2wdF<1_I3f^rgy
zFUDr7f%}_P3By3mo0b56INXG=QGi@BjmUsF$b<}X6hkpM3k;Dd?2%$P%Y++TfcP<m
zc~XpL8Gus?o@tesya0V;8g*%)`c477ltA^JG4%tKU?q-KK=e+5+Y~_SPNDG>Jul+}
zKb*7%Bh;UQ6`w*5D%cg1U_-@lR}-GmqAZar$fE+>+$p!20+`$>prvBNOY9|pJEj9q
z9-ugLg#=ab^~}l|F&pK0h%ayv*y)9PCh@`x(p}H04;mn}vq~MdIOM9dVZ$L;2Q3B#
z;wv8K0Sz*%^kc*MR)y_qIN+)jWV<;yX~>2Ht_rHyy#;0!)GRVePs}EkcGd*fGn{}`
zkbFoWJ*!mecE$vyQR56*m>5xtZ?fu~ZN*C=b8u?SD#h5dEKNNX7NmDt6fz8{rJf{|
zVw3{ZL=vr8sTaqoJgd~=NF8=KiT&bKtkR8<9&J$|VUU7uQ6Mg!C;zNP8aeXiEfRXh
z&8`Zl6#4vSE$SJEXD!0Kjm(0J!k%HOtkRW3-B|?m)UdJsf5y%wS(cnf&huDBt)MOV
z1i1o@)mnn4>Vft@QIh!F<NU3M$;zzk5H~YGGJ|vwbO5%NWi=g9ek4Dyu7j1uW-#?I
zkA!CemF24yLV3<rww{?p5$C2Q#qcVwKhi<VA`kLYC{VhJt!FIDD`EOCS{B>S9keXi
z&z*|(M<Ct6XK~WK9t_e(HYJaj!$?cV%X~!o8c_HZRJd0ADo%8aU4JC%AIMjfaFLw9
zN1*-zd_`7s=J!2qsR8%Oa1L@Z`mV1Y1$CC!SF?hn%%$9%HfNnxY<>@N)h?IE;Lvmg
zD8I+5Rh&wbqSZ&Dx>20`%6G`7%J2G0gph-G6)*X##z|*6YOb#~$sixra{Us{tVf{E
z;kwKcC}h)JUx^e7s~?HG2KJR|)roz@30(&+&LX>=+_;OQ=B;}LJeJA_?jBHVxQ~8Y
zY>{{p)>nEay$w%_m`6@=<#o>h!mm^g?vM4A(~*y4sp!rXWpAz-K7KIx+5{iK;A<Nk
zr_7a*u9PyiM<l&q;k&IjvGBE-J~9>FPjXwq`gx7nBUjRqPzVgHd~K@Vy0xb*wKzCm
zYL)?|udVP5Ib5%da2QqVE8a8`I$iDQ#w}(?y|Srlx4ybjl%HE)Z7Isc9f`}B9h>B<
zM}<T1NWR*5_l11D*l{ebukckmAM-)VOPuie+A626*Lr1@Pp<P`TjdjkeFq!O<U;Rt
z?%J7Oklw-wZIjOnvac%bOdUO68{iX+eKEi@P4arbEYO@OUz^tx1bywaKBDaEmw^}v
zeU-Mj-M`gu@bh)1>q)}=_1Z+AAn5xgRR%#{o9J02cD=UHajie=RqE!>3+5tCnZJ0w
zhWiPmzBb#b?YdqkJ1i5>d}VRxwZeMsz~<s%y>?)8GqI>Pb~YJqFV<_DdxD6sT-div
z>w4|MCT(wQd$8wBYwL)lJZ_5(fW*16Wq*?=H@2PCd9?$n@<DR?AKS~DjI*(APLrQH
z==yzpY<s8YPJ1i1-P1E+Ew;?*xl^&N>ABIHX@wKgV$Z+HpUWkH+Cv?QX-D#<nI5;T
zq`EI%$0C26G5ROEAIO7J>@Q<;$<f&U<__^lzC6&^)H)(%CQdstz5;!>s%h*m-*u%c
z{m*w6-;pDgJJtB=1#;~gSx+$UWaBG0nAf&f@;8O^b0yL&=B%ym$nVEj{xJG&{Y%2;
zD^b;g=)6m^vO@%2o7tI+IljV;Bx4R0c6@GH<osQ|>|*e<+R7#Yb9`kaWAOGAIZ8;c
zd?ZpfZ|hHf<(|)wp2;s{k93gaF}}i>q*RVAJ3BKf$F`XrlQCgsM=+q*djuqf_^Nh7
zD~)Y)JPsblvN0a%;5`zJFg>WT?39KL5h^Mg>C!rFje5a;wxJ#AI*VmP8zM)nFOPJB
zWGrQ#-nVaGy6a8foObz$vUB!S$EI`kRIl8+g4BMeecs(APxVtEvm6l<1)C+7EphlP
zv0RY`Ld%gXfS)?Iv232N{M}>W(k2o0X|pvzOF6`FeJ3k09SI8^X3CL#-^vcku3qie
zu*FPL=vbe{40R=zbK%2XiDjquYW!~9Pi20)%K)v$1l#iFACH9HAisYEY(k`Wj)kTD
z97)ceP3?8Rk$>HneaSjrgIC2~Z73)|$wTve-u`Mz_#TNyHc@9|c*Sk$fmAX%<fv@s
zWZ7B0z_4X!^#a6}t?6W_9D%&CBu0)~8@a$fiLkMJU-i@0Gl96Uw|Zp_;-7@p?S)xT
zN0Jc(vUzjmMyx+ixU(0_-D3S85wpP_5n=Z<nT;d7{_a*2VOmCksd7ZA8>ULQTy%k|
z5-urSpsE~+?Byh^gh^F}48{>Mg`uN_YgLz>Ej<)|PMAeiNLYL%dg?{Ouob*P!mt^<
zLBbev^lyOBrM1fj2;ozm_U*i_VE8K$vV@-kfhAnByKKdE*gXxFM#wz=A#IpqRd&}1
zF^!?QgzJVE5dBCrVuh2~eom%KM6>e<u1lDzRrX+nHlHy<B5Vy~r$l@X>z^SLu9#jn
zz!$cKv3-Iv>xIIKr>*YJ1PRw_FVs)`!e0uMmIynnDT)|jhxMjfz!41u<F?ohV7`QE
z%NGh3hRe^FtM&E89i;^$Y)w;1FwEO3&{SgD42Gx@Ft45zjVt)Rbh|R`t;UKDWd^O-
z-r;Hq_01c=Fy*RZz=vxvRIL1P-G-WF?!u)Wsw(@2ibGT?*o7-fRO;2mT(ojPVa4T+
z$Ayb4440UpX9930XjQl>F{gXdvh`+1ak?Inz5;s9N$bwN>zh=LdPk!116^4*<w3Oh
zT4y4Gt~snbp=%Cn?#%3<m1gbiRt>g^hE<`!glo*ycifhg4tn3u8&Nr8hiO=qvwOG@
z&yi#&n!7dmd2>lVDawx2KM%^DRCO(GL*2?><Ve)D$Rj|w98sleb(mdMaeajA9M$xW
z#4J`Edb5f&FW#(T?O@|9)($?JrByHMCDN1dAjqHa)pIvvc>UbXtCE&+&B*nbuX{@|
z_!u&KD+Q)wVD=ut?VLGSwSb2st=@VGD=|!At}s?&$OT<tti+HD`bci~$FgSNaJW`V
zO<v29NHr(Fu~40cP7JxAD~`Y;0dp#z!XuLM${^)~K9cNm_(33`=v(#rM$cTy%B?t1
zV@&rCcpLNI^quUD*EdetBgwn5TKa9V%fMTSG2AuaZ4B!L-o~)ro({z@XRG2gJ`$<!
zO!?4=fVVNMedL69VOhn4eMHjE(QoKrU8%4fqq)zM9yU1(Y7$n$wa<>=BHC!~Ac!`a
zItZYt6x(w}`SLYBaGohA^l9gOSN9D(8`XN(ZNXHm)K5Mllmc*OWF1M4rqap~(_*b0
z>0JD-a@BGq8XJ%}WOg4({y^`aZ{2ARGp=gQBbtLGjv)IY7j)&q=_jFe16Q{vo-3;m
zxvEy6t#4}q+FZ}Dau;?aNAZ)Qe6aMUl@b2J9gX=|6{<|AHe;>S{tMS{tVxwQ0_o*6
z*O%4gPZ_3Z)x3%PZK=)$P)S%BE>c-<&i?4(c>@+r!m8BlJQ7?gN0eQj9t5!1rv{Oz
z*r!#4iX9XDxuP6|Oz_GLZuDvGKx3aC)_Lr(;sNsaA<c=*(T7z7pRm4a1wZ?+-aJ3{
zVc396b41cR8Dh8YnPU`;bDbU{hCNr5L+q%I`?nqmoVvVgg)|c`0b46fo#-;ID>bQ(
zgokGDn}>rZv^P&9V49q;2T{Jva!*%iG)E%k7fpM$W=@;Eq8SW20_o02<{nWKNqhM>
zHM3t{?vy<`k}O_ZFS#SSywa7jLq|d<C^H#dc65avb0qoPr@|wNj#s)S(<Hjw(iL`0
zG`XcK?3ifV$_aA_^TR4tdBQoVE999YK@|tdwyo<PB%6KJ6-rK+GFBTP=>ow=lHJKs
z|KP8Mb?R{EI>kqHUmcY)u8?8EM6L>N=_jFe=dsyST`4IYuC!bm*w?02C-yZ%H6^73
z^2(E<47i_s;I3hpjjlg=G#lRVV8Vp1BT0j+*=UA*7EP<I0ea0wGjkEmhBFiPL=$iN
zh$dgttN?wj-`076*CXV+Xeu*WA?Sq*h*wB_M<TUAU$Z%$Y?&i~)?T5@gehIM0evcW
zRH4R%D<<7U=(jCJ5FVo0`sU>gQ@Sdze7K&}k>nU;Yxl&)C!Fj0h;EN<S$FW!6}D;z
zAYG=bQXnX@tk;7m2O<0WZU*7<Vin>{!0M{7X2SK$YBFb@E0SuCh%TE}bI*xt3%%n4
zt-^DdGf~YFsZeKvf^Ze$%xOz^{yb4_qqC`oiq}0?bjN6RSiM_wxIkWI^Nwm0ogF?X
z%2$&G{9J)FC5D;|R^iS>wLMP#?r_<`N)7KPT&eJga#Vq;asSo`^WYldi&f|~k(AB{
z(S611v|=!{+R9G=j%p*nr)eHFjr^x}5Y)7@BgvlGLho@~>^0D0jzr(kd9%to&+^()
zZFo~&J4^?w*hEpg9}M`VRq`OpAF=Df7yN4X>@QvxoA1=m4wJ@yW6TdoG2U0DP^;LI
zQJbHd5P3Ob^)g$cR-JiZwj2qY70i~O<hByjs{Gg$Lpsdbs#$vaxgxfRjE9I?{7^8h
z=09`lt8!&mN>3k&oHhfDGmWd>YSU3)E5;F8uf5IDB+B+fIVXz6RYyOK{40NU)2?oY
z-J`B7fB0xCwvb0>CoHy+If_MD9yst;Y&CPF3-hjOp8B3I=}YBgcqHiNWLIoglbr2H
zq#VpEp)1ll=54aLA+$u1#SEV%icRL^vqYJGs9@1ltvZ0kVv9Ks;zytn0gJ^(^AIc+
z8O;M!EQa6#Dniw&BcC9(;9~hK<^eDkTg)(DqS#^{0Hc{&HMuZHa9;E$CHG}4n9TS>
zPFu<W%F;b%kg~|Me(LqQgxOvd;>(e+)y(&{M*dCbZ86V$k)JTNtELMnip}E*Bo-UU
zR2B~sQdKA|r!B7!zN!$Ft6q}JX-W-%SmeU4kX(+0i^ED0@gtIIAhBR<Cle;j@2W6i
zq7*5vxF$=nZUC{o)?FE+Epi-)QEZWC@aA(xY(!M*4rj%w5Lv=BubM=bcx_2TWO?G<
z?lb`R%DBdj8n3Z-j@x2e!4G>R+N<!@9+4D*XRkfmGZE-W(35VYBj6&lQVaVhx*q_|
zUVFB)%JmUwfSmqb8|hg&{z(z@g1hv!g)Op+Sz8sd%RB#kDcz;79o|%V{z+)vx9qi*
zjaxrV(5krpBi+jnqQ%#wDL)`3I8Wa}D<{@gdWM5PR}}h;(ql<&BAyGKRPkfpPAhxv
z8>cF+%WG#g!SG?WRi!X`y!K^BL31U1<4CS%+tUH?y|$<W@Oy1gbK4Z+TRm5lU9>+t
zIWw;<Y;k5@S=ge?y!K}6A}n5GwJ0;Mjc#Z&uWfEoVqTfkV#K_!xRUiyVqUCiuJ%q_
zkG#nF+HmH^aBf@9(eqS4P0y;Na+urRZIV6Ajp>}pAm+B^3>ju_mvFAIVdl1bI|fP5
zyqe+19Eo(#+mc=a5{_sfIKR|sOLMN9Bhjo)lC9a4&Wqx?%?vq`9HLEWD&)*<TRDOO
z$X1T?&o+VcF8sM7b$8J_Jl%Pxe%ovb+`CUDzO8vNKQo&DL9%W~?Cgg5GPj-GBtn_n
zrgSDtxf0!HU4qOJNcZNqmoW{|U~ap**ZXUUYJJL+F+wBwdKsb3ZAdM18+;+POw+&W
zt)@PAbJwV+KDXW6E75Ll8PBWm3mK82!u%w(jzu}Q{oK%CjzoQ{%(ng9nL79gq&Ihv
zXKwEStI_{TD<{^T?OPvxZu_;VkUn?$#@85)S3A6#lkiVp>rMg4Cb7nCsT)JHZ?87l
zS$+~)zb`D?*ieL~$XQ2ld$G){uGA-=%T8?ylpl!{-*<B^JGEgW{Uo&RFsJET6++Ei
zGT7nM%w>~(#cfGx0^(dt@iP?$%`~B_^4DCpv)9U=8BW)tXK86aDH?q1drtPw4s7a&
z&n0tw<v**ho0(t6WM*eB+v3dNT(-sG+RSBRJb#I2E*s;pZRV0K4%cRy-&Nt-OiH;`
zm^P;^tMXE9<`RRXLadp~wl~C@Y0g)rbogAKzdDPDU(w(rXK^gMtf4kelesGN$GPmX
zPKxAnMH)e+$JpDKSu>YC)-Y@4vi%LSX0Fd;4Yg*v@^xh=n69*4bF(-CX>Pm^6)yzT
znj?^M@;-__b_9#>u+i*(`-^G4Ic!eT#VY&Zk?@Sf!)3FXUH3@THQ;bLc)7xxnd|j~
z!NVm-_MW$)j-~xK!(QxU%{*5m)c~StV-+gRk+2PdVn-s)#MvJas*~J!1X6#2aE9R<
z;`EWQ2hqZ#u^0XI5gek-PeO}yrs@~i=W=y5t%oN?3=r@OySlMMeiB-DrenHSITc5u
zW5NdeLWX#I-`mOs|7$UelUB~4oZ9W0WY3l4EH~&f(_FAd#_<{5-vZ^t;%b@8<+O1e
zG_2DZa#=Sl*q?;foill@8#eHf@XV$uYwih<7R}=W)<RzEc7q>ITWW!|FuS_JkeN}X
zs`HLiYw9_mYDJxQ#O&(!f`z7bwfB6b=%Ito7C&^**<6yh!q9J94Oz}dkbN!R6Panb
ztB)i*|9a*~ns!8}PUtg@tHG?9@&21WkX?VR8tjW#mT!YsGvl@HANtL0z4_u!Gr<}x
znj;ysFJd2o^xRY7bV-2*iRMV8B@NzbCRob@?wn?iG!DUYE)NmFoD1E6<6PFXv&D}g
zbev%|pyLb=DABRJyZU`fcswGSCz<8D9jMxpd6TmIJs{p(3GV{bn=9fKgL`vDT1J<D
zb0w(9fpJC5S4p4ePvlpk6!rW49#zzF-AEi!cHX~mDfHcB`39lpijptd(leAIb-vz?
znjPQpFI|z;CE{I?)?!Iq{K=LTCO}>h^LGLA3N(F*kXJ;X5+bieU1&MH<yQb-+fNkM
z*7+flUH>4XQ{jmj>Xfb%S`uomgx3W^%@uK7)1cH`*+7s#mrbr#CQSyH_;^cv5UJYW
z;ar)t&75+XT#b0yD;fxvzI5j#AH>)=KQ#hzuS7ivhSojUbP!$9$OnbSA!dEUwfz${
z_i6DPh#S;!kY5q^7!6L%mC>oKpQX7|TeDl;tF6hc-;cM|Qyrih4*V;k7xm31J+H5(
zymG03M9jD>s>VgZPb4>|>T_Qa=$JH}D*>h(B%CYD@j=455|%cknxE)(FRQxc^lObE
z`jox;Sl2i8u&RE&G;g0cD?cg9-@z8vsX~`OgH5bknC|vGywoA&T#+`HOUbzs>2JJ?
zq3`6IXdA0>C3QulxoBKmrHnc6`6|Y;{>~2^i)Q|~A*bfk>d-*A|2UG7ZOz$G2g7|H
z>SWNow&bs^BUgh^b45IO(!c2*Pu|nd467VAuS^}78pd=7riP-kSF3TF!}^KfxH38r
zybqtnM$(!qQV)XnA%;7^hIeJ`M5O)riMqeJ)K6Vzv`SNb-0qakxw_RW*>hD`YR3H$
z(WyLQwVDuf1=gk4RL88=1gB=|w<b6Zxl&srMl5BoJ~mQ758A82<x%Sh_z85>YOQ2b
zc2O%V%BWUfG+J*AO|bbHbI==7l;^|N5;x;@7loUj_11)&GT)j&GaLuknou)1bhQR*
zh7Mj0w#TjLq;8U5{Y@)QkGh-1-0nf+N04RL1f*v4w<aK+n}bs$qfl0mq6__w_p|L_
z^jwj&34Z6&A+y1}`N?dYH38|=<wa{Vn`~Z9Ksv+QCyAV{jCo2No#8$TM`zHahtnHO
z6N=7h-GWh9r)dosbqGL%?sG-p41Av}VjpM%+Zzbbnvm9!0PPl?au`5Mg3psOsapE6
zz2X41KuW)xpx3<q2H)$7^sxN>u1EtB^qSw_nxJ=fKVHZ?edud&Rgdhn`+;2-)M#C>
zJ4HWeU9dZS?CXNvj81=$@!tC6*TG$f4>agMM|7J-FKsmnb|JH(2U-_0JA|NJ`p*?G
zc=$e7gy*mI{7(L<Vd-+^h!~a*1szD9#RDMy<dta%g5+s?zYCJ5?fouDR>Z)O<Zt+T
z5JKendKg0GX;Y#Lm8VY$V)<N|`T#0BxS+xFxgxsIc|*o_A3FOx@dd3XEDu@wU8wB1
zfFsII5*W}rh&!CY{D@F)yS`6p_lD7hxFh^<A?~3U<f9^6Z2qu$u1NDCz#TpvbOG*g
zp2tQO$tzO_g2^R@p!LP-8`BCGqnietzBD=?5uj?{5_|fh5LYn(t#dXV-CKJXnhwR>
zwIMVe=|62lSUPOjk5@hD+S|vg`4!oy4S}hH1&)aMm8Z4kmzobqLvZTwfg@r%bsQKv
zybd1+28Y+-;Jh|;dL2gmAsBYpz!CAo*svc$Sip1$OilZ5B$K@&byINaP=GcBr<diV
zXJtRVriaj!#|TS@$V*4WPw*<Ht_^|d@bO?In2y)#yN2ckJp`sVh9E1C+#dFAZ5(8~
z4+296+3thD&^fkmZ^A<e?8t#OCWGPk7uxpaXD8e$P~f?e?6qSB+7RaU<$(xt9Y4^9
zAUAIU+5m5Rcxb}gu7ki3+&aRb4Z&@XZ)n0?hZ(fNbEJIn-u9rG?}q~n+8`GB%FwP8
zvV#oT;Dp?LS|FYE6-oEj9^7puWLE4e(VHZgcC0}gf@#GXwE1RBN4F^q?mh)fVXz|!
z+7t#ml%P#PFuQt+ax5ZFv?&NCnxIXAaQAUy3WIz1o;QWUjyz~HQP_b8N5Jo<GsZ0X
z)xP~@>LlEKG?+lIg9h5vVc2m4Z3=li3EA7sLvFX(KLx4XX8#nV_Tpy?QhWJ2rGqYE
z25kbU-Ok`CK<z$2Ojk_(4iFiT`4heF!q9YbTp+jp73krKyF?oNmd*rJDSOza5VhIB
zpF&gx4YYZ%vMmqPhtp>Co`LQrBGVC#6zIW1%C`Jq9Zelt(5Aq%*<m{cpUn$?0-w!i
zf(fbW%6R<ZHEFi_XFfUq%o%M{9~WpgCzfm>)V$#WEe~D4mM!!UWIAS`g&?!#Uizdg
z-{EG%J%pLfhI{ZWR(=RF+n|Z{@6dx5g3xBWK7^soc71@Mjy`BQ=N=htem@)Skw?~M
zlRX5ejxT5-Ky9DN9xdA%Q_~=9uZJ+UHJXf}T6fDEg)7T7AK<Ga4q6Cb9dyt_80(;e
z7TqJYb3cT!t<t<twiO@3S4APT(DAhuu@hPdavhn_La5tp?FXpaY!`%3H-i%%WV|1;
z>~RKNi3TjtZ8q&m2ysPn5kw-d;}2R0cpZVzLcpsKgcicxy1x+$cnLx{f;$)oA+!+k
zItrnMptpYh{}A?8`~O4GTXiakl`Zy^5b_d-@U#&4Ry+Sg$6v=LG-@VYk!E0NxZ(So
z5d1nop@mMi)h2()r|kHGw%%;Y*j_?b#}~9EWF^4h2y#(Y-v%r|w3<wHMERT7VP(S6
z>I;D-9Cc_yTY}L_Lc2!(m@8qbmT*+@32g~StFHvsZFc2~XiGll3a~HXZ1u5W>7-h1
z{V$zVGvMGsHd4a2w1lg*{dp8Wl#T>T5L&+j!0MV_?-;AApFRLA*AMq~zyd|9gNGX|
zlq*A{yvo%Fhb647YBIWF55r2Rtv*R`t8+y>SYBm^H?*aLY5hF^+(xC0=?v+&=YI)t
zZxBOUiMEPic&;R8x7gk%v(y!7Mg+ITj{haNEuZ6mfw#pcfTh!F(U<alEB5>^d6X$Q
z@T4rq>+p!S_=vR2e_R&L{1J<>f605SsD~qA5H|KVNL_5#Zy|NDZNFdn>r2q4$2RV_
zP+GwdZI^6GkwCgkL*SO5xY)Aa0%}J?v@M`^JVe_7b;d*JS^0h{Afj!ZbsZ7Wwp`A|
zHvwCSUd+U5J0ZRJ1h56^j*Mt96n`S00Jb1pISNw75ZM<t`0O}`wuR5dru-H@-#gm}
z5ncCv!4^Cd0?~E?bn$J$7C@Kgqr?_O7he}_A$0MXU<;ugD$zCwombfpBHk753--`&
z<@<s?7_fOETacZ1>G>pKwnHY`7WNif{9EAbaEG>m+6-=Z5Ya2&8Ej!~;SjI|w8e*j
zEuby0oE3VCbO~u+Ul?pbt)nE`Wi?*`l)Scuv@iC-7S1|KqHV#f!X(<3FPZ{APs;9S
z9XfF&+0EAnkF7)QD=)(-Pf9n<mhP|4unvFdFIfBP&Y-`7S_eS%S5W%~^VBmV>6PSE
z9SPkEnsjMemtYpI&6BeH2^>k$Uz$=bU-HXwq`z_{D~{s1GKMz!NWPWtuy)S84zB30
z4!Ez59#4OT*bb)Xua2*8cNe?*q;ta&(J6Dl`YY&tbsx}QLGO*5=r6GQHg{8~`?hbA
zguAcK7yT9PzRf)l_P)(sPv}*qrIheuHk!Pa)g2HzzZ@|7D|BX7pOoeAU#(uJ<F|US
z@;5u?qLT>uCo*5Czk+oIUL48Dwgw`|c2LC;(RCjd`YX(Sbu-XkVYY%V`U_&euP0N8
z{W_;#e+AnP!sxGH`+eOBp|(Ra`n&(xgk{``O1t2QP@it<Bar$8_DxhqhheoHmeF7C
zCim7^qTem+C*X*1+Gh;gK^L94u1(BEFZs9TsuVh=8-q>?@$F!W4vlK>@IwoIi)6v{
zq)=^#TXYyydxyK4zy97jJ9Lm?Zyg<;4t#6}W^^*EZ^vcyOuv35gZAP(Qr@21l;*}5
zb#Kr?+`Wgt(&-(xf4{iBx9<!(agKX;cO((@NZ1izOdSdP7KEuI$&1b-X?#n)8O*Ql
z3p$p|k!Tu5PH+=Rq+=*;#aMJAOSfYz`lUwgUH#a}5WLI_H^N7xF9j2xt@H8X@hx-~
zk8h#0czo+Bl?mS|uke%5$~k-8g~gmHmZBHDynDY^yz@POt#|XH>kQB_<M$1x=otEY
zIZIIg9R&80t=~B*>?KpbbDY>_^L6qH?IoMNS3Hh;8DjJJvQ5f6g2uP>oSeWTp|c!=
zp1tJ7@0^u>lG{3ec}+rq+6#-m!+zT2B|Yy0?5FJjiw^l|JHnzT|7owV(#i<6D4!11
zX)BzfLv-2>spyyHv>i{;VL2U%6p<Bco88xIzb)2&?Tl!6jGZA3>FspiF^)%c`|o92
zJN+M4lPI~@u&Tj;y0>Ev{d;xk8h1q9BOHt<t@n<1VXtn@(4zM0R-OCHcF09fR@7e2
zgPgn@O^PRjw5Pt4-(j!nZ^iAMEb>l%i0x2`j*n&&D$%J+blU35LbL4b4#{b+;^*c|
zy;t#bmwv~>gY%y?3BcMi9z%G#l2@NOop&v$Be)BGrAgk~%d~lM!#>)sC*E7REmms!
z3ZE;|S3oTVJoI!;ZdVNNxG#5j<-$!m68JSoRP$SUZgL}cEIk)I3VGy@<j$H3hd)=8
z1F(hN+HFa5nrk~kPfe3<yR>+3c>>&*gx4=$Xsb$iCmYZ<XRgB^+Bd?XLmk?VaCkay
z^X(9aj$eJp@Vo*<F+6;L$aJ~;pgXa{ss|IBU7Jj5_s{{V=+->*$h}=dykGXwHr=kn
zEZR3rqH{s9!v=C*V(hT{tivhVj+5wIer!iYbPDcm$3^tE=x(ERkIUQqxg)x(QBe{{
zFm6*?z&8g;bgqJSRG$GFAQ!fZVH|C<=X%~J?I>0a#t}>LTuHus#o9r=DAo@0x#)QB
z?`^R{JJ#)1oJ5C2bObz=9A4XH$vgLI+o2LY^M38T0eX<!{yH|IQ&n<LnY|RA+^$C6
zsZP0})IGgtLs~#SM@n=kMB9-PM{-}=xvZBec3V}+d(w=y*>#<3&`qF3hhenmvTA^E
zF8NS81fxBdbvH(6tfsu@HbbxXPXFSYDzI(J^zE67?g+kbWe08eat*!b)Kr0N)0QuJ
z@%GeCahXMX+VX{2wCAwm!Kq>ntImJib67RdM!E8y<fCnxUFX{VNbn7CwSOeiJ#&cN
zs)GU9q$YRahI99%C_7_Y7`o6lTdpTt=m^+O;0hhd?cj4o`Af-OCI!%Taq=91ZR5V_
zOSKvj!0uVC=%U-Ko`=o+R%uE9&~|<DBgp}!Svr8fDdzl<+|kHY-l4y2l`rp5WVQ%$
zzu`d*+S4eS%%E*jTZb34r<~*+>d#L?>lzJXyC<OEu-QzK(e3Kw9Y)cSuvcWV(tMCq
zx7(6h4rF7~x(j;P%7#(2lN0i!<c@CG%1%Df9yYQe3+=IJ-GyK#TvwW*BhoVxqmD!m
z8MmcggPAUAek9q~Zz)qTe2-~OfaZ_|JrXj94d?-64rkQtFow3Pn)d;24x7->i1x4<
zeOW|%*oYoegOn8wg=mjq<v^=Top%UC+bp`C6rw$xBd9|d+M`=n<fvprGu7M0&^zgf
zH<Y^5zVDaqW9W^0*g&RY{Z^^-4hv`xxxYJA@1G+Y2ySPadk=7q=9vRHN3&{x^DB1V
zdGEJrbN#n2_OOx7y4eFGo0YYPeBMWL2Pl{K5lp_q>Ysq*un|20$)VLfPao{o?h^<c
zuR8(+Qlz}Y$lYeZb=W?8z=D5zl704g-4Ot=%ctF;`s}_vejw0A%KIc*X`2$)*@kzQ
z=?$@Y_ibIjvtM7<!`ZK|Z;TxN%#Z66uydvI4xwk8*48f?o%Zd?a|L(0yPej6+L6#X
zu+4?ZJB0In32c25gT1>w))Q>&)13p`y4}??v8~%-J##yFw(6Jn3EG*ub|g8XN$ale
zZfEtS2%WZUTx^Q%n&%xl(C&6rlPqX=o7*G{+TGVv9qP~SHn=gTjzkXv|GM4Qm}Nf+
zt@E<Gym=>3VvC2?35ng^COHuoyW3w)SjMxvt@LCO?QSC-64Aaz&^!F0Z6aHTJ+!Zp
z_aMpf*-Vf8hO}~AbnWzx0liIY>j9NzcU$BXqBxQqVdQzymC=tNyJ~woK+OI*r~}CC
z_D=@~#x9%ucOKc@_BiL2?c(S?nqE^I<nV-!M5;l}Znt!@gm$xq4oT=aA~fR(brJPW
zBBBi`u0s#n%~twl2<_%{L7lVSZZ^`dT3O>99=8c{odf1>nB!Ds*=>Cf$o<Mi(>r{h
zD`ED5%w|t@=&0F(2VcZ&c2q<D+0Bk>xIf#hxDNMcH`CfX2ld@-ujg5QH=FB}!PyNz
zHHC7vYp6dx<MOsBc0KOdl3M5;qRuuauH((vO<wABcl>_6?rwm6E_B}Un{4ylIy{~u
z(Sr$yJfeK^dhfq818{hDvx|DYyaYDOuRmwE??k>hGd5Y=IE8kzhdKj6ce4pjT8=HQ
z+iz2+64Z8S^CQWZMXfuD_EO_G+s$5TWg^)sTHZ6lcAIt9GYt1gXyu&QO-+5P-QI6}
z;9RqtdiC3qR&cJ_0*8h3lhDcyrrO|6hvcrdw{cqT>eWb~^LF|2PAv4Z#T4sn-hbCO
z0Jv&f8At7rsAphYbq=47zjxO~>-Nm6j|4os$|sEvc~{%li-P96+Q5dEv#X8l%gouX
zaNgnNY;(*y9GqRJws$BvyV{~o0?rXg5hp;`Mek5>HWafbMUmf<s>PseQ7>?@%Ah8;
zf4dI)({FLSZ6;Z#eBQ41N-vPG+A9qwXII<Po7%0r%A!t^&UPvE&i%)RY}UCTIc-#P
zi*h8|i@9n!B6RQb6`R~#)ofKv@6dC0waK0Aoac)4k;!+YxG)}D*jy>?>czbiEvuu{
zJE^;lNUDI#ijmD-)pm*WzFW4K5^lA3wPPFZ&8~KAQ-yL@JGQA*xhsC{r04AFs;eD(
z&K5nbL(bXNu5GwEyS`T48BaRUo)k?!q{rldyiY)$*~M0Na%Z+_XnjL?+QlAkm@~V`
z?7sJ*+ttlGH>SJTrsh`lNaXP5?)8ZDT#&8E<GpjK9)ZRUvQgmtNl}i$#`#WcD|UL5
z({C4<;-vlCE`k2^drQ49+pH(&Wvh~Thw-wD?PmxtKMAcnvBmcC;68pAxwr?H_S;0T
z!Oi|IvY^LJz<ApDRt9Bte<J=lXHg#RBgsjW$vs|>u4w6wHzT2T=~j#{v~*h8`{t)+
zD^h8K+$~K$UZ|eiyshyz6jps90j^Yc0Dvpi9RTEt{nP`x$yROhE6IMzE*|d><Vvw(
zK&})ihWWBfv1(wi6syMn>3ZcOIWXItuK~B^+2z%fac-8^555OL7c?KRdbY`3<DIvK
z<vrjE?RUHXK;gTk1tfg8wE%>$xSo+!yHDF%a<6!|dk+}C+tbEj?_E|+>AGzS*SM6I
z)1F-)xo_T^X7PaTvfpLZfa7Z~^?>ZM-(}s2j<3$r1Fp+{!<rX^45f1(^nJUu`Cxq8
ze6MlmWWUpo0s3B<!OwspcSM7aWRGPB514ja+^zww<(1od6zISEmEU@Z*z(G4eI)nS
zf919w<OJGpTGXTD=V1~Lkzd{+z3G%W0x2$ceBD|(0lJL&Ghi-m6T^lWDsOYwK(SXY
z>+xI3`)&S)Q0x`e`-t+zZ0a14<)Y*xcZY4())24dt=<AfY<a77^_<*lO@P*0rKvNu
zpzL!+Ii$)5ayZ4B$8BkFoaWwQ9bDpXv$=){EGkicB{}_G(8*wV-#_2U*Xxy;I>_$x
z6Wvz)v-Wnc(yCl8Pd?x~FY~TOA=>eXq&30pNTm0I*%7cUl4E}H)Ldz6FR@JqRGB4e
z)_^H<1k!vK_1ep7(?iDYAQsFrHETd|Sv%aXO*dpdkNVOTna@XZcZRj)p+2JQ3m)om
zjgz%yPM`L?6DNCmV9_k)C`?iIR}SidX|(pV@@qY<J*+xkiIpbKd9`52tUau~FiwLs
z<d|i`)~MN%;;J99Yebb17=hF5ypsGx%dU0zwb3=FuO0+rEEBN?6(Wv=O@<N@N0QI&
z_iy!+az96;&UW6xX3YtZ%T%p_&A)cF;ybcu?P|rHAHSk_@Y7c-AH0Osx(B~}RaDKO
zX2;sa$|uXF_(78{V+@ab7W=hH*z#OS_U3i}g8sbpFX)Xd-vQNS?N^Vz`3KgPmwG^T
zS!=s<30Z4x&rHJFa@F#YbyuD%VsGK7dn8hx3vaD0<+(DCK-%x(UCY&<2Ju<Twao{`
zWR@9WN0L1>+(LOd673J|4*5vvAbx`*p@aApjwCxsnw};8)^kPo<y&z-a6T=+^`P9(
zTJl>DN&>Alt@YsB%ACLtf}C)jn~x+rKW{5BVXa{`HAgb6h3KK>qUHnE%vxU2L_n@(
zn;BBfG7D>D2A*fF?!GkoBA@iYNA;7?x_z+`jf-n71yl^&U~4t2=}c>L=Q^|6tT>-4
zrDStnw}$zENwdt@8Zc?rk~t2MW-Z&}$)j1TirqG#&McQcA5dqOX<P&M;#xMYvj*6e
z_(5@->N+53lGc%Ae~TX*^!N1$NLsm;%<q;MxNLpniCxQZjkk6!+uscsTu!L@-~Rcp
z&v|Lz-&cPhi#mSa{ejjStGC}-=->a#KmYTe^3VJGFaQ7F|KnL&8~NP-_=i;KYr5b!
zWiOWVQWX3=%YNL_nW9zo+n14RV=4NgMExh65545li!Z0|d#eRFZP6{h`DQ82d}5_4
zShVwiO5%oa=wBtF&!5^Efz>dLk`;3BT<4LEgGT1xyjpJdw@Zcp62djbXV0#*6l4@}
zP+TbV0~d2!imR=P`hYo)sgOM5`Y$ZvyJhV7m^7w!=rZ!<I#Zr|3h8Xuru)1+HW_`g
z32&nfV?ti)d~^EvEr<SlV|x32eg6K4x9nN|pDzwMmjCs|$v5E7i<1NV`{Lv-@~<yW
zz8U|w7l&u)#c`n~UYwiLxDeML!|AZUw<aI=y*SG6ulMGw`0~9Zf0M3evTg?e^P((e
zH1JzezBDU(Q8K*l`CgQ1%D>)}uK<%?manQNugZE~`|cB7rZ3caS3W0|-WJ!-=54u5
ze0h?p!VtgHpI(;_KY3lue8{)uca;0RF29$g%(KD#{usTKnE!uo3n?g<^KmZ_*v!-g
z{+gV+$`7#2OXc@pqNTDcFQ?(oUHd1{?Km6z3SW+|`>QPTR#*C7Rw$JOnK_qPtK|1w
zVx<1FI1erpQh&g;oT(dNTTavs?k(|CLB_?c*K;M=&B%YgJ)C|xJ=A)K5xtzB8`AW1
zB&bXm_7cbSGOw2jt|Yo&m)}Yr{AGIUI!2?JtrS*Rrm<pmEVEeQp)XTXp{ZX%n#DIy
z?TY?=BlXMhAl>b{1XZ%(F7s0t6Sb80G53RIaw=Bdat?1^<YlsIa{X60YKw4yb*ZY9
zQ&=XdlHGTSr^*hnOjKR>v>7%xuwa)dsf**M8L0$IEHg=|PO(fT-S2Z-`FToPEa&7V
zIAe)vx?g?=nGl>6Ryg8{1I04Wl-dU?bgR8NV>%yqo=KKjrx~2`TuG|sfN9bx)jk%S
zQ;LBsvrcz5Qs1-FVY<X6-8rMnTvASU%dAie7c7%PRV-zh6iOh^n(;j(JCXO)yWc<Q
zPrh^uzR3SL*Zw)P&epg&L7Gs?xp$dRnkVCBI_d6-8Vfq<=JaSXDW~ftE-7d44?0f~
zgkN*$65xNsRsyb;d8C_T<kZ0c|H3knG+hwSm88}@XqrWe6Jwc0ilgHQ7%0cgOy&5b
zBzrCo-HlsYQ-%d7w<ee0gubn*`)}16S~q<orHGajIPR5ipp1jP_;GRFrCaE>Ik!<p
zY2A#BH{x%ZQ%a$xWl|}%oYqv*md$bUOS@R!mp)Zmw?lHz9YMa4vbPFew>51qzuase
zQSM0vBwtR>Sl;|f?il3--X{OXulwqhTPToqMA8esIU{4qc+cg0j7PBfQp-!Ug0pg&
znp*H@F6CML*|fKzegbJGot78I%o>~K?b(n!z7STsl!fsKPRGnSEibsHjAlm!vW;cU
z32kdEYX;he_J<=m4-OgGM{wVm5z@^G)MVA48Gl=vqrv#XdWXg*cl{A%f2SV;@R513
zT%Y_hpS0k%U&9F&3cmd%yXpwiVAiTGTn8M<pnYCH(@D!qnBf}3eZ$8(hIJ?4nP6I|
ziLi!NcF9YQAFRSCE!=~w(XHyj-00S`7*V$#fG^WC<`_3GQ}frrJ||lIofCd78M5cp
zkn=BZTq$H2TF^twO*ybk4lQIQSOYhEp)TVxIrKlBMQ+zH_m4=b6YoZ`W?ZVHpcuS!
zKE~&WayUi0!Mstd`?PeCUGh%wN~A?DRwrI8WRh5>kd`b_u*@JWR47<Zs#vH{@GLV(
zkLdQU%WN*(f-Z4NOX;_vz5<ASee(n&cF|%AH?7N@(!y=*>dTrF6bTo2QgUCqzN8sk
z?918#M&<=rG%fW=jy>ALdh?2EnU-39=hh`kYT-hAIjLeHFUn7neM$^8+q95>WjR^m
z??^*0<+dx-t6id-K39}ooqXUtbhz7~U?1)`IN0TxFGWDuhc$zSW}ud24y-;roW)Bp
zXx-N{Yg<2v@&&+qU#O0-oI$aa3zC<4S|Ca+=RiD?ds<rJo|c*rXjW-~Z?Q}(J(BE*
z{P3l6yz4$u7fLCwUiIK|8+40QMa$IELb2x6t2N7e(B+0N5K)%drUm-S61B8IaXA9%
zN=IwAqpwt8(diOP{h^>pq@@Ca-HW(#up=j8sp%G7W{4JeLCX};0&i$FFX{@!we9D2
zHb2}9g?in~9MM9(g4MPs0gN+Aw4C9!Z%sq7T986d`>x-%{Lplww&iC6c}|%46xdzM
z2^0Sh4xXEbY_<5~J4~;M0applRx{#~@@zG)+X@ig42lJg+iKHlaI-d-t}3wQuISZ=
z?wGu`N!_+?j>ST5x8)p*M{<6{CV;MY(_BrB`-(KfY6a|?7F&C7g8<J$5rHFOSdHt#
zW(>U*1XlC<YhYVzex|0&uGR*)H63|N1KXSpu_Qn92>3l4f$~d<4v!??8n3~YEj={P
zvq!>9l3!gnBKSd&J@L|lk-8cXnv~VmysjEJ)^zlJjwt7`cvir%_Ih5xF{Ldmt=|UA
zrs;C9u^#yuR(q`&6l<@i1Qc@u!;-(`%3G!!ArM7k!qdLLpc508>j7TQN_g7$7pw-^
ze8G;>Q@*M4djn64ZGgH0%P9$u<aVEogoSr_<vaTzy1lQ$*OuT`4X+Jwt6r}Sa8oA2
z=ZbQGVcmdR4Rl|4tA<=S;YU*SfqX@)F9_HomXjG4_K{VmN1f>AWQK(duFtB*=f+K9
zoz}kT@9=Xr{WaX)y>nI9d@by+NAx}BBC@=~rE~79_B>}Y+r{R3=Bk5y)z=yw<f}Rm
zAIW`nowe{t?yFll6hEcsH@?f1{PjDn{N;5fE;ps`ABTAd@@kWdt#shaX$p@dJEqm%
z+ikEtfZeOgXH~jRb+yvW7f$@NLhQ+r=!yBhdF^9Gtoq?9*_K!Jxi>TYFJ~q!B>F!R
zRv`g5D+?dpi3i}S&$@lw7F!h-(sClhf)TZ<S9|9qw#xQH0JOs5?iaj@QM3bI#YfxD
z8Sa*$dXU^Vy?E_neXhdVCFA!h23ykmFQ_edgrHaP(Ka)TuM*bHDXz%%RXTW9SgD=e
zVU@6|dx|SQ$#zb0C9H>2T=7!nJh6&P1{6*mSH#>wm?^qRC?x)0#VeD{|3^Yjjw8B@
zwQ$0{k$0>3fXgvy6|Kv`*{;ZMRR$R_R`F8h@U@B$xOqNXMeMS|8E%nAuyDP(lC$+7
z%0YJN1|f^r>TNZv1tCkbS{R_KeD_;;Ig1Esg~RVEO?m*$QvKwF%~EaI4{)<oKN#37
z@^>9c4xm~Uuvt`wtc-qJ8V~2cqE^1Cc6SXxv)J7=aO|&Qe^&;su2QU(qhHY>8Q;Vz
zUiJ7dev*e~z80@FL#8Qqcu^f-mDhS^wwQaeX|M8H3ou$<TKAWDeT2@y;_vE_3LNYG
zOlO=x>-BMXTs(Yz^ria8dYAjfaqnH)@dtSL8k`4s_%2%a!q0Xz;n>T!xFx-3&lO2?
zvTB@Ju;7Ec5+((>yjcWK>rQhf5quDhE07wX(g_5QBu8UAdV+e&{r6l^-s1X%JM#nd
zgPi>9^;wpT{67h;(~a*WJ3+Zu#`P?8qkkHh)b5UP)FXS~lcJhWmR_*(W(+Jii`Q!l
zoGb<Fl?6Uogv;py%WStLt(*m4ABZRD`T9US!N#{5v~h|r=lm<_Heat{8pryPuz%xu
zU!(whQj{GwR8x*=DFI-a<2KZL(DJo=ddlVb+D@Mw8J!{UNOJiYsAnD;ogMH9ZV=>B
zcEB=$*w>~yOq2CusdG)ToEWg&dzAH>=u)_9S<VVrD4iAChwB;HV&W2mWBXt|;Z6i;
z0gvF<#n?uBE}3H6O6MLbwk>t4zec77d=RzU72y8nL5Xd!=XNW$kJedtHYKk<bN8Fr
zHq|L{7S0}6ZXL8M(2(*(8XNeZiQBQmhlISji!D?AR(uN*{uN5Xoi-Z?b>ohNFJ!bu
zY=e3fwAyPO1--hAI+DwA*tWN$<RS{?1^iDm4=zt*8^NiJ{D(ty3k5_b349Ptz9co3
z{tLpRF^vZ8XgQ6|W_>h9WXz7nh?+;#7?Dw&E9y|%z^6pNE%pE|xPKB_IT~B&q-Z)4
zY0aJOiETvBirBFY=+Svey+=@NF?OYuV=3NAxy}z~A1qw=hie5N9!G53=#T}%xd%&3
ztsZ^gQfQoNuw?zpE67)x8kezcq(`utTtoPXvhPOh2v*Ze>u`U3R~7m0$I@L@hyb)~
z)Wg*XXCEx&_dgO1FwylVp>;=-F^k!;1j=w$!6O;B&29m4C7fHZz-<ZT7JN$9s}H9Q
zEbwAt*&c@&6V4l0V8+A}$-FGC0YjMt3w*<HCcy$HF`P@VkX-Ia*okiHxmcf7PYSzG
zroaLL<_PrMnnS=`U-|mRvJ-5zC!370G1oS{p}+(g01JedaJs)jF8)Yz%Y!I;=4DHI
z{#drPSI@3BYwFBy^2eVe$jNP<g3jdHFSa@(^8M60549z(q=`XBz{1>|wjO$?FP5&O
zF5@Lg^j9Da$0|N(z$^|`?=35m;YJ4lujNZ5-k^^KS5~N7g=Tij_H(|4vAjZgQNz`M
z3ommllST?$mT(Q<0-5DX=w9Mbcr~%of@-}_if(^m^MTVB*Xk`)13!{{@u(OcuG3pK
z@E_)79?^ZH!&k(Y5Fg=13JoSgtsIPNaTG`}p*p?=5=?}zhm!>pVTU#QW`xP&1>Q@9
zS1kqI!)1F5!2{u{z2$}%ge&%zO&<6NlW&Pq2p8-v&_%;Fdkbl4Llt{VB2Z+#-UrED
z39i>$K(Zs@tp)AE#d-^ncqCef`v+;^wGMqILN+<<nF!nD&}Sl8?VICbxY}<?{!E0|
z{|3`s0l1JnKV1K}q}dQ5_Ibgy2v`3tm>)s$-?HcZTaN_O%=0P=zzNs$EwE_91$_&V
zJV8C*k}R5VHQxe_Ccc8c1tQHAF)QGl%lQ_VG!edyzE<36PrYP-U9gdmUjMYEJO4HJ
zkc^KCYWkjL_RIA?3Z`zTqHnpTa7<gxSj*u;y#<RprmmQu0%s;%skcIzi7Co$vSz|n
zdMm7%aGBovQV}DjZ0nk5hM2l#t{gpLE<G1Wo68R_Ne0$&{RnahI!RX;FJXpPh4BK1
z_-&Vl4uxE~-NQ9@EBW7JYT;Ine&GtcN0MqMt(>(XBdn73K3rqBz5tpjTt{-JO^dcd
zX8B2Ir5WIAyY(Hnr6=aOE=&Qg@K(YEs|s)BNOB<^NzQWfw<a^z+>yzQHBSMkHqEN6
zR3?Z^#j5WQ(x%p0eStJp#jSWK!bNe9BoWPJaVyl8Fkh=CwIyct#Di*6_rF!tmQZEf
z3b*A5r0bs1OwX!tTf+3L3b!TFZ}A|?pRicfW>l}oxf#|g-C!duttUk}s$8ix1Ex>2
z@f(4TE}2^k@aTfMN0RX9in*0o?GTZxUfxU$E#?YuCMcF$q0PkDIxkjuGcmSR1CV1|
zbpoXMUKPh*kaF%x(S1Frv0L#do;HId4E{)@DV-c)cGpwMVjn}t;(F_(glq8D!V%CV
zcq{c*Vg#y5Srevn)pWeZ@Q#3QHpa9b@Y2P0D<0h^#<VH`6B1Z0{r;^Hf|i4`bcI<H
z!-cpi)S4K>igWQEi4=DRG_1GtD_yJn`3b<wq4V~UWY@aCG;fQ&2C7WBCT}f*!_n1W
zu+QapYw~AecsqeV6GKPm%EdyArek{L_8~^IF3?Z)c<a5v2y?_L$u52pTDkLmVIF1O
zmZpdko=Id!l5<`8X*lsEi|j#^!>j5<BB)tpm3yCXL`&svC`2NAt|&)WteeB5BdF@V
zU<%X7D!iKzi>!)v6Q+?JQU1s}1=I@8awU?I`y$K8uUv^eVQyLFUM<WmJCfUDSM04f
zc}ti_R$<jd^2i=U_bn8WtirPilgTPXn?OsR98Dvus)ZKjkyQ$&g?VI^s%p{YOt0K&
zhInMPw%ZWwz|D!Ad-CXnNo4hA+6i;WDgk6+4%v~U_sz9=D>uAhrdZ_~ILs8QcXYN1
zD&X7a*R%9~$7P9CI5%NdSWV7Nm=spw+=Mw{RW<v<q_CQ)@WZ6A%H4SMK`W=!MnVOu
zT~_x<ax69!YTTBz=GiAMNvuMw36sQXB}GP<6jmYAMAyN(Ug|=a5>_EMgtHA+2oT|H
zgSGD4Qm24dQ^G1q@sET}wt}x_gjJQ53{%2t)}9QfAFR};3~|IN6p%1StU?nxlI$By
zk}yTAUam<vL1Ar*;}ZBo%L&uQo(c^o%oD4m(+~5+D(UpYJh3CWoiR`BsjzYap4e%R
z+fwHMMzh3@<W9F)VzrU}CYtSX_&Z<tToQPqd6h%p`Pc8<SFSnIszTri=OwHVcmfJq
zZT<eu5`-cZs@Pi_$#25^vkHMHOh2on<_qU7tfcP?=Pj(6!T-4;mNFG|!zl+V6tHky
zWo`4e^bOFmIlQ~V&<Uj+tnhK78OoE86Xusy2szPwZ&qRCMDr;CLQXhYVI?7dC|O};
zC`SM{uacranm&-@@g~sLZE19%p^_9<cs3y()e(VW&8U4}wJ^u5@-~JG?pEH|xb=2x
zCl6aRxwwxgXU&V8Oq^lfStVO%xU_D~1@(jr>sAteM$2aaaZUHul|>n<t6N#M@s-uB
zmsb<6saq+!9W8YNW~QJWNlxnPUbJ+Sgc)R&{V!Yrx032UQ~>t~#%*c_I6LN6_8_|R
zShuHu^P_oYwR3)~Ud~Ca2{J1@DY<Ws@);h%eRG`CutK&8=QOM!N2vDg?=9{5SZPjp
z3MDM8AXqqIVa@9B0fnq~YP>`hF{NfU-*9rmO2*%)(=!K@)hRt7S)IClt0Wf=>fhEL
z_iriT*y&=p6^IXKDy&`SPS?V%ka5Bsvzla_a3S0Z87JyMFTT|3BA69+PB?jC?SQ01
zkuN(ZTokur8HGt`PsM&ZBK0LdpcMrGid}XD+4=6LW*yVG1haY>H=(k(6~awaFJjEg
zpX9dkwCB>cb>PR2s!OR#%KR|DtY*smFukmjGCwZ6tPT*a`j)Da>N_0BUJ3Y!YBTy8
z^HIHGISxe4f7L;+$_ZZcd=b_5F-MRvk*vaiiDF}z5SZtP^1Zu3GGX3W<xmwaWm}1?
ziQ)x2IHP4D+Z-aNw6bZPzL{HAIlM*DVub<|E@68lm+l-cV_RXxL|N86{{)xU0d$#I
zR>_qgHx<)^BqQRzev=pzC9DSMa+%u-S0*^!Jt?aBEvW*zT;{ft{XSIX_6RZ@UXJtU
zh;m4*>5)%hO%o0lu5Vij84H)Ut%@s);zSSxpM|R1)+EnF@sh@&5m3`A9*_9y+E&~m
z;lj2RMoqY`ZN1)=a8cWe|0Tptd#)(o79Y;%ds`#_=J%01yy83xGtcVvFFjYHY#1P-
ztJ_xmR6%ju3gIS-P4r8;2{}kokbU(z8`e#@ifx5;6UAq3ST~V1Y@aK*?}4p!I5$yr
z)P{BwW};PSH{tTNbrL%grC2xUS_(q~TTMN?$sO(pe2%8vNhH&(CdVd<&&P0V!nCpq
z$0o|F-hz=LmOWRL@929!Fm4(WHW2tVVV+r?oCLpAB~#amE?`>;?v2-b2ob?Q$!#U~
zGR#D)8BiQqNb^B*2V-_x#kGATEaeFVnp$=w_l<kQ#u4lo6UnOBF|T4Ys@O4?T2{r3
zaedl4VWY;YwN6I;c(v9m&i*jBtddYaUZ1RI{=0V3$*J&Grai43j2HR@5MM2HqSeFH
zv^oLA*XL|v-ou2oN>qHjUh3k;m~M6?Y1X{D+^WHm@9q9tp@&}1WXKP5&Z;uxhe&5N
zOI3v_XO(JJN0J`^Lf>Z9An5B-)s<_iFb}OJhvxMeTof8rr>$bpywyj|0A^o&Y2wtp
zUf*zPOjD~O(3q1}RbcFjnBsn0`OHq|eY(Ckh+(qXX=hJe0Pl#hukZIrx~da*4L}#V
z*=gUd%G>@_QD$6*wo=F~US&_KaA@YX6Acc{H0SL1pn028oWMKbn^o?8r_0b*ZieU9
zSv!c?pWCPH<kd`b(kdzRr#WerTq4t@YHMa2IRd$0Nl0=;>^9^qnOi6BST{?J9=hng
zH;KG;f3E1ux1{7YdTOHV6ydDq4gcJBwMU}tPm&!=ke%DxMkK}_i8Pao$5|EYCF9KP
zqCXWj&fMNLNW?$4@90RqKb;TfNb)CPt9WYW=sE%(Lmsaq(PIid9<;Kz#`{I)>!}Qi
z^)f-G^CwoSLeA}tgvya~ck3<u%-?|=a?W&~#hQ$hxxJ69%FnEAge+;3EZt|SGLzce
zzT6|(+T1?auf`B<DL}HByV^>Fh%-r=Sd)%(n(AGrGu{K><IJs7`69E#+;*PB$2pSx
z$hd#AWY*v}w9}0oHAezzp<c4m+&;LI=znf+6KgQLYzk{KwZ4N}^YR|&_NI`j{jNj<
zOlX}>saWCZ9ErZg>2f+3VohewbmGGbGv`P&2??!p;VjFf{3N4#kTkwi^^w6>q$ja;
zI(uTJ{O*zHqHg5}q&Km3F3#;R=B86AR=7S>sTAwN-8z?-c+!35@?{!RHkWVCnAYk1
zi4|tfGnWtD&=02*B33Ah)A<l96viW=hdU3W_d(gkeBDl4`MwGhp8s6wot<T5`J8$^
zQ<V9@e1mr1`?-97Mmo{CbP$KjGo51bsgQZ*&9PV^@=PaLtjXk=%eQIJcIL7ZZiA!K
zDHSX0e>$yVWs8_Mt70X){&ZHwBgxUYfIz*;T&D}+R;qJPXm1r_?lkSKLf$<RUiPHz
zJXgdTN#4$MvD_obx03bEZaiHJx9)jcS^coG>Ca_EC;9%Q>}@6U{`_(af;MxhXje@<
zIs&}{0AhIU0&CML$|~45oujO7E+VJ1lvN%g&A_J8lpVo+W1Xk0lBRfuV@xWUjHhet
z)+F;xrz)#ds-G&KTQMW1%I7{;lq2whCtdS&wzBrVx0Ri5FOcYbW$lHWJC(7lkwbdA
zqVADocZ1gL>iksX>llvBZdh^CY0Dbip6Rq@4a;vTZ&|yh;dJ7%r@`%+H+5OVj-1Y2
z)<}0VoxiM+cYC@rZ+o*e<8(^1M)<{aPP3K<^iR_Ltw!I3*zKC(GrFkE4F=G3Ub6-Z
zXx_wT4Z6>a=FTNxI+NKET+iBcF0)1|^yy?~4NlN><=sYxn|afjwf8*oPaea;Sg`LK
zx&NornYEkKeY)yyBM<y^KC`EhE^s=dS%d#Gozkpv@SDzQ)_w=W>6~UQ4~}Pa0_Mi)
zaw@G^gYYw5F1ID&XF7{ngYYxM;USHns_8^#Ed#HnGnqAFv!*hcH4eyAsmz`$x<ewF
zS>v2Noz1Mh`L7xt;OJ_(?cD<V^?ilyYyJ5e@UP{x*}k=G8+4yXK%Jtp|6+B6?jx*j
zm+kW*b%X7bNc|uY{G+;*KQP^j&~;je(ADd<Ky&<Hx)njAmt9F{9Dlwv0djRt*f`ud
zfnj%d07JoYgQYW_>9`faqpRGuOy&RKaw|edaJiLkyw@}cAUmxz;El_zBshBM7C~Rr
zGl!v^Rat~<Rab_s%xp4koDZF(xRI=eT(#Hxd4N!T;L_uW)D0nF@k|Q~<s)xJSm=eC
zWn-RcGWn6@#OmL3Qk~ZnHqKNA<3@3snJJ8OaO*au6_8smtz6b#k412{-K(w5Z@XLD
zh|Ib!!n5_~K?@knuGKeTlWtWZoU{89BR<U{Z}l}IvqtM{K;}@<Dln&Tk0Z#9D5O~+
zCog)d0=dvZwN;^<F2Y((m<#I`icLMYGKA^pR)KVS$XiDFPqW64AUikQUCwl3jUPdF
z&cWHO3g$>^TodGmyDE$u?rbv%OEYAeY1(+Jf<9egwF>mf|J}%zFrkgND%|Tj@w7i_
zZ}br*y;1ju^XsU4!})b?_ns@t6fE+nw0niO+H&Ve;9>4U;~r4ybDCH=U%H%@teh`f
zPJ@;6CCh0rbC%f(4Q9@>Ojl@7a~4$=Ta8SV!w5+&&}5uBGfv2d-~Ob=k>W2ijuaE1
z>>7(rssFRa;+ZGnlba1R>g269{H1+c>^;zRmWc~3udg$s4*lJ9#k+i7i!U=38aL<5
zY=y?{`f85+YkyMfpzBX+om53;9dGi=`QJLN4C-y(<WJ83<}Dsxz*5b{Mvj|hwnKx0
zv)Z@CUlz_XbD_b)S!OOYSU9VtPN&CV5;LdIb46@eB>uTMbY6XkJUn`+a!utwE6<eE
zM;=km*X!|-OR?!D^hm~SOK<0uxO;fxY`0uvvE{G2L~Lj`sZD<MOK8I$K&{RtCc@M1
zo3>0uXiCUmzdY<D+i-Ek#yh>tMQD2QkBA*87sqme#Rh+7iLcP$&n)v58uXb}LmZ3-
zhh~|w&{{r2nu*XCJE8r_Rime7mXHNG;j}YB%Jd_*v*PHnTUl{59P&<8XOcXk?7#N%
zMtTnO6K;0$kx6mxC;Iy@naVq5f3A!-0&Y%<UVZG0@rw9SVCP&Bze>-`$SdN7gr9Rn
zx0%pbUSE<m7&=#!gMgy*T#-6(!0`&CK2LpDBwh73^Uo{%H66;?NFR4)D7t8Q1sXx6
zyYKQ-o4Wkj0FZlrGQV4}d#;G5x9qatE%-fGq?ZeV&z12i!0@>u-UTQ=SH#<p93Ryc
zco4Phyxv4uK3AenbjHl9*hltKp6?@|mwt!(P$%^gO_Uq$A?^G`T`5=_w4Ic_`q<2g
zGvY(sxuSe{WJA*tdP9Ac)*$a(kvb5(p|9@7kBE^p>nA|y%2M0X)HZ8ejILSV(&$7?
zZ+*L4)nDA|7T4SDGH#BbxCg2h@XFKO2G#VgY#`zN(tUQL68#lbeTeDR6?YpX9RA5f
z7C$oPS6=Uy-|~7NMN{|c(YQ{pNYB2`)9s6|29syII9P*qzkO@fVCFv?O;i-v%etw_
zwslW^B&RpqH&jP5`4(ryk!9Mp7wMo(8(*M8+qSoh?6upsSZ!cXZr@_H%kJ5}!)ma5
zwu^%`xI90}Z4E}_Bq}YrJgWPUf}DMa&^K}eUlA|wnEc*(SMear4Q1=Fb)!peo3%^;
z$`!FK5~gxR@<<WPa%H^GM7&&)`ViUm<+B;2ohu3^K6vLGX5ZlLT#-5v40_olA3R5{
z8q(VQWZI13<y?s#y>j(%`*GS^U(#t{Y`SgOA6wn_<~+8#t<8CC^*Vg&Ar<zO-4D$-
z8;oJTfQqB`+Z0qPZ2!43h9<I8o5IRv%R2+Zu7qu13My~d_;F!Op`}Cj+Z0+Z8w${Q
zu81j^iI!`~v)o8ier4)`@NoGQN5ox<@;8`ZWJdNsi0G&{@hOlbxW7#y<nl&7g^<?)
z^C05c(k6&>ynmZQNC*5M5${3sk2eL8OQ|~A1R{NB(xwp7{u)9guS5r@2}C;f|40~d
zbsvUCEKc(g(bMwH`%qWyznOsN=d76m&*klY3OjuPazy-u-tVWdGaWYbAm`_;A@|J{
zsf%QUxiV>w{1IO37H;a=q)}wyO4!Awku+U9Q#cxig9(m0hd_h(b45~?Q1GOTx!t^m
zF38ew&;G5>G{M%-f0J(BCuQ^#U+@vp%sv?!LcnVOO}yMre_KPm&^`<naCheRicap%
zAHG6M?#>a&DG7OJI?+zUlRlMbr$N;@L<8QwOV#<<3N1(%Ft;78kaear@3d&iUO-DT
z<pC|tj0e5;Ts9=1p>Z2Ax6k8Qcx5^bPlKv6m1C#LNdsBoitvXzT~15h%||k5+`vp{
z%xT=xJoBc^Y3AHicV#e*UVC`FK3+m2m%`kx&vHaLwLX?#zuDYAl*bgkf!2ajAjK1>
zmI2<Rn_|U~ZhUSJyr#R*N?yYU^`_7GBt<Q->3leiE5VO-&?s;;*Zv-~@$u>?mDi8+
zLu(e^{J@$U%&DX}&lRPc*Zwn+XqG*&zg0h%PxYeI7|oZi4?i@=DSRZTrtsaLTM}qD
z-z5pOntKDnlZ&rA^x(n>fbEt4s*d6{UEe_o-}_V=owlm4Hvly8W!BU)MP*P=xmuea
z5Q{DI;V{`{=JHx51I?dXlbfVwuFv@@ip^3*x#lYp>2Cb;2JWT8WkZ+1jS`Q4?or6q
zGe1aP!#5zgf|D`xA+5SKom{8U^N(5H7~RJ#Z(I|7wDGp42<tYdl>EjyN!$9E<a!V>
zQ09%d1%jD4-tN!-(Z(A$V`7ar?#@2uc;kXCzPzT5Tey!p-jY!B5yu-$8xzMHOdB)D
zpDUX1!u62_D_pw&vc?;W?qi9!wZ&NXp_!~X(83!mqbU9vv)Jp$6K~Xmg(v<X8j!$w
zEIGSAqWF<4h~Zb$&d*CrAtQ!);|&@P%yA?gQaEoN8{<bDZxqG*h~o_&4#e?a8&0c<
z;|(T`iQ`RKb&AXGwoI#I-gtwE^U=l|2y!IS+)N^GTPZ)xB5$BnD1m89LR}P}rQzH}
zdHu*v=U;oNA>Mq{@&@t7)bh47w8Y2lEtad!+fUnKxo#^L%heW^66Tm--bk2ZdU@NF
zYY$~RZPbZA0%^~%t#qc{EP<gMrl*-bTgvj(FoNPu1sVO}^rVd=bvQq1!;boB<t<O<
z&mUfSQ=Xg4E6)d*Tf)&loUgP&u!&4j@*o<2DCG_EY%<0hUW&^Y=b@R<>a|(5x28&z
z@eWfaUfD&RTI!($rJejWuQ;3?B22vIaQ0Wh_%8LBex2xk3duAan|&mT=*~~v;ASoQ
z{*rmh;n|)1p`j8U9g0hIE%}~lNPmm5H$5~%q_ylj6!9;hyF()XLb^MiviPce^jGos
zu2lJE{C&0R<~Z;{TT$Rr?RflZ-QA(!(oHgru65t>N`3*^J;^UmikQrCd-J+?1YI~p
zyF-5oDtmOeFQ<+3p}*5{-E|<S`B<qT4x?@N4s29V_j5%Vv%9TZ0m2*IiVoH)?ysVQ
zw^R!l9ie?h<4=5cr^M$MjC~{->Z*fQhYv$=^@Aw87k=gUpD^mK>^CjkIbcoKlU;<E
zaOvQ#>^HZvM}HMCJU<<D%_VNx90|vM5Z$139j7`wtfR3z@jcN*AM0Fn#4Y~Oi*hPD
zI=h$hMP{ECV;R-~#x)Vex-!;$7n5BXYnqs1o%Gz{!XTX#-r>3+y(qM}-_}W~=zGat
zNO0l1$s@_Wi8^*9*|%o3R0sItwR=)yzHsdhH73KgJ9fm0vX*A>t0_T4$N2c-xBE3u
zzUb|)Y&E{|?8;U{T7z2(8Mtbqh95}|i33(ob1Qu5*|EsNg+qE8ZO;|4D-aa;MQ!);
zr5DzylwNrHF_}jC#pTlB%q)Asdva!e0vbv_tXE@Yi=HYy#@?O-B?;cNGDWa@^rZ-%
z{zT@nUEiApitXj8R*K+d&7=r+Y2l(2!D?mFHG9ZAjGC~Ayu+xuk{o<}ZwsxkWg-JO
zI#ii(07p-zOl%DG4pAl?zR@c|QeOba5!L(>L#awL>;+tvW_Z%dj>}N*^-qdnG}la1
zj8>%>9v+HP40}aaka7=0cC8FhmtH;DHsO$u4%;Ra@zEjMgknCPE4pu{gFd=a)i~&*
zXR4a5`>qb(CLHn6vnt4w>5EaW%)(y!Rhfki=9M(UM(&z@zo~}x9N=?T4Z?|qJ%fWD
z1Ksy>Ikr<Ob?%>I8@Qp)gu_BQVfNv$kY0gPSIzF^xN%fSSB@K^LV8sK;^HBafY`f3
z<=`K_Z|U{RKnyfOgb81fbcirl!l<tW{M<Ce{7xJRmw~$ip9|owV5e_FI_#Oa*;8|}
z^53NeG+l;mCA)E;NUzF4EUlXaqTG}m!Qw0IOcgj)oJen=srjczQZq}jkiUINiP6-Q
zl-TGGKP7y%(M6D%4l3x4iljFF*zj+S*4xh4;#OqMd1{%jfBFp)yJpSm9#g$$`qu~K
zj)Y+*MP}O26Gdje^0;*IWJtu<MUt61u62=QrVPF0$V|T*nStikLe<Yk3Ys<ix`;^Q
zOnkkm=;-!z5)ZtF47*0U{oz+6>yoYEH>9a7so#*MvZM|P?qbn6hh7(pW*7ya%#82X
zg)+lk;FF?DIvFzV#F=p#y(7u~T-&ZuS$h~68o+q#sPgNo?&!4YtUGGcuBq;*p#jVG
zC&>ZAp&7R1;Lr>kbK=m9VJ#|DnqY7S2><02IOS{5U)Jzh4ED<!-o?9WkGkZ<5pBK(
zbamAp?X+(9Y~gj)9o2!YmjvoHY~ghk9`!cgRe96~UeA`4Qk`bBhh`4XJ3e`}js&%o
zsu|w#lPYrr0%}fwYuLWygt&&ccutXPc#H4Usu`GfPwzeJs?u}n&<t<iomw=*yEpmC
zPT5pFRkdiws}W==n(=x7l%g4|@eW6HD4^g-vilAwIHK(TYu%S4+P5{s5$#)wRhiTo
zx_TzPxuX0CMZCK)A^9}794mvS%v;}9tTNtxSvN&Yz36+Mb$ta`R9p8xsdS5kz#uI>
z0|Q72NOveGCC$(bLn9&G-Q5Dx4H6<qcXvx8(#?O+>;3Nc-QWM5=bSlv?X~yXd#$z4
zJkR^iIYZ`nLF+6t7nAXPFB|$;H-l=p?t@m}fu6(9xO7;8_GgAxzv+&RrZD@4;8UNk
zQH&BO4;*OUDkq0I)h|x-Su)0?k_tQ(JQA{QJXK?eU3S<j5YlN#cWsT%n)R?oGL)Ws
z#yXzaWf32@?JuZuxEOV+0yCKxcV*HUTMN9FHr2M*8OsK03)O@cZjET4;2WjG6yY}&
zrqb<UE7`Y4rP|O}!BVPjri78-e6tz?xY&rssYeXyR#I3KfOP4@7l}dXF490Y<Z<yR
zriQ!cQRYeeS>$Cxhs<Q185<o2q%fVkGzuQelYokiw~KH1U6V7XDw|JZr68h9#KJ$}
z?~t1_?~g`w@zss%cW-K=p0*e!yvnfJ0>ht{E1S+^a456k_m@<x6F{2a1zhb;GCvQF
zwZ<pnC$*`ybAVN>?W?OB-xyEKQ}O*otN6Oy`Q5!tTz*#rXLhbV%(i^-vzV((64h)~
zJ5I52a_ki6+ZyRWir4+_`LC>X9@r9GxmkPnqbl_Kg-ub9rGQ;Zm20FGZgK#UtH_IP
zq+x91&tdVFA66pg){pbB9jIdD-_zMz@IxH@H!4!O8pZ6URnG;a%ga-_t^&vwS9p@^
zdupSNsk-+Tj?L0iHcsV}=1uNyjNH;vOVHCz^j924c4_L(joq0Oy(}2|_oXeS)1?Io
z4{LyiRA01l1|n{r4A;TQUwms1Fwc|tJ-4Y;x6Rp$vMX9Rv@5zx(@p7$J}B+)waHi6
zD6xs&+>e`SauDovqW~C$E1?|6;5O=h>!qX;{pvJL+rEFGeaa!qFuyLt<%p1bq<5Bh
z-M;5DB?(>h9c1(0ujuxl?}k>U;x-PtEl}=|(;jU3Or<Kd-%KC!XxQ>oIWXAYy%ySq
z|B_0r{+p|3?12A#G)1Mb7$vmNL1>q9&didbeLupW=17l9IxOfF#riFFh4}uJtDN4m
zFWIgn)0vYN8(;T_%;5@-GW5I4jYkUFzBkinh-EnJ#|Rq2M?y1}TjW~ER{8DwWkxkX
zea9)zS<-UX3WHOVUeyZy@b82q_N=EIyJDHs0|E0);pMUTjf+wr_d=!y@z(;#?ozTj
z_ZO{5jtZ{JW9J$kDkV9%o?_y`bhh1{Ij=yy%N<Y9$%*F@`guR7-<@<Jk(J^a_<Xgj
zjB^2&oNgr2eB7T-H)r!~9psjTEjZA}(bV58dQUiiWJYu7;+oartK*tY)OfCybi=ov
zF|vC@u@NO#DQ~qM0l9x|QSzMt^uV;HqU;!t%<5~03;cTwUYu5zj4}YJ&A}eJ@*oS5
z;-7A`X}-wOc6#&9H2Hi?kIag16ONhOUY$#LZruvN%1CNA72g|)c`v8VKnK56O{cr!
z6!za<+bLO|ZluXp^xu-Gq=r1w)Y@!rr#-W$5NVjbUT=1(A>oWKy|SASiJXQ`6t_!8
zr#ufyyt!C;*SEV))JZ`+a64zqVPEsvHvUy*KXiL7b2^XjgmzqjNuO<_bbT)sszV;8
zn!hv&=C5Z+gz)z?9x2Y|<hi$eruaH<yR)}mOj^>XlTx3ScH3sztkRiVN3lM?{KcZv
z`7FoF(%;$fmD+4i$4KIuWuC3SWsSVXHm`gwP0Q6y?rD5ju9)AnK8O8W^=!&Y+HS&o
zgN7@iXVukh-5xdB)%+oG?+No@Q!K8|b{&LG{g;AKDHYq~N!S>ybP{{XG+Eir;cKTo
z3xqOPd#@mLeMvlX)cgw{$?4IAdLM16h7M7<#B2828HF^6<l3W849JUpTUt}BqmVNs
zQv1>Y2MrRCU7G!wGB&{IxypBbPb-DA46O$<o{WXFr}#JFCv-`rs;6U!Z+jYPAyZ6S
zKAT#(aTi6^{Jd!WQ6sqYnfW5A<#N`i_sk(5CS|CJew<<Qv2-sKQ{W(|q_1KkjD)b-
zR}AHNgVWCltTj<zUD4GVlHgLj#c({tPnfe&AG@{@e{q3_Mfg2v>H@5>(GSDiF??yg
zj~D(@5O3jvM9yO9G<EYu#{w`%@*ABXPYOc|I6!BHE$z7uf*kRI6Y9I?>o}X7g9}gW
z!fCH)bSIpAb?ZaJc<$l|!aU#P?uf)75Wi+YNQNKL;sQDdERG8dbjjAa`pc75hjBD1
zX^(N>KX0`kjWK^n@~Pb%%Tn6VY5f6jR6>=uvOQk*+3vg`=hDpnF|N|={0;J0`zd9-
zh+T1}7N@tiNn`u=JIw}q{6Z5lVbfHw<AXf`x+FHCch;7#)G2&``||?LFPpWC<HRzz
zw{sagX(lH<u__%ej;dKh)<G#hfr&ldAL;wHeTgZ9Y8`0bfr_QZwB>Tjl@^A6VqoQS
zV`Ak`wu4h-j~)yJKdATJs3J)4<Hlq`#mz=zHTn=9wdUVs=!JU@yrP#T_rdW<5Rj=a
z)`FfNv%PGYymNUeYAaaoxq_90rshkXji$z5+-O3PV%+}-(JWg3pvoE0Hfmh`h(DK!
z%W8>yo(=i=LHd3!^P%!vG6cqNdkuv|M^#OQuXvKNRr;NWrAH;8HZ^v6*cv>8;%=~$
zC#sQ!0}(;o_I@#^r;HaruQFzHDod#X^Iwr_!QZj^OzcvsqO>&4Sz6e&X`jD&;-ul|
z{O#n<o3G>BYV0)VyozvW&2+9t&8{yb)C?!Fy!g45?5th4cx@`FaYVeEzuYMz>wEs9
zUd9vv$Y{oU^O$xHG!UY<xujzBa0n6Ggx{-IifrJ{Y|qSvrdDrrzNM{mEn?y_!$=zw
zhFRsWKf6`1X%sB)^^}jRBg>;D>s+d!TLbhHhP+!6D3C~G6rINiEu?i;mnKuF34-`=
zrKG%G#nBDz4tWT)g;sojAUA_hwCX~l%$)R%=wZa9Zh@lqNJLLNt?@St|4w!N5$^>#
z{KT<n2E$21=4sI+?da%lid|POxp*4GM4@~n!#R1#)7)}Os7@&q3dRDTAG&Vy1I4E>
z9ZV924duT{k&zjS?&Ippq7_L8I(>r4Gf$S^Qek#=65lE-Wchl)2;LbM7m=ybej>0}
z3Virxo=mh*o?d>3+HgiK=o4<vOjR8L^?2TcxPy^Hl-vF=myrlOE1X8zq;oNMOKQ48
zCZH-d;#RfIcX@-d3^MMg>3Db}=u*UZBjVfKrrQ>DrbA=Xb!1%j&-eWbVncsQO95+x
z`w_7UPxxsHDB&+hAa%x$G|QFD>uP5O*N^MGy#gI_#82FYAho4V^n`ry<3}aHD4NI)
ziSSA&mLyf(md`d`;q=|+#`p#j*)Q~b4w=XcVX`0jq)duB)nMu_9kJreX9lFqtW?Nc
zD%=)M8pRiF8o}3VhpE1i63DI=C)Gv6{r)_|O(E=3L)tmjLa>)H!&I*(&xq(<>L(M@
z%s55(wU3K1U(ZJY!?7}4YC(E)6#?pXu%?Ot>J+>ATZyjt?%}77wCEtdBo8m2M2qPo
zqIacS>S;<J{m`c{GT#>Xp}R07Fz>iaNa+s5u_#iHGdE!dy)iU*|3-^1O%deDTVT&`
zAY-(c@^Ec(&9uo6T^c-1u!_!IP+`x1<$TK<8~)|+=&*D5!;=z6j^Nk+;%U|KgGa0F
zgCi;#rFX0c)(WciY{Izf!IfZjHnE?iG>UV9*T(|yZ_djESk{g6JGUkqN1KAT_Sbti
zt`-#*6&KU!-Jd~b-AG~f&e~4Lb#cOw+pWfn(hsY{>pvFL86J0F@Tz-j3|4*(!$NyH
zAB#09K`rL@!~OdB>}E?*5B61q+WDCyOO2znCKg-Tx?1BnX}+nDozL)FpmE<OyRaLF
z1dXEUS|C>9tQ#?vHIv=Wz#-`nbnG097sbX$dBCjiaa^mvYgQw>q9Ul$q6o0_%!YZ;
z>;ku=f^qUlK=$~Hh6LHJJxe^|{Pp0mgHjBF4XsENkWl651^SO9^wR~EVRCi^aLY#Z
zDV{u}v2Py~Bq#Jb@#SL5E0}@8nb!)rJ@4Kvm!I^u*uzn+0BVa!nmz2AP0}+?x#mxD
zn8EH43RR@|3aPEn1Z~(d8f8qgfhLdiIuEJI%aPx@uaE?&Dp3p#h=+PfiSB#4H*SZW
zyIVBanAPGw^KSX<5VLHp{2++Qp5U!>ZlsTWV{RwYG7{FwGx9zR4II59-g@ksZQCkp
zEbUD-Oqcgc=;M$DXXg6V=UoSQ$u_TTZ5f}0g>og>8<Mx-t(bGjijsW+#|-l%5U{o4
zO(<bo5Px?HA64dHtG8r6SYc1~!1%si_W(Q=0%<GW;cipj1aKF;JKs5x(nntMS;12g
z5+ZLcjdyQKL#nO+mUv(Q>fbmREIqmKt4_0tnDS9+(<t*vF!O#BVUH%JBI`}(*gvnN
zU-ZSa@w=5&%*2H?Lkup&Qxmd5fjxKdt+W%-?(D(qHq>P;m1P9Gf@rJ9eu6^}D&>dq
zEyM*;z3(TAFFyW)8UMW$ay7-bf!Xg59-4~3HY6Mvq4jU0UTprtg6M(fx_4Nj?)<q3
zcY6f+yV%CakG3*<eX_D3%ucRWR}B8aR{2H5J?{=it2Ml=cJ+rAM0f6;VcEl)8BZ|N
zjuh`CqrWRXtTm{n!S;o139EYdBCnLo=@pYb={*~de4Oa`v0y@DPf843Fe=p5l!hWA
z#<lZ%5v^dAR=M4D>7)di44I8uhCg@&QMw+1rQV!Y8&`@fvUaF^HqtL@g+no%s|S&9
z=S^MF+FV#yp!RXvtOQw)H1Ecw2tT}uc?6%9J0^wg85;SBU}Y$mPQ5itcTxQ5=(RD7
zbbIxf-S<=T5{8kLp&blrq-S}5Wvy?9!42R5+<yW90B#T`i06+S^p{*f;J%7o+zBSB
z3e$rb0e%baWqKU&0)Smi1i%SkH_(Hhg@o>vf1lYUtgT@G&^Bh}VC4XS;oYkIr3Bae
zYY@P{jRDxzoNbH%>`HnjMgTeh=P%<*dQc;HUz~s1vdbG8Li9wfodB9}5eI;qj}O2J
z<lq2k|56u&8;0xK0l5BdAPKd$xB16lejE8Ey>9~F*j3@Cp?X$!HuuI1od1ZW0Whe&
z(VvnST<fKg1H`~cMN;%$_}5%jjO?uKp$0~FfP25GVEkulJn-_pfA2jdXJlmpgTE8^
z?_o(mEMP`Z0K0?*+_Nu@46F@*S^7(n6Tk!H1K;=cSIC@F_B34Gh{l_QP24y7cKdb>
zj4R0xr)bHe=x`~~(a}-VUgNF53L%JiXW-o)z!?87BA>`73hxCnlJZycSWgm`P<(1c
zvuZ#9^?2M8tNPnQPkr)87i9}Mh0A1YjhU<RyM@6UxBb2}(8hcB!5=?T=wk4)B8^Z2
zJT5;$jHrs|FZo47aM2?36w-Mn6)6LIX=t;ksMTWP1O?0oGMqu^KlM|0ozKgCbH#gF
z@#1tl__{%qNv~H9=IjZsJi;yOL1kacwckif<#?T}kyd_ZOQ>$U#h7@g*K}S!J(`aX
zo%25l)nHHLwiF@NWE%W(S*vjtFL<jo&9PppvHM6IEnS3G<(ZiVQ>mEQBLc#z${zvO
z6xBa-31~<qXJ;M~WEVFT3xe9@xR3*l^_gf=*YReZmB$zdtXo{P6lh{%hU`XEAgCpJ
z`wW`266m0TG%Usb5UFGOIH_{&$GMN}8Ie>((TY~{%hv#ksH-25pP;mIe()^u;q}c|
zGn))htl?}N<>fCCVJDefVyyF!0hK$paOafm#bxikF<y8PWt+Jdcgo_Z^Sv%mmB>3)
z3ClgJj0Zb!hc-2Y-ggZjnEr`ghIUW(a;P~%mSL!I&yk;gROJ#y8-=+bJAkNw3%{b@
z!a6F^kp8<T3+*##`_?E!1Lcy}z|qi5Vw0wi=}&wjQaa6s!AhvRZ%$Oj62eO8(6ccg
z43C#xJ7@*uhPquX)R3mn6OA;iBacN|3HNqZdEAzymDahk?X<*bD^}1ev)+DsBK}jy
zlE-zOnn&Wwx9IUqs3JT0^5n~AQzh2G^f-=w-KZ`p{Lp+IT-n`u20Df`W0UpoSlgrV
z-;ar+TzX{&ET?)tQ<D0XE>a8O#Z&SMRW8lHv8J?MsCT@}v*b@pKmWeE&VV7DdujrR
zuz}4}HDjQJVf7Uj+)n3dANBS;W;mPPIJ>L)*)2$%&iygFyemK40yFPrXS-<3;95vR
zN+tfc;O`QWU6pB(5ihaivyw{V5uqs^8MUqYhqvTfq6xh<r?m^B?n(xGZ`31~DSdyk
z6WyX(9*}mm<kozWwt%~tML+ob^Hh(iFFtX<z6Q%#Ki$z9gMN>}#${Y|(B?X4uR;8k
zL-c$(eIdK&x7cXe2a6JSudssTOk<B7HqN1!u+u84Cas^*s+h#p^7StTv-iV^)pvGw
zHbzgxOayt1-TMO~86FyIU!H_J#&ra?_?%pG9tuCQRHONl;fUgsK(wOBM4K~1U`Q2#
zQb=yON~VR{MML+6+ILTqf41~!lK49=-^>Qm<LICV3`qhE5tdIgKZHGEAM#(wHsIgc
zesi&zH%yVg6Sz(oYpOoZXq|feRQd}V-x@vjmCM--<M>9<!*m{S&*sbS%tWoa87r-U
zoF=+a8xxayc`=#pr+Fe#E}HdK#=R58=d%qb{Dnd0i|-jqlw&u7U)vI>GWUOT#Ouci
zgep@%Lk;p{%L(2bB_6B|>b78Fre|xQ=T#|}E|k_vDlqq{OUVnady+RV@+o{Yb1P|n
z%-+&ROdUJxNaj3ORoH@;!a+XPYf7sxmpsmgtLmZV6cJ2TE>2rxopM#OLlY~ruTKE<
z!;dCgo1|uE%O%lcn7J1i$qZZuzd@DEndsGnzmA44jB{pw2BlNYz7VWh1Y@zYu&Lwz
z@N#pmgx_ABeLEJ*_&_H~@@&c=g|mbxN-mmC_~?jBvyf~k>cr4Bh-N-<|1jBG8mB)J
z_=cV;Ykj-^lsZfR{s#i1pHopFN*JOMsLo0_&qQX?>|-3_4MOZfm`#ZzTsH+rXuC`<
z+$sd56D=AQn-r6C6e}J-$JB;DS<f14Y#Po>W&0>O*b*}ZQ|pysb%Tm7q!g;gSER-M
zG5J{j^sPy8kwR(Z58HiP?t~x78+}$s)Lb_EIf7O~DI*rK#<Jw}7H-h52CJAAgdJrx
z$B37$k)%J^3MsUeTj^m|KAloi?*5rKY%jI9VTK0^R#_kp!UX;Iyx9b(s!<=UR;2pX
zxXs?f<ja`~A(c!tT)xW2G%YJ5CsBscdpu)X6?3y?K+q?R3;K>8!P|xGX{?tUI>H%a
z9wnL$?{y61g7tKY!yTB(Kg#Q$F{xImSW;@Ye`m6*&Yy<vq1L1d<_i=Rk2(yiPq9xa
z82J;AxRG%Typj(`WIrq9bRj!lM&#B$<M$g8AnAL^RBx7+wnc*Mc&NOsA-Ks%8x6@+
zLp#fC#!%Lc9v2l{<eV+{WV5%(BaaoVQh?Ze{=vJk>0qeADJrAFbgOjx>7{_o&R~G|
z$`a{igVQyZd^Y4$-Hz7eY?X9K+&7s>eVk$m3YcRCj*ujla@SObY8*H+p9K3uI7)rL
zY2%PHA|0$+kU9FTe(IsDK8=W)f9RBw-}fbI-!Euc^myK6Dj)Peid4(ZmlTS7a_Eac
zOME|VU!S`J6xLp}O**TFxkuoU^b!+B8$J-MD8W<pmobTU(HJ(=I#sA04vZWPN>-l@
zuSu<X+Shy?u!m2;nuW}$pa1yr!0Fp_(rL_Z^dVcd>+9dYXFgPyz&iLMR6BiWtWLwc
zp!q!Yh{JeKyf5j)l{g+QDe<wFOsn*|On&|AY=1#{2Y<7pO+s4o`cZQ)b)CV5&3(yP
zc^<NF&C?6DpX;1`5-nYx7QgWG&3VEQHR8W->2laDFKlf_b}>U}-6Fe~|1eiud$h*d
zqf+7Rwf5%t$d>xMTJf(>a`c!+mZ-}~BBKN23m?_In!CbS?{{!vES#P<)ZGa_kpY*6
zhD6VmC^vINP-1t|V9K%ktnQ85v|{IBhcgFbcD%=Pqzl7k__}2SsdIE<`H^op1srpq
zu>d9y#2LGqbQX%+DVZ&_+t5<(iYMI=UmKg?)3M0-vhG<_)lw!nUw_%65_nb;w8~X{
zL|Dir&96QV=FfeY*X-;zl+m<xvx!$YjP_jRdU@0C>eQ;z>DdpV!NEBqOmKa7UYZ8p
zUXPz?sb0s2fn<X(C&iqK=+TiR1JvuEHnVI_S#q<kSSVy32fSKIaFSFT@pb!bO7OTN
zKPxaSkCQ7dtc36^*iyf-E`4J7;m>)}iJu}d)~UN9Z`}-~ILMOr*sA$@8YjkyuC%yp
z8-D~<^wuQsbDq|k7-?hsw_<+OU7cF*yXpAZyCU|}6N({eY^~8b24v4s5T(ms%48;I
zYrfvCWY;X%Nz5!|6_RdfRAh6vG_|XY89tmgVNJ+!mCXzMx}xcZtH?YZI;I3{yb^dK
z*_0nK_@S0}H%c`<0nb{MPCPjw0#8_Ubd@k6UTx^vcQ}wP&YcV=@(oMmLnn`YG<@gC
z&F!9n6@Mrf#3@!)>%Q3ASl6ya6LWh%eSTSS^}vCz<pr;5o3q{zi6~KsvQ3=g(U#B^
z0#}f`i|`ePeF9jH%6RgoJ$#t%mF)N^4N!n|;kaw;e9VW-<E=ha#`krm`V{jME6hwf
z=?O!M-6aHux>irq056S$a$asa8cU}c#gVu?R$0w>VwuJ$VqZKie-~G`F~USVA@m+;
zo^%w@khk4~^{kDyB=pAo*RKTYY|n>NC*6flx(sqV^H_DShSHYOHtvp-N8VeUFN}?S
z_^_1l(&Q5JmF6h}T~lJTs?%WIwI{Rl=%Holx3l(eiK;JL?QDdD!ja(aG4#bXt)i&>
zIdD4I=dx?hYNyUbBSVp8sKqK`StCr5em)&fIdln09G}P8F&qM}*%dt8X<}V@GP5Xd
z8<xKBw$f9es{T%XBfR6yPip!6ZenbP19u?E?ZFi=!3<R2_eeF4FChfP<VH|!i|%<X
z8p~%?fnA{AU=%>&aZ7hymfVK()n?QbSvGjkg|>%woR}&1P;K@dQ#@|PJl%Y^<P5zu
zuIy3Hg`00xkoqiGCfPDwT8C7vq^BIO*an-64nxIRmruLfs9r#QKpD7KyNa%-Hi-V^
z7C=-<daY+9#9mqI#eGd$|F)oJvhB5VQ3ch4(t?*`%$*Nztn2|_WBVP8uDA8Y;+i{r
zkxeoJlL8(Sn$f2^Db7f|QD<onux_YWT+MGR%(>9c<{y;(;fTFE{HQ08E;B_fiWt_L
ztid~SJ@>8P!xuk@AVIkRD1<najp9x1zM(O1Op0fLwvmdvI&z6NyTqg;cFlwvd8O|r
z<b?|rU{IP!B!yH^a;`7q>yk*?V6Zc3OPi4ygm-H%kAC{7*1>#VGGULdtpSq~z)VXf
zpVgesPs09|D)l)XioPtjzN|dSMpSpqJE)J`lSd8&K`~;@U8xdXI^(WQ)|RacnkV9&
zlIH+UYOrT7;PK-&_aOXZD)roqeBY{}*9DK>zQMGPjBPmo=2U=IzVYB7Bl@^50!0t)
z&_xQ@n88?F#=fY=TGuzQaFr+A<1EHpV>O#fm950>X+yhFlA=MUwV&QYU6-FjnU8g!
zGqPI9?9((8=q{+!HedJVuM94WaXmGja`gNp(mdgFA@h{f(2xVqS1Y$G^Zb_j?DD*t
zi65A~+r1@ZT``!u(oGqDR?<EthZ(@KRz=caONBMbV$u*8=()bxy}3E@h{26cZaX!k
zgv!<c;e$_=@%%vQ&cxmflLMQsV#A%2!Y7aIX^NGZYV(!1^P4Bkan@61ZXGULsWUx2
zGyRWZtD|p1dv)%XyeH$iFI}mMgzUCP61NRtGjnkKO8=?g>j&+Z>R%NSxDZ=@qO4-t
zM&;%tE98uBB3-IpeuBw8-}$jRc#M0}k~G!WID6UR<+IsTMRFCd^&`CX_VbS`kMqpB
z&NpvmYlke){YqLo58lT&2j3jFByM$RQKxX^D7Qg#P8>U1rkPi+qOL9{FWv|Hk(`T#
zGpF$17WCVxzG0Z~;5xN=(~&)YCw#Y>$(IwD@#E>rSTrl_@q|pdGfs_9jzmS2fETNz
zDW=Z)mBB0<)HkIqGByWwn>5ov8eBsF^^;wD#tOKy2^HARbaoo0wm_Qg+&7Zn1x?62
zsDw`R1ij(w_lrL_Y{pcj{7h4iFH9&!C@9&}Epq;(Vwt1So3ESC)Yk=y@2FSjj#)r&
zZ^${al3CfU0x5^F*F4!M&LLi$o>~lg?SfIjFQpzay5{_D#IzzbO``d27mpz-k(4a{
zlZsrGoIBo<@t`AfX+D~3uJM3~OMP;ca92T+fz=FQVG8%sjCfXh)EotgfLBpAk7e~6
zH}PlKtO3+e40kNMC7OmPy7GAou7dqY1fpm&t;UHYns}AZ*nW#06Wb$hujO{SH$G`N
z<4wAEuArUGG0X=)iH-W2@V)oJAy-I=&$FDd?NFNH9*sD!BU@A>bf|onMHe-wyeeUr
zE;L7YEW%8SsjpNZ!NVI=TNWO<VRl({j1BSSmm*^_idUY9%O1mnzKG;Q4vcbl&lbT5
zVS=D7fI9B1^z`rC?^I66gIc`SczB5~lN%b3^2;=Irdr=)<CSrjy%^~f9=ou;b6-8o
zKPPXHn74gDuH51HZnm9CqsnY5WG{Ok?d(l5_yFPd8xhZW{@_6=_%#Ezwxs}9l`uL@
z#_@|$@}nJ5VcYpbZs|?iEmioVx{W`ZPW3jNOfp@Fi(WJAaYADzS@8YKo|e3yvJJ01
zaJdprW2_od*%Dw{Zfb*I=8?%!$(kP!jRmV!d|i7j_jT%GABRL12g)<uJJbEdS%7JS
z5*l$rS9u|sgI~(Zpux&Vy&hR>yD!OGOE#Lcb2aBxfQ7#8ACiI8DkHoj?bOfk8Jj8f
z13LZ$7-dusrNkcXgOJ=6UXRV^8)u)-wGoe5_>VYQUjX`QZ;Np39-*S<uqS$bWT3um
zdMEAWoGW!*K@WLTcEyiKL3yr;(A@vQockb@u$kEARjbFtC1!@}>IWq#OTFW@N9?Ft
zC0^`i8BNHyBZwZv2Nz0pTu4HM2M}Vd&m57upS&=6587Vx-bp_YUPMecZ0$t4rCrh@
zz8*&Q_~=!MBn18H!RiI_Uphk)YG0;e^BT2u{5dL{vB$=H(x~As)A~byxfV$X@1WUp
z5zVyNE1LD^b&hA8lM_3p0vd14$Xch{fdcK5M>a28OHn_wF0mrE5FF%r>SFM+EJb*F
z({rh#I8}P)A^ST;dm>*2pL>bfyd#~xlkoh(j^Xh27T`*QaE0<&2RRf;hj0k6^cd+h
zu5~c=U^@-LqZ;LOtnnfZVXSfa5$$Cx&J^pC5n?0CE=(-dlY*V^B8<hU8=XDw1)9H)
z*}FzhOU*sEWY1!UsS3U%YbLM$>IaKYu&W<@hW|kXQd*Ji!3N40?>j<;88u{b9^Q*@
zYEw%-Cj9Si8pPb1JnhHD-R7w^YC~QL6E2O5D^VB@qAWoW%_p&z%uzp)A{0gTkJpNg
zKTB12eiw@qJEimn=@DZ=5W**}WfP>=EIbz&h`sVoGOa*FSyYrpj|M~Zy8=%-*`;m*
z4Xvg1VB|8XR#8OE6plrlBQ7V=);S!;AD*53?-U-!peL{{38M(ap@m~4K*E+l3~e+>
z#w=d`<topXs1fOq@-Us0TB|aZ<`8kGGNoE?kn%7XQ?h=x;Ur{zc^^4^-OQ4}@{V9%
z0D?l~r1zBjyq&Rb68S77bm<JOYjW8Nk<i`n03FHQu+<51wag^Nv)lkn2#oZto$s6k
zS%QCw4bgF;^&?rGSgTZlFx5074bGRnRRH6=I?q`v`=eO_n;lj*_absD((g;PD2>`2
zeTZVHYv?4vsjvR9)+H@(+|w6UVFPy9UBh}x0*3qm^NfK?6s$37kl02dPS=p$3y)Y_
zj*J$Jn~Dr;7tb?RuVXGAMcfxj<SMF20w)eq=r7Ve2d?S>8DbTlw1`dG5dm)W4PSJT
z&?)f3S=!@Yq#(O7illo^;RKK(4r>Gw<Gn&^Qc`I`dAX9)WqN>dfEIwa^bOGpk^ayu
z48Z`sPNtQqRWE!E2hrh)WjKnqr?Ka=R==+nNJO|@bggC4nW#>Pnj(O0a;<ILF@&d{
z;NhrP#nI-w$CQUH@~tiJS8j1;+?1^U4JO|sn}5J$AQ<!q-sSr@2FiJl+x`NA+5ayP
z^q-igc2uvG4+oa`*#!oBelUJ1Vjh8LVIDd0`;S#r2!WYWbT7T$9Gq3J4y$b=xkb&H
zYj*^)_1hWbV`n+GY!dU3(3=aC^p2bRP<D0~(xQU4_G&OZ1RWK`4Xw`Xzt)$3%__vm
z!hNpA)ADt>n?+EF5g}mVvxx9CK8|ku>zbJ&J7M1JdBAIX><16c&PM7dtt0|ITuhNX
zPp`R=suAwk*vA_wQ=pB~!73>k-Q?%bDqN}aGb1tcow(+g1(hFr-|l}dR1q8D&C4p>
zB}%}srBC6^Z)381nu3>K?qsm=cp#y-vsEo%u+3ye>vChRB_@sTjKyv_r4ElRK~e18
zvnuw>r<-(|-P6$F4Uxs*W)n6a%u}<UW&<Hnq<od8zzM^sXbjz%J%{s4r-8Hj&7w1|
zr~{HV7AK78jw@H&U<37YcSO|A?ACvW>sJu|iWdmP@h4oI_dxp}%=$M{evjq9G_o^*
zLTq5x(0kzf7rd{aX9>sZCEv=)zEog-X=JAN+Flh7q5oYkp=SxPa0W2`t^(ZGG5xNz
z&@+K!<-or+MSr9DtehM`4gf0`7zp6x;RC@@eGu?3R9_mVX8|z~u`;nR0&x6lCt_!C
zPYdt?d4Cn}$9G?51%kML3B>elq>LaYrf}u}-pwzOD$L08HGubb`}=~_pThkN;hAUz
z1l%L`|3vWbDT{x5<9B!V`mkSgg&LeAxcAgAsi>Zv(J%7j|K}M9)D9+Qst5h!06D$C
z%ACO8gvWoo8}KV2zZZ+R6`Ul1SeXFW)ge|QR(6m-f?t-^A%-whJ2)!>;=G^5|Gk62
z9Dmh=L14iD9&m~VF8y=<zk7f)E<E?V(eEA1{pXs8_diy_@Z{nF-DlGOy@Nsb><ruv
z=bzTU^?*G8>4O8n1)n-MJR|PMbI+{Yb3Jeg{P;!nz$qK+S5}aF-UM)ellf=Z{+-14
zoYL>yl!X}Hd+DBbQu&)SvcIR8{=wXE{*#qbf?6Be8^F05Mgu(v)EdCa#>veFpCY3v
z3}*A39ZrA2r6y248&imZ9h)`Ogz0ypi@~`z7{uD@<vn%A`0_cB0|?~c1@dxma`JHT
zF>?SJI5?R8Y4kt5+aD@SOb?#<)+WCK{A&t-5n=z~n4F+S#uyv`PA&|Nzc&CpEFf-x
zG2pih%mH6nfM2x$tG{I2AP{_={jUtj4Ije&_O~AV`aVeiCF2GGfpCxiw~P-A{@=Fn
zG4R48@!xv9d?5HY#sA8{|I*_Ff&Xm-#P`2rhR+QQPn!Sg56l7Ng(uh_84RiiU)#`M
zESxID#pvEw_ct*WYioGW?|uGzc}ZIt!()3N_+P1H2h)SXet8$n0fKX*badj15*Ysv
DpScds

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error-high_offset.pdf
deleted file mode 100644
index 8cea1d6550d228ecc2560e0b6d161468df77155a..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67661
zcmV)zK#{*CP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lwryN)F`k6&?y?ZL|qN|YjE
z+JMo30S~(S%?uBWHoAev&OzA&+yCBM<XVf``EH(D?-mMGmEt|xAyJe>@ng}x&iDWP
z&EEgV+IfEc*Pq9~9OsWV&gcI6_5c6p|M>Oq|Bv(QzyIHdef>Z0|NURy|NB3V|LuQ&
z|H1k7e;#&z{jXpD@@4Up`G4O(=l<h9?Q4wlM}PnSpI_d8-0vSF;q~=jzW&qk+it!8
z=<mONcWXZ$e?-V`zZ>cQ_20k#!{3iPCwG6f_M`bZ+jw`MKfI0Wwy(ecJpTQE``h`q
z_0hlox8vXa&3=sk>F@vJ_@Dp&9Rq$lP@6x-HoItkKR17#AJgyZM8cnRyW5Xz`xM%L
z(rJz#_h?%$5dNf_-@$dUpM-yo{m+m4>fYa99rok7e#8F1&V29fhn@TEK=_l{+4y14
zvvmXE`)+UX`xIpo{-oP&6lHV+;ZM3vPr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>c(T
z`uQQsX#Ytk>z|@b!uQ?UGbzg1jf6kxcE1m|VYL7x{8LNto>#NW?)O*k{^R`P9q@Jj
z^#y3Ne~K~*e=<9tpQ22{pLBcg=nqjQ;ZM3*+t0{se&5BOLBUG)lkm^(fN^_&i<Z5&
z>iix1|1CSfuKPoj(f*U!P5TsO68@yy`~QE4G6{dut=$x5bOYf}x|vb5umm9d#T{Vg
zKiVH3LSO%eJK*t8Nk;qoxn0+%9Haexr+MyD9IZdOXZkPqeE(ORjcr1naO}(yr+-@N
z-@EhrjnMy_l%D5PdY^xV>~4A>3HIGV_1+MRSJh2~_YMEgo&)1OP9N|4;%mIGQU9GH
z@|Rfh-tS`@CYs;Q?R}K>H^Zuv2;X+I_qn<LbM-6A_Z{DIu=e}bQIzjH`bg!wI*Rfa
zmcjh31<v<r@O-}xe_<7DwqL}oDBn-<dVUeKqI}=+nI8+!_P3qdTV?rN`l5W_@qLbd
zu6<Gd!b-IF8PT6V-4TE7W^8XA@KfB1^8F;|=M(YgS5dz2c!&PD^&{c?ZqHj;JwH}M
zly5tB^N+P>`!B3SxAVum`*{4jmH104V(<2guodO|>AfF&pTbs@?>oL9m!B(Nl<zyf
zpG2Q4UzG1VKKJL!i||+0;(327m6dPT;;&tu?>FYBuodOoDXurIe;mR^`M#q+(P6)O
zN%_9xoWZ=UqbT2Zy!+lMT7O|3{Cxu3pYMskq%=OyFM?K-Z>P2lJ0F53!uQ>J|7F#S
z@_om5htE|n%J&`LZ~f0zFUnt0oyPk%oPW9}{+jOeR#Sfww4(fpXn*RVpE~C2>(?Lt
z*GxI4`?odm_0Gw8w)?%)a`wMY`Ttw<-H!40<GkCwF4VUQSf<8*_y3A7c8>dQ@2}3c
zu5hl;zqi$!w|^|C@6FSeCXz3(XiczWS^nZ}aM6}m6vsnmQQl&G1SubTAiXK6a)9#w
z*PHUuGQ28-vfd<b%3EfSUr23$u$~&%89)9(sNt?@wE0BW*VnO=T%TH6*P^5auPAs?
z2jTsn7NI5?<65Me<Xd>&lq<gQNvUa%)!zO+*S9!9kB1j6B1IV+UwRl@@&pHE@$OA|
zv*p++zA>i93(sRfNogYp#i}6CvK5@N;8g!XCYZy{qfaNL6`w5l)HXi7*>eO*e0sO6
zcoZ%2$6!l3@n8)~OeXfzLDHJd`+y)<ibAgB2imyBgM7v<${6~gSk`fi3zjQ3F3Gp$
z61*v<5ycXWxjxDt3XZ=?t`P;t-xSk`f}LZCH<s)hBY6Z;jL5|w3%)H1d35HE8(log
z9k3|k(V1);O*}fmqb44m;8Ej-I>Dk`g#)A*kV$e*u*k%;WsrCuXkyt32Ax0nv+toF
zK`@Ot*yG%oi?Za;Yg^_YFN$fr>tAm*|K559cit3qyHY3?1>LR(hQ<q0dgbZ82>r>e
z_a?2A1FwZ71aEwDA@Dd0d*$E{2Pb^8^`4{CTDS<ohBpP<c~RoSG@dO=%-XpoO96R*
z?^vY9(S}IC<dKw|bXTt%lkV(vW6n5>K?;^Pu4Ebv7Xb_TCgc=p6I_&>qQz1kL5L<6
z^13m}lS^{lSX!+9yB$+Jw=T9$yw;zsPt2%m^{+cxT*51-(|I5-!um+RYYAg{7llih
z4uRIM>J*ddw7D%xZ0?SAKY|o%)NA2WiCGjb{FPg|Pqx+q^-(>JX!6e|MnBk!pK}RH
zeri!DC^L6m_XEuwc;C9@!28xE$E^+jrYy$y-0w$HVoUY5^-9L;;=S^!SriIa-t~*J
zgzE@Ouv!=IH89?D>(pVUufOTA<fr@{ixhlp55;yQE8AVYqD6^y82@!(zbV(+cI{G+
z<m;kTuV7!hwqC)$Hn(1RMzy(h%hAoPTMkd!&*jl#5BerzUI$1q1y_%b;rZ4pho`&v
z>R?`8#s^5jy}otJ;q|RsEM{x^7?iV?d;UmLI#g=cLnCUob;}Xy(7&LFv^@0jLm_bO
z+`8q6&aGQAOd1(9yk?KCm<u<&J?e(b+n%jkjL1qba4*|kQ^TEWH^m88u3cNNV3Cz@
z;O=}=8jd(zlvculd(o!E8<(I>ehPP<NmIMlg?0p`It4eZE`;;l(q%AlFPTn;iCf5A
z7yC>V=S@N@xzM*R$pop|ORtU5_iTk5Y(hTgEzcPLJZ}Y)zV;^M7p1e!8(&RL=txq2
z*0yf>S$J6AglORCofjs1@{mux`OUHOVUM(lEds8Ei39t5c$?sf*-q&MGc~nik?=F|
zpV?vNhfk?^6X)+Kp_n*u&r2J5;(R?N6*JF;MX7EfT_>etg*+_oo+%Yak`{YUNd+|d
zMS)bjDLG00MozG#V&DQjr4!B+qD3M5;nX?1Rt*Q^*|i4Cc(~ezC)RXKk_!FI*X$y2
z1w2}0W(PBMcFfLIG;qJiN2D#zj&JDpfa7>k$deu|yk};fXYaq!PRS$76uz=3Bidw0
z$}_*&l4IeFB`I3ugy9p?8sYV^=aO7md?F<90HKG+SWknQdeO4TlN~3V$R#8v{LEAH
z%Xu$HGv}8EmvTKXN*h6-kmSC3Q&wv{spr|Fhr@_nv<R5v$n$kkFvszLNu6^XP(K$5
zKOFxVd|a=o=+L-!;|81bsu(xM-gIV-8;s%~<j8fNj69zgg=4+2z^1WY`E0XCn&!AL
zd}x|@qOCT^n*kSgOAE<ITTp0M7<sBM5_tQjtZ}?4*?Rv=k}~q{UlfjP<O|+ziAuic
z-V_}c!_iGw$jI%uDEzFaXuU~jt|h+*_Tq5-=-^%)@T%W~0yuKF+Z~@fKnmvHd{B&h
zzrP95YWNME69b#;);Td62d1Zgz8MWRnIz=s^t>3@Q#YTN16%429pC^dgawcDq{I)G
zC>VaYMB&5_rz9Ln$~B}YoLIq=-#+DDdxbSRLns(TvM3=BcInaK*d3Q{7SCJ9E-9oQ
zm!-X*0NA;{?wr-;1?!M~Ir<$hQ^UJqQSvIXOUDL+nJhK`1EgTpC3*4GXWx`;z5k^r
zh(pdV35(;W775aVr>tEv6#2y1^dR+t=n~yEK5}wa_B|gMn+_5WYt$l)Y{tKHEfm1g
zBnO__ut671N{&sYBzKHWw~r!UOs`x-I@qP>%bSv8laa|g_$FP&`@5xc#ap~77G<D4
zqSe^U6+O`k@r0_jD3E*TW=E1jJf{>|&(YYFLW?)`qEJdtgy`H-vphA?MWXEBs+dw|
zdR~)OR>z)K!K_zqU;kZ#)Ncd_g&_3{t$|h!T^9@9!8W^Y!agx}-4q>SGj&t++|f34
zly=NG&2RZbnDWqu!jsa5tg7t+Wp0!h(TEV(BM62+$u(=3;h1Q}3cinN{?}N;q1&}x
zY1=cL<Vkw-a5$x;#e-oH2LB*h;CY76ECQ9QmTz_&G_g8fmWu*mZK(n*3YgSV1y~e=
zowyBfQoL;goYeNggVTl-x8`75qu$Z5#V{CLFYog<@0-@aGra=w_*@k7smCK{Q6P`)
zy_L!o*l?E&sdlY_3wjCQC2DCM%o!S@%%t%(+#RlM*06)#l!11vxj%f!HE3G?Xbtn(
zW@SKZsaN@}@tx7a*zCbs=XyU_ZfkRisNq_0i71|_i!#s--uoq;=uOJu%j9T~Lf0)|
z*oi)QBv=Tcr+%^|-EarEj1&f)C#{k;!8d9V2HnPGwXm5Yx=0Y-_X{;YJh-ejz&TwN
zc(*RfKs%P&>#b^zZ|R~ioZ+rLfKXafh}xpWl60Dz3{ij{4_Jdpxl|8p_>6Q=Yxs;V
z4>N4&vUZwbO4$X9y6fUFoV6}h1h3ac;emzc>zlM%=M&2#VLu<Nj)eWBWJpInZ>W!c
zq8V~g#?cdU(dFDY!=kwe{8ebaJ+GTHCCIwO9B<S`;cvvzxCl5O&Ka#dFVB&7RqMJ|
z&Xk2k!9tz5$2+9_Oas<xLuyW3(0%HHKJ%=zvag;{P`jQ;XO9+y@x+4Tl1U0iH_^<I
z4NccDGQG0nHM-iIEiRf~z85?{txLr73AzY5)Q%VEq71Y{L^_ZCqvHv>NIBX?$@TMS
zrN-E)DJ?>rCo=9XO1@Tm$8h@t4N>;qMaiE@R<Cw4pZ4GWOiVG=nWW?lxltA+dC!gV
zrbMgd{BZen8iRTU46d;mxU@()KU^IB@th*>jYY^Qn!bW_AZ*GxHrzJd^r;>*JoO!@
zZ4BA(59|V+_Qqq8QqE6($*^RnI0a=)rs+2&TI9)zGrv7z|Cx(QL-iuWoEu*Y{Z1XL
zF<WI3;;=~7;{YjU-KgUA`&OXzKsz|qZV1$(#MW-OfQ~l_!qD<3LJ%7F>1qd?8gHYH
zSE$J%z9{(?Xnd6{Qp?}T8Qw#kIKu(HO-(WNrA5&caVxZ`DdL^mCZ_1>#3_2T45RHh
z58I?9+#T#6`f>;Vx#c_j`qqX%%u}Kbe7UI;zihc^Lm!8d+J?RjwW2v6D?LN}7KPu2
z4&GefKGiEeec{2`XpK1*iJcn%CRdvFnSN0^I_DkkH*35-JAG-3gw?(%9rP3|N_K)Y
zUz89XCU|&S`VtP1vJ?1#7!YezIy?MALBY>JNoW~Av1Ao49&1gbaR`=<9QbE~a`JE3
zi$Z@fgCOS(O|<D0%GYHO@Eb5}G@2HAx;2g<aWIX&I2Kbcj>YsT9OxN<vIw|3I-CgB
zPAwEP&30-$d6~463pF2gf`e|6*b8elANGRC;=yPQ&(TF-pA?&8k+M_#cNo`9$KA|x
zASgMunQs}Rfuv7d*e0h;hfUl}ry>mCi^9PTeG7w2i8#z?uwNwfiWa0nj-8Gem7rjB
zkOsSHRq3!hn^B)x6m}bEvlEt<W@JO|+!3S^1Z@A=)CpUVhGDzWT7Q3OtcLApmj;VR
zhw1o@e2r-1C({#dmTFTUk9xqDy-0C3*hMKExH^nJ%sy^)!&qr~wM&9YTdV2J9;rJT
z9~p}fN1h?yV-ez*#M5E%X-sy)9B3g$(&=im54b(j6crRqfvN+YW^YO~AQ*^wSrnW(
zcul`4*?RwLkoAMtgy{;PrPBsy!t^2C2?%~M<LhTpR;MFKK`?dVR7{;9=P***;6$+h
zO^)A1N_iYwo)f|qUHpMy(f!xsA-mdGn6x$?Ny-`etxh?^G&jm&*zrsaN`BSxhFpQ-
z2M8%8&VB3`goKw<cdR!961sD}9gng_$rY#9x;s}~_ZJ?Ni-HyP_|^EAbNv|C(jA(C
zvMalHtcA2?+V`xJ1D)$9{aIOKT}<Gz>rQl>^QK$TjYm}%8w@L^i_&3wHrO(|b2E2}
zap!iHTdj9)XWgcq+qp;U26uJ0B8nv_$%+n>a*%Q`9sUo4x2|_Q_N|c>9s0dV<L_`q
zE)sZwSCSz+a<xOcX*%kihxASv7$489&QqG6<lcEm>t632+~Om=_Xch??Ht6I2MM#l
z1J9Ua-Se$sa#D9%7eP6a1Rlm8oRCgNx-3evZ=*yDYtSA_D4m;&l<X|Ztqeu1N`tNE
zgR(4ci<0XEW!>aa?`d58XeXnjytJv@NW_bF8WfEti$yVfo0O4^lEy>hAt*<Zl2Pfg
z?ajq1w#g_gf8#FPDPi?7lPcAk7*Uj#gMoxV5&NX11Ja~`L9y8=_Ha_U3295)2+SD`
zM$xvTG}6d@Irkp4)D+>?8c|z-*`>yDUg9N&e@?NkC>$F#|8t0YU<`c!8$VCi0E+_V
z<@h=^v?7p~Sn9KDPNcLFyp)f#QSfk9!MDFj9*rp<6bWAP^RyB?F#W6zmr{S$e#6E%
z&#l#HOws0A6bThc+kOk)Eebi6+jvpHDH2j)JMt)4O&(r(dNdkOHp<l5l}ApCEIS-Z
z2MC{sS$oEQn1RBxEW~ONc$D?@T{f6YbZ$1d>~Xk)!t1~>B{+IXIfBINAV1aWHoz2G
z-3FdNOl60TgZ4labgQ)I)alPfIK@CN!YKxV=XdHiM_zHOse3X9L(_+D&PL;h(Tmh>
zs;?bpqIP2s@<v{Sj*A@3x~aeNYHv4pWqKozMd)MK2i}xTUugG`mH|f5)Iq)DO`uwm
z<8t)?lkQEM!N91^I9l`Em7_%oXNnZ4hP;VVvKrj$RK$W{(7MPGBj;T#F{y>w>6B8)
z8K2S$Ipb4WVVVycjTq8L8*La;THE!g7X%@rj8p4v7vgnGEp8W89U5WUh2RgW*X^RB
zLk0Xz`GSI;BctMzI()mPI$(XT`Bl$=mA=Bi&(+M})crNFvRC*H!1`T0lP6j&-!E9c
zi_1H8L|k0s$(eL^!eY@%p@&nuxWW^2fo4>%uSO#UUuZ#LCrpT{>(t7e6pN{);medW
zsFx`gXY!T8XXm11A2@m1eAEdunDsIpX!Bi)3Cvr4;@CMNM~0oS0P|8eEWqSLC0lr;
z+#2jen2H|si-aCz_#EuT(NZD0G1{RnxD!{F4Eo@ZoUT3`EKlfLgYDVrL8H^2g41ro
zgh^WovS`Yh!YrDyxG;$ZR+$`|VYAS76WKI0_+W6RZX6sg=P(gPZcSQBPw|olZkU-O
zwI+LTc!LIR8mks1ly91}UXfbEZr~mK|796l6n+bW31|NS8yiR+hB+{hb_$v58X^M9
zoY!EdILhSLXsVE1u+dZ@+aYsw%Djjio%KUGt&|AbCo?^VR!#f{Btmx1m7ar6Ts*k>
zWiSm&8jhRB(%6eb!TSid*&|8WOE>3$Wn1?oBdufxZo|}RWLQY#@W9~A)jHJ;=LnK`
z$|%hw9vQBWAdNC@H!ssRctJ}B4CE~h88V<ZM@&dr*&CyznywayA}4EoV@Q-N`YT=M
zrWXK$>r>qZ+HGu}gT|OAc^4w9=adKH0EvDKe!P4i{CN33`0et3jO3JW&XPv+23~tf
zN#BP~ZKv-;r?fYEtS&MfM~D17jd4nH0<9#TYixd^MaZ?j7(5t>J||sGO!AR03Q0cY
ztzwoB{aKOX6E;7&ycQ|Bud}n`?IqvYO5(`{pnI)#oW^p&wGJb<4#$3h{q*EDxT+T=
zZ$(;6+CzWzo3!}`BgZFvrt}{!N_r~kWL$|o*C;n+OQ-U&xhfYa{qZ`!I^uDVL=%Lu
zc|;q{C+RiKq0xJ8{1ScVI+i+p=X$un|4Se4kqJO>;__Pvj+P&|p?~^{gOI`@Z}K8w
zmeSxmghNj0$Owwz=#c3r+|*osJQRAV&hW#gf4nieOaAjlql=vEZ;D*-D-|eZUtapw
z7(ziueq(@F*Fn*sTqq)-rOD;kf(9ZzXzYOn%nr)HgVl=ofT^J(d@F+&4v>=jjBaQ+
zh$;f2(E!t@1`HQ^Zt){2DN<0Xa3EJW22+D7WMk#{<Zuwy(Haj5g?%(!PZb#wnL+0s
zJ;JP?3OI?RpNzoJW@`+eklN8Q$uk36Rx87s82Qp*#_>~nyke`QKPa|J+JfQcaJDjt
z$MmZ=RC&eiG`qLBo(4rV<9=2vKcF`|RAvMZ9Uvi8NI#NGuOOs10Rc*p@Do8lun{*t
zRLr$4@cgN$r-mm~MMf<OL#`mS`RF?kVwDsHU^TpeD@3c|X<cDl4R3gadL1C;XY^Kr
zZ9*|)Zvw)}S{idI+N>Fm1=j<{@Yqz;+RE|CpeH>>Xn#}mTVw{sP2ra&M~Q*RpU^WD
zXV(yK#Ynu>Ml>H^U?=QF3h7&vTpkJh35`@yfy@>{<Y4{~v=4?CF2X!3{&2NBq76AZ
zD5#2JJXU5<M1?XLHj;<7U`V76RlFoqhbpErQioy_E9kPFj0lw~d@>?bdhZD%KI1zZ
zOpJ%&XB7>~2_i;EA*3r)C?i5;EuztJD9^YtoNLIgv%<L)(2Crmig|5mf>cy&WEbW9
zWCuB6rc!wAqGVvHYktsP6rmeAM{%Mnh?hx673mvEM}8|7c(s#pOWs#P(LESQe1O8}
z<AF9~kCP{nRW$a9<weQRS_tZ)v?3GqfYB<c_~?~)lcD8Q{Uh%tLbIXgA4<GIG<N(E
zL(5&?XJ~nj7&DA$@0Ilu8f}GxFH#)$j2DkYm<lIfsV`#-IFIC*7}ZUW*COT6HJO`H
z<x~V0B}dLD^P+S_&ck%SNFjuR>tIez1>8qYO~m}4Xl1-VUapIf@`QN)l`iw(FK)~@
zRXQaEEW+4Q28`yvf+Ja^nBrv`K8|oDC@e}$QArGo5<B%$3Z?-u2I&w%fhCC<6HLxw
zI>l;_E!)CqIaEf5F+fUb8wQM(O6@S9npFCSDP&4HA_k0)N+d!0&X#Oq2&1|t8iQFX
z2MEbKYCufoseBg$Tt(%?7_caiH*<iLE31ulLz`6ojnPJ_6rITWiH|7`&n{;6@Ofd3
zy;4Gu0aBrohWL}nDLRr8zk{r!)y~W+2^N40DtU>6uLP&VGCoTwP-KD<rwjlBm0M+i
z45<98;O?HGWtsk8SzN|=t;qW_nn0Nrwg~a}${br1CY(VS7`vquw2-D42y}%-7|39=
z3&{_a^=1s?QfAzu<ZN$^9BQkQ?ksc7k1a=!n+%D3N!b$pm;l7&z}U;{!<jyKfD}2E
zwKlMmDG$+LG_71kLoRscGRBc|FxL?Tq&jL?Ow`mVJ`qK%yvjwnMrB<ZlDsQ1b5U~m
zyc3yAR0*DolEZhMEt3hG1Fg)e<n6a8V@orQ^E&^Y8)`Db@PQ5cP1({}jdok5ye<ke
zXCXGU<W}yiA#J<TYmLTTrQog`DfuKhm~etWcg+wn&0r)Be<cDhN*i0Iu+b!}Y+{=*
z>LBGfDUqa2EzFdpeQFVzq-|Qn*g%o@e4ria{>qIuWohezP?k1zthlvLrC=XP$uDVZ
zPe)3)_O|l0X}Gh<)7Et`@!YPI@kPpXa2IDXQ+wdwnWbH#!Yu8fD-b4Z>ZmWND$0Pj
zG-_9l{37K1Z~z=Z3hadQ5-SsoN(uRkki3-AF##l@#Qr0otj~l382FQ%;Vl`nnBgP#
z1Gh;41B()<4a6W=gamCk#eLu}3CqAH5hG4^B4C6<L@lBKn_T{@9iNsDeNhsvqG{ED
zZbaAcQe^>eB!{gbd@$i1Rx7_u_=iOq8$g6*()R%biPc=Jmiy2UX;>%}OC!y1((r1?
z0|%1D0a8L$(0XD6*g=BCplU1B3>!p^m<)jph1l;6eZ$}$5JHC`UA#a%EQ1;g=i><F
zJAUS_PDAE`Z0A^{eU2+R!5qy+i0iA6N!}zum%Kvf4>kzi#4=E_5Ks)s<v>X}KpL{C
zWIIM87X{K53y@_If++%RIoA86DX4nAUJ`kxsY@PV@(5U_sc#4}@#G0?HW~MA5Vps+
zZV5c&TepOH@vT>ayvgjoUSWwmGt|w&tf6k6L!4Wu5Q75YiTB-x(_`?n6qZj=PTTN)
z;@ubny!a?JIAaPpXuUUcfF%*YvS=j{0PlHVO0_}oo@eWnP&v=mDWREonG77I0!KRH
zZTvhNf|9}SLy)CK*f5xw>RC8VL5UMxU`~9NH<@(};jRS=wJ2kQjau#CXYULv3sQ{N
z(FznP-+Cm7RGkkEAW}JSWcL>UmH`Q%5VBx|NB}JZE<gcn86s{0!gYW&3aBeh9nZai
zdC~YGye|VnT|t5!LGqipVfdpQ{LNlC-i1D9i0&<PG8-qEPh)3TY}Utwa~2f81%zgZ
z2rj5JgL4gVY6nO$EdZ|BAW&YN1-K?;u%tCf$ZkiF5+Y7Y=Qs-<Zds&aMnaG?Cng@F
zRTd?XwFpE<!&ZUSnFEVRcy?h7i|<Np0HEJdz<7(4bDV6Qw&Ci*#8%LIi;z=RV7oa{
z@wEKDgZ_mrFTO!Tx549B;DNCB9UH`87zN`?&(<wh@!7g1B%)T@0VzquL&H}K6Os1E
zLQM?H*pU?tP!WJ%JV08kpiPcx$OYnPm~sI<E=nRsc1A8{7ij>F`%~65gKM>5Ck<ia
zO{Oyo_{3wwuQY&E6vkyx&K(ES;GzXsCMkr|JU~d+NVjuf@Re~4Mqz+=f)bp$i6gcs
zIZ?d`H_D^o1h?iX`OFiAh@<gC69q72{@Ezx4>0`%Yf9rbqc-qE!9?Pt7D1|fM%oi&
z)gbc)!wSl=LABDbUTCgCId{a@q6|t-Ua3bR#|CM`mStOZK%c^+rR0!uaelFKWg6Tl
z#i#_My*EaYvN0<0Y42iG5}u7wflpf-Q-oW?4Le`q|I$xU5WzuNyd#M4PAIm7)2+~m
zNlLV0L+V4J85hNCl7d7&*p%XfQWk})EXv*MlL{eZYakF$pS$PA9a1)KtRdfeg^MD%
z4Nd;OH%TI8<JjWi{cIcq0ib4Fi|5=J0>UN+Ye65|#Q+o<!YCP!ZDJ6FwoNny>}i`E
zkaF*Gn-Q`0DY#GVvk|S@Wh26DOK{@YdYs;P?WpG;_Sm!SvDlc;zQtlcKV#=rlJ<QT
zC3E&|7RSVM?S~5}9j|7dH_x>lF2RU<V^&Djb8pNdC7JbR`W1oJrn@18<axHkc>T8(
zzFmhgDRmf!NcFOh;KW{$;dL6X#q6hTr}3K2iaD>-IF@da>b6>6S<&ouTdkk$W$eIB
z)XU)ENS9fpx~}dR(b%r5J4Q6N>*|gXjqSR6azt~x?#~#}+-`S^5nbEuo;<p?+kKgh
z7lkak!H|2q%#$JacA2lCt^9;8^&<}QMVcB=FvQMHW9e4AF}0e=deHEK7n^|s`cXIA
zx&<@JM6pIv<_X}cbj7JdD?5U8QE9aJblrGyj&wz5QvvKs@}h#ciknDD$aB9Vf|-hD
zSL893(XKdRDy*GRz{giAwLvK@H)lORRpV~;1U;iAJvuqo%N&t<U{`o6RrE#Sv+Kkh
zZ#|<@(LWZ6@2C@VWS5+wOqqC4bcK5I(b3zPwv&8Wbj4`$>CzQ`$>&X1WF=ofy$Q{e
z&!k2AcuMuAgBY)^uJA^_$QC6!9r<QksX^5zmPj#(eERjKwa=GfZ?0#QrR8Lis#ngz
z)vI9+a#i4&+7aZ3cWh7V!~V{Vq$%~u8BFyVnRzw#=XBqU4{+o4&HB)=2-nsv7hy9#
zM5}BFaeAcT;UFpa{d^h``iJEqq~*i%5E28+L)k03Ob;+=^bf;BY=F)1kj&kT4-S#v
ztPgopb|Qt)3ez{+Lms?+vpuZ6yK(^GN{6|p_rCSH@=vNuj;_oPj^TNk4D*e$NbEK+
zJUv5U#_GMylLO<ct2qr~%9?!1Xcn23>J~$s+qYtM`=#gBn3=D6?#8>`>okbNCel7n
z8vJrB_tt3~L8v~-tY_;KBYCzy$t*p0#uXW=<agff-Afwc3|j<s$bq<|VZGM6+twrO
zL`<Mf(i(@i>Jkj`5(QkCn>7O0qn9uwGZuvcj?1u25_tWsL}6|u+-zQY8f?>x#Qm2{
zT<OT{_J9*S9P&<bYUl^7<dNpg!{G@|O!WxCa4Fod!*{>79;rGY<@zOyKC`l4vikQj
zUBENY%XAUGgC1Cu^d;oSpRG@RT>fi#DZ2mS$mlQ)9WOXLg2GOD_xGXeB0MI2(0dY}
z9nugcP__Dy^BR5`{z1b>rQxM(r<VZ(?`0(GA0UOS58A8p0o@fdL_bp>k`4HxI!>nW
zE8!4Tj1awAeMmOq;k}><=n=w+iEtn}&K7|y=7D!mzPOO&GI_u|2hfC<9C!d$I6%r7
z%6tV+V6UhlcnkZWzcD$fLnEH{M^MQ7fe-1_z+=A;-XrPR>_gWGp8tI)B$^)5KBe)e
z6SbrAD7~!2x_HS83qXw6LGaZs5*d?c=AwWxIFQPS0=ICVO(Mn@!IZ}f4(2{PTKOH>
zv}gP`i3*OI*=vGOyvw8#esEU0rk^~(Nd|u;4wYGgg3!P|^>~0szE8$Nz-iy-)cl~N
zP8mDX_1~)u5W@rd)D?pe0>HGq5Xsal0t-P2eU>v6kqdq56iJgupF~4sNW`LGFff8F
z3S&{0=A}?71YHo_=Eca2M8Fx0-iSl`q9`z)<5(mFi9qAIwD72J&@U}~#5%1uM}peh
zm#z$yV;~q%Qu0^yu#a$*z!OpgODrwRRUHay>6eV32z==m17kwkFR2cQoe2b_J+|gZ
zm?V5D_sqppAOMvX_7Z12F%lWi5azQe^splos9$<CMzB!gK)n=A)LHwP0Z09+RYp`^
zziOEw|Nju%)US%4!KJC#rZf>G_|+ao)o;Bd5Ng$LT@VPz>bDe#`&5O+7X!GCz~(Z=
zbOpO_S$Gf%)^9#45iLd(u$SVij(`d~NeWrGbrM8m+G;cCET0;;gaeUni^4b+guexf
z8ODeE>K<t2lxYJ(nB5{U+O6ZHxOIg@yk20gG1@JJ{nn{~fWLmrCIrhMz})u0K_b4r
z6kWI|<Q*=Wn^qzODfT;mb#QF-lOxixmq{>UA&FG?VyG9v>|Tne48%LUtup2^NE|=z
zjEd00-1;Lw3WCBGMf}GGC`%%OL>GnOlCTFoR9X>hx(N9YML24gVG$v#3onoo6gNNx
za@|h?4DKPZM}iPy);Olih=_><xM5BRfwv1Hu_(c#{^;63s92ygKBVOMbps$2c%eMz
z6cH_aEMUuvl-0@0yoRu2Kee|In(P&Bgg~hU!bz4R!a0ySG3Yds5YDrrqyzHPNtvKb
z#@^>6GjKu`wVmCRkbtP|037{@?DmQ?V)(bqDu)>HKrv-x_j;?ZcGq8AL%^pId*7pp
z;P*Ty{Jg#@jD6v#HvZ>iCN~nJ;THuiX~t5yEP4#7cLgOe>fX=FKN#Ra<rgD--+?)z
z82<o}<@^SC@Mwl{!35@P>hqaQ;0#?tvVn(HkjV%ESgZ7eV1X%r_r%3R=-Wzra8qs@
z=C<H-xrRA6m*o&S7Kbo)D-pv@=?9^bdO~tUB8L}l22wrT8pV>?AYR}VFmQSSQy{Ix
z3uOZ1c2j9Q=BGH&Adtcm?Tduqn-W~DC2}!7i^3LO_zK9O@xoKUn7ptOkc_jCl$r8^
zq;MC|fqB;E#fLmOG&DWOXQrm-_{^;7<=%4Q2LQ(`kf4#X1L2ZUb0sgiU7BDfJ1h#;
z6Dd)P0v27Ej8boqRkcv8`7=o3Ce*cZv*M5NJ2z&e)K8>$c_qr@Uv9cym`k=u=!RUg
zh3AcK$Vc-^SZ|PpjLym*%8)^?ta4a52`~OqhMZRlIZ(|5lpJRPQtiAl#seBX(am$M
z5M{L}nT(eb<x2iO8cdw7FfJwwdZle6p>R<uO)<XYXvE~aRRSeeuT=simQO)l%!l+=
zS(LHXM<B^#Mz~L!PH$vdE=t?7F@wP2KE$wRvS+SSrBvd&X%nqnBjr>gW7I2$x<}Bp
z!%EAf)78e%k(lbT+#-85K>L{|o146;!V_~~y>h0JC+n3nja*u9+z6fPelZS#!BwlO
z025_9rpP=@WcEfO0({CbOIQF8WC$<9#f0HpMIlTe%h<Op>5-FCo@NKOyKhO+6XL9-
z=!rEGIz+#s?gBZL$AEVl5}8-+Tb6X51HNTR$6UP&_W`y|mUuW`O7r$DO*)^@Q5pi>
z@_O^G{n(+6bZB=BxmpCK(XU6#YBPx*BGTgrkkr14nM1}LS&Xh=I%LPQ;Q31l^j=BR
zNV0b&O*_toUfFO+*7we*3KRMlg(v|X?4*ZtfdZ^n{wVPDy^^Q_E8qeVX9Sk_0%b@&
z-n)|M914|pp$P%#z$>*n9rw=cYWTsu7cj$A7bb86biw<tzznMj2tN)zq8Bj3jb4?C
z8XyphFwkNbej7JIXJTsPUb5E6i$PjP6eJ;T2!%r_t8lZqto($%Sd<TJjQk-YnV7l}
z8v`PuQwA^`F6RKTIt~{mKJYvi0l+F9opjqGSJIj4ojw~>VoBT(hg9(xg0sad_d8uF
z-h(gjkgP&4kobX|WLIuDP*4_u<Cy9-(9Vx2a~4UD-f5a9C`*)-!LL9u=nq=iLuVG8
z1KuAk(9N+43I}$6R|qDtX1vpqNj#cG;R2z0hgVKI4DdlonMv@QD5L|C0XU8;loJ3t
zN00#4W9mh;9#gOU3!E2~%MMF-P;lp@VcRRa9cFCS{&^8PXw?ToD>_JDna-gRSpwih
zEHU&VevvyZvBWrXmr4T^q^MMcs~TotSLi7KmVyHLP7Ed%L3#<IX;Cc0>4@XxbPy5h
zDGDj!hw-LxowhJrdd0L7R%(%mbo8iOZi4`)T1^fZSA`44;zE%bcOA%KOpT&YxlAx+
zvP{%VU|Q}1x&Yo*P>4a6n%^SDSWpes<<KIsmsiq1(7zTXUFHA?^FjdtgqX_<Mw~JC
z(DxFCjK#5DL@7IxgwHs85QYqwgX`RfNi!(;OzK;QE8dqdYwo%Yt}9x=9D}0Zg%5|_
zo{$8|CTw@#0pe2h^e{?m<|1$c52Pw@kK-liIaj1H;ptpuYzSc&l$;cdiw?)%K_omc
z^aEh!x#E=xsOQ2%xVf}?nccv2V!5=Ju>0H@UzzxRQDY7Byt%e|&%w%fxcrU`0(2*a
z9H0i>b${JMwcK8UD)bDDJ3wNW{E3N`((ML_L@&?=z$iMyun%D^y3>l1Rz)vd2PAR2
z>uGs&BkNAQ5q7;Q*1d!b=>-LG=PuTbd2<)*g$lSy_tM^hN$Jje6|j|FcoJzJbk{|T
zN+9lvsv{t#%VkT@OeYEjU^U(KD0q4n?90(64CkR5elLM_dI47e(DRehF<iiI<{5pk
zI^auaqV6&{0ddp|0t2X|pOiZ{GDC2Qcj|IF6BG55lKhj-khrSucQGA0y$f&;_^j?!
zD;_-fTnKzf#U$lOAXs;mJONPbCuL&1xseGt>vEC<l=k?AbmQCOtFUeNcFyM$9@iPq
zUl_VBv=HL#ep1LO0^~Y5g_v^U`MMKBkeI)p6fy>gxl@eD>w);ft|SIx5Pwpx{P+#-
z-I^9DFlW1~>;g?^9~3TSO45Q={%C1*INSluy!}QywM_VQGcmL%WatffNTBF#PQa2b
z)&SV<gFxmHL)*C#cM{o$l>+qACxr~f`X+|<u~Vj|MObaBMmyz0_-J!k?c<A>-<z}|
zU~H#o!$Im>?YG<+2LZ^p&C-6|aX>QPDZREB5(){BUL*pj*9kzB^*SX0#J&?6UQRk~
z2<YzkjrPltMO64t%HT0~d=->@orQ#(cSX_=lU^q%Ve5Iw9)h;7W0&z@byzbVtWI=>
zgXzRSgtX5~fl&OqNr>0K-8RJZuL}vd|3_U~tP4<A9cu^Fb;tq(bz!my!I3vAixku)
z%t8irQM1~Cu5!k6IrB|kjOZ$rfDv7#Hn7wJipvJ2OZ&(pi`ESRM6s$vsVuDgP%2IL
zQgV_rzD$17idb5rR4107DD{dZDoO+EREbJWL#c~W<yZ|v+8(2~Q1=!TDvfw7vG7Le
zky)C9iY6;}lq%Y3%#gYo1we9aWWu9P*plOv<_Sg&>OHDhHGs`lDmLnsxRAkE(xg;%
zmOYU+&yX#5IrJE`RWAYrZ3QJe^?F#~OT8Wzqh&Q2*E@leaJ>_-nj?mr|H5CZPRIZN
zR=tu~e?|`}7O1JW7Q(UWImS9SK{-HR9}fOvAFRlre%rMo)NebX`dFE#o|vrOQ}0k#
z_^G!l%K-5)d#F%QJ$N$!OK)NYVAZ>s0a*36Mg^nei%;^G${f|RJqsb#yPma@>g~^Z
zN*;Dm)?iA>Q(b`B)r$jk_2K|sy<qlZ4JcVKSR$&d9IPXiMi7>nDkBL>QKf+f0*!iA
zu(p80ZV=xLsG`Y+g|T4NIY43`jO}I@4((PaGLvTQhY%Mi<5hMjR{APq70ZE@K?`A5
zW%EMV)ovJL<*~A!p*mR^*jT_U4R9=Q1_NDIFUxbD8PJ_}3fcKsOO2L56k97(AwsY=
zb0X`tmC2Ds-O?n<qHkrfWMQ~8YUaQo2a2U;g*lo=S%a>Or>s*a`|6RE?8*SkVs~Yw
zWkI~M<YvjdGWDXU-fj;@>AlTpoIzP-R%ZFWGCi}zAI#GSNNHBqjYK;Jt=udoScY&G
z9HgoIKuJPZ%00^#mc5;&4a+8v>W5{vM}fqH#(j`F%>Dc}og6swZ+bXf-=>Gd`A|er
z$ITnDiawUNf<+<AqrtL~<@G>m$wQtImY*!Y2}@L#Z-r$n%m0Exmz$3U)iBGC!-ARR
z>S2ggxr4IoX8DT_R^=?O5=(cc*NLS)%PYl@s`6VQrs|Myi$z4s`-M8A<sf4z(sH7)
zS}8nj2S~YSIt(BCDsSBij7nDSbyMlC%MJY)*{_4{$%A7nq>5`}E2fHTLoP`cdOgZ*
z$!f6W+GNF8c|TE8R_;+%orMea0I847&C2q%<%wO@ZRx6gsrs$FxhRl(Y#v`$(Jikq
zEA6_nfU*{E`IcF&7yjoQ8)QLF>W-vLy0Lo}1}--@>jsxAT*ZacSI+9g<x6LMVi%M-
zN*I?v9#xKy^4YT#a=G;#m{#Tb&+^F?9KZt02p~AVstR*O8K6w_7Ky-8&Kat}!p{}S
zfa1`{7Vf~9v#d1#l~tz479qhZ)D=d-=&}g3IKEWPItaO2o$*zQ&RFHID|iFdu@T_$
zr2^W=76rm8+Z8FoGTaqS!fM_Xgraia6{*6S;1$i{3V-4~&pP837K38s#}+%ouq}nx
zcviEj0360+Rg?}2qcf5x*oB%$iuPfFbr;|gi?COS5R0@kjOb7y_X;y&t#^hdu^POq
z9126KD#8h6<&P~4ik0UpQi|2-6-dPb_7!Z!Upy)z%TaTsqP83bRVuQ}Q7omxzZ|7d
zj*1TpzEu2}ql5_q%oejVTB&QA5R0l2=%{2`!EA063kkL&p?C{90JFWy=Pgn$P5ekZ
zE9B0zm`4TWArfkf-17!xn+op>X+HN5KuUat2|9{tR4gI((y;{`I?$^!AaS)E0gV`4
zQ_LfW*A?%0ym$muOr$r4ZPJ$Ljd7c*bKhWTX8`7*6RM&#<6t}YNKOa16~aA(!njR%
z2J#5axJ~GqJa;py)Eh%KCucYnwaOU+s-OZ_7YTu@oaMDezIv8;Ky)k!gYmNm2+0GT
z=M3CZAa2~6r!iU=lp7S}T=Rmiu-~}F#~vEYn;!AQi-KHJ#26nSWe_amJ41a5M)Aez
zG%YfonF=vOo>TYEXzHm>6S3gDRryq?@alMAL@+f>CizH7k~VeU1G(4RX+^jz*4sN{
zy%`X`UVE9Aq=@l&R>tu7s^<GtVds3%GBBMk`ixvZK$+(r-OeX?MZojfjxc#pGMxR?
z;(6pQE7~4rg$l@b?~K^bmIC%MXGcVMMgG&6Qn>*%$|!w+7Mx5kpwTC@4-QZw(L@;v
zG(lAsgZq#Q9xdidaNvUjn;QL4x&%iL=~2!FErpes0sG@o$s06dW^RWgx3h9TmVFh;
zA=v`YTvr}!g_UGN!*Zpe(1u;9Dzu*SDRm@iY&kISb5xoP{V<hF<IW5n)0ZAjQ0Kc>
ziVlU8DLMeJ^o4hTtRF{eDDr|1km47VJmf&RsstlXd!w?F9I;bOTk?S@lXyhue1H*G
znNH4}{)?}FM-IO-rkvqbl~&~d!BgIqGyDGHJKdRYuUsu3%sv}6%}hVjF*}%kmOttk
zn?z%Hj!l}wKoU_UpDj}6jY&F~->wukAIvt>tv?2t)im#cZaQjK$~n{Poay9B!E<Jh
zUxJ}@AaYeM-=c&_G2PDxfL^8)(}Cn0BnTc!iaj%H^^ugOOhac%_>@3E;+dUz1SwNL
zbt}WPT6vC+R9716l9FkTH23(}Qzv~eCsW4<GrN_7xhRo>IXE~7d!=^zWCkYf?u*jK
zmLj?cIoh;~taj#7$_nDl(w@3dnWe3CRfhq$(peWJ8Pm}kdp4{yD_beEj+*tAR_ha4
zY|6#;2}JG6*!8dhS5B|v6U_Q`*n}%B*xw`C@`hdc)>7b<Z;kY0N4m9MEE9Qd%3(en
zM&wF#cBNQL7n`_Ols@gjb(-|EotuVP*scU?odZg+)~$i%tz_>-3H6f+;jSF(k_6^h
zmna~~+QkRlMq`tOiG1~v1?0?)k_D(Y%!7B>wCQ#^l9U{5Td!oGG?RIKQ8cilm9Os;
zl^iRp-x09aF?MKF!US-DyA^JLV~2Kv<1Er$*aOZSY{3&OO2R!z-@sAO>Cs<=Fa{J5
zg6H{BSP2eOd*Lbgd^WrVM}#0i84i&0%d@)R%XpSDNn74VN396~L>xg%m<h<mb#4F?
z&Wvq=P<S4y0IC2X-tUEG;W&y5@xqzdEw7bdM0%i1zyoj;x`qSCz7RMZ5sU)qScK$)
zZJm+}DskcP90(0$5t0wmPA{A_@~Jpb^STp-#xH<C2$#eW8(G*T&OCC#n=DF<hY%?F
zLy6CFZ{1=*f>K$O;E&K&9O>smWLZCibV_2j1SLnLn}ZqYviJw(xeFd9e<(*Zwr+_S
zGq!Gl(=xViC1MN>?}uM5M4R;oP@;u;;}`LEWOG1aj{?tGlvFsnL<7pUAb1ufN7uGq
zF}hZLa&RVlQ2ci(l^1|0x`cvYJF*X41lu{cPATj(Cojs_z>6H3RskF>$~6iC$>HnS
zV3HOofuQstxp1rsYssPI6&{l#GaokIBPqd5nRFf6Vu3$7%9juvYPEB~GS50w`UP>l
zC<z8N)G4?toGQPr4adqaK#mvKmBTqzh**n~&|7`$mgDbRuM`HMZ!J<z0B(*&NboH}
zcr8k>yls7Q{Pg-d0R~iK)vtR)6LZA(7UG!0QC6sAixS8sQGIr`5*tkq3Pc1K^qI%Q
zA%W4HSOo-5JA#zRXmt$aO<{Ek5b;j0iHq=dwB97-!Lgye`9+93S!@uBEWo%RJkN$H
zw<v88cJ2Tr*2n6CD2O|XO5h6t-!59i2!RJmYBW~MPJp{wcHrC9q7&avi%xtyRkvHD
z*hND2^BXWlLjH63APXHZD1Pq{f}WLe3TAK-a%s=4S90QHYYj$FhKsT!Ls`y2SVIvc
z;-bXHD;pmHB2HQ%?i|4ew&)1-E<i>niiAKLgA&8hroWBAk2yhHtYwaapS2()9r5D@
zGr1^>EvMjMo!At@t8~233)9l!uPxk5Py7lYV;(_>;YicN+rKb29c6_IhtmOjA*jwp
zNQ@%^dV;ipema8S3mDX4d03Qzc4CV@#jmzOjj}~P0X1H5rHhi-qx3r@_{LGNrzCCA
zs1B1z!KZrGO)7v@5mdZ)Q4)MsxAYCvdxE(ZK~6CE!T}1K3)z4xD;-W0z47k`tl9C=
zG7UCPiNdc1X~Vd6po|m_Zc(gw6)*C_(<P}ecOAa_!sXp5UBg{yw5$vFK@n#Hj8+)I
zJ7wrgAujh#IIbdH+uTEfgj&2)YN8=kEHHHxMcUEbH{|4O(KPyBzW&p(_WAk#)%O&y
zHs0j->2_YXzYo{1|NI}n{^iTQ&iDW1|NXB&4~N}^)A_l6Ggo!k_5_XDoR8jxYobIJ
zd8MO2im467YeC$sqKyZN+wwZ;EFF9*AQ4W}L-NdG*-C8aRdt#87`dE8GX=s=fG81K
z2(P$EZ;ubD7}3b!8bjPltJ+B;m9|25iqN@UsO&c$*{T-TaNoM-(;9PCnMDH2(Xq@#
zh^{ckIa0gj!@zq5criaz=D;(fU~HD>fi5TLUrwXUscRRe^C4sU!ySA}etg__^S9i1
ze->E6`#YyS)Bad|A`1<<F+cO!FcP7^EGu#JNr&*{@B+Yr5UU#T;7!;c7NJ$>2P`zE
zaw#1S8nZ2nB#wn8U`(%Mx$QmGe?+}sVBe_frC^~il;XO*<cDRD2yn&nBSYxjsAq7~
zJy)2e%y%=y<n<xcL|E+mt-L8K=OS~-D=9pWi6fHh_ITFw4z^ZQG6SG13XJKz^yh=+
z^q{^XTxs3hvhc2Z^E##Krn<8|Sz$^)JFToseEvW{=BI$PYW}uM%9Nu^HlOpmF4y@X
zcR%&aDM|cIM+huD1G@;1Z#yC<7jpeG4#f{a|IOUE9Xh*_@O;+|ap~MNKhyUAv5kJy
zk-M$4qbSd}9a)1Ld-7+TMmy!V9Z_U@Om-w?w(mMF7v#R@e@2MU=PB@;jx1Dut0RvO
z|F&c1OzTYf88+|FQ|6C5>M-i+NXqkVM?^f~%=#I&h>t_;H{E#DVNZzAzS|W{-{X1s
zGn3dh%5OWOV5W6-B<1<G<Cq`k?a#>i{yc$y(~$?Yv7;#0w;h{r=lRbBOxe!&-*n1L
zV6aoR-M;I@s*k)Weg^K==iTv}j#XGWJBl*fw;hrFOklg8fibvKe%p~(n5iQv*S8%}
zwHX)P&%lKJxcUCLo9@TXZX`V4bz_yKyhVQ|1oeKc{$`N4eA9aVbGwcG+pmp}EBa?u
z(bA>;n~uEO2RoAT*tZ=Ca^J|7F+X*J-*ltqaI#yMf$qCS=pX9E&p=oGR5*UqahAsh
z9YLArw;k~mqWbbPUId>C&2KtV?`i5t%Kcr(mJx+gkAA9jV<}93+>v?}Vw`?%npXd|
zW1k=D*H4umD~0Sg9ig`&Aou5{$@#Y(0qo#VNLpBrOWXV7P8X9}*r_qA@S7X=9MT(q
zF5}jwMgFG4t+<h&sdnnU_s1Rl{Ln>zrlaXYJN-?^u166&lJb1p@#-JC?$0gj;QKpW
zO0w>BQNCpgaUrQn|I9GJjq=-$1eTlZsG!>RZO3#+^z4(#AN{*Ohh{(H&of>7_Z)Oo
zrGW1LGa?#39s|GWmQRLxsT<x9{o8IC%)p05>fawPjo&K#ZOA?KvwV)<>X`CT<f|pD
z9qohi+m4Tngy<;B+&aFmy>q>v->>HP9eCaA9X;Gux%hw0^BGMU^Wd#*I!=qy<-ZNn
z_9B!6H%xbTg+!#bxWGMV(IMsBJ{7+4c0Jp-;+DJQxy;nAb}7UGZJELV3*Ii_CKO3N
zDLAUzb!iT4o4ym)Q3f_0JB40#JixBGO*1K@rkVIJ{O)=?)88KY$)%XkjY5u~tl}kW
z8>}#`EK577@t4D}bjd@#QOKoGT!@+z9(L4Xyi80&Eyk<DSc*~+0bv-uPO%Afh_7=C
zJ{ZwH_3f-AM;4)cV}&$LWSP84Y>q5pSF8%TnD@r2q+A=TmSoIp=TxlnoEu|eP3PPg
z6Dv6RJXxU?3$KYxL6&^mVv|tLamud<$fY*rR-9QfdAb;P!GJvb7S<8GoL!tkIma#h
zD9Sl*!AGd(I0Yo-C=b}Ci8ooiaVm^prVpk~d5jUM(x$=)04>#qe8xCe+ZJ$i>5=q`
zNSKh{q4@BLjGQPWNy3?hB>-JOqQA+!tj0Dfq6AglMn#pN@EZ$6zZ99%D%=Pa=SFQ#
z6sjAwIj77j04VURw9rOvP!!}FwJTBUPvtw`l-2rrG0^DPs(m^nMdd&lo>Ub>ee#J>
zQ2}Z2IX0su;vooW_fpIRVedfkyWT1cv}joyD!q*`-;Z(`!{}cTMhN0q6gq&@2T{dK
z908KepRHG{fj?WXRY;cqHP|oPJ50YvkScm)vETRLk(iN}+Ze_vm)jVAuS7Uv;7rWO
zD|Q66>3vqOe6W?<7-f(FA#l7DfYY|XqCEQA7FdKD_D;{S<rIADl3p~W%R7$C2CTAo
zJN`{iGwK~HH=RL8q2?bT<mlVhDfWb$1STrpEAtxxPlDeJzdfrPpIfJpDL=PvIo4BB
zcE-Em;zgMfuQX{#Nzkg`%=j%8d1i=L)q#eZkr*9{6I*;G#v(8Fer;VsHv0AJZQF&J
zr8~6G?e>Wc+2?lu<nYFJ1LgPzQ4?@U^|5sdc6Q%71vk5I*H(_u>n1r8k5;F5j;?R#
zcQUW@26#|Xyw3ZWVpGBi;ssmR1u(Lbd3A|3?R$h_tZC;l_+-WK3Nb`+%YJU>V2<S6
zPvG`!J+f50Muo$*@jtJ{Yxnl|F@$#Sr)ayyUR3mGt)fnGOg1^35c=8LwRH<#D9<w@
zNb`qE0&+VqN_7jtX(a*aC2MV{7Z6ulD;da3VHx}s<Ql8feCrir((0o3WJPC458`WE
zMGsAn7CYp*u{?#m61#kd>;d&J@UwC8z-QWQ>lOmqkp41pT~xm0><QD&HH6E!RS5FB
z1zJTQ!wqhVN|^B88Fhm2FT`i<*}8o?;3f`it4Bpvs5b=&OvFV7pt>Tn^IQCl{7l`{
z@FQDo$oTK^FU+!8ZAKibR+|we<E<1h9HNTnN&Tp8;XH^{Z>DP*^{<<0B>*-;?E9pI
zD4A-}dsI9N1bxNH$Br^4hv59H48QRtbpONn{hVTD^Z~~e;QvX88CH1DfNovkJtzYn
zmM(A}ps{aCv{2BzlJyWO9yJb>l#m}%5iUpccvF7fz(I9Zst7d9vr<J+WfvhpN0Rbm
za54|*f~Rh6D1ogK@Zc0!6pAVI!ge}&1I_K!V~e)nQ$e37S;%@8Ny+o(>}ckPbb^l&
ztx8kLkCe3FP{~ZZBPm0rI<g&-epY@7j*zp2CCs_)R4xe)h_LfN%DQ>~%O1U@Gtk{0
zc~l3y36IWg*tL(SWuio(5r4u7<bG#Gl%#~W?YWeHbgeF`rL!pE9ebp)p`58z7!hEi
z?a`5pimaAcjhWyEH^!qFZYZdWQh8Zxs8RVPX9dK(Md3CEYMoWgPlkQSzRt8UW8E9#
zLYk5X4<el{64U3xuT$|pfFq0QHA+y6-@S=e10=B{NJ^AT%QohiOj;CvX5vS5ze3YR
zF`fgY5&jouxkd1m?WusVCu~axOnHs!LFxJ@9Icg&$n%-ID9m#6{AK3&{A0vLRv121
zmnccmsqzf-H)}mY9=06AJhSYs&`*H(S>+g}PG-03%U3zD9#WQk-YQZ??767<bbhSc
zN2+16T*(4JfJ42h*VpDW@A&UIrxL`OQ?A6rsUlcd!}zFa=is?wTiRhNt+r(yBB*K0
zI&_Q-`Q}LqQDyF-7Li8?*079m?pbpTLr1AbyOd>uv<Vh3OG=FGl1Tv8^hM$L0S&`C
zX-NvUUD6K$xn-9Q8HZPwCOn{Nt#&2%u4TPS<}7EV`^J+&R;h`28X0TN9SUM%8M+q%
ztAfG-pO}@RP=Q7j<?isL=-338l2UpyYEdvxq+i%YbOS^byb0M_wFaq-<Xg!uNl(Uj
zSsCo$aIlNv3xw*oOQ`6P`h6w|3)yo#Rt7g9LfX_dz_5W?r#eb{SY`ipobyu*?y0u1
z5avq&H&LV$BWigR8k750NJF%c_a7(o?A2^TB}rcq?GZ1Ws9SoH6w*Fr0YwQGD_a`U
z5m-g_m54GSnp3wx!;YTXe|TuvR3s>J6s(f{SO+^Q$KsC|q@vrmZQgzTbckMA)Ebhg
zO(}eiXAKMZzJyR?Wo2tPHHIuLiANLeb|EgH{_rdC7_PyB#n}#KRmNXSgNGrn6@U>T
z@<W$8P+}txXOPkvh@iiTt%JhO@k0&c*Ym73j9+oz0GC-53^9Hq{*{_kRI>(W4a3*Y
z11_$WRS)HgqSp3FN(S>)(jby5qS7};2I(Do%^8GOX@nNiJG$=S479Q`_5oAI$|7h`
zM}{;<!_77X^-owC7HEGZ7D|kd7C~Uh*boSb;UYui!7D0HWyyJbIuDT{Ni|$sWiT`d
zctvsAVDv4o4?N{;$nKAqoVi|)z>6_gLPCZY8MT9?#MfQVNhE0)z6_}odU3eZ8TN}Q
zp&XeB+xJb17JstkXKys}_hp2%-2Mi<+2DODeO7smaQ|CbArmtwDEun!3Amuw51j}y
zay@<VI5UBl0>vmO7%-5I-jrx1;DZS%l&~o#WKcSGja3N<sI&-JAONKtR;J5DW-{S=
zItt^N7i1LTvIN`7>VoElw{vo(<&!$G($a-aF0_v5lM9_kbZ`szP+3CHirFKaQ$B0T
zG<r6S*_4uqv<@qK>52PH*_S77GnW>XPc#z_rV|9+gnH?Cq%8_(abm~?N_Aq$g-Lbh
zY3$3~MqDu~{7S@xTjxe0HklP%<&!-K@{Tv06*48BaHcBve-PvRO!6+~oRu?^d3<XU
z=dC6kP;h5XXk>ev?!tYEi{1RxXB<1@{3<{?>yJK>Nmo{QolnZ!q9j@+ayqQQIRS@f
z1<v{4+URV>PE)a*1q73)Ru^VDfcT8qn}F)G0^h`QkFlPB`}1ThaVGKLv%=d1aG-U8
zVc&SEcA?(^f6&tCeS8U{Fi4rPaEDRdWCbVE;mRKX&>oNwjUoSumKd`Tp5~qLheFfD
zBhU&@^Tzqmg#vwNrNR}ph)DtO(PT;|CZqu?lc<rlVP!h_H=w8!e9|_oOh>N*%k*dw
z%MpsjhLedp5LQ5$@o#<<!LcgFMW{{dE=FR*ca<&&W~Xg9nJ`mqIGKh8B24DVF8nmG
zi)@3*Jk^Ks@lYC+JIt6N>(mkeXL<w)A4i(yq7cRQRyP1BUX+GLtk@KW!wNg|N@-~L
zcmBP=h%ZWl5wbSy5nabAVPLHbco^x!R#2J%leNOqL@Kj&xu`mxOV&^E!O=~bD9FyX
zLf1r!w-I6U5X8$OaYS9+h#1?{jU#I6r4ccD_|b^cdc7!Q5S}^mk90h^jL@8iu!AE$
zJO1QUCvxaiC!ilc>VkzzAmd|^(99l!@<hl;B_|Ov+2o7~%op@RXas?m7YXcw=gH);
z>2NHW06!5&u?SE}2?K5N>;Nk|f~Yw}92!lv1b{cqK<ncrQ0gG%7C{P_HGmPr`C<hX
z3i#_v)jIwlX9w>+YdZR7wm8f53tMA~*aUR8HD$9*9QaKr!ZU@+3LF$(0F#fY52O^E
z@IsZ3)`VjZuoe@9Xn?h>!=mW~O{|vup&TRLb*4o3KyN`WqN2wQVy$56xqL3%)WPKw
zEd69BPGYDNLFtG3474Ng%37h)bLn&*4_7D5fNNJM^{MI|)^tJ#N|ZInzcUN3fa>vV
zRHA-I@Px_v)@hn<1ypb9#R-{u4YcF5Zk_hQmA<wP`KCi2;4DVm)F>T*PMA-^vzQ!x
zfM;2Z>S)IG({u&UCN1>Uj<O>r-(Zi)G+ItN@Xt)}teu9-rYi!qp$wIAJ02`XV1gq^
zvFw7iM^OiByhQL^u||lr4r{VJlAUG97Kt??xa<urW?XQ_Q16@W9_KO(2;aHP^mum~
z2ODiNi;~<IG`{2FZpN2or}a;WvK<<2P{3a3agAX4G~&UDdb|`TYK>25f~dSHXeFz3
zrzLE=H391Pi>#8C-Fg1%-s?Pn5o^~0pl$+xSd{!-){ubmW=$acwDvWjQTGA%L3@W9
zw%R}oThJ(1{xIvUK!F#^M5oPgqjYfd)Nu^0$Qog;p~{%xc{?z^t)1c~EW1re*d5N{
zPg1fp8hCOE;<sl`jtM%OnPetBtxlt(oZE{Mj4{2#fYG^A@Tjs!dk}Y@Dfapw@<iW+
zy}^tqy$l);_>F`U-c&gUH=_w+qbFGDPRJAfFhL1-fTHdcXljOgHNaE$mSJ$*H^5H;
z2^7cRSUL$$x{U&9NDSixB(en}^F9g9RIrCOzKvqyLds7A==ujG_KgWI91HqM;dmi+
z01ZBN(xm}I5COpZN#O|5>%3t@`5=+y_&#kh8)b^8IgN9Qfp{gI;Y{0@L7U1(@twz@
zh=plF>F{rFO9TJ*Ck2v(6+WRVo8Wk(oEttr@F$Y2Xj{ouN?O30f41{MQxbcg;zLpV
zQ}EAItU-eE^Q6W1gYrve_Omx?$039Nxy2_q$QI@W`Gi#Zr*>Q(Bkj?SL-I86>q$A1
zlzh7J2g#+X4#@piwE%Mm?rrd?iUV>FRw+R4L6rjJ7OYZ$|CpUl%gsi?^PIsti;%Mx
zAi|TLL7Uvk4eoa{S~?q3X-!3*QJcU3N8V_zA=poXa^&w$OdQ&psZ8brZOv2``hm8_
z^uR?3tK*_@byHn470!H4b>d1=sH$*g8e>ALuvGV>9fx(e?>Z!MJn+D4C$H2B3LDvV
zU$raq^KguF^ECL|YqPX0q){8=Xf(c*)B|j{1pOY`lVHW|+Lf63?UJsqtcfbg%2faw
z$0mJumuO**Fs3BZ`T<h%iZ99rV~U}^HBBj|`quDQ8=<DMVC=+p!Hl4gnZP&hGg~<u
z;N)6>SFKjZoes-fyP%s1+P_^q4O9~Qy44LLe_iU;Sz4E;fr?~bI1N-I`{HRpvu(Sk
zI^m_;uE}1Q&^6SHlj6EkpJ_CmPysq3ZG_q&C+1QibD3y4kw(_8u1+b5Q4{%7WsF3U
z4?Qz;`${!!S5qJCunQ<hrS&q8#DrePJQ7nxBJxP2Zm%}`P_V93oxu0`uoL)>{3C0`
z-E8xbu73^Ix2CR-A;Y&_&yj{?kb1y0MCj_3a|DTRvK%w=B<l6l5KU{X3T{tzLO@zW
zqCq{~nxFtwaC_AA@4=to`Pill5CBe>2He&l<+@GJM{BOy?CQc{b@d=C`?0;2BNGMh
zXAG&S2ZuxhifUx11tnkd$)bM*MS+VO#t2Y$b444pS`F>x0e5GkUo63N!c>w|9G5y_
ziest|uN_%EhDI~h4HAy%z%uzX**&JV;NY%QIcZrwba~41p^H(bkGcrqaW=&@FABSH
zM5&`SU08tLUgj^tw7{WkLRxGI>TL?DUWp;>#qpRr;Q$y3m~X7yvl2t{NhaM0IOW!E
zwDJ+BE5m6HyP?lEV53{3Pc|}1&<oOs9uPj{l5D_Be$zHbpH_3&OLOE5$fHTMId?0q
zuFbh!;aO@v)rTKOh)2^I?Ngoj-Bi!JQf3<bw`E?A#F8_u+x$56xSntC#we_Q>Iy{N
z#xj66@9M;lcNpY3Z92zzj%ISnk@k3So3?IRO&UY0Xy<Q$tF=zp+6EVD_zrL+BC4u4
z&5{l>oqr6W>J77mc;xFpnSO4rj@IcK>u9AjjkdH!p{s_VTz9&_yUwzHm#Ze{*KfI9
za(<m|F^2pu%IbcYGUOM@;A=`=((KY{-)w1i>5MLEo$e5a(W-Si$_Q`QdO6C#$gGx|
zez9nmqYQSr*2`1IPvMMb`MO3sj4IqQ|HPC5b3_8llO95R3mTpBW*QcwT!yVvJft*t
zqg1JSJR`p7uWT^PbR939;-TZE(|=lzuTKAIe&<YgYc77HaL_Z+8vUkFEgK5Em0!0t
zddlehZ5c(@iJISlVO#Fw2A4&+n4$F1=prcP24{mYMe0|0ug0)44UR!&T?ZTEytcv3
z_{C%)?j?)^6newq!D)?Wi_R$8X~M}4lp2K`w7iSUP2cj8Pd7bg0&PI}(~H8G2>uKr
zXG}i>V{BF>JwP%9TW~cPP@{td%9}ZZ?;4D-=Exg-MJ7sy4M_iK45*=1y)pbs;V8^a
zu}r^PIUo$Mk<MZau+gqJ2H3cM2B!xy{~ApN=2BuTL42gL;8kd<AKdWZG?gK4c-xvQ
zh`HHha1R#3@@^4AdJBL(Q$^<nq}z%;T1hY|WeQMYri?||YG%opOEoZ@9IC3_fPHJ}
zRX9KzL4cqFpUG5zycwfyv;&O6HrN5oo-vh*XZDP#-hETdmELJa5z*D11=kYA2h&D;
z89t2H<2cb`99!-yBb=BF-H}c++7|1!D2!u+umCN$LgpH3WEnyIkI1KqC_24K&Nyxc
zgOXaJ=UPtWyc7VKLpv|V9_q<(UJ3x@&=^9h?ZB9>q3v)^T-bxYs)piMHl*aA3?c0r
zT}s@b>n*cwEXuANXfuE^2aL;#07#9t$f4Z;L|z-z){n*rFU57XlR>2Pkuv*+0isD!
z5Gj<TlToDF5<<q(mY~6M$P9Eci1gCU$f&O&xKBiV4OwE+jH!(E)sB_SvE>7HJzfs9
zQ|M^G0LHJWD#yyd$v>gL;8#S*BS|?yL5x0lF-<y3jP}XN!+23L+8S!xO9?hM8Ed*I
z@zaxTMk8?Q?D`?t2~j!acrgnnNbJTS@u3l6?IuGR7p3EGCZ`5vbq-Ap7lwcu?1ABb
z^0Zo%jMkQ=^-YQZb^bxF#LPoyH6u!#|1D$Aam6zE#u#6bq#Qes6GQzj6O@H9I_u&s
z$|N1TPC<7fOUEu6M<Pon{z%ZSH^cm?p0BK&%mfg!gWVUy`yn|Q#6=K~XvZokBVbW7
z+#e<cy8+3N2?fmSv5U85q~FBYcsfK1jwgkT7)ow1P7*rG<>Ew~7=kxJN{(IBfEOXh
zrt^S+wkAMZ!pzw<I04*S*F-DFHZ}gvbdsqFKmop{79eghp}inuXA#JKC_2|w+=oJZ
zU1C38*Vj!cf*BNrx0uOe7ay#L-Aq$?BtuA3dBiwV8Vy+oRp`>@ziH&YPc8nb9G`(U
z6MQZbGQ-F8>D&{yjB5rc`bsY{K-!xspK)BK>S#;>vOwE@Wlm6t^G&g1pxUhy<zn&{
zZA*4BcZ;vF!>-ES;-{FIr85TA7#0PK#|XBYcgO}u$h4DRFm^#f8W^Mm5)|LU5Se~)
zOF)r3q+B;hYNfFmt+&ddW8x6<><*BUV>;k2NdA3mrno@wTQfzT-A!w<(V%<NbZsb+
z!t*RCDF_8u-771xekju&Ax;dIduWC*RD-d{G(g<20!5ExrI_kN-QQ>{e$XY;F!7Uc
z?>xGkE*c!3roqCF{B*Gjj)O-h6oc&^*Vs;GvbvTIuHwhJba-_>e3KhP@}8m9JoA3U
zsW6#<D#1drHhb{4jyolqIF0~nMKsUAWqy<~izxxff;qGX2&c-jHGo!BCaxur((zTv
zx(1L6d!T;UWEQK=A6%gJ=m44w5G^QjU=!K%XqtebIO$8UtZfw(EFOR-j;87dMv$P>
zG*e&#ohAkWZsMeA-T?0t>KV4;ocNmVI%4;nO)MJtSQm?sM;<yPMl_Is-N~YXlz3fb
zz<Q!i`%3Wk_?yAUDe~8XM5ehi)5$bf4m_FWN`e>Ew<`;tOzX<Hhe#pa`x47KSavaQ
z(Fh1}N+Tj5#EI*PfDkI^YYPzK6b$)n8=?RR#1kNgi3lMjREQ9#)`fr&C#+!voo%Xm
z{H8>UOM>bbETtU!>-w;2rdZ)aw5?ZuxoMS%5z)79`DNWh(+CPdob`mJaI^xJq9g&h
zJ3^f>6e3Jiiq%Ru0Krxm3ive}TbB<+TSFDVCQq{=!t`iz5u4B{E=`Z<6!+FG;3@8H
zygA={n_-wl&;##@rs6-A^%<L@m*QP=1}q3#?<aRtn3oZ!Lf%2k`h%_U14JEBhiJ|8
zpG9)x8bQndn80*ZCIN|#O>VJxTP;%*{+)O$T`CMJ88$hsm<QP+aMTE9p<q-apheT7
zj!WP#XeI#5*t#V0%h<XAiUzG@%B*oE3R|07kHo~evb90o7;!HIhhqVCwnlWLm0Y>E
z9yy|W>yaa>#TG~p4Vp$|jP`8Z5-sSgZfTHBImA1>;Dao2>W{GXvJ0Ry<ZcMcnLtG-
zU@!t<scl^nVX4*NfS24`^+{|a9q40Vv^vj+V|;n_A0V9x)r2!?;ILLoNl?zjfZ|U(
zAfO!D=)mdS$JQwaNK1slnU^jBwAVs)y*<*Va-?Gc3<Sh=$7PSu=ceo-1HOlHj+lYE
zD15M@lI0@d-iUbVMmw?r0fZ>Ppu~r$35K002CNc;$Xu0QCn(|e!2t*J6MaK3X0{$d
zVwc1c5;&?20?O6C#$Dnatr3na?H^n$-X(Xa8KewG0~Sg1+S{mC<jO8*25s}Pb;}v*
z2@yX_jeZoq97O|;kLFVnl?X;Mx7r}&+_m+}DPLQsh!$*uNe)stHYreqpu?p-2tZe5
zK5)xrhU@`SpwiVs<KC+ZHLzYbT0;#8f%N3Qj<0{LF~TJh1|h5M6iy))PRY$!w{&Wo
zRyyV|`j4?M+mI<K4WV?6Z|j)u^N)2LvM69!jY;8J*fAuUfDar)W+N`|kWz-~*lpBV
zZG@@pVtTR$2lP?PJ9Hhxlirk?zf&Yz$v?WR4@kgxHX%uD%V(33ME%s`pHeZ;ZN(FA
zQIG?%<ZH~+Hg1se=wrdu**0c`se!Q{K~ktlwYVvv+|1gPP^nV+JxCe}nF=<LP^T|+
zB2|U9OuA@L;a^8l>hw*usm(fVNvXpYDx9iXA3KSxg0eMf+8F__C_oIhOKU=wU*Xys
zazYCEcBg3Cv1|g=CFLm8T|+PhLaII}ZJT%-h|BtD-o^1)X`%%0gh$_rr5FBiQPd*@
z;TqelW5Wp(nd$!Rn%iKLQg_!$z~+O^+c(a~pWmYfngl7w|5)kB5iq|ZG)Mi>Vr>~Y
zNO^R#0S=%E!3mTjqDZmQsE6F1_Sqs2;$Ut9mttFR4?$QHc%-6;BI^XO3R)Q_HVT~L
zhWHo61OGx9Y_COq#>SazDC~F%dr^v0vD2QpaVjZ%Z{o6H1hgoJ!lXe8ZmO~sym^eb
z-YMDRVWf7>4|txBwh$-``A*9E7sJ9|au6bPoIkW?+l836QwG`#tGz4?h&^Hy`zyVQ
zYl#`?jz4;CMZ@nDZYxK1YhlJMO4QiYKEtid*!-l-n3NtMK*U(}5zva!kDXT}6|WZ9
z{W-Nw3Ld^|w0F#CA_|ff>mnmT!+l}`rKFtE`rOWu)u6K{&V^390*;Mdb_E<Z{d~4l
zIQd;F3Tl;}&wgkHckQgRAh>Ji)+=kEejeQ2th&rB<XX30zFZdN*{_zU(yCbo@2qVH
zexxII>)SQgZNCP))isFPrRJM55Rz*uOv>xGo0m4wvX*VBjKL-wn>LU<;Unarg3xVl
zO5?~fx|`C`ZEh-Kh?iZP0<oT#T><BGRd>6#ULihqZ@rQWDoKd{t`$Tva(hZ63)!$|
zdo0A9pY5p-g1{){R77La?c5#<Q5%u}9$7ZIwEmc%as;8ut}4je3nf#G)FpO;3SSry
zyL*%M2rr?YnV@`h#e5hL`wvC;=w|PVhvh>}Ri}?HKIf`7HGT0_yP7aWtZw~&NM`bu
zo}zK#RE2E5Jy}CLz4u#@ZK5AlA?`)V(O-2v`;W2J^X5ajYJT%EU3J0v;O@*zKfd@Z
zSAp>b)>P%k`Hrs=<$UX_hB>SO$5!Z^HiIgLPBTMQP^T$^X@p6+^M_jfbPP^~+Lz6v
z3c1rJ(iLw=y9o-y)07f>wfC)C4$rr4Aq>4tP5H(^d3yfPwU@AG#6ncLSFe!GPHR&R
zuU;@$z6BSl%uPAGi>(;iwROp%U0aVF+D!vi4D0^IZq|Eg#jBN5zcD2Fp$5v33&X~M
zJ=^_6D@4!Ftw*e-pIeVuOE;SOf-jpbBK3<!VHYS2PGe;(+h&JA)sem#B5;R$tv{}8
z?_0MViSGG)o*hA|ZaEsQKY}&7keX;7?ur_d4H+5LNf}DHe#r{mg=P;!b@y34k~5oI
z!J^3ysGIF_Dd48@@+sh^@oVc8r$YDgDH!;0Z{1?=mw^JW%Pt5nK<phsqGw?pO@am^
zEMFhz=8YK9mMdb7f0Wh-w7))V>k=OxdP~hT9CleW5=F4npm8YZrH^tf^dI>r>XM%>
zuL92M(YG$Ko4b(W47ES{aJ1sP<ylCzppWt_r2D9kfCZ+1sgLq3q!X%_bz_cbQIPWL
z0Eokjo~=VT4@nw=f_Q!XL4{bPvvk%e#!I@7t2lpwW#x*z;%9I1{lehohrBR$8mAAN
zcLHL_bD4wJV*q7f`aIDZiMuiA{EStZN`9x$w5#w5y{Ze-L%!Kqlro9HJKKR#ek3W*
zgQ<WA6g239lVp@ouOO<4%?~eI_|&ocCxg@tB^mmpwt$4EK0h4SF)_i@8VW@8DSzYz
zb#&&BU~^B2%7xuMb%QL-nj;7dh=5KwDJ`%!5Yy!q&iY=a6<8noL?z!O<r3-ffRKPb
zFHSJ^t3G8VLu5fm{uP1`LguEN8Hicv^CPYyn7PL_<bWS7-Q|MSd1buP8u7)L2IxOm
z#WY~gl|kl$;kZ|57DAZ%RWS|FUM_`qtZ`fw*O2P_qVPBdoGd|zk`i0us<?)H%LSMb
z+OhQ*iIq`Kaco>AFX=t+mutM&!dl9IfdRZ(5Il1bo#~|r8zML*WnC^p$z@nhXK^e-
z_b%)xT0Kyat6wsiUU&YC^b4e7_KK(ia&U*O=y)kEsxzkQ%4hENXujBI!Xb{BsQ48f
z9XGF3p&2hybh|4m54+~BsJwho5cTWDxTqsY{B3NLJAb4Fkl05&*dp*7xVDf%dn75A
z{nq7y;In?~?#TGGuE?kiU|TS0_z)b}i&8;vA*8on6acgC6*`4jx?Z7EH_Yo@u~U{+
zu&bV?-6Npj7<L9V{l+5$zqQ)%_T#5|8Swt0=(ybz@N(J6*;W7_O3Vi)ox&937`ZEk
z4>#8>fy006w<PXH4t4<IDb6zF^p-sXV0i@ATa-ImT#P%1m-30fT0ngmJ#^GEMIt7&
z-+Lr!h#FDg4+WR@r$R|_$&|ekKd>l_i-k4jG3KKN*8G_y3_n7+dPQJmWNc4^=3{}3
zm}5s!Z2%`8AjIq*xpVL{{gL*QD2hSBafkTb{?y~>!B%)GTDW0)I=O%d5a^JKC^q~J
zFLi_z_cDSa>Z?B$WbELIjAOt{SooHJF|j8KQsMwx*3dx6Y;5Kv89WS~2S0X!DUUK!
z&OA+Au}2JW@~8{3TKV6ZdUgiO{d6=Ie#HVj&HvZ~{FGt-(Pu%ZGDbe9=V!&p=kz>H
zeG1Tj^U2SOf6oKmRi&c=WW>*kZO`k(&q~EQ^98veXHWgn{Uk-%3OQFKc))h(r-I(E
zJfB>JM^-HnmpKsG5R1S$=Jl~Coa2o-%09@v3s>|}<Yufnn$nt(zu__&vSiAlaE>aM
zs?>CZFFEaqRjgN;A!hYEscu9X%agsBw9@oDOj=0=$Yqag))Qhl1&3h8u3)D~x`}x*
zJ;ZVsEkd?)54l308mx?-**M2n<^L=+WDYLhoGv3K6N!kSoRnaD1VpWnrMTc12s4H<
z!Et&n8t^+@F;dKWS`?-YrNkUAQ)dITj4N`gC5(mJz$9<1w$h@~(coD|=m06dU8zzx
zzFo;u4;GvEO9O-hps$Y?tA;OR>_{>T*lcD6p7^TLq=1y*!sbv>B`@F&U>ta&Y$Of=
zLA_rQ-jtIQ8V1mh76tHp5d#$;deF+5DNhjfi3^b;Ane>KSrJ7WTp(AhRON!wVqlaD
zHUe=`PC&4rg!kNKkZp-Y=!FRZTq#1WzasQ0SkRP%4D5VwR(XucL?;@Z(lA|E2~6g6
zf$JgTllbxnNcr2TJg+2DFO&kHfO?@6z^dp1Dd@nKBKrL+f|r8BiWG}{*Jv|yxnUrJ
zBmfetH#u(*&*ZJLc=Iw{l#BVexdtCuyurLlm7&4V=mjo-(#nM`fShDk)LBG4#V=Ep
zIwIsLembN*kb7C4;H79MFUWw7YXeA}EVg&JqSaWE&kG=+Us0)nxy~2ZFZ?2y9laHV
zOusNc;Q=IYo-4);;ZH#!pRnH%^|m%MGJ0Jg06prPH>J}eXVztoX8FTKK`K1_`z`}@
z%RE_EoLmE-pjX1b>a8nP5E$32pp8$hiEo+tOJDOXFF$+xM;d;}R7TGoAjN2SMK}%=
z0RcC_sJp;|8^G6{^#-GAWi+v9uy=aq;R6NU1!UY{>U5zUw={JgS;QQK*j7SJZYW0M
zLRD^Q==4g%N0l4YsXsspxm6lI%eYq>ew0b_O2bDimaArC#91Y?brT^N%lkkpyC`E9
zWuIKu_{JCkS7=~MpSt&<C4*)nVC)7@u?sw#rBvUdu#EUDw(7mWLryGMfrp$}umTUs
z9!Sb-hy(Ioz#-6E6oA;`zhC(;EUz~E03w4ce;-~jS0PT8wsql_H#oFhu7ie%#>2ZV
z!1O+O7gpM!Wav~tuBa=_5s_TpZ)w^vb}kZGFw~29C6m1h&xM_0_a!N%P#S3l=(+&&
z8$2SeM0_|rT$u9*QE9xVA-kc%o)<s>;+tIn0q{Y%;O<dTIcg1|89h{km4RL^1bqg2
zdFAgT&dYgHy&|lO-7uK6;3ow?Wa@^6f|=9(l%fqgr>hpiqGUH|x)a(53n(lCJ9RJ}
zi42RBf8y%H0lGSIfUZ8gumBG2UPw(iFuahO2D&v3Fr~tU(=^HT9jJ+&@=q>y;qaiH
zsB8se#@w4;6B#t-g;Ic29run_$ZKI1WEyG^@T0(W@Io<wIXNi#tFRqA$_h6aid`<L
z2CJ~U@*5fq!6@Ga3cC?*tVOY}_*Wh$im;6cvm*<Noh01&6LwFn%zdCWvLqSCgr|!S
zT8#-y=Ja<FxXcSB;i3@e$i0R-4cznBP&YDQs2h>XAOr$-g1MCS@&ZY1f^9TU0ol!c
ziVc(l9o8^nx+~I(Fmf!{_Y%~ct0GLh9@T|=C0^agpCyDGaAjFa?iCPtaZ$L=_&eid
zys#cJ=`#q)K$Iznl5_+(Oxunp9t6you5jgr;1@Ta7usQC55fQ-DVF8&UWpADQ!H%5
zlmG$1+?0Szcvm+iKrg79BA_efrU-1{h7;pM9$kY$kv0Ba0h^d>aHEy{*OhZ$suB1~
zV8+nS<lqeW#u%Eg4)F{vd<*1bx(kpdi*z_Og_ocsofsHEmvs3}7X^L50vHEfCDae%
zR<c@U{!uOfO)anlvRq<P@^=Y-iQsjX!F(mqW=!%yD|s($oQJ2q?#8F*j(D_-VVHAy
zc^4&DgZJm-SPbDRK6qLp)-Lc;2RJ2|4;c2`rLe=W=dPFTGu3M(tEM`E!D;OC0t<OA
zFjzJwSoU01?iU5j;`RO9<W&*KE^_=9yU6p0?BbP*GOVtM{PsLz7f`E_Tj_ycvRc6_
zRn$sFdvE6HF$A4`<}K>-qIck1d{R=K9V&y7_Q;)(SCunaU=e~*L&Y@Cyih<%#Nu?f
z`4A*{7&v_hMjRD-cM6X6!em*bfgwBif@2-Q06nWz?ahhN4shoBA!d=Z%SJ~%txpO?
zY=W7OL=47?MWT?U1Vv=xFYOyYoD$V(HYDYUC__j`B7$4jt^mO|@nY28Ck3jEz{~BH
z#EBq*%U%HD{G{YdUSFn7X(v$HF`+b=d=h5utAzR<+WBA%GUqn_q6Wt&g=>Ilw2s>E
z+d`rK2X}tNrQz#rb5BEj(tLD$kYE$k5fh<lzqGlK5axc0HLzIpeu_ER7X8#}=g!G@
z|3~}t*gSgQo4q%&1v?hc^*W6^?MEM!+|@e7d&1sf!pM%R7Vniu6y7T^Zg-lAbd&Tn
z6@9dmM=Cx8Bs^VDy-Vp<IhszToA+GrP`7r%<W-3I0rsUX(B7$Tp>$Wjb=h;85AWn`
zfw8)!J8%c<CSS2<pSOL)r(w9cf;7)~mBDcnKd~Ne;wP2^50lbWdb~PZ;Z{fYCQS((
z_AW&U92P~@X*~6<sSkBtVKbVgZRdAbmBU?iy}Z<Ier8Bbo~$)8q$XogoXVEU**Fz0
zlmi3&rn@i=S+XQZ_|~mI!X9uQ#;OoT0}GS*4%Soo%6A9Kt+-dY8>&+@{q#X?N_E8;
zP3FRMV>B7dUMJ=MXYFlzcFS??u=)NKXL#@6-bmC3scC@NKr#qy-;9DxY}f&U?tvW`
zN&bBvk!!8}R=Mk~s?$aR-LH5aZGCKQk)jqC>%kcH;;Ur>98(P(#K$sJ!KzyCp$TJN
ze2q#_wz$zwI(*0C@%hb&gS~g6P&M9^IDC(9N}S5Nb|uL0!x#Hz#98mD5hL8cIBAZx
zb!6n1v-}6MJ!c7TQ0Z`7HL!^-l+XgazI8+%i|^Ys625O`zFB<T#*yHSi&XRizgP+D
zaW_@Mp0FEhVO!YzoXa`(l&BVplHKgiS{T6QVTq-xK#%R%#+5}k27zI(tAn_(*Bvr|
zETqFEVPUAlna?E2QxI6@$&w#t?4>%G`@K*Ft7tFo5K2+A_v-}0bJM%}CVd1D>~$_N
zLD-cnW)+i@3e(`K#O{VFac)DkI@6QAJ~a04*G@E~Mtl8ign=>d_I;7w=;FhA00qo^
z(`bS@W(v4`VP5nLLO~<n+v_T1PPkc_Cf(?NMBjjdn}ceQk$F?t=~0n+lZhw6zcq*S
z6|&q-QHwGY-Yjm^2O?I(%cbjNC;=N?C-Th_{RIc^0}-onuC}UiuC}VNM_aWJi=6oc
zQLX7g<#OL&9$jvCC1nFQ7kuA*5UXLO6fkXy*fw!vaMoj;fK-Y}&Yu#|S&x~2o%QU`
z>#XPGA6BZ5s+=&-mz#n?FU;T%Hm)Zy?ZN9ICRYnO>!%JBfR#-#6<k=^{6!v1R>2$q
zQO2C@S2F7Qh0W>?hi^OHdmPL_y!SZOv#B~XZR5SiVaxA54qJw|Ub}X1U72P-xUQ6;
zEb7`uxyF!qbc#_rL0(hWT|bb~v=)PQ*x=O-vs4BbgLYFoYTh)JQMA!aOaGSyX*FKi
zp?_Qq{P%i8Z$8|XC7MNtw>COzB0uaDhsHQxZwZ-W_Pt3&7TT}3jmTB|-bezpHBF}_
zx^3)D2@EqMFFvbtLsy~LxlUS(_T~hJ#(5J+9wG#S!~o3SJKuDX#i2D#dlTI_CKDJO
zTGMFoK1?M%-&By`(VB1GM-Wy{5!7GF#{F|O_6)?XPI2E4K(?m%@kdf=-7@A6>&284
zx0tk^x=_cg<M60#kVT|5O<N9#wBDO~re>b@n#v&3dT;!h<9Uiw205T#-~bax6I}4T
z*`;6n0a8$Z!6+b0^%d0QTufRAumOhTY{Vq+#`VI~rm{X<nA!lqq9$S@o^>jh#B77`
zi17o-x^upj)xMlP;_aD4q%l!O<_QO|qrZ8=3pc>edN#iPvVe$Zn+o=ugrk`-kW6+y
zm3*X9q^E#G#81R?#GL6@vQRG9ySR~Ns|p<hBG?F8{R#?^6KVx!%9|L67`Lf(Is~gt
z#a>Qi8k<Vw#eDO#3v8btvs0)g3=%BLFV<;-9qYwIO+>VQ0ZjoTmLg1r0B1atO;AC<
zc&#bS*`!Z%3UoI0AY#t6JbUQ~#l;r9Yj)y76B1TUDd~I%;G}Cg3U#LC2p;X3;klTT
z0?}bP(reb0Uq0!&bBZuo*b%yt%L{VW-!bBF+PlWcWq=hb#97zm5pkxp>Qj(2su3<k
zzWcx2#ae6QpaeV^^#&I6lS>LK010@mq?RO-Qch5~5qmWo&D#kouGy3$iC^DT0QW?i
zPcHeA5aY=Xme;t+4RUve*<5|YrqYNK;)av>Q<RBNtsTOE|F{w?7oyV|@4C1dzDU>H
zF;7YGY7I$gXQP{Bf<u2cZrs?gzu;;=+q`zEzfcLxwrJZznY>utN%tg>ywh+3N}Mmz
zP_qs7o#);*^giIW5@{iUO1Wz<N~)*!<u|q9n|4lEIaiMiNwT~2{eKK9X`;Urawhd6
z+!nyv6zch+R0atlXoG(QSt2}oqcjs9E&Vr<^!|#l4d67AFm60QfDqSY;%o$K<AEsf
zBMt!(TxV$9MAB>j7(~*`oF%q`CemMYBpu=&&2#K33EmA(!&ky@Wfs&P@3Riw<6tYu
zWBV-`i!}}WZAPFR*^UG&jKixA`X$EES3em-Lep?gMv%zgPS45+sV*Q1M$qz0Z_cVX
zhtO{r`LH;=S!OeaR|_Hng?!I}3t2kNXq%TL_st<%TipAXm5=T(M4|A8n;yj>4qZ4R
zD*}YwM{rauO+MmAXk_IzI!`54tp2SB#fkvZg2PSsm2d!vYz(b8Tu~45O#emB*gRLE
zZ=rM7Uw-g1c?1tibV(2LBg57Gq=bTcr>2Pm7fKNH!dr$sG@^4S2i)Ifjxgounl><g
z1RXoP3LGGg=5^f&T=qQ^^cW(fo@BpJ%+-XO^o`4!fT9hNUr%yOhzV$tKSB{;6FgsU
zl-MNqg96FsLKGds%^=EGAljjcSX}xsN>YJw^jFUXIP?&s(FDie^_pM_kng~?1jugS
zv{~lmGAM`5Q$<XMmcYUqPuBHY%K0?S-oiX+Kd;;d6?VuGZ9D^;OQl*EqL-S0&y7vx
zPf~>nU}e`T5L8xd@-U`{jbl-OCO#wNJ{u&%dS(Iat~ZY_X(K$-HDZJz?$i*=(_zTr
z;yc@0hCe*UW9w@sAHiN2E_BG2#vuOy5MtM?BJIGQddC&5wRIdK&%mB2RW})HcO|tb
zwyaIE3T%DAU^TsNT}(B@hE3}xzr~`ueITd++pehwAI~QB@!YK((A5>Nw+>ObO>qNk
zdR=Fc18h1}Z@K2Fp~N_Ays8amnx$*Yi5A~r?1>Z-ir1d#;t-YHWaK}l{3%g2#^e0l
zRl<}2S@;H*PlfptsB|UkYlQk#r2p2mnBv|!E#pfR{DfnDkT9e~`FfO%WWv|}#@kPD
zD8DiJQ*r%M>b?T|zr^)V#r12sFt%R?oMQV8yh~HD{aP*x@3$|tYM9yqGQ1yO{|0{U
zr8}4i_Z~}U3Xtaw!5*%p1}S@D=VtT_0Z}HPlS6mx6S*k|Z>=Y;2ZkU-6B#W>UC}-e
zt-8%?d`iAa-FQxLe-EL&Ciw>lD7$k70)oV;P0|kt4>!p^pma#H*az~ub7GGg@5SY;
zSo9%u;RJ?rh!J!mI(_IKaN?dKxjgDZe1cqk=sIq0a+nN$Hl#3l7Y8X!hP*MGG$!0k
zc9D;8Wr)E<E2G%U=DRRJ=*x@e64g(*II#QZLT8qm7_)t;Qq$11XL-v@anx|^M*us|
zx=y)8G~yua8u6t{lD@>RYYhE+zC6LOvqoLs*I*rFCocwk7JuRplzbw!3ULA@DS{j+
zB!u)|xB-|yQ*=&|<e(aO5(K%Q;9(rPQkb~?89@8vLB%n&zEsPVJ?58c#g-%0<mJvL
zJ<wC4nqfKS>Mm(0i{T{4g1CrgvOd0SMUyN8FP+gO>jJ|=uAutYztpP!byY%;`b)1g
z>yqkaV7h|pP2+>fe|5gpDFQ5^cqVdEhz#lq?i*DY&xCFDa!O4QRf>1&^Wiw+d=+Ih
z$?#xur8!8ibO0gggJ`gx>14gySf$vVZGWj$9bR8rD$=W^I%PJ9uxpYhLeXI}$0*B^
ztPv*55;t>$ae5`n6{#e>DLF+shW&u_5=<04ai2F3ME8`aM!-9iS&2$sj<iVv3dQG5
z7|%qC<(%)LVM7%VV~GxalA|Ko;%C9FhZ11V%Aj&-^v;(W#c0PTt^%v6LVo^AW1o^)
z<aP9577@kh@8=K3EM{S!xR@Nu_&$O19&i5niStAf>0x}ZRQvnhp?^BxyNjWZFOehz
z{eACniM(!5PZiatULmaAPR)S>(CETgr05jqAYUO)o{IZTNe*1TB8PJ8RU#E4`U*X#
z@Z?EukKS22MY#CZuwq=)ZX6<R<W>S#PCI%Z$=1`}&l~I@2=mU#hqp)hDpGQaiZax>
z9B-2W=^;u>P@<$LTi=>&*zd3N&q*x0INjtGrMK^yBqM3E3Y?6ZI`}ymHOD{mG1c}^
z2jQ3-q6V1JvV_hB2{onO1HP$-o6Jc<lP1*13^HmG#4+o*o+#nN2N%VrzRe)TW_wFd
zL6NJoxWcw0{fwkh7t(yx-&K^Z>TQ+liZRQp$Yb%c1N6#An{t4aS@~`zuFLIgMmx`n
zVMwCdUlzMMdnYu>Zq?bMsa;<t7c{l&%j`yualW%#oV4@HJVBDB;_d~8ghkE|SksTR
z?-vPY2vqB&*_h1UWk=3hkj^AnfAwEUI7eXXKC<si@}!7QzQoT*9$pAUJu;C?>`JCO
zObJipKqerL;THmy?i7kx<(2F&(~v#~Q`#$tGH~M^^~&-)=2fvDEZvzb=iBoOQUB6%
zF0SZbUP(&4tki$^<KH~}$NlfW{GXNc^)rygjcp>0U@hnW@*jWvr{{i0?bE+s|Np1@
z|M)M@r~LWvpDL?cUq9BJdiy-D|M-``KL5ji`lt3!?bFu3{HN!C|A&A1$3FcZ{>y*;
zkN^08{LBCR{7?V#+z)$2*yowMpWW`mKS!Ru{l~xk*FXOAr`~;d{qKMHYjQQ;>0FuU
z@2}#;s&WnO5BBzk-p%iN`w#!?zyH7g@n8P0>Sf?j!)<-q|LjoBV_q2g-|8m9&e=-?
zuj5bjauiPZn_m8J|I5EpFXx@gd8cq3>-+PEx6iEhzuC!wG{EfT0O0X!FaO(0z&xlD
zjQ8&=!Gd17j{ho)df_Ae6Z281o^RLKzxv0u{^7s=<u5<(%xIY%F0;PxoBRB+X1_TT
z|JKw@gkf-$M1%a17x*`yS9Z@raLDI@bvLsVE%G<#jn$CK<@Texq1-NiX1#y*+S&G9
zmKRj^w-?hteRdPArawQv<X3)22fF3&#x|j9RcT81ep{{X3Eo<~H~6+vp*p|R+B9On
zt%f~E)Bgqq{F&+h=o|lhVo^SR|BdPY`N^Lk+IUAdXg_^BIuP8v)jHkD-&Gsnv{$tu
zlKXF~K`p-3#3c7^wLS42!tFf&^lq=!pBUWVSpDtqS^f0cy<?LT@7uAB_KT&A^6yjv
zI^?Y-xX5?auC0irj0AdTe_6`ESq&DsUH}DuPL+M+-7j_A4R~#T`wRHde*Oh8;Qk%m
z9)Dmd8-g_6Y6?&Owi-YPZ#B`Ud|NFUs@_T<top7BvTMH6Pr;x40zUfp(q7)&m;1M-
z|L^$%KxnDKq5M0e!yU<6OV>f)Rzn=iTTOv2-&O<T&Rb0sJl|FWwCsHay?<F+fBFmP
zmo4mXZ$dx*4jq7SVh!%hKd_LI<5`uI^ZC0<dB>(IyZyeRAHUM`;}7hOg(iBpo&7GS
zKfUTNO!zkz{oiHuoL{cq^9R=M7dw!G{@q5k>umQ{lYqFqKQSZsihr(~v}1kL==?21
z<fo=2omy`<QT%pnz(Bv1B>1*k2eIH=@0EOC5j0p|DoXNwMMU>~sVK=$yoP?kPW!VP
zobTVmPrL>4zJKYdB;OAac$O~}CHcN$x}?5TL;2fEOgZ~jdnMmjM4-Tzijw@qn@C>4
z^SfWf&uPZXpY_Y-_Da4V<o@Lm@vlE#$@dk@E%>D#1>aXgCaW*?B>A@Db=iMyj^&?t
z6X{fsvCjPNP5hLJcwG*^Tx_r8`{4nr_NAgE-&fr0S8x86d|xs8uipGC`MzR>VtlDb
z!Oy&l>t!ut<=c1hbE>niUoEy*^6e1snRfnS6MiM%R|GWhtLmlX`-;e=_@$yG-&c(B
zwNjRT;yvW0%kO^^KV>wY^Q(pSO1>T1Dq7gLo&?`l!<GG)dXju!5pn5XDoXNwMWFA#
zRFvdrOs9((+rRrw{G9EyfT;b_S4n<nY5&p={iTihmmj}=@NaH(`6_yUw~zFxN$}^)
zo6k&@yQ^nT<==3)%%9oH+0juqoOdhFt1?M`Z-kbZjW6{KQTg9js}Pbe)fiLqZMAmx
zFI$7)_o~suiMP<cdN}|5OK7ov>-h6e<L`J04PobBhPTi6`V<v`s{K-NG1}_;ir^gh
zQc)}f-&X`l?w5+9&HcV2kPPp;5VYYZU&f7e`;C`jf6vQk9fxd<u=Veb*{FDs>Ou96
zazA`q4H%%en$JJd8u%pMYP)~usAe_98SpI}QRDs8OE{M~_O~uUe*PUC&<MSQ8}pA0
z4vgt<HEUl+_nXxa1@=}`SlD;f;uHW))hPI#YH|bD8;GCr0$*13GArZ1vlp1XM0Tck
za7x$o?cmn<Qe}<b`*|Wh-wNY=bNz`bw!c)c{d+%$qZo7j#ZUa_XZk|3{yTab(L+DH
z7{j3a#CI-OR*M3oyw!r}ly9qf|5a<=|43_yZg{IH2iv#RK={P@XZa`JfM107Z@huO
zW5@Tw>og8-e0!b7YTY?FRO|j_biY}x&0n?F<{xNn1D&I4TX3Ckt0BCJZ(u9j>8IYn
zzDTa$*lqp}18DE@tHJGWFXC7YA!TnhQ9^!O?bjyn{zDe;MxgOq&Bh-%3hZ{+TD^gG
zzBKmd-@uJL|BY|p?>Yy3@yt;2?SToHzAqJD$xoaLFFv;p=)M1U_F8q|t-o~ji|BWJ
zxxbhi6o1B1ePeYtZmquc1pUlLW}q1O($z1b-}R9GY5{x^{fr~{1|9yPk^a<jMJA@N
z>-80V@7P25<kzaN=x3aJmub5Hk&*77@hc(s*O%^o5&e!YWB<bE@Yf%&<Y$~`HxTC!
zjWd4Ae^$g9UwiwCe#aFSzg`SqL_c+_H~)E!-`|CP#@wR=>1$_S(eHTAf2~P=wQ2w5
z$A9zmKQitd^FQ6u-+TBPYg{t+dfC4o_WyTB{pA{d|MLlpK0dWQzF^`0;s4e2d<RRt
zx848GZ|ao*<UQ5OT@2yy69Lj43L6JJI{?g$`YnP`0e8NVnqdHX!x@wc_;5I*2mtgA
zMVLngn1?fZ1UCtR<e^}+4=25AW$FwCq$6QxR9M7Qk{T3a%@EcfPUw0Jbc@teks%zR
zP;@c{gfnC@DsCyf5QAX94`%=)@^Xg5b(TQVK&;J^<(+fIm^38$yaKejvVi6mrnW*>
zVqpY}(F8b=1k=KTSwEbh`B*h1VoqXX0Q7)VKF}v6b@~JnJeaHY2eNTqL3yFVYw~#*
z569#y;sv=m!{M+jripL{J|T-|IKlVe<_{;UM+E!D2$=}XEop!**+mx1wvWKv0<0f_
zsZ}6%1V)w(9E^%6p2`Cn$_<P(prQ1^fs78}M684DBb-sXAdCxVXeL<x!`oZspbC0*
zIy%y-a67RH&p6fi6;!VfW)MoATxmU@l%UNTQ7Gf`sX}emNb&g*R3TTCNCb`*`2R|B
zFF-IvY=(`TI_GbmPC-of5mceN>kRCN$0nFY`m^zexCTH56Pr;%00PCPd+1c$RaA8G
zQxdvQ@WAR1gB4C4fUf`@tlP{hK&zkuip^*-U^!xw9PZo?E;hp*fMbh|pd$pXM8#x3
zCCS$c&Vy55d~8N4g9|UjflxUOVk4I2V0>3lALem%yD+55fp-h&prc15&jBf3Yy}`5
zN0*3TDwezytSaVGBlqtKygPys56EOf><K5}sp4mQ0!xh{QXtifP4c*Nuso2M794xA
z8Rm9Q4vemGz^Y>t6x_jr6q}K5SAvc)8+?vjxxhiT7n`wfS2FM${2t4yamTu%T31ca
ztT)uuk@DljQYvaheq9M-*m|Xh4Y4+KF!se#R^euF-ZAlTt4;3;*wpxpZiU*ZptM+_
zAwrogB{wcszm)JHAV2s3sX$i0h)}#8b9G~)8^qCdL=(hvcC0GYxB2u2b+o+x5nWJT
zc_g~M5_SsuNTd)w<My7Eu+@c*^ZV?rzRQmUrCc#fY0cZtk%$+dBh&2_v6<50S28h&
zP*Q8^F^<m7_d%tn79+i{AW)0Xfu>qh-3@eil0U5@E5%2IAKZs3fpUYUS_m2K$dDUr
zsNJaG!z*ILP*_XZnp<hC#gN60tQO@KzNOrHmvQgBqI&1XmJePzW8QjiSwf@8uN#X@
zTD>FqFl7GsOr3Gd$SaMQ(^w3W>m6!vAuzI6cHUb?FzS_5-)X2{N%g<$!5!UK8to2U
zS42m5>U)(q8fZIY7`f$Iv`W^EJij4cjVsArJ(Qs3itf4))5aC#x?pyVj?msvo{TH8
zs#6)cfqV}!Z}dK^go%YRRPux?$<87#!Y${wqf`XFL)nR#<8wMeKU~i(l@mhwUrD{f
z>3DFeyQ%!^9r|v%<^&o~Nv1xhw@+y^ko!}tX`IL=k6gkbZjWBri<nFnpCpcf`~tU>
zJX*m711YLD7i*Np66=3Q7TyrWe+PkQRAz(+qFgj{>cN3on|v^|78(0fQj<2wInfdK
z9#h|O@{Pu%S$xZ>AV{9yt#n6-F284L-aE?tLhZK66z*U_4duPNl6wD!Qq3?8)?NgV
zPm0h5>zFe}qh85DH4NXNwZuH%i`exEk&blm4}2sj)vPu(4IL&{`75dA-8AzyvWTq&
zJP47g5^st3Q+#BdzQ)lLdHhmJ#tsh25OK+sWY@+)sjj&~PlZk!#TR`gD@%MLbeghK
zc4WK>v9)&)PR0ne3d8RsLNU9}+ldZN;VY@_0kp#*o)h{<V~Dk}Bacpq`lKhXMJUT>
zM>gOPC3^=;atxTmPY087h#RGYZaGBK-a*NHCHOk6G@lsRdnIqaLtGjaRNq(}6*QmH
zr*?zl8~Cg(Ro_qs<qnd}E5g<SzUnJs(>SMzfxUzEI*Nh)DM`LaeffxLi80YKw4W&0
zJGeJP6zsiH13f81+vB7DM8V#H*9}pyUrF_Cs0Pk&LkZh^r3#8+ss-gH?({3E?$v$i
zE!R4wA^h}#V$JM;CKK<=mDFqPY6iM&bTva=HaglVO*UjqgMB8L*0_&>@pLs^nyiNY
zKvGi)wK|~NM3mmagCBO(IbJU-eO9m68Oq+=@y0_TN*${rNI266&T1k)zmmJ9n!b4?
z2nfMuI`SKZNNM`mSz;>%mAsN7L+IcU3bCMfd_5ltN;Mi+tEJzRO1m?a!WE(Kj=t-I
z9ypVUxV%@U>`-d(4tmwFO^-px_Enejy>e587;ZYaR>PLM0tF`;^Il0Yo)lqI0R3v%
zQq!s6#Ea9BkRvdfdbLqo>;q9QCL{Y+2VHBJOzPQcfU>BeLvBQPmFk-`>Dk${RC^Az
zR)|)oCs%9es_>SpmqQZ<!mUWg^A7&jFs3``VCV|+@buEkx6EE6*<P4zV<e}!61EJj
zX#9vf7+yo<J^iEk!^BG6kyq!6&@xVT*3~o=r**Xq<!MUL+l#pDO4u@7l_p!c%$+Mh
zOA`xA)-tW8E2^K=@7Z<e$}Te)sh_R{&xES%VzlkxgblE>-*N&)NF&sd&no&+-=Qr#
zJ;+Z-cGl>!o?%(01k<0|QVc{LOmkPVP)^@S^ibPSpFPyJV~{ek!Dts<M)ri4Il2sF
zfbCO)$xPMPw|WQ7*SGoy&3EI^9|)>9Qp?B-cO~`F6_H=`t!AM2I$X+6igIE0rM98^
z`cm5mlMY3Vv(7DJBdP<@lOp49YR2hZ?s=?=PVe$9*BE7@FP!}Pd&pi;eSN4J&UFe7
z?%53e%e-j{(a85Yk3K0v=b-z#Y;BxrBZ=iZh-NQ9No`=Z?d=+LpQz@q#0u8Lmf_;;
zwA+#HD@Z>7q^QPY_(ARgU55LbS;7_xPeOEA=nDzRLQM31;S|@KdIm+<Wnshp5xsq>
zRnFl~UYQOz%14r=j~Z+;!57qElMN21Of;p=>|l(IcGNC(p{VJv<bLB#W;&9#e<WFQ
zd_Ur;zoHypgWtJ>S2jdke<dr+Y!(jAR{IPbU(sZR7lUjx8sR`xMUxR;EUD3ykEA2%
z`xW8K2DfSmve=OaKH64GP@QeFsXX<EnC&|pf+23J4yR#=>%POW7>$1EzL81miqLrZ
zCqv}-9huRBj948R=A+3f2ea&z)J6kx*(*TXyDG5VjuFZx->GEVWE(tsHW}a>Iu;E2
zH<r(;3Lk+pWs`Z0?DWy(w7#P1>d<qcLc!G4_sGB5Z|Ki9)c1j{p~*xCWo$J1tvdi1
zA#SfL$)z9*9j^7~imKs>1!iizG-{K&2VZQ6609SKTQpI7cd)%)QSBggtq@HPY+O7<
zlLH$!6VV!J*E()5LRkVjm|UaLg`GUEx5&<v>TzWb=o_qESH#9WOV|K*ofQ4h{@xBy
zrJU7uwF6M)14%|`AAR0C(6Y?wUCPhV^?baGXsnYM^@@gmbN|tq%b*tz>MdiJ0S~HY
za)S<jZGV}`uBayfR32*3m|h85P8w4`GRVE5>#)e56rG%uw7<bm>PH56C7$ym`x|$N
zSHf0$nOZK&v+iX_y7DOW<OlU5)7cGOnP2Jz>d=vjJ5^Vvg^p`iPgb;Ecd~w@YwOxJ
zCG~NW5Z#ab(N5&7tZwjpx){~E&n&UgYW_-aBj3T+>4#Rf6QC<I+h@H}8QGxXbf$8+
zv%m0O_1S@a(~qodP;I(++B%puuLO<~ux4Hf8{1jJ*X<i4kWK9yZ%7{L%7}NTN@g~A
zFRuin+%+bd*`Ty^&`Nc%SNdt%BLGrxWsm59m0k(kzWUIWO`?N%(&K1^<w5n3QyOT9
zE2*Z-rR7RDaV3R*mZ9zCI`fdB4IqbyOl@F2JYZ@kQp7_xG@v9NqW<jQWb}}yx)>Kz
zg2#eT(ZOfciz@LJtG7=Fn8lT+q65w1Axj*178l1|2cYFj0*W8(f39Q}9jtvGaA|`|
z@0PJO0G4ur;jClnKyWeRbs$r&<gHa5q+K23Q;@|R1Fz(@m;qh6B0jag!z<xa2j1J%
zQ!&4j=#!3YfgZBF@sC%6-Jt4U0X89I*|?HQB5)-&dor~nYt&!4*n`$FC<Ctm8v`IH
zAIXE_{k{CvvC*8YVWbsw5e4?}Eb)QJtaZUrRjkR9vl?klJmjnnD6x<=T?iE~*39Zy
z;Pp3@^5wgX<y`8w%x6NyxxCd;+50{cl(H8>L0w5j4AADSFV{W3JfWygLfyjme?^!L
z>=EvAPa~6|yS~5NYTO0O=s>Et(>MlF<qFU^pepW61JD6gaewXQ0<5?|RlV>i9|=ui
zz){>~3!f_Sp}^<3P*hhmP=!xTP3W?M4>X~Ygj`AWf6>toW=~hzkba;Dfv39V?7XaC
z;8)yf2|pbG7I&G#hjATpPeYfw(>(rYS{KBspUDxzGzQGYUA}2(ba(lt55q}hKNr%)
zUHNM|ur4mBRtH<EyUb@8A?~t<VW+si4(pF0<1SMeOs(#+g<<=+!xTm$$6IE1cPR-a
zLg~ot_=dl9Kw4axQ95X3uY@gugV~WRr6=&k1;Xk;zPQtRK91qYU!AQsUEG23&0W?s
zl0&+1TOBYJ-!g*%RB<4$o)WDTyp^&mTi$9|(Y|3V8*Fdi^j2G|8$cK2%3#3zrn}l;
z<-0PuT*-a+n;z>c$kT~4w~K*L_zG$suA~MPDAj;m4fh<6Q_mO>E?0zSLcs~3Wx%Sq
za>7^}Rch5yI9+{jRe|=}8>O6kaT*$qdRM~nLv`)NyTmIxs5UW?P+fbe?NVKPspW~8
zT_}}VyQi9lZX*oK0D*C(p|Q5I#6}l-Kkte#9I;(6EW_E|_fW4kIx*C(jn`YB<Wr*R
zh<$lb^~BgU&jPzuZ^V_h#>$EDq=-#J@d;gJaD7}!Tl`I~tgeQgE332Rz{=`s9lCLM
zwGRC#l$Isx#W#qKOHi+{@wo?MXnO9!QYp*WDstU-Q*Tdge!gh-T8BbhFnbMo7F`%D
zL!M4wW%XJDR{YJQV?eC<q6^x9SaD_6F(mTz6>1skkco#%beG@?HI0+s3N&4YjxV~P
z4UWJofzB~_3a^Nb8wN=qv>_d+FV};h0SVu-^o`!RqLpiKpk4|42lcl0KeJBtM&CD_
zvYx4<YLGKa*kyoQ@wL=7sJFG$F4WsvY8R=qU6?I{)A&l*^u&}ejtJ^)Ew#RC!Y6f^
z!GrB<s&yRw77y0eq0iP(pEr6q=q#`TtoR!0AT*j12Hg;#dM$$;ghE?N5@SdO>j}!T
zM7{W;6Z)2GzD<3DK3k@CBTGOk8uHIx5gLVp6C&$MYBYvYg_w4=iX+|XY83~#)ipM#
z#6`3FO6mo*FST;oU5G2QI-)5^;tHxSbU_;~oIVniGH~^1;&El=1XmfdSX=>Hfohv{
zLL2VF9CSHPiR!^@x2z0Tg&d9WSO%z!&tSXAZ|pPFa8A0<P`fzI%}_J-DqS!wtDDHr
zmMSiQE2{3g9yGGIu6cu66bQ=<YH>PUDuz7JKDPz|wKz8iQCe|sH4UveVS+y?szJ~M
zH{9U*+-e=Fac&LkK6a^L<hAm-*m7xRpG!?ceFF7m2K}jwPF7HwE1=o{md2Ii$!ueY
zQ*G}WBh@&r)1APuCq*^HiKadO<|Cm_rxZCrGd^isn*pig;)FCLJHHY<w0b`@9C$+K
z&@@7s7AEY0s1`Hb(*_vLm9X*Drqk3iPMg!vGIY=tu<d$e?GcrI-e>=37OP+S+>yiH
zD-r5bl3Rmb>07QQX-8j4ElAqY26)VsARC7PN8%G+X)C0OPr9WI=olY#OB>KJt_)UJ
zl2)n<A9h87YHYpioGU?7I7p78w(=l3<f}G7a$Jxx18cbt8PWqva@43l>TkH(<l%0(
zrV{#ZP!R(R;{tLSa7!NvN;!{1o@zt-sVm}eq5H;G)1~`{RP})B19;^rQ3c#@{2;&K
zA>;ca_aVa@I2ae8>q^St8Zw#zKJ&q^4OxU;39<}x;X{TqChYM++_WLLu#c%(f$AGG
zOZNf#9s$0)lH2N&lA7kBW})`RP_s~d%DH8Qmbn7J+6{0S7o^JuRNtWO4QPxjFP9}W
z#)qu$0l<R~S>IT^E=ZSQ$@`G8joigPXlu{XjgJqR*0U6(AX`^Z9qxKC6y%^|+K?W@
zD+AaAQ4NCjcWwr*lwbznj04qWK+W7TTkg>Jqp4{e5r=H_+H+ia#0;sB-KfujoVfy^
zL=4cGE8<UbDcDil^?I&^P1mOCAV$4w0z0n@9cH;TyU}-T*u33jqGN}5gNZ(oyWE+u
zEJapN!HxjzjGOH72^DItmP&;_SHz~EL(S3D%D*|nI=DLVVg`7P7o_unD3`cxH4GhU
zvhqs-yUEB00jwiU+H;x1JL+KTm^f~lEcEGF!d?Sd%$2YP&znZ;e3tf8*0d|gg(^6h
z!6tH>dN7oqDOdOv)k~awa4J8Wn*G3Hk@=3S%P!E^XN>g&HVp48Dbx(Mq$?SlmAUDO
z5wk?LxEaqpK(<^7HY*@oK9VezQZxFo4TiJ}wRI(R<S|*)6%XOo^-$<EtAEC+&*;iF
zWLb7o>hUY8+0u8sQpZ_S!*GOVW;esp#QV`haZV(P%htSw`m0{MU{{7DtKLIDzO8jx
z$d#A%NfA2${ialKhIFppWi{hS=fYiCo%)`a^u=&8yb`pHlb!O%8OYhLgpEVzb>|hS
zt(`@D+yJzAr^O6Bi+7pKg=g`;^-!usLA7i_Eh-0{)j|9UI3lRUE~9x-Ep{5s$d>F~
zDtJLF0;*-Jp1@|I7yD~5FDS+?iy6ol@3NSYKG}uTvcke#0TN~zJRRO)GQ$^g%WNEq
zvQLc}nzGZhek{E%F0_{c_;MxKYIe)gs=v{BS<Jf@^5cSbS-FtB%REM+W$!YOkuBLl
zNM(Suc;(l7AgaF7NKTN;EwULX#7-Bs0pxNexH!C`TFPBbLnU??+l7R2;kyh-81J18
z8(fpUt8FMmxSdK;W0XY>2cj#<A2LZiDZ)mC#K$gH90QQW1@p23vUrmv4Is<o?WogG
zaE-<_+^F89Yxl|$wiWncuY`LQe6`->*oHs%O4v?mpesQ;<wm*!Tx4ERjj3utn<?Gk
zmE?F_1H|dC$w=QD2MU3|j98Z@3!7jUp|%WQm$tuDDtBp<!y7q>KN6I3l{Hz}aO=AO
zS_ap@mwWkvC{T?p)eqPRoTqJ}R1+&JovGuUm@Pxd_!Y3((s)f)I`J`WqEtQCjgt}U
zqBMzyV0ahW%8+>1n|#^c(Xt_Y<4Uq++0#g}>q@U^NV0n+m;l^1Iq_CcimHq9XBTFs
z$-*XPhB+CHkeMcLHZQ`wNmmmx(`0l5Hq&Ht6B5&CP7@K+8nKdgAu$csG_LksSsg8}
z18<pKudR0<S<cK&y9LiOP&sVnpE8g=>;u!e$RPHS<qR;)K1V77XqbKE-u4C3Gkwj#
z$6N{9-dSS12uQf11;Kq&x6GF7ySWn1+6LL0OzFBP-bcs~LxR_RWJ)8~$3C)^k#=<x
z3}$}+StfAZg+D1`cLTkHr@QXdvy3eP_wJj-w^kSPyQ29YNHUSgk+U1fm#t)$1|pQL
z>^D|qDJkK7Rsv+MfNdYVdm7UK8f@jiv}m6aq1G0SBa{Y5-q0-onE}+YkCZP!EnDy}
z%hZkg40R1D8uyW#J4)N_L*qF*-jFmhpfDc^O4p*?M}BU=V6KFHGt9R9+(jLH1#Gu=
zkY^w50Wr{jL#ZZKp6wVp8u_(jU@-k1-@s_}wF6gk3IAAaiUJUuM64{a8;i3quQu3O
zJ`$8Z6+$*PAVQnqtjwi(e;z_sUs2AgGJM_?oH?s;)NroND`2y=d_NMDa+q82Ed!ut
zGbN}2Pjdwvn`eoQmO|VSjGr+eXtn@dhQD^m&W@;_Nu5TZXJu(WC0eNUKBsyo2X+Ly
zM{_*tpV`-gnGfk?%+8fycfbtpkSz|Z%?=sk^(LOJq^1V6%?{e)z}jr#y9`*H9k9iL
zw7F$kl?k=E0<;WZ%?{b#0M=|_zA{y8u8!AVeL4mO<GXN+JLIwkv~df}Wq?2KkjuIt
zl23{_0z;2sZzr;5hdkCm*6fh|4P?!Z*JBN6%?^32u@hVg+a9$ZWRYV(xsvii09tbe
zY#h9ggpXZ8pbj>gGqb-itq%^HTW~SMez=3ib#19TWHw{h-669XxZE8IUN+!nb~HU0
z`Y`CoK06ESSlNHu<;5=4%#$KE4TUJ!m;p+2CD;a`#jb=cBhLPc&~$+tx683zig3Hs
zH-OXIWssu;kH!h~S4VIFWj+#=KxfK+LH8-~mX-DJln4Wa@^iVmVTXJqDCJE1R<CL*
zu7t;g1KsB|#Bbv3Ey&nSj9s(1QK}iFQ+uRI_N1g{c>pf6g#{a69N#`w3tEmSu2Ebr
zw+zPtlYeig%X+|q{YX&CIiuHlzy`h&Jacf$hI#^(=0oFyT621>D^2+=vstJ$7rJ@?
zA+z1s)WjMwwKQu$riLcgh|txeK^F?zHQKGx`Ot;Vc0F{Vv-L^d^4(UQmh%-<U;Fz+
z%rxEAS5lpCnmLfBT@jit)h8I&0J3I#`)B^3y57_@be}g`z5}?L?M-cewBJ5zw-)Xe
z5^MlPb0rJq)Yw<RcJfrXl~P~;L~|u<r3~IJB-p3}?%qO=3><>@4h<0sa|hana@?Vo
zPL=R7s2#Vf8ED7t8c=D+-i~QKm3q7)6fc=&I|@`Cg}f<Qy$=9yQi8Pr=uL{S#DKj?
z5kI5E-=qZ1!-0_^%vUd;=SQR^(L4Ly-bZzIoHr6zRGrrw?j3y>SbhLdlcK_lj`9qZ
zh@H3WsL=5P{-qSLxzczk;<wn5eX+?58*pBw2=kW;G6kHz(vT@apGrlhgk2alywDPW
zuk9mpwKnl03SIv|hEBOAX0cPeP8bEKNePw<05vJXb<F^zCS?nPdR;QPM&Br6aHStJ
z#Rno)2XHtkV{5ynoF>;myljdV1i?x<C-oqV4d<tUK-`qD2acgl4YnLaDO&X)=QxP0
zA8>7dL_>WFyaQr`1{~xm!ac?SrY2?R)ZuFx>eS)vntF9Ox%R%i!=Ca0HQ>Nc5qe>*
zis-pDPPySy|B5i<w5SFy3O*vbIS1|%QUvW-FrAb@O%H%@QdZ*w2qz`@v;nI5h?;t7
z?3U=)27>5I*7&o@ntYhCUk%0V6VA#{iRwMb!WuU48f0Q!QT5#QsRNLcB5p1T$w>*@
zA6SddI<*pIV+~wMr3f?^0~c2%!<^4riXLiz;stx4STEP<)O?054g~ifSF)<iIa}<Y
ztIvy_bQIH;{FHg*8UWO!2oK)q-&T(|*6C}884jB%V+S^evDJaiq44ZA%x`h2eME4i
z3>|Q+hu2~QX-$gQ1IK#sr4C@jOBr?|(0+VGQ#FJA<YmS%6xqk4PRX3J!(P#zGwM<y
z?ym@)sw390QZXq|TU@3*W{p90Dy04xRHsf?>KKR-D_P^uRteC9(Kxs|YFz<d0gqZ^
z^eWOW8XX^{o0{(&tu}^1wfP!zfH#z=&WB@^-t?v}Qg6Q2+o0a0`8KFDU2$+@P-{94
zU1LCNIuBk0XphY3#BPFLy_FTmN9AU*k9vUA%8i!YpduBbe+(+peQ<CZU=*qhQs~0W
z@xHbl5IrekYgE5Gc*q<;-h5;-&IT3f=H<m0yNcMn1{LXcZJ!`=N*U&<^yqf=k$QAH
zis<3i1~aHd_g33fqsmS*2GpoR00!VbDT1B>-X}%a2L_dG1_F#hO{++Nkx8c%1~3ZX
z^OTHD1z)zl_(9bxT>k*xD@A-*y}uN3AXL4=_m4r<yQdyc&AWBz8^Eew*)7kjc9l?L
zOsd^Y_`#S|yIaS;Nwr(i=?`RBw>tSv=v{>m48VV`D2tto)}#d|H8Z0J#-wIe2*F7B
zPYN)2;C)gA&)=9;r~c%yc)4;#7#0r&6DoOk4FL3$DdP~RlDF*rNtL{1?@y{^Mhsj@
zy~CzKP$TcAVNfe?nG%y)dFzxwluydo2WVvl7YyKhQiLu{tdMoohl%|i@daa+T3)pD
zC$+NT0<Ne!iNJs{p>dZO%&!QI%dVfBt!u-W)VRy_aBAEOFQ`X(m9Y5(&66U|2Nmwp
z>0nafF7Z4Lut=ti9dJx8VhA$vY_8(9)nH(BTMB0eN2enKpxT*Yj}@tL83QmT&ZcW>
zYoFAni!pa&QJb#vpN>Ucx@6d|#vV-W?W=Kq2{syw%2dGuSA_Ycr*%}Np###QI#u|<
z6=6Dg99TTOE*%FJ4zEkWd1LYPx}@<J)v&?_t_UwihW(<3g)&`Krh@$skjbWq-K08I
zD8N`$r-^dnv#Ou^rWds-9z$Ka2wu7(yn@D<y0NHCmyQRkl<8_}esXB~pcj>C#t>BI
zk?i3-Y7Gb3se{1cL3ZjOuy~H0N1O1X23F+2SQ~@E`=_>@p=X!6WuU;5lIpc$1;(Pz
zouPqH<tlz)EUMhP2^b6dcDjZ}eLHy&SX8%)Fc^#KcKSOs>Rg2xjD_d0@xZ#Bj$*A3
z1sIHlSmczUb)JwFWH1&^$Wx~U&{?O5Z6EHzQ&vK;VyA>FiE3K024hi8GuB}2RwW+Y
zHg)jSDPU6vE0SPr>R^Quj7=4cUA;s#76K>6rV2(h!Pr#7Q^$!-9XzM@yiF~v$b+#<
z3oG#83h>@|#@L;2?cHBCPr_42gALWIpn<V@7*^cC*wnlegzRJ2A$Q8`-&CnnX8)#2
zon6nSN}c`f6c4%xGZ-5Rb;=pMsZgg55L+2j-vdMiWPU_VU09q>92dZ?p8`I-^e!R|
zKA+BpQbpRsv8hpq4E#-v%AkR<udW=Sf$DHNq`kMJ?Li>Z6|EBR!PJx^^k5!M6<RPh
zmFJMdc2j*0eefIVbLdR40jf$F9v@gHLpJ}eC)b}fqhs^uRGLG?lEbMrGhATQq3ctU
zh3-_DiWwMAl{soJeM(kqc*t;f>dYa--BAl)zEfq6g(9qfg&qv23LUcRojP>Lu6O8A
zMIQ{FbFU0#ygwQ3UPsm;lijIM6<;u%3U$0DyN@b!OoM}vz3$YpW1xsJnA#q7qmZ)t
z<{kP~5eLJmUlnvPoH|xP2g9dED(Aja#|}d=pDZihsb3j|Fr3HN(TPqNPL-?3gyGb>
zL)N}S>kiokPOV$P2@hmgAGGY@3`z+HOr<+y+Jg`xMRXB(X<o%245#8%1j2ACUWOnH
zr{1;mj*yBMK?qlngHaH|aB5yfAq=PLwb%de)V(JEzf<)ZPX!)T!k*&Pyof`1hEw^P
zod3?_uVNDhawesSGY}lE>;A^6eifiFoF`k8$?x<jE52Yvt0Il<pk`Hk!3b(r1Q=XF
zeUzr#fPfM;fvK*j-nlI`Mm=h}5D4l~g(i%k8Z{8w4e-aL1XC5%ql`}&K|N}^5{N8L
zaz%`w&)J~ZgL>9<YzUrIP1b+#q*?(74`iz(*p`BN)y9`c;YIOC5LBV|9spu;dbMN3
zWIuHP2;~pgbwEIinu3Q1P$(%wi}Wg+4h}(GYb;`PT^@!gRcks);8rI^crd-n3U3&}
zgQ>lqf80iu4AbdsU!MP<#?2sx5v6Sz!|<e}X1B}U2eVX)I3rZIU5@{ty6vyyKcH{B
zP5{BvYG<WdZ(W}Mphp=A2cDAEcoiNo0zYBv^dI*?v0h@A?hks88TD`_7=(=d15Mp!
z*B@%?F5CVz`s=%+j2_FlKh)9;h8U+;i49Rn_bnB8=qK*7><<;Sq9MkiqE<Y_I8f9T
z55Z^E`eZ=FI6UhrB4Ql6oV#uU4mElg5^J1N>0Kv)LzS+`hyjG+N2C+Lp$aEQLCG*g
z><b6_S#b{IP(OE>@`w64?`$84&~@Dx9I9u8K#Wrgy6d*!P(k;hqr{<#?z%2G)X-gL
zf<q0hP>FG%q3bI9fe32__XTJ1UFp8yEDTt<kVBPScj@&c>THEfj6>bqW$_;>Uxho2
z165nW4G%=<mF^4<b#2EX;84+a9Rdy&ZEti|@F{GInzre};84{nN@66cIR${^jYCb_
zU>_XnSw%^VLp94ViE-$QMgpIwWI0-ePFzWKv+3Y*c*t$^GTii}=%&!pv+)e8@Q2x;
zYa8zjW}~WA0K{xmwaqb4vlvNJQd4y$=$501E^W0%H4CiGQ?hymilmqgMK(@fa>H?C
zHoB4-NAaW#L)-XCt;)94I?lWbu9%Gn+{UBFGaEIwf+=R>@wH8Lak5W5H(U`qB@EbX
zRK1P&0kcu{X57SVP`hoYo7B2(ypu$|+jzd1je55Y^?<s!4RyU#FPWA~f`vIy#IiJX
zfZDm?fH51jGiLQES-pQ#^E@3l(_rauR?Ni&5%NbQywGe^>kPcOl2v66geqG>6<36=
z>##5zb#~*;z--jn48E8R8oM=3CN*{wr{8Q;+X}*%jcU6!b%I)3p&7HC9|vI>IZ<U7
zToIZtH}w^;`BLl$Q5h2mtD~@t*>E>`4$l%Zx2%r<M}%9xV>k-Bn275-h`E@({^nfu
zj*juhV1h#YD41dbMs<$sp&fnmLcz>}P#uL^OdzPvadoxc{y985OlXF4cyxFs)W=a^
z#sstaQC!9>`t_77lmm6x_;|9&mIubjdxHs$d(KjoiQd8XpQ*Rc(Vf9WoZ~rD9Vv}^
zCD;*wn7R_|TL4U5NnLba$v`dkW?_DLUoc_0TnVRP)dUZML?#TS!x)Q+$kL-2i<!`<
zb4-uj7=k|YjvL`CVkO6fSLyz|YkYw=yT%u2v}=5kjnaglNU!jbpj30#)P=yDF_vO>
zczMrhYWUPTZ)*2oq4NwdVaA^fr<gGGPlzRGehvaBXzNd$6i(38pEyn&q4_3wg-+0B
zp9YWP38~mRz8rz_u3(@RpHmZfCFm@ULC*<#@h8qoA4!((U-~8ifI0z-egge;z)O19
z1JF-L0TvVBr=tjqS@@?Du0{<b<VX2TK%EZ5DJFnUM<Eq6VNOT!6cZ??D`7)m#X3Uw
zO`BQ5w{H_8S{mcTkQUpW=)PhcuPFPk&(<dTztl`=$rDRWEevRCJI0~^#AI75M>I9U
zg%OqYKH*(BG1W3)Q75LFuKndG<YE>o>cr3>H`c~r!yAK?r+$Lp;e@G{XYXi{Pw+z=
zg-T5LXbwUpCh`*9GP@FJnRfOB$mvAab8Atb=z4DOJ$5{}{+W{iwHDIH06e9n@i({g
z$^~@=`N2n-<a0Dkn?7!!kB;(*&(X7lFSUGyPl{LtT8jY>vs{x$8N(;sm&f(x0-JOt
zz}H-nRV_ZZu#v}u&xJm6dgQMpXN`%&pA^*qWMPkyCAM7V+HvPo%cMI>Ej~w`08fJO
zX5xhovxHBu0UcrHCh$WiBOE56Lq`z~&xG6jD8ymHuYP=KUZIG5Y4}h?g3INDa$=X7
zUYOYG+Qy_#4IPTgr&`{1<UYzFJ`;U(1h<<&7M%=}n7E)gE(5tPF^<c9Hi0QRij$bQ
z{5Xn=m`J#H6c;f^pt}R5JT4#M=dLKfMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=
z&~vlyla6;a4IPJAiYFzt__|t$*7L5`q4|__e9o37e4!K8?O~k61c>Mg@KkVk9i=6o
zxK}$0m6*l*b?OG_fh7B@*ocX&l4sNGMdHb$Y~&N!DGwlZ&zx0YE6{w3l$d}J9Yso9
zNiN$RY8P4T4zrTaf*Bp5>n5&24+1475JqQ*nua3WK_AKl!07By+XEw%u10##BZS_Z
z6aDjds-W98P2X8mbXV}!st(HV#WnQVn^OhNwq^N(7w>HD6p1W4Tb3`7MQ1NHyl|@6
zOHJ25p1ssGR2$Nj&jKGE!R#ik?XLvB0bK203ESQ^#Hpqo1CmJ%?!p7i-BY6KjBH`R
zg^tj2v(Q3Ufb9fWp)1J_J}Ig<MSB?(Ku5{RYXGv1=Rsdg&42**Y*Rz2-L`2S4(8X`
zO8JM5@{?al4XDi01@*UyoWGJB4PE6E@R!5%<r5H@Lx9|8cz_0-EiGEepd(P*1TN@o
zI>{%XKOYH7X*8^(o<RF8nav;>J<3i#fhf8X>=i{;S`T8=BTH-+2eNfg$`5+U$_Aq7
z6ei>;NseyG$}T+7Su(N#7CI|X$`3(ExJjC!E8;UsM_maYva-ZpLuV?b`IS^(-%lAC
z!_V4k2}*O(f?lOEmkj6ymAS;IIe{2D%4$9r^yZQY4H(f`GNThkbe4?hwK+&y(SQ)0
zwbVFNt5Tg$0EmuIbh98tXNe<d0x)#eR9jx7q799yK1zl@K}UQ5sk`M|U$Tz@Z#+u|
zGBVa5raGTM0i8wn_e9qF=ZY2t+1a7qLvgO5nS<h7Lrp_*zRAuf*8LG|ZhpRtvt(rB
zyEzL+HomO0=<~jk93WlZSFlk9U;l=ZTr#3Jl;q;qy>B1n)}9+Ga5Z%VDiBG^ClI+u
z2)GHf&sjjhKeNC-XEk*M3UJb=JpuJO^Jx4~fl5+7H=>n}AaN7h@R>Bd0c<|=sIAZ0
zZ-&~z*>A=>MjZZxkDD9HPMOLl06j;rwwc=Kma`{M3Ua!qoYqikSAxz#w<$6C1mOH6
zfNgHXV4o?E^@eVnTb+Y$n{rq0(rr@?>s{NybC|z;ZfH9}*RG^Sv{A~hd&*gz5TRS9
zjSHLNDChYE9Oz6rszDZXrp#@S1)ZtusR`)MnKHOxPF)Ef1pPPVwuV{uk)U)JyV9Fa
z1WFv@&?Z7+&y-1yh>J7juSQtLbEd5HLJ^%QBOM^3lS$Ag@IyyHwh8pmNh9xpq{b&R
z-Kz#$#c@%&(<cn*BUsyXKv~X|MUF%iS5hPNIxi|S`V~}HWp6t)=6oI04wX6OpLQG=
zCvEc2dE`vl<2bJzB}bn=xJ+e`11EGPY#Lf~$}L?ep)+Km10?iZ5n6^PR7un)h=>kA
zaTD;MGi0SFLg)<91x=jw&XAFw&C(jj;qeF{H*vr`1LiogvYZj`18Tog()0<uPf9TR
zP?<xXYUfdNI3AoDbI4H*@Xr}?R0I2Sgo>NM{+uCL`@}*04B6{-mOn%0I?~{r0Y5bo
z<s9Wue`dwy9YXA;=h+gu&?kU8N0_(?Z^jw)QkT2q^Y*5?0o|uW=M#RDBfQ%Lj^|4F
zU<5>7Q9U_Y{ySy>7@jlaqK<||AhSIEIcK~l^1zvK(Bg(u=nQ$ND-iSync$%1IK;Yr
zHg#lzI!bMRCAC;s%1M-$8jiCw<fSGP$zjs+SrN8JsIysNxL1Nw&6(WP$ZvH<d&dVo
zH{_;{nI*OgJvU^51BLUEpi~=-$>1)B<T2UXa9SSI*N8ypqx9tyvCz*UQf$V~e`gIS
zIFqdmN9~ocXV7sb4xb5s@3BBBd#0}s1U$#+lZFrZnC$C7Li1xXumQ_CCL=qMIY$}J
zCvZ7O7_$is&auty9T1#jvZxDya|LV&CqU&zpMc;TK+K*JdDUW5fkDZl4(LUrL5<k{
zqde%(%;b1SNV19adB^0H4roG?R~nd{W3s0Ya<?9%MO`4Bqg3b<_a6sfvxy6mTSn8k
zMY$60#kgv@BD8&O6`9<)syWP<J^{};CX>6+IZulClZ`rTxMMuBuyLhyOdt0tZE1>9
zpP=r#A~pqeX)v;JS9O#keV$PzObKqakIAtO?9DMbwvmPMm>k>4RCx@3?SkhVQ`Xf9
zc+Md_Z33KgOs;KUbB;ANJu#kgpgkqp_z@pd1JXVL@XYD5vI{$N1Vft#fTz>t@dk3{
zbei3HA9|GCeB#FRblKFnRlO2Aym9w>MSLzaTc^kS)Tep{95*x@5}ZFJsxinoKc(Bc
zoZjH{JDsLDX#b8<pg%KjsZXNKW?^0qGnr2yUQU<&48Y4rf>KUwm%Y4jAAdSs+zXfX
zM?kQJoBh*iL9ZlWyk+=S7Sif|MEK{LMS8feq$ZIj_iE5|ouBS%6$y3vRKxIv_K8yU
ze(0%H@@lk{T&5;p4N%V`+}3IX4H_$yg6pOZK*4oW2cYD-{L~9@lf&HPDXD(ZE?(`U
z<a$@bP;$MqVIW^l?`j%quXi;K|EKbmufo6_VZIiyEzjwVPlj`|H$6BHfJ$h-fa*B{
zcdfRw1j~B?D|FgX|Dg)oVJpyt?Wh$fLZG;wRav`lS*_Gw(T;i#W!R3U4TrrJY8t8Q
zjv!nsAuqSQCx4PFua#N60Czbp)HIZ1lb3n{>~dPD?b42oXXyp3%W1Bb1A}zZIWP46
zD7E>*_>S;iE9d02t;az1HJZWC0z&SJ7JgDarX9S1v^&IhEx=kD-PWrE{(Bnz){DTF
zMz{5q<lAp_TQ6_|omLk0>h*gdi5I~yZL!^Q%3J{(?m51xR&fGU8uMoXxp)K&TSTa|
zp{_xTHM*?V=Sx0qs0OuIBh>qfYGDp`4k}AY$ye<TN2skuTuU=;fdsZRQ(Lnp*VGb}
zRx`FVF}2XLPl{?th9A^$x>{aY;^1(aYh7*N68{LzwFqEgit?1y^y`Bz1WRjQ>eTXT
zG*cJYeLkWr`Hwh9y(+6Rl%9M6?;OHit&V8ND`Kmq%&vs(rZT$%Y>VKS4?MNLv^YVu
z$pTa+2+dkR%3J|kz8`g*P_yMB!|p&7ObD8_0C9=q>eoRxXg)7%=nBo}E6JT94n5RY
zRDFSmdZlp^hvxJx@0>W=(+d_&kfX3f)n7WO7fho#TaBmn6lbaFS`twv&RtqS$HZA`
zy<?nG(g4SV09(td#D<M8adJe45l91<*_o31#i*`L^>v_YqOV>E#s~qi7BWO!2{sv|
zkhqe1?##d0Po(>~B6fCS4Gy(j3Ni%MTCn-!m>SNJJ#kD8PrQ6X!waw8)cC?8G_}3(
z=8aJ`3pqRDbTz*5*>pW<qsuUcSDwW_We~PJDXHEx_0Q3thW<HvL(6vo>Jq2%vB^IW
zhhFLhs7u6A=SpQo9L-FrwNTdbRe4vQ6k%_{QTIyNczt*ghmF^lc?E1eKi&vse_Dvo
z3gtFmNG20Pgk4GXQ0f+tmn-4^FmlLOf)2uOa3$y<{0di69Ry8J5Wn@LC>LLN{^0(a
ze(QyFKN0j>FQf#D*lP9aw<u2F2ZEY#o|~_vI={12Iw4}I8LN>jwSwrOP*U>+)J%lF
zXhc9p$Yus8CWOLT#lZ7KO!Z};FZ4+-_^3V-l(H`}qT%9-U_ix!8!Td|nTcr~>fFSv
z4mDg)Wustoj?7`cfTRf_wib{y5j4jEq=}F{UO1WvBf4z?IulBLz5tyG!MGOOixD!e
zD+gFg^dQe7yACBNkk*w{f4d&*=x@^qKw23=^LvyI3|Zgs#70P6!&@66`+GnQh6pwP
z-H(6s+(p|yRX;y-Tc5fgrPVy<_?(6Q?Z5u<pMUfp?eky#?|=B~6Z|%6@B8ZyP^E{+
zf;!S(#Nxzs_<3T|(CHIX6!cm3Ri8#E4MO*u<(=;1UZ0-7Y{)IM1#IQK>$MxXu1*bE
z!CY4yHkn>Uy!asXaadjth~n2}CNI`oP_dFac;Kv2?1b5sB!Ejayerah98u?prv;bT
z$=SeoXGVa$aoWKE+b#@6Yb1W_0u0n){0mw*_m4za2?qj<2XB!8va76_^qrS~MwexB
z`t&acA0Bk5z6Wdz#U|EDn(MPH=4S=X@u|N*e|YO>_iq;xX8X%RQu1{zB(7>LB)Rs#
zEF|SX*Gi&GHCK{Y^R<%R%*3^l7B#}Vl$45sOX*E4$fcx6(swB(i@d`C{gPckOG#1K
zT1!XKRPS0+;NF+DB!0-RYYA~k?^;qI{JWOozg<gBD}!rEms40vUqMG+IGFW|mE`i#
zaU~7=;&d#ZM#!<?I<e81<VtG4TuGl}-)AX(7Es@JGy43oX79fL*h&g$Vqr(4S0TFr
ze#;PfHumQy9HqOriaR@M4TPw(!M+({ZY+k*5N+cF7SBk)C>TCNtl3}z4W}&-hVIf7
z_^7gQ#b`noM&e1KDnoG6f-i@#qyRXFxEBLpn-B~X-1R}S>{$6Xe!eg}d`HNQ5JjbZ
zH%M3xAtvpBMil{L0mnn+i-48~sTT`;{-glS;=>k^HWC7a5TnUf8-j}lwC~HJ4IbPe
zJTx5diF&@i`w%)5=3R(bu`IwRCADQ2%0Gk*MI1l~8H!vAL6U7S`-Y2r0qnm4j_t^k
zrWm#(FbrA*ux3O2+O&8>{Ms;zgQ(H6nnU!Au&V>)j4-_8rDjCvML4ggk?SHvtbN*N
zI_a20o{SK!_5p4+fE2|!BZL)2mV^*66x&;fWwA~#@e*hwjwJ*OMW{;v6^b+=A@=Np
zLcUtCVLu`6Y@{6tVLwm3_Sm#2POXdBbsc?j*~HeCcFKed>2DkoL%fVQM~0xINRtqP
zjvidW27sbaLLvS|oQXsD&N?;Ua_t2NC(A8g*}>Uz!&QcZcnHjSGa_WMKKHMB_2A!g
z(qB!BlsH$APuzH0yvsT`b8ZG$z!`A``1;_mh|O#1a%hCGqHuY{rU3`HNbEYSpE_@D
zp2QL27Q%!g3hoN<L>x9ZkKss6bOm|9I8lp?-}ec;9(dPIV2RO&I(2Z2&GR?CNU?c=
zg{(`lX&)g1FrXU|BN&_hwu1xb7L2U7hJG^6>PoVw^uJv}b(IJ74&U6B6hqRL<YHPp
zkoP-1f{gYCMJLE;hsQ4j8SRbc(>iLX%=TC~jQ5HHjm5M06_j084~0Hl^0@VKUtS3t
zh7w$%R-gr!j5I{a2FTBz66G=zPV`E$FaD)gE-L{;KNeBFq2(x*%WZAVOD*dlDD(<e
z7TE|+p~QryBv57WB~}$S3bna5N;MSv+IoY|Bp9?;0=Xw8Y__zfz@Q&<4<lJ>25NHg
z^18#{|HPVKs@3b^=i6IpKA}B3LdipD&)(o@T|AxlN{kR|sDDs?0DE>^YJ||9y+Qj4
z?fG<EkA&c!JugsVnOcSlT*j$^3S6d^sRM!c?1;w?;XQlB?1%849T^g1bv_nKZi)1)
z<1`gQfOcG0T?w9(bOpDJ?t{_b9!jF{>>XJhW05oY>&b;@8E8NNMSJCs{BpFZ6q8Si
zu(mr?;A-j&wAwtX2DLVihESRMu7q8NCY!wP>L8xDlA4@KXb|K;Ou;~%S`Ijk#tbzC
z|LY8O59)1(nx3DMt66$rNq%@GH6WeyaVvWz{6#Lz>1wxB<aGKmIygZ>OotuBAt}LR
z)-mi#*xQ{Y_H?svyw~dBM2Wfd5a_+R)LrPkxzOEGds9><9SkiYHp9<B2HoY|R!2tL
zm{V=TA3GKHd_^k-Y#JI8M1~!w))0?j2Pz;Ypk%$%8#||(E+sjKT80vw_{@<W;g+#?
zBRRsA7#7FLuIUI4{6vVn@Jgz4y!^V7>YOn!q#G3Dgo3^Ts|TaEfNF&J4X>ouB{g(s
zg5{XJ1?$Md9FxejZdC;%0?kp(&W52WUtYtGY|tTI!ww(Gl|Z!^PJXkg!_a)QWodl6
zHKcv5PBS4&!z;;l$!K^5+3MhZ*Oesc!$*YTU2r4R2WZ40?F+b3i1Dx&CMhMbDm#En
zF{F@@==)08G!)}tDJNB2hyAXG5Yb^bD8=Dw7m9KC7mrT$ZL1b|hEpW};mR_5hQr_M
z20{k)0K&6_11;-tfH)5l;@JUwy8^x}_+E#$03hhD1Sq0j9?KAmVh5jF5DMDC`E~_-
zaO%9Fue+$@o)mHJaB36M^Ga&|uRpzy&yj4<BiNB%;7T~Y0o6r}XV2UMAu_{Tu2~x>
z)r|4V`btX64u)Cv0j)Lk)fQ|shCI1|c7}KiuOtn)7=~gkldguU#5N48MBgSJ6<{lT
zN|ck%f3KIT?+!557_z8q7DAMSoii1pB<z^Z5Gu68b9N=1G^n)1iT2N{2osM%ALRiF
zfkdw)yDpGu2a{!(RQ7;IGm(~E(H)-YBOf^SS=E4k6D8r5<ohSi^a@hpgutdf!OJ12
z=`H8`7u2-F=^UmneC#aYP}h;KAcQsT_y}LW{V0Ve6zLUI*KuzC?CS#xPe9TRjCYtc
zHgMo!w8|4E9>SIOLXtlz;tz5K8__ErM64m|!VZ6J2v^#R(lt!HWgWb)L0st-)C-c9
z2fjW85$%b<&vK6Xxq_PA`K40z5Bj;dZA0MCE2xHLg-_7Dg}lmFluJ?&&<=GIK!Eny
z^KZ<-geo)fjdjFCgaDyENq$3c&<=GPfO>W)+%Hb`SrLgLcxZ>-{#qx$CX-D*amFKG
z;T2TRb>-dX_!OngaZ?k(f_8+fgh^9_eK`d5>~o@LvcAFmAEw;^%>Q9JU?V0cg#Emd
zI_q0wcUKm$9ZzVpuH!Z$eWL5gJ#ow{c*p}$4nYXgUc}cS{AdR`b`U?>VU<QdME!J_
zt<evDkn2$thF7w(%n?HY5<A)_xR9>|A3K=DqqCIVlCp-~9^KVZocId5^FUPn()k+)
zgh=S<E!~Ie@I7(b>(cj(J-Z^d4ERmg0UQBrA)3NoF>WCU>J{V-UL*#!BPuTXQqwpQ
zc4=-T9|(a`J8}<17t=|{87>4e?KtN}pS-&)rPz6)(!swUeG(qf!O|azG3}u74-pPt
zNq!r|nRXPg`z?AnJ3ZuARIhKSSsVttbUx0|A*R8Okjl@4bOK+{r$nrFWE%)UR(s_=
z2q9Llphjpq=qzYMp-r!(dWg@t0#t92oq?L`^ld*Ku8knpv@fVSVNE-3cmqs=9hm?^
zSko)1BS6>D8L0uHH#PpzbwZzZ_;P~i(~j`pC>-SjQO+;mryVY%5d5^4Pbq{x?MTTH
z!kRuEi914A(~j&OA++h0tgkniNDy)*UB9T$M%dCT%J<l$tryf^(=B^xzb1zoqPC;?
zyWpYznpAp4e}~YgeZlG3sH_(hBmla(;8R03eZmV0Qee{#=Vmmyz~BH4phWx50m|70
zUjArO!(io)#!oTbupvxnhoAOJ>Zl4&ZZw^e;q8q^?{<enIGR*-xr_tUgHK87mKj<Y
zYz5JziTB77pNX?xW5m^!qzMvD8WSx1LHuVg7XD~D0E2`-nsg=z8lrOGJ`h#kx~2hV
zwI(BbuPk9_-%xIi2jGo-4AHuphH`6Cy&Jl%N%ij1ZB3eYBg7{fwJInwqDiyn<%l2Y
zRq$-M(4!rRuKc`ub$b>$no>W0q*QmUUO!Z-yVks)P&=N!PCwG3;12O4JqmsiKRP?(
z2Fj0o*+o=R4?<g!Bhtr;TP@e`6JBt1aK^ou7bj|suQZ+?>EldemIAh0gLQ#WuVk%y
zaxdt3FTxj3FiXb;pC4&o+yS}(r#-I?{YcT)z2cK13<t^KJ`$9w^U}1HPA(<&ReG<k
zFW!n?N%dXcZtv*(Qp=?zuY?VEtb=-L&bjsiF#0%wryZ%0UBJ_xnF4N^Z5jqL31YsY
z8jbKGKC1INd;??SN2=Hd`aXC`-ir?@MeO`Q=kxsS^YfR^-ndJ@622G&Z}`#K8+Y=4
zq=j*9??;F4y3}{22fl&~EA~?jEvx{Y#*u5$nH;!-bIO$)_yRBd)Z^hLb*1+0NFaG7
zsK2WVI#nZEr5~ND-O&rhgIrN|LwSC$<Zcum)W{c;kwtc^l%k6!@VTOVp-TJP!3E~Z
z`r85g@Q{NX)cnr;zP+-2J}F^i`EMR|9o=szZ^F}@#p;Uu*hn0IC8c-@K<482>%gse
z=nRZJtF8pTSCXp;aEGTvxr~s$w*xxpA-xKCp^NdagD1|F()Z~}Bj+Jc7ue_=sd_tL
zE-r?@UN{$Ln%*8Dm+_Fcjgcj+SD-Xq`FJ}}oL7Qp05cVXxZVz8eGeUh>mR>h|2nAl
zT}ga<J<$<6{FJ1om;Nwx%$2~m1M%w0-+LuBxe9vjv9gHI65tmPYG{C8TuFI*p<i6|
zem&r8aHZt!`SP5}cRO&wF0Q@~?C?jDB~QE>800!o#~xC%AeMAx>g^z(baDB0FjP8`
zj6I<LLYf%(7S9~L9pDys>0!WITp4;h;4MJYJrJ#`gm$6)oZm4pF8P$k=jI#s_e%!K
z<%+oeO8>b&WPJBmf=>zvHdk)met>qpB0MKS@VER{s{YAr2A1BLthWQu;_f;N0Mg=)
zd#XaTxa*n<h!%HQ&49GHi{kT&^2IBmZ^y>$u07yX2}>V4yE{Jrg9DhmzW<CuaM#z5
zI0aV{-;P)YcYXfQZtmh4>R`BammB+hbe2!`3p&g7`JX!Pxx?dCiuOqX`v#5W+yP2k
z-?AF1HR!sL0u%m~(84WpU{~he4jz0*;@(@X@#xm-EDVSH!2#g&O4#;C(YZDQ*g&rA
zydAg~cj;uXD!aedH>j80<>F3qX7~Q3QoRt_-!KK;u_Js|M*TZG2A$=yy+M2LE+;s`
zm)x~09I7$bwopM(?%EYjV7j?00O8`w(%S)X@uG}*Aj&arZ4F75eamdS%z59izYX@j
zEA{SUbtd>o@bCG?Hf?V!hH&3By$vklS5mz<a*d~`P_|$szmh)rqv|Y6_o1}C4TmJ(
zvc0X2QYm7~(2koISB4{*Z&$;mAGd68Ltvk0+Fk<)#+9|#0D^Jl>@@@s`ldN<Z9G|I
zvt@I7CgQ!N>ig0op*?>gsjjbgd{Cc4nO%t$2AUHK?MalGA*Rx|g0T%anU4rRsIE`7
zyt2fhRYg}4Uu!sHx{~-BATKULK?CH)m3`Ncioo~yQft*J7<w7dsLH)-$a~<Kde_=V
zql#eA8Wd_#b3G-=&r3OXtwEtG>8`<x;@i}!*NU}wj-XL@Jp&q5X?P8g8D|z=17PL~
z*l<EHu7K@Ae<~@jAsK}$C$E9#-j$Nq+Tm<BHdRMM(GnWGVQhVKcx6qqZ*1GPZQIGj
zwsvf1Vsm0^V%xTDYhs&|oA*24ckVgQz59<^d)2D$>h4;5?e+YstBOHeB&cOF*>Yv~
z$GxjZfbmTSH|nJ}&ylW{8+;lzCUZV8%R$uoC$pis&yOBlCRUC9Vc9VTo`p)$F&2Xw
zbn_!=Xb^E87rOb!Z6}6c@u*&;AAaOE>r7;RlIhxNW8PJw6*TTO#6O}KB}H8wRMqv*
zTZ3Gf(QpjetFt;GG-GP2j`w%N$-0&;{_<m00rAthi3E|ZC+DpAm$&sXTikKBd8`!d
zv(%m#AnW9KP{PuSqV_OzbfGb;eBc<dF+8OASzKFp_q3fWV0*wLVPiJr0h2hBM-gK;
zU6jtiLt$IU=*#*<(-PJMT=!$5znSa~I^4o&$I;bkm9B|@+DSbhPOQSXmWPAYP>n3G
zw<zUTocAf^+lxupB!6)MTcr@;Xe=fHiyg=k3J9@j1Ttcz{^;hx#|p)zt@*oRmcnQY
zy39m$1+rX=bYjqxz=sKyWgg0UG(T)OTQ7?XYIp0yqPpQRb*z%>q6gky3xF7mhRrk=
zn&hejgf0REf*7nCeu>jD^;+r*u?@JE!iJlBYMliZqzC-jf);1hZEK&u(U*>a+G!BB
zg^6?{SC0#svjLiF&9j7<jfRah-=%d5n5ib)>C<hjt+e~Cx5^5NoB-=>ZrJ8-I8(`W
z<$HF(mS>>5+CW?WcdoQ2;f!#OT0<FCV5!*x;2a^W2jXeo`r%GI11E(;c{d4E=m<PR
zKnoQB>uC-&&lPV0ffobo=|=t-E9ZK3E7Hpf8rToc$2z;);co#!7D|gVmnJn2&DS8q
zaSD=yjiTJ{ZxLFV%&?mdoOBSv`yFFJJp0rl_NO(^0zx$w)yo{{=;b1#40ws^Bpo>I
zATUP@*x6_Pg_FnzkJ?p5$qp)i0d7t^=cG~RjZgTdQD?duI>(KCttGgGKi+gDSdrDx
z(FZTdt_4i70r<FV7oh&VYf0P&n@5S-6P^nXlW%Ic(t)oLhMdbP1SIUBzZlzri@_r!
zAoW^Sju1#&K$iy@tGZ@M<^X!poCy43?~D#1cl7$bu&}-75yCxXwIk;0oD3-MJ9G;_
zIQVtdsx%f_K`s*=X9OI;n&+q+&jE@xGJ<;z#TE;@V2%}qn2p2)tdNvxWQEV_5_9y6
z{f<zUJYnEFejitb5srst&NjsX=U9eHxC_ts-G8AK<w;+<i(&0Wb1es{MTaIz1B(;X
zwgh(HJnzZH?7YeNugjk^cBXIv0l1-$VsOib;DuHqTMoxUy!k(?)}2Jwh+<7rrQrdw
zj=+mHEN7}1JZU%hKuslLOWC1>KJ5h$Z5)mwrcax+qX0CKDGHw&hVTrdRJTNinwZUG
z-W8xcN0M2a{SS*iS%OU3C?6^Wf0+pD?;scBF}PW4O#6KK!YtPy1O@~H&N9QB51u`9
z>ahs)^+_Sjix7@)OK#gWUuyX;r_DO_W?<*BFjTH3FRoD4ruR8H1WZ*%!(xWz_W?Qn
z8D+<!kHc-`y1>DV$R`gS7B{lYGk5!eg#-1_HNUqEq=>Nw^H4AgfMA^pQ0Vw`_Mys}
z+_e}(v*DlWm^dE#`b-Xk(+9)Qxt^R9ru^zc|C>m6%mp3`*MdP0bZ}UH`6Cd)C-Hne
z5Cu(U3MTwuywVzIzZK;i=fXN{&$A~FoSq6VgE)FnKG#Dcr&T)UU~*Tam_JlBB(Zqb
z;l^PO4F`ep+qu1_b9ys$pC50np&HdzW_BV${OvN`?rx4?Zx|#6j_1yS_JF5k#k849
zK;Qm;C}XhwX0p~uz?n<-S@CaoG@7>Q8z_%%Yj#UnrKM^ku%F?8##S2N(pn6G2##S5
zs7CJ{P8L|f=muOnP3`qwj+a`C7hHps=?Payft6unJ$CiHgBHwYjk(kiQEI)q*ovpD
zQpLuKlxl@E^HcXzf-8nb-Ouh`-c;A{JF-@@wLok}You&^rz!z}<*nIi361P_JCb#>
zb9p2j7~f(xdAj;uc0@pd!l&krg8yKBNytKC59%1}P&UUV;)xAzh47E1C9NhG8F^P4
z;NnE_HP0LwW*{Xn#KnBf4`AI9_p=Pgdt~tT0R{0E_d!Y`M*^hum27wLK)O=jiHZVM
zxQhp38S8dU;6d7rc&ls_F(!X418q9`FB1e2E{15czQ}Yf7>Cg=eY2mA(`9_E!A`kY
zw~9*z@<WvoN={X3T-c`3T0*5v8U6M^f4Ehu;SzSOnx>&zEc`=AD>H1ZBm$PAS2Ks_
z^)zL?tb@1Mu-Cpxs<_mq{DONdm@q?L#$I`Erhv;Pg$G4nQw)}x28!+mrK}C6SN$oi
zBvvP_V->R40)_~A6%p&Wk~P%Ov&3#BGBYV%CNjGy-Ntde&?;P?4TPPK{aa&S%yq#m
z6Iq^9ohP5VDOfdG3q(5zX3kWv!){D2ixiSBwr$O!mEWHRcHN*hBs&Qrxx`C3A~{;6
zR=p%yl~@3%Ul*ruQ!BPhaYj=ouM6=CTuan8PcD@F;=>$ItnIkCb!+_tg<tDRnY^bZ
zJXPulxISyVrH8d8Oc;k*RugRSk9sZ9X-@k~e8bDXI))syY?BfUTA%@+>fhAwQ=MjQ
zB(nD>;dT=CsAO}kHN?*Z-$B#hEH@o!i>Yihwwv#F)j;@_<F*KGR;9v=-=NG_bI(7f
zt!ORfB3HkQEdGIf=DD~8&BTAc*BNaZafs-NYq-pa^VPN8!QL2`vi4uKAunVX#LK;S
zvefFg1F!y|?XyFN7d;HX#?yZ9%xNiDTMul&E^X~*dId6SK(uk&wQiO|CY1G=GDpz?
z<uj$Vs6r1kr8TPx;4uHD;0Yy{tUDtfYW;KpCpNSuRYSct6J&7#+cd<z=xSkR2?kX1
zDQi!?E(>Ik1Qy>JYD|ERY<`jB_;c%wa?l!1W7JLowXcPBH>df;+%=0Ym-gKByR<6!
z&#P1Dg2H~8Q*2U-2gt1c3UFSR3AOeYxm@@$u0M`OiMXTAq6?~KAcNzlDmoW|Uz<&T
zlNn+WF^)c)o!#aLUz?3TKjVLCQ#8Wf>(=aG53xCoaW&<?*oK0@D0mhJ6r!s&o?~se
zyA$D25t~g{xAK@*RoJSbtY=o%P95ge8`d5X(a?W+8DEBAxudSH3#xBH%UF%BPf4Ct
zud;EC;WUlX*ASA)O60+T`UeMyPbb2O5H#3=R-@X8-sYATXL$m{VLCQHNQT+a@MaTa
zSZm+5d43b;hJ&}5$MOV`{k@OcEy{TAM$eY4z3J_y`EC=Zd#Z}9CA7vp%u*9BFS|;t
z1>)&r>YHXPeJY;@@cWJU+j>zHe|*_rT6x)y#2o1N>@!$ku;wpL#ce}`gOWw{j+vsH
z9`qt0twwP%-93}KX(Y#v+)wlEM8L16ej*G}kk_rMy8ckgRjx7tEa{Ip?xe_GazSX$
zdH6drk!5%oDdUrj=rPw1(ttjTy&$4Ydx)VkIwX(GPr%7xMPX7af;|Z(3xf~QIvz`b
zh7lssLJz@ySIvE3fFyD|Wz|G7CS-5(MgFzJfaDG_W{>H?D|*-h+nN32um!aEB7f9g
z<JK*7)E+Yh*2L)xo;DKLfBT;3<<<n_ua5Pr`*%^96RPb@;VsYjXLESR{WP#=TbdP$
z8m(AI(dpVjoc%6rbt99rQh@<w+wf;|&FL8KRX32*aQjg5J)qmEv}-0YAJ$rz&{BJd
zlxd{LsmLPML7$D#NtW$mFPJJ|5sMX9p#1%Qts`H!x;;46Eau1b$=)ICyaDVqE>RmU
zP-KgEc#EL{Y~ul~TL(8rc?908@-kbY@)HLLmT4gTY3-SwU$k~g4}^#P*kGSwr4A|7
zT%x92L9Opd*jG$cy@+*tmB1v&Wmf*9W7%vSq;<qJS?rVdqPkq7T%4mJtYSW*E?l7Z
zN6mRjad}V6@Rgb00>Tk~;m{UEgMx#>tb>gJYLqXI<Y#!nQDOAcsVgMU@H_L}&1hsR
z(5y_`z(Z0jc2PD?(BBmFOI@3!SOtyPZpg#4!|B3`eq<$6)4sx?3lPko4UQ3JT${x7
zSpBH?04v3Pb7E&kd5^|3rU;DynTyuV;$pAxn|TRJ7>b3#Sbf!wMR_S@c^n5+s~O1D
zz<Y2iKtAH5W{$k^qT6y}CPll_8yTPgHY5#T9Hq`*_|j-JKuga)wQ+i}3zO6^t}Ix(
z-j-5*?%>V;Ja_su@tsS?JKy6^QErD;fK|q7)U-aD7`_=U_qK8sM`3pgG(j{?y#c7A
zOr-h-v}Z*J-{MDUH3GZ9>QeqTqMPdpb1wT@p&SDv`zgm=;DxSQfqT@Ils0C^h>jEt
zJCRenZmOP#Ra<*K$zfrD{o+2qYhYzSQ6dKql80rHm95l*0xA(0?w^(jW3AAx2e$mN
z3N>U<<&9f25$n|&MbsBkh~g>R4%PcYl}Xgb$v8z&-9WS{Tb?#q8!i`WTXu$*-d`9%
zL#}gG>jrBOCiF~`m296A5JH^{2yfJc4ADHPdK-a1QeU!@8HCq(;AU0q&T@R?VC&dT
zo*S2pUk+WG%eZ%)HfgIe;e4{#md@eVGB!x)JqJ=78;$k{j+@yWD|z^`y{_+n>)}9E
zA;n1H;#{~Sz0+){avIBYVVdT!0V*ZrAyn)IMtK1JOOPF`u8-+MZw(X~8r()cdh)0Q
zPE@b<sF4me=jtNdG`1cY7@g<scl$5y{GCw;H7y_7=op1D2y{;c4B0UqIEZ|ONtNtA
zX$r929Jm4oB{5Zy9pxIG0>LHVh?thVEz&itmb`!hDCY{^Doh-0RzUxNxdr-t2$x&>
zPga?A3a;20e2C=C##;J)ha*}7GwPa}68cUZlnVA*&-q~Y`SAYxbj)ZbxjF3yk-ai4
z;K^LJTTBljtMs2q@QM-U;G|Hp-OG_cE;?+qyDkB2j-4_1c20eJMJ|>tWdlmj^Wp8H
z+;8T=df^Khz(2?(tR=*f@v5+qAAc0GlNQJ%E=PyMsA)I+0N+O2r#7>SYs5a^1#jwC
zjab656b6)^E5MP(l1#(Oy9C#Co5@0jMXyrZYJqCd$XEU%{i%a?j`iyYN~4ZFUQFVr
zNs(j<hCUzEjT|x))5v^(4hl_?LZ;ObJ3(Z2r>(z6xj%REB;)}}t;>9%ET;T%GZj<0
zs83wIk>f7daQ^6UL{vJoVNPn7YJfkNi_=205fS<+7xC>cQ+JX5s0c&OBmz@~PTZ0=
z9S=@4bnaUPminXM4#z-m3qytC2w&&zcGRJETkRBHVwC*`$u)<aMh5qhT`Qxj>EqyY
zCrV2MTl)-Dc1h8?HySnVdl9*a`3zL1G8yl}DxQjHV9<(V4r&LdKqHOA!-h!iwQE@U
z&8g`aInZQ_Or=WPwWj@0EVB%!K)z;ZgsBqh=%2ZFjz$kfiXHNvkZ(T2;Z*4`O&#H}
z07fvdT(%{+%RxyblDp<TOq;BDDm86q662L8Ny^p7YAVdIr4o2lPkWd0p2c95{y*C%
z$<7otGTQF$BzcE`DpcTPV#92tRaf<LSK~ZY>nc#NB5mtzqSd-KKsJ_UdlRJ139FkZ
z53<sH(=sebk*;<2$#OcXY4%BRaDc6d1%ocmoGB)lduZZkfZ;=#&10VG%EVw4DhRJq
zD<;sBh1qt5KT2hj0#K6qB}YCZ%o^{&^k2Fu-gxEmrj0;K(5Od+tPAZ*_kL6RnJH2Q
zw~z}Du$d$6YIlhQl$xe#srfOcW`tE|`YGXUX;geO%Tplp8~6F%BJS;*#wE1nuMe=8
z>0Oj)zjHWxy<CPW($<HvC_@)L+8cycwBsF~0Vz3cZ>O_CSq-wSh*So&>p@w{$T)R!
zpU{TBS>^dA4lM2Vf@@(V*LojYB(<(Yb0g5&GZC-ZpYvdlScNoEy%0gFiv0}%&(5jn
zC2=s?dQ6Bwa;R^DO5m5e(fYc#FGLs}zcsJcouS*U&xGm6;_8>+v4hPy^)f~;LXGvc
zWP^lNpDX}OP!r>fwZfWiAvZy_7pd!zZ13cTScB$0N`qT-+owQuvTJTSvl}YCOyQ;D
z2(`jOu0FtZ0ju+wd^k3L`|gDor{I8b#dJ|~5QlRyI`1k`hzzN~*aNuLn*he=tdcsO
zU>xE7#UbxN@O#bl91^4KRlpELD=8VI`!wFY5D5ATxaQNst!#bIhCqP(KN_BhHskc!
zGbVu!@xk+|IqHF~IJ+lgR~bS+9BoB4IElU1Z<Wl@ofL+-YiawBo>q(4HHsiL)P}iW
z`m`iL@&(nd?0zKXOjQUJz)M(hiX`Q~b_^4Ve^bxrH17zb<{hx5^3_41u8`$rblb@d
zN6oZJpzh{0S4S=R&RGjabS4cpNpGr+`^(dDH^ZAfh+Tiut*TA?fA{O+Xp7=1UoyHz
z#v-%6T$`UjvF!x%`&X6W%g<zr?ubOA!duGI#O)htCNqHmdE+uM2gFP`wq#So#QfrV
zI2#Zr@*wNP_)IMb4oX55Gn`ejeU_zOid*$I2o4SOHMgqqxW+n1iK=n-T4~*GHgrRc
zD-L>Y|5<+98~<54HQh`&JH|>hidt;|^hV(9)BGk=#8PT^u7YvX;`hKR(&r6nMK@$~
z6*22@py8Xt7i9po;)Uu8K}+suzill2fXj;Vt)rxT0b6z96Qia~cIU+*@HrP*=2%io
zn-ucYQR2E<yL8!`wxSkHxpc#W<NCGWgWZj8R0zWQ(j8!i%taCKD0Rt$hEd@$bfLB<
ztw`?@v)!%bn!z^Y9IGUzv<-ccV=hTC1Y8{@h*gjL`Enj3m?nmQ$XCyBT;xeAK#a^N
zR!M9O)&(_#ZDmfrD`d;&USj0wuE8`z{Yk}uiIS?ugQ&3QX~obX%VLe{6Y7wL4YRHf
zql|2$^hjmLuL^V~XIV9FmGjio3BHnDn4JHP=0&t&eptf(e%CI<_dR-I8nS~oEh3fg
z<e2+3t;>-k$6W=f&t110IUZtj42Z6Y2Mn-b_`8wgX(FvBI~n%Hzh$+_z#6v}I?yYi
zS*Hc{HPpk=h3`qRa*c<^Qr{r<dsyvh6FH<{Ts1GsIl9?7f{}hlFa!}z(;D;z3i(+H
z3eva;@T$zywfg$FeE{(<O$$2=JTLYO`0vOGam|A<qTfOyXGue0giI^<H4*WUj_gwD
zbV;G~HyJ9?5$nQ23{8sH3Q76suggOX4^oQ!%u30IkmDiuNyC`*5|$EFv`Yp<);op9
z2)2+u)JDolwlxIy5Xhb751*0Ysx_2~jt2eYWt@aJIYPw)RE$&r;`rMJ0K2Xcol1S|
zO7RQ5U1vl$GSDl5y&F>2%|H(vmjjT@?26Dl<I0GNqypa7YL&3wq=g)Iwceyi&0{m@
z+gObpU|0IaB>=-N)PYqg-X{s0%ET0e)m`#6=?ySWSc|TFCFdkgJ6cY$+Yt_<+OYNG
zYNvCnT&VT%&W$8Rjq{JQI{6c(mWwWA1|18(h?J^|zDUQ+JBTi1MpvX7&H@u>z0Eaz
z4MgZz`0->j=ViWZK~X=vp|hwmc8SKRR?*8CovBN1)KsbpFmU@#Te~dSPV`ZZ1D<u<
zAI;d29v+O`y>SgOnwK$z7MVxD_Ci~3Wxf(4SQ~w@OdEZ;b!evuk{MpuCoBj0MXVkN
zR}FXA&Cm)QS2SLvc^tt&+ek2+5<uHnFf9}<ZNOVDB88k+LbTrv9a~S+Rxt>X^QY0_
z>?a0M^_e>9ZMucH;t}d5-VH=fkz&&+lMwdO5nMMhD$iPso{5uAYw0^+1H>Q&&+S{G
z1yq9veei-yl`w)Z32Ep%PoQ@w7~41Ec6mM>l=4Z6eTK$bnU_3-g{Xe@0i))Ng_>lJ
z`%O_=@Oy8}|IjZD4&b4ewZT&K2&O>wH>aZR1Fq_;1XCnX3ARRp;UN_>c9~5h`S4bc
zz@zMXF=PTyM8lH}QcCIH(-aDxN5iX#R>}xmQ8vZpg22aTVv8{`5!Hf;T^u(|>E~G7
z%?LH}F*r7D*b6|=QzV3Z8*FMdfyN@~=T3>p7XuU2NYOM|5)ffRB$f}Qaj+|*Ez#A%
zx}rG7$U;qZ%p7kk4h03>Ui1I~gi9P7(u?0TN{s~ah!r@0r#p=Gg@~dq>^s+}P>ums
ziEM#>hQcehJ*7IfP2Q|7$xy;B->T^4PI=*soh4aTR^c|Udx#_zgNC}{=}*&?tsxD}
z)`SAZ1O7or4_B?X|Fb9P98LN15w?S~j_P`EmvU&nBmJQe>2nGhei&ulAT$)R+xX>=
zRsk+}81d_tEwx7QoraMGo!yGPY~Tz>9iXP~(rS&l)n`c9b{&F4e-!&1*q13&q>yI@
zNFb%+@{X-^^L&>!B+V)80PR(?-zjUmfxc5An~Y&kf8<J>u4@6)a$oq5{)m7S-PJlb
zhpZi}%zK82gH6leyg*mb9-3?omy`l=K{n<HHGS`X0oPDF);brJLJRblKH^?kF=mdi
zJZc_C5jZCiVXev(2zm1K_bsx7>Zf6lu`Nw>Na8zOm7KZRyAgVq@awTTsbmKGnmrfH
z2|bpjs6tNNfwuvuN7w?U?1875t|f#%NF8rn)uA?Bgr!U0rZ{c0-8nuza10KCMnx_n
z!e&7&`3w`nqIi>)i}f+eMqJ5;%Yit_b$2xiq3n{!twJ;c5`jXQ=(aa86io%hCzk(O
zX+0n)7)^%PK?*kH4q=mr=caNWzL%R<n?@{4PXm}F66g2@2uVha3ojR1q`foN{(Dae
znBw0bRPcR{vHIbtE%ewI!P7484oM;rPzVXiRLFf%1!&`<4ku9f-;!ZA%HeFsNEquF
z90GH)My<e9$B%G4@lM7Tliy-0;qYtaNL5q9N-(wSn+{oGRIk0aMzm=@yW90Zl4lF6
zw#dc@?^<%;2MBM<RPVjQ1~6uXHWMQ3jc|@NrPpHbuE8LhQV}b%WONdxu6YH@D0m-5
zd6QSaid`JRe%2Dwl%3g$BDAQw;<t<D!-2UoC5e`|BM_*-r8rq8ht$%08jLJb0ilO+
zENt>e*<jXE$#2<?<;#I@>5UsD1y*|_D~iChBjhMc39kq<!AS4(oQN~mzW#Xx@Ryb-
zrC7CA^z_#E;c!QKArrq~4tUD<uR3^w;3aNXiOM+WtR4*3=X+qA7J9^LyCY#3V`YLk
zNRzHa?I9(My2i%_!n8?doTZ!&O+@K;TK2BVV#0IL4sM3o-~)OmE`%x^`Bw%t6Oj&x
z{DZ|Dx->~7Gs<uE!zqw;Atk9DCfkGZ9+J-OFYtIgB#B>jATOyP7C!MSf7|wb08P&|
z?-qEpOSw5B#WsU~2EkcM5wFP7u({B^a~w)YxX>l=26C6}c(u?iC8^*Q`0G~%38C@u
zeLCEP6*w1VPUgjPRRv+9p_FW;SgF8nbayO2-t8sbo@^3;irU~ZeePP`okW^Bdc7j^
z=x?2e-`n=$LhG&D_JsgTCX_s?Hg`>MUnYYJOKXKi<(tgn`?k_knFVQgC^x!io(%N+
z10Z3wdp7!kg<6*%8IJJ7s|Sqm3i?~1i+mb8mOJu5#8<ppNYxjZ&$gr18tFZvgx=cd
zsg`2qo!lDfmNJ3O6?ZFJe#`O0JK!R^xDbFGc$|n<Hri4vzM>EyU;vcjmnHLK&;a;0
zi}55?LG?Jwg^$3u6G)`CndOq}T{s<u8mLZd!qVE1Ba~hXXNb-UQi;pVj3H^3`YIYH
ztu7;z7zCTPxaelV)<1ZGbYtC}J^so|21tF+EMRLYPoT<#1F>!nkM*a2^ic>j@sKv8
zO)#VKkq?nVqUmLG(sQH+WIx-Aw*ZUW!Re_a&fRuU-x1N@U^eR(^6QT%v%JLhVVt1s
z#eHm)2Vx@~$o^171TmumSWieM$NP=)MAYm>hGihKGfg*0PO8G#b7^>(tc3JzFbbYq
zZ=&`@j_M#C!r5Whn_!Xs)*QBcQhFO~{}T{bGC*jOgD+9W0`rBwC%9w=4_s*OO+WUG
z^xHC|lJa~@Y*wfPzT=+eVTd(zjH{s#;fi$;)_xl|M&ce^mNex$Mq`XPKuTmqm;$Ek
z<c+Uk&^(}M$br|eJS-r}{w7o;ur1crLyBqT7aHE~&ULyq2;Y#!z4mn2gHucXTOm2m
zd`wVe+eou2Vk1p%3b|a~E_TSEBR<=22l~+{Gnc{$cx;}f)d>*u(_<biiC-67l9g!1
zs0H}QYMP~HVu=ZBkI~~IBpn@mN@1U%Zc%v0qirzIhh9ZyAy{?@<v*lIS16wqV}|sE
z&w<4{^9R=Oe>jFC9`7RB!ZIU&<ZlGecl#+fZ-x4(7TTPLuZoIs<&s;X?DxHb@oWf{
z4M*#uLDo@LPOt)1odV%9nk%ODA4i1GJ_H6WqmtEgWAOpE?ecF_rijbot|~*<t>bw{
z5$k7KSeal6YF|5rz8LA&F#^>Cv}%DyLsM}jg)doj7`QmdqwHiKC2M1COPGwg+=`ol
zYgnncjpW}2#K)i)=CR5NjJ|_-XDgZLVyx{M<aRsq7?3DlhA0fuQifL{qh+m4F3^XI
z<d6Pn?dL!}VIF`81O+ur*kHfVcBheEbJB+g&~kEB7lj5?=LK*d>h90uhE%P#2KQLw
zX%&|A%GY(^DYI+@rov#)ZS+qdT<q)XTBh1eF_>rv)XVE?TLcB8lDKhmaXG?YItGTJ
zrn(g;hM=ZC71hn*W2WxI_IgIhU#$}K$iIT_9u@7jxvjJSU$fTlwuDTnW~?>mrH3E@
zpyLLfLB4W;JOPfe*RYP<WACvwNR9wk1SbXE$mCnwgKzjS*2+~sS2C8Z&)r7^x~>H;
zSF0J^89AJ1BQWK+l>-Er;xR|Q>Wu&LHPK0MtHFlyr-}_ertg9}OSgorY}bU5Rvs!)
zlkCPYm+xKkp-#*J^})OdZe?a`MzyA5jsRkiBPwR<TG;nNIn{L(+!j`!%Li@~qw^FP
ziMK5oPwDmhZ)Le*&`9FL^K6I#Lq1E_5)!FOAaiNf<o$k7Co5OhJ;DxXVY-YNs8~8>
z`MV<5FN#<)rb|=m5jDBG??*klij9twC1JrTN6~xW0#IquNu_8wqYFp-@ya<8{v_xp
z+>icFEY@F*3?oJ@jxZR+FQ}%j+^ej&Sr*&3uL5GbXD`EqlsnT1Lj&<Jwu<tDL;>eg
zqA_&w4Wg3Fg`yjdN)B0@S7%&uTrSFQb5X&lC<T{9D`3$2_=_2{Mkifr5t!h}?1ju5
zQN*Z)j+aiJ{o=MG%#*+<D+~r|ptzG8%D=tGSa;J^EqSSEh|$*(2xPNlUM{8@MneNE
zl=3d~rh?fld8Js1;n%lc_O1^lTo||I!qJxd!k}xrct)9sJ=bz{(||Gy#zEOV=5CRV
ze?CHZpgvmb%xf_9cnw5=Z5a0D9(oG}tm#Vzhe;XWH>M$-Rs^A=+VYz~xGY4R;LBCV
zW7sMl$w@^t2XUdoXBtaF+Ea+Zo##!7Wm@3@trWlM0Z}rqZ^w&Z*p^?0*eNt2grlZc
zati6n%sk;W>`I%NQMrdP0Ed%`R|chH#tcr!db{c<jU%bAH)b!UNw{1U4u@kk(|hjV
z-nQo&;s%r1ylbhg(jis5CY`CbX7D#SPcJsd9`g@koyVIYP_I0p_T{!3Z8$xq=Hh+d
zP>$RXs*8Y2{K*+4<Vq7eDC#AGF7rgoLO-{96P&f&?2EKvt%C=rFrqGa4<sh*ECh>I
z;BI>M)(mz9Fnjri;Wox{)7e-6Cr*#9YrR>X=f+s_uR~i%4GFZm--&djk(z=5F+4S0
ziEkvz8a??`E=b;j$V>END{e{|Eg{qBIp6oBe0UvWe7jdfQ_a2$eyz<h2BOKe&<T0O
zhW<zTMgai$AszhZ>5t+Zh-O_s`kQW^6INM^2KQPE3~@W}Uly^AwWkkOAxB^iW+|<P
z_`2yu3#%>U1102Y8?j3>1*Ml97w1k>-4lNph=1yg?^)=#;_xkZ0=Z2VSlTi=O`<GS
z1mQIlB#v+N#c3tfUFMBc&TjfQ9l=b&Yb3AU3?1h;{DF-V)mXqJfc)$IsH6gl;Heql
z6UmZnokQO9#lo$W*oQJyVba$VIC1?`cmQx}^Qga=W-Clh*ek2RmD3}ucipP7!g_<R
zNF-?QI%}K~tFe<3Yh}}BqRN=$M4`uH(6!^ZhytiI0R22D_F|Nnj6@A_Qtk7U?4Q|x
zJ>y?vkcDZ$-#bQmuOJoEOHw*lz1EtS-6+OWuj}AZu+k!NcQuu_g|%0#9*QG>ZH)b>
z5dWrlRpk8|l7`(W`nF)#*8Jbql|Hp)LDg~?6586A*qX$S&cwa7sI!)BIl0@K>rmxk
zVlKrJQH%5vWv^o|f03s**h;UYc<67aGMr8|!V3HlX~vW_qbF|O%lfquY%Cz8EPgIU
ztGn;%YD&N`*V(R>a?@8LDr`}OgEgQx&#SQ^Cwoy9`!P-~+?YejiVw&?MjxO@Zf`E~
zaZMUmRAEIBEX!Q1vWT!ntEG>~bG2Ea2jtnxx{B90nUxR#KoZaq&84lIO-LQ+Mc6Hw
ztf4FV0<~mc)9~5S$bV`ml1yrQr3(jZp{Sp)j_RJP9tLgAl0#^W#GY#RThKx!acM)A
zm_-b`x`09`CpD9zdP*lf83_FJ%_4m7@%xyGYjDb$LG}I}YEnkz_dK%m^W$ojQLKaU
z>)@-W;_DJ|M6dhned~=&<@Z_l;`ZOxHv!YXVS;#m_Z`>k?w58KVLSL=Pg96HIRZVe
z2f07rFMGaj5Jz@C9WGXCc1WEKT(X$gyW8X51@8}Xzy2Qdd{^c>d;BiT7j^))alq${
zdWJ|yDKOTn)b%bCc2Aewg5Y<r*z=le@Ap#U<g%yDQS-CKW56kM;_@N)At?-ETm^6P
z9$QkS?YQgr*IQgq!tZX##pmyg;O<I(g3y-)8~2o-Y=d)m3l4_c7I<5YgD>flyBa%B
zf2VSPe!a(C*5?H7syM{*mp>D3U57b+G|nW$5v7hrf6}C0!{!ivd4K#7|0Uw|)Zgn(
zMnf7J+G9obG;g>4Y%2()GySLJd(PFFPvRCm7nXCUcPVQ6;Pih^Q)!n2G#MW~M3&#J
zT<h;;n?h|{Tb8uxnR2aSXs4f-tT2}KEVGgY-BFeCUH(4E*BUsWHUn+uFdDRTz6|a9
ze&spbE7ze`>}WikkI=t8s?i6Ee<<H-8!V9+j~(k<DqbgYnuM7dv|_I?wqYyX|2)l)
z_3>O8=nViX$K=W1wPklO%C#aH>8^s1nN*RNv9_<+BNEyMPZ9J)O@O!$(K`M3;2&j7
z^IPV=uQ|mNz~Eb|UimYQSz(lTUA8Pm@2L^<E5DpSe}BU&uk9XzZf^T4LwrQ<IP16^
z-RAwYW%sx5Uj(|+bG~fc18bg@%kSc;!`pxPX4HLYG=09DRo>c7mP<r_LixPkZ;GvG
zn#g`SlXewV`Mqg<y@1cW4OS=cus2OTRGXkOuc*i$`*&7B6i=wgd%b*D9{hPxw!E^^
z2+@u*;uqQdP{vz}$QsAE8DPM4aNXcQuWxRM^Rw7_mD{KMRCasAN=o);`S;7Y9(&H$
zZ>yOAq3@aAz-|W|Ges+I1@Ji>!Zu7XY68KB7YJl0%A9RX2N=AnqV9bcgd=419MP!q
zfE1_~TzXjgv}O0<nZuvesGQjf$hLhCao@!p0#@uLnRvAmZY3hUQ}v-+G3cq?h^{f?
z|ETWKs`!eFcN5_`8Ct?z*igv1p9zH+QgpF@9+TMad;Wa?%Zj?@N&@@k_&D^?9EOR)
zs$U^ctoYzU*o14aw4lgejdbVXt53MFk%J@kR-;C^K<U+P=Jx)|&X1paQg*Ph8r8vA
z+`=yoF>5WaB``OW?cw%QO>o8H4Vq!Dq9yLsR`9v{FpeM;^Sfcj#`x2H!>mP$H-6?y
z&9p%Av*MKj(O4YC<&NLS(9*ebkHBBVk>}DY7&ALlXBQ_kBinzz*&ADZyBe8@{y7p6
z5wUY~vvK{0&-!mZAKyQh7{xtYBvo9DT+E36i}4T7i0S);h*4CSh?$7d#ORv}2>c`b
zUzAbeyJFw}kT$1hqGuxF`0iHu-$LJV{~iR(e=8$mRP}T)BVtrCvM?heCu07WawQ`t
zv+ur`|I?OH-pmwWBx3JDr1Q;U`e)!o%q&byM0)=c7yVZJE$>Xk_TLR8o$Os5{>Nbc
zOUb{u|1|mjFsgj3b~3VacKAn`iRXXV(nKy!u4ex^6aAJFGjju&m?=w&{KNeBT$Rn7
z?OmNr%$$k-SvO^v|2s9#@AH4w_n(!LGqbaBu_WU9?_o&*Y+THoh!`bozE@Vv%*5XG
zUz+|c$V|k^#?A3hU;j3lN7kjLw+EVdbIqB`68{!I{{nwHG+8<sY63BIO>i&}a1ydu
zP81O^>SnF5u~-r;)E$zRzATY{sKx9J4mnX^J##%0!TH%8im19f^!5ZgCc2UfX}vxg
zCq=Ti7YIYgv-4Ni&S&=qyP952HBZf3wu&efu^4F-RD5q?8ET2&%g3@Hs&N&u7>*#|
zsS?POP9QbDR6?YbD*f-tA~wIdBJp6DZT<5c<x#TFm40U2qXslHqvB6f<GMY3pV0V|
z<GPw-(+j3%+M?B;gd5a}CDR%2rbWzH8=SRzAA^n3sL<SV-@mCRoWv4^EZ*$oan{;T
zjAqb<Tpv>}gFiKzw$IGOJ}keaB1#R(J7LPyq-;jVeiGdwF7{!{M4RH-TV5zkh7N}g
zPg2p2!BA*PlSi}71h*d17Kk|deoZAh@#Gh#=_g^x$U4HG1FexT%cObk$sI0CmXaAL
z*P*RAiEC?z&?PED86CWGCn-@K;sO~_guEJu1gl9FTtFsBxi%PiH1RTiAt@j{GFb9$
zM~j)VnQzsOVF^(5<biHoLvSX-c#~`KQKs4MAp|0zGR{hF7Y$@oJk_R)T7|J?Z-`!e
z3Je+(B6HY6jwweB$3IQl=&&?sG&8;qG+2c6dTwYl))^Pl=Ey;jH)sygupgKVL~`1s
zU@NE5aj4U(L0^8Tf(p*barfC24^;fV57qF#ClJw|T5j>e+$`8=Je62WAF0WQV=(BR
zv;65cg*Gx}okGb;f^=?|@tvn!KVdQ7#7Y5#!|UkbByCezT_7+m#Ub^BL7q*VExd*j
zFO%<Y)rf)j^VW()Puj@LCGz>Eo#W+1PozC)K>JlXWU~!-{5<k&(x_8mPnH2C4?r?O
z^oP@`X#aFm&eEk?4=?aXck9#WBfL&72mcBS0CJ3le@%;EB1yR++$`Y`!Hv3Vz224f
zZ?oNJK>7X=qF{KY>Yv|YU0gwJIp!v3!VLq)#Z>4MLvn9)*^;@%Gwb!;ve726TF8zI
zYWV??qRRC9%XE6AgO~N2gSMIqL92|Z`KK8R^RBl3`4tp%uTC#jvVvCaa3#g#LU?vZ
z%kmp2Y-n|)B*t4974-HUc2Vyyjum><Q%LKf$<}`g9OeYj68(zOVs&2Cv;CGBVBslU
z^e8roD-6Y~FX0xXIGm#M*FV>#Ogee=GYjZBF|g0!<0RstvUy!ouk0j!6UOAW74FaU
zEh=f3ztg2#Mxq%4=Uhpt1ZhX+?8~w9wDGiosxu~tIv2{NjCou0KjuttOH|XYWCOND
zMcBwfhz3RY$ikB1P5gPJaBaS`ZM%k5^08#ZrVRH}aYV)?j?f(7A(kUrnLO4_gJ=YJ
zC#i|Z7LKi(RF7<mFZ+z>uIRdBYn3r9q;gM0vuLEhgS-Cjp3^!lchNXio9?Ray0SXw
zKQCCa;#Zb}X^V0z=C(Bcq@Gd-G&lY{47FGmWF}$cm44utpj2Y3ch9NDQ_dKX;IQ|n
zlsepe7;@%8bS+y5$bWAor)6pIr+$iJrTI}y7IB6#y-26_`$={MEv!HrA&f;x1<MTK
zj+bGpTpD4`Qz!eXGb~gi)6Ga6jdmwrle=Iwlw->L!Ftl_8CB+Uq`7M2n0>fW^PgZ|
z_qwZf&8NJCnq<p{(*>Jm7Fq8U`Z;~WjWr6h>}H7#aRZ|sbKYcpZOwb@UM>xGehi<@
zlHs${*<X-L3SPY@qR#o4*ZB{s&W~~?RGTA^WdjfKKZJ(oK+1p!#C*~7x`)fa->6J7
zm{S?pI2Pc?^|gysaj&s4W7J7OUGrqdXod*KbJ3$lPIK<}Yq@-Kx`}i66c+$Iv{r4a
zcN|sdqJ>7vjcLLYKOn2*OM@7Z646-b4ik!EOqqWZ59T7dr@^OYGX4&>V>35X)~S5$
zAxA(FapejJHM4v?(?g0Ru_9qEqb8>*#!)V**idUiviXp1PB49PooH%Lu@0w^KlZTD
zISzvkFtQP-lQJKrJ%_1t(Yz{Gi=)Yip4dKS&Wz(U->Zfq9>JYnwQTlNU3{X7z?io~
z+nWf3wRpF2h_ZtmKnZhOySvL5^+jNeIy(ycB&fKWO2JWYtT9D7MxI;`OG}P>7e{71
z#k~uX=@tL;hrzl@BF@V?JM`@4jFcR*ZN?%<!){~SV>6CZn}99)bHT^{)#09scH>TB
zgD5ij5Dzn9{?}E7?@@Y8&C)W0&u3Z7PX6`Wz<hN|#70Yx7Wvc{@rTt|;d$*wu@S_4
zEfU}+fs2JdNyJB$-nDYKTZ2mQuuyWH@NSVu<Nd%VVc?i(fIQASUJ#^k<kvd~Q<shY
zfD0+eRsO@@+l7OH+v^d7xZ_W0zjcGN>vO`94l3+exTYwM7`fjIg@A5=qtzZ<QU)V6
z$lop>Dd*l$0~c5su_PFsRo#P1L9RcG1Bu&yx|>KPmR|QIs%6P;)unug2^7(O_o{IO
z?>w&gU1bu#PlRsgZsp&fZ5uo@*1RHedj>FV9^zwcyNQOg;h6;%p1`Nv-vV`XOww_P
zNvV}Z&cNqH_WHqP#LvOk!=}+`2c;cF=t}NipnlL+htG)7<BOO8@bHz%2~ai$-ENVp
z3J^`!vFC1$lI)W&#I-*P-KiiDxVO&opSqW>)?4M72M@3}x2buJucIU*>+9{rKJLsG
zYdr6?j{*vU#i94Wgt*1Celr%B;M``PG%1ah2{dxH-rcpkGH$f}X%ncK5fs(dnVIzK
zn#mVcme@MZT`@`_pvs|&jl5>Y&(`e3Ez396J}2i2@lqtu4ST~@7%PgCmUAdgD2S1k
zlf%k8g^rk%lmTGhr@W1?6V|Wh8&);(&<ii19-!R`WepT@b>c%5tyvW0-?CT{=IW53
z@94AkbRD(D=vCJsO(#id&E|&|Dr;k9oUMGc@2tVc6hv(gt!Z3VJTATSJOV-Ixl1q1
zKPddb-i9+MIcW@T9DES+QkJnQQ!h{Dk%f<onN1+Gu18Q{>IJuBB8D&~M);u9m!Fcl
z&ixzp5ONwdzfu^sP*c((36&x2YiqHHn=OS}IzvmjgY9Fw3q5^0hpNa>iPProqqR1G
z`$o9qc`rCj=v{DlI7nVWxQ4s_{xRZ5wKns1Eh{@Q0Shnh<m#1gGZAoj$m#3^BY{YW
z?owi-TYtF}%<=Ujh$AibyX;*S=4Cux_DxLn5{=e{<4e=_qT-b>Tiq5=pg^7QSBkKN
z54S-2gOIT*cOWd9#Fk_GhFn9j-A>)kbp<Ns+~4Z(s1MzHm6e&CE`*8<KL&<yL`%vH
z;{^vClTGShn)l~Q83X$)8gyDmhRoAsQO+E_edIuQ)@nydV+e(jr_IC#U$2zU16K~b
za9i>*pf>c?_cBS+<)qp&2Y^_8WyS3QX3h3EM3?Aff@E`9=NDxFIHS8wJO{5pst-%4
zZt?+<#2${NjJMQ5_8$cq#pT53B<Cc#V}2}RIIAe6EJRV{%t=DEqnp!dwc1EQ%2e7v
z(=w|x_G$>d_DQG?BCqZ*LTxYxwG|(-uM|ErUli`tSpn@5zvjr2DSpttK6K1;jBD=`
zsr#%Xd@=~GC{s)Uu;+cGy=scQGpm&p=&=73COpJTZjX}W9I-=|!0_M}H%Si)q$4+$
zI-ZYukwwR}CM+;@o3*o*7rp863gOq66s2|@ZD>voBtjGp2-iy&K<x_-ZxIh15(`9P
z-kyH&q?T3f9ky6on_chV*iKSOc$LQ!L|~aZQsv+nA_18I0qa3K!$hf_EruJoF_lbo
zGIeT?<n@OKqbO`7;JoFhMpE54ftKI6X^txVepA@^B|@3)LLw>!>=`{tOdEkB&zl(A
z$olYIg79<tJ;t#ySU@~C)NHZVms38_#>IN9d1Vq<OG@=H-1%6cMQ*q6NLFblt4k*s
zFjp5&*Fv;CC3Yb%YCj+IQqZW(UdM)n{)BDh+I4{lxlCD;tnuzvDEa;y%EROXAGDaT
zGon1pE;p=ahib7IsRcMBw$+Ff7Uba1s2WLvjk~C*m1F<lU_`(^nFI`JNyg_uasmBK
zhil7d-LJ&GzOcX6?%~fvOVB07hh40XQz~I@SG={38?nbDov(+J3*fmwj-8R@__~jN
z+XwcUY&Fn~`!zYPWSz1em$+;aLVeU7rFU`UqL=<Q8ZF7Sfh`&y92WK#ga{>bDxbux
zf|pqBNcmMOCMREz(UT4B)H#*MIAea7zo9Fl)4B4ptb^=_({{XN`N4d6U@&LZgWV^O
zGmbMceCs&AZ~+kDweyVbhl(<)ql<mF__cPYQpb8={+b#;pGICMyPxvnp19?RQO+1H
zk+G2Y(4P6X0ShgCmgV&F2-zcIEa#;mRo2hZ?P>x3Rin&(R+M>vIEUZ+Xtv3>*baxM
z#JIPYb*rKJ@84tIl98w$u@7zTvo?}_6BVhSROB)g5@m_OzyH(<dX-?irMPOI8{oUR
zDSa|S|M)2-6AfGNN@|}<Dgg4krKf`Vu!_{RQNKLQOMT?rv=gvQCKYn>Y{$z_)&<{9
z-s<aW6NQ;jUr<zzzR^<CE4PH4DcR|~yw!4at4M{pB8X1EkAp9MAYl{Q9cJKlJNgUL
zfQN3XLjIJh8`(fmldAjggvI{EC^$lwD_BcFrAW8B_=^k$wy7c2DnXk}@&L5nKu!~M
zg^IgrvwN}2-MjLK9lCw8N0STXklDJz?9)1jXp1fTe0{(N0!3hRqO>rjNtB>*^%%bL
z?4{UNjz3I-devH+^Hhc&@6a^4we)!|V`Nj*$|Vw~{WcnBMQG)BTKLa5a@iFbN}5#0
znoZsIPAA<w^Euq>p0DA8456^ZKgTut{02W06tbF3$LJ;t;rIMkzs9+s6D9U}foo2L
zbWMo?MJ6X=JgI*ZsuLAtFhTG^(*pzoG!l6lo7cZm<C%Q@G4@^pbq;=T<-8xfC<>xI
zw+hjoVzk4nyr}a;oZ`PB#7=ze%l0Px4iQHslqiBT;SyQ@it6GMT&~oyKNulE=l(1k
zL8s3Cn#FXL)FZW{dz9J=aF74;`#U1)EJfef5VdWGxF+ImQ~}muVW_BCPCPNHvg#bY
zOg!l_)U9{O!yUz%n#i*{0EI76UzZwxuS>#dNw5}YeW=VhHKfB~M7s9#38=y>x4~;Z
zYRdGnGJL9V?FNN##NB8*1T_KD*PW!S2y;x%39H-RhHL!FjKK-{%m}e9u!BjrCpIaO
zhJ_GtI}b3;XEX2u@>aO@QjP%N#IF2K&JjODSSUKg^CU=P3%2=v9ACq8hpz?WIWO|P
z@t_RsR4~MP>EJopl!EjFZz(*U$AnNh&YK^P`XHZH5L0^PHff5|vrtCjxti>Np?T14
z&ZO~&zGD9&-3Oj|Z<q_Vta-;8lJYhMFcrz4R=1+h7+sNL;%m1I`x=HRBXJkR*Fbb?
z#DjH8n^=dL&w0?%AJE*9p0PG0ioT~TRH8DMa~{eya3<I<{MC7MLe<de5ZtCP%SVa6
zg`qAXFv_vC;xEbGx7Rll^cSdyZCL`ezLIBq`Uwg$tL#ba1acdo1gfUfLIs7gy_G3}
zqEQv1zwbe>(a2mc?-Zx}%fQOVO07)v^O~DnRRz4N0<ErUzLO1QfF}yRmh~yNyI~8^
z2r6x{oNVh<Akeg9z7HRoEZG@xJ|VVqvY6XzPX)c;YOCU>v2oYV>!xp76unC2R+9z#
z&j+u|Lt_pxZhm%?N5qE1=kg2Q9bG<8A!bOn!YslL3f$Tnh{>3hhfDS%aSB@ET+*~I
zeLYh`&^L;;i$!|!-bFM<`h;KGrlp!>*Zw|anDkvMTBg8~KyXG}8^IZa^8`yD>pEmQ
zmn*(Sl!n(&Rcw%P(jF(bKWKT<)?v~xWEkl@Th@Oz&WU|BA%g=n&Z*+erC=A3NnVbJ
z1MXPKK(u5)>y?9Fy}=rNCPy<-XM$1Br{STJf5+Es2e&e37Jue?2X|nNl4g&Yib=v5
zj>0yxr71=Zb5<l{glPLA%^rsIfbYH2wQ2$HwC(BubAo+nAay(T8PM)}A$99}B7SN2
zHo?4<gWzQDGRof+`7^%tE&<=P`Onnvj{jl)kO9{njz}HpEmCBCDWZ5`0~J8Nsq>H0
zy0KvNQ3b{X^EnCl(giw>>-B?r0V?sU1)64uJ37V?8ZhK~FX8&B-kZC>8wawDd6VNW
z2vu6+&*}>O5$)d&=D`W80L#@jxlj4&K!Ots%SEyK46==Jlj6Sv?V-|Z4~~cKAl7RH
zi;xWQN(|ft8F%wf3VXD>Aj#cb61QDW;h%X-i!hKP7o5VYjJq)~rN}q!{#L*}7_~K6
z`p$h7-a#Kr#;YA81J4jfagh4L1qOh?Ef9T-TG?I&L{;e3+k~j=(ZE#Q8)N2RN10ZT
zX4uu{rLh+1)w5vwOp})s<5gY2-4wGDpdS{8kI_&iq>mH2l*y3vXJZ`*N2U8MJfL<P
z{5-?(GK18o%AfsDh|d(VW<z+gAm-tp5G4ZR8Sp(V;0g`bg9`A<GYHyWQ_0UlYcScV
zo<<=E6Llt@%t-}>GC{SIfd<f;?SuQW;B<9{b^hWY7%)&xf1Ub3{>lQwV)U{OF$vC$
z97FB_fbYR3UHkATCzp4rfg3Um%~AQ*z*sX3+x-C`f8~2orEgmOsh5ES%;5Ma4DUcZ
z&~V8?2#}TN3={mrz~wGL#pRj$phG|iP?+?Egu91fGl&d=Ab*>@1ZgoT^lEN;UI2~W
z_hDJxF<<ThGe#3&3`xRb6%BlXNc^2VBnAJN3`PbCJs5QW9th3w(L{rb;e1g-4aH*8
z?Da)wDh0VhXHq&Fhvew<Cv}){fPy|@+`a1H`><o&T$-7>z7y){hPcMGauqcIeS;cB
zpY2FZeYOkK=a=7}faP~~*<J|7!}lT+Y6jNYa?K&n>p)1y=9yt55)HG{Q`?>juBLGr
z3!Kgl>~v;!k$JvR5SIFOr&z_8Y=M>upI|L|N^*j^N+HM7<ptp;#Lti+f<+S7L8HWn
z1RIBQ_Qs(+z=m4~t^y+k#b5znM&;wnlxO=}eo*m1_<(eR6o7d+1WNjcbZUe4>H=LE
zJ3upK&21v>4z5jG&VpM~l!D-KO%V&-2I|7WL1JtBBi3Sq74(c1RSU@zfmqVh>p#(5
ze)#PXe{Fz$Oi=#q0Zxj`_!nyZzj5t<K-T}@+H6cL|3R9$|6e$k`5y@RUzjxG{|}G-
zpYW?*!h~HA6O#Dz-$<?EsPHgQY4TvzB3umL(ndm{r+5-{6YTokYu<wh<ucf`ftT%y
zUtx!ve4KW=#GZ%^0LKs`7mi&PgCOCPTNa+=KZcSG+ui#ca@iWt=^M6Mj#isY73G14
zK?terHnraM&T)t^KnX2|%+XgM9W~ChRZnN1hzcj_QfhiZLjn8xJYV12ccs~`ab=GW
z+AqhRN?tbkL<o9VvBxGcFn6%wvODt1=Nm(<u&hF+|ME^C8lOVmZ-J}*Nht)#h^z5L
z$%VX8`5yix{tV<sSI{EOVkIObRUsCD&JB+eHKkdcDavJ)J^IBeyO;3FBvvfqJD2*S
zM!bew<w1P$x!^keo8KkT8ETP&%{G%qF6kVb;xqNC-I>v)eN@tq>Cr*mEwlaVD|v(i
zQbqX}%aO73*WBLc&TWH*hR;vnEV5$6e@ybfZT2rq{M%@(tnB}>8S_8D|9>#_|3dEn
z@hym%Ih!~E99-<3{sH3u<!(?gvi<fQ$jfP~X^GQ{nOPaByQ+Lc`u}}h!pIizf9f*3
z-n3yT4BzuBd{Y%PLH&_9p?8#aYPCt5+O56zLI{>vf*d1l`}KQ|O&}>WQ6&8O_~U#y
zk$AR$**JDF>YK#Qt*P+ey*ygpMY=E*Tyi!|v}7WiD^La{50v4_o2@Mtb+s)S591bX
zL6~AL^U$RIQF|)k3hi)dc8{g4HXs?8CP**7{Qb)EIG!4hU4uMCIhK+ULFf|&LMZ3a
zh|}$V`G8M;fLTzaf_i7#GQgORB4b_ammA}{0DLuvwvZ9P48zSrLgI;er~xf(U9p=t
zTQBO?c0ySB&93~W1*K7fytsTT%@6%rY4*_rbcEi^Gmx5QM6%+o)9!bcpVrkVuS`)b
zUB0y<UW9c-H#*wM>@){w37k(+6SN;<Jw%_N;0f>v5UKfDTOv7(-ZlNiotH6Du2`L4
z?26(<Anf^wvGxSLdMruwIoWsDto8-y(YP?yHB8JzI)jVjjrY6T8vr?|l{34IE!tV*
zs!1&MCFq~GO?^)=Z+w3%xs*JYITuMP^d~N_IiK_wJ(0i;&MggUzo|lsg9`^VccNZ@
zT)7@`CXx|9UJPkbDO<Cs>5Qj{5M8Y9G%hkM_fF#)i5X~UP?83k<~%_<hMLv_AA+IA
z)f{mgYH6OI*&(OM*w9WZ`F<}Nb%O#K+GXP0E|W=bKJN@pw+meG#r`WPR`im1ZW<(=
gVjd6JQ@uuRLtR7?Xq*qx)tQ_pqpPcjZ=Xm10pXDm+5i9m

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-high_error.pdf
deleted file mode 100644
index 5025819c3db55cb23db1b746584e3f995ca67a77..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67660
zcmV)&K#ad7P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q$ck^V`EflKiig~m{q9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R`X9q@Jj
z{RL>Ve~K~*f0&)mPf;e}58d87`a_gS_(L~q`x%+d@4MJDC|JpU68^P2VBFr{qGj)`
zI)BIhf6ETA>;4dBwEr->X`iA@!XLW5|Nn<5lkkUb?WQQB8wh{sW=7G%5`geGcYvAy
zXn%bOef=BmfX6>28SU@qc3q!xjQ01P=DAC8wEl3<^k44z{x3Ki+k`yf*qJ3x|7xj!
z@6PKtLjP}4dY(_|ef|ZqyXk=>*mnojdqXT<RW}jdH~hc$92oC$`gq?LU*mm^`tKBx
zzr~XGejnQ~(foF9@1v~08CIP{__mw9&&~DE)vqYucYMpi+V5LOQNHi!BbD#!D9Ybh
z2J^QTINzti^Zh#fja9JOei5^xd_TqO`9;u*@_ol=ek?rO-*#$mmF08ki}HQP_c{8x
z_C@&{E79I(M1TIcBmUma*xower??g6`$^8vC*seqqI}=+4*hZKN5c2rp0~1keyoNl
z-*)WgA8XI{-&l!m=Z|^!@%VQu@wZgO-t8A*E6VrNdq4I*g{>&xcYHrCKUcme-*<dJ
zi9T1pDBpK{?$4DM;qR=)^Zr&UE8nig-@7{BZ_H0&E6TT1TyI+cIE0JxeMf(y!+!OW
z@_olSgLzv=QNHhZ_q|iJ{>D1^`vkT>?}@*qG(OKSf>xAor?w0`AA%;r_uYE`Wz~!F
zeaCl)&s8tV_Z{DF{m)e|%HL6)#``v$f7}y)Pj`B&slNzXQT`y>pL*!0j`{lf^@sl@
zQ;zBW)0+5t=j1%w{oZLg`(LO0|E>9M$9Vg3-tAr&>RSaYQ{%t;f5jI&$9=c=SLa(-
zIM?Uj+v?5RzZTT@=4ne4$ro6(CRnm8fAKcBXv-^#;~}#sZ?Qgtl#e}--jq~1KzaYy
zoAS{zyefmT-Xw3zTV{`6NNs?yo*LH~KmI|e;jU@4`9#;(*RhjapITbiqND|{D0oo^
z;r&mGP?L;tEmBSLEj(|^6<_$I)U?NHZ~r~lw>UwMhZij(MHw4kdKg>s1P5jD?oD~K
z<=82{F{Z~0&tpJIX(I^5svyv^6`Zo*RR2LHn8VJaPbZ}npDg&)Ha@-Ca|B6zdbg~2
z6fN?{U`smjU=2!4Cic@o(wfctfFM_jLayWo+PKAoe8w%x82X`D)^UpqmMb<c$+zVa
zyeXy;#S)CUKFS{oj=xE+5e3KJ6w`=;onweMmh2lNc?437$i*KEzAXxQbmop5T|CMi
zuqfiunQR+PJUYRnCLW#OQR9X>!J=G+1Ed&`NpeoG$i%c|ka!<xV%Z4>oj>@q@1Y+-
zFpW6a<J_2wvgFTeTjn1xifO#-zus#8z4Z$2yea5*rBEyix?K+pjTfZ!%F}xh`jcDl
zO<E@hUJFSG-uUD~;BglA%E2EFPWWW&Jx8ata1nwHZwj{aqQr-3JX@5QwR26D0`mUe
zu}F=h4UvG!BPluQu3k4L-P!5JoN*R|6fAFC$ut-)0v7U3$SKk$xF|VAi={k*5KS!P
zbz_nzm*l#!v{?OjJEnMUU2L6rtv_3zm{Hg2Uw5>)gjY_d^FUsN^^tzp62|f_3YRb)
z0<B-wDJIitb6b?y+#TzF1S!_2*TSa~vnX8nE4Ol=Y^??Aqk0_C<eyKBey|lk=Mt3s
z)S^&OX70M~2bwwXzIDlg_pM8gTO0mOS&Z+w-;bokmg;Tmm5kTLd*xNLC={-|>lbAS
z*AbLpwJzRkV7%wnsl!ZPf74;fPx(6*DfrkPitR{Nw!3;oixTTF{_DVgQ?9k`+NB=J
z*F~vb!M=8Fy@GvhZoTr1YIEzBqnlf|9G<kF%cI2}^i9OP4v=CBt{xr3^Q~77Pj~Uv
z!MwbT50HX;ee0IP>sz;2%+~ZVC}%DA{E?(|sMM~9M$~NUmLt-ke?bvxdFbPZLg3oD
zb;}W*TeoDGG%{#-%^qDb7jAfa)D4%nJzKXJk(FTJUbefYhCA18iW9C}yS84zA}is*
z-T9_89C5fPt%L*jqD_f6E<v086z)8ergp6h?FdSB3T{|k2<N+{%V6SOGMx+)w~)Cm
z_L(Zqn}k+!p>JK12~xF}UK^wD*$Ow<gnZ6ho-zJ;-U=pt?M=upN@trlzM7iQk)-^r
zZQb&-@UXrK(ZJC=FHH92A)k8ln`7t09%&O>1Y8Rf2ln~!Ho+6Koze+rYHG(K;b-EX
z*<t2~PpNnl=kF<@m^g6HOB;FOd_5%<GtY%Zscs=%C#7PAJS^^>DHTVO7JE-g1vL3Z
zfmFOHIZ6ITPOzk6-~v6R6V4Q(MIrm))H%CW4F}`dwFb+0xY~v%)^tpg3jNI2>>_Xl
zJX&OC2Qzhc%+6IbaKFb#q%F>lZ|L@b<9JcXlO8R+XJ(#f@4wMb$s@}YzOpDI+GI$|
zGr!rAW8sV?DO%)&;S<st;q|fSl3ZDQA|&ttp@+v<PlK6y(Xz;s9VeW~B_t>O%v1Br
zc`rvZ=a&YTay>6f8$qCu<i2@RR%<+|=h>r&!-!q92$<u@^L0@$$MJwkopT&eKNkr<
z9RCbHuGds_Xk5E-gH3u>j2mNbI<v+NM)41F<T_7Ap3jTIv0hkU(^#*3w%H?1b6glc
zG)+9wR-5C^fD5~&h2*0xD6}h#Jk=KoynR#FINp?Oz5h#+GV<<U6pn1<3*K&tO1|jc
z6de}B(M?y#$nCf&{H&*Fy-8@UCBFyu;&A-v;9eZ?s^5bGIC8h!9iKZu3g+K@P>g)P
zzX{Q5_zj&C1DosCIWZasrl)_t84Wg>B;@GyycpP1H=maSTj~xS-~cIv1&{Nj#1EG!
z7=E}!;lvN8BpgY~HKZt<SizIuKIL9}g*7@uC>TVtC?OAa>CxfX9hYtv&s)bXDWo2k
zrM;g3*tx#$oYm$9>yUjp`W-J*!@FTo@+z`R#|DC#EH(cFq+r!0dGXX|-;`{<|4UC0
zhn!y$7ROI55~KxBS-WH?@`<tOLFxn1CAw>T<m9aEdp<BW9V8yss6`mrjQ`HHPykDl
z9C&KO23<5MIX0P++%Y!YK8k!Xy>b!hV3(dRZ%U3$Mkepzn{*ZL@0QLLZ}FyBl!5k$
zR%0_)^h7Jf6RO&xK<=TN9Z3rDoKk2#M`Ke8E#B0NLMc5FqH{~l^3+5ZiL!&MVoIIq
zc}-eb9eZ8{vtGG<{ksII-v|y0LFyM;1FamoE*89lZFb#+ePZmoDLTYv>Za(qqiyIY
z?U-?z-|~kr<)ICQC#4NpRoer~+$b@k5h1Wg5Db5kYt}HsG0}<@d>_;N*I2`$+qGS3
z+cTWxNqX~eIHjb;gJBT{{~%i6d4|s{0+p+lZ+06ru{vIsivnS7sRAqtnAB1QSQLYu
zxD9Ypyln%V)b_!H(}onc=3rZ+-qEndFc@4f@AEeAo7TZIy#n$0Tom%D$0KJ^Adl_6
zmC6*@aF-0JcCCR6dI{hqYH1zJ85*L@r13S}9j<NGu!G)|fp)C9KYYkFXj=Yg4fEM%
zWk77HSNW~+ozcSB?7>;*dOuihYjcUH;aYHsD4wZ{GSCj*`z4*|P0HcR<Y<sW*DYY!
zi9UHGSO}q~ezGLpa0j@I6b79qt&%puH);_E-Nt3Lu$dydND$ul3pGDHxU4q7Ib9Wa
zw=T*+JC@q(t!j>M>7p>4;jTS^P+C)n+M>jgbefwCQGgx~Sc6EpR1a(TjC4?I_>3+O
zGi>OxcA8;I*#(Na>*6q+wJuczuh&K4fraPmo3vWz6U!rEKOd})g#DysNJl+ysE>Z4
z8FEp^(Gzmf<=i;KqPYnCRcO9FubVR^$hyQFZ`4KMZ^Y5K2sj_k8Ld1o&yjXj>$+CX
zl!ZmXLY=tBJEZ(f1J-IoYEE3xed>Zf^Q^P7ubxm)yPimAj~0aS#De3JNeV_c(aezz
zP1i6oy|Uvqy4svAE}CAx7d$_$OT_aDx(GScju+^n475W;I*<LM;|aP*Iod_Z_48<@
z#@MMTEkc|pGVU%)zE*q3aQg!dQTE<N$)8D9uXZw@_TT<YOfl7&q~r{_Q5Ge6&yDh?
zM62ceaQSo^gL(!GuCW=ov`9HWTpa!JoFeayMaU_dzJhZgY|1${+&10xsU9;t^&O~f
z4B77w>;j$k#$%CE&QE>Guw<t=1!YX8={F@><jILMzdd6AnTtw8^&-Ta8($0kP93W;
zTV)aAut?S804ZkOsN(heR-p7iJ2=&D2-Kp))^50fjyDOy(DElj5E}RCY6qJdZ=;S^
zsL3L}DESs>e3dLx%iqZv-b0-@!vVfcO)>SQMbQ*-E3~O8;+@+jrs(R#DSEUFqwP2k
z+oUAi9qb?aatHsp<vaZP)`mXJQ=$!gxv3MsY`JJdABU3KhQ1B8qB$QcJwyB!h2Mq_
z-dx{4)hj-I;lbHxjX4&Hof`ipSDN;jeo;C)=N;}hYrH)>eQAq?)xIbl^b{;gc7ilt
zln@;zcz9a+5)P2E6Zn7_5NlLAJN!aH!OuWRXc<4TWECzRYfYnZ2$qf<_-BH0@^9FS
zLVq!XAm<HDwCNPe*JTj!8!&7%nihJxHI5*0Fpa%97E>>d#q=p0=ox^r2)H^roCwxV
zEfh4(c4|C%nY5D&H6L|?gKm-73u`qW_JYXb!DtQ7(M4dN6q{p_vQzv!jBBRjZss`<
zlpNd4w~Wz1(kCu#lT)U{CT^xv5eD!@;oye8g~6pn9A-4wFA{o13(_FRPDhMNP%t`3
zgWa^Mbl9EEsLw14yA8D22}?^evLScw2+{}ww*PGEge^$Ju-#~_zrQqA!}haFgT<r6
zbo@rXMzryh=?OPWwW*IsJ>bh;q&OSwq7)8X9Y!B!AGf+;thBt^CBdYv)pTZ$)E$kF
zj75ke&yer22ysl}>9F`TCOcscw2&g{bhX(B+#YF)3JRt`)qzg4HzgVn48*)F3eFt7
zrr(roz5i>F^@G=h=?b8w(*|e4^da2|2!1i+>t|6`rz1!~Fm>WoOr0R-FjCs!M6mx&
zj^9N}c^q1v6T%f;{DEN6{nz6myV_Wov^E||${G5tPC3IgH_Bny@k|X$e%0}YT!G>T
z2q`7bee4&6gqKrytTzJ^x^ul9kFrI{6{pv_J6Bxy7ao+0f)(}n)%Y*x`Z2DhJ2V4j
zS9b4M3u()=?^!1YI@eG7v$Dpzn80P%o#;5{O}C;OkE$*<7*<RdrNi`Wuw{1VX6_W@
z&h0F>TJPM>x=lN`bC1>y?&@wu6iZN&6&)t!Amv~>{2vByUGI48TO%tv^m~)W-{Fc}
zB=7>SBtv%OYKL^wbksW!>76n#KAu^fr!+muz4MUPz1};x#YcGW4cuzlIfyY25@vx1
zo-xO|=Uc<%r0%pXf^sAYJd8g$A)SnLS(IeoMu`^IpgojOIyV<7*;$lZ8H!ky23yYu
zWm()7CD#ecy2+#7)42H2PDV+2X;Zn8h!^cNC>l)`i(>dTDI*yrjfciVP>v)eqtavB
zn~PO!lTldy#$C8m!s=rtRjM^Hq9`o~0||j5_DM+xq)7pTVzW`~;iPgC(w4Rnm@^uT
zqHRZMq>=k_?mcL!DZ;HaqP76DOO4~a#7hkSoMK&3I5ukj=MeY682J7-ex9xY76r`9
z@pWowMIbM+)MwY6NNFW_DIaH};Nh%-Z-0|K8dE+f61?Q+X(f1I`dJ$;rT(n_hK+Ha
zTdUESqRq7^5-O6m{T94i6mlxJ@uGlJB&5Q2<WaDiJiPMsXf&Q|l&P~TkDL}+b~uy{
z5IzsH_Kf{71BGW<h}9zSDC_CFY%rJT+-z{!<8TFq*MVb7aP*RL1c}!{eyY`NfGM=P
z4LpCC$_^a|?SUxhR%y?v)1QlQih*2&Qw#*p@6>OOyy8|<_hb%+rVrhmjm8h77pdJ;
zUpvf1?ZzJDjl2jQ7de=9Q-9^v-fr&7^hO?w(8sP1yeXT$(C#5E1B{}ngL=oCK(!>t
z<>~<@-J3Rpfl-@rwC1@hM~f296e&;*c@w2%HMrNQhy}r*b&(@R&bwG*QVX-wDW#Az
zKBX0M#;3HxG#@q^F{F<++AyTFw(C(Z2tq~~r`Fpp#Osz?+%Bp*G{UqC!5>tw+eJl(
z3izAy1qD4vM#U#}_;yWo!1`YEtDXTXeT9FYtC_*6`)gulukam!^}Bc`PqbRTU$A@^
zmv`!jxVXlXGwJMv#iEr$52to<g(v0$&8S{qjYbN-(1OBFm=IOhsg*e?7E?>ZmnmmZ
zFH<be<ST{G&PB;SaPqYIs1s%|>t#C7=DQRVn78`Gv2#R@3_D=~=A~{}fXRnSw(v-~
zHQ0$T6+P$|2|dX0IoOM%r9yOLv_oBRC$20R^uZxHU41xMp3t`j+q2VyMyEXmr`?1J
zleQ9M(UdiXSu|yFVG<3jGC4NGW})pSvT11W!Qf2YI5=F+VIqp$nzWRj;w25-Ff&DJ
zP4?jM1`XUaRxL^>-!y5xBDIFyz&rT=%QCho{1yZg&i(^7Hjp|Db6_Ct6f)H{L<E#M
zufa}nl*zBrR3W=yqp3o+L+0p|c@a4}>xXh$DG{_!W_k{-n)nS!gzTIvJqMk*cyRN}
zU>cM(95;=nu@{Ge_YrKfN0PFaZq5PAw(dzrTFDIDhN;uYu#m{%fx(%pb*dZA5hU@H
zQJP6SGF%@)8fDsUUZ!pEf|d*z$XgmRWI%6@n2@rvH%3V{T`dkpPS*OykSJO7SGvwk
zF8~DBr@9Ta+t@q@jWJL1E<{$(DG$T}68#wbc=<l~@$!A}+vWWj$tmBQC5`3{y!Mik
zz7L(+PTz-4X>ascU1T_p4*7Q)<CNqCT1h<D*!)C`kZXN0crX%uPP&?y<Rf1cl6=Zr
z#VjBCvm(VOY<_ZiEmCq{XJ^OTOTM#}#FGm^_gd>Xjpc%C9Y$^)j{O4r>B(zwRWC~3
zinN%thyLg{Y4Z(6j!*bZ=|5bQ^i<NxxDtD=QEteVPUT~BRW4Hc<8^#>#N!}|CJ1Bm
zh&Gx}(rcPSqxanSCHl^FEOq+M^>Bgzmp<Gh6M*2v<+l(VEkAHW|MV3HA%#QU<VC<N
zrNMUyhn&)p5fsDGA=6K|sk!=iDD+aD;fGECcw=;z{O65E7dhGA6uID6Dp1P4y!5Rx
zgo2Lz#sIIbgQ7vXP((mWlgqIM4Mcj-*aHig9h89ws}=D9Q$t1gRt7H|ASL%1-Oz9l
zRRlz%0j5t47%ueO;zv?aq@YycK(25MrUq5W#>(-@;UKJ|H69cS`)IhHDl#N8gU&sA
zgjqioa1u#B8G)hA))+n^wWDQ{X9l*cR)#k*@}<Fy<EQj^#a2mwP;8a71;fqZY-JFS
z=~r*4@`~GOc5iV#4T@^U{j64gKyP-a%m^MjKtiaHek7M(K}c@`0+b@*CxU)pBW`@C
zm}^_$`BPC(4Ns_wj9L_iTtR5_(RU!kDk%!UYIp%xh*rbXy27{`-tY+ZIzY<L=&c0X
zgkr|t1cZ~dH0D&aSu-9Bt_O_av8kxFmE)5^PkM~d{-)@+$P9{`!Y@sZ5(AMxp=T)0
zt|8uvk$9_(Xg<EcPS}eS(zhtNJQDa58mXcJnJt9K!Tcd;9}F*Cgn3r{;c9n88*+3|
zP!+{^tjwT@3S}~EBoA%DkVqY>cuA%XRZL~14#g%`&}BOr5h_*qWJIX+-V;WA#&<TD
z7!SkGDjJj%M2wC?NLQv%Muf^*M5E(So^fM1*N|Ojg>xyO6}d$f^V-q`si@e<F3S1I
z4syawrSRHC$-q+A{Gh!kLN{`b;zU;vFO!Zc(l?Th{8lXRYA55Cysw0!doYmr0EN-V
z18v40Cr=`)XzUToi;|(W5Y$6yMJDJ0qg7Jz(JSvJL(8f9N8U|@W<$?Elz4+^?D!*w
zmb<>s(DEEHW*E`lE9)gR+6o6>q&V&wFCK|76;8fVU&a=29?3B=s+%6KMarRTGB=~j
zsR%Agj+{^CMd^r~hv|NiLI?%d!JL{3xR0Egi1|O!%6NagTo)nb3Gw_ZUFN}G+?a8y
zbV>+Vgt4Uz7|nkLN3uvU#mh8&9N|h(Sd^Hek{A{xcIu@ROao#J(jkHZOA<3Cn4H6O
ziq#%lwuRAhsEiC_fRxfU3>Yhw+F?L7sq_z1$dqzK3>Y7kNP_g8E!o5nMs-az2D4NS
z5R!M)fSAft`7Q>yipq&GU{N4%<^U;IRvYVvHmUp@qm5E2I+67gA5$EjUCiv^^THT=
zrGy{@q(UVP@h6c}bR;Ey2U$m}otae<EC3f&@)8GM2~LM)e3nw6$OI)$82|(-x5@w+
zQ2AHE-91CgGX1}@xQy{yk@saZfif*@5#sNaIkqTFID;@Sc1tN}Ax$w5=n9K4kiljb
zk{>GT%^1d|%(z9#+1?sC)K(?kS>~D_TaF$#84~%DvL*U40f@<gv6t6}Gkx#?DRL@n
zZD1!;9-_f$TDgjbT=2|gj3eb>t|JIYb=0t!sHszYB8pgfm5XwX%DOZpc~@fQqU7*-
zCo-3)5<C|rhwnODCKEOXTA5YJ+iy|EmS!5~b^bj!)MSL=0~_|6vZb>c?Y2sJT@+@{
zLTqTst=w5d+IFSa8jZV3!Cf~}@=0<q;RJu~njvDE!AKnbN(5e%HnvP*qe)oV#5Q5n
zLCSGbB1xNCm?=s7)FLuT+q8(Wfg<nuKs(a?l^bo!($)o`EN$voaciGS!9J3bU((i|
zj+AiiZRKgxaA%RHt?OXoxm_vai<If$F3x18_P~E<mUf8>v$Th<K$x(pqrRl7C<ETo
zs9iboi;(lf0dNE<uoKQptV}Q}CFCzc@={921dxOh`;UOKJ`)OH;7@Xfw`9y>hL6|}
z+$I4GEJ~m@5QAV5613qI_kq78ECZWFj5yhefDsB2wTJ?2a`~@zd|E#AMM<=Zrd0#F
z5naPel?A+!9JYq=!Gw2Mt^6|K9~Nb701=i+-v<yRR&%jh?n6VQVWChgjWoYW!>b_=
z97q-iNC{Oz>xm6u2MH2`s;y8nY!EeKG6XghV!t=^4TF0?2pxuW@dEL%3~DT#k0X@t
z_?f#p4VeqFonw*qIj-acb2JwruCGESd6NWP@(P_l*dTZl%RtFOKrtkj1104EX~?FM
z?HGw%6i8bvK$b-arU<m<Snrdjpz8H{N#vQPE_sB>BVd`Pz9GoOlP9p*WZbtw*dE`y
zCGd=I-4f=-w_XYICbRo`g(dRLP&Ws&hPrtUac-SL3<`uN-gg^LkHODUSUy2HZNvMC
zcVi6j;-l2yj49xt_1??@mP7!{qLoAdyyt-_)ds<Po~=_t<vd%bgl6JpGH{d%9O;O+
z@$+m5N(R3VL6#O_!(d{nXW=vjB~EmKIq_NEWY#r=yA~+aqKpkTYPEx(y)&#VNHJbV
zD^R3->yaQ*bv`tJNaeth-CqD$1|)z&$bu0f0kjOb00ppRh`0p^*8$QfpsqA^Jog6X
zMdOF?z6=O;1qpTp$#3F@;g53gH+$iD7y6hXy0_5DY@B31jh$h!SsxS5Sy22I5Sk$(
zxS-Mu&NaZP9U#TD0Jvs@KzVf*;F^%ZlGY?4yB$GFh&U;o<1Bc%Ws!;*2|>=Bn0Sm<
zS(HH5A`l%7TLo5U4lE+!*@ZDIzALo>fPO~-<1JFoak6#VhN}k?TS4zFLQYwM?dC+q
z)AIWc`WLpm_y!H#29INb2g2TWY!HKC6pSxDTen=rXX}=bh+1g}q$Cj!4PPxxMA{z<
zH8Ch-M^-dIMF4*B0BNy;HaVst7l@-_$_4beD2W)^8M&BUqyaeYPg&CpuGNB_G=z;e
zna(WW6ORqQ(g0FX7?(jgcN|QEixyy+q!3Q?03lf;-Oho*SH>|Ig#q3PN^s^Tj@Y8)
zMD-%vD368{+?uE4GfxyEj>Zp76u^-AXQPlm!1NQWDUI8V+Q1J56N!&n1gY{FX-|w*
zgUlBUD=5bX)k?#9p}7X-+!0@kGAKEDr5=SG8>9_emTlPqeF~43l0(YH`NhhWX>g+y
zqY{kv-WWy7#;C-ny^B#vcs51_K5cDG5pE4P?0kj)OFu<H1P5jDjv&H2q1X~mw?ZQ(
zDbb1zsSkx_TokWK3KIEXQ;H8tSro3aD0i<<Duj@&fj~Tc?w%WWNZGithJ5Q4E{fnb
zH2M49B#D%bV~dCPvvCXrfSPeFo^xXe2%8wJ1$}H615juPqhvg`i9rzBHqj8Ur)_dT
z%Du~NM#S2u;6Am_Mzm^|jR><X!HHw*aeCvmqn>}*W6!q7Vq-r07K{D-jGb3W+V@$M
z%-OeD923vAA1<JDyqbC5JlA%(1S9T^Ss_)=y)lcFWY(MMR|Hy{?uHPO=h+V9^=~VD
zyAESg>M#zG>SZ6niM=Aj>oi`A*-zU}<29QVb6%%$EZrj2ZMD9#qS@=VT0hy#*nyj<
zm%+o4F0)8=UEMLFv0YbpjA(4v)g2=m+jaHih~{?PpE07j-R>46y0+Urd30^J`!X9Z
z3R!f6A@_EfCqwS-GG9Ym`3YU>M;zpfG&P`Lh@G3p(yex5YBiDdpy35CHUkCpqi(i!
z3ucswVvVHC6TnsJic^PHb_D67(rEGNy7A&1>59&#0@#)0MFnvcH<6N%=YB^7GZoFQ
z$YUy_U2()zSUaPDkFQi}gHl><&U${T#@*@(dPYlnbaJehIU@DIuJBf>=!?Q<*NHja
zdPb$9e=HK;Q77ieE;&P)GV!433iafpqqj3{C;77IiqYiLr7QfB&zr8uO1^-46PhQV
zNsILHl<G|fF<x6;;f;KeElPAc^3AqVgQ`y~kzx?}^y^J)pD)AST+b*=%gG{DubhLc
zSHm3Ss=za~BghZ$*q+vh{hb?0Q|gm5nCde!^J?tR>Ao2s;Ku8l^`T)AuB}@x!e)Gk
zR@o5Z^hm?QK~nJh`7|Q*56eSH%ZKG5BnFm;vR8DO9$?bwABKn60Gr_<nY$Su93sD2
zAM&Q`L<*r5rf;@~Jb3$NdsusS<p9E!4s%cMed}}OpH!C|U6~&o!}Bs3<{M>^*ll2V
zdWOP`)q9yI2gX-da~i~yHTja!EHW$AErvL^Z^i2NOV6z_Ghg%Ejd#7*X%L4^q<x+=
z_~lsct<yMyP<@hF&(<kM@@##QS$gh_D>78c@4VZ)mo&r~wg~Ew193^idaZT0tw-32
zm_VDPH4bmpB^cr*3b-&gYXq)GFJVY#ED8l2mtmPC@cLVc!rVx>*}U{L*rpeW`!AWe
z(vjKi0VjAk<elWy&<|M2Bh8tI!xNmC>JftBQn+D<?|yAPQguMe^-C6gW@W!*_3vf6
zfM=kW=^}gwJ+LO}OUREuTc7;6{MYbObpOSX(P0`oUT}5<g`M*5??cx`cue}B_ar_$
zq#;b8YV{%KHT*LCgNBbv!%NprF9QbN%ShHgKnhtOv{&T=x+`Xgex^Po8}LPSoJ`?Y
z!Xc^{A$qm?kZi=mdqES>BZLzZ;XrbnEdp1}1Mi@GaUscN@_=^^pb0NI@BplEfRr<o
z`3j!EUQt8v7WP4ZV{%f5Mm+70ppf?iAJVCT$9^BYN7A#|hprJk|NBr#G(Dt!O5;x_
zYDeW!dRd8e@sbx7fEclZ;HzCEGA7T=MFC@QAe9jXZs9(gM2s(jDUTN%%zbvW@;kC=
z&-gcq3XYoDYl2X`%cK&1a8|mepFF@x27e?Dm05y<(7-<Rcz{Q~PsT#PY2WA6{Gg;x
z89USU->VD|!vp%%6@w50z_h#&$<!+X3qc8emNOKQ3w`PoNs~vPL_=gq#G+s@FoG-!
zV^NmorBEsaT@c;o#mJ0Az!{9*h(r3KC@`MmSR@3AK;yZz@ThOlFD-n;I;}QGg4)}c
zt_+l8AQ(_m@>le*k8qU06H)|AEG^4b9SUmcmyDkXeCZbhV?x?5sSb#p2?V4)w&qBf
zBz!6N%*9h60F@T@5@$Ry5*g1B=CdgDup<<xUwSk~uu$Say%bH<S^Jp*NByc*MpRzE
zYMCMb{}9{MuZo|+rK#AaG!Z2D)gDFFZ@nZCYSnLD5D3TWw-ku`RE5PC1GtXB<}$@}
z1-oxqcn}KKZ$2s!Ek+cum*T6AfC@WF3R$>y5=3O$YBT68pBlG>1Cecu!Z;O#zXggJ
z#)tdr9%$v1X#+x--6AmBt>dJ)b%jK{USO^<+AW0r)~SGizkbUm1j``6-1fjhBEG#8
zUAQRZ9WI)iRw4u`_B(%daBTFGBhs;#Nibp|iB$Jus29QPUW%s-#5=sLGUhT!96#=i
ziqOK``XfIIg2EO>{Kp0;OCo|q7lq-Hum?R<S`lly2>B32IBJ(+5h1G!FOU)xH$Vk)
z-A@7x?jf;9f)HZXIHt>ph=~NaVNM8vw+kY%D8Zxt=-NQ2SfDdLq~!Q@10WQ5p*-dk
z5iNWyV9Se?)yd1ehOlElwYLzO>=kZ=K&b`7NtPqRIgmOr=rocL&a<MV1M<^JnV?L@
z-sdATa6%Qeo!yj>fT-;N9Q}yw_KGuN__xa{hZyldF=b@;daJK?*I!&iz^4&=-=m4(
z_dF;3yuK=oec`A!{&O;u8;Q~IivpK4W2sygJ%-e~f|3|@?`P#74Dg`xixIx>z#LJG
ze*nmGegiysG{d-H0&_O?`AjBohAtu5z{4uYWP|{$ReD0Oz?8px;^HCnZKXZ9DYp%C
zTkyGD!<?JTa)=y@Lm0c2h~cL6gHTC5Avq$E!wWY9sUB{PV##a}FYpQ&IK6-=kXGV_
zGJ$cssWcw*QygdzNMVWgMMCgR39i->xfq{CVGA#O1?13p;VEEDURVi8##u<pOnE_4
zxC`jOJZtmfL!KNOnx5k`Q`2*NX4dp_Z#nS;fMXU&(8$?=aLK5-l9${rO)!%k76t2x
zl&D1ki!Mw?sW-@~S}4~186<HN>RP#3@kjWb8#7YsC(^sT66Nt<Zn|EWOSVYphFr6S
z=Z$X2NApTpZ;*wI&dMLkkU_7ka#%PCFaA=7oL34tP|X9B9A^Pi?YuI^0~$Ti&2y~~
zWwj`ojF%GSO8!0?Oq{MTE+z|lrEMdja8W8vF}~zz#N@nH0wq?jRRSfJPeEPGhxAri
zl(E)FAjxA!xKEl+Z)937O53tAgTUcF#IR?wXRcGFRN}g66Rlh$<y0bL)GLR&N6@vy
zO3S3v)yB|~nCi0JB6~GJ`<W-3o4l#Q6LVm_a;A|d>y<N&Tv~732%YPGF%E&jRjaB1
z6J<N5$UIDB_C_HBe9AFPSO5=X2rt6LgyCF8Axt34*taa{k&{xMW(T&rZ%NS;;;f|T
zi8T{CM8Bf$0y&k(fOi@anOE&wmUNy2zGX?rT)hkT0k%z+csO24^Y$%GI-k%{8Uo$&
zdh@RR*rAPdXm<>`S_G!iuSd&jGl?D|(&Gn^)V_+DL&h9gjILlhWXH4M`AZ4(UP;qP
zvUep-JI;k(*>FhK_s*vZ6Z#j0C;=Vpq=$2X0<2d4DDd>XlBfYI-~th61eW&#Wk@~V
zyOQV}3YB-E2?6N9E44Zu_s;BU_`$swFvC<ACU66E!TYbk466zVKMp;j7cj$(UX_X(
zAP|c%&|(*U8#h5`Vrt}Gvew9pL0U%?Bq44Hg+nQ;aI?9r{Di$&ln-o-{2?Nln7R=g
z10teR1~42h=K!%f4i_dq@H`d)z$zV`blW0V(wXX=J{weGN!$>JRPh*sv&Ad-J6$Q>
zgD>!qtU@o4_<@{cS8g~^P!@sXnCdmq&W|W_7D<oZX__V|OO%wsuRt;A4_etnXBM0T
z-XAT{&9Mmz2X=l}2qv*+ywj3NJeoz}0-<_`S57(%@IgtLN${H}qyv!wIF2in6976#
zkO0<W>P563Q?L9BoEMeL4oi1XaOb39+bg>rW^C5}c@a8j)dxZ=I!Irc&Y=-m0^md}
zG4vvSkvlE1#5i)7N&^(6s8ocj8fIWu=qUh}f&%$Y3?>#qdI_RwQ7pshh~wmR5E1Gr
z3Mt`-@uqN{wlG_I#k3MuYLSR^^r%~Ig8-*mO%51Wg$u^wLXjDF9mru!jiOMwOfY4#
zOw>zYTJ8e60Nz$mh(VT`-y+3WPz}}P&?2&zSJFSwzZNB3<^TxuLID7Tn9B=BoH6&%
z_Y#JT#j##QDLayc&p3M!h76a3>)eM)Gbs2>>RX2^-j^_I?z#=GD_X!DgQDPt4~N~J
zkOavlY<J%Q;!^bVFiLCYB5(o^q$+QZ<0a@hSEMoF>0D)O2w@kLoD__U4#(d?Bs?$l
z17PL3;*|-g=fXp{xwLwj-N1BWxwMzC``j5{nfQKDV-54Xxwd-G!OC~I{EiF)bSH)!
zpa$J_f89g1++Knz^bCwUKw_8tiHVic?FNWMFVF_SC_2Ni4`D63(~6Q-MK4?jByqay
zX?b%a>rT88cD*Xry@U+u1qE^EF4m2Ca~JD{3b;x4(%ykd>CSr<u$5kT5@{cF*F}p;
zAnuB)BOs>BWlPXZCkh2%HQn_nczPD>%h4tb=b;*YFM)M>0apOf^OMpsT)=MT8GW!i
z;7e$t?lL$5anuU}1E{2*lsh*vLvV?A>T)_06ZMml{FBa*xT@}VF&#R+3vdtktnO4R
z9z6J52z*GzB;`mTSa+2?0Z{BGWn#R!kqJ2Ka*_j-_V|T#<J;q_ux<Bt&gT;z*BQ@W
z7`iUB5aR59QphO+<T^Qpm~!Izx)Vc?n7^MCG6smbQ;f*#f%w9%BnDy-e^Rde_zmve
znieTAXS=KH0!?Qh6fR{-(t=g~XlZmf+yTtI{YE>rO!#y&F|;UT=nZ*Dpy+K*z>+T3
z0NCz>K;{uc+qn^U64{590`$@+g$%{|CWiL0Q>LaxSZ%6CJLN<8XmeTZ<BOQzo3tWe
zY^P|$LF!xWx7-;A0m!$_(th1>Kr-Jcy|x$<3JH*2Bm$_{2|$$fIwb(az7rZ=PC9J}
z=<fK9_REn)RQONI;4yc66_k9Pg@l`TMbZ$HUMDDF>v_l?g0`<?m+@eASTi21PIQKY
z>BK*Tw9iX{Q2e?{h}XZ}HpKL=3kkUYM_pR13s6@bYX{VI$N~d(VX_FpkvA%f6x1cm
zLI!nFv)X~Ka>jEx^G#li=qi<f5nZJ=u+##I%Lb)O`^Y1U)(rtfv8qF<EUf%cDoyuN
za*{K?On%aeSX!b~CzhWm^@=4bN(1XuiAqgFsf$wOSPetk9;3HV_ZAc?jd(1v@J8v8
zS(<~2CM$Q8D%xqxkh&TLKyqwk!lO>ulH-)-2}TU+J*rqWfX!AaHtLnQkil5eq*Qg5
zJ&`ugkS%vP^cb{NF9HN@1tmN6dRX8~y&e{$Wi=VsJAspMy%VsSBZiy*g}+vvkO2U!
zdL^;`j2==fP*ZO$gk#lnjCF2;a)7`-9Q?&TSdl^fwrfSG-*!Uvu`*9RF<HH*-l44U
zQ*Tw40per!P@$lD@MZv(-oy&Ps&_L3u<C7%3P#5lpX4u<IjU!S7DB3bJ!>V^+n@E6
zJnW*Z!IYAxx&X7Q7YFF-#R0l{!R*HxP_kgKL{wQhSVt<2AS^RgMiP{wN&^i98uhAR
zZ2^VdAifz;MUxE+W5K9%fW$r++s!T<+O1AxCe7LpAudqHtL#v$^i{?xmIEt;7Q(K|
z=7q4U-7v<=V`V)<b+R(Bv4B|`;8@@c2D+?XmghV(pgZjpvh%T)8ZCh+wpOM>gkWvv
zMAmC7lOv0|rAd-S-^yai!f<KS%z;4;6idwtb2N>z23;9XS*K3+)gvp}l>wH;?#fEb
zf_P=g&60U#>P1n#-5!k6dz;ZXgR;u3%<_F@dS;0~n5Per(yXi-iFOQHxmirG4B;#|
zNK^TNl7z05dzLLMdpk=TmQ5bj56f(i0*MEW`yh3g`}u7;IdJ6P^l-SoO%I3jp@^c6
zn>S(=eJpPUi$a!1gJmPj>w(gehdd)JKUsbgmZ&V>3d>lQ{{@9EHy;hEVU{0<1vAUl
z!w{=-2W8pK@)sSf%2{3|mhMci6H9xRSBfE3<+nmi)gj*&i-?x@3w1`zLB>*~<wRq(
zQh3@9kaE#<7(Vt@-ntbSm8{(BrqW%P8~QP_UkBZj2gg=O71zdAOcmFLT#_vGdX(Fe
z)nLoD$%?V^exjzV+@q>G3m57EQXiX}mE~*86T7P0(pCFX^;>y!Q6Tr&Jie@=TV7#S
z+I3|CWi8(FEwfrL{LeWy$by{I9Z8vVWA`i!TyAdG4K7!>iVLT&oYjZRm(KdcE+})9
zFfM;QsvIBXvu7#fa_c)Vt;+SE<&!HofCZKjKyZ9j73PXEK$+$(5`m?hGgN_vpDU69
z#i5Ta+<`G?S!w<&t4xnALV{JOD~y8CWf5p`e5sms5OTLV<Es>%vC3ap@CK@5Bf#TJ
z1+<SX3WQa*D^i4IxGS23)x0YRMdiLLQiV0aE1Ja>{=|Epb;c_!2F1vaEp~=sTMDo7
ztY%dKIE=@tC><0=XCzOs3pI}v?ZX1=F2E%gVXqJ&7HMY~(V;@_6=uX*?+i_1HF#G!
z6oyn)gcHijA6pm{E6-P?6syxKkctKDE7*#^cvM7|qvlFQZ8-|6RAiT<SW1O|IZB}%
z6(1ISsrWHR2@?jGEoNu5Qr9#g7F8qAQOUG|+1w}=5^P06@fLCbW_y*-Tcli?_>p#2
z$em{~j|$2|B-9qU=MBg<72X%peC{EDl=uo0bQII5SVHWjV+%NRpjTx;;%Yep8Zo-2
zm`4t;E8g*V@d&7xNN)_=q%F}K<2F_2zQNMY0L()tR7GjV!FKMEoDOg+gnI^sahvcA
z<Pn;2o6t3R?q*b}H->CZ&TuMfl`{lXK?SZZ5&~B_%WI2#^(^s#=vWX2<7W>Lk_S4^
z8MviD+_*JQW3(<PHz>%t<^^40zj2F?Jv5j%J>rKK1-Yh(F+M=bAXvtChWZkW;)~O1
zT4X#k6=H@wr|zB6)Ki@%V!?T<@~Kea)$zcHU}~65@{y7xZR)-Ua<8}3if~t~w|B;R
zGa!7u_A)I=5##Z!jN$QB&G)Io&iSBaU^-p&8M%IdGS5A_olo$JfakLvVe+74IQyx^
z^T=IRv^~rU6_D@V8L^)&1?*$aj)?Gz{HHOcasz0TQThNaIGJ8RqfcfZ9H2y^i82&u
zf~qVA_aPNLTFjN;zy}95HTt1+3637pqnry`3M(-K_Q#`=H)zJp+zv->XXSn@`zn${
zvIU;Gt~}TZE6Ie0<w`@L4ZBiRXg%js>PXVqa$w-+s5BY+VJer#of$f&FFl-~&UddA
z9SSK^bO2uI3-16~KaSK;<OLld#V;s%$boWI2}YjwMr9>AVyBq4<O5MA@rcg(03)t4
zot!!S7hnI59DZd?Im4?et;zv{r@Sj?_Wi|ox-;KixmrG$eKu;EnSQ2Yb};=cf7CHH
ziN^38n>2@kB%(?_TcpezlXNh@T`6onm~Ez8e+)9KY2E|fbkwYrbEelh)5(>B=gc0z
z1ViaS<f>f0MG28&x}OgKy-X>l1Iaf?5Im9;duG<^BPmUphR&4mDS?2*GduAJQl@_D
zR)%S{@*Ewht~AsoCDR;f?(wmwPWoU@rj8G0b}I#QQ6dF%aBvXzO6~N?3{2YH7p09Y
zMRXBzv}qSv?aZZ=6~vjPJ$0cnOIzux4g+qbvo1<9rlU3XY*=Sjwo+ytHR~&_)+e&q
zl#A;Vh}xC0>tO?~oL<K#nDy(h30GRMzelv?4ZHHKrNAlQ8tKQ5bZfm>Ci2{r!+bc5
z$d%~qO0kwMHgT^gecFTTH0ftMHx09}T?y7Y2b5r~TLa5m$=-_+>L(MzT{+ez3CyuB
zQ9zQlix0Ss#wH6B`RXML$e9}@3s7&E2k)?H)9rF3DLL4-UdcddCiD8DXkbSxU*9Jx
zIaXG`BVey%?9ix$3E%*CE8GCb4($ZTS){wL2b?+Bf+tv%gnN*_fuo?)qrV7Y3@9K3
z&-0_O5*()X!c*}1Y<LTf2tj}{93bVFXLZ4s@hoMMw!DpwS`z|@ID(Wg6OfDR+yEw=
z8QTJ(@H|ujQ~^S~-wVycaTFKgg)^~RUMs(d^gx+_2jD1l4F`^WA#gY%7zNU?2+0N8
zIwcoW;=<uM5E{rLBp;-mUN~#yQ*of?btejqUjTs+E{P*Hvam~>dE|mOS(F$LAyD#%
z5})PXy2XG5rLri&AEB){($9s+vVI8Zl*DWaN{&c32Q$)T@ej&#7d%Y<P>yJ9-4Zco
zY~2E<Wo+L{#26ah55HW9HtP?dL<{xCFXHXU=77Q;1)j4gsc>|O29#|<@GMG>u5G<y
zbgla2;7s<Q_;)Fl7l0_bgo0o@vJYGY+c~#RDeN>SFUr`!iyWF(0URyLH3|aB;p^F8
zk`^g}p!6WQaI6Yz$)V*H9+M+8A2!}2DZxycbRF7afj>FQmk=CkwR6BS&pK231#!J7
z2?jOPDYz?~D!;A`$I352ju+UK!#P!mSc{U-TYc-6<L_Iq6b7MhEmBSZZjMDr@GU}k
zElRMwZGCe5^!hph22^9!uX{ribHw)+;+VrxR;Xl)638V{eRj1H8%+-iL<AS~na9H+
zfzg~;1q4nzf|ST;bqwT9VRZ@+@lLOai|}@|-X!F~v7x>BMTk3DY!Hepz_=hh&xR?t
zC~XjS?f@m$$LfM8h&zf(;0poYE?UC~fd@)zG*-(_fV*0D;M>)r6W>mYPJBC6w_Bvx
zMMC!T8!$ye{&V;s3mq^he(w;1o|SP5W^fU5Y0s@!a^hrb4MtFgi?Sp`S<XRNLlGq6
zqQu548y^88PFf-E9Ki;*=m_*KKt?Bugg_gE62sA^zm33;IYC^kWsZZNwIC!N@#6(E
zxhRV*r{G|n*c8I6biB|D)6(IuE!;~_{0bps9zlrVNYlgHzc4l(WrYfd(*b)SsLn-5
zj3WVhg0z8tI)dN}7}Q~TSd@WwVv9b-ueL#rvPC`tHC}L~i;~!*^gAT@#!;}RByG^B
z4wFd1r+U^+Du7iHRJ?al5`0#-^bOQ|g1Ht!PB8ew0ScQ7*?=o69ZnRz@$Uw#+40db
z4K_}R!mkBs!?<;zj1&%TQLK0sFY?0EC8;oX9lra*<=rV=!(C{!tPA%+5oZF7Rv5uM
zW#~&GF8571t|DFA+(UwdTD((gq9Ii*Fm)6~+R@!N<m7D8H2R;u{=>2M`T73U_Y|)-
z-sJb`c3!u?57)2%`0u~|`<H#4@BhjF`=5Uv{-8Dl%nUzyoo*oNONk4L3Uxbh{#GR<
zdKwUNMKHDuVz{!fE5m+JGmHoHx=LpdDt+Ls5U2)HWD&)mBbL8q1<9)Xi1MXXM=(`9
z%fmP^^3qe@Oz<-C_}_uj2}n)&A|FDGg}P&~IP@t{(A$5pA{Xq0GC@0i*u43Ub}@#T
zr+$aCkCv<q#beSg!)+?tHh=n%8>-agb_t`S-jHd!(;X==Ibv8H4!d6DR|F~L$j5y*
zf6I^eXMrZ1Kd$q=-u4?Y%5$RO#rYN^M65LDJ0M!7qZufgb~~LQEZ93}ON$tQCkysg
z@LR07^uY-4UcXbA53C7hrtGMh=eMcMOl$mU<y4-i3q7kw8ge57hbO+ar2ER+Iz)oS
zAw4#XU*`Sb-&3osB8Z!HrZAG|7XT*9O~)n^*KcHbSAHD={&9wPy5CiGp*y4d8S+8d
z>*d>qce6F!V;vzMXJ{?+T*4PC=z25P@gF<jOoe}m&0h$H{VEtpzaizf9Vt;$9YML;
zw;g%kd5Yn^iQ#WLKvMhtA-De94k&y_Vg8wqst@u0O-JkksB=HJec|7B#F2;1@-vOo
z`|kNoH|{ZGHxjPzy0z4`xe<S6INnD2UB}$QfzHZ~pvXS^mmT{vKQ{VL1=Q5m|4m13
z<AIK%$lCMQ9btOqLGm+$Qa_HC-*n^&bgCmM^V^Q?`Z%b5hVkO_==$r9I^nuHlJb1l
zv7wS9&%vLeO74{3c0{F16l44ORh0YNjwn&WbM~jobkxcF*ByC40}|)wc4Ygv9ozgk
z$A2c0$;Zk5n~s#6$&REb=KL=^8e-LWPy7tLs?VF_ufNC(1`eU0+m++rbu>f*^BVe@
z@O~TRw;fr=)!C7h=lr%Ki_GOU_cO3zKkmK1?#A13s9O?bK>6!#@aFOk{h6TFAGhjn
zhRMtKR7X<gw;iL#$c+tbP~N}Uyau%#9pcerf9SB^`<T;C`DRWxO+*jpM8n#59Z?dJ
zYQ@ijiyhw{Or?)>btL8awj=EfskZz~P{Uo1`As)!JI-z(Jm)vvgcFxK(NC3=l#=wD
zZnr|MvYT|P@m;qFH>bk&6Gh5O0sBp-8!$#Zic)LyZ#%)63{CE5A{G?kcirGc0Mx|K
zuOi&vbn5^gq?-6sX0B2kf77v2V9`+;r+?d#&_St&{tTDahhF-dZq#0#-9Q-Ucimtn
zr;htG!aqK>-rsbja_sD=r`q{l$BKK+qvvOaRBn{tbtK~v>iBb0$H%uFnGgC_(SK%o
zjuiIabbwv`xk4wShTng$I9{Rl|4hI4^?Sv1y$|LSe|REb<Tt9XeLNq^&QK4E-*j~O
z#@LZBk#FTr#_D*Uq+<W)=ZfAm4V~D&)#?24oa=4;ei6U#x9eVS<ndm*YyL~0#-hk#
z`$Xx_nVCLpDW3O%w`(a=uw@}>pjGGuKou6u4(tJ<Q1uE*)We;oFNJZWA|oD@7_Hcd
zjRGUW69;!24;>{%=$cO$D)n9{%Dqh?uj<@C#|Mdju<U+=)}ftJvkuGZnA@z+EKn$C
z=Ht<7Lk;;aX#N_ClzY-+*@o~}iX;aHES_z^g@Htm)g~WF;cFsHZA%%FPUFDJSd>#A
zPl`fb9+Y7n3VC^uIMCD#VX82PjY2L(wd)~I_5*|7IOYF-(&4*EZR`YpHeQ9W__OgU
z-^$O<t0fA8JaA;iG++bl?P67|dIdH-h!t-Y-2hbJrrdCUU>jAkwWI8OQ(ClVlFpHU
za9}9xx5`Cclwi7`ejK<bz@sB2M<jFG1Jkt%i#m+hsy(_0$wP%JJh_aA3YaG8w5`ag
zXRcAzL0yF8P;FEA54?ih5R1zitPTKjK#jk6m#WgbD8V14W(H*~X@6wLg<e}VVI9v%
zm5mL8@0Df!VG&!EpOxW9=HEpL_9%hT9~HJ`YoHRY1{@X2m1nppAw3m@@StdU1tB~v
zb4&NeV*x2i8~?)^w+cddPO!mg_Wv+mX3T7Jr2yOm&Kl=4DoD8?*$M{o&ru+{0zQCD
z-uhjh2M6EF)#u_nM&;mgdHP&TmYc@KW!mXne64P2@sg_-*6fD-P5clUOYe?<HKbuW
zd=LcYObVGu4@Zv+q9J|Kkr^2Ppz4z|>RX>I+Dvy4j-g)ZBM2sLy=|Rx^lj^wgWtVK
zx#}ioFugQ=cN(oDx_|hLV#tdBqQ|PMwv7B>?b*7;5SzUE@XNJl_vNi$28=AcMj^OO
zIZX63HaRcXc$>CV8unVdwhnntwF}KGDNaemhEwJp-Loyy?82e@JObX0L1BM2#q`|k
z&*^&(o;Kfn+A*N=SE1JIf&?z7c5txutyeOzZ{2cOZR-`1*(&)Bj`~))Zuc3+2F5|4
z&~vMRo=5hGQ{f7+!0p_6Wm$WAzfi)tX|HF{LsJf0>YD3Uwz!U5=tZe8jbN4{J7T-5
zBwhq|L`~O^$d2HY@ehJa@|H22Bmk+^BNouE1I-+TB;d*@kyd$Vh<jN+o@~XTQwe7o
zOLL@IXE0PIN5a?|*|60m+2LD{9Ej(*P`}d@0)XhD018(;QLKzfJBsY~hJ3t;g+V=3
ztEiqV##-SW7b?M4cn4mHi;|rVhFdkO(4GM{FjD|FxMn&CGR`X~3_!^$MNMg57tB~E
zVGUM%*=n%^u7Oi=19ZlnKu%&@TdM>vgxwRa9+Yq^;QjEcvn_-7azzx$)??%qH<%2l
zD7GdBRJ0-F;6yWrQ6is5+*y%KP*N(34FQt^%}>$|p9mQX_2Rs@ZX>35DWEghcGU{v
z;5wxqA}}<3#HYeZqno0lFBGyrx41SOPG`lnp-la$=+~U)9srwPQuM?`p!gy&EILn~
zlNts<F;?{j#)spaIV&a_h2PJPFyq`bXT`(c`J)vMk9zHAg~Ov5J95pApv3rX^AhK0
zlm>~1X;ig185td4VthQ$gbJFOxfoVKGcz@iMIjUN6j&4mc}GC6JryRO&X7f6*!G0Y
zTGt|i#qA@Q+#Z#yc$1>Z0PI}LMXBKTiTH&Iejm|h<a=BY_EcQ-K*)mx12OfB!uh4@
zV+yQ6?X&m%T=R4ANvGuunXpHPW#Zfhg{zn^P<uL`+>u>i6<dS!1ACNHJ39ufmqsG+
z+GD!6P<_sxijjx+<f#yO!=#jghcpaRHJihcZDDt<e(ttaY=$$>-L@$F*b=8GP@_Jf
z<jFsY{FETDJybj=+v(8MV}ImTyePcm$DKhTdIPTFidp{WVfIb_ij-OSXjnohl5H*w
zMSB`a8g_G2M+M1u6aSsR(DfCRGqPLZ7yy-KC8eZ{Xjh_AOG0D5Q^>|$G0Vu1S|rX7
z;(aSV3aM5s9`*V){^Cdq=bWGFnlKaBI(}C{`!HshQvMFl3=X?>k&n*8P|-@Q-B{tu
zk<AfvMmu5$tr7s?)nU=9R~V}w%!j#7mWy0dwjYBNK0wGB>r_kV^PrI3lv?G5otW~8
zRy-c;lBy4wGP`ugk5eVYUJ>ZC#&s!x4Ca$Xq45R5KrB|4lo;8iI}kvVcF9Tt9LFq^
z_9`^cML>?{jj_o(7Jsh{;<UiqB@2q<T(`;>1cV>TzJU@VSP6r`+Ota<q61xo_2rTj
zC(EVxA(BqAaNX;R;B|I!KRKlK(y^C55xew0O!olm?!5rdW|dM18;)Jl5gisnmiT*R
zZg2dNOfInMuuR}fsAr49#9LUG?2<$w4aF+c5bh7Vq(~t$VHH2TMTvN4n~##EGng)?
zlzN&er4ZRAHm@RNn8j6z=s29_o*h22xaPz5;^oxUgoF^2nfY+oS!_yCXDG--kY{&A
zc(5JwojkERic#8Bx;u`MDR2hBV%n4f-t$DXvO^<}BfQK*f7J0ukUPBht&G*cAc~r`
zgOo6qL}6R~QO6%aNMIANp^e<*DPThzxyS7_Zej*j_{+1+A_REI9NP0xi*7Z*#W0ov
zcnKhY<%N?H^Qyc+B%DO0V^MMv7g{Oh$_mUXC{b=XN7v#q9R<e_YME7zAOKfwsFJwD
zT)}G5FBNuSk?EwwY7U7S5>imnn$Qh7e#ZYXK87}RU<|R`_KR>4sL>6=I8@jBCDaM4
z*i`^i*w8f$+Xm~7zld#dgr}Xclmq<cErq<5sFRM5rygLHd)QKu8%<XZj2=<g9bfO@
zpDwP}!9OYF$YZfgEe|*l>;`<f<#+U0Yb{!wAi{n|p^?DmwW1O@L7XtkTWq-b%DNB4
z6mvc35>&<fsR_RCIzb=@hEGJ$z}64XrU{JK5#M8#)@Tf}6w>!1#b+ezc1MdqFnDPQ
z6gF^b7Q<X1RDr~^)=P-4iNv$o{F&6Oh`LIM9rFU;0nmu~j=mE@={i+`v12Ygp16R#
z(0EdPvMLM^;6O10`ST3d4Zua;?f7r<2nS0gOERU!Tu3}P`6_+V47`>m1~i;SDP*O{
zt~J(`Akd9fLM1X<%yomNf#Xd;BhENCG5_ScOUO^IyM+8iB$CTZbz<3#=%U1^F@azD
ziBrRAmpLyCPM5-YMT<iP#;>_{!wE%1D3*&7yz9Cnko96^#E<8H1eFnID^|5^`gr~?
z3c;@O^=GPVzbJ9Wb<_oT1)5A85nZU<{}}cBKpPZnB@#^*0e1gI8bKg*8+5-ejBB9W
zo18Qqp|~bs$^#HIThKlbXsquraUmfEMET%7-U}vf9?|57pftz@5dd}wzvG9nwd9ll
z5Z+;3k@0YQTft1iWo)W~M9@7elu5W850j6G=zWXApUy+IAS3Ziw!(~rm&>Xi6u|_o
zFe8y~VucZjd=pbGD&iO}3b8R0>(IK8e{V_wVSaB40iRk#t1)^@4k0fZ^I{3iXq|7)
zj*79SOxeVDv@Uqw8>J?!)6x_eH8BU_@d8QGI!}d;Lb%5KS^`oYCNB&TX{-x=H=S#?
zK}B*O6;vemkpaE<<~A~Yo4bg(y6`nwH+>q>w*4faz?&4!!vD-J0**vplofd7oh^P9
zMG;NNk;rXZ1R`TXk?iMJqM3$tv`5U&U$e$&ijIs#D`d%ZTPy<eK^}F2kRexdQQ*J>
zB#jmJBpe9VRM+5wnWL%tK&HhSy;6xc!(LzlDs`Jm`gK_EtqFA>NyXMwroF=yZ%yaV
zg;TZ(4Ic%_tqJNLIoKwr*U|BUv_h^#NRYKl9KyNK3N5#*m+^<Xx{*bAh_nLCg}p-A
z(H+_P)`%y6A$wv`xMHSW18w#p%S>Maitwo}$i-MB_9Dkla6>rnctu(vV*=yB+MqqO
z&qv(|2YsvCK%1SwFJ@~IJoD&?CpCqq^?9im0ih`yIyL_xWhY|jM-Z48219_*F*{AR
z4fwZdo^3)apMxwHUOA1gO@O!olw!&X?~^joqeXcrblgdKXyPSQaXB43jHpd`xwEMg
z*woaAqc!&7Sn<GXO=HC|p?vf{v-<p-f>!q6OQKI66T&SYumUtZv^(&Btf|u3n-op#
z8(`5a3ib`6u}mS`Z%Vdu<Qa^01c|Wlc(^qkwTQ+trOI~%W0~BnJq??OH36FsJk^>`
z<T2C>k}~qPkasqaXo4>)bW1FnMdGBOf;XMqgXtfqCKd+uc2d{}PXe9fv|P4R^W@T>
zXhjeCg%{3DC<=?jHNrt)f=8zjQpp@WBV0|+WTMX;i^P?~>f3{&3s`#-_%NPrCS-w*
z@4_tJQ7dMVm@#&%3+9aZV7>r&GkefVCy7v5J1Sq9Np(g23?_CYWi26rTRY(E7J<hV
zDodE0<Aj?r6DTs^W)@|jo!l4rWv5k7Nh{s4!R2D_wCWjwl=C69+GGl!S|(^^pc0zt
zCUd6R+-M~qb+5Taiw6xtiGqZYF{P(!yuiq3s`2tvwk)pro)#NL1a!O^OwbP<PXrU7
zEhA}z5^Vs!F9J49nhHPKhVeqWI&OTS;&y<;n_ZHyjvL=p^JOG+w|2*H!R?M$fJ$^9
zofbx`vM?_GlG4dgw3t{0{-?5g{6b20>P?c0tC?>4f5<Ie2rc<u{vh#pun4fDZ3M20
z^n=D#nL4%_mqqU%TFrnVoK=+eR<4Oa`7;6S_=S{<BE6$=O^Sj=5gIpc^J6D*4TSjL
z{G&zwQ=7?K6@&v6P8n<64D+crXN2PiN3AFa>u#A)lYwcn6Q(|m-ANnG2gNB5>}Hxm
zQMmjVkDdBf63z!toSMaXi{(Y(ERd@U3)W6J!5i)!6hzy2e9nE5P(kgJ!r@|NPt?c!
zBvHyBB4?MB6=jpNvujmyA<rgmLQv19DHnxPhQwz80yo8x6mkLk<TSAXn+w(OJ}Kl&
z1~jaSdS-OwN69_(C<^(4<Znb9)YeCJzvF{+@hJVOqJh=o5ejGmR35~UbbvIrgN)@0
z>#$=<L!F1LdiX&|kGMj-Diu@N?GKMb)&6|A9Z_HU;ejZeo`&%0MamUw4-Z6D1BFe*
z=s0f=(=-RKpoTbKGgY}qjIIgAydl2Ugc}qkETfG`1eUq9h(co-%-XP7D6{q^OKH|t
zRISb0cr3`Nea4!dwW(0nvvv^+e_}fvUsWEIJAws7OWavxw8Z^Q*@PBFNe@Y_Dwl3z
ziYVbtOlkM9swdic+*Ae8uKS&g=n_uyp-DKwhX&EaY18iZ%LU&6i&IL#qEI+FZBs9}
zvRPzygY-afr}P+>sx4Kg!M<Ve031P~Vt}b5pt5wXc2R#-9Z!I1NqIX|gID?;>-3gV
z$XdSA998_cw9TU-!@pG0hB!hgvJL+5QgvB-xYS{kCyo~ZniIM|r;t7*>EsOvdZs|q
zc5%fY;-I&SORk#X7nfZ47FSa@&Y-CmH17rncs);|{ByQ31LIpNTBqJooIs#j)w2m@
zsOxFfWU;7v;t$?l7(AdXw?|!*y@D^lCW{4J0j#WTjo2nl1`C<|nk*K4nl@Q1s?K=&
z8Jnt%PxZ+GA1oMN59gLZsP(pHnQ>EL4VEI07ke@{s+AwxtDY6j^VQ!N2_~xmilUd{
zfHl*@xBzKDVRdU&Vq8WG4z8&e+1b=-4em(P6!hZYXtwBRWe=4TXM`6En4sW1%rsb&
ze}G~^7yzei`ND78kKSb~IY2@W{VJ}HnldBDWT<Jt>a~JmX$jVAs<2W32CAYyps6<%
zQ6K52qMhl8e6;MPqUk`2HlY+Q3VLA)##AR5Hk+&@G?gK3%@jP()HQ3a;m}Az_d**P
zhiocO(+2JqK`kx{dyzdbs;lzN%1g_`N*D|Tg|b{;V2PJOu&r1x8Vn<gE&n*p7cZr;
zh1n6qhglN+O<l+VQxCGh($ot17!*2Q@&g*8k{lXhu#^YUoc8lcPflaRl`Ox_VLw-K
zZpK$NUZYMEX%*FW9yz)s{ZcRR6%|iSFrAG7R5XMiK}tJ3KMwB-D?T-+iB#7X%_g$c
zH>V`r`Zn!lx}=<vz<+OW8h};stTY*pno|gL+c*V5cZ>IEVG+H_?Lp?^xC&1RW|+r~
z+$)QaF0fPcfvrp~nua2XNBD6tAt)S5>tPC<sghWOr`J?$tN||MFw`S!C^Hy-D0I5z
znZl=#tYw|8mX0(S@EeeMt?QubFroE^uR!^bt8FF2l`pP!`mcLOlU_m2guZK?u${i^
zj!z8v1bOZuYs-4qcVJHII#-YgUv5jJ$5|J+W9xLgF($Ur5YwH=Rdl;CI{r=B+^kKo
zUrg6402jtsFpI1Fw~bL<UFSqBn|0wHHY~Pvy%2!fYh4EegQ(<lZZ!Fj??Kue*M9*V
z*65f;C{1hh%Svf#k<Jk@2swTldz3)fTE#kG)(xVfyhG%9<qr|ZY(+cd52V(jboxfy
zkJFUjfZuDVys}mh_`MOmfq@JKW?--8fo>|Q+Th$VR$e`n0#@KT4Y!XXOICJQ46y5G
z!p@-Zl$JMY2DM}l7?Bv{(r}rZvT&LERlzc?Wf%<)t8|7iu%<y_GuHlX3WRd~BqO18
zt5FX%B@Hth%v1!qDfmh92Cd#y{J9w_k(!D~H)9-(9)fuDnCtxpi?6BVcFT8KMonQ$
zC<sc=D#bwQ$%GfH5hJAG1%8-{!Z*C_E3AunJ|+PB28crwieUq|Zvfv65Ewmnk$~Va
z@Yy_L)bLpb#+^D{fc0B}Zi|wUg{S5S5g9t{4Kk9^b4xY>V^tA$%nyqwJg}HyqSC}I
z4wNCGw@gMhW#Th`%2bb_0S=guJul^pnR5IiUo30^EOoH*qcXY=Vt>M-Jg6BqU<8{g
zC@`nWhH6-?d?|!SVtfHwVM7|;i9=^F0=uE)SHy0nZ<a|_h9VFRh5lAM*YSkjI;4=D
zP+Nx#FDJ?knQ)jIW2}ahFveI7ovkO1o*`St$wZuSX;ve{U@@nR{~l7MqGsX>rUkoC
zk5=xsqn#A9TRfnY<uEIT7t_UUG*7gMa++rCl{J;o+&Z^u*Ax=!KSE136qQ^QzS>Sa
zgA^5QG+a(T2V(UmZ)jr_*kpuk<U9qt=1><HuO<~{<}2AG6AjfwP1R>icE@?E8#II|
z>`TCL*rc*(K+3TB=x=(3wom<0#~%TK6=_T>Mm`0|Xq~*sRePu>T-5yxcnfwJTAA#C
zXZxEFjr{Mt1z0v{wMS+EkeB)F6t<)RMZm76<$!7HYU0ufolyX*#$d0Dp$bfivWt7y
zP?*dvYF36|ufr}r&=x7D!{-<?sVrx3=Wf5CHLZ3w!+mYQy|hb$aKjRI(WYuB<7*f1
zr$x#11==wWqdoMR8a_^hi@S8?TII+tjUFb_OHn(E6nQZC=axw^7(B9?E^gG7ij`v%
zk}3)wA9nE?Vg{F~8W%ITOclF~X4UJ__=OP+djeCsOi;>1%rjOBvzy6LChjpkD!oKU
zl9+deopm!m%JlWlgf21<mO3UxMdDLtM0NaoOj0$}m>5+_S9Z4?513$h6Wy+l5HPUh
z3-9W?<O`b6ofF38b`PpjV1}ux9P_5QSV_rWo%-^rd^}GZoWb0C(}r!R0I=cgVnr#C
zFJ)AP(B@ma;0>$W{SV#l>Xt)92D~9MGJXh;u=~-7AmgeU$Q&wDRYA+LYjz6;fZN6h
zWXH@Z9u!H*WYtsSnQ_>FUAbS6AYr9wSAM9h7^CE#hE}GFHcc8w^`p=xLp2n8_;Adu
zD+5-$p$-er^jDl$ncm7WZ<dDVHMW6frkoD(2xjPKh(|qIIOl1UekKwdn5Pwqw_p$s
z^=FDfQ1Ks~H%KgB6v-5#bqT1Cqki3yTv9~uDvfwia&=UZ3zr8uWJ*`2eBlN8JYqF8
zzDLK)b^e+gZAu|8F*uR0UShy3a*09$(jHr?wxKu^v$>HlR_WdbFhOc9Ny#s50Mx4)
zXUn{i60fsm-blV@22I@e@i)lI3zZ;%DwN&+CT;2OR3j=y-cUx1IrIj!d1ToiAmwLt
zav*=a^7Re*<Be5j4f*3t`#+L&jSU;XkUrj2-gZ%PIV2l1VIxk8#zA$dowxV^+=%l*
zD`5*H8^|dyK!im}xHaQ>faJTvSumiyHB}roAm$3H!H`7W%!*k6`LQMr0|Ua^4|Ynx
z2PrGl^?rJ#PMKp9a5-}Pnu@MOj^9XR4;%{cHZ=3C*V@aAf;A!3#HdbsL%t$0FtH{E
zI}mDOG8#UT2}k0VRImK-)G9WCpKuicsbd$F>NiQR=U1rK`RN-iV%ma3zk<6@;G;FW
z^%H=qF<li%K5UA!GdLrfBKmA18Lx%c%usuv$pdCUT5XDSGz4?DW@sg5j@}E*RcwuM
z@`hyi*7%bNFeH^0d5MLfgJi}vuFmFZ8x9Y$8#k;TzNHG!$56Wxpg#vlITGKxC9;rj
z-9CYZ)*~+2G8nGPcU_b9pU}i@ZoOiA$hvQlhTmk!4>;pw)wOkMLngMDo}5jg=!OD|
zO)>43VXa4EHlf?Z_-=KZShr{EmIHjYUV$=opb>-X=hh(suFkDP0$lOm6X47wJ}`T>
zUcvxOo6bK7V5_$ENMNhBbx2^V9_J_!1Dfp0s-)4oWHf=%WHXM8&oeQ=U>JOp5@`)R
zaJcoMF2p_40WpYs#sgv?jHxNf#|DAV=GH66JF8a?m;M{ey0wdd$PQRf5>f5s4<~Q+
z?j1xrV>ut@o3_g0GQd1GC4bR)6MhA@&nC~q3+A4tyfhoALQMp}$XOi%`2z*WfYm3_
z6lF9(#oy*8-EZ^_U64txg+LhAs`w5ay-0f%kf9AI4+VBeqgMeUMr!PanP`J>h`#m7
z2`LSj*|P!1sBSqWDUk&A_K8;F9O~7Y2#>lLV8Uz44>c5AZnB?RqD3@95YrF{kKRF2
zOt97+kcKSVNrPgOVKi#fJc*h~%@hvI0MZ=#qcvw4KMmN+i^3m{8CRJW8aUgiwa*q8
z@dT2oUYh9KMypj!*upASG62yem{PG<P^Jc~4T7DDzX^wW><m`Mw++BL30RdZ7xpSs
zpb5=-6w3wODwYf1H7FYbtkz)EQI2fqgpn2hhwgdt|K3Cf0JbGD1hDPgMO>4oRzG+r
ztO2c&Y=Jg*C|#`4vEl8;B0aYdd9`Q)?WL`I1!$1Bsi(}w=oo_!yv?>PelT}x3#ZE2
zX6;}=UCqwum?G6CJ_C!m?r}V2rXGD8g{B^O;M=V88hC!Q&g-IF9AFy?$4NrIGp5W+
z*f9+3*(vwN(Oi~$+Zw5T&3j`{uGAy;L_@5J7DNs%iv|dfBT2Drm#%10jIG6iOIP$p
zfzV}%fFt6tz$R1;Xcxm+;67;=9SR~ylSk%9goPa+1eq5dAcvP8Y@*P7=s9-=u^l^U
zZgULrxUP?uuFCNJwCmmmKQfr_787E#-sd*7q~K+kKT!rHv=v~euin?TJW08WvwI1q
zXgwRdQW)+>Ukp(w8x4;0_UKI}iWR#;>>k?(mL%!hfJJUk+ZdRXj#kS8c_kwOASmE3
zI@sFd8&63oiHP0yjBSqj@O+A^u}7cr>q<QH*Oe$!O!EGjQY1jQiV4B^N7lBDQi~Hp
z^iYdFBzrQu6y@3G9WwmLkpQ`Wc=~$g%SPEoeSC3bQHob<x?MPS+@-y&EDo%`MdA;y
zv9GpH;0$Qj>AMCQ5b-)+)(|2vo|gql+wr?T*w6j=UBB4RQlPS?C_n<@LPSx~^W*%D
zDe+hPlLa{IG<Hvv`>FAUTDdX`>NFlB%YD{qOo~q98ROlL<A~hv=YAYtBmSmN<6MIM
zG$uv&+mrQ6r97Nq__Jv?t5u4_2})@W!Cl!^@@_t|9;@!+V6Q+fdF?Z;qf`T?er&o!
zH~vU))7qvx1fz&TDy5|hr<97#qHM~;e6oD4l!xF;nO2}f^)jtM@nZT)T+pbjE5$fC
zgD`(8%3YE7RHnOP;w`knV=MDZt-MMB8z9)aBFIy>?~42;3{J0{Ha-YCBdzgh$l}G)
z|ChYjy*(Ln&QFOvDim71mOIKP(}~_UyGdSyeY2Y&h@|Q?8^RQOv#nc9S+Tizd_|U0
z^$PW>YDV)7r?S#~<W=QqJ_M^gHD8NIZ(940nt-INNw<=r9<BOtPMkn!HF4j*yiSki
z+lO=7UZag=1-Q{GV-Q9Vs!z^PZbMCRZZF#${?s!ywsKbiG`^XcqqZoH8C*a3I?wUT
zFO#qHo`3;-o#!gu>XU19Z+$`xTOA#!`p(+w#}^Q$dV98BA$9%Sdc}AZX}ByIF<w=A
zKUkDX)!<?N=-swXG2mWruqgfBTlENap^DN6Y4NwWtxxc`_v#hW(d+J*(b6M2jn$p_
z^_EYn-s|O!s_)%5J5?~VkJ@@D``*W9cM5Lyv31MA&CObsql20l!5S-NH2(1d&wjDI
z^}bu)a%gPju<kM@rh3u)y>&^R-J7v4m-P9?nArPM#>7-qyPs^WAMvug<qNTU+1*l=
z?OvA%;HtXY)-6Wkwsi|8DTHoOVl@7XG4=>j*>7`1P2F-j-TT%pM^v)#K&CcJ42q?1
zwiswan=J-vj^f^o=&PMjRvG0IZF(!9eYhU+0pZ#Sq7@eNwcf70RwDQ<QuPUmQGgq9
z|GMjfnYh0FDyIkTZ@;&0$qXD26IZdSkHE&?o$7y<NsEs|{YTzIcLpmP9@@RkGpznQ
zq*<=F_mO3E)hRwbR6RCxE|~D2g!uBX@|47<3otI6C-Lp_-{GoKNti@l><TCgzs=$~
zF157*5i!&iL1uX5_u<jXTcZnG&k}^V4=I|Nh;jsp0)o?aNIue1OPq$Jgq)R?2e2H+
zR_=C=tZ^(aSsW2VYGtA?2Sq({p+}kL<^aRXTQid3w9ZW&n`PC3Q;)b9!KpkcN4aWJ
zC+-pNMdx9_Z=C#%nDZ<b9v(<t0bg`f_9-78DsWYB7yO;Q3_Wm)CV+@sp!qR+^>EBh
znFCnjc}fGBIM-%rpK#&!S>kYGUV3RxoMMyVg9d9!PvZ|f$M{;w1kS7}nRvjzl8Fc3
z0vuG5)>2Jrr4#S637rBsHvt|a*ZW$iG7nvR*GyS;uUwNp<?#ckPM`Vj@n4(!KLl?I
z!P8)_StN!mtXE-|ndrjlF{Mnvc+)R|VKanbkr0c3!{L%j3VTj3`_R>+rML-bv6rq8
zgj@8B%0!^zCP0zGFJh0EZ3rkx06JnINNlc)+9(3d7Ge^Il1`d_=`a8YQ_u9p47do*
z=8}2$N~NJ!z!?yOiTm_Y=vf!waE8o8w~FDJ=vFa2*iF|S!?T3p(lc{mARj`wN<z+|
zLV9rfUlq-9gB2CcamS>d3Y)<mxM7$_>{(Y_7=Eo+To{6x2nF`ah_$s+6&7~k^4-G1
zU>^|ZHAAWTEnDCXcXVf{SXJQEWpJC2&R!YPwbpiv6vLHycg+zP+WjM1ES6x47K4<t
z-n5~@O~2U+|4_fR>+gmsR%{raEL&_C9wfKy5O?Pk<<9xFIQqg@56C)9I4`bScLfIB
z@471x<JN^VZvdI=!lGy7V1Vj9q~roT6)1>H=YGT(DC;-vQukc=e)(T9GL_mz2;31Q
zjvlv3g@XaxzCThV5O3KZ6PFO+(1qL2h`0WfMB%P@N}_OAJS9=kvil?LBH~DU8YnZy
zv_E`^+)p$(b{zeWd`HQaBTyMn{ZUR(r^}6_{*fyBz>4)KV&tKuKk^ErAVF6}1_SZ{
zi-#vA7UPldq%rmgsLKj19?@oCagSDoBFCc9h!OE|39gx~l=Fv529PcNJd3b?%1<2#
zPaaAO>2rvZo%oz@uvz-asQdUimlY2YUw||Hs+jUcsVMW9tDhA<pVv&lrh<}s0-;rt
zvKZ^9QVmZ$=>4SSW(9YxpY*fB=JRrJ1wb(XY*BI!=?qM?*aMW9rJZO67mUyFcFt&3
z#=v_G2uPcR@pZUDrC8f#;o5S-c~!8IYEoi)EQXVTV9UipfZUgA>A30!vEEJq?VhA8
zF>^#%RUP4`>1B({@#OH8sTX{4qfsZ)K4SEYtyw`}@g@v_;2asicU^YEh!g`Q^J)wu
zWk!=3xGXPwl}e_6wpmMjW8}KD9INu{EbV(<7#;?&doN55gDeSN19Ni%WngArKp2)P
zircKQp_*+0Sj5a+$WjgVPcPsJz%V;8B@Py+a=Y>G`QcmhP36-I<N+p8mwB=!!cAaQ
z=aL)c>(P`cUk|5D@lq}<kS`7|palS1xM1KK2IhsEfUgGX_SZ`RW}cSK1ElztAoEyn
z%muyI0My_@>}!D2^QM51hCla8vTv+BEOAFznFH3aCFr;d3?K@zg^X1GKl13k^59$E
z`QDh(7h30PGBXkoxZWy(kL8nL&1%R|_sU*xIBFDMwgSWg_tYy_9X3o?K00#7f%gtd
z2&`~1S3ae$T6l+|#ax!p2F!Y|%yMLH1`>TrNaM;*ie}5I;FUqjl~!UoGDuzVY0NTp
z0h*$?;E}-jIh=kbvVL|!{FpcV8<tNy0JyiF)diU%+p1uB5^_nEFOFPiZ^{PD^ya7*
z5GY|U)m=mZfh5E-(|d>VjX_}sFV2d_L@TBzdnJi?k2(g-6wa56D^QLVJQszT!VrwE
z%C;y2>caVr5|$%>hu_Il&IK0SkTlG~5J!??l3iJZ8EUo&oKvo-3(PpuyPy0WCiVkb
z+Xaf;`W-E>E^EdMMx;Ypwlwr7E#$uCp+6X#?ypQnX1R%11d+vgQmN<wNk5#q=zeNs
z%;Gmy;&^2~ez2*d6%y9@+B}-G)VlV6R;PE>^K5{XciFNTb>;-RUJ+%XZ+lmkFF@_1
z@;Q2SEEx|8R0C)Ik)#aPb3Z^xRtn()DZbuyXaLyX`#>vuC>7XezABt{a}^-=%2#&?
zhE5fPqB%nvBN8o!uK@Vwl#4*Xic#s{0Whb_>fVsA>s<+!G3qI?N1T8&9<ss7z6hM_
zgXIcLGx(al>mFu#XqWY#HKe`kT!L5Cg%9805Orb5w}E0+E}(e?rFp;6$R1Kb2Ze%(
z%IV$mt|BRIP$p70Z^(^xxe3~!ND!e3?jjem{?P^x3|;YvVRMCYGKS6NTxf#_1`oKv
zZeh0qcwsjVXsR30O)mA)h?a-URh*!~wc)Dc+~B$J0uP9SX0ECSZNR(k2qkTBEqGxG
zL?tz69fbx5fveO4A$8mV26V>X>x4vow?zTg5A;x%>K!p{?gf!#9F<N?*xKC-B&nej
zA(EQD!+}AkNEB8g9*rOn!3n2>^HfDTgsX-{gQeP4=i+F{&TtnNN5D=;ohJ-ts1pZ+
zWq0Lw&(tCd<^TZL?m|Vn)Q6nP&Eu|f5|-Y>RnMc%Tipr*i`@i)71Hc_KcwZ-UCzP=
zb1ceWfs(yw0BSI#M)9ot9b`T&3SsdwSIUX3aOK6~^d2>o5cL90xROb(>M8Alk=hGK
z;p*xJA-P=Lur8>9>Mr<?D{Do#JW~xeOOL4GhLky1ZTLl5hjhU;z)tB-$kGN7doKV7
z0NuNa&NpNVy5r4r<@Oa2;B`^xmH2*fA$c@kTt^+v*A1DG)_4Kf-~B=}yGV(=xQYb?
zc;*5X4j`9x1OCH-UeFTAXLa9!|JV&{ghG7o8}MIKH-a9f8sRSBza9<Z9m4LQx<8AO
z8lVgH@8;4gpa164>#j(fq{}VXP>cO=!Cc&2eMX@**zJOXuXFit&3pdH-%V+_r@9d2
zk!!Cj=jLI}E9d4~=Yk$d8kiF&&TV^Z-Va!=YYAzl4p(MCZ{o&wfdxL$`kjh6tY)qn
zP7PV4j*!5mkv=dbx!$l(1Ct-&hZ=@Mu+R>U>T*jn;E^N@ho>%e{3ld0xmp>-=!%VJ
z5Tm<n@EODi0@^p`1a2XSaaCS?DS*+3u26<B`p{$I!Q-v~NS=IGv7qBiQH(nUZzmrF
zGo&eR=q^SOqYuFwB8c&mvP72UBwq?+bh(%r#`sCOG3N30QV^pfc<;p^MiCUm=z>sT
zAR`M~z7)v#NfEztDG|u%1Ns8v7(WPPRxU2%7(qEeB9C*uR~+L<E5&uFC;*Lw8wF{C
zK2%Epag3joU~mou&oZ>2OCvz=NK$@8H4RQKBJ0V}SSLclxTvb=0xG9vPNWrBX!zk=
z`3_6l2O$}$f(xrg`bSgag&Y7OcBfqWP7dzYk0xd_LhiOM07CktaEe3*?=^hLDew!o
z3D7$8LE*>1hc?7uTs$2$O^Tt7OUAZVjf(<XM^O$$izO*#H?1unZ88h6-Ut@^q>L0P
z6|88uO^cE>eq4=NB1O~6sM10(9Bd+q)VxiS@ml|+NdEJ-=rE<!9_hV$C3k5`(O%4_
z^tOBR-F*B);_-rA-(ANG&I&wxKPfj4!2FbsUW!q#<F_a`&p*ub;%Nd?RK$bfJb}#g
zI(<pG#nTiKJoR`$XGMhVOpkCd@DodoN~s%#h7nyC-4R)k_esw;Qe8LQZNH;H;cbXj
z!UM*c<nfBIF2l`>$`?3zbzyeeLUgNk@9KoS42FKWDmAWftp048)*@VE)5W?|xuH}2
z=uYKUg&~{@4hlm!)f?4;@KkP91;VA=stklv;bDyjze`iaVD4Wu)$Y&#&)VDcT(=`x
zLi7DA?y!1Lg&qEg@DvGJf&l`G5n@8C8wq6%Xw(A!J;xDit$i}P?sGHWY+Whybv(!0
zAKTjz4zE}tOSR0&F=+rfN(Y8G-T}Q8GLXlj?W6P!`AO5r9*d@ssN@$-Ara8y@0gEe
zs!_Y>GF8BYES_k@!Vi#bN^04zp@Rk%DKc%pXO97B>w7#Ii>A@e63rqdwYyG<IyZ5&
zv}hLxyj6z-E`wG{py-d7qJ<xHNa%<*7SE<il?S@pshG`Cl(-XFTAq^B`%|tcKp>|w
zV~%xrfaFU(I(CBNWh}mVhPx1oHI+PbY`%HkD34u#$9vq+Iyk&S#431iyV|WayZPpo
zvTyU%Pc6}Xk2ACWg`X>X-{v89sM|crFrQxmt;$n?<p(_7d*&aYhj<+WWAj@d>iOca
ziAnzuclY`r22gFUn_^Vl-4xbz0JEm7)_)SRYLdcnRKn>g$SRYBO$8GV(1TscERXl7
zyw#IzkxEA<_sjrj?DgP`LWs>wF^a5b<v79wgHq*n6aj7ZdXfebb-&&wW?_4-XhDEF
z=oy%0<ke!bH)iDilM=#R3EWS^c|4M`cOH+Vq>+AZPHAADs)a)|^Vm(1fHK!z`u5Pp
zrE2KnQYDa}5QH@o=}Z9D>ttkhzDdebCh&WGl}PgUd^t3k3GnrL4kV+0J)_Jh_<B!)
z$$GwAtiySyp)^szRn74xBIK1uXujh0BC|)egN!%r-;wWm=sD%!mHL5Oq_UGT<6?Pg
zrCtK=u0j0a0F-JDDGP9F&GF{&0iJ8V8B2lZx{`WZVXB1*0s&Y#{zvHcLpyt<cawJq
zBY5?peH_TG_XdK<E!<KtX{PQnFcDZuB4ZfzlZdQ$&`(l)zL_+Wt4S$OW2@Fe+3V&7
zOE!4@q3txlUpmDdaYc3iG4v7w)wGEQ??JR>2EdyWY{w&T|Adx#3!<ceadd6PhItM0
zCIUQIBHZ^5%zcGzjKc*&EY+ykP+jDWf+sy+7kvrN!aXB~c(^>YjU_y3zR6GNdKqGV
z8T7q~&iYDl6Nxc_#%n5kWq`(Of;#&tQO&sA1*a}bv35c1HI>~Iyk75}>^LAEnWnwv
zY}`Y0Z#f&c=E`S!a3FXSngX8n=n9#+iRYWX^ti5~IeR$$*;iiVi92p?sfV}ip|*J2
z&XjNT&xmY&Ac@cf8%*Y+uFLjp=c2s^uJCI}SF(A9pYw1fb>9v{_#(otU-`ZFpN-e;
zG-4<HHAD~0#@lvUrB_mL0vyRFAzc@?kR?JIYWtX=Je^|MpKWHT8UVQpQ{KOstf#no
z3YNx<_iuXaE8%E~t(XK$GSBu@ssf_d68?d{d6w8O;wuKH4B>?@#$-0)D@=37_etzZ
zV$x1wS89*V9Oh{PDnADyV&6X^<b|K-mDD>#$i{^G#uWBFiIh^p%-M;8;paI!Q7|2)
z>K$!^*#&*zL3{R@B|ee}n1+(zM0fy>2mQSLBG&HcA)62>Roj9|aZ>gRlR`3g`j&cV
zo*eir&Qe*01Y@D{7lLbc?$QEzP2|LxN^Uff^X5g15mZGy*`1I=Uu_!U6Fl56P>pjq
zmBwls5pz_J(}<Z{AR?S}hxLWO7haC1j?XI5TgX!3<+S__TpWqhn-o>6)Ms48lR?1K
zh?g7x#B#llL9IQFfH{2t1&f*@cFWH)%N#D@a=hz&rV%ekILI{O<+Rp;fw~g(j*z*I
z-XSsZQ~>oPeyUUPTnRy)?B2!*w6<$UOduzxuU1sk+`+DFN4<kB(C8}xj;Y|L4+J@Y
z1{E^t`fEqMJAVOVB}C~;R-u_Dc)F(80EtL?A+i&pqc4n>7$ib%pAsczS1Mr?6c?``
zGZwsvUfKXte20MZJhi(XibnkirK*C>oG`0~J6OVOW}5)1PNaO8B5$Ofb|p=cngJSK
zGzfuVt_NYyX*9NoytvvE?;b|?Ri1yU!^JtJ+EK2+DS@*IKNzB=;KA!!8kp%xB)C5C
zi2%B5(eOtI*%Qi~N7NUI&ckp5*d+m6oG0)+i)R^2{&V8LHd?R*417VT=#&`8P{IIt
zD5V!=94QC5V}{s9=+haeX@HvpZ0dZOSyzHJ3CGp7XW6@5aVJNEahk+W6%ihCP-5Uj
zZ2(C3JA$SY?`lVcdXFfJAwHG~uu>ZI=su#&LJFboN3VdLKY4Bl_6)HFA+raUlOu4D
zqL1_=K&e7j=<I@r_tBx|PjV%Xpi`>c*dw%Tz-SR#H6*79ksI=EVT8UH@<;?Xc5*_*
zP}5zJI&hKARlz-M*(#33)H0&Tf^L(Ed`crs4Z~M6g6D@xs(`?*O%{OAf~%PS&~jsh
ze>BFyO<<`;Xt}{<c_nNc(fNKjXoQD)T^c`=QS}~b3PCm=8YO~kT$?T2mP7R7&t&wv
z)3rMpsxG4P$w+g57XTtGeMt|(mq{N={iymlF<pVjz!f+bgT$o9S5&N-%vJ_~yLLjP
z5gR@<TL>I;<80N*^cmuMn!DY<*S~7{i!5p)|2th+C1Fq@00FZIOovPN0+TfyC%Cy8
z;3&nq8Q_S)?2ZtZO`p!(3VO^ELcw;ZZ?$xl7~l$W>28H!O~yxyxoaYZ^-31X`6jlM
z0f1fuEWdwxQdIrdd#`Bdz13N)=Djq+fuLFGiw)5E5R2IrF^&~)44L@GMqI@N5AWDh
zub`ME_I!tlxH6?|m`M6JHf+2KlpT9$l!$E>ciS@=+q|_IAhvnyh=bu>M>dCv;O5;m
zOk@)tyK9(Web_SCFq309y-rX(Y?)^p(HcWkcN1~AV@cU;N7VMw^gy93`U2+$UTCb)
z5_LvxW24{DF-tlIPG;Ual*B5CoW~t3zOi`PW`wht182FRhZ2xX1~_AT$@PT*=aou@
z!Ocs13i!3JgmZHg6wet2QhzM194M!ymE%pfKv_ZvyjBgU=EhRs?nEk#vFOyF40m2S
z3X~6gELbA|?TtmV|CtCu9;>SkVnjtHIT;1btN2+#(7L9c6{lSM2UwsE{l>f5iNNKd
zYt!j3(*i41zn-ByLK7&$At=<9tSsZLfiivw%QYEH4dvw~dI?q;qL;vT0H*qp*Nc;(
z)w&v-MW#1&t#<`QEx`-AiSTRPu3bTKY-nxx%o5zplhN3^xtgVAlBa_;Y8eZhIl<YN
zx4tkO5SN{-AgWd~FutmhaHQ5CvIGnwV4oC`Z-fgG%nP%>wQ|uZhu8!`;1Ck{nNYcd
zVB*QhZvm1gE;fdkYu|Cbt7_uAnN2H^<I<|a{;I1CjZ4=QIjpM?ugKQ-uyo%rVG~@*
zTWe)mRf_pW1Xr^FqeHh38s^}h<6B^dEP<6rHf$w-cv8d~=-K+Jl`}QgS1r==aPE*q
zeaKHgD;dR5BEIRQ<(aDGi45Uqj}3ghCpyP*K+f`ssQfYPt6EK*sUg@@L-|>+s3xy}
zRdY}!p;$B5zgi*#Q&ssas}KcKRf1_Y<R+;6F++JKC#=W>^q`#E=TJV&39Rj~_^MQ#
zS32e(voz5~CCQ`7P`uS7HGo32rXQh}vQ!f+R;&pK@38%D>Yxu$I@5{F*B3H{j|m4K
zd$$#+9C&q}5*6*$d~12JfxVTAwd>tk5QzOIpq<f*b*x?*5_OLxho5995PSTri?pFE
zypxm#RysLgvx=d9CXK>SY~lnUc^EHFXMjM6p3o;nB#Faf$Ju2lx%IrX2g;c}gZzN{
z-a`a|@m9&+D@1e#`2iWEl9E$Acnjrx73IZzAX<gUYkX?4;K_+YdIjaKzmlZEBY6Fp
zK{mkkRjY=mlS&jfAYNw}hN#yW#v$^3&LI2W`%24H?*oN=U9amfNc?9y?Sg({ypF;s
zE<oO@&mi$1%>@9zhXS>q8RP=g)*j#jY?^*(@h0yP4#xul<+CUyo??nbheuIKV)CKq
zo4({IhuC;McVwYxPLCLl<m2_zRgR|7{CjRsv1+cbX>9T%1bGIUJjR^eCZmtD+vfXD
z?^L$&^;V09bI54m>^A#)tCYNNwa7YEIz?dmzSiPOeLp--cKdp(<Vt<tYfXQ9-)j>1
z*m=K1kjbC-OB`9^OC2EBmA(HZd8fY>L#$pZm~{Q?#oh-dYFn>}63tYR<BR-Zf(PYF
zh8l;2rB%eaTP^3U+7%5oUDUa{41-h0Uf1H61T&S?{zn`uuRyZ|qTKN{Qzfylnc6uq
zu;$5)as}^96>)C=nkh=&1z%LUw9X)S?6j}hOmba0cOX!*s|gksi}N)xCDC2$1Tx`@
zG!G^4uVLP$lfe`kW=URc7D&0E++?prC*qh{LOU~KQmT#r`M3Y^>A&6o{^S3VsbX(K
z%Src#w7{kG|Kq>^?LRzseYZ~+{__7n)&J{%em>>TfBzW8Ahdp4m%YV4&+EVa^S?a*
z)qnWM_K)q;)<6G;=YRc&fBrXp`ak@~|Mc(w&Hwh#|K0Q7{PS})=!(zQ{rRf;+3i03
zbDZAWfBT>Q?Qj3rr`~;d{qMi~mrTQY$GI-Q&2Rsblumb2s$4_+D|>rm;O0-g{fGbI
zfB(P#%|HL2)yu%6hTHnI|5*pkV}7*DzuHY?f@UvCt^W(X9OVf9p_l*5fB)aAm-9~L
zyi+)i_5JyWx6iEhf3=ge4%o{9oZWXX|MN<?L{cS$nEzY}5#a0Q5zI;`pZ2%TN8w?9
zTx0+3zgg=a{?niS^xK^oEwjUA*7tpLpMR{`Z*IANZEEs{f4!q5q~fo6f&c3BO6e{5
z*FO)eZ+Z#4{jbg&s{y}$`%&E(REU4edjISNv+cVqZ%p*RzL@^;W36d5{q5t+d+2v`
zxR(BDZ1dC(s!A06LAA1u-dbe*`mqwCQ{P&fm*PKG!=9t*f5XuJmg)bP1U_y&_r2;k
z{yWqE>yu9y)jK-js(u_DC~w|s;=uW-+5lg@stpm?|5yzthPPVuuciFE)%L`92&eA+
zn|FJy{`9B+&gyS}&+4Z??H!vOY(I{zZo%JLqy6zx9w0z^Yl#u*r)t;I!%~J(arW0z
z{@rT0)Y1zu-E#dcs_Y~0-Xk)Qwf*Z~z;Er>Ux4Ax;2oVV5q=yUZi?S(3QhR28julh
zHL<z;SS{(X-b!H0`l$-jg=+fW{Gor_7x2-)!z<_K{=Mn{d%l2c0DdoJl>cCKAb5Ri
ziShNvYKV$>t0_$4$7;aIywxnemh$gbL!jdO3i`J-{WpIBy?+eEe|;1B?eEY5Xa4z0
zKJ%|w$naRIlKWq=jFas`Rd)MhML+&R&yT-iZ!DDOyY1|EIsMJ6{=#j4XVL#%M$h^4
z)qDPmwfkiUQqX_esBmNXR+E4S-M?W*?j71(*Tc2$MeXkyBEK{xNe}yW6U86L1`PFE
zNrE4%bs+WLdavZ?ilF8Cswm0N6=&Tje^r#^7hXfZTu}S78=Rlt!!Nvr4&=aBPbK+z
zi13nsRg~oCikDL0yBf+rRx)^9-)gVq=ZXLqepQs@7v4lBfIWZsMf{p(B(v35UnTi@
zko(V%i2w52EBU!%Q7?bhqu}RiNK*AxPm&)ij%1^JtFinGZz8i3#aL(l^d^4EL>$Nk
z`_)fLejXm;b-yY~@^eKXWxgs(@^eL8ZG2Uf<mZY-y8Bg+f?s(T*Fjpw%8&2j*HkBn
zRKFCVBtH(3;Y8n_6iR-s2n5Bq>ZRo8io4);Ulk?!xnhj(N?H1a_mG#OfBa4SlF^83
zimzTu^5f91W9QEnngl;r1K9ejo+Lk41XaRUMM-|H2+Y-2MM-|ebh`1^`wzc~U$dPS
zf)u~{D#;%#?LW6e|J=s>({F$I;NRWo@>TTyZXfAWli+VNZ$2|s?yjC`wSLFpGJj<&
zXGalxdbjet29e~CMp)rfU-cMI^>el4>He<P&JV|1R%>Vfd20~-Q8juv@fO;*hx2cL
z2`$#|9e@6D{2ec$0Rs3nynTMwr>F?b;8#VV2!E~!nvk!G%H92QMUeJ>RTPcy&lM3p
z_Pz^c82rVTaWNIY^D^x3c^SCT{u-g~xPKbqiQoXM9tD3;4LG~Eni8V?SZ#MWs#$IK
zpB&Y!25J_*g(Iq#UwR4WLNkBw66Dw4!2tvBJ2+AD{x~?mdERP@bo{Xz5EySYK{9@-
z7Px0uwa~@;kJaP`t~U_B;sw4Tie*;De_<~$dx?}(@8I_SYX-N*SCuvX=;s$s`Bh<@
zAFe-9#r9W)3`YL(=WrBbuD|@mfBQ_|{HOl~y^ZLhA6|@MP!#+;Fh{)6TTKB-KUM=^
z`mLtaPd`>eio&<riod2cQ0#F2S^mX0;Fq!UcizC?vE%#Tbs7gZe!Na&HRM}(t9Abx
z-S1Xw^DkO!^RH-aBX^IgZ6)*hv6>ecoo|5UUwi}mf-Qe%xA{8^puNXm3~v8;5yxtv
zx_qmN`|`(Xe`)gWzslm>$T#s;Qv!+~tAW!|Z=jv8#{Tv<a3ivR=NtID&H-PZ8A^UU
zFadV^Rq>Vl!m04W&+CBR`+s4tRksTB{p#wM=ns6ke>OEJ{)(ge#(8brTK(t=`jw3=
zQ@`W|+m{zuqCfPI{>1|L68(xJ_;Ua`f7M8TX}Puvjrv}%ujpsT9>PMutG=RNaqeB7
z!v5EcbpMK9382}p?tY2>z?ZTA%;)egzrB)Qah_e4t-orV@k{=*LL-0o_7(ksD=hwU
zF?@-B=~i$4(;9!g3;l|@M+ee(XJ64Dc+dY*ll;Y|{iomlv#0+x<IXYv;~o9Ihp(~5
zMdH`X{>x$ie|OYh*YNwFPFVEuseL10q?G>Q|JC&T1WUcQ-T%+;>Xks;NUD{)7=jVt
zQ6Z$^gt#GcBM=cD^;;0jR7gfjYK9Si5lY#KaEnm<ID#v}iTKY*iYEnVv2GH=D=7$~
zBtp^Ug%}QJ&<7y-QL#o(Nor8!GXQ2hoET=Hy~7#mQ()<E+A7Sg8O~5sPz7AUs$$QH
zA}~EFmi`J1Kd1+S&@amI5YC`xkhz7jt;Wg%np>FK3Rj4Q5iD{>;Y4yJhF{dgGTJ0o
z4T+eO*cbpkAc0V}a7LU(L9N0W#0qkUaK@ul2G3hY4aejwQ!&zdUP<-Ks~aT03CHUt
zYb7Y+LP>Conc_(aS`ExCBi1s*<t>(Nj})N6yt)yXT4Rt;1V)w(9E^%6o;WoshU$ZD
z;|kCK;(=3=GjkfIpV2U2`UofQ<7wzbd#fB&L9c-D|46EEJE641$Q2r!bU8?tnSzF2
zRIfJUwZTpo3j9A+sLdKd2azNIl~(gpU|2_`6n#>Xd%-byE6DV4>YTrMIz{9|WM<|w
z&|PPwKRh<EK`Qmx_+yjQ5qSl!0G*rY58Xqjf^LGjxl=;-2_9JeA&~&6V`4LK>(p&#
zh+5z*EG?z229_f>gMu?vL2L$d0>>5`v3#e#)~NXYrzH7WcYUd+zW5L?0m$@X6SR7E
zbsKSh%xn;wA7%x_q+nICevS@0dPJsL#Ms0h<X%D6gV;ncoj|9G!Jty3#%4^}3A{Uk
z5l>V^X>3L#BS}JRezph)3gt0J(u6BOqX)~wDop4cOf`d^Zp2X*(dfaz2ny~E>PqAX
zSAvc)EqjifG;AID6k?Nirz2o0006t?T2@Nja7DGQnx0v2sHr36$BD&A_}-wFNS^Sd
z=+5doY8skpF|w*70xTAjk+<6PVjVR#KBHSoUfwE@>Pk37D6_?zfdIfjKff!<b-zLn
z0XxP=gyQX(5-zuiZYb?Kq6vcB3m@Ae3!rc52$TDW>W}CGBY-;6!d?kG1%0%(T3w~-
zmy-Rqg^u(4>|n`?ByYH-Tro=ts55_TEYKyFAQ#P27IS2jy^@JJgpyiQk8yNvz7Hxr
zwUp8rykH^5hu)y6)>L-`-JK+G>7X3@i135^(4mH*sTNbWBl7VI*e*D7V+}P7g|(Cw
zya>`lL=qi*iRBi)rQCX#_)t4o*RBXHAG~tLWA)y$ghoN-b|q-EgX=$J{$J6`G7=>t
z({C*0u<lTU3w#8<Voc-BBXK3wcN*$fQvFv3W~9FjF<5k@{*B^$x>Mh)#L+<8A<aQY
z8sLx{>q=_THnnTDtA{cP^j=C&i2|-5*9CI`^j>>pi1GhQtm>=><?O1`1@%6wgo%YR
z6hp?9WM?O`R`()*3nfwNV2}(YTI$HC8_Lhr5hoEs`S;4P`=n?=u(HHCfxZ*fe@BdS
zC{5Mp^!6z!`)@~_bRd1!E$7E2=8az1i<mHtdj@02T>r#UQjvsMH#+<)!9--em&Ou>
zd`A-CE8);8EIg*NMP5-Z8j*8!gp&tp;yZHm#+(`*)K=wNtAz#4rJQV6va*cbu9sp6
z^0#+n1-=42*RFQCqs%YVZkxs*Lu-jUy(7LprlC|bOoO#s=bX`I?a2LdCD;i;f*NA}
z=*SkFlA6b&!F)pG=-r^TCjVZus_ga#9VQm^4w}rEO*3yJi`YsG$F1Ztza`#J@sV}<
z8b?p$@oUi5?MNvcVkPh3vi(R<s%x&$Q=!u`cVzWyWr<IOP8*?qLa&X`^gyqTP^&Qf
zVz8K9=j}uX<>r;t_JAxoF<cEp$rb1M15u66)pBY&W%9h`{4fXY;|^BNV0zG}gSjHc
zR#T1<ZH>_}B7L1jiF^fouygj8Mg`SJ2J?=j#32Ur4l>Ux;V)K};4HX;8UYRA4g!x5
zdwE9`V~7={gFHIKUfzpeIz(RH5!DhPFYgBJC-(AgP<~=kxss&a3$d5?@lk(+Ms){X
zH^f}tks>HWJKm9OIEHC6tbEKdOtqlgl##b1F>oMfZwJLnDADiJ2Z}YbNY@<V9PgkI
z4RMZlU<^a7<9$$<fw86Ins&&Tu5PEK_91YOhLR{>Ne-vI1LSow)GFv`LY(6rX^BFd
zE?w8l_`shO-OiXyW4!TDh*HO@2=a;dfwP*}!>{CSsitp!Kz#`|)4{<X%8=d1&JtTG
zsAMFS_yb8!uDHZIzMe4FsL{AuE&XP$Mjhu&GKXJD^<5t{GUbNJ94_Xf6ky(<<Vf3F
zBHq+jDI1o340@!nrLI81nGED{*g09qNU{{R)O0F1Tk0(iXBbVr+Ndq|fhZS~G2p)=
znMIgP>f(S3C4ukIAvYqtO7%^OT)fYorP_0#wZdc=XA+RmRbfX$>!_Ud4@A|~fl~F7
zOnn{9SyzHq>KJD-i;HgSNfFzHRuo@(N5a`F!45N_6-~zRNArhuS>#CV5@aUt6DK?C
zY8r~ux>|<vwEBvl66GS0^$g~*Fxkpw?py&{npjw}mT5IzQT?QT&#psPiomBMbI_IG
znNXGekb|^?7dQIhGYcrfOqLzFkV3pa9pr4$=|O%vvMz<FfI2M85Dj`y+cUcCXXJyr
zl7({mMxuw>hWZqHP)9PWE8(!AK1Gz?C%nwjWgr7=pAt-Fsy;Cab=dXMxB3Uo*O8Zs
ztP#<rmM0Wnr`22;wn8LC9r-^mb|!oGq$n4rh>1EflZCj{JB~65xw&PWb#56OQ5}e$
z6d8Y0GfwYv&tp||dY3zLcZK-YJF?qd2@lyIC=3y*cO>u%1qb(RhW=&VG({ik9C&)7
z)7HkBHAJx9ai)zVNxG%#h`nuKw(ad2bYC|$UAj*k>>YW*qSJ0i{_?<4^S%Hu@qR@3
zLGA%vhWnaX!WIcnLUdW^3(1*74DB7+%tORW9gMqIf^7lrkLc~IRyl`7$==~c`AD+#
zQG+6C>Y(fmk+XL=Wl~a}&MV4^Zb$7x7q+8zOBagY=?ZeWwW<KJpJ>wA$X9kHwUdDL
z_X@B(WkU53CsYUJ??+Pof+`i2d#`L}(P)GNQ58)__$t-eXmCFrjK3jz_r9Pz1zGG!
z!X9m_C8*A}*;JnTZ<#GYb&3?e!)X{zA3Ge2A(r^Q!F?S~c6s?Hqsb}<y=ydD<r~*|
zO;$NLVXve%8YF#>M*no*Re|kxj8Hat(hEnMY=cM7CIfs!$2J(?#U>nLqrZacsLbmP
z4cg?i?#Rz}MSLz)Xd8I$$bYln(4TFn@8EuqCKG)_gEsoDI{+A0f{kjI0&TL;;aY#9
z!9*{5;QR?2FOAxy?!h%2O=kOs&TLBib4B${(c-Rag=lhM<Kp2;*coWVrWC;)w-?c5
zb8l!w5`A4kJ(ry+)#FDV?8<5Xq==1smaqYU`}a!lOb4h^&g#0_0jTnUBqOxN7S?y5
zWtr2vl%J#P`FKC_PFE(mCq+ZQxqrM8bmdgTvZnVzyXm0zQfYp+>{GAvoQqrRO75Kb
zk%#(T=4BbpdPCP?kv}OqIVov>BR`!V8Q|V)G_t>Ohj=Ay1zDx82pfWz9qC8Lb5iEI
z_{lmbbN$S(I)OTLq~cE14>Oo_T)TcGC}roQYwOxJCG~OpVBh4Ab|PnGb%Q0>l~JMl
z%n}=|=C1@d@*U){erRPo0lG4?eby_Lkqx3)$4zC<{=$3JX9ogYKeDpH3+qQNXkS=8
zosJUFzFr9%+gZZb?HePIO%0aUD`7jJ0Ci=3=%BK9^0f7$boC=M8<egNTB+`i0V$1c
z2T0+H*tTP#${fFht-pE57zbPHm2iaRL3Po;b)X@xq?#_5)-7|?0rayBZ7<iEhYW21
zIXq-)1MA@dQ#+9&9<reUCGpBG@jz6alc(AbIwwyxm`fdeR=t=?UHK=T4ls+0nXUuP
z;>t<UfoJg`iA)Ee#e>%Q=RqAKka-Rwx+_^I4^+a|09eWehO>^P1K~>Wp#zz6C2y_j
zAnocHpMorAuqJxE7BiqLSH!2*cX%ay>cD%OdMf635`EIazULv!8-MiBZcz0-<kbdw
zp9d`M=Sph!WNJs&sDI^RC!^mj*HV#J8xWL_<U#TNUjFLXXinBJC<Z-b42Nfl4+M+r
z1xHn}CQHuhfDQ{es{=|bWK9=B<qGJHMQ)Uj2&H`aE@L^D`YrRBP;oAAbs|chD?urH
zAr#b=RKx&n-uiM~Sv5L7ZYTfoM}+VHiZC14Bi!YlMs^u@eSf*txC@rifmCs)aSWu&
z6`*lIRoqF8+yPZ_f9>T0thhi`9Vv3$X$k|5;!5$+PnGyk;B#Cksw*0(!l$MtbXma%
zn$TqiBbSf+qND#n5xVSP<Y08*sctztFDn@M6?a;~PX~a-U8eA1T!-A#(53D)k3X8$
z1+nU-iJuhV&$UEdzG-OmE8&P4P9pockS^|GBkjPtxS(2>aj8Zq^BG2nD}_mio#OsF
ztUrc~yG-E&#pkkxVf(nl6h<mYcd6jSvpgliWJAj-{G|iZ;x30Z5=ObpVST)GpgSDa
z34C#ZusV=0?zEnfPSRce>TI>?;tq^&?y{zlUeblz>VT>EmKhA7iUWD|lxU^kt(0Ba
z@>au&_6=*<V0-(fx7u3W0J<Po1_R!eh{a&#`=-14O76Q?YL+X=(~0k3Q&3==Cia!o
zpaP{DkgMUI<8kU41H$Es@JuK;0kjNQ72jJu8C7c4Q8-<FZ&iWz+8d>udvO{Xj(WbA
z#t+rCmCyW&4ysK|BvjX4YP(d|UTS$_W*16j*6yjMq1y<<GC*K_)8@9evcyIgdOz=q
zFdVU6Ff7B_-S<$hHaaoXt&P_^$dqfy9_LCPb0yUiW7j+j>{h)I-=?m49RXa)Wv-}t
z%g@x{`tVIl*~&ZOyQ^X6%Ia)6u(G;Zhi=?mtwTQwrDchF@$w`*5Y#JdeD1**nx1>G
zRLU~8id?@%_7<t;e9`Q+4u!a2_8O?jT^KCu(1)w6UQ57=FF}|Mh!tOSK^qV&zUYF!
zlI;EpwG4H*g6<0|T+5ZPX`K94py@Jne9;AMa0I&Y<U9sX;T5rQ!yxH{Hjushay<wd
zknk-_-{_qyTDb-Xsw;Pn!O40htW&+w_YJ4)mDJss^_eB?GQh3)TIw3q+gfTD>TNBx
zi*&Uv%$C7v?8?bwa4cU5Mg;Y?mResm;gh<|;K9BkwvMCU;=$TF^w}Ef^F|K`ods5a
z6<<RgghpFK9fU?(gB^rIgCqH4X&JJodV;bnQ7^7cKet@-ZR#8J*)p{oSprhgkigZK
zu~8^EA+oNdMq?;dh-p`=IMS`IR&jt^U1NhvTr|54d1`&NuUa|nF2t2t9nlmdaRt>E
zx}XggP9F(M8Mt~h@wl>bf~(A++LUp~aL?tFPH4kjn1e3oDN#L`?Ut3{s*s}*9?Jlg
z@fmCv`6#c14d<j^0o%oCZibqvSLuRjS=~f_wp4Ke7_xKtbUkQfZ(Z{SwI~qQl~j+#
zm2XHZ>vL-mP>XYO5TzC8R@2am6DIhRq8bEEaKjC*&#l&>8kIT8^07+|FKGU`*m7xR
zpG!?ceFF7m$W?pGY`4yjb4hIgOXG8?-HjnmwY_VMRO7f#cLKwn6x9$Xn)duR9|?6j
zrN{xANlD{x%GV=KNJHLmpMwvr-VY52p3pfojZmhA340)_#Z33K0Y-BrY&^B;G_{P=
z<}|bn9puy0c0IE8h|1#bv;Px|)h~VS18Q`p275|!YtSow%he?9=qsrONjusAk8x#;
zdJH%cXYMB}q=`?ur48s9A9PC_&@n!a8b_Fe3m<kxfog2M>>Ovps4K{M97k>CL2}4f
zZGhysAY%sBavw6J2bAQfQGe8*l1E(%{aW_JHI>kR%qL|4!?=K42Hes|f>O@okf-{J
zaw5mpaH0E@hU!Z0L=LIy0o4ca%2T2WxZn6ee#1k?_ebtShBt69E<l$J1Sa^9(G2jJ
z4}NXP4(vllGv>mF3};N(<Ab>AE83{WS%K;sGfVdY`W^wkyOP`LlaiX|p=P1>#!$0R
zeM9DWp=GWBuyzAn#s%rJ0o6BXdjlHdL-uz<V|>W^9soS}koAql>w<I{mb?!c+p}Q|
zw6$mH#^*}#=t{@tf@~R5t+}#p*@S`|bW9u4WB6$F78vp^JBhn3H-lTmm;jt{pt=mG
znOkPd9r}JWHH{<Ukd0n@j+-oWq^fhHJ_mBfO(+oqbjFeK%K)6YWwu?f=StXgZK@7p
z)Vn6I^SaPsmRqwcOPFEvc9V&Y9o`Kl`a~K~w@^!^Lj?viU}xN9k58yjB^EQJ2YjxG
zO+km6qp6ku<_PQH>coo~;5A;5&Ih7g;<nW=bg1%^St(#Q8TlZ9bt@zPu?Y<-*x8j-
z&t#!b&l2_;z+zn4%WU$zX|&E~X+M+UjWp9PIGDjEa+`WElwVmT4@C76Cm)>3&!%QS
zuvlci&p`L-$Nr45e!zy|eI<pO!Ir!NKDAV2V#F+wEpEm$50EWag3SuZmX9P$rPPdm
zY=a@~LTy<klYUZ!Eu!Kf+`1kLoo4lCocfHeY(oanE1}b7LB|QkWtleAt*K!+LM`oW
z98J6*Jrw6eqPT3$Td054YZvUwkS^ML=*PFUE(>{0?1Wu5GLB;2Lj#9;>#~}0q;uh}
ztWJH;OZs9s8D0t6#>uYBt_C^Vm9TN>yzaarwY9T|j~jp%@3feKXYnqRx$rEmWN@~q
z76sL^1+~~^G1o!-3OFLD#V(_HQ7v{F%?nzwO9d}zML@M|)f3n(^kRQ4W~93IE{hq+
z7w@u|7ZjtAT2@$?E6ALbCCSCuVKT!Pa?5NSin33Q8Jbf0>>f+6iwo^#0KQxawwm3t
zwCdmJye#Hj3;A(DyR2MD-en$ds6?f}Gh{|~5K<W+Ew@as4}4WlD3>M3<rdit6rytG
z89**qf{Q~#=H@G6(@=>W#&#iLT=*^n62_Tn&k6|hq=aolA@-)W4P%r=4hN!lS>zSG
z`J@ON(Z&%`tT+ZBiwovu1!VCiOBz6y$J<e-q2L;gYq(LpN!RX`C2TA3!(IvZD)?%z
zhz&uXHF>s?-up_>PPvgBx&NLL)tIUVv{{p9d)Ilexdw>SpK=3UNgXHz{xV`+nk;OB
zU4+^)fL+@Ds#NaMCWrTil4~2KTxCsGHr)CyfR@4a@8w>8APQ7tOZ5Xb0_SO4DAmNu
zO0RJ6Cq>TRkRFT8mc~<NLnA(>O_ZwVx^XgMU7DQP2!?l|tqiH{y~&sD9W5KeH?AaG
zmObrId`%WL(oA0oCIGihPQ2BVqUxgj*@c;DvapGnX|%8jnQ8K7^CHZfbTuI}O-46h
zGfg%(Au)~SG!ZeCd9kKzX0iS}(R*3bc^!Dm?0RjzTWJ}s@+LneYW&e%`dj&@3}g@c
zz;rG$h<#)^0}Qjzk%|BsW*@n?k^Fg!8_$4`xe~U$v&420kZ?r{g8Qa!nJw3Mb0wU$
z4YD<v(sfb1kB}i(QbUv}ja(o5$W}(S;!QA^`Tes@;JOQcQpD~CdIwK;-Kl38TLSLg
zH;HepF6MVd^FNSeB9S9!H;^y;$k`1dl&$PHR%9tD;eA#DWUhd1AG~`S(*PRmBUg8{
zPl-@#i^dU3gGa*%Wo`r1vX7K6KrLJFFU!og`zU?1A<^wVa&sfC?LIV~qvH)pBLfQa
zk)U)f%B>`r1{lnhuy2OhmY=(*gRg+?B2no++5?a;^dmv3CRU#9OwhTH{MyK)xlez`
zH!vD~?ZDMs!ar7<q5#Au5i3jV#^UVDs||LRj|8Ppg^-O6h|nfD>k6_LA!PLx<*bIB
z+EJQqD_iH4SUs4{*7E&GP|9I$!M6;6nkzxeb=2D-lRZ33Y_t^Oj$r(Z0YS3`=ra6k
zhwSW17P>>~Gy**<OZzF&Lap~X)jK(`BhWpX<57QRUk_$Jq?0i_SAyLEGq^*xIIuQ5
zWQ^CFcy`Db2ij%_ZE;|2w(wmBtj!MC;y~KmGOfyl+FSuz2C!y_Y;OQ-wlH6r<uzBw
z>#sf?gM#s0xWyfESp(X*1?DoqA9u)QeUQt2hiq+NYj(iiPGrpvd8~n~*&+KI$eJCm
z#~RR@9r9RXC)gpAyf%v+vdFQY>@avC0Ik^}mo=a@oA5ED-c12EnlrP%Fs%;`n_F-(
z!+yAf#&vC}mspcMgFXzI&A{dEQ1G$=H?yPZ!O(|6NA}rSV8_b-+b%D5p=O>Gv1uqo
z!Nv?wn(eZ^p~be#^gf8QzalhU;KuE8Y?mV3F7*xI^p#)_LJ1xX<Z0f5jTwM49|=mJ
zGiAS^`;>Ug%6fQ8gaJbNxm?|_Lp~Cea;AN&S2Yz^!ehdL?sFRAqqQv62Y)kJ*DP+7
zY6j`l9%+(2DXCc=fXi%Q!3G$|w@=lAmLrO56qm~_!*MWRoo=VgdccDHNKnc-qt|-C
z2EGzJb8yOrdIFW^L*s*5b9${u20z>~n}u3)p{oZFGTV(!O{@`9OS1-KYG`7O2wgoI
zbfKVKqunZ<4_)YN*FzUNTc2d*R)21BEdHSS+TSN)rs=M}lIncZ%z-rRiqLeaKEb#K
zkTu)eKk*0E^`@qw`@GTe9l+IWZ)*Fa{q|A2wQ#qPU;`+cD_JO~#=Zi!lc&P1lmY`F
znk!)|W$<nx!A2c$_ZE6&;1IlbXoyglJJ2?i;|{fSs)Uz8?YLddKs#>NfJ!^|rUc}p
z;=59W;w7_eM}exNkT)f(_W|HdO0X6Hy-5+47_c`f;%Aijo0On=I51L#`Re8K{D`z9
zdS}1e`>4*2^G4!|s`Gloy`%2}%MSo*QdD@+QJ$d^vGbN46*_*vzmy_2R~j!x{1!X1
zFE*KB1J0`yVg6D<rhwB|8Zt%bQ>n<5unVJx7g_@FwS7dc)+Sy=q3a*W&?(o%EOv_5
z38MftDZz39pe9AQt{H&Tq-;S@uS+J^=o>{0uJmK3_&}uU01hW*Y;D(+)8rb6mrc=v
zAXq8qq#lH^;ruiZh?^4jz%jI`!Ipz4MXMg<90!s01Fr3lXsAztcR*~=fP*|mxW^d4
z)T9iZI(#idojROdQ?Cvu*WQ<R*i#;$1|0Y)LNBaU5k0rYDK}i|UlC@U7S+H-!AC?l
z=fGV;il7|}rjrt==>ZT<%4&Q7;iLqgHb6BWQByCC-4gxUKoEV&8h<uflMgfYtD%^E
z!ddw#QN0IQSi=ThgG{U|s-C+(bpUcw#LXokIVoZL18dP)r&gkDtbr@36oKYq;Nq%e
znDbdn(L?P|ykHL$>*YF~n$NJsf#Ck*N>-IQXNw(l^?9+Aj$+!9pE8eJ1Av+o;lUgI
z+v@SgI(^MB!(lUJ?7-$QwmPsm6rR0?`7JKBj|h&Gp#zTf@LFsjtw|Ak;8+j7)B$XG
zDZ@?#+K-QDs%EgCyv!JeBKvsMDVcM2*elv|MqMhz{S~28b;KH0DkcSLi_4V9tTCug
zh14H|>eT5<9Ro39C2RcIDgk;h8V6TLtt-GQ;8AOgUPanPqvNA=Q}dmp)y6QWHeX{7
z@P-oA`EZQVo8Ht#>dn`B8`PUL-v*VYD-Lc9YE8$XYYb>j=fP_L?U5Os*iG=Ox3c2+
zsN5{}Q4f$>xzVy4RHQ=mk3mJc4-QTPj6#(`3SF2v-q*GRq9;Xcjp}y?519kVn~zM!
z*`Olbyu27=R}q`npd#I_?Gr>!DZ@OK9^I}!Qjcy&5k1`6U<S45-fEj_RM~09fErZ@
zzyRDQMbI<A`=ki_z@W0tK!7o*X%z`DGU=4U07e0Po|3Vt;LFw*Kd5?z>mR^-rHBu!
z_m?6LgsNBg{xPU}_tfL5dAAOI16b87yXAS+t`cgDNwvEPKNyp0ck9?Usdg(m{ecYY
zRwus+y{qtn0r<}qWwCS7nzZ1gW@hxjnAFS)As7k&NdX2AyibbY`5Uw9)IT{aUanjb
zhQ&j{gi79B0|5PG$~Xk7<Sl!DQYCNM`;#h}5d&9J@33hQ)X2MO7}UyJro^OH-Z~`^
z<&!e@0a{tX1p_#r6rl?fD`Xw@VPbzre8HHdmKQDkNv*87fGes_A~0Y~Xxt?R^D9E*
zvg_w&>)J3THSTgfoErDS3+ho`C2amc^Q4ILL4~_?I+#?rOFWMQERrc>2ON`&7=lbZ
zo2z(jH5eG(mcp6A(dmc)sCK5<V?}CQ#sG|ov+0`J+9$Q?V$9uG)TXQar(;o<E*bW#
zu?LfT`)ZtDf{n(aGF7m^6=8nqX&qH*=zz4SP8B|IMVL+=2Nn;nOUHqQ!|PIT-dH@n
zE@}KlHLS3KE5eJBVZW$hp-dN*sbK#DWU?t@H>pk)3NRMcX`-C?tm>z}=|ydd$559p
zf|srcub?reZY(O(rQ^XWWxAT0pB$P#=tX6kF$9%)BzriITEjth>L9RqkexaRES_WM
z(I&j8ffYG0*2ZA){;6$e=-H)i87T0iq<XDbfw8D_XJ{Z)xr!eciz>Hn0>*;Aovxu#
z-%cI`7S*jH4923mo&FAuI#*!^W8pb$Jg{!3qgd-h0S03s7CB{TohM`k8H|M!^3-Vo
zbk-?i+lPDbl$B7d*eT&kqMBB$!B|w&j5Qd$Rf$KpO&vUS3fR=aiX<4DI#{6uV^alV
zS1(bGg}{lise%zrFgBI&)Nx`{2hXWJZ&M2^@?h-J!U{aN0=ze#F?Q!$d-s>klkn8h
zU_<pPXkcs}h7~t3HZ|`AA^X^M$el9#H&yDC*}th$XV<f-QfGfV#e*)w4912+opJ_m
zD%7b1#8$@C_W)4=nIBP87Z#@z#|3cfr+^PHy^BbL&!@AYRFU>@Y--dY1AkMaGH77z
zt1CxnpgNomY47c5dl1NUMXLmSFg4`}J(x#Rg%*rW<vHZA-Bh1LAN+>;96A$hfT~i4
z#|M_lkj=mA$@R~g(Xsh+D$OBc$>G$R87?sD(Df<FLU*c6#S9Fm${e+qJ|(L)JY={#
zb>@)a?x=+?->EXkLJ`)#LJx*hg$~*EP8~XA*E@8mq7MeoxmSiV-k*$iuOsV_$?jCB
ziZ2*Wg*sl7-A9!<rolnTUU%x)F;K)9Ol^<4QAk;R^A7#0h=bwOuL?RCP93YDgW*#n
zm2=;zV~3%bPnH$$)US*}7|!GC=tL(Br^;1i!f<NcA#2~Eb%*Q%r`E0Dga<OL4_fwc
z2Bm}prqUfU?Li2UBDx5?G_T?hhEwq>0%156FGCQ9Q}5b&M@YqsAcQN(!6*n}I5n@L
z5QbCr+Ux&!>Ryxo->G_yrvi^EVNY>tUc@0h!>N2t&VT3eSFs5LIg?Vv83+#7b${bj
zzY0(o&XcXl<ahd%6<;u-RguPaP_rt&U<5TQ0t~L8K1$PVKtPF_z*JXM@7$IeqaHO~
z2n6-0LK8+%jT#8;2KZxAf~gAXQN|~XpdK|{2}Bkrxgti;=WI~yK|O0aHUv+qChI?V
zQmuf42eMTXY)e7CYUArscu_nO1XZZL2Y{HIUhNn$*-sq+LixjW9T3o>rr_ZL6iUj_
zBE8C{gF{f)8jBcRmxm!r)tXKcxYbD!9!#&Y!W%~LU}~@DAGc8@!*n{^m*+pIaWjZv
zL}^>bFgz)#+3m9T!7P;`&Ir|Qm*YREZu{%_59r&j6F~5^+F7aATbJiQ=ut+(fv03O
zUWG@Dz)#pZ{l`5}te4oO`-9$NMm<~!1|ehrKvQ?w^@p0e%eFs_{`&4HqsKDt54ALd
zA;#%dVnbBYeM<!%`iZ+N`$I*oXozvBs1*+}4it68L-1L(J{b@(4$r!Zh!}@1=dPQ8
zLyg{r#2Tkmde;fyP^Bv}VgRA|5$ObQsKUunP%;b=`@(^KR-D5))X!a}{Goo%JKF~$
zbY1rahw2$25aX1B?z$~FRM36sC~>HwyRHikHFVdR;7~&=RAL-x=(@^&Ai`R~eZg6L
zSGq4a3j-D|<WObTU3xu<I$I$V<52f@S^S5}SK$uhK-E@o!vhg|r8|Q|UE6U8I8?M<
zhk!#x+Z&w~d<xs5rfs?~I8?QYk{F3<P5~f!<51H!*awGtR#6h;P|Y$-VjTLSk-+CE
zS&mkr6IW8*Y&v)x9&#JK3^zR~x+%2uY&^p%{9!ie+QvJB*{Et205Ka?ZF9`iEJo6l
z)Kpywy5%UMOIvMG%>rxll&oHXA}MA=k&V-r+;AM3jjm+IQ9LQb&^CTjtFkS%jx(=<
zD`w*XxAExl%tno^V2aszd~H)*oa__N4OfIt2?I78Rd3^cz-&~#88<N-)NUK<Cbe!G
z?<7(0Hl8nLquy;pJ)rJwLtQV`OQxlgU||jvu`Ep;pmuIJV9ZACj9Gn3R`1``JWt2X
zG+6qZ6>~8`g!~Z+FEks~Is-4RWL231p~_ZJ#TB9JIxNgao!xjdFdKC?gD+--#%@iM
zNsZma={FnIwt_HbquOpwouJlMXvS>kw}Y^ZoT#!3t_aPSoB9gad@1&WsEi4O)lpc+
zY`B{|hi8eITh>Q_Bf>4;F&qV5OvH5^#9Yi?|K?ovj*juhV1h#YD41dbMs<$sp&fnm
zLcz>}P#uL^OdzPvadoxc{y985OlXF4cyxFs)W=a^#sstaQC!9>`t_77lmm6x_;|9&
zmIubjdxHs$d(KjoiQd8XpQ*Rc(Vf9WoZ~rD9Vv}^CD;*wn7R_|TL4U5NnLba$v`dk
zW?_DLUoc_0TnVRP)dUZML?#TS!x)Q+$kL-2i<!`<b4-uj7=k|YjvL`CVkO6fSLyz|
zYkYw=yT%u2v}=5kjnaglNU!jbpj30#)P=yDF_vO>czMrhYWUPTZ)*2oq4NwdVaA^f
zr<gGGPlzRGehvaBXzNd$6i(38pEyn&q4_3wg-+0Bp9YWP38~mRz8rz_u3(@RpHmZf
zCFm@ULC*<#@h8qoA4!((zw}K40CfTu{RH~yfS2^H2cVyh0xTxLPe&0Jv+z$RT#Xt=
z$dB@wfI1z9Q%nGzjzTJC!kmucDJD=(SHgzCigkqUn>MqAZ{H?Hv^2(vAuYB$(S5}@
zUQza6pRG;wf2o<$k|&m$S{TsOc8o*+iOIHBj%aFx3nMD)eZsqNVyb1pqE1XTUHi*X
z$i*yF)QO=%Zmf;LhBpQ&PyGbH!wFL@&)(4@pWuf$3YD1f(Hw+IOyniHWp*XdGVSaM
zkkg5-=hmV=(e>Qmd+c~{{h5;hwHDIH06e9n@i({g$^~@=`N2n-<a0Dkn?7!!kB;(*
z&(X7lFSUGyPl{LtT8jY>vs{x$8N(;sm&f(x0-JOtz}H-nRV_ZZu#v}u&xJm6dgQMp
zXN`%&pA^*qWMPkyCAM7V+HvPo%cMI>Ej~w`08fJOX5xhovxHBu0UcrHCh$WiBOE56
zLq`z~&xG6jD8ymHuYP=KUZIG5Y4}h?g3INDa$=X7UYOYG+Qy_#4IPTgr&`{1<UYzF
zJ`;U(1h<<&7M%=}n7E)gE(5tPF^<c9Hi0QRij$bQ{5Xn=m`J#H6c;f^pt}R5JT4#M
z=dLKfMn*|o!O9|Afqqkv#Kcw5anl)KK*_nRVjzx=&~vlyla6;a4IPJAiYFzt__|t$
z*7L5`q4|__e9o37e4!K8?O~k61c>Mg@KkVk9i=6oxK}$0m6*l*b?OG_fh7B@*ocX&
zl4sNGMdHb$Y~&N!DGwlZ&zx0YE6{w3l$d}J9Yso9NiN$RY8P4T4zrTaf*Bp5>n5&2
z4+1475JqQ*nua3WK_AKl!07By+XEw%u10##BZS_Z6aDjds-W98P2X8mbXV}!st(HV
z#WnQVn^OhNwq^N(7w>HD6p1W4Tb3`7MQ1NHyl|@6OHJ1w&t7U8stxJNXMvB7V0IJN
z_E!Sm0Iv40gl+E{;#AX)0m-BWci{o%?kQ1qMz%2ELPu!1S!kgvz;*(x(3NBdpA^-b
zqP+|XprhpEH2~Sh^Pn%LW<UUYwyB}iZrd~u2lH!erTjxj`N^-O22^J0g8JJ;&R<E6
zhOY7n_{(AX@(GB{AwcdkJV1lamKH5!&=II@0vB{Po#YeHpN|BkG#b`XPoVvl%w~{`
z9%Uz=KongG_KG4atp~B`ktH^Z1KBz#<p;fFWdl)k3KQ~_BuBSoWfz|4EE(AV3!N1x
z<%b|7+$7D=74aFRqppMxSy^JQp)-}z{7R~?@28B6;b(2N1f{uXL9bGoO9u3U%3Na9
zoIng6Wi_7*dUMHy28`$|nbC<NI!i|M+8iXUXh4Y0T524sRjJM=07OS9x>*pSv&0cJ
z0T?=Ksx7Zk(T2uUA0<Pdpd&tj)ZKEfFWJX{H=ZQ}85!#jQ=LzsfX<@(dm`)ob43e+
z?CenQp*Yvj%t3Lkp{AiY-(=?#>;4EfH$UISSu(Qm-JAs@8(-F0^m$)N4v;SIE7+)l
zuYW^HE*a4qN^<e*-nS2OYtIc8xSBcw6^JC|6Nua+1l$DL=PaP$pIKm^vzj^r1vu%`
zo`CwCc{F~gKqV=k8_`NfkhqC$_)MDK05+d_)Yj+hH$&~<>^I{bBMyJU$IT68r%dG&
zfSw~*+e~eA%h{7B1v%YQPHQN&D?#U=+mx7m0&sp3z&1Bxu+NmodPBF(t<FKWO}VRg
z>9#3{^{(yUIm}-^H?*CgYgbYu+9>7MJ>{%Uh|n$5#)VCBl=FN74s@m*)gTKxQ|30v
zg3i?S)CBbBOc~rTr>=w#g8rLwTf;2-NKm?qUFppy0woS{XcHl^XUZf;#KoENS0gOr
zIa5}8p@`0ukq!{i$t36#_@N^p+XQ;(q>=YPQsa}E?p1@W;<%{X=@SO@5v*-Gpe$#~
zB1a;ME2$BBofnlE{R*n9vbP-?bG{C0hsvDtPdg5blQ#M1JaVS&ahz9<lA})_T&6O}
zffKqCHVv&g<(4j#&>6DO0TOzy2ra`CswC<YL_`OmxCwaB8M4w7A#{f5f+o&-XUIs;
zW@(M%@OT7}n>b*e0dpK#S<Z;}0kvN#Y5D}-CncDDsLUZxwezSs91l*7IpnAY_~#5c
zs)7AELd8vBf6frBed3^ghV1n^%by{09cggRfS($Pa*lGSKeOWU4k32a^K6M+=o3Jl
zBTU?cH{%R?smtB*d3#gcfbLVG^9jGn5#DVA$8#loFajd4sGb}x|Be{|hUW~qsH0&K
z$ShBP&Kd8CJaA?lw7B6EIzt}n3IshvCOBw04zX^ZO&yt_j#8UnNi7zZauVgGhU4rE
zd8x@na+tJyR)p;l>TFgR?v<cab0#-6@>`wJ-tj@t4Y{dfW{Isr&kb4NK;e8ODAfjI
zGPuhjc}(^;oR-J*H6qaYD1G@vEcA1T6q~X0@2mj@XR?*ysJ#;Q3_8xl;WOdyJr*cs
z&-C?yfae%}((oZ4lYJdXXnsrvHefl&WMn5Y=P1MZ1TN<YV>W@oIkvgI1A=o*7Igt|
zu7C~U1gN~|6A+vOh}lyjuUc#>Feq8n0ljE6s1e(Lln4EpnH=v3Nj8x_@0h&O0ZnM~
zN&}N~O!o9a?$%?ps0*ZXlnQ;~{^I~_HgQ36%V-+6C|AP07*{P<gtpJEB9j|eHHR6~
zC*V29WO5fe=SdNNvQdW(cZ^3CHm;P8>Ek}7ElpAC6VzQ-#HOGw4MsNZs*X~m&oioo
zDZ#DwF*&w@y*VbwHnLD2lVcm1Dv!ahUGSV^%DOrM&pCvrO@MQb$+Zn^&atMZC&p6_
zw5LQHKjLF*K-wn&o;h7sc423ZU}*CI@N~L7-ayWrPP04jLyxkXPu!TEE}I&+s#ijX
zH|}1qh|h&)>-2b^`c$ug<A!EKg7c?DH3k{yr*vDF(;J+Ar_&S%?cY%f^k?QR^+~kZ
zEX>PcCi4lz%jvS80eJaHP|AtzvX>X`<4>oHd*Ral2ne=tvwu1*=#>PFw+!FPLR#IA
z2!F0wq=)-TY7%L3uLe!m`RT4!kx-{kH4I;9pD0!Dhn`v`uSQGBWoq)(0QEe=ZLK!Y
zps_+JxNhnI6kIoT07|aQPrU#)Im}I-lIj=j;?+J%u6H#ICD%I}2J+?fuBM^(dRNo%
ze=1-3Dh$jK=4%1l@|@oIWH>i_(}VK>sD$PVsGcKm*J?XUu)G(rLZ=<|AF8k&wgOGq
zj#_~t1d8ifm9_hp)k^IZ?Wp%qhV5wDaM)|1rjfet2*R}z@^Z_2@+Z0STA9TQaF^3U
zO+z_0d8rq`E~kasF74QOmR`WRoaSmdFi0nz^FrT`QkyS~?+EX;a!yX$dJI%wqZ#}x
zAmpxS;V0E&+QAD*yF+Z(0<5LcZM{0+zo*e}y$Eb+bX#9ZzWqkG^#Ui*X=PEbUcU#D
zcoF>47TYbS%oVWVp5vQp6(>NYF@F}2i$}n)MTANl>Ke3Iqsw}IzU0$}YEX+cLcOo3
z7Up2*pt6*deAVu7gxXrfwKUTfNMK7dwKZ#UO)WubHDgN?QwuHoq^O2u_(2V)tL2p?
z4i2Ze*3||s@sH44ivSj;C{IaEzdq<fu(bA7r<PZvnYzI4^ATmqe~WX}tFkIX>B$%H
z&LP~@>WFr{BDPw}>`K^fDzhuVwg`^-z*Fl>ixWhfEI?&~(5wZd%oVWZ`%%XUHCrAs
z><&c1grHdq5SKWvejRj!=JT?KuF!nGlH3{M&_jJi)fafER~jdAXineq&WWQvy<pJ<
zISNZu{iTC?!8D4q)p%M@ah95{B@t!f+@%F{Oq`|GJH{y`4RA~du(hm8Y}oh`Cr4x$
zfi!TLohhkbjOyA{UkAD-`s#&Xj1UlOAw$HKV3R=#i7Tn+&ips~iF7|##LiBv!J(E*
zL584O3pRfoQ^Ps3CyuG%iI;C^c;VHX8edq1rnVQ}yfLa~A!kRNuEsY$o300KbQ#9*
z%Cp#~48oQtCDogz{yF;7&_73SX!$NcUE(x8Hu(qQ&`Z4lb%{9YT&b*xqnRnS7Rp+_
zD(}jZBJ3?V>Rt&OuMaQcu<`mbuYj%R#~Y#SPYdx`q1@&R$z(!^uq&w^O5FnTawXg!
zMh^K(&_VbOt^^%~U*SrsgP`dN;<ug@<>Cv^AKYKlZ@rN2CxU+Kg_J-MTdiLG7R3qt
zKu{CTbMuu{=XaJ$CqyhYV>ObcRuDZDN@~7<nu*XCjR?pH*~|dNgiu(k7<itDslE*K
zg+A#8AJs>KQuakgG+bN}45(OegGCHAGcm10otv1|p@!?JY!qzHkvYs4kTfC0)&i0y
zg624YG!e4L3r7=SM7J$KXF{pZ7oamC7}tV(F+#?5<p4{G9^_eM*P#Rj(z=rBZ`WfT
z{cRcnNGl^~evi_DA?q8S*a)d>cxxkMe-Eg^5TWM({M-Nd+(p|yRX;y-Tc5fgrPVy<
z_?(6Qr+@p~|Mgq{t$qHh|NVFW@<h{Hy#N0%zkw<}m^Zm2>qRVOyoZ}722xN@%ug8g
zd|&lpL{lbfx8Iz5T(9rW<INYGsRH&_>d@MYG8t;NYRC!podOHVRZO`%YT-GI(+4c^
zt1<zQLm6DGq1aiRHpr@YMaD26mpL>BqqGGC7`VnxIsiu9G6v+0XAXwgzIksZ54J~f
zAsvWD!Etf}IsRt=4<Q*g0)3816(*?X&X6;b9-sH<%0rG0naH{HglMO070vbeH0EdZ
z%yF#m&p*8NPy0VEB24zzB4QSHEg~iU)*_<M;cFSuetwq`eIK=qlu;e)$jRi6Wwhu8
zdzX>Y#%LM&f3}R2NQ3LBePw9?+pEl^?{$P=Cat3*s)TnPy|K3MI?@V!*OA!1-gTrX
zukUpPcP*CDS1<{ekx-Sjie89Mt)v%s^0kuwY!!8R3E>I)i*vF`l@I6%2T;9M(C4W4
zSwf$M)A!wgKL1#=ci(^A3IauCIE?(Lf7eF_O3M&mHn!xC;Hgq>xx$EIOAnGYMtW4j
z=}wRO9Kz{L57=-aI>(~z3~@Pv*)tME3f9jMjU$*r10;@jO_wSWiQ`ATh3Ffh{zBZ1
z(2n7>{{eh{LWGL|M_)lL$OKg1VksW**N4*!4vPD5lBvYX0{XMi1v=5NH-|_WVPJ$4
zl^qLuOhk<ZFb|P50)if-Xaq<-M9>Hf`xR7|>X;g0XG~7p5HlmVaf6W2C~rxKZ?TNN
zCncy-x>aCMK>tHTib$UjPM<c|e6Ik&aWMV{c(o%>mtxh9z)aH$fCU@k)TWgi&W!<v
zaEO+%Oyv+KBaG<)BO|Qsc=;F+ZxK$#h6EQOHpbIZi&ulEwvzxD6i10Cga^fWLwdh-
zb!=MW2uum#JQ2GRFNY#heOyWH-^c|L8=KLof1`V4i-qX151geTeCIKAnwQR}Y`hQy
z<H>~(o0k14J25r`DRB}EkuTz~7{Z4l7eWXhid+aG=EcK<rof&D=gg!}tb=iEn&bzE
zM?p9bPLF$m3<sy{5P%a}<s+!VO4V7L*Ox9ucNX3hKV(E-g}4(B&Xi(KgtOraYO%l{
zaRs$RPu&2<=C=!%#uenJ2CqkmH4*V=v1!{QMC}T&Ml*;lHoxA3(<GS?k$5P?gLtCW
zT-lZ7^0{l2)(TQ21t|^@trwe@Pl)J?T_0)&`~{ev?z|sNCBIbUatd)D9vmmdeArt<
zC;6pbiRDzumTAylyFS(qzuPU>$8{z3Y4B^klKM8}LhrXHiyv%92CM*+VMmgzSVs>n
zHMVG}H>8A(#bb6a$78He=b^Vmf7s!^46q;e2HmxSC)W-)=oO)*kp(sa^|f4mhyD^Z
zVsD`72~i_<1lz{q$9yF@Ab!og(w(IQ4cB^&r8KNpl#5_(wO%UgN?<j%)QyWD^eu1H
z0l=*zom+?ku_HqHBS9(qw$xcDx3$#UU9U1oka#84H->a{xaL0+lvbXs*iW26*QA%Z
z;{xF8_|>)!WNa8}aPfQZ8AzUjURMqs(dHi!{$6uG)O6{|H8e+1lwwWnEjT`Y@*Pq0
zu}nXLW?QD;lxkb1&XsO^u87kD{f53km5ChjbAG5&y_w$duIdwcN;FUftt2l&h!nAd
zx*!(+TGL7x3XUjGig0Lw&vi95TuSjh#UPPn055vWH4f?NE2_2Dc%X(>6kxRXPf1|W
zj%&o2`0zVIF0KGC97Gc#<Y%u81~K)aBY{B(_t}xa;E745v@6QK&G>q9c5d=h?=uVR
zX)UOjB0adG{7eKM?YM}&5;hH=>(r;-OKAd5`jjNs8}Xza%pf5=X$O5sB%ZV*@oET8
zdL?&b)*<Q&@+}KI+CN9xAa1ndzB_~)?VwHhNUBfei=F!DLC+F`iGEHr=;hMFgJPVz
z=Dwop>cS81L-o~ncw&Vs?Krl^)JNYj;UQdU2WlXMEA0g=2*FA_um_Q_(q7<%PifFs
z+JRsQ0!urRCxn2dy{8gQfM^GfA_Ne<l00k2gi`NT?$@c$9dL{gBJ@hCBQ(mpK|fBh
z7Ib7<4kALk^(>%UU^0ryLv%+j=MZGH8$AkBy8v)1F}s?E6P5tc4g^dHB-)FhDW=#9
zI$RVXjA%EgydfW$!Rsn8XD=L30J`~<B&U1u>be6<6hw4(gMJ&K?m)i*(b+45_mcv)
z1O+$9P1cdcAO!pDcSwSKc7y&K^etRTjYt|Bz^nk`^Op0omM^6jmMaALd^!+d*U!V2
zUe6Eqs^lsQpgB9p%)UHBq&$nU)p;nvvGiCd!Lc}T@Wqa$iL3Md6JzNmK@pCnA(SE<
zOEZV_;Gi=L9B@|v)OSy!xEK>7D2+GxQ5g<%Lyjwhz8iJ3)kn*J(-K6sf$L$#=-~B?
zA%|+F8i>J@?=9D~86U|><E7OV)ui!o+y_+L(3e;^&KNu%UqJ@c2RuSoP%EkHxmDsb
zaj+Y7jP;^YjO_8<4gpFHxpF&jt1+k~3)vb&I&wgtne^m9p3JbLIe|X2qgjDI1CL-I
zGyjdvdqABTGYVWuE*g^w4eH7;>DmEpW>U7bGy)8QPf7B_27_Q9P-Z4giv<=&O^YQM
zCT%-PpPB6HfwQ2913UOY!}O7koh9fEd_-45Ykok-85Qj)Eob^3@vVkv1^a-Ov)5q8
zHy$S4iftf_`Zf27Fj>^tNkSxpeSnAcil7a_zIr9lhM;H-lNv4_*DGMt0h5vpgB{yt
zh+weSjvDxLYBihxq+<1KN@ow84J~zN5!r?)1h1ghBVi?1lHauPF5pVij1Re%uc+Qv
z>eJcN+l`S!ONEF8J5*Vi(Z|x0&o@lgHJE|J>JiXguM2%bQwi63CHQWt_&Lj2*RXJw
zv#tj~vGJCrBf=!0fu9o9Wb+w0(K4;Us2tWbFlaezYPg8sL*UI0!v7E%VTXYfNj%tL
zKn0lxKa!Ot9-Ux-g}|O2Mp}q+u!Gw=1m(PvT-U`D_&~H$z<xkO_0Vg@DXp`V??jNz
zKEYfZWDe}0{SFZac5wVhcXbZRNmPQpSjM9}Z>6pz=Qfd@A0dV#Z9Ad8$Rc<J`IU-D
z@JjB?_pNr}!0hkc49<BX4D5(f3&B16#LP#RE=4wg5bs|{GJp{6Uq?285bIy(;VC*b
zZXT~fkk5_-SbzesFP!E&oz+)T9Tr-<FX%e)1onyx46y`u@azY{p&eZOL5jd9MY#w;
z5qQhB42RmT5=U%!(bDCMkQy-oUQxYisdI!%26zBFG6sZ5|9a&vNCDRAf{qm9U&rA+
zdRI$Ok-e)WsK^B5<p^gMcn1d^+4=p$%MfA=ypmeEP3^)oiY~WVMYDz&1UuqgqiYXX
zP>G#Z0K#UYw|9)d)QB+fO6rnO`@q^+;!~jl#SGXNkXAuvz>aX?Xj1zKDgH=Mx}9(F
zHc_2#q3s6QI-==#jg%hIr1X*ZBN~<dN)@U5&8NdZc175b;6w{i2zEHyLJWc(&bXB1
zbU(eEb<ucZ)e+Dg$sgDe?;WBK>=hFpO{eDt7Ud9G;1$(~cvE#H)w}got$HWBd*}On
zLY#jcSLo5?7~9aEZJ|`}REOjZ#o6ff?z?A+Z2*!Z#=s80Z#12c(=8k#3+x*=JdtF9
zw^&2bez2ij8}|cn4TOjSd(ja@6AgI>WkHB0u!Gbfnl=SE&7<j*48Qu7aKkFsdx+ex
z!#N+izVD#<4>J4pqWO=;bMn(c^B+wIWl%tb0HYmu3nBKuj_ZeLJSTr1be}7~_=a*N
z?O#V0s1WVnmDC`cTIQ9ZNdK<L>%nZf^skf9uY-fbkBoW{clbH-vLSVri@>jM&l0Du
zJ_A3p;&**2eq_aO;8k55e^-=90C4=>@~2aNbkGJni60%b!C>Mq6<|k-SU)o4!G+?Y
z0_@3_;vxd<xM%Z&vo>?nx|jeva-8|0A&)F*e&jK$+dLN!;1#Uwof3%lqL6Wr{&jH7
z+%i6Tq$0SIY9}ux{SY4B>(=r~5xS3yO+T{Parfy*MtfzcO9`IatG7$Ly_XvDLzwuL
z)BvVhFNN$!?lbRL3{z&aSCK6nRs-#SWL<Vq2lh-t;35v}ZXBar=Ey<dM?P~mj8O-D
z9~dL71s^p;-H}~M4N;qe4-Ang)?Q>xABk)T@HP2S#8>y3MK(M!MA#3NIy=i)KDg?4
zL0G#(Yx~ibQyI8j2-c2Nj#si!uI|el0M@HQdsWZ&rzArF)LJe$YX|PZ0cY(1M!4Xt
zy>Jsxij2R>j>$m)@P!M{+PxIA3(tBb+4*=630|L*3(tBbE6Z%VzDXyV^$PO63(fj;
zFqC;{djU4Z1!wJmueji>-48m*ec`#H>fwucI@uj5e^9r%(5xLf?VV`WUU~1Ilt9%*
z&66jZ^_CKUC*2SHjSJA)0l@Lt`i7#EvWIqtD5dOzv~~a=J#=&cIMNg3+5=&LE|hCe
z0z4PUwSyzig>miR(Q{#3I{-Ew?-ve;jfV_?7+GS^240BNKTtNF0M{PK{NbU`894!5
zfYvLi_pBQ*WC?HqTCe0<J1$UbM*?F{Olz+`e@Z&|1F7r8v|d4t#dHRZl|{C?&~^FL
zF*hziYX`W-g;(vdIr-A_39xa&RXY}d3$EI+NStWZ{#im^P}S-fG%H94J2)|2NYxJB
zOb_XJkZWE^gFC5kIv2{vcA;4b?&|>RxVQ^DkUH*g?iEhw`SUvKFKXo4`l^v{*yW?g
z7wj(VU&nXuE^DH;0(X7wU^aD;B6g%azY@emcjQHP5ghj1@Z9~YQgu&e0Jcqcm;nbg
zsqS>K_d@Ep2o5`-I_}c?!0Ncm#Rsg;<1QZ`&^qog1Wx@MpE}?=PNu{TMdB~Av8S$a
zmv;{#7FWVHpdiJJ*r7Zfd2a4ffQEI^8ul}@#41p2E`1I>&Xu5Z)MPFNUN9XO(P0Np
z$6en$DEi&y<tx*~U75r?%oq2;rl9V8X#N+5G*GJ1=yN~&$s${YwsYeX>*(pCH0)^v
zy7L4ME785n4FszFk0?v`k8;0(WZzxxH*oB`>*#%uO3qz67vWSXY5Y-6VN<^XQ<x4p
zSlhnE4BTOkUlE(GFU`eM*b}95%h=n1!TCsjyO3TS{eAQ7ZLPEy83+w<n=7bCSRG2P
zfcWy-&aMPAW;oe=L?~59c_DTs)lp|Nsi!vmb+=p=;dZqPMYUZGcMOJ_*Z`dM%`h@6
zkj~?KtL-{M`rco_=IrcN>(GFEt8pm6tvE7kBa1-3gUa6b;#12^^}X~|Xgo0%TCwv#
z^&^Y`Di4%}w`>Kw1~j@s-|eNQq4SD+>Vc>RK-1oE*uN4sUO@qDw~m}wvQW-}UIAN%
z78KCU;Dzu_%iapf<9n!G&{p^!c<@I5hn~C9e|+`UK1y(#`UxGlmB_>3iE$AcUP<+h
zzIg)*$4O~u1;X*I=uiU+$F~6Nh&}e*)jHImU~q;YW(RD&V|1m>vo{>uwr$(a4kxy4
zJDHdh+xEn^C$^nTY+Fz6KhAsBI`95a`|9fIuEvG6e$`b4tR+CjzI$nfn-Mn=7OHqc
zyCWuyep%8SAHEq9$~trLc6ewM4%CCfS0;){fn7k(G#tfw89>xgZ{dX787gm)+1GGv
z#KY!6$e)f-wX8WX<YM7qpa=a5ZZnm<6AhHHN4wxqQ#B6l$|`pB2GgW-M6OSFpu(s=
zUJm{p$_P|A`p+WVLLL+{{0<(b#H9b^O_QaSX0E0QdRbr7B5PTn*l%nDuI>~si7F`s
zQPA1$sDT-w#;d<fY)BVxN{#Z2Rjnx;^9WU~7yx#x_WLSP@`Sl-m|Jbk;{1n7^ktPw
zF4XGsSz(39{Tctp8}<cOu+I)C82VWb1}_m%+fYX3qdeZ!I_G$BIo|tHBHPePB22-2
z;^?HPyqP%ju~em7o!O60b@lO?+{y;iGDXA9>Y_j4@H^5!=(#U|B4$ScX*5~L$$)3T
zY16GU=jmecRaYEu_kEl8K;C`Rze)Mp;yriJ`u0$|1%#>$)CT%OUZXfxqb&t;ckvrL
zZBQ+6^WGSdO<ta39XXCaA46IecC|znSfrX1fjW=jfOxrauVRDpI@G0+@7T0`YprYF
z@q|Rm3JpTW7@f_|ts^-`cfwqS$Y8o~rMxDpEAIsW$wtcOXbjl~f<s?HDhv2=FK`gs
zKyV7IFGV2<9e5#DVYV2@K(KnF7h)wAmckt9(_@ZSE5J|ZJko4u!SN7`!vLt-pZ*Fb
zs~KAeHmkNRX~9CT5EzO8^KcSq=Y~33ABaF*Pam`)We?{y6r4o35cSCn=%v-c9wKQv
z`5Kc}=J_w|`Atzcy=aKMEr%Onc{D`Pr~L1%fcfnsYfhrj+sNlcoZRLNK$a)C4F-(5
zL;G-C;QSHp6GSr2s~9NGNGXSZ|L60<kshDDLS$`|KipLO+cFTM6Y(zG36Rh2_Z##W
z#zBdVD9#7(0ny6^k3Hv`H0gB9L8`v#Rsx}Lqe9?1hzZ2}Q9)Qnwu1UpD@Nx4iKvF^
zfHe@RR_TSnilarX4S>9+O>iJ8jfVX)8^PQu;A=F(a>?I@BMWBm6E%L-gCv`Z`@1ae
zVA1=*1&v^PPFIWktTC)4MsM(qg@)!UhS9wRBp&VDY{1~|AMYtA_;i^7*bIWI{i{S7
z5z`-~h<8Lw-)YA}ir)J;@>In`ETBwXhvu{bJbbQ$Ke6%>1)v6*cWATE!#VOqhhi*x
zO}q|)yNfIBlE7DLkA2c!AqdanxMPdYL=X9vTM*ao8VtqwMsYnP_@Oc2k(3F4oi&N%
zd-<xqZ27CWIx^r07^+w3513#6m0<%4@PTUZ5^uZCuo8ZXF4+?PB9Hn@e}IE(ULf~v
z*)56)-JC{$vt1$CjKOKwF3U{19BiAPVaDSb>hK`vCYWPb3wA<#D40}=G12o;O33E4
z)Z7WtIq`r${Ue@WF(ZWl6YZmT!a7Taqw%)sA_QsOgS%*DIHube!6E#<BQ<Dkz}9UF
zK_J>g%~~UD-(i7zQMjCa$`<vYo5(tAfY-`$i*pXinKcDW;uKFMphiW48BqYtv0os|
z)*Gr67y<Zz^b;%O-zSl3)D$!y&OehSyyJ^(I3)ePqW1ds?1Zi2m068|p9P|JN?Zaj
zI*#7<gG(b(NXkafIaZ!~%Jv|^oSO2dbUHX=uMh5sbAxb*%M?)4I8j%!FFb$N{zKzm
zenkNTtvwT3QiEv@q3)zN(AFRQvj?$Qatot|q^eFgi|N~A%0j~WR6wP0$3+c@g!2a;
z7Lb@-5j#h3NGIzc!MAPRK$%s>2BI%v>*0me*q=6}hTOL6sZcEs;BE1XEA248{590L
z4CPTPMAP%gw38TZ+}px-hYSX%{M&3q;`!<z<Ysht?(FxShX(G*`syH%vmmTf<_1(?
zU)PK9n)qr>3`S&M<Pe)kEEYAxTnNcCm0U5vK4!-|D6#KtPP703A2jfz$(mO~u>yY`
z*g=p%DhK^?xMSf7Chbc1)mymO%@$G!#52_!As_-lF~@YL0F&%0Aa9GM^B&@S20ia&
zQ-J&e3wI1fu|u2TOFXq2a%31hs{!oAV>uPBW+l1PwL)_MyeS!UDkOpR`M8r6WO8Tt
zu9}p+K9!44?mM!};-J)=Viaj`H=5eijwzY-=%Ua`_<gk~hflJ+K~`VpiEah1KR)Kz
z<YSX%Mz;u%TjvQan9=aMFg2yNY!pOnO-tb&Cf8@z4`x!bHSymTP?>IyWH@!)az!O>
zecVP;Y=O=hXT*xu@Y{HfTqLrMx{fpq{bHnOrM8oF3mH;q(NcKvRBMOX#8PPRbYBc8
z;-KR_iDI)H(xxW%S8qqlOIwPr-w%V1y$*B=;w^vMGeVUCI~lK!k|Lu&rmlpB+#aPE
zoZP%5D2N}X_+Mj#9rthbb2@DvC{;>^Z5k->tMyrQ5r+;Yo{8A-Dd3onf0Gx=imYL!
z=8LQ&;w@ia!{d>Q!-2_z`XzhV{1gpxTS0ys<@yBR4<)+@+7MI}pBVSc6-MFT04ii^
z>dt34NTfPZDk&QbEi#KF*)}ZfevoAZ(Yr^H&c?CZeN!KEXdL)n%+Ge05x+LXDn&;1
z+s{K2c<etzDLt{B3VP->(bl~>8ZlE4eh#_Ku`$gC@~dGuv!t*#1v&TUr26Q+^x9yN
z>Pp7(4P&5tj!8~bZ}>WvUvigX10io1-UYw}4MRB=t!>*od>#N5M6-@!_irzkk$q5n
zn5`;W;pjmgKI%RK2);qgFGMD^?Vgk4$OSVI?Z?d1C4bvhfU9+HvyB6#){kiuY+l_T
z(>B8M1fVYy7(A0ge$7KA79r%TA_dq~3*WivF}TKUnQ8QXz(?frN#!@AZ0n8sR&=`q
z8C4evnC%!o#<zo~nG&{@8k<7v6PB4bD{X7-7}+N>odYTmI_j8W=L+&pxBJs|rCsGb
z!Ra`7N)-g%<f?rZfjDhJCgFbhWlA+riof(hS(yQip3f{3=8*f8`1jfvjnD~!w1AT|
zi1hk^X;LjVfnzinxvUY_+<k3-e}gTYafjdDBcG`7lO}3AxWBXMa0xj<Wl@z9rGmNn
z_X-RK#P{TeZK|?cYkS>Wp+m=|bd4J(iq=2>P=?3<Y$ID>x*nH)C=EDQ?sI@7xtv-o
z|KNpx3pwkuH7bubQGRa#t{6xAveB-%qsF;xw(;zv{#<QVxuX4C1>!b~^ylb}PAAE;
zm3in2^XG_UU`5Aw-?^ABNP#cAP+%U1*ncc-H4Solb3P&Bsj+k0v^xM-XUF$Pc&R5^
ztZp}Ba4@7O+=?;kmp!3JxMnFGu>{>nqYhkSW~wN`vI5<+!w|K-ug!||<R#K&#lCYR
zlV>T#vIc$6p#HPw|Ne<)Y%5ge8d=AIk~=w3Txc_4<qU5M>rt9`Trw`}I0Lc5GOW{n
z2cmDrV3#4BnvSA}mp36B{0F}#!aIRWL%P!f-_-c_XX6S4kP(9%5>UMDt_|Gcr)~cP
zSiwD5x~;!7zqlE$Tysv;yr_tWOQZ>h+a68PCD6IN_yWHF;b?e!p(p#DUaYylNXWu>
zbk_;(J;IHQ^0;=;jf_=d*Vtw-r#eF~`HU9%<~pPF1eu2ANHdzEYDZNzY~^L4o7{pd
zO;kIx@_bEXQ;G;9H;}vDH~uvhcztHqsuxD(tXkW$)KZJK^*M5<q_tJ#@{)oBJDC>E
zR4WTc^(ue6f@E8nmQ;cLtr9BGCgK2lbo%99pLCLVO~ye=^r`dTVuCb^TQh`^W4Nzp
zG|{h;p&$J!gX;rC{Q_6{8KBEzh^*(LC1O**TWFM#?Jou$_r*rm>s^*xRd@_8{F0b~
zts_0Gk94UON#V0nM#Eda4L>S_+Sc;p!ExyUGc4$rOY%}M3exGCKMB~clplbXsDY|?
zX)8y8THQcSdDPZ`mD><!S$W@<=~_7Zm4O}LGY`svTG!`%f8KtMAaxl4uqSzX`;u5P
z0)SbOftP!Krf*m`m-7to|40_@GXoG!MpCgB$C~Yo%AOYDo362UPN|r;Rs$Ym<C0|`
zK!Zc5lv~zA3~WsMy|3a>2}9_Fy{MIYiRxt7ERgkM>hDK}nI~Nt*m*n{Oy>wyHMO8t
z!IQ63<*H(0ImUy{t`vCJgF}a(a!vbn>J<vFsV2xV*}2;QELm2`Ap%^%?921-&veB$
z_xV6IbZN>AkuC|*_Id3|Aqu%w98q^517Xdk13JK;GEsAXXWxPg;C`>0$Q7~JB3&@z
zj^+LyQ+c@<<se>dg31xHMb*<Sd(NzpM`dqiGc`Kf`fVE*YJo{GNYJjaE`-9qs1nV(
z#Zq@aWY?}U#OQ)Aw`?$OgPKqlLSf?r=a&>cEw2_dPJwGq$$asE?U|_vn^m|R6c;+3
zapj1oUqWExYorf>4#vJBS-sYqN{x%(s=*BJqG;9(J?h00`uYRI1u@1o&TOpzmhllG
z`jc5>Ri?%PuDeL)08uSX9}$beRIfxi2Dd9ozG?A5UNgrhZglZIM!SHe&r`Cr>&}w;
zDu?#7JAhP~V&XT^Xi@|?&(?F7M~hkBSQ0!r#MVF+HiWyG>ECTEXGf=+Z|9_$AOlmo
zMaG#+qc7ZN2Gjn4v*teP9ILff-ccRSt);46c=?HOw0;q(&?I^Te^8tbMFMK&X?%Kl
zB?v`MI2a1X%<;k@2sh6r4NUcUdNpyvi<REonE(^rECjOG&5H`%g6)9ypN;VBOG5S;
zvYJd2`4!3~emr0nWBsqmfXQZ}04oc{^+o9kVToT|o;!x2hRPghF0<x2j&`UzX7!t0
zIe|>98zi7uWo)K}pkjw_37~^!e#{0##pU<n?00>{!=-uNSu{UugR-oIjUkaYr!!1{
zP)ra)aVk<wfJpq#q3(%Tyu+R%&r?aE)c5B0v^JEe&C%89CC{3>ikS8vOAIT3_ynXM
zo94}*(gL#@J>8}IW6yfKo#3{Wx&b714%I;*BIPwTp3lj{yHS})$)?wsuy-}|fzpsA
zj#P%!DY@CP3|&H<kO9&+oS<UzwpriXib`oRQ#=-mT~Dpb7<IM_rd-jEo2Fs93o#a6
ztW-$fcUKMD26Fg)j|lSAH3)hNt}P6R1~wc5Da_nY;@(hEcFZ5sb;9vA!*`hy%^!o|
z6EDe){^rfMv*JDIJ)E-{E(!x0AvE2{Tvo?m<7oY9+HXx3X0{&pXJ%%^+30Y;c?_4i
z)J;`>Fsr?RiPA(qnit7(Z15JkQ2F{yXjUp9A5|jg`b=zAihEagTdK*wusdFhhwBGh
z@Q6Gg9K0kY!JoN~bO#yzIox18eGXu14|dbQ(!tpoB$s}R4PSX%KleyeWbwU}M9x>?
z4XZNTkH)LZ8=}sLG`d_x+(^n@u=TX#(BQQ+Ee@_;juIWB+R)HeRE;1$0cRr<KGHSl
zgg$FuXCR~JuwNe9AeM2KV+-);Vv{q+;0+zJ(Ts9mcCeAKBIaq2+<g~T*E#(>spUTX
z<tFCz;n|bw+-nQQjIu+(f<fx27=zPTG{3H~VfM^~_mzJ^!IJ1h{R$ePl+zkehcqR@
zg2-nC`(ya+ZHu>Z6Y1GQ@6gop(6?E=Z`lG}BW!^uHp8{32A}6>C5R=am~cf8m1neV
zk4odCmXHPm@;Tdlnq{=3jYL0M-9n_+{&>s$0~OC){K{}ByJd$!4eZs{3X)pHTDa3?
z(@+bEZPu|iEE%o}yrp(7zi9_Ut?_Lj&|3rfyVvf5E$w$pml&cMfaYWEPKoM-=XXHH
zn|*hfCa4#vq~!kJ50Z+K>&J+WY9tL9!J4xNEzo-EnUnB!)x0p78~p&YC4W@g(<k<b
z!MXG%X)?FvECJx5gp8(9UmMHGwSA1GCZgPp{y>+XN#)+P7Ec_w3!5tMLm5__0=zO`
zE3{4O8EkL1qD`$VX+UNXb8BQwQ4;pby>uj9a)AwJV74e()UwtMeVS{H>rA^zOAv`W
zbe>w7VCIgu-&Ms5)(s&y-|rj-q^xpH>n<Q`*lZxKj-`XHq=7=F<e)w0YzmcJF!O=B
z6EK9#=4t2pL_n+CdV8W$+Y*K2N~3SiprOU`S|_hCT-Kl=^|D<eGvatp<xsJnbs~|h
z@MyE^oyfP}EVKGA-%NiU<VRa4Z|i9aACyqJ%xmch_J9Yn{m4*z)Hv%K5Ag}~vn@NL
zYC~(k-0Mga(2j`KrY3F!m_rdqPGa>z@9#3jLQjqSt;r6>zDW0yT@G?4#~~;4O87G;
zaqGa~jkK<=^36t;$nlb$ot*e`OD2$wC~U~`WyhS$>hWL2LS)~ek!=btYWOPKpiG>3
z&K-4>7B^IFVn=Jv_(hj93wO~<7rP6JdcZ#&uol}`bGD?rolYWi729>lZPJq2f6FP~
zHitS0na-{6`JuwJxN-Ia_LuBP&WYr=!8FP?2yD-0NwT#&B5G0En{cUk*$V6n&NVcc
zw!kzkH`nBT6|Yon25XdWuIVZuOU~FC{cg0qpcn+~EIF{LQ=~L&bZN^WWF`Np+T56o
zq1?wXbUP0IpqPj``leG#M@vhq)G8*(mc`E2QBttk>xH&uzhYJ}^VO7En*AH++MC3S
z@H1dBX5B2<Yr~rz;-z?9M!Ff))MqJdb`|0xGWUqn^aqy`hMK?)k{PPmCyy;~{UON$
zS%BX#0#twdYJ)8qU94NF*v@?d!|FXK1|h2sZM2B1pgV74{BWfr=m>EC!NIfRLkue2
z33ma4!Gs?CRcKV-l<z0Ugs#4g(U+v-t1YB_b8QPP7v^>nWkEyJP2Yb~EP5->Mb5vy
zG%5ZI>UG_XnN&MC&Ff^xhrL8^t%xxg&tvub2m_SYiHR++FeA|G-_Ls#Eyin1<ko6g
zDC024E{{vtm@fMMO0LIds2aI?L4z}OvWzZzp=ysuh!nNV_Mt=}PyS&`>7q_HtGiP&
zXJo3O>J~B;j;>ECSRInSEtFcS&@S?p5~CGuCu^?=dJE}$w9&1EXXunJ)7*2w%TfYl
zhg^f;T4P!SfsH@<{8oa6mnCJ6nDQU^RSuBiB<mJv1WQFT(qgLT6tOXD3k<nS5yqT&
zO84x9nx?^$yE!OXlJf_=NYYN%RSl!O??a#pBy?>rDPSvSb1)PUwaX!7G^M^C9G#Jw
z_R>3K++Ve14v{(A0?Kwv36d=&d)g=$Q)2ZPA4*wGWHZ?^;;6@D+}5M~C2Z#OiBC(V
z^6jV|9t_C}e0=HWFOqYO5Qj5AIJ|`DlDMjJ%_+T0ZW5`~>l^$~cI9vUKEMXExrFW#
z9o*#k4+94_wC!Q>a`=94b9nH_pBwt!KHFsOIMgx~c?sMp<BqYaa0x4bH2dA&D#LtJ
zq33<#_MoDBmNvYdKX)!XLM};ZRk>o4<*TpILnHOG5uqcAN5_6BZ&Vs*NFDUBgqNK;
zN;5O4trXl^f}U~S2#c{tttdqgsE{#?>%}m)B1svIejE~j#3hBlMQoNIg9zm|_W_dq
zByYTF@}>ody~@(_uhe|S-}4AoE}wsu=1S(f;K-lT>3-8Z8j@z#8m6S7X4WznS~!1b
z;dG}a=Rd=WNN=}t`?Z|(_}f^qw8$KvRFIhe%=|0GFQ6h5CC9Zkl_eEmHzIp7#WNy9
zy}4>z9;zTc%~RBbI@hpux}Gd?!oNr!V*ar<G$kPfc}7J}bVh_v4sO!*B2EpyYOAp*
zA*R-Ym7)eykAR>A5MB}%0nm)_Fi|Edp7|G(4vlS>*lDWYsFmj|=uxv}-j#={&8sbE
zHYFMD@QUp#-`46uW$(}NGWp=nq(|H{DwBgw^6g9IZH8tL?W`%Hg89tPxn+)VM(g-6
zq^<g~Uz*aS-LucurUL#{iA9!N4G91o2k{yUQj3*1vjiVzI^M!po)F}Jq+dJHEDAQk
zlFaZ5oJ|bntJ6-9stdGrh^vp45-7BJ1a#6L901rM9y{AmMrUsln7#d38|kT9@*QwB
z97qizH3baH8OTA>WABpZS_h1NYR~itV*-%Rx;Wt_)1Tu6G)LGU@+vnEl$MaoNX1c|
z!S1+}#OiFV!q~~`N~P-ueOv;;-M2?45qW7=FYk8N>e>La1I@)e1uKT@^>6vDhQrM&
zk~(-bg>{VL2+oS(PB%}R&^qAiWjkoh6MguA+5TozV$|0m>xK-HHD0%dHXYco-LgE=
zMO9|>zq;rFRNYAmv!}j7#S}w0&T%11Ma+=eR8cI4L#Tk8Aw0sHBb?{sRbjk;3g$4>
z^cur`qLFlmpv=9H(91DI{B00^+YhJ~vABNFmQT<!#R25LPz{ytej^K0$fj>Dl;WRG
zSwO`}`uHmOIxya+c`(JT`UoY839ko*KPM@U>#~p>9|AfK(O@UenCQg6&-qu9m+Qt9
zwsf+W@!l_RxXiCZQ+kY?ySY}JLHtz!R4(QZ$In<j6x`z_OOOW6CBmRxa;3=Lv~>=N
zDz*Pc2#6;oo;c;YnaI>H<8c8f-Sp#YQBW(Tt;6ow`4*fKosb<H@ap=C+zfUNq>{H8
z=nW5ezUebBeh8n_4<kD#bRKYp$~(4ffJB#g+(Qky*(mqU#H8U_@+qS^NY1p_8V-QW
zU*4!V^k?SV2+=v#Zr~K6y{_jgC*r?#gd(_Dq4f2*x39k@{N&td)3^e+XFzZC%Fl`f
zx`bLvg#o^FrA+vytsK&dNBEKAo@Z{$#MVhqqXnoRuPU?f4v}D&1{eE-D34Uii_+(G
zVNP<9PnWHdfRkFD%Zyt?J?^4Hr)oq*fQcw)z?KRN%`-<*SigMOxr)4*MVNgu9AD-}
zxSh;{yEugV6`D4TSZ)$qB`?u$E)4`8g{g88oNhFT4SdN=Zt&lVuYmGeo>pG!t)=G1
zH`H=Bwnhf0D>52Hmy9((k#oACT_>HXLo^#6EDdhZ(Ocbhc_inA4SGmg%2JMOghs2s
zOTfzN5-TU*n)9j*L^1(`_+mLGJJ$omDTzi-o~+(V`2+Z`&g=bw{y!oKF1LusoUIn#
z#EL^JJPXw}R(bqwVHmpntFR3q;dH^}(1@;!pbQW`<!R8`f_fA2quwoKQ~~QcOgJdB
zBltyOSsC0yhtl9=?!%gvG-RGFQ9{e8_R{kZB#@=gItWIR5>^~GkCG5q33zxpaJD9W
zB%?$F1IV)6!a7`QDhSdRi<usYN~*5cc1jf$1fZV=gM{lWJgA{QaIFJy7m*U*p*ciI
z1ss^;A_*@Ila0!|P5}^z?nrLUz+IRw*{Q{}kZ>wH4)zuDfaJx#iB$}Y`BFw{!=*ym
z#loV_Q>dHl`~xSkQbpgL0u^=s>lZPA+v3f*3Y+6FC<{orlbW?@?H?8_)=}YM>CtMQ
z5i{xoReK37O$`UzkFr6pq<q@rXIFSka8&neR~8RA@Ot^s6940lHWfO@Veg3<t2S(3
zMo<)8Z1_i@iO`gB^Z@~M%MIiM0dxx=?KO3HTbD~XU#?wXq++^CPC3frvC}x3sTnsc
zylfR9CqyvpRf=DBiZ0FI#na0i%xtZFv(lkN?o2K$X!eGg1#nazIc0@Yzlm<Ms?k|p
z@=%F~d@mjMc=9uPC6+0$&@yZTNP%RQUlwe7`Q|VQwd}`TB|<E@btP5O+UH%xLQeR3
ze|-lc?Wie!JonY$!B|4YI^~JW(4)o(iq>sc+Y+jExhN8Lm0!-lb~-rGVomM$Y+u1e
zXqRoDD(_8^9_GP;;XcXEu+WSih2}nTsmjzo;4ij3%?l`9QAMbGrgKUTLQb^P5=A4W
z5HEB>GE(BB8CDOX#z_t$N(_H#^A=b#(A=lFLf2~NDAO1uk5G+q)oXt&MeTPu5z+aL
zrF>5N9YCNwZYL&|NqK=b7pMl!aICIO?xwhNxr@3vDTpeOM26dgMKXczU}vx>?T4R!
zvWPhdv6;38oc~O&E-e<b<yuo9asxe8X$v~F)nYRl3p;`lZ9*jS<;SR0Msqb3T6~cz
zw}7~GUB$b^bsL)KSf95vbeh+^-W*$nU6uw-cgr@son#>M!A@V%@ejTAo}`TOJ>yd}
z*0GyD*R_SRa;K);A<T7XN9AG8O=`z^+mq&l-G%5@$8T*Mi^ie{AR|HrPUkVoWHdD&
z&XK|gJ1s?RI%gkwCsZfhyAcp)zJ-R~iQY*Em$EMKQsg*E+d?$+&6wMv#W&$6*SNSM
zmYH6@#wkVs?p6kALuJT$a&ntf`~<U>1;t$<*3nF_21BLO5`+vHrPhT$$5n_Nj~Yy+
z2$qAL)}kaCd=zL)9x(>w5VmY0#^4AU>Gaorzu8vTP(9H|<%1a)56w85Wra-whCKXM
zZ3HbD8orlimkTyqx^oQpyFX|2)w2pA`a)uRSpfr0Y!_3GK&hdd+{WzRUx2OiG`307
znH}kQCEth4@q9~@#qr5_906GWva-W<C0DSc@zmvM9}2fPBd3@CWc|p|11>x{<~BT^
zRIw2!`+6CK-Ism>Cpr`+A7HVeziTO{D==E!^oz`BjT=#HiAApXre!hwOjrKwiK0L~
zX2mno{-G%H58(1rks${|=A-$v6nI^wNlN&+j+EbY_+eG0vYPNZ&Ty#fgrU6bZ_L%0
z^RXB7b`E8+ax9CgvQ<H!t0=-G8!V92ZSr2`3too0+9+Bnnks(4g;QEiR9D`!2111l
z0?YRq8aE|2n(0cV36OVXBuB_ea>ye{9nb@hL&y={gBiT|-k$tD_F&|Rd~On8f6;A4
z8)f!73TPcSa?&{7%K;~ggx+k;7+C5B#g-qI-!G$;CwPKP@*St+6*^o7_p+O1Sg;#%
zbif9(EK5yN<_Cjve`yTuP|>xeV3}D?<%dVIgC!;WN1Y1Yt!=p*=BAZ4&MA4&X<kp!
z-$d^QeWl$|{QcBUo)EbmS8EjTD{@BL8ew1QlRPio>ym;*ZzI%^<9*5W(`eC}1>xXP
z8Bp|BhjO962=Hx5CFPWjbxI4g_QdUIH&(dq5?CFr_wqvo?mEAYien4#mXFGJ_ViNE
zs4-H41QHF@JwbTIYi^CE@JtPpYcbK<#`+?q<IDf@?dlOaLH2JR7IWnRPxW!Yf6A%U
z=eEypZizkGo*W*o2sD?|GO4g#qXrBXrn6CVF95|;NDoG$8Z+1A*8}Gln1P40QBN*#
z@eUaU<fTHm`LiaP7=UB3QoAl#NB{tM?0IzQzexQ$W&LG;)E1D_C<hFJ(xj~S13;Li
z=hi}VNYSMD<ZD!7{{T7v^PE4%!O#=r9qp%!{Q`=h9DRs9Tq+`of-GbAd=w4HBk=;4
zW~VMt_g7B*>nZMNr9@UE^n77raAT`65-2le;isCz`31Hv8v+%J+N-5gMRl{tS30(j
zp7%EZa+EPi0^XwYko!Sa$l^ym$a&i1rGN2OGDx_+45wk){-0@96^3in;NQlXKzZhG
z!1pRZH?|Rgh9o^X@&~o?IUl&XY7kwT;w+qFS84%OosYL1@1XP4`Gw16aQ*LCe~=1w
zAfgn~e_(!<@eM13U_2bf8TZODHy4E21H{;w`tKIfz<Ccx5-T5p_$j7k&<7uH_uKh7
zcn`^NhC_@O6L)=Eiig1&V}syuJRlsBsjU6^N#&L-JaY?W>4rN5N@<`5lR?g!@7K9$
z(e*Jbq9n=BrqxPv!l4e*y~s$C%unOtOJME9v+1fAcEAAi)U^<CHrgwC(QdS<TNuY|
zG8MmnAhnf^YMp3avNVk?YJ+bl_ls-ma9X)nCT?8Y(2NI~C-PgXrYj2&1y3fZS@{b$
zBs}98%+Q?_Lwp~O3YxBJvopPpW2vRl!nO+ZW2F@>ej02i>%bvuu2JdD#iCq8c~V=i
zg`5ZE7}(3G;E+e7(o>rb*`8`4H-c7<C*%Cdo1{A~{Dbwts%7Yp(T*0#D-^kk(aJHC
z$>uQZ|E(aHu-$j9M2w={%wj9QziRzSX%^z@1z*IVuZOI@oqn?ubL>)dzF26Jxl@S_
z!+S8fG}2Ke++7Y>Vth=wo1Kl`GGF3nhf~tYs9N{$BzJg)^|`Id*Yq6MpE@$a9xdfs
z-o=1R-U0IXTA&(JX;L~Kf#E=rmD!Y2W9$5#(9Wh5n5%*6rj(3B3H-Kk{sOlO8L*mO
zGq)cPw6*KH2}1Da;p)<PfBa836ZV%mT+uz((ZcQO2lrvXgfvlvqhsQo=!SN-QmP9i
z*ry=WMtv_-)Fs2UkD#pi_b?^lWsqAy_4DaZiXgbyWj3mS%FWQ-X|Ma%wK{{hQcjzb
zq~QlEHBkWYP?vO$Eg*bZ#u2^fOPU&|Ax}fJ$F`RGa)@m^XAN7I4b|iU^FY&P^wADT
zwipK;Ad(hQ`<2VRtd(T1G1xrS5)IgT6%wpzoHFN?Ou+>DXs3~fTXdr?;8Q4=WIsSl
zqpdC3o&xr@P|V@P)U@`^ZACk#MSlaWnnie{%Qb6;Q|q&X?Mv^l^)_n~8Gy^%r9P|u
zFz+~9%4kvesn4!5a&Ajwj>f`!UX2C|+%IflU0O*@m|bOCk&-mC)a>G$0_g4#z$t&O
z^#~|_nAZ36)zN?K`T0D}h`H~?z&GnK@Bi^c=y!L}GJLssRLTGO{#A4S^X}sY(DV6W
z=i3&Ub?>!+A&ci&b2k3eBl!8+vYox1UDMzFb#YU(?eleU@WlD^dC$K4qvh)B^LhO$
zmf!F1qN*NZw)&K_;O5a;?%TNF$7br6-@&@Vx5V&OEUZbwS;av0_RqHGNoU-4H~kX_
zaTw3DYtFCdtFOC@r?15r2EOr2<Qf!x4~MPsi(A6`r2MOW>cDBAKeKb)o>#{`@87vC
z%B~<DHsezEGHM7f?-rYv5nnB#GHAYoIV<^cUqefB#xnmbfPFt*54Zn(?%4KSWvIj?
z^X_AJuk7}N`sq6MG9d6Y4DFQuzFgz<^3Z!W{zdTfMbYQoL%gO(pMEyiYwo&1%ZTye
za@l(w-=KlX@43qN$jegj^gNaqrhD7Z^urL6{^BIo{CsgS%m<W`>8hdW^eoJV^73QL
zjQ0&UoN|3MmSoG^8fs2Eu3-O2uODNt^NP?9`Vm&IKf-zgaWS#|^6fPM>yEgvjOB_|
zq-Rf5g4(Nd8fxt(?3b~xYQ&0$z}4TsAjgS}#<}yKBjZ>-`=&x3Z=&!Dmk3*nOvrRX
zFG{nZTV_E7{fTmOvGxtbThEDdz$4pcq8hy2;3a}DD3Jztqz!WqFYdiEyQNO;<bK-R
zP{RVNXe$@C9C+LOtMa${Tc+Ch>^q|p0}3WVKD67t30Y^;nl7EUI!{e%jDtTt(0sTB
zzaTJL+Z7JPwtThQY7sRf{U0Bvqh@YQfO__9Q<h_%Mwt#3K0NWaE2|vSzS>f@+$jV%
zmV4d<yZ!bq#gYqleTVF9m~(B`oVzC>XeJXcy1Pr*!d>`Ri-evzaF6G0etwS?!VT!^
zJ)ZL#*32g~+?R&3U}$}8cmH~{WG4K3W;Cmba)x7DrkT$oimN38*glyTm#kRb!2dL)
z$s3NH;OH>`X6uvnq2au+rh&XXOq4U3YFYjC8RhM<8sg3Gzcopu8(+8a<-hF=U=>7r
zyxZ>WHh+$1zK(hXo(>gHIok|$5Y{>yeb)Fht-oTMuv#zm^I%(F>0MA{4ZM3CQe7}@
zOYOG(tH?6$UF^Xv+hz&ZN57}%bwZ4TL8?@s+K;KLYPWZpoUlQlL}9@tEM&5#;-s{l
zmVrv}ae4T@xdh_#YxsBU2`c;MX``dBoZJ!RcOnfkABU%)6I;2r#9YBq>T$|bO~PSc
zRsLo3Q)sn0NqfTibuWl+@b|cfpnn=tb{Put!}^-FVRCtX9iJO}Z99K~NPpVQeQu`q
zcz6k(E)RbJ>v5Id!kF5bIJ-ER8ruGIWp88!!%oCR^v^#L5fM8#Hyh`F`K<rp^YQ&t
z#VGFKBB|_R=weFrZ^l17L#FQn5u>Ou5i=2^vEerr5co&<-;`0p-p=KJNt@9#(K8Wo
ze0Qt#AE9r#{|tiVf0Pk1s(3n>5-}<onwt`l6EXiwxuT(y>33hu|82`CXKG?;C}QtH
zr2Wle`e)!o%q&byM7sYH7yVZJE$>Xk_CF0Io$Os5{?}mst>j<af0}&%7?r<OI~m$J
zJN%=}*z><^X(AUVSJVHNM8BoPOx-MvO_d}?{$c)Su1coP_O4FGrp`qFteX<d|2H+x
z@A5zE`_D?rn%bGWSP*gj&#)vcZCp&9h!`bozE@Vv)Y#tSUz+|S$V|k^#?A3hU;o)M
zkE{y~Zx1x_=9*LGMgC2G{(1g%XtH!N)C6Man&4m{;3Q<RoG2n-)QwtUBe5h{s9PjW
zJsBeZQ1h8<9CD(-dggj0g0s_G6j3#I=&f;dOmsyT(t15KPKso2FA#=~C+DxO?T_wt
zc2(V)YMz?cY-Ld@VlmPvsJPyua@5kF&+kius76)9VmN}9kH3LD=>$^a$|OX}sM0@=
z7qI!w6o?1IZ0nz9DG!r<F7+~FAJn0l85R6YjOupreL~}okLqfUOwO5_X^U6<2-m3-
zOQ$m4Op2MY);Vi+-v=9|QK7kKW8>T&aS}`Avv{+U$5?AWFq%Q<bA3#_^bcw@Y@e8k
zeOTh9BFYTNJ7LOIrEEq<{fKT67y2*(zfAD#Ezad9LjQ#RnV_N_g`v=tCjZ4Y9o%|I
zTOi`-`!$*9#FJl?rk8{Pka2`R16n0v2BdlJ%I?okl#%Hx)uAmriEC+v&?PEB8ScGs
zCn-|x;{q8{guEDq1glCGoI@r^xi%PjH1RTiA;}{=Fj(+y{Sq@_Gux~k#S)<C$phWI
zg5XSq@g~>gqfE2iMF>PdWt@@RDjvwFe5_3uwF+a)UKc(85EwKfMCP!C994?=6Zbe_
zqs`Kw-pu$i&|n_Y>$$GQSZ7p3n<EQF-k>o=!@g%c5Xotif~}NB$Du~63Vrde0xCEw
z%iU*FGEiA~7pm@kM<Aj#xzyr?xlyp*cp|ZyK3tOz$DrRmYvJcMi8efGokGb;f^=q=
zkuC0{m#~m;Y$XrE;dOX_oVFpXCJ>mG;*k2zAjc-o7G6V%m&x~8HLUObw7D$NlQukk
zfqb@M=Xf#R6KM|`(0-W?*=)ldH;4R^G~!g$lci6|V=0*+`on2Ow1288XYoR{hZp$0
zyY+G80bV<ogMXRD5^|J<e^rxUJV~h`+%#by!Hv3Vt=^UPv)S$=pyKZ#qF{KY%0Z!6
z7gtbQj+ybPaKnI62^ISIknAg6wq$O}^jdwl%r9eDO=QP;)%<`+Q6>7nOLV%VgBSH1
zgSHy-K`V@@`6n6kbFQ}j`IQv2FHX-@GJ;m^aHS<<LU?wEOLFTdY-n|)Bu1MUmGt%<
zc2RH7j+MIAlSpf!$<_x24zmJii9d_eVzgh>vVSfzz`|3y=u&JDR~m>}U%<^vaX9_T
zU;9{-GVbKj%PgSh#K1m-kCljn%I0-Vy|k0`O&FEklD|9EGyhGylnqd_h(t30&bgFQ
z4$_Lu`76uL)5g;Vs>YZg>Rcq7GU{#3|By4aB~eYgoNc)&D#At<LNqACM;4Y8XY9`-
zg=+)n3hx^Bn~x<UCgo2*6-Q)j;xNq~9%2QemGMK}6o`6&cao}zOws6?arN+q_>#}C
z&a#d>wq`lQd@A?&FBbLmH*nX&?pe)~3K#Vg)v2!Pu1l*k{<DHbD}E&@n6@al5^f8l
z59&!Z%jQPE{ZR8IL1q$0Ug>*&2}(t_diR`aJf)0b2@ZRIN~!&g`ypo@MA!29fc&>s
za$1%Kf9l65R+=BRWD%zrQwwyeg^%AE&ch0{5W-l5l(9?^Zh09tE2I%tJ+-qhJHtZN
zGu;fu(P+2xHMk2_LOCYQ?yV=Ro=^cF!_8IeN9=zZH4f)_tlaA^*EAmU5^9ny8cybI
znptGLQ|M>)4AxgEOtYIM*2VP=d(3!~@wGJWtb4iC+4(ViHcJ1Tp3KBUF3NlL9*a8X
zV_xOot2jT%8dGfyLzWNR$NdocGYe7<L?Gsip4a`S9Q>8aID<KrfsJDxeoRlRSOxbA
z8#7vs6x1~jFiJB-IF^eZHGGnD_qUeIC#Rb@hfiVNl84r+ZRM7u3SG3wP^mFZc>D)s
zm0Vd6BT^z73*CM~akL3@A@N`?l6x9_Y9?c0upOJ3sgm~ZmmYEi6cJaha8Of=hf`go
zND?a&=5lIsni3qP(#mz!CM278>E;BJN7wPD_7v-I8o476bM2!r=m0|-fjTL(5!y4D
zIv0)03e{Mej9=qhN6eYAoMyY#P{hNyQ!5tDKUEeUsUk4u?9g_{!(h$dY#gHOAO}#w
z+*WUI^F@6T7^6-P!#)TqFDFxQ)Ea9{P>zr%*22<~W8cJ)8BcI;g8;qa2L}w+O%kzQ
z*4d$_*Qcc9kZsfELF#tvTOJ#+oLU5Izdq)D>|Y%2sA$)3CDw@|llSp36XxPCD}4{s
zqiYtI5PUw$TekDBW(Ve~QzF(|dNj!=zlh(hMvKmB*Gmi`=4z2FuM@af_>)9@ROnrQ
z?{uqE3GNq3t`XiY@TkA-`6LV+5e<;XddCTZ6b;9}aWHk+=nc4#f?Vd`f8NaR4cuG}
z>&G5_NdH{ZKfO959PXgPj)7~6;)s?loG-HMwsf@Gg-gm{qz3uy@{w}x4b^vn1&AfV
zXs_t({TAdpSQtp$`l+*lRBGXMSE^E;>{eaIx1T`q>*t+HEWsO(YkpU`MB%Z}&Fqcb
z+mmgBXU3{mL~hRjrp<j^v~4%hpKN$$f%!-9N%z-4ZEfRp9AZ*xC6QC`S&`j-aDez3
z_*&Q$I_;peqX=E;-80k=+UoFWF?xIvV@o`IC2|6k^+C5Aq^bf$<2CHr8^a{~<a2SY
z_ab*H2n6oU)BMNo#mlu;Ip)DV?2RpIUZblh$;kS8JF)j$(}fz(Tdl)@f?#pzT`(bT
z@vK6|0%M$;?BgcI(Q<)C&eq%8c2~yrwu3f-nrT5%E$!)vpIy`WqDm5*N4d*}DFjqG
zR56iP%=p<Fow()sCR%6YTp?Zx<hfz5*z%*rvC^^*WeEk*(z3Ex-`?&K6OsT+?7NiL
zu{FZ_m3)J$CLVg>dDK0$TcNChVy;enh~icAg8Um6E5clD67+37)}F4zwrJhz8l<Tt
zDb4Rpnng-lSQ)3w@9o>G@X-ZPTSKer7nKi-Z#)k`(0T6C^K<v|Kd`sp^h=K$gBu6$
zg}jsiR^@6HsXQ|9vC%ULWY+Zv@=U$pc1*+&M#Kp3bb4}=Qdha3QTHJyQFF^hVe>Vm
zEs{_f!oIfV3%J=*sAbc%l-t-oCOgnmC$p#u48L*OynQrR2XJ2rw>|F!{}6f??C%ef
zR}!w`uD!hv|D;--e!Y^B86Ss*mveIU%C{L0*x%=Lc7l;WBt&;9wb7}+SPbU)`VqvD
z7PDe%n1y)}N0)saUA;)7dG7e!w6&mcDa=;42^1($C;XKnEaAf~kbW;@q{1Btizcz@
z*uE~?P-3@Tw|!NKiaGmP9Uk?rbEmvKozsO-nemf>Aso?yGQ()z0mpcQI$q=MOfh5N
zFN->z=Ai-e6j_urM{gfF(5<!VVbUl<QRGQ8alzLM<<r2W125dBTr{W+ef1q6NxFhm
z3$SMyqo<^>HNdRV9*gMmE14kKOvd?H$r7B=-6oEMS0L4grA#Mzk4Rz{#{%FjwU>P$
z4^UW2d`faol0D+bB8IbyLdrrEMb4ZcR6V>tnNqEd6r@b0J(vQl(AcXY^x7w(I*7cu
zKMS?N=+{=h%e+wdOn*_hQ)dOVOT^ETB~$#MeYx+L;~3NWOQhzrobbUQxU57mX^B1O
zBkfgF?44PyC{KrdP?T^VC%H93l5@xoSqj60Thb&wD3FfaSmt;(;zjl=x;0^*soS)j
zt)lo<msbeCzO*>C>u_CTVjvNsXh67Lx&Z30;Ga$6fqi0uNX(m)_wR#MRlEBw*4Cz1
z+c>rpR1#hlaRd=qCXQ4&I0i^S#z4Tj(9SSXs;3L#`fg06<DE>MTElt$;lU{K>j^lo
z`Kggq*G`}n*KQgk@`bPR>+vF#*)AlaQox?SCWvVxP~><MV;WiSi%3sCrrx3*8-oSJ
zb3;uRYJEB70&QHZN1K-?fHkF5_QRcz<XdES`VM6jx3jvmgDq$4!s%LwwkE~S<wWi0
zqMr*ImDuapkkB8o4PCp=5h0f-Ym(L9+=?XM3ZXoV-|<092s<Mxvg~rhdbX(+nvq(7
zLt<JDNnt_u4n|Z-5^UT>MXenB2L~ep{*p<+kd|hA3?vuOUw62+jMT*^?)HU!TDylo
z4J|^Kmh5-2K1?cyxn1(sI<ChY4R^lmPt1eo{y1_*lI80@EVK{oGu~{V8T;AfxSVyu
z`W<&`gAnSy?l8TJBNzQU@Y+aet_^JQpTR%E-hvRJWKI<mm{sr+D;+8EwPLbz1sOfr
z&`zC`d5qI$xB2TjBHEqH&r90KKXKZQHZ9(n_xJQ?t$MKg<Z#At#{b+nj?JH23h>%_
z{_2N{GOVMEc{7h+y;ZJb-7|Yhjhjm&uao(k^6Z|t>4;Im7%q`9pLpM%`PqPlmOjIB
za&d_45iy$c+>k2s)6wm69{xqW+<iur`R|_`e(%GXCf^b}9G+66-d@(thU(AHBi_>C
zs2;I*E$-7clE22vQhrqA01Aon#Nfh%T0yT;Y_}9wjWd0G7dOQZX6PS&Qh;Bu1uvxb
zsiXoRg)Kdm%==ZOu8n#X-{E?P&rCWkm&l|-j-Tv!`N_KAyUAO9U2UQ;6Y2|!E6~?l
zYI<cCkuxPbotHLS4sR5wFqZ|<>Hp&3i|<L;gm#DNd)<u0W9swJO;*aCP<12g3u;hx
ze~z2~9UlQl=yC;X3HUA2ttS2qpujdUpjshl10)YX>ki~JL02lfn>4$ZxZJ)ez1yMN
zCwnxxP!5@{$<I8lafr6qvd`5AydzKqHYZ98QyNDJ8dZ<tE6rSpZRYsHB&b!bwmDB`
z=<*Itky}fj<uXP#MJ-<-aoTU8aaM-@)@?WWcqNxv22j$ZGS+P9w0An`<eAOlUiEza
zDaa5COFTHL(c{<mOOVfMG8v_tD1zVhU-=s2f=-n9%L`m{ETm&XY*}o4EXI@inNXc5
z55NS$2TczU2vAStX>4BmN{wUk^~czK4%FWJ!Iks2_pBg@_S7mwdxFspul%gW6LEt7
ziV!pY^;f1hp)f=ol~AG>&X`MN?JKH_PjKnCw*B5P0Xp|b`7k<l_SX!itE4We9o>V}
zW`KL#*U!&kQD-UozJ{nRJH%BHcf(4s4s!zqjSAxN5#<%<UrWRjE<@eA`#juHtf`4S
zD+5sY67_Ydad$c-oE8MDvDW)a-@dEb9EPN;evd$vrnwDXb5WBf55L1Fi&n2u2#4Jb
zr$SH@Abs6Q%8M~aWu36P{cX6$E=?JnkWUQ}+X6e7bb4Zv5@}cnEpO&5P4e0Fy@0&s
zZ@iQuEOBC%3zKuiPZ8#e_whUl(%6D+3XkGycy94EVLazVz`|_G!A=B2tQYs5l1(T`
z-|-g1<9Lh-m14d5@u>ImX$3K*mv53LDLsn-5>M4+dkoEkZnMUXKlBv(_vzm8%zDFI
zuw~3TR*{spD1fO*4qDxcKcaO+j)<?^GVE&@CJn`15MKh(sS)?qC~aaKra$IDM}9za
zM|#HCkSO?`uuzEtE@nNHYT%5qpZTlv=!B}F(;>J`V3rOOeTza}LSU3)XvLqCy>G6r
z$LY^e_uH}rXniG5cl8qF0W0iD>;$swpad!=Q$htrGQGc30!5=LMGNmhuh7U`FK!hk
z{ma2BM$4>>_41mVTvY_TssgPpYeMr1Gr$uCU&{Lw+TE}PXap5ES&p}~D-megG2i~|
z8!y@!ay}xqbF!G(YfT0{<7%nkr?GL@&grCYm>0iD<yMmg`p*Tg$w6ZdF>ZWxlSjma
z!{_n~-X2~&O(JGUw!$pH4hr1Z>WcwPE5apvkvIh{a4u+C7r&k;A?O>$+Qq&-IBp{v
zBYncJY|~PWvug|Y876#Ji<c;{BoLetSBG&%;XJ|8N4xf!&SXn&5T)VuQWY8iPFiE+
z_IoXlTG~wN1`NZUr%QTIMmaGr#$<4ojk78^vnkjGWRe$S;g+|oWFVRV(E9J3EZ$&^
zJ`*FEsMEoyXH)P{$%Sz>Tfwc&nI#{&-oYJMBc$1*CSsCs1|zV|Y-tLSe>f|XF+#L{
zBF*fF^nmZa(Y0y<Z@2Ae19O7Ct0Q$g_UY5^cp-J`c_Myk^)|sgSAgJT?l8(-7yC25
z_AUZnxA{-k?~ENVzXQN^{zRk>_ZBO#J{MCwvw;dAU)T9ZX<nN%`ltY7g83W=eCYrk
z#rFP$dIl=}Sqn794tIEjAv9pX^;XK|r`DVMcPAEP3-db1Ul6LS#-G&{`u&%GJD3M2
ztUN4N+r(eW4+j#Q7+5ZfohOhjjO!HtZD<eWUVCsnbO*6sLs*1lh!<kuCdk-pEnrAQ
zwA&!bogEUl9Zq4tJf;O0NRe|+;T6W6XqYnO>vn%D;2w<H8Z15MzDn<)_eG<Xj^TkP
z2*X%NJ>dd<%fL+#J&anJUU@_n=#`s<sH>5{RGn)h=3qxaD@Zf!O7r4q3-roqFny-+
zbBfW5j^*tnv!Z1`EDj%|fpSP6Cv+K;0jXbO9SFy7_ZxW2+AZ+241<ddQlBb+_Ja_g
zNo0+N@MJ;E{euui0;6g0T}|Lhb=SR0@ZYBpwDFV4PeQ9O*{Pm}AqeAj#-7Yc1x0|M
z+KE7YXpQ#4zcS!-bq00*;vg6>P)(mseITDQz_1v-tV2wK)5AxQyOzLrU=yx=c$5=M
zJJi4p83tyke5+ur83yhCmLQ*Uy{OXHt^U+YKmw+4d=v(^ARcJA<RApdigX4E{$b#<
z=b++pOnuNHAOt8(dP2h8e_%6+^n)M^jh}-wndEylHayRPM(+BstZtbvc7Yjx5nv2S
z!eSK<e1J%NPVAF{zfS}sgM{vlH~<fXX835J!F`ABQA7>JV$$gKMQ17lxkP7DJRO7N
z=<_Fan0A1IK4#px?BIL1W87Grp1ish>gk5K!nAS~)dzir8bP1wNKJjR3)JJ6+Zu=E
zcXrvD55~jyA`@x`*4%W>A<yeTNXO=xW+M^}v(r`GnhdU{aTyJq$`0&wW_AHQUCRqg
zJqc-9#g%S?mJ1(aEqF?Dg1Jf|$I;~l;U>gQlOcjd64yba#DxSKg>&}CqTIuVTL-QH
zBLzic0bfMr;{z(P{Vm?9cp!X0IzbA+JRAZg{X;snKznt7E{z<ZnX+a#kah-Frz~c`
zEhx%B@VF+4g>C|M;NT#!wfqrlF~JIYM!$25%MpQC(9`QZ(p|j&+$H{62YVl<{Okcv
zip}8qzqs~4AnSi|Z8j#B|02!Y{}+yB{s%(-7bea4|A)u^Z}?R=Vcaf=2}%6vGg7l8
zDm)BSnmkyg7#G90tdS7tF^&Y?7`uMwigzzUsT?+K;CZVuK5T!3kJC<v*b}kA(lNx)
zg=2?BKS=oahJ`2jz(BHLtNZV|Y_>Xd`ns*AqtymeWkukA5JD=uO|5smb1WhZP(q6V
z^RG*gjv8m$s>jn0MEPSiDOKH|p@6@7JYQ>aP||EyxH3n3?H8kurOz9DA_P6G*rO8|
znA_NJ*&TTmbB&=^SXLoZpS<IUMkkPWo8YPkDMgk5aaEou*^pN%-+e#gk3ep8c}>zR
zRzgBjWnuy7-0&z-6PktT;#^jl!+2Ji-Gmn=u@VvA+0-93;x*jL_u>mr1y||c{4R;k
zQ1cXQw&^@_N#~dppUD@k&WtXt!_t0Cj}Gc?z}Abe<RK1773C+EBV%X$?C!_*O@q0*
zj~{RrSqb9*-Lrq~#D6x8m6iR!d&c|^@c&;7{oly_Keh!iQ)go*O9vNwr+<L>f0-NP
z4Q;<|2XeAns+!`oVy0GxYOc!PkpBPFOBmW(+ISLC{kw|jpE~M)SK1hwe`EJ7|05~#
zZ|ed*GZPCF5j`6R3lTFXH|w{RftBSyRt9MoLmNwDVLNjhQzE8+wG(zW{>Mzg&BFDs
z;y>g2r%ccC|LQWko(5qk4Bzip^u{=2GW!7qz0;}DXrl4+x^4`5AuOd!jKALZv}1#9
zLP+RKX?xCj+nWcW&<dw!c~{u70?EKIL3;JY_Xo@4|J1na8WbVySV%?$p-&VDq3mZP
z4!8R90iV2qSx}~edS%)oz?lCsV_oZ~m2q7H9?iNfWCSq7bhA*9xMOZ=Knq)!?CjIl
zmvw79A<X<~=e}w|X_TNS4&O@i^>?i_`|kld!q>wikeX&hvf{1N?mf%5^J>^DQ{<(?
zw^qc9Fpuc|j{Rh|9fPw3!Kd&9t%q0-(I+T)0(=5QYTj#0B!|&i(=Xh<jfrwacRtuT
z<%vMp%LZeu2zvEclIU}?XV=VEGti^)%vjejF%jtmA&x8WmltOMa!^ZWmX)2glg5=N
z(dtvsKX04*nqc1e`a*Ikc`kD<5|zkPE{{1s=})>PfgPNi8hF1cLy1EOYc#i|UO%o_
zj5rg?h;J^2vZ$0TSk!dJQykKCvAWZ^$PnX>#x<5O(9obF4K&TULdJ)h)?~b)hHj|D
zP)l<%%8qtU=h0BpO75;j!#6PIuwRB9zNg8gH=cI}yW0gW_-cO($`u_FFHM7@Q_kZC
cyRR3hZSX}TfyVieU7g8uH99)FdAc3_0d__~>Hq)$

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_101-low_error.pdf
deleted file mode 100644
index 8c3dd640942f6580b83c934beb0b16b39ceba9a8..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67362
zcmV)&K#ad7P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAJC7wckEb}p_Mp;1iBd#N
z4Hyj=@SwYEW_Vz<(G4_q4%!~retU0`Yb|Q$ck^V`EflIM#e1|vq9}>t&!T;u@BjHH
zd;cG6=lS)Ye;)t+IDfQpKKIwJ|NlS!`>+4;|2V(?>;HY&*Z=eW-~Z+PzyIy{-~RXa
zADmzR=V9m9|N8aczbt+-|L^<f+<)AseT{Mc=<omk^UM2>`~71iyuSX^*MB&E+pYH>
z{r%VPZtch8j|kcAcO(73{_EHO^v}ngle@oK`_cTIZM?hBAKu1w+t)w;JpRZ3@=xbK
zt&jfme>wi$KiQA*Km7B5JO1Z?{*D2^9jMJ8W1C$xzn_~w&yVSMbt2&p-R}0|+CGK$
zA3DwP;~s761;QV?`5jyr`$_oMvH$sTU)}rrtHXXg*KgSW_nGg#{jhVN9SDDzosA#%
zJX<#qzVG%HzfVyn;Sb$zqbQ>r2!H4{Jq0TlAe(<v`un_ojNeHA`EQZ_?$@U%lkkVR
z_47lN(f&gx>z|@b!uQ?UGbzg1jf6jRyWfY~uv!2T{#8rxo>#NW?)O*k{^R`X9q@Jj
z{RL>Ve~K~*f0&)mPf;e}58d87`a_gS_(L~q`x%+d@4MJDC|JpU68^P2VBFr{qGj)`
zI)BIhf6ETA>;4dBwEr->X`iA@!XLW5|Nn<5lkkUb?WQQB8wh{sW=7G%5`geGcYvAy
zXn%bOef=BmfX6>28SU@qc3q!xjQ01P=DAC8wEl3<^k44z{x3Ki+k`yf*qJ3x|7xj!
z@6PKtLjP}4dY(_|ef|ZqyXk=>*mnojdqXT<RW}jdH~hc$92oC$`gq?LU*mm^`tKBx
zzr~XGejnQ~(foF9@1v~08CIP{__mw9&&~Cpt6x#R@A#I3wcodnqI}=cM=IadQIx;2
z4CZewaK2B2=lgZ|8>?Wm{UT;X`F@Jm^NXMr<@=7${8)IlzwOlCD$D267v=ko?{oBX
z?Thj^R-(Pni2nR>NBq5;vAuP`PjM^C_miBTPsE>JMftwt9s1+ekA&~LJ#S_8{8$Z9
zzU|n}Kh~b@zp)bC&L8vc<MHoS;%}*lz1uIsR+R6j_kQes3R_XW@A!UPey)5`zVG;c
z5`C_GQNHi^+@C8i!rxho=l!izR=!<}zjt-M-<Y4mR+Mk2xZbq>aR?XX`;PuZhyCg$
z<@=6v2J^O#qI}=+?t7<b{f%|-_X%u&-V=XIX?&hv1g$9FPHh=>J_JpK@4NN>%c>XU
z`;PAppQ~P!?>oNV`k$*_l)s}ojrVOh|F|dqp6>KkQ-2Y(qWnR$KlRX09rN||>kt1+
zrX17#r#12Q&dGVU`@Pe0_P<W~|6B9jj`8;6yxYAl)VB&)rpABw|B5emj{9!!ug<rw
zaIVk4x7C}se=Vr*&C`}9k}t4mO|WEH{^D(L(Uw;f$3tdO-eP?ODIa?vy(y`3fb#y=
zoAS{zyefmT-Xw3zTV{`6NNs?yo*LH~KmI|e;jU@4`9#;(*RhjapITbiqND|{D0oo^
z;r*W$p(YvQTBMrfTX^1-E57hascDbZ-u^w;w>UwMhZij(MHw4kdKg>s1P5jD?oD~K
z<=82{F{Z~0&tpJIX(I^5svyv^6`Zo*RR2LHn8VJaPbZ}npDg&)Ha@-Ca|B6zdbg~2
z6fN?{U`smjU=2!4Cic@o(wfctfFM_jLayWo+PKAoe8w%x82X`D)^UpqmMb<c$+zVa
zyeXy;#S)CUKFS{oj=xE+5e3KJ6w`=;onweMmh2lNc?437$i*KEzAXxQbmop5T|CMi
zuqfiunQR+PJUYRnCLW#OQR9X>!J=G+1Ed&`NpeoG$i%c|ka!<xV%Z4>oj>@q@1Y+-
zFpW6a<J_2wvgFTeTjn1xifO#-UvD-4-g*Uh-V}7ZQYaP$-L40Q#tTw<<>|c${mHHO
zCaseLuZ1K8Z+vng@Hh*5<=_toCw#K?o}<%RxCp_9HwD{yQR2fio-Inu+PNl60eOG#
zSfs|$hDgBVk(8WtSFanB?(B49&Nz!f3YIsnWEu<?0Soyi<P>QWT$G%m#Zn$Yh$a^D
zx-rR<OLE;<TCD!N9aB8FF1Aj*)}O6U%&2SiuRB^?!YilKc_1&s`bfWP31fK|g-e(Y
zf!43;6qD(+xh+a;?v8aof)s1iYvEIgSrjh(m0P(_w$=jmQ9X`m^3NwmKiG<&a|ud*
zYEdXCGk0D01I-+G-@4?$`_?7LtquRCEXMcT??+N%OZB$(O2+Hrz4EGA6be_~^^3BE
z>j+A)S{Ls%Fy3?P)M2Ktzv-~#r~Dm@6ntzC#dahs+g-h)MTvD7|8-!$Dc9O|?NX2A
z>!MVzU|+koUctULw_bThwYhc6(ao(}4o}+8<<Vjf`X*vt2S_mmSC5Y2`PM6kr@Q#-
zU|wFv2S~xazIDst^{rbhW^4Kwl(Uw5{zy_fRBG2lBWkvF%Mt0&zo3Y;JoNEHA#m;7
zy5)$@ty?lo8W}XaW{<9z3pczy>W0hPo~>Jq$VxD9FWX&H!<}n4#R*rgU0bhUk(F@Z
z?tD`kjyPPDR>FaM(Wb;3m!M643U{7KQ@hrMb_At51vjiNg!A3fWiW9snNEg@TgY4&
z`%D$*O+qWV(6=th1gY9fuZ_|7Y=s+aLO$m$&lvwaZv~US_9o;PrL)Z&UrkNuNK$^*
zwr=@Zcv#<rXyE9b7bbi1kWan&&9U=gkF<#`0<MLL1N(e<o8XDrPU!?QHML`r@H6qB
z*<t2~PpNnl=kF<@m^g6HOB;FOd_5%<GtY%Zscs=%C#7PAJS^^>DHTVO7JE-g1vL3Z
zfmFOHIZ6ITPOzk6-~v6R6V4Q(MIrm))H%CW4F}`dwFb+0xY~v%)^tpg3jNI2>>_Xl
zJX&OC2Qzhc%+6IbaKFb#q%F>lZ|L@b<9JcXlO8R+XJ(#f@4wMb$s@}YzOpDI+GI$|
zGr!rAW8sV?DO%)&;S<st;q|fSl3ZDQA|&ttp@+v<PlK6y(Xz;s9VeW~B_t>O%v1Br
zc`rvZ=a&YTay>6f8$qCu<i2@RR%<+|=h>r&!-!q92$<u@^L0@$$MJwkopT&eKNkr<
z9RC@7T(7C<(71Nv2AlM%7&pe=bY_hkjN%{U$aS8KJf9bZW4*Azrm<f6Y_mt2=D09?
zXqtGUtv1J-0T*^l3&}@YP-s^ed8#iGc>AWTal9$ndjCt3GV<<U6pn1<3*K&tO1|jc
z6de}B(M?y#$nCf&{H&*Fy-8@UCBFyu;&A-v;9eZ?s^5bGIC8h!9iKZu3g+K@P>g)P
zzX{Q5_zj&C1DosCIWZasrl)_t84Wg>B;@GyycpP1H=maSTj~xS-~cIv1&{Nj#1EG!
z7=E}!;lvN8BpgY~HKZt<SizIuKIL9}g*7@uC>TVtC?OAa>CxfX9hYtv&s)bXDWo2k
zrM;g3*tx#$oYm$9>yUjp`W-J*!@FTo@+z`R#|DC#EH(cFq+r!0dGXX|-;`{<|D`90
zL(VS=i{qyj3DSb6tX(n``NY`tAoYRh65TaEa&lJoJs%jG4iXP*)FO;*#=mnd6u{CX
z2cFunK^IL*j!mW{cZ^N9k0M`8uUter*rn&oo04Obk;yywCSAq*yQOo*Tf8Y2WuQHx
z)!57xJ<$sBgsQeEkbCH6N0LH3rxaSx(b$wii#PS6P)bjP=-g7XJT=ipqU_+Rm{MnY
zUXxZ<$DUWgtXFPd|6PLAZv+R0AoUBafmRM(7Yp9OHoI=ZJ~4LP6dhtSbyM`*(Kd9H
zcFZ`<Z}~%*^3aCDlhTH)s_g+~Zj>0&h!EH#2!=n&HEWpRm}tcczK?1C*I2`$+qGS3
z+cTWxNqX~eIHjb;gJBT{{~%i6d4|s{0+p+lZ+06ru{vIsivnS7sRAqtnAB1QSQLYu
zxD9Ypyln%V)b_!H(}onc=3rZ+-qEndFc@4f@AEeAo7TZIy#n$0Tom%D$0KJ^Adl_6
zmC6*@aF-0JcCCR6dI{hqYH1zJ85*L@r13S}9j<NGu!G)|fp)C9KYYkFXj=Yg4fEM%
zWk77HSNW~+ozcSB?7>;*dOuihYjcUH;aYHsD4wZ{GSCj*`z4*|P0HcR<Y<sW*DYY!
zi9UHGSO}q~ezGLpa0j@I6b79qt&%puH);_E-Nt3Lu$dydND$ul3pGDHxU4q7Ib9Wa
zw=T*+JC@q(t!j>M>7p>4;jTS^P+C)n+M>jgbefwCQGgx~Sc6EpR1a(TjC4?I_>3+O
zGi>OxcA8;I*#(Na>*6q+wJuczuh&K4fraPmo3vWz6U!rEKOd})g#DysNJl+ysE>Z4
z8FEp^(Gzmf<=i;KqPYnCRcO9FubVR^$hyQFZ`4KMZ^Y5K2sj_k8Ld1o&yjXj>$+CX
zl!ZmXLY=tBJEZ(f1J-IoYEE3xed>Zf^Q^P7ubxm)yPimAj~0aS#De3JNeV_c(aezz
zP1i6oy|Uvqy4svAE}CAx7d$_$OT_aDx(GScju+^n475W;I*<LM;|aP*Iod_Z_48<@
z#@MMTEkc|pGVU%)zE*q3aQg!dQTE<N$)8D9uXZw@_TT<YOfl7&q~r{_Q5Ge6&yDh?
zM62ceaQSo^gL(!GuCW=ov`9HWTpa!JoFeayMaU_dzJhZgY|1${+&10xsU9;t^&O~f
z4B77w>;j$k#$%CE&QE>Guw<t=1!YX8={F@><jILMzdd6AnTtw8^&-Ta8($0kP93W;
zTV)aAut?S804ZkOsN(heR-p7iJ2=&D2-Kp))^50fjyDOy(DElj5E}RCY6qJdZ=;S^
zsL3L}DESs>e3dLx%iqZv-b0-@!vVfcO)>SQMbQ*-E3~O8;+@+jrs(R#DSEUFqwP2k
z+oUAi9qb?aatHsp<vaZP)`mXJQ=$!gxv3MsY`JJdABU3KhQ1B8qB$QcJwyB!h2Mq_
z-dx{4)hj-I;lbHxjX4&Hof`ipSDN;jeo;C)=N;}hYrH)>eQAq?)xIbl^b{;gc7ilt
zln@;zcz9a+5)P2E6Zn7_5NlLAJN!aH!OuWRXc<4TWECzRYfYnZ2$qf<_-BH0@^9FS
zLVq!XAm<HDwCNPe*JTj!8!&7%nihJxHI5*0Fpa%97E>>d#q=p0=ox^r2)H^roCwxV
zEfh4(c4|C%nY5D&H6L|?gKm-73u`qW_JYXb!DtQ7(M4dN6q{p_vQzwb7}re4-OO_!
zC^@#7ZyBS3q)%MfCZ|k?P25bUA`IY*!odxF3xi9EILv6UUnKO37NkLrosJllpkQ>6
z2D@oh>99MSQJ+~9b{lB36PA`{WJB)U5u_0WZ2#HR30shcVY|^<e}8GLhV5sU28&0B
z>G+L&jcDU1(-Ur%YEvJNdcc>xNO3mUMJXJ(I*dNdK5lixSZR5+OM*#TtLe-hsXH1U
z8H*4{o+0035#pG{(_!&xOm@N?Xdy+?>1wkNxINMo6%<T?sso*7Z%Q;E7>IdU6r4GD
zO}{DGdjD&X^@G=h=?b8w(*|e4^da2|2!1i+>t|6`rz1!~Fm>WoOr0R-FjCs!M6mx&
zj^9N}c^q1v6T%f;{DEN6{nz6myV_Wov^E||${G5tPC3IgH_Bny@k|X$e%0}YT!G>T
z2q`7bee4&6gqKrytTzJ^x^ul9kFrI{6{pv_J6Bxy7ao+0f)(}n)%cfl{TSEM9h!l%
zE4z2Bg|ubb_pFlxo$Dw4Sy^LUOyIKXPIR2}rd!dCM^zUa3@fIK(qVcw*fP6wGk1z{
z=XRD`t#@u`-KL$}xku{;cXhWSiX|w?iVl-<ka92`{ttt<u6I24t&tTS`n^fx?{Gyf
z5_o}Ek|8^CwL`jTI_jN=^iCNVAJ44LQ<|RS-g!vtUhf^;;v>BG25vR&9K@Ih3A4Zh
z&zNJ~^Q~cWQg>PxK{=8H9>yP>kWNOrEK0I(qeKg9&>l)Cotul4>@3Qy3`ML;gRSR-
zvMg?klIsLz-Q-d4X<YnhC!?giw5i-k#EW(s6pbc}MKOGvl#z^*#zW&FC`Xc#QR%Vm
z&BZFV$tWy;<1XAOVf8VSD%F}8QIwX0frLO2`=q1;(xiYvvDqm0a8kJmX-nG(%oz<v
z(YB*B(#U-|_a3y=6yeqyQCoo7rN(hy;w6TEPO+{i92+(NbBKFj41E6^KTp>Hivs55
z_&PPTB9NC@>a%N3q_h&el#jDf@Nibax4%gqjVT`#310H^v=Tfp{j3d_Qh(Nd!^Swz
zt<`8u(dJqd2^C4(ehc0$3OSYAcu~M95>jD1@+eqM9$tBRG#XDf%GBAFM^1|@I~+;}
z2%m>pd&Yj4fx@#a#A*?El=bvoHkeCvZZ^2=akzrQ>%cK3IC@Drg2d|}Kh^3sz!X~D
z2A)4mWrvP~_COSLtF-6T>CZ(t#Xv5?DF%Y)cj`AsUU93bdol+@(}!-(M&pOki_~ta
zuN`Khc4H6nMqY%DiyX|lslW1SZ#Q>kdLxfT=wsIh-jq#WX!nqo0Y=f(LA~QmpjwjS
za`ga{?oFG)z^KhQTJzkMqeTg4iWI1Zyopk>8r<tt#DZYZy2ueD=Upr@sfF3;lv2nU
zpVA6B<5OB;nhzU|7}7@@Z5UEo+x4gy1R<l0Q|oOP;&n?cZWmP@8e!Un;18<T?V_SX
z1^i9<f`XnSqvDe~e7mMPV12LoRnLHxzQVuH)y&}3{WY<&SNIOV`dvJeCt5AvFIc{d
z%R6;MTwLSHnRIr-V$n*Whf}+_!V`0WW>l}QMk57ZXhC5oOo*!M)XJO`i>amI%ak*y
zmnjx!@|D78=b~gEIC<K9)Cn_~^)el3^IeJw%v*ip*f}CchMlkg^HMh~z~n<ETX>}0
z8tg=viXQZfgdSx09PGu>QX#rA+MzDE6IYfD`rwe9u09+rPv~2N?b+!;qtl*(({93q
zNm~iBXv&(xESj>oFo_0MnH-y8v(R=E*)%lxU~r~x92_p^FcC#=O<GD%@sb8^n3*EA
zCVOyrg9dIIs}?1cZ<@4Tky^uU;2r$`Wf@x(ehY#LXa4~k8%Q07IWUlR3YqE}A_B^s
z*I=hO%H-E*s*qi<(NrPZA#-%fyoel~^+P$WlnB}<Gd+h^P5cHVLUzuTo`X(YJh=H~
zFbzr?j+@5P*o#BK`v|t#BT3myH|Kz5TlXX*tz-sn!_;YHSV-jXz~Ic)I@Jy52$Fcp
zD9t1u8Lp2YjWTUFFVi-7K}!Y<<Sh*uGN3m{Oh{ST8>6I}t`>(PCu@CUNR%x4D_!TN
z7XX6mQ{4vIZET){#+WC07b2_Yln3GfiGB=zynG-0c=<l~?ecz%<dkpDl1B3eUVBMN
z--k|Zr|(0jv^RRJE;1ZPhx|K@aY}Lmtt6gnY<{9e$hE#0JQ#^SCtXcU@{unJNj~MR
zVwMm6S&`xsHb1$%7Ad)}v$NyvCEwXf;>iV|d#!bx#&W^64kNb?$9{qR^yD?Tsuv}1
zMOsYSLx1#}wD|@j$0vNI^dBxtdMfE;T!}r`C^uwFr}DA6Di<mJ@jAXb;&G5f6NIsO
zL>tW~={3!v(R*(E5`E`7mO6dsdbq&<OCRo$2|#e-@>>XwmLIsGfBK4pkisEv@*-fC
z(%?IULr&?)2#Vq8km)Df)LeZ$6nd%7@WZBmyfL~<{_{qoi=6Clid^t36)0t2Ui#J;
zLP1A<V}MuJLD8UGC?cSx$>rFB1|mIZ?12T$4$8oT)r$Clsi7i#D}xsfkdph1ZfH1&
zDgvU>0Mn-i3>SKC@gpfIQc$XJAXhjBQ-dmGW99hda1hqf8V?GEeKcH86&VtlLFXPl
z!mOVPIEkd6jKI)lYYd-|+R-w}GXq;zE5n-@`O;v<@l$%dVymP-D7H%4g5l<Hwlavv
z^s6^idByECySKQW21PaFepV|#pf@{IW&{r%AR$ypKaxwYAfz_|0ZNhZ6G1<)5jQ?m
z%(X4>{Hds?h9^`-MlA|Mt{}Ae=sOT%l@tYFHN1c;M62OxU13}eZ+L`y9U$dr^j3mx
zLNQ}+0>a5!8gnYztQn65*8|4z*i_Wo%JIpdCp|`Je^c~ZWCq1e;g=>yiGj$U&@&Wg
z*AQ>TNW9fXG#_7JC+tNE>06Xs9tr#jjZ{&A%oalAVEz!a4~7>m!aOVfaJ4(44LLd}
zsET4dR%TE{g)$j7l83fnNTd!`yd+bHDyA}0hhh^e=(3%R2$d>)G9pxZ?+GJ5<2xHn
zjECW86%EP>B1T6cq$^V>BSK{@qS0|E&$uz1Ysjv%!nqXCirk`#d2MNeR8(wa7v=n9
z2RUJ;Qh4p6WMHXle$ZYNp&L0zaiS}Tmq|wz=^IH$ek&GuwUcp6-d94=Js3!QfWqkG
zfi`20lP8f?H1>$)Maj@w2<oA<A`|q0(JHC<=#_Vqq2*NlBkv|cv!Ul7O1wcdcKi`T
z%U$1RXnBqpGmL2OmGu%DZH0p`QXKb;7mq}k3MXHwFJlWhkK~vb)lHArBIVFEnVV7N
zR0J0#N6shnqI5*g!*st$A%ueKU`|a1+(%AL#QdLVWxPLLu8WZJgn0gyF7x0oZp=7U
zIwb@w!q`#<jOM?BBUz-F;$<2>j&LO?EJ{pKNeqh;JM~furU5Yq=@3DIC5agmOwM6C
z#cGc&+rnr$R7Qp|KuT#F28@+T?J%I4RQiW0WJ)<A28@qNBtiPlmTY1Oqq-&<gIOvE
z2+2EYKuqPSd=~>;Mdid8uqco>bAXg9tBrL-n^gXd(MG8hoyhu$k0}n%E@t-dd0~vb
zQbLdcQlXND_>;&fI+7B<gRG;~&de$a7Jv&Xd5MFs1gFC?K1(T3WP%c>3;+U^TV;R@
zsQjzo?w+A#nf_l{T*i2<$on#yK$#Y{2=VvI99tA7oIw~EyQLJgkfs<2bcID2$Y8Sz
z$q$wFW(?y}X56CWY;TPmYO9j&EOX6|Ek}==42gV6*%JMj0L0|L*vsp~nLc=c6gic(
zHn5W^57A&Wtz1PzE_miL#*uO`*AWDyI%-%<)YK_H5k;)L%0;<GWnCJQyelztQF8da
z6PZg?37(6R!*`u6lL?yxt<0+A?YAgnOEZo0I{%&<YBIv`fergj+0t2!c3Y*qE($Ye
zAvUz+R_?4JZM)KIjmBN2;I11f`6M}*aDqQ~%@8roU?dKIB?2!>8(XHZ(Il*FVw*7P
zAmunIk)%y6%#@^kY7v>FZCb?GK#})+pdIP{%8fQ<Y3qVemNs>)xV2BEU>`}zFKKH}
zM@qQ%w(_)TxU<O9)^#xP+^&@IMapz=7iTh4d*I)hrCp-JEbXBy5GHKus4uB1%7C{t
zYFCc@BINvV031OI?1b|YD-(=L3HghVyp+;00VJWs{v)8Q&x8UP_>-LBEg7?z;Uo3~
zw@Cm4ixQ{}#2{FN1Z_CQec&$%%fKcPBTjZAV1z<MEusLMT>h&apOz1OQ4+19Y1M#k
zMAz_AWdUy_hpi!eFyS3mE5A(mhea71K!jz|_W=Zn)m*HW`_K?+SSS=rBh7Ep@M_2d
z2a?4BQbJYGdSV0EL4w4fYAe(X8$^wm41o=W*zXN}!{8neLWdz;yg)oGgBlCx;|S$D
ze&()DL*{~P=UAkDjw?CA9L+_D>#LAS-XuYnyh7&>HVEFtGElM*Pz=fCKuI}38nUTm
zJ4PZG1=1D^kYy2qDFSUd*88L>sCvC#5_zVnOCDkJ2w0}6ZwNB+<Oysx8TV}vw#T<_
z2|VLlw}g4|tyhA)$?U#fVTn95)Xl-Hp>Cc-oLi?5g971+_uYomWAL*SmQPSl+wgwk
z-53MB_$W0vV+uHEy*G1!B@w`~XeAK<?|EQKwL$QnXX}(uInUN9p_zD@3>>8bM>^td
z{5%_ilELpokflY~FqoL?SvXBWi4$F5PJEU(nRN}}t_2FUC}V?-TJ7Lx?+hyoQjFKp
z3KS{ddL)QcoevElQaNyB_ZI+`0STZGvS5Tr04)P9KmlwSB5nb~b$~Pqs4Gn!&%J?p
z(fA>}F9SkdL4qAY@|(C}_@f;B&0aX(g+6A8?k#jO8z-4hV`o@w*2jc%78Jh)gl32c
zE~qqva}9862S_n30It~}P+pw{xF%$<q%}#%Zby(3B2G%@I13(bS)^h{LXa~jCLW_z
z7A26i2t-H2R)N)-1B*y_c3}*Q?@Da|px;rzc#D*CoNS%8;p)M}R?vHkkW*G*yE#$u
zwEVt<{)H_szClB`!Q)uqfw1=-8^mB31>;N4)-6}@*}5epqE^}gDM`db!&eIvk@m+z
zO$^G|krfS45rAJjKw7MzO^#{E1>$I!asfRqN+L#fMlNO-X#kG<Q`R(tYqek}4PoO=
zrZWrp#ACy+G=NkT#$`~>9S76kq6JtcDTLEJKuFd|w{u|dm2nJ4VSsmn5}dh-Bep0x
zQN0K^%A?@~x8^DN%oBx(qwzx%1u$g(*(l@>F#QB;O5--8Ht<8iMB<|sL8^R4+7n~d
zAoB&o3d*rTwbHO&Xs$sycf{AC3`$O3sYfBl25G~VWm|SYpTeW1<dAZ4ez9_88r&$w
zs05?EH%5`NF)HzC?_yLEo{dp~Pg@&Pgj>T6J73}d(oazk!9iKPBZ%-$D7J*tt<Z=`
zO0;4_>O-L!7sYFmf<!*pl;VR@7KN)U%H8Xe3L#``AP`TVyXVFoQZ{a^A>Vq1iz2uU
zP5!<&Ng`$A*y7>+Y#ajtpk`c)=iC?q!X^f5K_A=202CU+C>f7!Vi1J3O*91TX`397
za_@4R5wZ3uxKHh~5v|%~Bf@M;aN^i{oZfitsOKN{*t6}i*qG10#bQ4{W9L<p_I(y5
zbM|c($Ha5(hYKhjuV$V%&$S&c!H9cfR!G%zZ_FYkne}G+6@k{KyCH<+dA7rN{kIjq
zU57C#br^?8^|FuP#9oo%bsDe5?5Ay~@tVzwIj_?=mTr;iwpw3V(d>0wt)J{=?7&Ub
z%i!TimszB`uI?Do*siNPMl`nT>W&eO?Yeq$M030D&lu6%Zg-0jUEA%RJi4~qeVL6H
zg)F+kkbAq#lOgwZnXjR({Ddy`BM$OKni^0r#Li7)=~lZjwVKF!(C~s6n}GuQQ8(MV
z1vAP-u|`tn3E--9#i>IpJA!mkX|(us-FR`1bVX-V0qjchqJp@Jn@CB>bH5{knTlpt
z<S~`et~g>UtesK7$5$$~K`AXaXFWev<8Ji?J)<Q(Iyu(M9FclpS9mK`^hM#b>%<&y
zJ)=_5KNgAas1tK!mz<$YnRrlig?jSQ(c77}lYCip#c1;B(iMKm=S^2+C0{_j3C)ww
zq(%C8O7*6L7_Y6a@J7DK79~0z`DR<GLDeUgNHK_f`t_!@&zE6uu4j~`<z$hnSI)uJ
zt6>guRp6Q05#)z=Y)|XM{?3i0DfP)2O!XO=c{TRubl;2*aO3sO`p~cl*VZi;VKY8N
zt855ydZgjuASw9$d>Rq@hvgxp<-_t25(CRa*(<tC4=`!;55q%jfX(ob%-xI+4w2ui
z4|!8|B8AWj(>L2g9=v_CJ*>UEasc5<hq<TszV*5CPpV6fuFMaP;dz-1^Nq4d>^3kw
zJwsu}>b=a91LLc!ISpdUntaJ<7MYdm7DJrdw_<hsrRUa|nXh^7#=G9@G>F3{(mqcb
z{BkV!)@d9;s6NT8XX_LrdA2^uEIoI|6&b4Jci!#YOB&(~TLg8;fw-h$z1F(h)+6jh
zOrTBD8i%*)5)APY1zeb$H3HY8moOwV7KH+i%dkumc>S$JVQwVcY+iaAY}1Rx{g+H!
z>B#K%fD=3%@=kJU=m)Iik><?9;R#Mm^$5XmDcrEbcfYnCsX8F#`X!4#v$9{Z`u8$j
zz%$UxbP>LT9$1s~CFIAStxtYj{%d$Cy8q(H=r9c(FE~4b!cKYj_o3?|JSKh6dlH`=
z(hw$4wfd0r8h#o6LBmI-;iYS*mjMIsWhCn#Acd?C+N<&b-4!!LKT{u)4fvuuPNwiH
z;Sg1f5WQM`NH*f(y`Tx`5yFXya3DF(7J)0~fp<{8xRB&BdB8gd(1e#9cmP&7K*|})
zd<9Qnuc#q-3;UqIF*&J2BcAq0P{{j%59!pvW4{mHBk9@fL)QqN|9vPVnjX?VrSYc|
zwWIPVy{yE#c*zS3K#bTy@YOC78Ixz`qJS|tkjjVxw{V|LBE}cNl*bDW<~}=G`5oD`
zXZ$yb3XYoDYl2X`%cK&1a8|mepFF@x27e?Dm05y<(7-<Rcz{Q~PsT#PY2WA6{Gg;x
z89USU->VD|!vp%%6@w50z_h#&$<!+X3qc8emNOKQ3w`PoNs~vPL_=gq#G+s@FoG-!
zV^NmorBEsaT@c;o#mJ0Az!{9*h(r3KC@`MmSR@3AK;yZz@ThOlFD-n;I;}QGg4)}c
zt_+l8AQ(_m@>le*k8qU06H)|AEG^4b9SUmcmyDkXeCZbhV?x?5sSb#p2?V4)w&qBf
zBz!6N%*9h60F@T@5@$Ry5*g1B=CdgDup<<xUwSk~uu$Say%bH<S^Jp*NByc*MpRzE
zYMCMb{}9{MuZo|+rK#AaG!Z2D)gDFFZ@nZCYSnLD5D3TWw-ku`RE5PC1GtXB<}$@}
z1-oxqcn}KKZ$2s!Ek+cum*T6AfC@WF3R$>y5=3O$YBT68pBlG>1Cecu!Z;O#zXggJ
z#)tdr9%$v1X#+x--6AmBt>dJ)b%jK{USO^<+AW0r)~SGizkbUm1j``6-1fjhBEG#8
zUAQRZ9WI)iRw4u`_B(%daBTFGBhs;#Nibp|iB$Jus29QPUW%s-#5=sLGUhT!96#=i
ziqOK``XfIIg2EO>{Kp0;OCo|q7lq-Hum?R<S`lly2>B32IBJ(+5h1G!FOU)xH$Vk)
z-A@7x?jf;9f)HZXIHt>ph=~NaVNM8vw+kY%D8Zxt=-NQ2SfDdLq~!Q@10WQ5p*-dk
z5iNWyV9Se?)yd1ehOlElwYLzO>=kZ=K&b`7NtPqRIgmOr=rocL&a<MV1M<^JnV?L@
z-sdATa6%Qeo!yj>fT-;N9Q}yw_KGuN__xa{hZyldF=b@;daJK?*I!&iz^4&=-=m4(
z_dF;3yuK=oec`A!{^w*SHxi@a7X>b9#!|T~dJL&|1tl@+-p|TE7~nzW7bAS%fjOcW
z{{WEX{04aNXohjY1m<k&^O;QG3|&I9frnL)$p`^htMr6mfhm9Y#KlAC+e&+IQ*ImP
zw%~KQhB-Hv<q$a*hcI?45yMUC2ceRBLUKeRhZk-JQa#)n#gf?|Uf>llaC!k#Ag#m;
zWdh@NQ)xWrr#R3ckirt}i-h2t5?rk%axp%O!WLfm3do`H!c)MQys#3GjI)rGneu|9
za2L>ldDiB|hdennG(E>>rl#lk%&h6<-g4px0LLtlppml!;gV5vB`>*MnqVe7EDF{W
zDN&087G0Q(Qg4t|wNR}2Gf3hl)U|T6;*an<H)f>NPo#HwCCcMpZn|EWOSVYphFr6S
z=Z$X2NApTpZ;*wI&dMLkkU_7ka#%PCFaA=7oL34tP|X9B9A^Pi?YuI^0~$Ti&2y~~
zWwj`ojF%GSO8!0?Oq{MTE+z|lrEMdja8W8vF}~zz#N@nH0wq?jRRSfJPeEPGhxAri
zl(E)FAjxA!xKEl+Z)937O53tAgTUcF#IR?wXRcGFRN}g66Rlh$<y0bL)GLR&N6@vy
zO3S3v)yB|~nCi0JB6~GJ`<W-3o4l#Q6LVm_a;A|d>y<N&Tv~732%YPGF%E&jRjaB1
z6J<N5$UIDB_C_HBe9AFPSO5=X2rt6LgyCF8Axt34*taa{k&{xMW(T&rZ%NS;;;f|T
zi8T{CM8Bf$0y&k(fOi@anOE&wmUNy2zGX?rT)hkT0k%z+csO24^Y$%GI-k%{8Uo$&
zdh@RR*rAPdXm<>`S_G!iuSd&jGl?D|(&Gn^)V_+DL&h9gjILlhWXH4M`AZ4(UP;qP
zvUep-JI;k(*>FhK_s*vZ6Z#j0C;=Vpq=$2X0<2d4DDd>XlBfYI-~th61eW&#Wk@~V
zyOQV}3YB-E2?6N9E44Zu_s;BU_`$swFvC<ACU66E!TYbk466zVKMp;j7cj$(UX_X(
zAP|c%&|(*U8#h5`Vrt}Gvew9pL0U%?Bq44Hg+nQ;aI?9r{Di$&ln-o-{2?Nln7R=g
z10teR1~42h=K!%f4i_dq@H`d)z$zV`blW0V(wXX=J{weGN!$>JRPh*sv&Ad-J6$Q>
zgD>!qtU@o4_<@{cS8g~^P!@sXnCdmq&W|W_7D<oZX__V|OO%wsuRt;A4_etnXBM0T
z-XAT{&9Mmz2X=l}2qv*+ywj3NJeoz}0-<_`S57(%@IgtLN${H}qyv!wIF2in6976#
zkO0<W>P563Q?L9BoEMeL4oi1XaOb39+bg>rW^C5}c@a8j)dxZ=I!Irc&Y=-m0^md}
zG4vvSkvlE1#5i)7N&^(6s8ocj8fIWu=qUh}f&%$Y3?>#qdI_RwQ7pshh~wmR5E1Gr
z3Mt`-@uqN{wlG_I#k3MuYLSR^^r%~Ig8-*mO%51Wg$u^wLXjDF9mru!jiOMwOfY4#
zOw>zYTJ8e60Nz$mh(VT`-y+3WPz}}P&?2&zSJFSwzZNB3<^TxuLID7Tn9B=BoH6&%
z_Y#JT#j##QDLayc&p3M!h76a3>)eM)Gbs2>>RX2^-j^_I?z#=GD_X!DgQDPt4~N~J
zkOavlY<J%Q;!^bVFiLCYB5(o^q$+QZ<0a@hSEMoF>0D)O2w@kLoD__U4#(d?Bs?$l
z17PL3;*|-g=fXp{xwLwj-N1BWxwMzC``j5{nfQKDV-54Xxwd-G!OC~I{EiF)bSH)!
zpa$J_f89g1++Knz^bCwUKw_8tiHVic?FNWMFVF_SC_2Ni4`D63(~6Q-MK4?jByqay
zX?b%a>rT88cD*Xry@U+u1qE^EF4m2Ca~JD{3b;x4(%ykd>CSr<u$5kT5@{cF*F}p;
zAnuB)BOs>BWlPXZCkh2%HQn_nczPD>%h4tb=b;*YFM)M>0apOf^OMpsT)=MT8GW!i
z;7e$t?lL$5anuU}1E{2*lsh*vLvV?A>T)_06ZMml{FBa*xT@}VF&#R+3vdtktnO4R
z9z6J52z*GzB;`mTSa+2?0Z{BGWn#R!kqJ2Ka*_j-_V|T#<J;q_ux<Bt&gT;z*BQ@W
z7`iUB5aR59QphO+<T^Qpm~!Izx)Vc?n7^MCG6smbQ;f*#f%w9%BnDy-e^Rde_zmve
znieTAXS=KH0!?Qh6fR{-(t=g~XlZmf+yTtI{YE>rO!#y&F|;UT=nZ*Dpy+K*z>+T3
z0NCz>K;{uc+qn^U64{590`$@+g$%{|CWiL0Q>LaxSZ%6CJLN<8XmeTZ<BOQzo3tWe
zY^P|$LF!xWx7-;A0m!$_(th1>Kr-Jcy|x$<3JH*2Bm$_{2|$$fIwb(az7rZ=PC9J}
z=<fK9_REn)RQONI;4yc66_k9Pg@l`TMbZ$HUMDDF>v_l?g0`<?m+@eASTi21PIQKY
z>BK*Tw9iX{Q2e?{h}XZ}HpKL=3kkUYM_pR13s6@bYX{VI$N~d(VX_FpkvA%f6x1cm
zLI!nFv)X~Ka>jEx^G#li=qi<f5nZJ=u+##I%Lb)O`^Y1U)(rtfv8qF<EUf%cDoyuN
za*{K?On%aeSX!b~CzhWm^@=4bN(1XuiAqgFsf$wOSPetk9;3HV_ZAc?jd(1v@J8v8
zS(<~2CM$Q8D%xqxkh&TLKyqwk!lO>ulH-)-2}TU+J*rqWfX!AaHtLnQkil5eq*Qg5
zJ&`ugkS%vP^cb{NF9HN@1tmN6dRX8~y&e{$Wi=VsJAspMy%VsSBZiy*!e6US$N&IV
zy^>geMh__#sHwLW!m;W(#yU4aIY3|^4*p^vtjM5#+qELpZ#$v-Sed7un5^DY?@(6w
zskbW20P!(<s8CQncryS?Z(;>t)w`JiSoO9>1*7AOPx6<_9M!Wu3nA6Jp0$$d?az8j
z9(GaIU`okTU4Yruivx7^;s9N}VD@7TC|NLABC4z$tRt015SE!LBMC}TrGW+lje1qE
zwt&KJ5Z?@_qREDZv0&6WKw=+^?PeDa?N%o;lV<IQ5Em%pRdy&=`YK};%Yl_a3t?Af
z^Fr9wZWv?bv9g|_I$0UmSimd|a4c{J16@`x%X6L?(4BS)+4)#Yjg~+ZTPsr`La;V-
zBI~u4$&p3f(j>{EZ)LG$VYoDE=D;8ailt_SIhsaUgRYFHtWziZ>XDV~$^gq^cV(qz
zLA<i$X34xV^`fZWZVyK3z0GKxL0M&1X8FD{J+s6g%+m)*X;#*aL^}qp+$<(ohHw@f
zq^bNsNkUi3J<ArBy`7~E%O;QNhh?@$fy9HxeULiL{rona960iCdN^F)ria7%P()G3
z%^R_bK9;wFMIp<h!LpI%^+0LKL!J?qpDe!#OH`I`g=H+u|AIo7n~w(7Fw2j_f|=#&
zVTe_^gR<;q`HK!#<t(ofOLwN%iKRWuE5(qi@>?OM>X2`XMMTT{g*v0<AY&=ga-y+X
zDLiclNV#Y_3?KU{Z`}%vN>=W5Q|YeD4gDC|uY>N%gJUbCifdylriyDrE=d-8J<4s#
zYOv+nWW`u{KT%Uw?om~pg$wlnsgKRg%JQ}4iCxug>8gFH`mMaVD3E(>9$!|`Ew3;u
z?YgpnvKDXomRYSA{^uMUWI;~qj-*Vwv3nK<E;l#p2A3;b#f8&X&g#SEOJ{vz7nC_l
z7?(dDRgRDH*|QXKx%C~GR^|H7^2rq(zyiw%AUM9N3UfsnpiJ`?iNI3M8LGg-&lSml
z;?Tzy?!cI{tTg|XRi?)lA;But6-L46vIw*|zEsUR2)SFG@l}e>Smm!Pcmvh35#aHq
z0@}wG1;Q%Z6)D0p+!am2YTgxuqH^CAsluAz70u!bf8ssQI^z`<gJR^z7CXbRErr*3
zR<o)A9L8f+lnx4`Gm<CRg_=i-_F;i_7vK_$uvdr>i?lP0=ujc|3NvD@cZMdh8oa9<
z3PY+Y!U<*Nk1Y&}mFFu`iq+{ANW}v76>P;{JSrl~QFEoDwj2djDzeK_ETzJ~9Hmf>
ziVq9ERQ#Bugb4%87PB*2scV`Li>eXmsAO8fY;F__3AQ4kcndiIv%SjaEmAH`{75@1
z<j%90M+M~}5^9Uw^9E#_3hxVPKKBqnN_>S0I*MsjEFt#Nu>~AD(5o^aakU%)jTl{1
z%p-@_74LYwcmz~Tq&J3b(w69rahs}h-(YEH0Op|+s-iUGU_19nP6xOZ!aak+xJ`Hl
z@(9hiP3W3DcQdNg8$&iHXE+tL${7NxpaNGH34yDe<+Vk=dX{)VbSwyi@v{dA$pf9|
z4BS#6ZrqxuF<KXt8x-VR^MbCh-?+uc9vaM>9`VDAf?QL?7#|>I5G><6LwyNG@x|#h
zEi#^&3Nb^TQ}@nj>Zwi>vEaN_`BbRz>Udy8Ff~jj`AA8UHg(?vx!2oiMYt>0+dE^u
z84$i+dzqG`i1Bz<#_;&6=KEA(=X}sIFr6;?j9foJndcte&L?<9!1LLTFnLfioc+||
zdE_oD+8$<w3dncwjM&eX0`@UyM?`o<{?nLJxdAlFD1CqyoJ=pE(I>MH4p1V|L>US+
zK~)xm`;ZDAE#^va;DZC38vRhZ1V<0)QO*S|g_W2A`{Pl`8#H5PZigecvvNO{eHF<e
z*#gg8R~~GIm1IK0a;2frhFz&Dw4U=RbtGwQIWX{ZRGJL^FqKQ=&I}#XmmW?~=et*m
z4uzB{IsmWqg?E6gA4h5^@`4VK;un-W<UqNq1S3y-qq345u~ST2@_{Imctq!XfDu=j
zPR^YEi?4r24!<&{oZ(fKR^<S}Q{I&``~KoP-I;H%TrD5WJ{vX7Oh3~xJD7f!Kk68p
zL}Pf4O`5|%5>X|eEmG!<NjjL{t`s&O%r?`lKL(lAH1C0KI%-zRIn(Q$>Euemb7qfU
zf}wOEa#b$hqJ&5>-OmSrUZxb&f#e$`2p&m_Ju_?dk(8!PLuX3(lt4h@nVon9DN{dn
zE5o!}d5(@$R~qV)l4*`K_xRXTCw(v{Q^yB0yOn~uD3O9WI5-G<rFQyc1}5$9i_*rH
zBDx4U+O&(TcIHyb3gXPtp1M$(rLA;ThXJ?JSr;W4)6p7xHmox%TPd@Sn)Q`d>l0aQ
z%Ek2wMD5Dh^{@d~POsw=%=&fMgexuB-y_=chF$sAQs9(tjr3zjy0u;`6M1gRVLlv2
z<VtjQrC3WBo48k$KJCGEn)I`sn}%7~t^{kH14^*gt%2pOWbZ`@^^*zVt{m%<1m;+m
zC?Lt&#RuF*W0Qr6eD#tA<jjqd1*kX7gLl}p>2^7ilpJhZuVkP!lX-nnG_a$UukRC;
z94o8e5wO=Wc4$<>1aN@66>flIhjxPFEYe-r1I`?5!4oV>!aYdez){fY(O-lx1{4s2
z=lM}s2@X?x;VJlhHoOH#gdji}4v_N8v%28Rc$P9rTi!-TtqB1{96?H$3CP8DZU7U`
zjBSBXcpj<%ssJJ0?}cXJIEoAL!kO4Dua#d!dZ0|e18@|&h6BgG5I7tWi~{Lcgye#4
zostVGapCYB2n}Qrk`K~OFPt^<sW?#cx)X)QFMvP@m&6epS=c4cJaWOCEJ}=r5GeUW
ziO+Ix-C{t3QdyMXkI+^e>E}XZSwDnyN@BJIB}b&2gBj_v_y^^=3mztaC`UB5ZiyH(
zwr+vbGPZ9eVhj!MhhHv4oAn1!qJ?_n7x8vvb3kE_0?%2LR5-ds1Io4_coro`*S20U
zx>kL1a3*_D{C6pp7l0_bgo0o@vJYGY+c~#RDeN>SFUr`!iyWF(0URyLH3|aB;p^F8
zk`^g}p!6WQaI6Yz$)V*H9+M+8A2!}2DZxycbRF7afj>FQmk=CkwR6BS&pK231#!J7
z2?jOPDYz?~D!;A`$I352ju+UK!#P!mSc{U-TYc-6<L_Iq6b7MhEmBSZZjMDr@GU}k
zElRMwZGCe5^!hph22^9!uX{ribHw)+;+VrxR;Xl)638V{eRj1H8%+-iL<AS~na9H+
zfzg~;1q4nzf|ST;bqwT9VRZ@+@lLOai|}@|-X!F~v7x>BMTk3DY!Hepz_=hh&xR?t
zC~XjS?f@m$$LfM8h&zf(;0poYE?UC~fd@)zG*-(_fV*0D;M>)r6W>mYPJBC6w_Bvx
zMMC!T8!$ye{&V;s3mq^he(w;1o|SP5W^fU5Y0s@!a^hrb4MtFgi?Sp`S<XRNLlGq6
zqQu548y^88PFf-E9Ki;*=m_*KKt?Bugg_gE62sA^zm33;IYC^kWsZZNwIC!N@#6(E
zxhRV*r{G|n*c8I6biB|D)6(IuE!;~_{0bps9zlrVNYlgHzc4l(WrYfd(*b)SsLn-5
zj3WVhg0z8tI)dN}7}Q~TSd@WwVv9b-ueL#rvPC`tHC}L~i;~!*^gAT@#!;}RByG^B
z4wFd1r+U^+Du7iHRJ?al5`0#-^bOQ|g1Ht!PB8ew0ScQ7*?=o69ZnRz@$Uw#+40db
z4K_}R!mkBs!?<;zj1&%TQLK0sFY?0EC8;oX9lra*<=rV=!(C{!tPA%+5oZF7Rv5uM
zW#~&GF8571t|DFA+(UwdTD((gq9Ii*Fm)6~+R@!N<m7D8H2R;u{=>2M`T73U_Y|)-
z-sJb`c3!u?57)2%`0u~|`<H#4@BhjF`=5Uv5-C`xe&$KL*sa(+hY6ycVnQ0d?4km5
z(3fk29_uwr>s&+zKA9;9sG~NYsjlebUxyX40wC~AwLz*#trrkT{K*h34Ah$i)N&L2
zG9N|@3xF`J#H`<eu-CRJe4GLO8x`MCoG72MLigv1cvl_9g05gvFQYO}M&_=pE99st
z^nH(>c82a(ppP^AvOKHEb(ZU@<9YCuO$jgYYk$Gy^WfR8f!LDkcn+4P5c#<8=5OKg
z{w&0V_kd4(ru{~S@*r=h3HMWaPSsD~L%PZj(YUHQbm?Tu<>Z|nVGB>zg=TP`zeT13
z>Z2;^E<(u|Gv&M?L~)5xfe3^wD#&Po#ZZn?!tKIMXa#PB>OuuXj=BtE$5(%H{}$eC
zqO1yr!C?McQUnAa+*-G?#7_Fos4DD2gvd)Gzi-ixCqo4l-|x)k;-S;C^4*dooG@_u
zEoUfvQIPVw%MftduTp&R67KTQ-<dG~Ax3{8DCe(&f?O<8e%p}}Hq;RmRU7>4j(DC?
z5PwP^Dbf5*M@q1<qbS$69Z`yug8nlN8y}+on~vNelO0Ks5B#q?VnEzTKf{3kv9*5F
zQ9E#|BPe(Kwj+u$ai9JSm+I%v{Y^)1@KYU0ncsC>{>l9u_!;p(pC`j_I^qCnw>t7j
z@ozi64?CVSKbOsYJ9U23VI53E9elgE{<=fFu6cI-47<dBmi?wv9C!$t`KbeNeAlU=
z>?04wpP3c6QGVMIb&&x`^z*AI^V^QFD)Z3&89C#h$MA1D;<QGL$j|Nk{&vF#<ji)c
z{}jGT9rM5G$lIW)BPsWH9arJV{nGfE^$<U<k>7OWW^r^BWuD)5yinvEchb))=Biuj
zHytPbtf?a@_qQFhfE(_-p8-a@-+{mB#4>#7g!c1oCzkBU+w^Cmn(x=^Z@RHK(v5Dq
zmHpdp{o|_sDfIrjynjE;__L;tq}<<kymwU~Cg>lO-*OW=1R~OYZdyhEwj;fAscHNy
z<XWm8zv)H=rLh|c_jlcBmx3DeGw~Qd6q~>9DE-IOk(BGZj*a=MP?LUUwaX91={FrK
zHi;cUQT*9ockJy$4g0yl`kdbhxAeDmsbd9ef7fwdA6nkefJFGz`~JEk)kCCD{M;1A
z@m<GA4BoWJpP5tpp;!K<Bh}BLj-bc`_tzc!{h_7)lq;$9*1zs3^|q@cDbKeZnFSJB
z@XrX%*tO!{bb{*K*=aEO<Qt9m^j*FFnQ?@>zWtkSmtsz{o7D9FT{pzVQ+NLv5n-R&
z{BJr^=^yIISVH@@<LDo6gP##m@cCN!O-DQ`P%G=__RR2aI})B6Z;zkp#`$=S{6?ea
zqh+ci9eVBiju&m3xfVdQ{o_+7{>az~?Q4H#Kj(U9zhBqyv--N%dwaO8+VcOxXSOJ1
zw?oy=OTJf8x?%zmpVh81!;vBr8)|)CWnm-bESqc;QNGTyP5sC!WwbM*Jm{1)jf8s}
zU6|$r76&GYRP|eh!XU|JQN}NAK0iBZs7)eu?Ic<jW8H}Lvk^v3I&SjG6Y|(d`~%Nw
zbW<NDrI--<$J~r`={0B-`GV-TMImPbAgOGOVfLGCvoVsws0!K-r)}2PusTkY{gv&_
z3VCJ)z#DE|SUl&s8(?F~r}zZQcs>oVgrSm+_7GOpX4)P1W`NByhGl+@_Sa@hX3>q!
z20gCLxE%{W<hiDCd(6$a9V<2}zKw?TF*bIlk~lV7cC1K6w$R2ueD{e2%ZJ=jbQO%g
z`9y-ndI^VHB1TkhC}=oslp6|VV25o^k>sC!I7M1HQDWl^1*XHV(#E;DNYZ5SY%Y=|
z@?Lv1qa}{!+N36px|}A#8?S9^0<{2_Kxn^9<4<tPFGbwJ;nbX47G=Zz+AKy_Rz4*w
zSwof^_MrQ#d2Lx1mernRUD+W~WLa6|L!@gi>${e>F8JWPi|@&buhlF0(6>$zvr1gU
zm;8xuO0@pL><P2FD$CMCjN-EgNXgy`e91qc{}eS$l|StlYM6TaLGO0fuWehOWTtI>
zl9#4FgXMV9PPUyoLg8v}er~SzV4IGH3uQ;C1;MLd1%!`q`&Wfwh6Shyu_H&d>J)p%
zvsNu*zfduvb%n(tM4>4gmSGH4H`!s=YRYX5N)|JoTen!DsLvd&6Xl!1mzm|APX=n_
z=oO}sKc@@f%JA&A#j~W}t!?ov17ojv7Q}g1wd$~3j=i3>r^4B`c$NX?E1)GsegVEp
zxEuqnpq6x2v<hm0#c~U3aSZvau#qTEULh^4P5x|sLiV?y7S<-0x8Z_yzUq#zXrQ)*
zv{YSkc0pZoIkzv?CBG`<fQ8Agtyjpx7SaNBpv~=DIlQSW6}39r7Sw`!SGC<E=xVgB
z{`;cD5cB3Zl9FTet=HH}%|{H_b8qG7J>Mi%vfeLxgj?Tw#rjr8AX400lcsRt{%Lg<
zAOgKL+qxykZ0nW-vaMTk?A&?<r<yDl48L2H3hav!SxE-Yek;j1F(P}mZZRUew{9^a
zySHvJB4g~s1u&R}zpY+@#?4?<6#rJ-OO~K%74-sbbx{}!IO*q6m)MA=xHlBP32<?E
zw_tQK9u)CT3CS^6w;O!WVKGr~+jLk!GhXQE*~&}a`qrhTag7nID2i<vGJWBz6*G;y
z!kV(CHopQxh~eR_Aef2k!1Msfu=AENFd2{g4?aD4iscwWfNl7W<xP%NJk#BIFi^Ku
zj@rD0#{W`~Z>w+?1Om4TXPL-ZU6!1RF^(Bj1{ySfI%!`DR&JGIHh~=cCZU<buQh{5
z>6Ge#Na|J*F7MYu%jlNmw_^fbyv&~q6BfQ3=j+MPB}9EURj&xgQb^s|#HRdU(;J-u
z<za|MI~k>2Jv$kt(;ld+twLfD-QG?f_ke1(M~WmKD~CN&B@sk#j{=(Te&MI{%v;9p
zDT+l8CAK>P`B~88r4WBps0`3&7lC32yZciKxhU^uk8Xfz_!vW<E&k2Ho%o7E+a?Yv
ztH7B^4_Ix^FAt<Q1+6ftKb0tx>{=A=JwV^sBVj=e_f_{qIT;?k^rpz10(<HSk7t%W
zx(QGneo-o4WJDDf=7-#1i2~xYG~vNgEkU|4WI21sg%K-|X29Y2C@4OY6OOD4bMlAQ
zm~UF*93>l3Uj~#39|Yq{!X<XATu7w%tdHM{c7&tQWNv4igR$<91K!z?cy}ZzB%}gz
zfVC8bcrf(=mxvAwWHlHtMUNygzJwfexnMY;)by4C90Q7_U2QgFeo@uvVV+j(ja%XH
zD2r;9OowW#Zwgv;)goLKMP98k=};J!m7QK;ip`-(6-Z=n!)x<MO3vEEb8M!Yt^Cyz
zh!ekB0+FS&>{jMKz`N{HP#xZ>6-DH53){uFC@K^mZwmhVr(c^%dv@u40oX9RDt_Tq
z(XS(ab4~cV>l-;R#m{Cgp(>6gB?rdfyo11xc1fauy=a#tDk6I9l02o8$}UCgC2-&>
z%oeW?q)Xbx*R5Rp3b_R8o?VKn#*-Sg-7@nu?IU*S9h%T@cIncJ1Q3(0m2h-XdJY;4
zFy*p3-Rq0Eady#Yl_>ivdY6<Ooz#!a6FIVa-os4U9G#>xf!OSlQ08+vs`iPHW2p#S
zSpDr%7MC;Z0a;vlrkj%d9RAZQB61zDI5r=RHWhc9(r5rTW>Xps9@#c^YI(~#icCk&
z9W`a=iYK>C1%G;OEGrAA=V@z`u_Xu5y;vslmC#-Iqe{At2~HVN@G`flT2PJ}5-4o>
zN*u13<U}iYG7+{9kCsinZ#t&NDxFD6uIQ@6%iPNB*)RN!bk`0DW1CWh`jxdy@dp`J
zSgCFu2g}eVLl~W<36Qz_@u5M`!pP=db7CSJYLB4i@=GW=rnI#qKyM;|QMNsR+*l>4
z0q2wzs$YK*u@*5dvARR%+?bPcTw4nJ(0*92#B_IK^vIlJ?eAB(eUcB-&szr{py@SS
zAoP|mLh_(?Ov@3mc6w4`#|)`{4VTDJkZglSmWOlx5Mnu8Z#+CCqYk~3vgYmDNzLSB
ze}(@m)MIltV-1xN2gn#Jn<E~S=7sPA&B^bA7QxXi*yu%x;S2RNz(&rb5LzV8Y2>)S
z5@#j`AJ`U1tgtdwqTG`S3e-^&%7pV7*eP+zS85$fOPLTk9k~`JyiMZ67<27x#=lYV
z%2ChC%D9QBR;%<ogB~O3dPnBPq7bJ7KrmJrdG9Buxr9FvUd$!?NW3s1MtWBHI)cO*
zLc#?87#{Wb4qrBwjRNV3&otTCQL@aOt|)_MPQ#_)7<8#821UY6o6z2Oz916=SS5yq
zi{Zp|?y{5vR>jJ)c>);QR6b)lVM7o)vH;E$DHBBDqJ;QWU}OTKn5u>ZAWF0$IS4&4
z0Sr3a<|a5nBA^%({f-1di3n?DgPtQ=gqO;bc~P)j$jPv-NAt;G*&cF^LVzY{z(pC+
zCfXF1xAQ7FvAV3il%yP(ggpL00*;!8i$V?<1}2sIG!9H!&WY<V4X?=6Fy#@haKIZ;
zeL$_l!*o#+aHQj5YMok7kKYj3>T_c~Y4PtUBDp97J*cr25??+{t$_IOFnv?d3W4r|
zKYbX+-UK)Mk8#cq-Z|Yg7zWiNZXCETM!>v7z%SN?Ci-COcS9@oPCxaT)U-OiNC6EK
zT2Tj5=mV{)pPFz79|a8h;OXBU{Vwj2_S776uQvgDKADDVG7xtLDz<E4&6~o#pGcXq
zCX{p3AvKwhJ1Qtx6JX~J1z$$x&Jw5A1l)}`s1;&fzCwcnsKmS!nh-h>pJeUgvAReh
zLX9ZbcdBpJgvoioRh}k1P6R+(Q;7BrsFp<{R^mv`2`}%4p4|kuc@J<-kkI-1v?f0&
z!CMxIGr*P?W?l~;zBS=8!@+G$kU|}9Wov?A4o9vDLXXfb)(EhS=Vrxl_Iz(1LE@)V
zV`#2#pI8%tC&M9VO*=RpdDi4k>u|{#LuEP=T1?n`f!-3+2D&B+K(96&{~h6MCgXdD
zb8k`b?ThO#sN;*v&&Y~^YsqdxHomTCL0(a4#*~@bnZnW<@nvT;a6@*unBF9`@~@fQ
z-ec8`lgB;K1iX1U<qPKs9)TuszXj34PC~flM~E!j*@?Ki*+T~l-h0MCCjz)E0!L!%
zG?G`QKIDa|6Gn2X4`c#<0&BwRya3H$@<DVw@q&`Vg@W~4LJ}}sOn!<LoRmtc372@@
z>IP;Zg308|=&*~MB3}EXea!d=*+n3ruxK0M3_GmXW=iG&iiTNL?3hEnIJ}{59Nthj
z4$svKmv)D_`AtGAyXY+ZOuE5~ZW}Br&hDe_9BH(gdT^jn6SjfEG-WsMYrwsj5F9)3
zVa#-H169V9{oE1u8lxw&bsiD~dF-^ynkpgC2rJhSa9kDv2KY`3s|g;J8EU372N@%4
zCcIRHf}835A8=g0NodAdDVJ2Iq0|J?Jn&2~RxlV-op`$fC&`q)oiHv207`<mn5j0w
zaD>_m#hExxi^TD}x?v6QK&}jcj^G!QhpdmzG%P_qXDz_WROomBFN#q3Q|yHOjOVUZ
zdU;3ebCA$xCr;~BCrB3FvPQ_v_fnqG!W{8vH4|L4<AM;TW(NkD$(`37R_aB<9AV!R
z>}E%qk3~^|g_JWIPI}hEFmu|xJ8D^&(Kyka>#w`gDF7-yK<k{z*N}KEW(Ym$P6=>L
zoD!f5HeZNI$){9zW_(160zCg#;s_^=o4{0|0JTAlD52dOk3VVF-qfp-)z}NyG#~>P
zg^b7^c{~7w&`dQ9@SZbyM~TB?!XqUPizQ-f6iVT~<}<c;?rY^C_8a`x<qt4-3%~1X
z<y+Wj^;vPI$z19EfKRU!pWdP56S5$XQ^Me_Nc2TYP8Ed*xG=jr&u^&}z!Hxig3KVc
z#7vq7VoN?L69Xa#4JLS_I?`e5*$Ia6K(O$>2nxo0BDslL%$EKO9=Asf1CMFh`=D$&
zQb!Q@Gs(er>sLhJk3jZl{o5!RK(+B07}%c_tpf%O)$N0Vi%<&zWYkXzc|6c=V{0-~
zTA-pGaU|PXB9dfVxzJ@l+hh!1hk&8o78mFzW<*sW*2yR3+?V_4_Gn5e05rsv00d0%
zXIrbC>@?Ks_#}OFO1Rul0tc5L2Ih1UvWVGLBAw$uFS3_}DF!ohb{01?geP(r@XKK6
zIf|j6xI_)ha=JJS&tpGbEY2Z!PKr%V3F2{f@tc%JHB^FjHcecVU06>m(G-QdA8`o_
z@#6X18Rw~m%*{hX3kk%;*tTGTV$?AQP>c^s?a4eGiH%{VYNgLjm7z$N?i%EBKbLL|
zQl@T=JVpWwV;}`Q1*-uZA7_3Ncu|1hzuXgx!g~VuX@jjq_e~{3)^M=8HJZ9F@qS(;
zPJ-jB3lpdTG@sM}tuDKKqPEBCw!?T%&BDRLQ?rPl0Z49LvMsG6$95Apc<Af44)_ZU
z2Z{D~n9OzOHxz(?UXYbI5jY_5@OI~^;P^MS5%BJwrHx>0llrL2c;CD+S>KhW5L12E
zn-`|)y8_krFhC9ko(7bqfsgx_2^_uMeBrn_z{}HN$ZdC%ZbzOpDR&Ta1dPA+NVEoY
zRZcL$kj+&7l{OD)rwt*`rr5G}b5pANYdY2Qhp_S&6N3j@1{D`mytpS-`}Mk|#$$>X
zFG?!y?Yh(pQ@pNUl>c@yw^)^5T1NENBcfe=-l|mj#pkU`z0%Hs7t4{Pjz<osIn)g+
zNsEW6yzAxaB?u0WCTGRvRw>tu%dJwbSJRsj@_NC1Yo=nY7hkok%zBx6aaN|6CZsc~
z7{${wnN?3(u2ns0A&!?`w3xzt^v=A&EYw}9r*WIy*s6{?sr#z(>7?#^1JjVHIrUU$
zYEC`p8v_68$<NG1nFNl^&Ox`lOlD@ltA6@KQnJcCtW=!r@@T{(Ou#A*(I)R@1dX)G
zYgr}LBe*W?I%u&2o?I&rhh4zn+0ljk?dk*(nFz-TWVhAIqpHz^)PO`Q+f}8&?}gOU
z0)C2-X}Ld4F}6(BF~Q6+S;tz{Qa|-A3=e^3hY7FlFOX0GJ1lcy8#u-bbBEzyO(2Pj
z<gj~Us_@U7f{q&?m#wMrIlySGNv~ZbcEenS8$gw$r4>U4)kZr8jjl)L?0i^e7iDa=
z+eRx!)Ac?&EYi9vM^E2^YM76%P8>^9Cyu7!Ly*@|mT%bB+9=yMM}vDn<zp6w-EtYu
zPkVXh`LNT)zhNINIo$D<(#E(Z;V)*2&#_tend4(kRl}WL4;2ZAQKQj=*I?8*OkwiG
zM6sqzz-jhYy>A93H5T`FTE44zH=~dgrT?a+BLtrw>VgGun!j~Wr)&J!TrSM}kyoan
zW}~Un5%Ydb)sR}&R}6O#N<h>0A$ZM(N{H6-H+UlGFlF>mQ$=Wcx~=K#bP5PT{xV0$
zSP-f?rQ_C0Q$8MDv5XFqGp#vXBRU2<<pT#HO(Bh^-qAWeBXs07VA5JY(MlI7&F`(#
zMM_`#oAQ>8t`m)sL2@xR_@u)Ni7rqXI-#mshu_?^k7zyVrVmYdJNd0aZzow9W#g>l
ze2Yx{^c<VM<ih`exWKDy%&Tb~PSU3D^gIkr$v6!L7h`3$1_!Yzfv2G`n<?kN0krEd
z<^3#DGDim!24*S`*HBl@R6?$WPuMuDB+x_7g*pYE#!o?HP~HyNJ*H%)W2Nro;xo9U
zp}unZ;TvSjRC=#9I8nMzl$N0n<?wH`$gt{Pqd`V70}X{;5Lf_8#v&jThS@%*qJ)Lp
zBF*m~kiHgW@>6)$H5@vT0oHKN#g{M^yfC^BC6o^{0tQ5)&yk@O_zdhbLR~I=n#_o7
zjc#@6bd7Fx)q;MLG7JPPz%x+@(5+EebePbhBkY>i0C{O$dKRO#y0j`d<*W;G3`&Z1
zodoFwJ0eI1UxUxfTzeZXE%Q^|aHF{N5X<l$Y60n%G1XRW@VS_h7aPq-s^Z!dOVy~R
z+Ek<wN5@#IreB`X;;%B8O8e0Ur>Om?Xezv*6-y<pK%rDLi8G(aytIIbuF`$a=qf!w
zVGA(TF>VT_($+HMSetTP8;n}!de*^I8Zl;=079&$SQlqSARZoQ8=~3BxKj~toFn8z
zb+#LDZmr<v8w$6XfD0RNs?2q(qT-ba#ePvD*6z;65%GL^?w*LK7ApRtFisFlimV}1
zx^e>$uCRfUluM+$kda#cXk@T02|FZmi9&@QCz=C+kQm;~a8+%Gb4Ck1L*YFe)X9%U
zGDK}+1y9^Qf}&)qkqt>dBe#?-el%JYRrp|~5`|n2>Cz`on86zfMF?$lv{FxE$%U0!
z#PC*5DAd~_Q9oPGSo$u4Xej{+cR^&MBxG!^YrP<CLuxC{kYfnk@MM&)EF34i{DYEi
zjQA3AoS{ghA!+1Dl7W<qx)O_$PkhJ!1^D9w<rT=G@k3WMb2P}+S!h@sOh;^X({JF6
zoxV}hFsaaLdn$mtC>f5OZd*fDRAbQ>rq9?^{%hpRJQ<OWDW!F8@}4k+E=_8fZ$bvJ
z=XBCimyz(`<&6jZWU7TRl4<gah-8`wHs_ld$uviV++#xbR8T(9S8v#UF7A{?$+-L+
zEIcL`D}_b=&6AXYHqr%7_K0+Wruk<JtCjGqnS;Rj!=rL(y=W37PD*CyoJrxx85?(X
z4IQB}m!lQpemPgG=g4@_ujCy=2KMWS%$!VO7-Bqf=B}aP!xnrM?kp?|$VQJJf~E12
zBms89R17L|e4?G;xrn#Au4tTGxl24^w#_9uVYbaJ9#ystK5_v}IRL>Pk|Mo>4dwwQ
zi!Nr{@FW(f9j%(L%;s5NzG+?I&sWZoF+l4!v@%bO=&TpiDyBLmDHG6m)Ecds%9yeX
zd2CIeNzLQPJS=1UmP(wF;dXa@Coc+BN;4WeZylY6k`JbuYg})okrig2AZbw)0%*r^
zP+hQ~+*31vzww^iFK4zHMFDj!){c%Hw3csZ%fBSDivsCDZc&^aU<|G);$SnG=*UA0
z-SAAhb*><x-kwuG%|y~uKi%LQdbH<hSrtyWC3w*y@Rykb+R@7V&(0^rI&bXh`YcmG
zyFLr8N08?{#TI3toetl}H85yFkG3>zvk&z)%QW=JEY07At@f~IqM50(jQBK~ZUy~r
z3|CW$NFL}GWh4(!m?{g2nVA%-Ej^hOsx6HIMsY1>`^Z}}r#G1nswJJ+MUR#=fSTeu
z#_X8#eI96L!t|-x<s9PP$0+i`rgD&!%$YU>ZWy4Qn(+P?B|pSqNP|hasUGLLee+xC
zfjt%>Kh?yPQR&$j&iIiz-Pl3O0!N68r4{=4qGlE(scx^-14c{r4g(=lu;8MR1g`p~
zrZjLJ{mKHLXk`XCohF8QYl}jj^aO`FOHP3H#agb5kc=!b0bGWPN<@~{(#}HR#smP4
zao*|%d?{6_HAMauA^;#n*E`@qGpG1S!hqmp=hh{rsgk>fV8KPXAPm60P%&Ra_+UX8
zSO8-+)(AG_h!+lmO(I;#$-hYX?WT1j!bMlN#4?g^)-rc|0aNs?*8r}=`geZVw+=aH
z*FvB8ZVD+v77Jm*VBl|Z;4Ml{m{wRrdAcU2TKrG~J4ir&#Wf!Uyr2cdG8VEi{4n(5
z07;ND%m(2uE_J#AJaMtt4cLi$>oh~A?B05XD4Mhf6vu0F0WC^0>)CoGGLsxQhD7$J
zuwa8HqsjeZsIu4OSus?2Jes^F25(1Gc(ehKtf^!=>kqWX|DG^1g4{s5qD(kRNgSDu
zR*pm>1VpnY??YhmF7OpcBNj<MghgqIF;jmZM_=yoG1HQTKSowSlUd*3dTGiaU_xb6
z-hm;FzR4nQgUChg+PdY?uB}^35TELm94b*5(Sjp@ufx_#3;<iyN(^v*wh{y27PW_`
z!XRu>^+`ymbL-RcPavfZP$iusSpfA25<BGsxY4d`a3?hxku7unn{3AMiuOcnO85Gr
z5C^I{C5BbsdL;}LO}%)ox2{UO2B?6h+$W}^hHaa@!WNDL6}hQt9Y;HXtmx7)6qgMn
zJ5~U7So&0_5v}S$04@M386XK32{%Nd3b(F%1sDa(kI?wDId<GC%R<qFwEIfK$dj03
z=z*hOCH5>q4VtR(8LRL%rTiJZa80($%%yG4|C(@Uw*9>-0zhXUK-1$lV<Jj!49b}>
zZ4}~!d806%`BZAkskA}dJn9vLz<E+DU|?!qtIgZSy?W)`#@1^@yZR6%j}n4Q$yEai
zmagVpaAM@ulAoBf>aPr3TeA3t^{go$mpQ|YM!q17CePzb7P#gN1BkTZxR;&SGR!n?
z$~ZP>;hJab_5mTj2zgHoy#YPzz;JXaWo<O}z%8blqd{4t%fh4wNK4#?o`8UYXrpUz
zfO;B^R;<s^>AfiF%7&<@Mvb&XAc!wY*JxwO1{^6tIAeZQr6d8PR0`IB+t|t^=D;LW
zmOV16gEBb7gvZpwAv#DEgin|?dtS=GZbSQ)@Q{rqa%lu^LmStx<YX=3MR-!O7I!w`
zd0tBGZc~47Ch9493skD9`#NALn~DZU`v^kUSQDwXiAey&5?TSx+!-qJ*{0b7Uhp=3
zV^m<y`o^bNj<OSqGT_>PjXfyECsK-0i90(tPQ{wB9`v!1uKa@t(-D`VMGiq>DVrip
z|83SSy^$b)P-@DKxKSv7c-c(^sB9$F=eEQvX_qVjBy6>ILJY3Ggj1domx(8MGG0wQ
zA*Hjmcy>wa62<pPhV)!slT5<crZl2`>sLm^!PU@GNfO2koh?<_3!QE~0MMS>M?x&_
zL7%^>R@H$3!rmza@UG2H%BAZSparc=IilR#6hi#(dz(R0a3mkwq@HaOK~c>$OiN%=
zY}+Pg2~eiuZelnKz-g7r_Ons^W9^SBHYb^Rx^`nxJ_WCAKqN4WT*CVJ#+#7w$2Z<2
zWo)Y(Tjd#bY+;L~$){TThJ5CBWX0B1H9+k6y=0&c0b-@;oKWRKoi3_Q$RjCDJRir_
z^Xz9GC?98?N+j}pR2juXhiKJW%yYNOG4ibLWx>H&-cQ>Ow%FHI`Vp5xm50RDvK5fz
z^;1PAc|{#niPGXjzTKvFwyl~aFUG2P$;%T}F?lrxvisaF&mM!BbytEnQj-E1stR--
z)Cj7Ir$HZ5rBA95RScABMimT&a<W$yr3O=lN2%mwVN!#ZRfS8bC84<K0aEbBYM-Lq
zcv)8*wP3YNQGJ{lK1Y(CtjOw8(LzS7c4-!et!ow~%8l3TKNN>GM=4m}`rN0f#4MH0
zDnV<`La?JAE35=t72jA1cIfSq(yfxXP?0;WDTnmvuFzrX+Fe1wsf|~CUh3;r!xuXJ
zvDNvtz*MVRz<L{Gtzf#DtCFw{R2t5hXCMJZy%|10KFZU963d}DQa+P9a={P2rGoPD
z-0ID?=T?lYwe9s3qf;9Ev0imusq=jHb%kgW5ou94;n2!EEFdVO-n^_VsH48wKv>3+
zPs<#6*+E*4d~6*;dFz`Q1Vz=`+@Al*$ufhaxc1EolKF+bU0bgl@Kr{G9PYin|8uza
z)+vX4Z&rgVYlT;**x>Eip8q-Gr;HjgV3w&lWasD#)Pp6YD=JR~iatysSs=Z-L`X{S
zwsnd#smp@~%T3=*AuPPEO+TR2tRzKt8yH~OLPid-Z@qGWzI7VW2Cq<QeY1lM3~y{*
zf_<`upwN0B^3t+2N!J;V1ne$bNNQC~`b<hJu42M$K(pxx0W;uVc47E1OrZ<<CnzyR
zUDpU)h_qE)L3p@T1r(Yndw;fW$t&5}Ve4F3vwHC3_Vsh?79;X=>lP#Ok_yy8ub3{H
zXuDe(e`7%2wqC&?FR{QK2&|~%izegled`sgwV6zCf0fAuca@<04;Zk!>#m0tynCG#
zaqW1O?tH+CIx8OBtv<F+`R(+^-~#dT+TptJ^4j5c@asTxL=HIJHz@Bdv@-Y>m`VPU
z`=R?Sn?8ILy-X+oyJgz?OU{nYIuGd#>8b<)cgYbX`h0MVGvbMEmoB`xaMmnlk8|_*
zEM5=O#foQj2UeW{7Pu?I$p9VPhYpRI&bW>v{S~Nz(WI9MC$5n9=(FlWq5;2FAM(-x
zd9|vq!e2)Cgx6P<`IX^w=D|3y*C&p}p<*+J=X@^<3Y>d=5I=$rz(tYEFh2z6#Y>Sv
zi^M6U_;poLNmpba{C9pucm70NYadeg<`m+^OQA-<#7IJXVaop=u}3}S>;NG?GfgZ>
z-L_9I=@tJjA8~%8mh;L>x=-zPqzo+z_;KMY<yV7RKg+QOUiDdyH5@h5(Tc@UK^{Xw
zQ^1~_{E@Y#rq=|a5m#guEEpZInBkFM!Zk}ypt-`s{5ljG)m3xIVB}a7L|UAJe|crB
zKy;85<~qqJodB?k^r<5NkyCy0X#hJ(S7D`yc37^pUQu3YJLy6)wF`>eq?*8jSeG=!
zD_c~sE~sQG0!3KYDl*L=t1eSb)<@{5Iq*6J7~8LkyTNY0D((i_(j|dGnTLKsU=D_1
z5sWDRCKyo`ovb;Lm`2VxmFy+(PhjT;iBTK_-SiklDdB#}+H$eLc6nD(KO|6{PKNqq
zH@yb0*j~a7HdI9E7Y~LD5Bq+}_y!ayf>0%8M4R8i?zv=dMctT%cEytzK~alDrs7_{
zBm>wkcga9*m-{4;fB`Rya9l5iY!R~SrLeAk>&!ra*P`%9zpy=SstNZQ=wS@w!}WRV
z8G&f8epe(PA4+$H^5tDb?6Mbwz!pKFZ>#C}cQ7t3aR*4jxx2#l8s?`5B%<;Ny!QIF
zkhgvae}s5IT$eYF70hh48Ow;v@t)FNvP2hv;qW)fe@PkYlr0LG(7`FmStd0fLD~Wu
zV|=pvBIvQ-3W|*3@t^@m`YjMDgr^079-}b>VNao$7@4l9JFO{;!qE?yc<zcM#ol@p
z1cHFJF4TDgL;AA^lIHFANa}7@KxFJFuAPTru50j530PWlo~FC~hMxN9kU_j{;2>g3
z8J!j2iJ}DiAEf{otfGsA31D&o(kMz!NzW66#R2Uxe&{ifbj=_vu9vy+X_&UG5SU|+
z=rF`I2gOf1yAUSksyY#s8RAc5GJW#IamGR&3I$svek&I{5JoYLG!*(-f#5lLM+E%q
zP>{EuN?Alen4fzf_>I3|z<jQ?1F|E2D36!`SJfZQCn*e=PhHkk9|Y0ue)0`>WQ>@f
z7yj!N4MxkSJS@T<UC&aTNg4PHrez^Y-xWl~c(FyPlz@)EA*&o*xRta776r5|7&9>E
z%4isv^On)D&~m?+yKn?{u96w-*=y&r5PfuiNLef}r8vJi<0kbWk}4JpOu5Uja0ZC)
zNlI|QvXvK-n~5KAFD+6feZ=%l8A334E((W+(!YWeiU_l4Ghr;@WL&r^4OPuu;3fbP
z_JSa>+<i`Djw47RfCak&$YL*04UF9j9|M(joNyNrV;0S1KQeio2o)Hm7Xk&~RJ_n7
z2*B(GD1kwFK|`2F>tgcKlJLT6004%Yoc>I33M6X$1Y}JiV-09)UJwe1Far?w0aE_9
za14;N<po=S#4fk{s}jFlScT1C{C7o&t?V&3rOM)8ZqHX`pSiFYnW5$xD|UP-k4^C5
zmFwoJV#Rzo7ZT;7gvhm1r~yc$Tgc`wRo7a;=S%`jS#(8?F<;MBcMC~>N5HJJTZ)m(
zc*@+tMNzt;;M}vl`01@H9T+K!i<AO}EJm+{cNjfgxTws8^f0g@Rq{wcdJJu1Aj)Jz
z7N)DzSte?_Ot4Jl^rq)lLxQw7$t_Ysy$udGluj2gE#tnN;I)UcPZtT|gzQwWJalBR
zF6e&DA+ub)Noi*u>>@D_HfO0kQe@M*>d9rot+xyR4o|kL03GANTrqIW>-9=7&rD%g
zR2=hzy$QLJNyM%|Ip!I=(2QAF(1m!+;)C9#r7@@36;Q{#XBWCMbE91$b`3eZ-t>g1
z!sWUI5FzF)4wwOAzGZ-8+jl+}js~l!GwiORT7;_z;i4?|$oSll2<t3dh>DR%P_RpT
zPS3kG7;;=)INA+x?JlhC*5Oj}9!)>jzqT~`U}hJRh2v7_*p7~)p*KODc#P3y;Et#<
z^dU}xfsx8SMP-pi0Zc*5^;;C;6yO#RA~_3%x=_obkZ80Er66`-_e2VC@Lt;*p=929
z8vz({5%^u4Cq4K1@lr6EcWw2o%IcLZj>4_p3HT6OK(_Z5&h;ZG`0$0*DnN=$oj76C
zLhpr00jrSrLZrB{$c0Ej(I`ZUYzZzSJ8WnaI89*WZ{v)A<4hQo3*CW;!wbs8zX{FH
zRg|<LjL<7rd{8u$D~`e+ETQts+QD&6D3X#9X<iBBa8$Yc2`!ya-h}{!S|*39xN0Dw
z1cP;;q$9{H%^Y#HUTNm=;CQbSCQYi|b-=*+;{DcehI(;4Gdn%fihy++b!i^{P4;>;
zo{PO8ByeRc3QRf;ZVIoA_Qd9Oma1i}nybJAW7XV4MIH&4;;ISJ5KiyTlWsihAVi<M
zT`EN$W>r-0IY44B0{R$x5zoiei*Q3YE<FEx!`O5>A{W)2rz5g6+@*bFwQ+YT)<^`2
z0!18KS1+&)mQ<%Jr@@fwm7b5nK#LL~7O$+K9=(*YkE9xRDLM#Vb0^LQV%MA@w1<M%
zyt4Y|6|I7qVi%70QV)#xUgeaO^^c4vSB;W}EGbuHZbSO22BOfkV;jiDWyCdbVG#uh
za&Zv_W^|dlz`W41?kkE>fxup$&|~}f@YY1-mE$E0vqb{*m}dp76sXJ9gRo<+4*B<k
z6|{0(18frN2=LgPjy6KJu@cuyux<`0gd<7WD|E^W=evA!4JFmwbsMD})K!@VFmy+d
zI34JV^5_xI&J`9-%sVfXg}}sf_nPFRPQ>{;)hQ>r;P;|QkiRr81|`0HG?+NOz#EWa
z>T)L%3D6ahz0d+<;S2f?_zsH%Y(p-5LH}{#bwA!*cWKIZZsEgGLx?ek(Z*<8orw9!
z<>piI=4va_soh*}!L;05Z{4!U31{)Rq~ubmMhuZ5U8Ru-AL-8P7>JWDUn)^4-3t!z
z=6NjSikk;AuIz`Wub!^J$aJ}61*GW(cLB6bl+AkykJA<UPRvd(M2rWoFP7hX3H{Tf
zkQCuU-33hbK=JyZBx?#*1GYd{ko}@0bEGk#kf|5+#)Es*FPUc^T%<14tLFlHV8ePY
zFo$iJ{|dk3K`}U%CS0WFvjtAkf7Or&>P|&v1puBH+bk?vaH^1J;}lTa#Jt>zokl)q
zO#0DL3Aacc)pA`42t93jA8m3aS8c@%=H<Fml212U$)#*@cc~`9IX+wY?sZ|7^mD2U
zIdXlrz(W>TIBzhFQ9vE$LibzjfED(Gk_=Mi2IJu+Lt-}`UaCcboW-5u`aBpyOHNYq
zhpvD4q372hYNvh(BWhNo#)z8LuyZ0Umuzp}AN&Dm-v^<Xo=k02TZ%IFMQKA!FAB$x
z3xiQ%u1E_;g}DmV^>%4WMd6G_B60Hoyn*@6<4^T5*3&)O9h|#0Wm51acNN47baafa
zC^trzCq;+(<Aab-0%qj&&LdJKL%K;|i!w3dJi>d=(cz5my@{Q9wDsP^PHYVtJn#cL
zEGcC@Q<ry29ib4Z?!TM@4EEYiiay9Ho+dPG>;#?ykdAyA);YEaJS-^=eb#x2DP479
zqCIi`U}gJ$0{4W^JGPU%(}tnbz0-!_tSW_<PhAO7*5HXtpYO^Qvc+Cl0k1<AE8wQ<
z8XSgJALU=cKH4RC8+NGQbzydIx_7}X$75rPS>AOQgIV5n7lS$Ox{ARdcU{H3>RRwJ
zPImavUCg<2pH9u4`*bqerssS-g15SJ*Q#QPbJx<S&>fnoYM8h*(;-gW>P1daGaZ^Y
zHB%HZ@zhJ@;p@nWa|NIE!54`tb0G%H1rXN9Svn@G!WflIEI5q~KG3?Md}Gq%|7Y!O
zdUnfk?Xda&6=!(wpgR)vL24QxHjoSg+c%>i6B~AbpnG5kMv{M@N90;-zg6yftNOH2
zK=&)2M_V6T+N7w(MOdYD;fy7#lsQc3W{}Z57OhgH_gb_{mBVDsAM?#WIS~2w8t?<a
z(bvcy>+30Ctfd-w$qU!U?`dMJ_eg^EyncBkDGAOxc#DYFex^9x#&Xr-h@7=JAh;tZ
z9qME8)r&HIEWUf3%EscWSF(|HR0~UW@l=wjMK<7>?-6nAI+G}k$fjBskw0jJ-@|C4
zv+x`Ex5l>jl#2&(V>7|RHq}CR_fRG7qfPBg{PzH=?sX9iM8L_5FaVj8qv0VS>&HZ<
z&rtzz>A=9am+G*?OI5H;_WqS;By($(zXByXUpSloOXthjF6Rr)(@n#eH=Dp-y^fv%
za;?`FbS11*(D{qBLM6`TVI`Exfv3D>#q&J{+8vJTr`NAV=+*1|$~<bVJX`1-T@mu3
z4exYKDsLHF5kqOq=!%fPZqOAWF3I78Za-M2K2!-y&xb1Id-d19h-bY1MdL5fIav=*
z_aX}PeX<*LEmEQL_gnp9ovnVc4pL<KW)=2}zDO#Xf@(cqoXErBi&X9_r!P`!!|95Y
zlJK&l(qYZcgsSnK!Q>nI<U5YQqFWv1(HIH|91hJf-einT?*5vY@@R<VH8ERo_Se66
zd~gPD`3Tv{D}!n{x+>w*3ux0E`t$~vzNZlTqo7PvRJMuHLal}Jz^w?|9;|{Zs0*;F
zO9CZh0(skeyE2gS;k|(wvECb+%AlEc7cOzGpq%&03KRRwHBh3ja1F#p@m;A5Ne@J|
z()pDOtPY0CjNs~^6LthwM`s-60E5<h_XWJwk12xWK?jM#H8QIy?$r22jf0!Gg&)*A
zdo#H<%swx^uY~t-80KkZgn!BH+Hp^*)QLrHm=b(~4)6{l=eU5YTVgI=;2m_=m^ox|
zv5A#?>eC`#?13;%=5v4k!gRGMsx1nxuBo7!OnO_Fs(37~#+AsG*s7^uoh!oSEFQac
zH_QHRj9H2Mz|D0f_~sn1TV>S1*+79rgZ`H{kLz*WJ+qy_;YD=oBdNKjf|dr@xiTAl
zmXGe&`J#{R*J&D_gB$iAl~B0`Lkn&ad8PcUvk?J-Tf*6jpm7?xDXyem5RI)XDO3ba
zt4WWHi1q<Ddn$?jGKjKs$}CQ_Rnq0m#%poz?klP88qXVqqfKR2y-+hN-~<LR1=$F+
z3tyYbDw)JpAzkW)hgDCyM$MJ*CLHHVXc{$vEX;?RfUkUMO@oF7q1>iSOFlc{`x87`
z&lTZ0fHf%zxnNC7LXObRsk|B!e7>_QFS%e%%1lnrkn(=aWDcIn6+*DpB*oJ+kwI%J
zkLE-Msssk%DX<}wHf2_pqp66=SvmeD38yAf0=<}|iR3<0DP<<8v!;SIXXSgm|A!&2
zKUcBT=|oza7d|yXf;AN<$`<+bzf`ZPA?*xwTxhOIUs%$85$^Qj!)8Yo@fSqKS)K}f
zoq{%*riJh(<GdW$5lAOCg>5noQm8kK(OTi=7D~WviPdHz8gweMcOt9ri_+ubFBIQI
z(zw~Vwhd2vk$@Ayp|g|8V<K6|3nwgmQ{oL5%f1LntiBO+dDJ(;E|2;~*risxy{OCL
zh2kgcN~*(HPA$|s97Y<wNcrtdge3LGLwM3`THLmX62)7rbQk<0{6+d;Hab0^Q|eQ5
zB&ty@&L}iRTYqM`hJ?E!>bu!w3lb1C+td(%q-;~K1xu<;4g3g~3tt|U_-sRO2Cm(v
zB@GiIk;0PH<QVNEnlD#`*H>U3Duur!1m`LZ{xcxCT6kkUsqZj#Fh7U*DJNL^Q$0%p
zaCDZO%Kff`QRwTMV;~^L(Z(JxuKSe~u3Ou*4r`ALn7{lWVql1hl!wA0#)>(K>(*AR
z189NQF{$9pABP8C9({)hGwQT_t+dcDyae^tn}v|CRRUMuM}U%$_%*%oAY2IsJn{Bu
zUj9YCi!?zGB^3-2nu1ywSAv}}K?a-FEry4;7usX9LhVB8V`jv0IQx&-o$v=m213*;
z#BJ&j0}5|SuLMg7WcdRj2G3vQ(c>ZDFLD#&oB&C7P0Awg7)NMxk$@({Mj&7q33`t>
z-QW?4Uf&TikKjtiLFj>~dZ#rvD+GoMCln^bSwqZ%0%vfmkzq0@R^UfhyC8jFbWTbt
z_@k@YjFBZ(bP4KpG_6=LErdSv;0XIjP^z#lnlG!47sIu@3N-a4l4*ik?TvQ2l6s83
z*X7vEpeYn{&KOiR$tIw<tGO7u#yj1)7`nEJhnWaCePg^P!b{&cunADr8!I-EBOCE#
z^`QAB;%qXs-n9~dv3ldwCgbK6%XTH{7I_2SCZpsT6gS}}edFdPNE_eSx><Z-2)}zE
zVMHEh7~wXqPY<KuU7sEXu)8A2=VD-}l=$*2ao`9;-%`#C957qoj#b%s$JVz4Y00h|
z4x>ca+IEdH8CCZCb`hkr_d7@|dT{H{g(WZc{VS<hQrVCU6yJg!Pq3AZEkkk@|H$T3
zb1FC8<8wnDZ2G$A25oe@MQgs1(`{^^YbHa%w{#B@!3|N6&E4sueX59Q(uaUi-<wCC
ziu&I4)XvQq&@Q6}p5iOQ_;!}+FGUY?aHjBK4$crhOglu;-Q4pE?v|Fx*lv9R;A5uu
zyd)JCyI`<w@M0)w!`wsh)f_x1E|$&}z_N{{TdA3x%VTMK?}-O*lqv#ViUC+RUPoNX
zLb#@=`eu2q$9k6lV&2xf1fYf1y8>!guE8T2R^eFh3cwaz?+QRTw*uoQ<GGWb^RCwl
z=U((=O+f12@cRj}?IBjg2|{i}@u!4AsY+)u%W?ja0bD^v#?#zjjJGHmCxg7_dEWq{
zyv6M}cYI+km>WT>x|pBkdw&@aCOPSb{=J&@FEy%J8S0xv5{?px9O&|&i~tt`X>PDc
zY`tc(NG!c)vPjfhe&&8@B;HEJs6n%HlSD#m!$~BewNZe?=ViH=P9g~{4sg@IWEm5A
zLx*mPt|Zwcl!I}C_5LO1m|j#KtkE$IvI`JLK4lg-5}UjvA=8UoqJ61TJ!xMm-Ja-X
zV>0-BfEoO&fOV{BPwI6zVrg-$Fzfna2**4f{L4ev1QS}36fBd$>chWODuS5(rB3x@
zvttOq6*caJJ|6P<Ur7<f;JgOJ=Ai5TDbXqRnzvG}TX^CpY=M{G=1LqCII2<+uW+DG
zpI=CHCZpenj76X5nDO`Mm`R8G%lpH3L*5@&sc!Wz&G=X9pesPP-X(w!=XjR@2r%qj
z1F&X9Wi;y==XvRlCV;7lh*2%_D804Fqx9BFIzX{6T}kpN`Ikz?qvT&Ik@*RAwuql-
zoFgg6%NI548fn;iD^-VOFd{?9l>qiWan<xvS4|`q8H%-<fYKKK)h!jr*7#DRj%u$T
z6}gyS+N}xu_oe2Vb%XV?cU{4){tS9SQ&c_fUuvxcbiI{wCz*}{WF*M^w+|%AV8-js
ziPSPz0u=&=%%KRr>5-ggtO3Nuc>R>POdI{(_@y8EyX`^A*SYOOjBHx;X+J8Uagql?
zsiv<aUx=9UCvwmX##cTQDCD6$+!MEW<8?BUJ)u(pcon!f4o5h(qR6%PzG`soy)PPc
z3;li3wTGVZ`U1VE_1+f^Musk{-=VHLq6kuOiXD(n90%K;)IRPUucWJcX}P?vJcp7)
zbn-oPU#^GOYX`oGq0|u*7ng%RI<i4D`Jba!)_8q%ICfqM<{z{b$-UV4++t(ouFeb5
z1Z84`NVz_m_B0N-qe;^T%yUJirzHEge$lu2wo+Zwn^xE6mu9MK<4ZI37Da9O_D-)_
zz0;dk@AR(GyXWQFyrQJh<hy3MeR%^#9ofFj_<ga-`-y{XG!U2Sn;oDIMJqi~!<YnQ
z(>S3?=wvYs%>tOzk82iQ2`8bb*Od<Ei(s&0AZ$PKss<8%oTVvvCB_aWt1T!Qo)XO*
zpib{!BwZZ@Ypl9gWj=Hjr>zuo)LVGjX}?M|k40AeIt_y~_NRZDnxe4nU#6xc?aSPF
zk?sz)bp>&V-krG5H<5C@5`BBYW?~UvCV~=N&QAn7B*tI;Darma)Lb&JmrfGpzL{~K
zyY!bF&7g;|7<^?E@C5qre*BxK|G5ACm;duerse!}WKm5pn{xS*{>y*-@t>Z%RokcP
zumAs3{eS$I=TrXt_b22%TR+xyt=i{#{l~xj_4yzE)1TU(+NZ65`A^UP{!jn%&wcto
z{g?mxAOHFP_?Q3r`JevfxkvvMpAmdsMnAjVhks62d;5=n`>%ie=TE)+@cQ5X@Ym#l
zy%Vvn2lU5ZlhEi6uF5sEKiJzF$~C|1?LYmm|Nj5}=YRRXs+WOB4Y&1a|MM|!9`mDv
z{$@9k5t+Tbfpd59{X{QELAJl?<^T4-{44cx-l?2-3dgz0Tt6SI_L<fGH#<qIg1sCF
zW%}C7|F#m)2C9U>>F+B6-?7s3`_~^TpZ538N8M<AyT<<2Kd<#q|Mf3_`Eh4P%j|HO
z^?l#m=Z`ge_x(4ghBx0F<-G=am)-Xr{+rJ$H_1Xw?B{_60HEME=8e^W{J#CDZYbXQ
z?^*Ak<KJxiF3Xz|`fo3$KYhN$T1|id_%5Zzm(lh8+iQX$)JRIIN)-G~wE{}LwF3U#
zZ!3YE?yV)Zx^JuDo1^J}<2?SJ>Hk;+KJJCu^}Qeejp_gS$)Dg<ct@vXJKv737@ogW
z>qO6eS8X8lN!2L$oocWj-fGdmEal&<wkP(Xe8+$9*Iujt`oMqVQ~Ia&kF0*W)84Vk
zzxM6eisRv}Mb3wBD}g!ZttBd*@2VN-u2jv$fAwuO96s~{DERwS*+<^}rq;c-N&DM7
z;79xU7hv#<zoXmZ4=iOv%7?ew+<#yxGq2WLO<2Bft0ffWtpsGscU5{NMR=#5g1>hM
zeDv?|RUBo%HU0m{4geLR28Z(Rj1KoHZ>`<`z*1%^__vzEi@&V~rkJ;ysAImZ258Uw
z3WW9fsU6TS6zXq(gns-3I^fJ-uH-ZSz(PiZxhlE;fn}T_7OJw_?<@N8D?LB{z_+m+
zi|=P=zsu?GUiFvk{Wli<KV<ZrU#{Ns2iEQvJCK6@-G>U7kZ&~!cxC-}%*efapX;M9
zeyoogoxf#>{M3}Blkn{(ir<dylz-^0B*C}UdawJsx85uHz9JCSUn)xSeMJQEf2k<R
zPrQbHqk;D4YjD1Q4?po1m}d4%PbK+&h;VOysVK?!6>l{C*J>z#TZ#E#-)gVq`-;HQ
zeW@tPPrQj@o%`J#@pGDyj7?wqD#`bQ+`l{`{`JQz`MzSgDZkXC;QMO8+JC7h$+s0N
ziOgG#<)3&HnNcUkI`g|X@lz&ZhG_p{vAvS-hX?f7mx_{nUlIKEUn)xSeML9~zf_du
z`-<g8{!)*EpLrLTBDjo|Z{Nkwsm{KBwb)+Cw?mvrlJeD)Ldo|Pfu8uPdMWw7BKYgS
zRFvfViZQ-c%F<7~hrHbS{XOwhM&miZT4=B2+o7!rJb3F#@O`y0e)ZO0$@djk`_)^2
zCEr&B{neL>lKhP6bfIngclX54*-qCv`pbp(N`7Z)|I!ZqrH%QQAHRO^Z+__VRrLOT
zKGLTq!QW@zd}gZLT|E;!{f5J3{>-PG9R+axe#-MkN0Q$gVUfOmsYe#r@2gcL(U)rN
zd~>{IwRZL|TZ7>Ds?o!Vx6r<NIRE~a&|>}8@#jzDA9x9E9~_J|ynVjcr>KZbQ(r1B
zULJp65g7e16{r277QyZMrJ~qgzpn^_=l5Oo^%DmFmzQy&7{Bo{>>qg<t>cib5w`x_
zF&h;R=*3izg5RkIpwnB;=O1ZpcQ~q9ZTIgS)vN{%ExrYofAS@q%SQTJmmoj?4h|T2
z-ocIeM+OI2&|6J7p>L}-hc}DWnt$ibLbX7ku&RX;ynb6vZs2+Y@iSiFOL0|ZW&C&c
z0<)KU|7vi1|B=D1@ukWdzxVSC!~9ZVoNul_QN{L`3budm=WrBbuD|$+|Nfc2k)8h?
zy^ZLhA6|@MP!xPWFh_!uw^|Sl_H8xft$wR1k@dILz&i6*Tk%I)1LY6rpXHx?1AZyG
ze&Y@N17Ca}yiVib#<$mLtk#`_L$&T-M)#Z50L^-<39I#8wS5{)Q&gkicd7wq$v43A
zPriYD;V-}OwfP4OpuNYh2DiVxh+{RxdA-$E`!c%UtoCb@cmE-acOwY+t)?up-&R9n
z6uki@O8L1ra5HrL#vb^G&H-OMGn9OLU;+^8OT}066Q{xpO|Aoa@Bf{>Rvp9_U%L85
z^gF)XUrY^(KjWyrK|ve0R^NJpe&$1F2>$=l)i0vo^^pE*0elhtj3f9)`Te1h{?u|s
zDx$CJ^%Z^Z*h3WK*Q&4RXPkRCinjlek?x=ID}f2+OLxDBe#e)wf8lfZ>yKCRGtRRc
z8}o<889(Jet2n~1y?sT$;|hykFNQCopSsnXe_rGFzd}D_?$LqtwX?72cf9An)+E3B
zX#eHMfAjP|GVUDnpYG`IJ$#KdE}vGt>|YQ2|GT69at*)#e8QrSPwmT;E~WHO|F5R!
zJ6P(y?f!p$Q?CTj{i#;&Vh9Fv17jXeh#LUp;dOe5`YjN?0Ck7cp8~-471Xf{IO|X(
zI55)TjQvR<^OFL!ST_mb6*K@+vT%kH7wdXBV@1L+reL@#qUgg(It$MAD?purZZV{w
zD9XZVs|47G!wF9ZWm$M32BU!E;fyT=fmt|QX9*+?WD|X|ymPLIWe4rR6`;+P1vIxX
zwH1993nN$zalnZr9Ju#bm{>-s#Ht|?a{})7kO!pr6rPmS=@aB<;beOQ7koIQ8H&as
zoQLsnOuo1dK>QF6hh^nwyhU`&@p{RL6M=p)z>QG!aFStyg5nC$Y~<vUoCBm4;fRq&
zCd+U|#6@6a*}%c5h~kM;qaq|9tn^oa22KT)hGOZ#vKG!58esLq87>Dtk1J4>gDU9N
z>F7wS!tI2@?oTy-1=XulvAwYg@UIYpCnadJMiiTYxTgyBu|D<H{s^j&D@xgg4<brq
z0}^!%-U@OyoI2-ko=#6;*FJ(ORCjSsdw#%U6AbzPeE4IN5&2B?h2j1H0)<j5gTp2E
zX57+w-6wcp^@ntji1-L4Z$5RK8JlRi0~+ZNVF0iku^A|I?uHA|2LQ(w8v$acc577d
z_fwL5t;jQdYRAWBR1s)wLYb-0u5Kf&=wN)YxiOEU+l3*$IX$z04mx^7hPLDA(qKdn
zk^saeg6RZ0RpBfrYN;_G39&pOFycW{pin076Yx}V+n&HuWBAKC=rx0y&cX7qin>K!
zf!O3{JSPW6*EnF+u?Y(9NGTATkug_-jxjfNj+{}ey+I>wrMGTSNdSO#<Q#}%J9r?f
zb=CCDdP7YeDL+oUN!T0I5}1B(64gpR8gJTma3sZIY~+=c^X{;v`siH&n;M_dtx!7^
zZxkX@=*UtUZ$9}}D<M|sA+vPhM}*?-n5!ET-5`#xBbp$Vvtw1E_U6;Us`nAqKcWlD
zhz*LpD`BUgkJeVJt2F)EYIULG+@BpeOe47)I%xS~DP{Xj^_peG_;;{!#ae2nboiAZ
z1#W|qT1x#40<b80hX<nj&X;n`Hz=w#^&DubrOfn50(&LM;&VmS=ZPQOhbpNs5~0Ro
z9_t2GwT9Y7LWU4&L`PzXSVIk$#uAG}2c25Eg*#$2V~M!yit3#kTRwQ@O2pk;me6Q#
zc;(8h%sjCn^Z$xgmXTN)tc0<c*0m#V?3DnqKu*6@yA_xkl|}7=r24Lu&mF36bv?MF
z`$|s^2E0i6p`7|&C5{H#Zeimih&JTLx{_M7P3?kv@`~7SDZQz@*1br)uLJ|CZ)8ku
z{9;4Ag7u)BT~!*5-e;9Cu~3HM$GDR0EYeH#j5L0-%zi=HDYL@obb@}ko?9v>g!1nl
z(RqRF20a-SL!=tFoG(y$2|73yLrDler?*dOGw`q@zB-Vxrz6R1h<2kF_9Dpk-!q6i
zz@2|f84?*H-RSVI1oJ5MUK&eDoI0|}#+({j#WY3{);|#Cq7g4gM;Lm{$p=GgiKwF^
zZaqLi|CA{A^wd7?sk+2A-$CygWQp%qx+6s8(Gf%+$qC=>w#lsBNH`nfXzz&9|42}(
z8K%M7NzZsi=z?|387W{o_y9um>mB)QL-gytm{gw-7f1)$YE1rn&1zHA&|%7b*OAO6
z-UNBwMi%iYLB`rhj`WUfwf91bkF3+zIC>(FUqcz@L81`i66r`-`;nkj*Ic2eLZ^w?
zyx%1xQuA)mY08OsB{}QLo7h1Qc_nNWhF=U8v+KN_xPn|^q%rTHmAC>n3?)~|As>ip
zbgq_D(<#SfM=IM;9?C1p*E?ViKOMXmA%gS{7RoE(7#$<h?kqlyE8v5jv%fSdsJ^i{
zDri2@pLcLo2KZ8X=D)cmI14(cD?{Ap9RwgTmYT*nP2}etv>{RC=TAxUMQZ0GswF_W
z(!pUJVn6R7y9}|P_u|5SQiQh0NBs>N)g5@<5c7El^<{{(yo234inRQJC_87W1?48<
z@{Y{50sfYbEVd!0@~00JYi0*D+2C#BmDFqPY6iM&bTva=2GW;~YuX`W8eHqabi5sj
zY(uQ&y%O2RXzu`doeZ@KBAZ*rM+W(PLZmQV*UQ-8Pl|45L^s~?#zP@W9jhXY#`3^f
z&14;qBnA#8K)!-pV}i|e5c-6LTH0A+D+QH|q#u7E$;lP<Ovmo|NKmTLxLPg!raaKS
z$cUa4q3@2qYeOS3LWoPeSMr2VUh6)f<V?BUJ3e1^Ip6cs_9@6d9?)-M7VpSBbR``B
zVdrEaBcXEGQq!s6Y^k?6oMANeYQrX(>#islljv_cI8;N7<h{~pgb2wybVwv0PM@Hq
z43nOnJxle?fz}EoK<~+%8oDa%NJSFGI{rXZT^%S@FPVv@gEcFRc5!LtFqy^7w{k^n
z7g|viJRP*FVcf(W`AV+@pNo&?4^ygv4ieTYLd!VWSy$6goYvJclqWLMKPAdVAnO^V
ztRXh@Ugl1axxB+53PE@}t)?rgpVaT!b?8bF|8%4=3bL4Yq_4b!&AG=Jupd6NfFdM1
z??}}Y;tJ}ZW{XY_@^eM`B^HHHhh>=(On++2F8di-tgd9CoW79|6?#X)tPtr?2f1r>
z8QDnS6<tR5gqJzG3}k@qQ-aA%)h8yR4!b`3R{x;+IvB~w8WG}0?-Poz(`ufj_e5TF
z1^E^`T*^<1a$)wRwxRm^QricU4n>W#&Mo6Zw7^vto%S~lO(71Xp2w=_^e%U#&b|_~
zym0dC?;#uXgwcnp;asQS;GWIUzs#Ga5Y2jLBJJq3wQ**>0(K6r%RW%5j@a7<X4~Gb
zLHBi2)1~{msb#o0JMH!b4=0YA_XRAd$8PvRegnkT-q*|$K9TSwgoxVvLV~RnVIFac
z6J1jWbLExbvjF!;h?~9BM-rXXKOJtAk0eVUH7Itc4zk#2vcch$NlAG+uP7(F9kmNx
z*pAvQUD#x%Bl-77k|i*uhghPnD96{}cfNugUX!W5^1#?+s4qA;TYYEX_=+YgyfTGH
zqY(~7RfzfhO1yqi9e+A<hhGtPHt1zTki`yq*=SoWL3NUg>I$w+(qx0fAsC{I?{FGM
z(`JWbF&h2Sy_}ErAT(b7$!N05!Ppw)n7@Kt22EBuXkM?RJ~YTQ7Gk~XyDG5VjuFZx
zPr}(C3s&DedNvv08#=bZ057iE5G&RdR7YiAgWxtLa07v4Hrmj0p+eihb4UKoenWq@
zp}r4%8k$UWaPLN=-?{^UaV7Xr6=83PjjO}8{zQX`4wBznX5*z%o76q1fuqT6-_V(@
z>j(tG;UHmGuWN;9a$w`)A(|Z6xS5EC?f;~x-jQr>P{v*f9-IoX$%75bSU>V$lUCV}
z?DXwf!Uq7%%vXYEIzW|jR@c=IK$Q<98KHf&y}=6YN9Ob{<>%;nKHiVK)5Xd9q-f|j
z_aCnWT{+dTtm%EwZaSzzzv@TS(H#lluL$D<|EeE(sPAQ7meH&?bR8D?lcJN8lJ+;K
zRsF~SFKX2*U@P@$zY?|rE-^o{zrE~8KQf;0RcDoJ&fL(I`K3;v4jrkuQ}si((T;1^
zj|8RcoOCS+Os}LicU|m0DPhY*&dTa8#?qAFqwh0IY_ytprqeD_ttDF7PJph=>|!8w
zk*8fjy;6H;f8o7q+xfz4m6Z)vcRzALgG=;E;3xr6=#{Xsoh9sUP=a0w+u3+S@<<m2
z=$$H=*}gF-+S$HqOfs{J;4>xl1IK`xz7YT^ToK!LEL54}N!{roW8BNZdnFuUc~Gwe
z-w~i8JYbA_xwLMXqYj{-WoUc3&OBsj1IXdZ6VZY7@PMhEND&X&(14P7xIPko&^dXk
zK`wbEcx=?C%fV;WlZ`Qp)!U~7%yLDTD4<z9WQhaM;z1Ib4nT{G%kJ}_juFT_k9zM{
zvQQqVgiixtDXx4IJ#i^dO0dy^Ou3S`R&|heb&O9z7BkXAc)S)fpet9zr`A5a5<Yd{
zy-ht8^E-(?=}1`NN?g(Lk5_`PLDhF<vgk;`=OpTTuB2v9rgmhF`YRWE&^ktTjw`^2
z0T7gr<U#TNUjFLXXinB}Y&0ihI6O;yAlP3oII4;@S#nkfbXdq)9Z+H+Yq}6BUOb)E
zvB2wZDCNs{8OyoU-K8n98B&5-sWf>X2};=up`bcQ8lChry>_lEKSsyqz7lo|``?u^
zqvIRlF8B0-QgiLU{M5J$meGM!aVFO2K&rUQI0jV3og}OsP?am8y<C757pSU(($bx#
zFyJWevV~8T_)y?;Tqvq58mPjjrY3Y*!AR2ME;ASmobHQ`{sTqmvV#v4A@EeaG84MX
z3I=|~otE&^0bp^LDSQ~$A@?+NsXNW%kEV4&ta@qUCq?+@TB0uBG&H)qeA9>FB(k3i
z>Eb@*JOb9m1=Z?Eis(u|(qV+Sa*cG@DekYs`eVqr%M?CPd@frUwvRhZ;R7A#Qo*N^
zCA!P<J<xIrf9Zg<TnSr(nsYg<iyHPx(Sl%Q310&sU)*UuAIEUyug+GRF7Cki<}Pa*
ziKkq+tqz!qZ<)aWsyL8WPl;9v-b&e(EpIifXy34w4Ys!{Pl~m=0dzsG3<kV!x~mOV
zzHhp#ujIb_O^@{z<mtqBuqi08O%vOYZp(L|R0DD~+;comJ!3$)_;x-M3Qhnm16IZN
zR!>HiT6GjoSKnJzpuP4+Dd%3ChK8fwm2mt}U6m;Mf#{&x#6&`MDSwMqUP#|dEl<qs
zLaEH!J=HXH8(~-m2+S31OybHC8(rxAyeq<R#CE~33}<)WL%rJQ#89_3UT<y5r$p5e
z`|_abiLq;*1$L|6$d#~bUPpi{V$)E3LRT4FA6L>Af0HY#t6}HL>TEf%vbtJ_Zrok1
zLq7_oWr=$6@+3SE)GKU!?!g$Eo_nxV$}+Z!T=(77TV!eTMYGqCC)1gh#=u|h!eAK^
zXI=?^v9bhn+kjZ{MHjRIvEqv^=qt(YuTaZShXu=eAi7I%g__364+(D!pcY?rK^q)_
zR|1`5@DyGV8#fG+K4=3&yf4>-paBWrvh<DKxuTV8aG?6y>L1kG+J9!9>W%g{oU&I^
zcVpIPmhhDUZpGJ9*P!0kQoB%Z%D;0Z=}>fGwhT_=D`C?UQ@%JNsJFG$`l<<^)MW+_
zwy&wyar9FjAM4O(YpBl~JsflvSOHdi4RsJ2Z4Gr08f^`B5DE>B<d3Cg$e8L0%Cbbg
z_@Wc~mTSIEeS<z*rgkGsKq?v%w_Xt%g@O|z>q=@ghEj!?cD0Hl-Rf!;2e{QWHmJl!
zv-?Ww1+_1=a@t*pE3-PHDM;c9sxNdw8!nta5|lD<^=RU8W#t4{nL)M9qgJ5WCY{iR
zyD$e`&Qqd#FxxFF!&M<iBRrM?D&sTQu9f@sO4x8ty3bI%IL*yaGxaK6FfBv=<HyAX
zV94!pC4A7x-n!-uYEdApE2$nkT`E^pUEUf5)Z*M6L}|sj)iku?gbDtns0Kk3+;D^I
zbE|czM&(VieC$%g$Vu&UvE|atK9`z?`UL9B4El2}wOi-MxuiCLrE#TRGTRv9RNK48
zNHvb@bSE(ENl^`PqG`{+`ADeKDMb#@j8EFuW<ct=I3W$`T(1NVt=<m}2cFP5G>uTE
zg$a8gs>MwAv;jur%J^gnq`76bjML^cv<w||1#G(>S>FgNO*;FZS*(6(yCYNll~_V-
zEWsVFWKf2L^jCsTAW@J{+R+Ah%#|Q@mH|iN6JBX6q=`?ur48s9A9PC_&@ryGQdg2z
zstX@>MS*H;z3iMTK~p$Lj-$5nAUWi#Hb8P*kTC;mxepoA14?q#s6Xm&xZ335Zn&lr
z`fpGX0}SH=av5+-9|=l1k3*j7E6Rx+Tf>F!8(U46?i*6o1F8?;m8V1%aKG_`+`~$6
zWgoc@8Q#FbxBy*OQU;gOTN%J-KDgVEb<2m0X3T{T8P1rn#|LrKSF}-$vjWvOW|r;)
zv>yS!yOP`LlaiX|p=P1>#!$0ReM9DWp=DgTwH^ap#s%pz<O}ve+Z)grAF{s_8skIO
z_W<C*hpcZbUKgaxu;hKn*q#kzpskI3!q1i9(X$k!AX`^Z9qxKC6y%^|+K?W@hZ6o=
zQ4NCjcYX|R5n}>y#)0ZGpk{8FEqCbq(bP1Kh(k7deRJGop-;F#jrttOnJWNF!~mVS
zBK{<of*rM8ujfkGbbVAE#He>o;LGbmhgp7_U0KEqA8$9A==j3B!9<_PnC%v7sdT8o
zU<T}ro9yuk6>6@QN`*dG#HOG_&C%4#zd6D>xH|D-26&B|OIHA3<F?f>bg0S7F9qx-
zBOe5?Ze`>@mpQzn4n7?d$4!%kK0QnL)&Lgc%6?{(=S`z^K1=(V4DSi;CpehFCUTp4
zFqB_eB@aaP5+@&=%Fm`|Kd@M2z9SK`3pDl_WBq^)!~04KHG?gA1$=6$$i#?QB3s;y
zXC5G1t^^+|AX`3?ER|9-`mqg$v<tOmOl|DSzGf8<;nwv~=rpT;#;MQf$~L6`yb?NX
z7Id6oT$U+A-I^MPBh=E~#?i$4(L-@gB#O({yoLI!Ub|pdSCY;3(2s9xT^911_!4&6
z$T*654-FjZt;=f0k<Nv?vO4uWFX@ZnWOyZL8z;LiyBg$dSHi}j^Sbkj)Yi@-Ha7q*
z-f1xd&*EJsbKzNBN#tx%Eefh-3u>{;Vy=Vu6>vmQi(N+ZqFQ9`xhtswNChuwML@M|
z)f3n(^kRQ4W@J_NE{hq+7w@u|7ZjtAT2@$?E65CsCCSCuVKT!Pa?5NSin33Q8JbdA
z?;cC9iwo^#0KQxaJ~g{#Y1QB8yewv<RDN90E-M$3cbUf<Dp7g!Y(pi2kjemQxn+8N
z;Hz>%xhz30x5#Fo5S41r0CKq!TpSvbFkcayhDz)(whIa4!gm>vFwXRRRzR31C2SiC
zu{X7C7^5t5I1s(dBCp`hCq?)WZ5$EBiemt>xL{sZKo)PZqyc1kyd8BK3a-((h8xwJ
zbnRYQ!e<43*el_;3clJaVnfhpO`h#t8t6*UPPvh;02i58RAZ_d&}L1Z?Oo@=<{BVQ
ze@#aEMv7n;_{)fOX|k{hb`fgJ0Cs8nOQmv`HaWaElw8{=<tkIoL4#Z01<*3M{=MAG
z4@7}#Y^i?0M&LYc3#FP^S?LuH{-ntH8`5L3+0uATRyy%9ZK6~?*Nu}A>(b=RMlie!
zZFMCzjq+t9ZSa*;_=Z*5;445^9Ez{WqIM`hWkWRFHaYQDPl~FG@@E%jrpdx4W~R}?
zCS*nl6pa^Q-lVGunQ1b*0h?*Exe1ABG^dG(X^mJ(yO5X$YZ_O3x6DVT=4>*YabviT
zEN7o}s^5ZV8K@k#@=qDa9`=FhTx1aY$Z`f4W}hP!0W{1$a&P+r>6vyj@G)1yws)4;
zE&>v+XhCq_)Gf2++Ba9iS=%66lPO&n#rp^uawRoHnbOGhv6VRTN@@VKmHqy+OyIf;
ze^SKm26_iicipLH8J`5)yKfTTT3yWVispYH$wVSbMrlC4>?3D4h)}k&-x#vG?(^Pf
zB|zp1*!ID@r!ftn!9H?zNBfirwYF#+p)@#BlWqaX44{^Mq<jHt*@Ayr=D6HvsB6eq
zxsTl3$RW88jc4R}+(#N2P?(PdrE5{{BR@A_FjvC98D?94?xGI90=8RUkY^u#17e{6
zhEh$eJlipHH1cc5z+n12zJbwbw*yym3IAAaiUJTHiC9@;Hx_4KUTv_md?YA+Duiro
zK!i5ISyzy~2qCMlC}%a~)Q-|@SHgyKZC(MJt>ycXpp?Vhf^QiBHCKX`>!^1H9Gho}
zjg~^(5saTPAZWG#U53AQ$j*+ao=KfXpl4-iKYvlm(JOkNQ@xV|I|ALKIUe=T?CZhI
zE9<CXcCG|p2h89O+2X+3?2s{DZ{pb@V;pFk9kj)Pwb{aV8L&1xV2cB3v)_cLmQb53
zK+6Eu?2zpZV9gfh>t=oJxjJ5d_30QCjPJrN?vTqG(8et=mjV8`LoVxrNIogz2n;=j
zy`9LK9r9QMS+hg-H;^?uUXL}PH9O?7#+Tqq*!HOPAd4K|lPf7N1fVrnz{bJ*NcdQ$
z;zb>NXm0x6PZ_55!C`X?E@t>1?x1m9pVUjN$(}(UhRkN*a(5_r*?^nbN=IwJ&Fr8f
z`|K>RV`cwsmlvB!jJHdBA1Fk@#tcxJ?Xtb0#jb=cBhG$1ZSPay#_e)!mm=IQ^$p<k
zb{XU-!J}~k{nZg1K$(vOCD56&U(kI@yk%uQJSD;aq5NE~ZrC9o2}(KBzSXOmiYwtU
z;XwB}4e`-hmTJS_MAkKn8>N~-I<-fdWKT+JmIvT6TUf9G#_{b_wV>sQ;u^)}a?5ZW
z3|Obz>9QWMU_TO+a?a?r9<YJ01kW6tvZ0<prTNhKpw^sT>yg0^x6Edt)?Dc70ffwU
zV^b4r#MIKP0ht<_SR+DLj|N>RXxB}IzP<CI3!UwH=t5^}OWyMRtU4{{OtzkV?e7yY
z({xu~Np-$y=0KWuMQFNIpI}@_^_~*`pt|1FG<2UgTD}9gn(a+(f3)8|YPS~d77~m}
z=&xj<oErNI*iN1bw^9lWfM~9St(3vLg#;UQz};Kuk%2?--k~8vVeUZNP>ws)(y0<&
z2DRgMH3RLqT>~oZ*xNC!r&5nsgyJQ$Y)65rqmVZxtM>umO-is90KG{OmKd-%DdILt
z{7p*GJRBG)!hH4ed45D%61}tE?R`{d$9W@hMb&w|;oi}Af#nAPH7P2*=qS%niP(9|
zjtU(=;9p7+n=6f%BJRbG?2Aoi*nsmYMVP--kSXBwm4-|a`cx`1CG5he;f0m}d~F|*
ztF?(2QRw;yGIYu{F^iqzb;2k>O-is_0H{e3u4@J$H7Q#V)a#PTHTp&ogDd@*DLxRX
zI)KAT8C%;m<uthl;$>5`AP82<IjIL>Y&bs+1mdQIJ#Y+dYOv)XO3|tZImba{{eWxx
zBO2;c;2jVfG~ggl5$-VtFf}Pdrw(7sP^S)O*VL=S$+h?89rlz5r~wCliqH#dRYcFN
zamo#s`d5S*r$sezQScGb%{g$FkRoWug6X6LYI*>Kld>8gKsYJE)&{8NBWmiUv0I{F
z8wjE=S>w+pYw}^nel--cPdF<-C93xz3v1ZGYmkX`Mb&fHRtF#_Mf|uVBqt?oe_$;-
z>(ok=jWuv3l_Jnw3|w5540AqfDSD{=i5KjFV!d3aQ}Y?NI1t=_T*<03=WMZqu0Ahz
z(osxX@>AxKYXDG_B0PAbe_K7?Sf{TUW;kr7j2+k<##RS5hr+YhFu%p6_7TC6GIYSP
z9$t$Lq%|pG4;<^kmpXtCUdr$#0`12~G*vU$PhMsWLy>(v>XghmJM0zhIioHW;{J-z
zsXAf}D;1LhwZ&!1W7Zf{r$XwFL3QeMrH+9Zv640ZY?S~#7>$Fgqt+GR74WDvMz136
zqS3J_-PC;NX!T(jRGY6c2Y5q?>U=mx=}m9yBK78Ly$$M3ns0+j(-j9d2DPT+&@~3M
zrt{!6fcD6YPV6T5)mvF{d{llc_E8UzTDj4(8&sr1^p8PBx(^Oc1B^nIK?+@%Io{W{
z1EMEIY>n!72M?J8$eWK$#@V1E-MqXQV^<L$uR%q+U7t@7Ii(EqRC;u~`ba&x9YyqT
z>jN{WMfX<QRHMpHGX~VCLI4KfJ}H8p0p2G?_znyz+YAI4gPK;603(x5DGXo~z~?C$
zn+m>c?f5~}D_s8o-YZ3XSiQd#aUfK^!uO9s)w`!2PtCh^=o`SQUfC_rt9F%8V@#^u
zP58l>RJ&WpzDc!P(diFlShqU)P3T>P4-CM6t|*J0i`JwCCp9yp2gamkRtUjJ_)iKj
zc;J0f1kc}?Rj2;suz0z0MHm(j1rsWHcMSmalPTj6sFJtr{YjO)W$#a_WJU~JNxj3S
zK~N*_reRPkZ<!L4T6yb~K$K6)*av831s4q9d{TriOstS~)Q5@hJK_t*EVaC7=}&59
z#RXhZbrOLAV?yIDF_>Qw8kb!^H(S>SV^ZTT*TboCFT9{0<yFGRA84KwaXzSUmre(h
z3U`U;aezfKW$b`sauGw2iDz>audN0HquWwAGdMaO5dhWB6nm^ljmsE-F>y9sQ=j%p
zZMqn9Hx{+&D*x$N)TK*?{c7yN<hOk_&M(16V^NtZSm25<zx1?@sx)*!T2!YBAGjh+
zCyxV*hu5X!z{25mDL8K|o?e$U{-PRI*uWLx#mKN<)UZ&di^^26{{b@D6tSCBrwRoa
zi|RB{PJCANQ+s+*o8mFlrHkODE5a*ijHw%o%5>>?uu7S(rsgMyrVYKQOf!a{GLK{r
z=TU1o$W9#u77wyh2Z6<N>^%AiFKS>#4ve)i7`%UK+ZlRxsapmLJSnMOD^_4E>f9L`
z2vx4)2gahxt($<cpl_#ZXw<ip2Z2R(s|bU!sBWjfL!-`Bn88?h4jT`w+vzCQ`cQzu
zScpYV8CvHFSwRM4;e<SOS^%AOirDtyH+afQC|2y0a3xVqE7o8vs%gd=jNPilquZtq
zo;n3=>R?3@j7=S^P=c|kg7H-^QH_PbiLt4I5lt{QmGIPYVp9jtsc+t<7FOiJ*rkOP
zcyI-HZ#-k{&bRh{Up7y|Q%8dh)vKU^v3VF)+`!n>yc2}%W7i>f%Ix1%sZ(bErb?Y%
z&!$S9{p}PFx(G8E8wz#G8N8`brw$NX8B^Z_L<MAiL`_{-oK74Uz^$JGKD_iUA`L!U
zXG5tX?cvzes6z(+rbcDZz}Qz;j?h4LI33d7+tKzQkm-t63HV@Y$`N`nkERMO7@Nv-
z$YHywK8H5^hWZ>j6KsI0QijI|mdTLKzw62MXU*u?{5h585V7QNYRwE67<K6Slw_eh
zRi<JFhErvZ`j$Q=t2I1ixI1;`km2sAg`MwInPZ^{>tCS<!>K}t?0TmT9kS~kI#kgI
zgXi2ULmBT+M!VOMb;x9QDpbW645vaJugUJC${f?+AY`vQb?g`@VhpCXN8Ko-toFP^
zzbfKjIQ6T74u(_5D(GPN)JWyrck0+-DCU!8#XI#YqY#Gk_&Pe#3B##!6`3%cT6f6W
zcWB)qyTGY+D>&hS4C{lIJ)A));ee@hhfI4ALZpZ;0x!+0_=Dk8yox{=PQ}X*gyGb?
zcHR+E@gfM}3UV+CLKsfXt0;uwRK524|DC$m<o|c7UgN32qe}RuI5jWg5T4;wz9#3t
z^Z2XSgn^t%DdG$ShwHk(ajIVhC=BPx)@1TKeaeb27}2UoV>_r>6<;udniT;CS5TYM
zbQ=&*q9!oa71cYprN*d7O&0<|J*v=z5mciFLc0O}n3Q0uf_jwk2_vXSO;-Yu#YwJ+
z5%f756njw5nvM;@ld8%351v#j;NXF5l?0!qpkB4{<xzN1JQ4&|sJ#b(n4DgHF=Dcx
zIsk<7hwC~ZphZo=!viRkl%Yj>l}!hSpsqC*F}f}fLzJpDog{FplOjBrUS)+hjNrl4
zUe7;nqe_P9bha<ge^BFQ5W|Slwv1tTQc|<qW$%MoDn*<Ts@pEde^A}_*YO|Fw_PWI
z;Ayq9QmwZx&wtRPjD!PE$!fd`j~IcUuyy*6d!Se^u}k*{y~m7txDpIP#{Pk(?y~C-
zHFcM5e;WPu-BCu5W!xWXX$C`#)2qaWsHFRr3Ow`^cUks_idxYS<4{p69%39Q>WYWp
zvub@ZAYvSzbrlgY4qeV&Hvxwly$gvoPO0>+6TqQLS7gKhLh&Qg3E)tLlcS(y7$Uw4
z2l`oY4&zWicbW2s`Z@1xABfO(-4`6HXM{kEQwqB4w%|}f_o1W2p^EOhE;!WCU1x$r
z4Xsd#aiF2=D*J&5YX$cOXYpO>zThkjSh$cwm0fq~^(5+Sg-nb?-P>jHA1YskJB$NW
zTfq$vMCg_73=VZ|$06WQ(RLjI4i#;0bXM>wY>S$<>B8Vp)hbG2B&s<DfaHxsP1|4}
z9O_v`NsL1^%P@&?=!-@IpQmIwT7^zrNp-X7;Bk1!ZS*qS^rYyf(9*N<46E>m*`RA1
z?+j+6s#O5QY*e+)F;BA?NmEi&btUMQqlhkTwM8`xtj$xhdIgH4m<>fXPG54vabz~S
zk{L(wqzpsb_(`qGw$wV#yb7+EjR)MuqsKEFHMW8&X5;a-O?7dyPdqnV5jrId*lbk2
zjrRewQT1lr#B5NzZK#{nx^29ZM7`U1zL<@Aw+;1xy0;B=y;LummP&$!IZ(v1G<AU5
zx#55@8?`fL^(k4se^c{39XHcp>2Frd#RL)ZM<l$^Y*gzEyttB8We$WYTR|09gs$tb
zFdKDt<ITWq)Y%Nam<<}cHBBZpb`z)HY*gC{!kCR}yES!!T3ewRvz;FYVHr75Wfxo#
znlCr?6|nhI><3X969}uLu#DMoH+c@v5;H$p9|4XCw|vKN6m&5W*L4tcF?;>Zx#}Gq
z<Bh=th4@i0#RQD%9M?lT`sRg#nFXOb3b&X*P@UuIYQ6n)cy^f34CnCZ@Jy(Wqri*_
zX7!`Ej9K*SDOo57>ag+gWRWcojFI;S6B_rNr79D>gY7?4Z=a((gNZoDbEY~{8ud!>
zMF3*zO7PtRVCqWhqVq}yYOyy9^UM2!3Crb5I1Q^Ncn~BqVJIEOSWHBg9>rM9ghriX
zdhEs!w9Pwigs+H|91~up`}3~x1={QyU!c*h@kKUD6MiDS!bgHq%~?|y0&~V#irL}i
zJ*TPRQ|r8`-GhbBGr)uye=?k6!q7h<mZ14L2%Mm;KXFnxK~sO?IB|sLo8T2XL7ROV
zJdP)%V(a*F1j@UDfm(b{P2iQFvp5DlC+NkWI4gZ5S-O8|PXYjS0v7!Q`ssj|^sWb>
zpN;}7CcsZe5f-!XPbXZB8b-)X`Ak5a4#O!XfKEpt6*FN@NAVOBD5oo7Ltw=^LibIZ
zS;F48i4iT0abie|?M`%GF^*T1{nxg&iT*D&Q(E%GQd0{9n))2$(0^jGt(7C18sWl-
z%6gyhE}WQZ8L+4mQ%%?R<tXH07Aoq*&>%O~#$dx6gOsO!g5TkUsg`H&Xpv9wLmY)l
zO!#OHLM0~h65TSp5@?xr_5{f3MAvg`QJ?5~Zty*JJh=XulK{0A(#HTirKIsUxAV#c
zbp^TMqfGKS8m3K~8|b5>eByKTEMcdXukc9`t3Ycp;9-_)@+f2Yg!}Tib}q0<R|0&^
z6<O8da|;`JJosGbBd16HN^;hiIQ&Ub4L}z57+GS=Wv(4}KDA7`qtxPa)Cuq;2yZ4{
z=rBw81RKy1W^MvMbTYzW0y=aQ;qXkj&5uGHCj9Ehm*y3U$d`r>MI^XfJ}4)4sp*A@
zt*&iM>eSGosC=sBT}SSt9O5(4M@MkG31rd9Fo}r^isLen>k{L*+-DP*qN6y8iOY|p
zsECP#dq;5*a|F6OP|D--5q|E9ayK$c;tEz4*$VWVf+Qxcf{vTc00T<SWfcQ)bcCLp
zb)R&+t7+&s#8Nydsm0gTI<%g5wGPdvq~mk8EMbRESht695)&YzE5K91;dPXjeBxg1
zC{$t=@7Jjtpa+uduVN!6vPzy!vlodckFt?ZWT!lU)ID=nfvrIEDN<qrLUa@<aV5EI
zcc@)tu{+F4J_}}agsz*o20aLrm_Qhv9cmhia0h)T69A*LLv0U?P`VoFJ&zE2b58Wn
z->HIb+cbS=QPEw&TdO)K!xz`kXKzjwG~1Tt3tqgl`K3r?(b=+mfh;<Eso{lF#a?Q<
z{_*UkrlH!9u6!2w=m=&vaczGk@D1Q<|4P{Qt|3k}?HG_uYH$}GVD6q0RcB-i11@xg
zmYanZx&nMofEBuu?BJ84dQ-HQK>>7>oV*4g+jt)I#ncQ4V9z!+l-g~Z=HXy|jjfb_
z=qNw=mDGUBEL~84o5=Yq$<feNJ^_C@OkX|$kvRm&eTD~U(Am<Wg$z0ZwN2oH&Zd)m
z0{Zijpp-_#I_e3u-;&u3lF_5=<P(UZE5Wy-$V%%$Y<gsg&Ei0|4obP9m#l0cicVod
zo|5F~maOc;6P+a^8(^Wc0;SvtLc&eb3|$eQQ99~M_>h$)_8K}<Db25>`uc8VWDGxR
zt0gGSMGJbB%3Ly_7gXjFqvix+=qRiCT+o|KCNy9~XUU9C6wz5SqSxjiX+;A<bk<Vi
zP_0UJJ^>&)Leb5F5S=BCpb5axSyOF!jfyrjrurxu`UD;E0i^DhbA8D^2E6es8OX?3
zf0*ig0tIvy-QN>g@1HAL5M*bEdJo09hGq_ma}6~O#rY;XpIG-tu(|o!7iY=H#=bcV
zMmBcVS@d~dNe+-M?<?4-g5AHNB$tfn4JEm_yZ7yb+}d+P1+J!!Km{U6`2-^O2mv>N
z_BjhE_-7W_=d7lVKmktrv?riGXC93oDo{zv=SH;B5hQNnGkhjZZvdOmJZkH6_M4%0
zaQ2(=juD4H;p66pvQwt=2|&*gtZk+?y5;Q2lY*S?DW^4*+LfSl&}~XgJ^?sC31FKW
zG1zCyW4)o<=2qvR+os&ryL8)>!+O`};5p1+J~y<TplerBBibnC?w)d1Cq(F$Y2(7C
zILdiG0S7u$j%ttvohfr0WI<=@dTIjtbEXV#m{V862SNW$xvgQAeIzK|#jf<`6M+(k
zIJAk7*fV94BjVyr`Ku9@@ti3uy--AF%18%@=wuS~3H;CzkZl4zbkfLsAgS@mO!un6
zR&iWZ?(_)*`UuuG9Z;4tWsxHh#g)_uz0QlujD7{xRoUAPjX7TjwL@i2`KKKR#z~v}
za~?TU_BhTfN6FEr4=z&~<iH7C37dx2oN`MSO6Uw(=l}^lSA>?~2~`sH2_m8cP}~GO
z=nPrui4ZzNbU_nmy)$H_XS1}%ad<oe$W0tD&wx3OtSo25`+)jhDQWry-X|rPeW=VK
zPqp)?IUEm8jXC6~2KeU;IjVvEIYPxvV1LdKtbO93eunJzI?JCSa~)}L&VZj9iE@r|
zs6Vsf@(v+()AMYJT<8-(og+-#gg4_1da29Z@p*ew-GJ^>qVoyA$r0Xd0>^VDd@uqc
zuc)3JE&m-e01VF=a#2UaB9K|0{+u)36M5jwIB0RhDRhQB)D;MNhD>nKavWmaJ|A^t
zf;viVekHY7SjtJ1ml}?<GvuWv6UkxH@>vnKN2s$|VYpX<Qq7s%)W~mjMtjExJvZd0
zj+rI43OzSufdhr}k)Tu`7?Z(W4#{J(x8bxrrrn4@=cDxH6S2_GAyRC{&VOeOC^(a?
z3`gyiuxHS5CJvtofA6tCDSM{f2LhgB^hv{qd`$LrAffp&8Q6g39Fviq$eg1L=M%V`
zBaGPu2Itu3=N%B7W3s3VfO7?G2q!@0MW2A+96-#T5_#2PQ-MLrq7LXqqd|?>{-ZqT
z&&=d_M@X`X^m)hRl@4e^lUEv;oMW=54|2C2qeWdHougFf6ZannV6%w}l3Pa8xJ9`V
zev5I{az$wS+$u7;aaD7eF?|A_b4(_8p>v)T@h2N~*l@>qWMSh<>6kY6DQ#(rQlFsi
zx*|3Ob!jlNaaVPeB7L4wB}@r!wU5cM4eZS^Iku67@|Yak$W(a@e(i$i98=cS33$#S
zJZ%D;b4;#nU~`T&H9aw&a-cmW+V~M4Qv=d>0^pg`Wn~w3<_Ly14**Z6%i|5?%;_|{
z^FH(_yZOY8>FKhmajSYIba><L^@{jhXtqv|_o=OV1spdt8xov9C8{yVI6tM^x}4tN
z^gErVIB5TlQlLLGZ>dkB&1PX<4l|igAYM+F{S3g%M}ksLY?r;fa36m<UEB+o_D4Xl
zg`54;X+f_fV7z7cRu<Cgenj}^nnilJucRiCCiiO4be&swwTgr~eX3#jLi<FidO!5k
zDtR?pN-k5AuLh{+5pHX>fd-8gO2Ktg2cY1(sRK}QU4H5XxXEE|@|0A+Xcw>cQF6Vj
zVJNxY*)WhVr*}0Cwb#3vhW}If%2#1vjxb*f*p}z?#wWwM*_$4m2S6n>UqJO7fxA}Q
zS%T%gfE7CJsQ*xf?XVSS!gkaO6d_Pt&#J85x2#s`ThWes4`tYnrVWR^7HS%)>y98?
zD<LnpyeEH>E3cJVya0DOEz~rWW0RM90qk;GsO{2@jc4fvtjlSxmIH%y(m5~m{V28h
z!uXExUMuJ1w5`WL^);Ho&jLd3iWYuSJ*FMJfV4Zrb}hhK8r{~b1O9s&{nm@XmPWVr
zmE_xRbXzZQ0-aVC_3HI|Ac+^jFKw~ia>`r*8}2#2saA0UR2uVV0l9bt3|mB~w4ts+
zi#58e*Jmf6HdKRJtP$#cMYS*oI|r4eq~xo<4o9f1MO;fWeF6z=X{NSjO|GdWD6M8}
zX<}-jWuFw)kPJVl;dHgUvc$pRG}pS?z$N|>nrjij!W88xsp;2-E(A+!U+UEIYBW<9
z*nK{tEcuT(N4+YmGL)Wt0q-2bU9FC2$17s1rOd8`?WQuj0(=(1F&}tp?X);Sw8;Wg
zCJ4=1K+0SJTfUn*PN>=Pkm2h<6if)3wE%I6<LcKzH)uXDYv>Bi=PSuCLmYajuc-P0
z5A{mpBo58#Ti!Www5Jy=njlAEiK@SJP%oH9akd&y>nYAs)3qd`Oq{#4fR2f?)OyD_
zrKACl2?4g2Rf!E7U*hD53?q;RF0(Tw^@~wmo9gR8*F;~v5R4H5Vl8BdxDtG1kV4{0
z>bW!jW<Qbc=Ze_bi8VOXaw*6VRBOTJk7H^$NA|=qH9Yb14Gk~6dQ;;Ii_p~e!kafn
z)hy)fh||^h#<uBt&_<VG46i(keaawgc~VlnY3iS&KMnnJ^oEx20@Ni=<71P5AP&9M
z3s9Gcqt2Deia45?Qfr~C<*V|pJSoDr1xMX0VdJ&&A`Tm`op}XpJvVQJvOg`vXN7W`
zFC>!*A;PYtdMI@Z$jg=R`!I6ISAq`0Z*V2(Ap8nfQXK?MPY}QLq$n3(c>du2nttnr
zbUzXFTQ8&pir8xP>bEFP;0J=5aGsm5q&mN|R5~GIsTr%0EVY8@p-@uu1=LK0b~GX&
zBV;oJ6ca*WtzzJLBBuH>&=>lo7kpG72};=)8PRZYMKGXZ!3`EM)Xc=R4s~u~R)-p{
zr?OG7IY;I&UqI4?5L*jKnh2WX0MbOr9xohCgc04g0G$b?K3{;&gkW3??!^ch*Odb-
zC3=u&kzI!p6iDkzs=r;2b@aDs1R$-9p!q#Y2ZpR~cw!@@uHmhXko`TN21A6J|L(`X
zdG4ZZpQ@jqxvfv#kJ4%$b9~N1|Mp-1_|HH3kM{Ym{`Wup^$G5cYU!^(K$RX!-P@7&
zA{I|39e$pG=eJKxP#A+>`>LH0vdO#K4;Mjtubt;FXK%}70egw)y4Tm}OJYo91@oa4
zGazsHk_rf<K3;}?J_w9(`zV1K0K)rav%`TSnJUR0#z>zEtu1aR25P_jIk?IGO5ETK
z0~w0+2}aqLH-OP1ihCf^7O2Lrc)UV{5ds6C2d%@redOI2o%c>3uKX47{PfUa-DPaU
zL9md0Da6%T%W1C99+{tIG{>>NKYw`ZpAP)aYWn3$swMk%C9U6HN4bpP#`?OB>YZ~P
z)xP+;j%tx$9lbem5$XT8*Acj&wT{HI|79J49NA%kZrMFw*U|cKR#CR~Wfi>?UFQo6
z6Io<_XBAb=U#y~fwXKmuu)%Zrt|55Nw1$Wa(;9N#aq~V{*J$q&dL4{hLhk`uO9<Lo
zD@d#7bKd(bpU<M{`+kK!f2`TN@84fN;HV7ekt3j@9qxpHes-QWqJE7}HNMgz#>l|p
za{3LTzGopSNbqomm>`imA)M0<KF=$tF@x{(3h+=vFL|^GLpL32@}t<o`2~aG3#S_&
zdhrTs(?E4z0h$Cu!IhxRROTTPNr0k*6p}zqhZrOQtiFQkQaQQ9={HDlb~sNTV8;)A
zhhk-+p1v@I#V;<>FI)+J;PrcSccFXq&jY(2PVEq&rV6Jo0Qm&MYmq0_ZHO;2pt_w)
z5sbM}H?B`f^3&tIW(&v5=J}((Bq8!hSc?Jb$TBCNETh%Z+M<m_P(e8F;3Cj1o*H1<
zhBKF48OY)M4#0%I0(9bFeentoVHQ_VpA&{*TuIuppWPQuM>=w1gwv0XsE!aH<Y`!6
zB7%Yn45#-1NfLs@j|XQ_@jlksB}DpIK`c*7YV(5LI>gh6G$J2C74A%Ks;5(5yeqha
zynU)qc5JxLapb$@+TF-#@DWrYXKmAEj^Lgr#N>#iD<Lk&GqX^WdM3I{cK{SlBw^#h
z?P7?pvChUJuEvA&qnH{G4v?Ft{x8ZA=N4qGdDSHn+r;Ks98p#w+~>jBQMk{8TzFT4
zhv1~Rar>NcWg)~T0?%S|)gv}7l8Wfba&>~55!r%*V9yiv?z!ks;6+e%99)T92^y{Q
z+!dhFz{{W~4Y`m)=ugDu#pcdI>|O}`nZbRrdD2EsrjUw7+NKcpv$w{MadTWz^^BL(
zJ*#jd^wzO1c+T!{x?M?itRr*Pl~m6<(pyDhL3;&ZhM=HVP*%}V&)`A`VL^L&5Mv!R
z3{@l~Xm3zGi_ge8U2>d#EQu_#5vZOOY6H4Q$j^^CQtx58YT@=Xg!Sxcc!aQ>w_N?8
zDbtY(?IX$3{q-gYp(Br45YyQa85{z2_J%VbL7gedDHW#kxgxJ8vsLJswX*~zBShzw
z<eDO&vo|1GLWs_up7ju(v%?)9OQ)j-#j>d0I^w!x2^7{F+@4EzYo#f;0?rz=$D$7F
zxMT=`I-e3%mxl%c-zQO>J?}GO4UGUwXbm+Da9{}5*%AC6f^~L8$cJE^y`t!2nVPP(
z_*@a%hPGO!)}gKd?7Zb#3HF`|vV<e-JtEX<;JLix#_7xPGZ_bB!G7)FB)9@x9CYMm
z)IkH}2DgmyRldisKd5&`wR$D>bs%`O_xk{<&5nD#5O%b8s5H?hc3cR?62(f#tzi&8
z+Ur^|gdXj<c?_XPJ7^_>=+P%dxBDVgyn>u)LPa}nJ3~;>-ai^nP|@D$J)Jz^bntG(
z3{`>J!T_&57X*c7IVXPlJ3J^cks9{Tkuh|r>9}EzM1*#bl!O4Gom3_vL}&-$NeB_z
zix4HmXV{TIHWKZ5OSxdCRO=P36!4i)ds7=7xAZZmx>Dc8nDBc)9oPLK^1+T&10k?y
zN1}lc*s~+iKnU#lTv7FK;s>{L+R^|k1i_wHP?M@n-A|qRLTJx!wSYok&nvNdFeV?k
zh?v^b2BR+~w=nV>hv1#vdY0G>G~kq{2Pu@Vgqs+NmP3fo4tPk+*N4<GC~jk*Os)VV
z2pw3InDiHv5)_4DHz+}2LOU3jVs<r+8@muDw1d1UhzadBvVe_j(2SrryyY69n9i=K
zM%dKwz%p%WxQ=B)gmwUf0@>(uggA)-0NMdJ3IRYn(sRc+Y6<#P2+*e^ML`U0?>kQ-
zPV5F9D^%!}<d}d8z2&lLN2r}rs3J)0fNq8O5j)^rAx{cjI!_2FdPOxRm)B=yi6g}6
z?aROC${7AmH<YZPq}_0Q8?Nbw>ve4P4hnSacV$9>j;%qZz8p&ffW90{{l}>d;L&cl
zv$z5d0os!2(JQceEStf}ZcOzK%5sPZp#z*4LYQ{o7h}}9w~v;8Lq{PgK@eKn$;B7K
zm-fs^5JH#Ua*c)-|CQ9_^3J>u+!Bu04>xd4I2f|kN0nFw>TsAk2X#1%oii@6uFjP5
z8+2!OIGke0N(Z7f1VZfvdX3Sgbp{T9#GrNzB?Ln4Ad`&2N7QI!=a2bhk*(q)QIOLP
z2FnoSv=3YXnvC=T!mBV|c=ud1VdqPwTwZq6v%2p2NV4=%m&Bhww^-9^GTR4qra-7y
zQeIP;?E@;4Ak=!$ooNd-i%UhT5{`-Hnh@wzf>1lRV+e)XbH|1ts2v}Mk0eVtDH{D!
z9gM6|;L-=8jUVwLbu%b*X-86lFj@Ba@&!IWPl>9#GVk#T4Z=%%eq+O=@(1*+;HG_m
z1}1E&aojHoaM~vntpKOJNNz)T(<>;;n0V7G$ptCE>6PSyG?@+)s#lQHKC1>lUWkPV
z0Ze-;#vr`3PiR?_p#YNL0J^jnkMNTMHUcGUJf2@kj)%wdE2#IT?LG~L1Gx*Yq<YT-
zd7mGpD(Gm384`kyc33K5N@LW)#T<ft_R0egrj3d;0AbpzNCR*sh-~eM&<P<yJM6kJ
z+TF9B%DzHDCZ%B~d3AIh(kG6fqBQKV9YavkUJTeFAZZ6n_7g;sc2H@D*bJ{E7j8c&
z<)Rgr;gzf`YmT5Ub(wP|`I1FtcqO@Nbx+V?f?o+P*g9<V=z&rVM@Ri)G!HQwUO{fe
zt_?pycN8K!yrLS9Z2pNOYGO}s={{5z|AfBngrN5ceJiHJj#Eo?eI#(I3DF$(I`{+*
z7*9!Zr6h*6BdRXCJ`gxO1?detau<Zy4f~=#?K<ygWMGK3u;cs}A}#DVBVI{8w@#3^
zJb0^x<7U@kAEf^w62p%Bst||amE;;OaM~RrO6)CkaMz(=K?jS!@JebO>!iP^mc?G!
z5vCae!S)5cOb~2G0)r3=wpS{JE2!7FKF3W$SNnoPweyVL;rWOT+rENbZ;_pt@MU&=
z4B%slu2cAe4i+zAN2G0lmarqOK=jvmUkfuU;~jYhLd1l9ee|$62|FB50i0@IP+%dT
zYA^RykZZ6b!$$~ldL`@YMJAGjTnX;1I#P*T5%1BVQk%^31+^*+>XqD?hX?5?N%fb?
z8`0g-w3#acJev0Mf|_kK%%8rXA)9vM!ci26)4ogfHKNiwJfqRH%{JYvjr(jv^$AVd
z;cpF~N&D{kH>MW!{m~RN-ND`;P5Us(`=e<WZs@`$$N_xAfs4|<>1AzFxWz3Hy3*`$
zKu6QIgpWF!ENUbOdZKAhZ5$69z2aAr(=8>taTsjUvY_n0lG;J#vk$>ZI~e<eaMBJk
zhiFo|$g&i0DqqtNxtO9!^X`=;whP_YWMOY8yGDC@^K{s{8Y*Siv^h6UhfSMvL)kT{
zYA|j*SH$O(Ch()pwmnPG55@VP5<aAKjaQ7q1JUiUAF1A53*8U*<Ib(%NA582iZ~t$
zP3A|M7l~c{$o2+<i65!n<T&vYYPNQ}ALe%Ml~Xn)&>%=n=BQB}@*~ST)0?G$&0?T_
zT<x41jnpofVO((4jsyZ92}<|(TT_PYZ!R2a$CaQT=~Ubr`jO?0i^Y!wr8`PLM67jO
zOZwqn$Hk=!f_f!8r&VURgUkAg*s|ph*s5U-ER^c~Yp-X*04G4TJC3biU?Of9$txKc
zi5zu4YTl=stz+fm0<!jEMf&`RCO3GK{74J?%o3ZK==zZQ!M(R1sZLytJK&}r=@MOV
z(+=J!C*1T&(LyD5ZlQB>vVo<_nJD-oFZ^idJJL;D5&judD-Rn|OkN4TZ9oyY@&ot6
z8F*y}ejuqK>RSN#f&;PIfp55Fw&Z`Vhp-(lJb??4bVa#Bg>C6z26I7HJGlE@kk#(U
zUFQMq4Zw#haqyMg5eS}o1v!9_Lk+MI4^b;zQI093;=Rm)D_JP7EOCt0DGyv@cgKm-
zLtZu{t#@HuJ3w+C^0HOldk^{80G)X};6wv_#)Wz9z|S}_uN?py4~Cp{pcXw8jokrl
zbmbuK;HYz9Uwbmxxsb0NBzGR06hR$KcvpnR4P#mwrPY}9EdkiZ1%K^@ws}&-whW_M
z8mD1c^u@)<0>?P8KFWdy-o`_Ie*kV=@YxPL>y@z8f#FO76t3u?8k(ILp}r?*!(*tg
zt4f$zfFE6O*bXR-CmOaFlE#%}xC2V#A^$wEG#-jP>mZ7BfnPh&G#?2{_o4E^;l+B$
z2Uo!7r$m@W&(e#+t2raKv*t^O_JYbd0IzpFK({KzaK|Qjk$gQj(Tfo6*k<n9{oIT0
z+Wy$EE`r03P3?}|Uzi(rS?*vZb!S@94(k6aVcVr|U7rJdr`)mA@f~yV8$KN{8F%f{
z!pXSn1`TYl?%Jhbgmv;4_H*amwfg|1xe~k_D2XfKQ&SxZaM%&o;7M}$K$7d%<pxK5
zguC`5$ZlOshrRf49ctz&NiG%VUIVPgUHk3KTdKcm4!J>~zul)?65z=9<R<LJ80?}Z
z>>$T?9~wNApv!lC5ToiY9Srlt#a7rq=8KD|u*1CZWGd`1f80&ihp>^{<@`oGkBh9Z
zSHO>ptFVKg`6EFo^}oCJSweB#shR=BaWN2fn1n6{!hY)CxwBzYy35TC^8AkkrRukC
zz7QhiWGL(zMD?VAtwQyQp|Asub0wTVXg+Uh_;7sE)``e*Q5JSUa-5Wf9grLsWnsr5
z;7V{LHk=f$s2aZ#s|OSE3tcCcLMtwECr9C9VA#Ks8kB+P+{H?GB~_>TZ#W^j2nelC
zP)~~T!G>d&Z$Z*=6!Tq**y^n2+tm!z+IF614H1OCU2Q|H?X9+<*7j!8BMbFuF;dVw
zC=3l?9v6e5fyq9x(U`b_5pJ~$#kQ3i$Z*hg@fsRH<F0JMS7L?U2gDi}Am8<2cv4dR
z=a<1+)~LVgb>Yika2~kQ{2Ck#AIXDay}Y3wY|QFV7d9r9p9TY6zLROIMAfUI)#X`Y
zyEuJje&1WFIW;wl5Jwl4p~1!C0<&3pVO-gL4bB|jhEjgO3)KHWv{Haq4W*_`z6REN
zR~&+Y_WmP53H@qXKu~JT;A<6^?MmQl2;Fw&@3oFIWbv^*5LMr~^$h?WSMpv<-<vCS
zufaR#%-s7JJb13my#_Czi|o(<+HoP=tUx<gfCb!fb>PhJdnNfoMQ3OTuXmx^4D9$<
zf~}FsR{YKPYaJ?6B!`BqExx$*J2a+%aMqzQS8e^r3Z>&p_Im}nN|o#PN^+Gd)vp1`
z<6=Fu4$5yQM9%um0``8#852o=tsKo+X1jIl^*86Qfj_~;cxWKqcOm2qr28qs8^95>
zJh2Z%HRHV5zEL8+rm8@@Dj~4JY40E}v<`2o3;SjT@o}a8HRMHdW&XW^9ra#^TB=!n
zT#SYWbiD;sT+OmJjJpQ+!9BRU6WoHk5AF`Z-GaNj6Wk#X+}$051Sh!slUL3?|GM{^
zy=GHgUES4P)idl>&vZ3Ie9-jt2RIj5xSL+vFgDb>0JHw3Y1q0gbNLC;{>aX0hqGN-
z0%AZOfzx+wz~$425D2t*`i)vjv|(rwHn4y!ICe<1VT~_^MR_cz@U7EMluu3V7uOOv
z>sV^`5h@)Y<b>?UYKAMZ-H0EaYN0wd^OV_6YbjTv6g~Hm{7G_GCtDwG%Fm+5L^PZX
z`VaC8B?El*;5Z;Rha}7`TN7@}Ut`&AYIJ+d>-Kfq{3aw*mKi34=?<dM2?`F*%Gvra
zOkkjCbk~wKU!gMLc}{eVv|s>nY@cfvmYdrfr{T*j)<rw6FYs$B^p4$QT8S*4^eUh2
za2h8ZD9@dNqMT2PI2~Bo-HM*ewM8Y4*KJD4qCM%JDJKT9L+B0Wa_&c}-slclpf6ty
zWE7O2eD$dK@mzu-Vk~@G`{emBr8{4h0_WJ73C~M_>Zlgu^G-lf$`uYUYr<YO0wqV$
z9IfwGoembLPz&B(!`0I?D46L1Y!jt!cmT#&iZ)srSI)K6u>COtDbS8G0{$EQPj_yY
z<KC2JF{t_q1~a3q1Yw~jHF{#Ld2xl!`8%P3jmVaSIE~{7G0xETE_xpc4_7(-ZL@^G
z#j$XkOKv%ePaDX5vj$t!h3^oW(fjcWo$Fw9z*^e-G|(T<Y42&->vr-33E}}eW{EA>
zGIu#7@&i7}Z6LuVM^3qCbsk5}cqb=X$j<1vb??%HrWM|hm@*o^<(;0EXSHMss%Slx
zQ$_Lc2ZBCFC6{0g6_a#cMR2~o(Hd+2$<~BZZ89_6bQfgAv2^MCPs-IP0VMM>UyY)%
zevKD+LoZ<Eq{X;A)-bfg=qqS^(4!A8p%1D7|8ZQH1J1~vbT;Y_?P@;FVWUl=$5`5|
za;*y~GYF02jkE<pa_d9@VEPD_27bLO)>oSNwU|AG1ahg19<nCjWHTLX={o3Wmz3Ry
zm8i|$zD>P7VM|}xO|i}1R+M^0IZT$C_M#e`_lA1~33(b%<3tD2Y4GdgqJO62L06O3
z)V@3FZR^J;(V!eh?|y4pO1#(sK%e`Zd;?Z;ZB+WS@cpTbpLOq-4qE|iI++!F+gas^
zUoD&h@8(O68LD);kT8StSKl#e<jnJFm1|@uzc;Z$>jE8+r*T_C-11KcbRR%J&734`
zh0%?shpwUI9Fz}bAJ3vU>UZz)FPt{yYP;USx1s0CDY5`^77uY4>aHhY4Pm2r+F#xT
zKAF(z>P&wbe72Fr1tqEavWFk9$s7d#Ovyk(_+%HVau->{EM^ndqr@x*7M?k7;_#&d
zxJ4E@ApdhWn#~cEAy7rhJK{ZyK+l0S$mk+45ig$6ju+?W&h{sGg3wsm)@8;6Vs!2C
z#c>r|RzrgtuwFOFux|R_)dyO`9X2LeDZ0We{Sl*lUvkIhI-2hTZyKH5Yp-+ZcFwT&
zz0sA%{bR3)dAA{n_Vf-}rdc)*@O4NiSDSXwoest$tr6uUKmJMs7uowBi}$@lcbcVg
zuiBj`){(|fSIe>b=q8)T5qbadqh%VY`b0<bYb3)}Z+jk92vkSHI;VIbo)7d#inPAm
zZQmUm17g^VQ`_RjI;Zv3zzQtQ@$EK;fFCtQ3>*bNYD~@0bFuv$2#@WM(Xw<T$2!c)
zQ&l&&(;Y=dkX)WNT|G9ZGXn$gggH^D2UQE!Fhtdn;_)xO^`Pq=ORHP^FSj}^;EQl-
zsF8$yUtVVwr0iX8y`IO{wb%rKKG%#d%aF=>+5$N3EvGL?vA!4lLiU#W2kpKLd%AjP
zY+|NWh)Qmh98^SU0rifQWle$0pa8suX)QxN0*d>n0_eYh0vs-zzg;i)m2eV9O;rQT
ztgrpm!3gZagK5@zWX2`!NcJ^$hLh#eAOg?EsJ1nnY4-<Cxrqw#W;aLPQ6uYtWA>jO
zdD@vMBjU&GwfZ8}bOF`ig>%i?A^4x0waIB<_Y>|h6x9?GePe~4rgWQNB>gmuwbx2z
z(xM@kJm<jiQju#YnwlMBZDeD5b62rtR(?Nr^INVC#>fjR%z>}wTO=PW#zT#Yz~3a5
z5l6ehua7{rNKPwYv>}V|#Yj0ynM-K6=|Fz!p>M0+SscmK-Ew6)kpJmiH09NK>>rD%
zGpW|BE}cbnvytzY8M}powVqVI3O5PVn+icO|E>+mSvnF7%Q=K@>$?Pg4ps|CLQ>$G
zG`|S91Y|vB(v@1VnFwfhH*esGmuvmDqV1&Q(O=(PBgi#3g&)t`Vb?(%Za2hvJ(Y3s
zl1Wr%))9xvqs0Au6n_R6wLU6n?Z0DVn%e}i^NXC1X#VLr7{)+2&R4X1qTPH`%EHlf
zb`7?f_xhLZK`uue!vfWPyWsjTE@&IfIx8oG1Di%5ojdm3SH_skC*MUrBiNXeMnXne
z4=RsLPSsI-L#XHBq}V~cL=I%HYQ_(A^!(oic}0SXP7!~gUNTK#D~yBrgHjTnK=s<>
z4<Lc1F-5EP_WTn2#tsQ)j!0(??Y~0C%?@VR{D6#1XhGnDs~F*gw3?VFvliyf3bX02
zu&Io?-kZ5`O=CrVd?q`WYu3zPm(fZNZoeX$h_}u7{3AfCiq3c!TR+o<ew&e?tWKu}
z{}=S)05-$8@JNq@sii-fZT@!#PLK4WJVf_foBZ!c+eOGqY2e+BViq>rhMZbR$S+^`
zV(%0mN^z}PFxO#T#=wGCNH++Jr<;5AutP96Al&i%x<bxbFHh~2@$qTUTekJEi%QA5
z#|qxE8`NMUh<KHxXxkVqQ^DaItoK2W6;N&C2nY>geEc#qw#FSu{#`Lk4m}edUvwOp
z`eir2dux3RWNb_ga5KjkHiKOv*0KBung0d?aoyzKm;j{iN5M#q`wD4`ke^)T@j>~6
zsju=6s8)6b*z<sH!vSvFIh*;F=Don?Jbf7M3GDST1ce6ZJ64BfAN6D5`pxz%EC01$
z(`Ibl%sTsFp%klpn`@>%mo;T~cD`IK;Yi52i}XeYZ|{pWB^IgcW#`Wt>t^5J8ubq1
zR>{yQH1m4vL~VrOKgeK1Nxb+HYh*h=Wsj^|*lm)Mo9Qp{+of)t3x2%6qBUGR{4xd4
zQf#~|Qjw0y@{6TGn9JWvh56U^LXqYww3s}jz?#yG5O(J$(gLAWw<$n@kSxqEy0POJ
zTmvHZWB9=(S_=d5$CGXKsp7K+f4`$7e$6RaxTL<ObQ$lpzMAwre^&=<g%$2=JPL)8
z5Lf>fwb(Tj(oEVE&9J*S-Ir*jljkHVO;`cH1WNP!?2z`7jozUj78`axy}8B-ctv?X
zchA#}BG@zn+7|FF1xH;qspZi}kWR~J$<mFgIV339s)k}i<f-*P{>sq<4u7f)Zi6wN
zplBHHtxPvg(PFVabmD;Oo1!JHH>voDzFVDAq59~ET)ARm#1&AJsMcgs{xNM;#s`yQ
zLby1+paidsy&<I-M{a>uRaJP#%x0ugwM3tnsv$oKC$qBBZ0OgK6`pWs`xE!K0ZCXp
z<t1CfBNDD(NDx=5ye8@&u2o0ukwsRZo`2D)%Im%5y~N}1(qCs9XW)_b)0U)T^&QG!
z=zy0*TA2fuI~i!QpJ|I(`dP}-(Y1cp5I582q<^;Lw<t5(J~pK#!pR@E^I^~WK-f?)
zC3p1$={B9VJ1szP?!5OfEP&p*OK$zF&UCB@T%dPTEQ8r0eoYbM9BBP{z@0v5-*0tV
zbEBfskdst#fF<8Uk^-9k22OHi@gXOa@_`ljJ^7j3C1R(yTe(BF|2(i7HSNSM5G=8z
zbaz-}HNcp&#}#hV0fN=mWrXFMw>3YZzTLSUe)I5b@R|IWZDV7dFP)1WwmZtIeme<D
z{-QjLe^cM4Q`k*fMT6{wY7HA@5wdu?hND%WVIjM16~|a#IZLLC!|2aX)Sr;Kso(<6
z^T(LHB4Xq#kywCvYf<i|!;sQMB{2#NcOh$;FcoqcN8<X!3xX&FrN}5Y<DY=a1a5_M
z;;5X52ZvOpO_A(#;;@14>mI)iE#x#%6>1BJG<z!jH(*b>atMHOBp6xZNM_l_Rhizo
zp%;)q{7w~lJxOJlRk@69b`Lh-_p;xEen<2rpW7*x?cQvX0*KiaqC;yq6c8zOSmSMG
zC2@GYtL{ZFTy9e?B&BF=Ek=TXEz5VI{OZ60RTz@GC*DveLjfijG|O3a`=lr1WSI8-
z)>N_$0vdK81nEFtXkxQeTN~Bk>=?K)G7ut1WQJ7!*H&+ywWs-`$c35awNc%eY$5aV
z!H-r@lA22GpaA7Ws!pw^3bHQURu*ePu_k7mrF|tvxlW6S5XEZXY%$NTJx43&<)+CK
zf;~a@kC}Uu#Tr|`#tMUxMG{QJ(8bQ302Sd}oZ;NS?`8qz!0%DW;+d(RWGU!9Fg>^O
zW)n(EwQDxx7{`vQQ=}y=eHNu9ZG5mlN!sXsh~**|uBkZ;h?~-eC(Je(HU6n<4e^;g
zIN{u05)Nx?E1@6}rV~b_m#2gwF!6zo4T%kMAYs~m`biP77E#(4`*SEiA<%>guH5*N
zMAeh=!#hjzn&}mZY<FtzLNdB??(byu&k}oF<Q0*__MFRoc-P={PgOs9(>`J7;-=*}
zkHL;VHO|08)N#L?H$=J^8W-?a@&?iDkCnJ)qkoln<{~Exy0?cZ!YbWDV)bOo#0CR!
z7X$0{C+r-bC*T^l?=sKmE{RZg6<3!rcB@)nht$|itO5)NR-S4Gq7H1*#m?-<FL<W?
zwgt$lwdwJ-w0n_Q$Z-{`QKJnRerP*?ucfe_fbU7nWIyy*hhNIT(5BS0R<O+W_oA*7
zjQ-*bK@V*+fv8bzXsw`|99qru)ipBGa<g)LF`|O(jllF~Hn^D=wo@5$QpTG}eyVty
z3#<bp%3=<H_q=$SJ|)ah@e7LUOLA)W0{ZtGwE{?LVb$`T<?u#wwYjkg(p&eiOqCiA
z>d9D-8i~AQk7}L(H?;RI2RFF4Y;L{*LH=eZzj$<;?GMEff^y>uv}@WkQL_b}%q)CE
zC5XYlK<!2EmT4A)xKlQNbytiJ;@CZIFGe%DiO;?%v?_?`-e~)GMry-zi+EVx{D}BI
z+sQ!<Cwsf-g8{F4w>XMZjUbFCgCT&zZz~oBL9HG~N^#peP810rshfn|Jo$o4-XVzl
zj<Vztpp(@6!yvyF0bZ&6t!U^a%}Fjiqs+@1GLOGe1{dle|MPbMv+Vq08UOP);BTSu
z@%g4E<z5CY9mq-=d9c&~9I@3S$SZHlM<HA)+3m&co3Z)*z=hUQWI@~^gVPXjT@r0(
zB*{^+iwLq02gQv5T=Bht0W3%WAJl6Q;56_pgG6Hm`*Z=yrTQIKWU>Bj2t1K}x^zU@
z-AD+fvM54OjpCQ+o5;GW-FIS)@A_MoaU!*d2e5U^(6>R#wTMSy1^P?IU(h^#%fD<*
z&9cCCm0MZ|)t##5uLI5#9_{~-El_3j$~u+z`suBnEO4DQuzp}3uF}0QjvA#<HfZj?
z4yrbrp9j>kgN-zNgy8!>zT_YUZ7g(+aHmm2+dx#gs`OIzX^XaT!Y`g{56SH|(GTVZ
zTf6fpdocFt1{HZ{EO!hNl*af+7`MTV7oS(li`JmvEDsQitimvqiEH4#pB(wiLsZc_
zFu}}x=G4zZXO6{P76+>$hvCEnlij#WLt{No>#P5)5qy>CA5{p;3Ext4B$(=?p^Z>N
z1^6J-$QcpG%W9YiHo^wUiTbdD5v>SQ_aTFW&_^C)n=*A6xE%ujwM5D10~w`|H|TJz
zqkVsQm_}Y~Lk#e0f%*puIeZpRR$UHXw)96x=+i{uh(t(@6{}cjfkkZek8u#1X2TxI
zP_0qhgAHIBtIV;Y>p#-ehd{p&5@ba&D1(e`XA~{m5!&-ycm&fy0)p&@O|G5&VHoiM
zlT{!)>Z*b#vNhsqyB-0<HM%$Q#JSJyMyfTcgkA^hYEuL$m#TAyZnhRNKUx8<0H-g0
z2r;&}9T2TQAiDRqZX9gAnx_-(AP?7tyOTkD^VxfFiWE`@$<cGP7n^0_HkwJYHPph#
zacMc{wGH}+LtsB@riymdU_gsJ{d;^Awfy$PGTA&n@ylnpiaogI@I1ZKrys+hWcMaE
z+Ql*1q*c3WfsFnYD3r@&Wp_$wt+?B6)xU7a*K1<BB(lyR?wTsgy3s8iS^Kc_n@<J4
zg*Rqfd)XkAgy?8Q0al?;5CN;H#L|J52JO5ejZEFeci_rI(slA^XQs@nRN-#bXIvtU
zLLEMtfYr9K7VrYzbVCr?bkPD|pr?J`47$s{fP}qvehp3@g*3nydWr@ttyW1hRcL<s
zE^&Tj8)&%{x``d`CdE^kMo1cb@(^GvYPn=>%qDp@SXkQ(pYMs#7e9LadA^%Okfta?
zY=`iu2Fw*wqyzgV6K<6+5?9E#a1E>0P4LZ|Ec6svLXJeBKl5niq7+3^gG87M_X23L
zg_Av_zd=>zCa}^W+yrdv#@QO;k1)*4TW!>6fv@0=1d$bUaLsu6oYhNQBFRI@HW+Hf
zyw(Ild27%WOZEA>Emg-lYvxC^MA~c7{H__joMejTX&+VV$h1+7Yv;}5%IzRf(KPd*
z+N+^Ont%~RP>X5_0urrdzg^MP2%MR8z*Jp>djrvdbE(aS;;W5lsATr4baIH_YZX3d
zV!oUJ0-(iIh$*<S*HI}8>g(tld<$w(Ff`FPi|MUJ)@|Cnx@TD{<lMu<5~7;`02Q{y
zK#y=pD4z9TaYE8MFya$9Q2QCG=+F$qj0d7x3RnXwi5Zdbc^(Kc(KB{rT;@hp3aNZ^
z3^G_{)sseSad{%5I>0=KnQ0SX@sn0_dqE*2_CS-45`lPgLS`38)i?`j&DDc{07Djb
zQ}9)&pL8r&-v#z8Os}F$6E;*2fhIw4_w$M{Bt5Ndc25O-X%LJbiGOFC{(YvU2h${2
z4}2J});5>XSx&{uHU-InNkF18{gb>}$Ime9KKb(^B8(TP<)@er3f&JAUF-ZJ+uIF2
zkz&=()*7V<FNd4w0yN_1T!3q0t1MhkRL;o>y==zI%*+nY*6r&|zK)i$0EpSO1%Bll
zw<d{spI8iTln+HQ)#yCwqPH*rncs`{cE2|VH#B?Nmb{%+H|=*1C*(bQBC=a{c0;mS
zpjciH)oY<#;^4Dc<SEZ@H)UkJoJ;Q)YdW{WO^Pc|x#}OzFa4!`Zix1{xV-G03Sxl`
z_<A(aT?94#b-(TK9m#%8=y~>_$IIX>+1s6Ow)pHHp8HzwelWB*i@VN5^WMthe}EQX
z2u3bH=5+}WjciX%<yOkzc1JKKPx8QJDvK|u5kuxHD+8Un*)bb<sMC(+I^$Mh|JK^a
z@)3scR}oyw<f44AK7>bHn7BQWj3DWP4lG%)nthkZBS7Wu4pT~f#=3Ap<x+F{QJotv
z-(9kS!3elBtr~~f<+^PweY+U-4Ktq$98Q*WM#p|RBxV{CsX$q&d9jZc0XWaA4xQfs
z8(Z9urBd$7z^sp*G>c;w%Y#iT@<Y2eF&@}kv7KgxE6<3-K#Zs(n1^d*)y&M|fVmT*
zqK{dWTHa6|LhKsTUjaY6ptP|uJpyUZBPXY@&Z%qNJ`if{fuKkn%up^!n8-QAvY>>~
z9apT|#i0OhVBbu5a3Y^l5u}I7UA>)$9WqJJ{Y}hAx;vV!FTW6O^MXFg<GQ{KHA~E)
z>e=M9Ps|04KWy8O_=ht}AAJcNk%YqlQGLs5HBo=O_F4UH1-k>Rch|5eEH>d#ZBS&>
z<`iYh$JHGHjnhq1eth1l?eI#`Fs#^OuR527>)bU*6j2p^l}6CrMqsS#l8i#)bov~g
zNaJ#!;Rm_I={5s&96e#bBoXI%soIxhg8{33kBI6YZ9&?Y-gz#57gm0G90K!(h(8v^
z<jVu5(V?W~Nj#zY_*A?yc?BJF<%n`|XMUESC;#+5%|A!%H=|ila@BJ!zVPw#hW4%J
zlUblhT|&`Ty3`D~ABOOTrdch3<=gi(KIIvoD4H&Z81hrSR10w5j#t3;K#j#NG;bj&
z{E_yk>7|E@h!7tdxYAElo@*QeGp>#8sSHR_K<4%k%n#m)W&GZY4%VVAFtA#oT6H>&
z4kk5Or8MdwrBJOj>A*#!9wKdSmqN+kzRZZ6h3;Te78(o3?WSw;$$Yk+i9m+%{09<(
z<2+$>E~ppS4eBJkmuoo*>`~-%!{^{wFz)6up`xs?B6$Eg=p?FDdg_Pz`Q`ROFz%-C
zIG7|A6$d7}NkrtY*e|$}Z~j4G@hZj+u!__vDb33_pzWa>u0B|B2Qc?fPG~YH=V+(!
zrm*g4o}w##Ot6X6Nq`qkPP+Q57zHbNM6+T|BsV50^&WO3e#FcquJx<0R7u?HB27Fg
z0Zx*ihI(hfIa!=rpR=LaA<PwM+*^avFkFuw0?SL%Q@%}K!WW|orNmfyyzl9Jp1)7H
zvFg3AQc}1w;qg^dxiT3RR1hhL%rd`RizH_<lOrXS=4KheyLvjpk>NVuUK>dAXb5t|
zkmLSCtJxs7%a6yXJbs&xHX2BF0X_Z=B)hI}Gz>V>f^lOvo*Yen*xbgjGNp4G;#yRq
zbE=)H%h%nHooZph0#iL?l*b*7tT9IMgn`Rguf8^(86d1+ugA}h)V-46I~1n%ohiU^
z@?gPg7G-5B;Vh3W57kaP?yaC5za5~1AK(?7?qQ%gfI|L5o(%2t;%eE&f!mkw?-T`0
zK<tzV6dEXN$q9V-R5qr1KpN_eqWV7ZamexGOWLKju>O|G498AYFZN?VP)40Te6V7A
zKMe5%OWzkue!p6kiJqU-zjLo7^Xg3H&V3(+(>Oy`@-l;q%!rbb@*1mftSJv)xnX~0
zY4XLzzFD5}d$~%-3xGwb#R!Co{>Wco(_~?3_Mw#~(7q4EaAv3q4qhE%Hyl3ZfSRQp
z!XOLe+4nHEq(@9D!Ii!E&hl+o-9Jz%$n~;B)T%DFaaW`w4K<u+aGJL@A#n&z6g3Yp
zpik79j;1`W%oB<-@7;uE?7{QE#4;GB&7%R6+D_?05M<!@F$~vE`gj3$Th^*JmXsfx
ze_Lrq0Ncm@j_}^Za1CxHw87Rt@793GCN2K05>;G?<u)1zhbmP42Y?FZKrb%;Jfk`J
z&{rmc2+%pOy+k&(g8#wIHJ&OCx<=7(4Xl4I%F44C`hsejr7(-3+Z@SHhBvewM}7ig
zNpg>i4t9ug;J1^KuCe70fyx1O^o%~|P_u+k*CXYyMk6BoYBbgH(;sd~Hcf_?zkjXM
zlw1(E(>cTwvV7_KDwa_j%jKqY^IJw0g%2OBGvfCF2HH;@4Y^W^M=zu{7ert;FZU4X
zhz2Y@6~*&O-j85z!<?$L%i?5!^t8yCMi`jlgUX(;0<h;P>&PTv<8#T$-o7hUJC7?7
zpmeYAqofD7#-<>(cX<=n@B!&{s-j_Os{smxf)Zdc(GTOTlSsG+e&~d7Ju{xaD##0i
zEQ}{bM8s}6xrD7=kKTi!bT-f%>^9h{%0wQ!2Fn}$y_UV6*02KCa7aaOcFd4!w0-du
z!?9>>PBxE$#xOS7yfx)#6TZCI#s>z?{x;qo!pc>L3S*u!KGNN^pf-%Wn8%8(!mudZ
zQy(+`R*ah80v>#%+UY^f7{<vw*zX$QYHo4?R<1_=Rn}kdEsRA+CVjP19&*4*sEbri
zxjisUBYB3oNIz*aUCRS<xShfGGns8!$hQ$_XL$p^q4kZUw?aRfrCJ!`Bow)3QG01A
zjc%r;+#L_9XM$<Yj1rOp)AS+2ZTcJGrk1(Ja4n&}Hs6jySR9&-l3=#We7?i2&`aQn
zD_&g)^sYt-D5g7wdnYe9jXeuMOCGNeK~qU~wP7oQKCN1h;D+HuT5oK3UEaqO8;^Q)
zLi+8rd{3+U+d>|CPM;M8HZ<KYyBY}H6%be8tv945R-C;bvpsdYy+gQLzYV_yonY)k
zB<2SNuUdqJAS>;%*k=e&N$ZZLDH<{As}W(K7LQ4rR=myyAx%5Un?N7pnslOo(Bs_y
zO9oL#g1<cLpc`3WKC!jhi{>^|Z5T@>-}NXWcmY*k*b1SdUc-Z-bzxZv32t8BjBd$Z
z?}MQgm(0(IV^RC8jhLFBZeqtmMT)0}L&4v&_~2Oc`G4lTq$#C1Z-LF~>nJN-MbuEc
zPcazjW8M9Z5q&H=t2Z9e1&W3YG}c&Puky_NHiGkBB#qF5{Y}|kwu*8h>+;>j)>{fk
z#>9d@sdl~Imsn2IuNe55QNckN*ZC`-TBzvCu)zI0<WoJd>mg^F@Oqya4@_sPh#7oY
zpV$1>5uqi+Os*c|w5F(W9SW7Ki><ZD1Z_OiOA^-!uKpR?$MBjVE-*H|IQwHF@udd*
z@B>}|3+|}vj<IHnhx~T@Yy_VmP(q^-L0{%}aEXtit-u<Co^Y>3zRDpwvwKMN{ZzA6
zv)7{Cgzk&fTZ{!xI&IL%08s?J82k?b2Pdiwr4I&>g~0a;8v6XKT@)`FW`owCoDXM@
z^NGKbELXQ6cqo%t*ZbrnO2Tnid1ufrQ^F^cVNlEk_+~I6VU?<A5n>VGGdYVPX~W_o
z<iT6;zv~ZANvJL(MzmWZc_(gsuoch~=U>MB9S9;TfM7bAR(RVf26WCP*v%XggAZxG
z43>DAMe^QD4^+gqWyig0w)3@k_c4Ok;rsRMYL)jl!p7^CHQF&jlgl2MvfH?ti1mgh
zHvGaso|Icp|7j;A+*)wav9YA$8yu5ea5`Cb)k5J`bE_ujZy6cT;~XXpSn!;FV8nSw
zoeWwKy&Pupd?mkhHTwM<78fG(nbwI3;=e~P4(H=dk3|noyJHGbYCkK{Zy{HY@C|&a
z&R47QcN<HGDjSq`_aAa*urV`Kv*%!I2=3|y@0&@5FD6{%W4{f*vJ3tW>Djo4(xk0*
z0lG(motx9<CTGrEg0-AzE-!p9(^-jvfunM)MQy4$kkCLVNJ90=3o#VEJT<FG)Xb0G
z9#WZ9F7WhEaAV-2QiWInWv=DozZhvokD#r70JJ~>f50v~l}4xZF|;N3T5hYu%tfMF
z?g!6Cq9!OLfuhr6OpNie#3N8hlpjc>l}ThM1%*kFia(IV(+Q?no#0Qip*WOD9utMB
zM4*09EF0q;=0n%8V)yAprmaG8kWJ$9iPs_XoAbw3@ZV%Vkw<r@?z7sq{h(q*<gquf
zv0&>Dzz8cXez9KPA+$C9iVO+U7lvO{Dedp-U-RLEAyJG@)+mLbu$D5_l?X2ag*xmA
z&3*ML70f0k6`p?x<LaCxy)0p)Hq1HPqrO8+{s`|d#U>d)@^lOrykg<)M9Yx^<cA}^
z<_yN$wfbBZda(5bJ0h@+YW7`nM^E~g2QVl5+0q(tgt6G_!O9uNvqcbDU$=Gqq)vA=
zbBX1k+UM%e+#RGd37K`Bja2cKK9A9EzDz<z8%+$ks)&<P9~N6j$Fm<6+mw%1tuUNg
z2dQEPeZ$tV3<gBw*A*r}7D4wz@xG~VUd~hwaIqiJ^1;ZsPU)SgTecK~c{3~sh&aKv
zI7Fp#ICvR_F*gzTn9%UITSWNr5Y`WIg>i+dc+MVVnmp~S&6a5zM#*vTHVd>IsX>}1
znHY^h&efjkBgyr|s{ED+%Y;FRwMnRx%>MWZGBZcZxDrDT{pD_CC?YooW|^7~s?;#g
zCZZ$OG|z_eg_t}4=9@0fq4-*$X4yI+;)S>Xz#GxT+ZOzyx~QNKVxminJlCHwS^_1x
ziwkzUlk#r!nlP=IlAKdmZN+=+(cfOw=u(Z-bwF}P%`GBauTGO!468mM{#_IFWWnH#
z7$Rc6f)pKhtcDJ^=d!Xnu+1Bg0)wPVtg<#sO0c*r6~H{qpmSmb`Ap}nvCcbwZ66J$
zN#}jqc-hN2T>@C{Ri9zm{vCc+WU|9_ZQiyH2J0z{V3THIs%PtsTn&UHoMd|;;>Pr}
zl@3C-i8`~js`%Ka4)bJUWtPX6&E5n~HI{;~43=nS|BEH2sN9Cu8+lr-xu~lqz@(I5
zR=;2UEe40Ane5)KlWbcqQh!KAaT~h^AIx^ksuj(43*Q^CdMG$o7g%d;57qJha=@kW
z?DY1y_r(vW6a`$)O4^sH=6ZivW9sQp=z4aYA$fcL{A%Cbp?|O>)U#@!{mocEm6w3P
zH%oVS>viYpbnErxZ2^=Os$)y<{VD3gZ^h?zH}1>R8Poe&M^De&UB@ZE(jG@$ZPX<8
zjiAQ;<I~pDwc?ligC2w5lMAQs?|Y~kkl=+)>&#F6se@ua%*r->3;WYK_pAGR9)`ZW
z=NkCk8yp-BHrf2Xvby>m+p*;4{liA+kXChVWNuXShE^)>`<TzgQO`?%?Lk>C_;0p&
zZ0gjXuNtR*F}BajLdane`=vWs_ZEZ#N#7qLXfIC<Vy~ivUf=EwV#hL|`?RJH@fMay
z`VA7D-dd+97nxE=z+S0R4RCA>-tM1nqIM09#Ae5rq~}-SN*FS}^hsyAu6k{>uz|-4
z4##aZ8MN80YGl8*7v_D>)={TMwxm_;(XXEs^(`CXR|XyVh5M3^zqi}6aIXDXaKY{)
z+m;4Be&u;!5uuPfhKh*u>w|n<t|JDG-(9|Uf|&P~kaVq28O^8Md#tbUH)0Y8gP`Nk
z626eo-Mz{)k}3F{OOWgRO61xLRx@bBd;PhN6x>YWRc3gvhYDFKynx7vxTOyH^>;ay
z`RSTfULyYj#r^MQd|bp%MAV=iRW4E<G6PTgrm3x<UeWX8tj87?6e+SCtI^H7W_-8m
z9IMqqFAZC<bb|%UhX||qrk_O132pDP*hICwwoNggkK%-&4bG>w0+5qaOP!tlWPgVG
zmN~(FzW9>E%BBciHrZKy9m$i6;QKZ|bt7Cqh(8o1#5HT7@jmqPDK(d638y(`zP#AC
z$el<B&C0LhQ`@60N4!{$Ri&@2wNkBDMa(N>bpZ6hm4Pv|?+HrQ!0J^p-zD4T17hx8
z?&R_F%i5&T)<t=VZaC-+LBn%Zd1}|K&zaNa8XWk31^BUnmni%z<btlS3JNICqics2
z4E|JbtBOAdmi^XvC@6d@VxGk=y0y>3WH%q>={Mnt5=t|IKW(b_yQ6G?6Ft4J6LD`L
zc3&gCRB>;^YnlQtu!9M{;Vb?anti_x*~r(iCD^Hb3VV5chXW!bMWfdEF?XGr>TD6<
zV+zf5%~5B1!fxGP)C%5^ojzc{_bs57v<Up-ez>eZF?kYKRLog^D9Q1&YTuRJ8+v?7
z+q|0>{_(E)o5i=FRI1mt(f;`OMO=}{;JaY!bKh-qDYwH-eF;PE(N7-I#qRRlXSUbq
z*zAI#wV~VQTnmkB*u<TnV+;WSot}QbC&t_KgH5o{7ljRR$FJkBY!r`uvd{MhZ@*4l
z%eQpjVIjWYr6HKvnL4{TnHkysq3n&V5I6wLfIoi$000LMCp*u-e71l1{QQ5am?S)0
zq*PsuT+9G}Gyd?5m_Y>qlb8sA1;Aut1iA|f{t^EB&LnAX=kj0D=8VjY%m7YMw<`Y#
zf#m)f1nYm40hrW09n1hsN=6oD07?MMU&@t?oXkLdvHaVXN#4v9Xe4Uy0nh=lm_Y;Q
z0kE(#GXwPg5*Gt02FW`E*#FZ&%E{i<;lBp+x01iOf0}?^OsXK&PDXal4u6!Hc>c@&
z1aNV3HT$<D29gpta|4=~sYr?bVg55$6*FghS0@uQXTTr3sUZB%)VM(9Klc4&DLFGc
z3l~cO_kV^Z3AAxBa{@3)+JG!8Zf0U{`j@7E1X%!F>^z)*`ufLZ9$9Ca-X53|&9x`0
z3j!Mg0&@cC@D%A37zw2CwZXw);7RD>IZ*&`jP*JZWAP+JxN9^meOZ8isKxXpJ|!UV
z8_PE|;?tAs4`S->@S9^;I9N(9<lpo$xu}x8y&yhz+&jN_ZM}A{aeUURt>LYG%2pMl
zAr&W&f{X7hD#s}O^6;`KgkfAwDvmD%ysHB9WDrb^FOw84qe*`|n#U6`S0o(>v;B5I
zLw%U+bFQBm_ge#=g-OxR)VO|!$R{-Z=x2THPg78$XZqr0Kaw@t#L~%(XVYR9+%>K`
zy_bQ;PZ;n#GjZ{5cle2=3R!&F$)jv_uh`9ybGbgIUIquXnzr{Wq&}=)r6bA=DLWC$
zKTF#TkN5$uQRn+`WTH(8?Ja*PjE4?}4vy2%k04NKeWHwJp9*e0q%RP4^nIU5bmGk~
zO4CommXUQtJ_TDLW06Vo+>zU#8!w|UP^rgUa+1*24q-@CgfrTE<VjMZ*(U%qq6&F5
z4hjA&RqzWoLE5#!$fJpm=^af0<@ZNR{>^A{Q+D%>x)EGKs-8T^jSCpAL<Db2Eq>}W
z+Z~iZ6bz<msm<d4jLN&ZbTO+i_UtvWU$24##w6&Rwy+~A5rgq}<2E|14I0f%kNpi6
zA-$e!+D!GvMf5pxaFh+2Kj=92O!_0aY*O%4(ik|^=|97ty{JJ7&B*ce*_8BG7T$zv
zc;66<YELY-c;T!UtTi4>uA~pu<|BPH=$^6kbDO{%ny^lx<|0Eowadts@X=40&o{AB
zfZ+5xygf==7f}}sOiOV{efcQQF2NpNOHG)`|5iO@;C;WbB-xWTG<Al4x^CwP+9DQd
z4;j#Yo(|h=!xKM?{+KlERMeAYK+Ox3N)S_aS{D00*_5+z_PK`-{H43~ZumE{PA;dw
z5-SjPgjHZgi+C(ar6JrbVIRefwtDrOEB#xu-D^O_?jfpBc&6Gxp?DW}P+N|<$%#lq
zzi|l-*4PiZCx&dP+>)u)Z{4!dCWu<-j&q;$10uy#7<U&L^vDO!zO4_~YAOURGo|Jq
zXUxsI+WO~LQq4R%JygpIS+ygTmW&D$+8r*+uYF+0tS2Wk-oUP8wC}KsdVX-M)T^05
zTMbRNJ}7XQ5yVXVQk)j6^QfNvW#J<tGPR2y)jDaVp}6%K(wsD>Q*{37>#DR#C$D~H
z0V5YS-YIgNWIS9ppKI#5os@6Fh}@>a&56E675!qijEZF>rXhIFxwLAKc4W>j==rsc
zw+&LADM8G+NG@f>+gjjv&g7<K4gFF!a6?R#ogxG<Aj(e>mK1N|&nrz}gXD_r8dk;6
znh~2a_??C`GA?n5ZjTVP0@cdocl{)UMu2zHXHnUrkyVqLp>>HxpCR2PU3WaK@{e<=
zJY&(U8tKo_u7%w*TE`VG8pod}yK1`5txg3_3l^*dRHPBwqTEV&ERA1jC)9z>jeh%~
z7K=hGWK4XYZUrQ%mDs<z=hP6YWDH4i+WS*W@2}tfaOOpIEuRa>e{Q9uXKnDOy^CU_
zQ?8?kIKiHrXZT!rC%c3hR-la%#wx6eYld>o_i>}*6UvIGPWE|cSg1y(n~?-2{Z_sv
zPr-61=Y;vK^|;kNhRo|wbM@L!j=@IF!#Q3n_xkfy&AYsW+GNXy<2jpVR$1>9#u<IX
zwG}F}>}JU|2?L`ZbG~FEZOt3&UTzHzP#|u-bnxVO`YY^$f>-a6m~%ePMgFat^KUs5
zn)M;r^8VX+W#PdYh;lGuabK*w?!j{CCmNFsmeh~zoO8&d`r5^61Q&QXG3w-yu6Z&e
zbU#Q&bFrd^j&p8y>$rV#x=C~R73YAw^j2-l*PPX$gYJw}8q-9^lwqso%YvBD5;0jB
z_7jR@Oj!y^2XfKe(~wg$nF@pL*v-vUbgCYEC{aF$x^jm@npyrn(L;+Qvm#?Dr=_GT
z!B;7*T>IRFX7lo?Il=VKb*!m9#X6i${-=k9&d)IT03#d0dTH}v`cs5@7tQmE&vA4a
z(PNuGSu*3e%y(+wNQVd}mo1yWsLkKeL}1U_VeX8DAzD1!I7HdO_J0U-Te-f@7xP77
ziaI$AdnK+spGd)1Z>%-_@DqJ}H7qST?pXqz>6qX;NTyff;NYWmlVqHib#~~<<q0_@
zY}=GYkcQpbrpJ05mo_nb^y{3D{iDMT4gK1+<QgC{d7ls`VfO2JrSD;SOzpxViqC6#
z%U1ryO#f_6O2k@Aj~3;`JL!wnNYQECT8R<NY#kc#GJ%^_AW76mjnTDgyIX@sXun8m
zmE?M!SL1olC!zl*pr10%J6;H)Xz1%RCv%sLe!mMj#CiVh+tu7&|JB8iLEO*RPhVCI
zPA*PKhB|2QVv(AnIAi1r=Zb*cKu4<`q@)ZcT8OtUA8F^_Py-i48Sx|pon_s<Dk1KJ
z`ToSsFS_e!rIubdrE2BLZZ&26`w3LhUvAXmh@W{~^SjC=3y*}aX0GI)?`<1AGgiDJ
za(nu5Y;NOYY`X!2*~lz{b9c}a?oWX_IwtA(q~x?Jq9@QZqC4NAWh73aSHmW;=m$PI
ziZYbmJisZ_*Mv`rGZKlK011gyD2YM4+TE_ustZs}R`F)8jFRk=e@SS+6uHyDpzv&*
z<ll8KoUgXZvkdIvt#8uu8DB(6MSlBcC;oD6Hec&`t$i3!5G(<|10~EOkyXf4V1j>@
zebl5hQZCrY)p~v1?#i^*cF-nRJ0&Ehtur<LrE4l*Oht0zXYP_w3NcL%O>E=^3sJUa
zCqa3>srD%)cZioFWp3CLp2A3R+$TAQvV?+|PjYg&dB^Y(<5Ds}yqlD#(N&Uf%lU@Y
zO}vaEa~OM=*TPx-#oV1lFvTkt1^HL3RwTJPWLR7JY&~6vZ83T^wP=$`(puB`p+zd%
zxEUu)FYQ|^$T0;`n?F`G&MJQ|JoEkrgU@sSG&g&zpp3VPWKeq47~D8;E9|8rV^ywR
zk;*HJ92Ya4Kw<q2MS-~&+K!nN#+Vf4g+X6_Li!^2E$TMpIBIsOC~U5_v_%RoL&VqC
zVxAyd8l!BAo_Y(<$8;Nh@^}VA@naQ!o41eFN<YC9$(HAh&>)F-!T$aLWhKc9!RqtN
z&=;DOsizBB*|9N1WO*l7uY8-afc<?gXD0+nR1z$gQXAcGXA8lc@5(`(X|c;@Mp-y#
z@eJ9QF*OTxTE840nl|SZ&qdhlH^2e~>qXvEL?nH91k-PYjn#Mp5iun<9NX9A8cOW8
z>bEW`F>q$yYQm#lbZ=CbrgFMaDl@)({1}dENu6Ol=YVgrPWx5!=2R)8f0tE*LF>?v
zWs)MwnX|W#671Ug^I_5mN>Su-Giky5BlUg%xdR{4hI|a94P(uXOwy+ca&4JCV6481
z;$}aKW_ui}OLQ`Evbn7Dg9;Fu$=xQNlTR?!hqX*Mc@H4DgKsJ0Exnh0pdh2Tn0TM$
zoFw;C0GAZWDhe$NRSZ3IoaFQ2<?-a_x=11FRQiKSnPocr&nUh2Nf-{IkM0k`Z3qT+
zl`pc7R6bMhRPMA{0qv4sXDE`Xl<6ODJ7zgYwRZvPK1&I&ABC1ws3w4Tvp%1^YKy%y
zYm^ii@D7R+ZsVmkhskmdIbcf>cnM0HJ`D(_qc@g0o(_9aM8~uy%rSSHwX;_gKk4xa
z6MZW!PVG8e(;V+lgemG5`Sz&*ZdYh<gS3C2R4@|f>iC5>wY+*~zs1_x>|zVwcAQ4i
zt0JB_0@u`$29);#4a@`#To2wEA?owVe7J!dbLm(obEo!D-uLj}4+?7u_)qz%ku;Z1
zkQJA1n!^f(PYP>aMX9r0$i$?<J)_4-=_5YK^CiYMvfUPuAHPmM$2c|y3rggMn$6ew
za>)nUxLA)gFO7q1NvrLLJO5N@k=yP&lvUcw>e2}Y&eVr9v;a0I#DB?)+0Vv26f~-E
z)U%^u-QgLzcKt$yU8Jr})_8U+l6o$L^DucKf-E8FjHt-6%MI(<qM2_-YXJ|5Z8aiC
zgxEV6{!Er&<1Qv<<@kMIAR=IwLK1<zG~=~Dxq$Jq!?k6&{%hh+U)Y<qd-(m21^CjE
z{VulO6RKfu=X`aJYq39vIv@AP=b&?ye>$Vd@pm5<+6VTTY&6h~era-C$~tEIS?aP*
z0{2pXnBK*ii&a)=G+df%gIGK`Feu_J1QSZ(R56ZIjV!s`k@B@pTu#0qqbD2QsdFNa
zY0CUMe@$0Zr*r9HQ3w4Ce%sFt%NLgYJ%bsm9=twz{89X|!7InnxnDp*K0D9o?{HB@
z^$fAk7GGDcRqNUI%pX(ZXVWO_Wp`5^+!Hq(u`8IuB{Sv{Z`(898gMbwr&*8B4$(a#
zMsgk+Qf0q5x}DD<KWdb_Pm8ha4(14WA5J&<me}F*mKyi=vTZcfyuJP8D;<jJ5r5I<
zIcX!?HBpuJqoI_ck}OXQE<C6c@+!r1OL5gaH6U_vQ+j2ASN4;ZiAF4VB)3l`7lbHm
z>8WJduO@eG)UOEhQXe`s?F24TNQWHV+wlodbRl<Bw)(o-MByZSD=4nOT5GB8m0Lj1
zl<IU|+-NzxQl!CI62fBK#V3;3le7u#4m0q&8vcr7z{@aEDSu4Ujcy>MNz?r{X0baq
z42{y|3e^%&CEBen@gPHmXKF~ZObps~*AK7PpVI_isp@Xp>|Ww>{jBn0hh?Aa(d0t?
z!)#Sy`fim|ti_gN_FKRU3RPfp;wKSmlPDqMnh_$E=`-<-9Djra_3D*2=ZOqGz8{m6
z)}KyunIfB_md?<)>^CvFDnqOE+D%`dC}o#qsOeIfYS(q!JDqg%%x4HLdfo>MGK9kt
z4}R9_3mEt%C}cI6jxdZDA@BGvzmIamCra+}f!7`h>za}Ri%pKic~jpKY7!M>a3F{v
z(*pzpG!l6mn^)gc<C%T^v3DK<b@r6GbDsAe6ooMFTZQS5vD=YVAJlmxj)|U7V#nTh
zWqT6}LnJUrB#V(uxJ6grqq_Ko7OQmZ_lAhEcwWnguxPX2r*T}R^vLZPeoJozxW~VL
zc^eXQmS*g0h}yJ6T@iIRs)XvWFjUm6ARQZ4U3QLMBprA8(XF@7%M-<xn#jA{4@V^V
ztv)sWMwg7sl6WP~dS8WU;)f2W5&4SW9ayDVZiCls)P(8ps_==TmCFw#L+(bCAs7j;
zzV2k@#W*8!PPpCvHr%7<W*?o<PmEC80y~&>dt#Fk=~zjCSF=FVe0BpbFmHt`FO>)&
ze(X|Va*o6a%3Se2p(k+~d$3L6&-hy2Ya%TK&skBZFq?9yW1$f1g}wV^Q!4To!iDg7
zUK0|PIBx+$+P!>wA)HT3S4k7po<%Z}_cauIADai<W=tBD^%cMGGrSO*_lCLP$(nbp
zps8$9fzyy3w7M0)#^{RvB)xFUu&@0%VI<*#`WT2si@LW;Z4>J-^*ReVtPIZ+=^1N7
zrs#XjN+Tw7HshgEi)4cLAW)OXAY22V4#Q)Luy~m0TNLUNf}j#hFY%D<eRXj;#`p_k
zzb#9U-dE~mM?XP9W|<?2gII12l32}jQn;W<wzn!JP%Nratndc%0+Yh^>{@ZczZ|M!
zq|C}hKd-sTRZY;VI?(F8HZ-p=13FRYvAj>Q-3?EWPDp8k^=MP45{0fE=Xr47WWmme
z>khS@i`Cp-dm`w8KwFI{jh&}%RyTd!qWDodw}v9ne>Qkk9v<fh)B0;SWkhT^a;|{T
z_2Jq51Zsv<E5bbDfZ&y_fw+uWMYvQi8kdkI{uy2C!uvfn3}d5syLhB0-*rS|q)+&T
zZCa{Hc3t8A$8q14;zcT4Nfc+)l_C5QBu}XHk*<B_Q@N5W)KAFzsfrCUPTHfC_IoXN
z+B(b{h98GIPZss>jdNljO(>9njWcTaGbwll6jEoS;lOJ)3J5J3$ZsmakKRy?KI6lg
z7*oL*r<2HV$%XN?o58ItnI*5e-oYKX!{pf`rs7gahQo->>}iUTgItx#*df|q(5Cl8
zdZ2fn8Ctc#x7xOKz`3AaG|;*o`wZx}z0kV#JyGAadz%m*Dj@JPx0&QGi~X6NdKbVi
z+x(}#ZI2$XyvRW74o0L7^%g6#Jrq+tutN%>U)K9aX<b?{`KW>8K=~X6yz7GfjO+aZ
z_W)M<r4DS81L^Q5ws5~8_j4(?pL%cZ?sgo+CeCG!zYttmtv{P9{7bZdJCp|(q5>j!
z+xRZ^s{<K+EFw46_C3TV_GOCy7QBaQuRSy&=zy?ZBSe&Bm`76ZCfK-3ZE#pr%<CYj
z?QJr*Z7vbNJmz@>SkYfxBFjwMF$iVom+k&m;62!NwYd7ueU;upFAK)Y9Yg*1Fh+5(
z`XU7ez`zX%ee62fUIkP&_~omFsEgsiRNYHsmS9JjR)}WA<>rNv7Wn0pV8%?7hZN&w
zUEuWuixTiVB0fKpp=wAU7knABA-P{;Jp^Z!`xP><ZWH=6!|*JF+^5=~;~>Om0$sBq
zJXr{5{~$z(*mw$hM+>}C!*#C`y6Oam{_8~Yz3>V`cB-dQ2+CN!i6=`^L6J;Q-8d*U
ziDvu2t}HY|y<xq-1Ozq$T+^FVAH<t1I3jj0+Ye@;siB{+J3#OosBzamLhA9wZCdb#
z3`27a{uL;;48wMRAjF$|FUF_KR)5+>FhMgUek#Lj2oFpGN(f?fB?iL;|1fB|Uyu^=
z%zf}75X2vt^@T;c2N5#>20^feCJ#Yc%nH4l>z=>BhHv_Ct*%+lcEFjUiLrl3A>tPI
zzd}g9jqj5~zl?)&vxV*rJAn6xX834gBE@h$C}D)+GHdqwVlkINoMSO7os7bA_W6@L
zOgX^8A2Ds8cksX1F|995O<Y_H_jJQt;8?ke8Gus44r5Jsq^9261?mgPZ;l}fIJ<1l
z1rri^Q3yAKYi+pZQ08@@q~q~Uu>-`y?DRfwP6XG`xr_u(W(RgUv$)9IUn+=5-wSJ7
z#g}eCmWv$W&U;F6LAgq!$1~&w5hTP<QJ_LalGek2hz|)i4(IBP`*4dGZXLJ`jusSy
z3w{=rPb5>3?Qi))!wcgB(Fsui<>3%0<sZ_i4cV&;c5dtd&zv>0j<!9pGHE#tZAn!I
zLC8HpDtr~Fi-ZJ=r|pkghXYm6Gg4e5EDwONWMtI8V>o;HvP1g52K6#V{ni7X6qmvM
zzvJ3}f~^0>wb_|j|BW>B{O@oq%byVPUomN>|0^E*-{DuigfY7yW;BWWw@9s$sPHhz
zPn5xG#RS;CWsM|YckyIcCV1brFZlK%RLT+4`X4qczlQCv^K;qhl6s;x03Ab&TsXH`
z4T40Du2^}K4-BOmHoJG%<gzv3)7NaZ9Ie)wD=Px`gHTdAZ0fwfIme+QfF-mTvP7Rl
zbksW2SKpnyqADDzOMli2`Vp|J&-=bA5BG`vf<X4?Ui;a|UFpL*zbJ7J8{Wt`HqI6v
zQg%mP#cX4!6|Pmt<Qv}@s_`-G%?9-6gOnnmjKpW&D7la)8sB|C($_#9ECns{EH)An
za#d16_}uU)F;lwvsp4EV*~71FvO5Wn%;F`YzB8%HwGy>Fs<#sJ_XQW}Abyu*XQ)LA
z9{W@trId4QiqFKOc4tPH_F?IF9FGp#Zkf$TU#UZUh-&ILT+k^rUuSk+x2_s2G<^KP
zvnWbX|F_Tn^29$*V`Jm^*Jmt$0{{QU(EpCy|G^f-&74h~fDSJ9PJaUNf58n3Mz$dA
zKweJ!vz7$CxS5rax~nQEr2n6KNh4dJjVFNS?<&BbI@-T0ZHz2Hv3u74NQ(ZAE-<n%
zvoZr1**RGOEL=QnAe4cP^&gbslZ%lJ&_u+}!p021{8u{>XOllL1rICtU&TM;`%`9Q
z1x@A82*r#Xq|Ja9mLMbp)XiTkRTnc`bpZF@?f(>{|1JEPA!s?8u>$@e2>*>J{DDyZ
zw>AFm&ehoEFZe_agjxKt)L&dtBWJU}z?lD+Wq?l3E@GBOPX8J}&gh>q3+vwi%>Uoq
zfWI8__a{ce4g^{N?JNLH8bCV{J7?g(jK4H%08L#iok1uK8_S<r{NEQFC-Xn`oNSzc
z|JNG?9f4~9?;ieeIk^5HS$|)g9RJc>-2bDO6STaz*#4}g|NG)(`-2yO^sxNf`foW_
zuK($S8Nd#jJO^k^{29+5tmhB<1mb|+e}PXR5Xt_t9q<p51Nie@^WTp9-^=(9%Jui^
zlm(jpvC|(QOyxf?mg^tT>%XuhmjA}dl$`8MT}?pf5sirv(8(Ua@{xt(BWQ{=mM$(1
zyi6cK4#c%^GIFp4nmB*7ce0@Ud#Q_o&_5TTy`A_UFpox@mz9~7m6@BBn;GP6R%Uu;
zR%&Ku+W%JiKS<!e;GCEdXzklu{N>`mrtl9m_dlqYhm)B(0yBVx9fA2jF966bY#ab{
zz~4MhPA-t+|EdMp{eOdsnOa(y10w+hki^W*fDwWs2IPPu2}R7*(%b|X!YE>9X2yoV
zSU?psFaTy`G%-_C3k-FpW}xs!)oW&8gl?~ynSlwgvO!a4fkmCA36gmwMTx-NT?C#N
z49=`d1%(x;kO<1p2Sz$5%pn=fGcOGox8QUEnF&lRDglSCnVF@fDVM6MtG^o;0L09%
AumAu6

diff --git a/source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf b/source/armarx/navigation/human/test/findings/start_0-mod_11-low_error.pdf
deleted file mode 100644
index 36aeefc8fa67abab03f8c55b611d7aee3fb55842..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 75469
zcmV)tK$pKIP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lw*y^b9=uV1l;&fp%GM5#We
z27(3xWZ?Fl1sMbmY`{2s(8<8gzt0xA)}re4TXovc?MC<eh-a%LQ7RTmk&ETEe*X7w
z<@5haUDwxtelP#BtY5XS=kfaa-+%t6*T4V2*4Kaif0y$5@1Ots-#-8M-<JR5|NQ)5
zef{4{SzrJA>t9~Q9~uAu^Ehi?+ge|}uV1#7*ZXDlYwv1*zy8zfKi-b`|NPh2fB5@y
z#3YYbIls2unjN3+_GPv2M|u7Iz5M(C^0)PGW6Zz*m*wC6t^F^5|8L9x`uC@0+|JUr
zuOnt@U)y<#5YxQvR*j28HxPd5ww{9(*(=)5o!Ys5){&ji{-x7VF_Qlm%|GOQJNnnY
z|26OJ&w1ar^SZET|FW>&{m0o0gkQR~`c*F7K=`FwJ${S^!Y|!Q=V-xxwEvX<<@l;M
zXTSaf{9ntD#ewj=I6IE7(vIv#!Y|$S&wnr7K=`HGR(^~I!Y|$0&e41a*#5&Eu#fQC
zZr*_M=R07Z|CY~xb8#U2vbehXf3q71zjRyoAESZr+^wE=9gT!vx*ea7L{It8_W#rl
zeAcy=y&Ru^9rm^U^$xt&Ki`46ZC|}lf}Dh37WerYt(R^f{L;<NAESZrOSiiH7!8D9
zx|RBspMYrnDfd4DtpBwHdi?|E|00opm&WDu9h$xu(fp;$J{{cA_~qyQ_-bvQ6bQd`
zYwhc7Deu|-LvELkusUzf`adA=i<KXX1L2p&m7R-2HxPd5wzeOmf$-ezT)&QU68C67
zciQ(aJ5$)B`G?&9$f<U7)c*lxXS3_N(Ed$d<hrOYP7AyLVtyTcmh#d5O)`Di+zIVp
z_KE{J*UxE~|M??dzmA&||Bq<*X@ihZC*|SaI7|C{Tt8>NeE7e8j_{2d@F&x3hjTfn
zDMEQtPPgix?d&GPW4FD#Ws}`Rc<gq>Cn~#%@Yt=aVG(7&r2N4qoadMQz6pQwf(~)E
zUKW^?=M{bq#$?!j`jPP5?elTC^g{c&)8{)>FTF^3?zYdzBwByK{IVUN7xh=}|H-#$
ze8jIzB;k2spYt$2CR0CA9y``z{^#tNl;@5go$I`en3U&^Z4Kd_9Yy(ry{I2~zW=@#
zf1;Ju-u(MA%~X`<C2nB>P8~&g?sydc3{D+IdG2_2x96sgqC9rA_588Mr2Nsh;iH2d
z*3b5|8-He@e7?a~F`ty@CE|-ebrj{fV_$!MHbr^v_*we(Lza~1j{EUL_9o>|c4Kc}
z)qdTLKeAZP^5g57l*c8uaY8OjOv-b|a{l;$Cgr)K+1$xn&mG!!mBAwX!5$39+WGq)
z{K>bXZR_RB$@cT&#+kVEBH_8)G0TW(J$C4Do@J+`Ja_!q*4Iy2QvQJdy?jRfo&SHL
zDfN2(_;x1cd5PmpT$d=ybH~2@5c5fS?zpc%#C%eoJ09)Frz|OdvKt?3(th8Kf566(
z5q33szF$9A@^6{9&-rg-_McN!VzTw9Uu|<M?dQDzzcKCUTlmq3j?V}DBXB-aJdNmo
z_dm3}vi9SsuVGQ0+d77C+vk7wzg{7}1$95^fe?l6+z-WD;YEwq1~0bl?x<Lt#2<w3
zq7K`~&DB8}3df*iH&O})*~hQPgL*bUtp<DCDQgMJS}qiu1{!|2-7W0pN(slvAh`9t
z+w_>A)afx}>4P$6vs@_CbB0y_p-j&KWfdp7voaJeJcy)l@H)lY`QT`qCexgqe5pVg
ztfJ?};Ex#;@sET}3^wQJ`qh85OESxxq3g5)r)($uQG@ak?SpV=*&z5pvBu(l-cuv7
zT}2q&{1A$m5R_vY=kvG4NjXw+hw?G4$<OMCl828Jof~h}zDz9+8|Fpbb`6^p9)>NB
z>bC3fI%RPZhYjs-P&jN{ayn%#KPWu&t^<5@`#oF3JDwxcU!Eh2q80eT{80Q%TuC`H
zJ@GlRAH!|aPLtAOaUeMXM~clH+7IT|zxa1Qa-X(o0TztvI=fq(x(_7>jw9A|m?w%B
zP@PdtJHO#fH4V;o4jxCU@ziZNJ}pkxOtNYJ<NR2T?Jezqx47*c((gm!zIPlK<FFk^
z!^C`1*z(oZ5P(7QlTgWdwaNO9bCBYwW78>)7AN`Qs+gaYRSSq+FJgZ8T`oCv$eIsj
z)AVDX%UA!=ChI#kxg-x_M@zE4huB!f`Hmf2#rdRcT0rdS>eF68@-?l~4#XC&I{z^c
z+28Prui5%6u%CMG;v^0Vn9yRwJ_K$+9L+)D1~lKJ55c&L4fj^3_#el2P{@B?cBR~F
zu_N8Z-tvRAX$jriU61isv8U9F?`91jmLG?BGX^CYF}9%Z)54wMJw;t8I8M>ZLoWAy
zTDmj5r>JY*;<DrI8Wb+uz~L>J50X!B)Ak#9ylL4MJWf@ESA!vX7LZyz8fVYI;uL=7
z+)MSuz&%MigWT#V><rxNT6HK8gJOD4jR)t#$G?_A%9RI0n>IW=4ug^l4}LangL&(-
z>fluc`%*co;9e?672IoDc3e{S*sUcfyjeZ;oZz036;-#fn;sLV(Z2YLzIZd|5=T!G
zu!47{?`{R}3@zu|BmgT8V$Ep;+foEpFeyb~^%ggy@V!p)SHQNac@(g%Xg5kQsc198
z!dwPv({qAJMdz@9OR2>baH(iR;&1+-oKSG8=y(*cYMmw&tXiiT;Z&t=SHPZino*pp
z6pIB6OR*S(_=9*xR<I~Fz%^LZPMwjMiBt5T;88m@qnO*EbUny<)K1N4XrkWMWBfh*
zP(IUHKynVXbDEFyqaD+H#_?&#G#x)ZE#&0_k`I1N({XmR6q#$Z;vrkCcTm8a?SzHW
z4o(JIaBVv$Gt^)od*^JR7*~bI42r+WgVgn)?rqa!f))ETA3qswpXOs2e1%}xPON;J
z=Hn-$ZPR>$6<f~7Tb#;)7pHBS&4Du@jS@=vpl~(^7A}o4)b#P7&ci%NK6ck^4qvzo
z!|lMr`!t_ec$bE|9awpv<`WB-?1gvSDe<yzFl<}XM`t^{iSNJ$qqIrx!U}N8%HIt6
z(4cmPQLs3{^psd5^-fp`gHZI4SY$&h&bUeQhS4xcJD(BjlNg2-F(~{+td4Sc`H-Rs
z7Qv2b(nDcs3<|d_Ob~dEf`C1&+A$att%^%-7__P#gJIAlnm1_utx7xEws>nLoi}Lk
zP11RTcHY>E1s3fWweLo4b%SQzq^xext{aq9m@lJEzCZ<TMN(($Sb*d*Y?^VcM9x5^
zZR<3hSimap!v^KFtvWwYP8+Q74a(@J&GQ3gv#r$JU<VBfcMhs$TiHVB6W@B*4^0Ak
zYtZ8D)TTilRCttyp)?5GHK>DjPIDXUSq2G*yZPU_W6<mDWXp$;sNO<>Gm7eEP+U5i
zbX!<ggTjfqzGjE!6-RtfI4?iti<5Yq43j^m$@yj&hw+WD6y0&^odV5!gIZ-NyF-bx
zl-$smOzJSqv_TouTY?mwz%*z`wrg%sh-^nIW|~5~hKwI1ZeYQ5<qO!L&Df@?gf?TF
z7!@zZGDw&U6ctNJ9*WAK@bp7Zu@vOcN~}v~+X@(-vfRJ#*75InL`vHg2e9$wUEN7D
z2xN8~_(37J@zpj4I$1x#1_|KK@3c_@haorGSYpRF*&3JFPq0Cr0GM`z!X<WmgN<Uj
zpYh5tT5}L$#*oUe^hO)s($3GTNiuhQUd?!TKa@S5i}L}~??XW=CR_EzKoFgi^wgNF
z<aF4APS8_hwh_0u48n>BbGmTmn%tZ)7YBv2jc=k!aQ7Ww4P!H=D<=bNN2lniF<WWb
zJ^YI1s`Ua&Oc%1e@BVMj6yG<KWQQp^D4gkr&$SiJ6`wO>mocWKJPgZ0!LjXdPI(|o
zOl$KN&m%rTCV>tEu~s=4diXx7<a6)w?HMF4KYqZSf=i;pr3zzlw7GnI66zVE5TrE*
z=KB4+P$jQ>)71DL#7CggAF&t=$U)-tVei+2uK^7FDk0usyH^SE4xhY}NbuQ70e6ei
z+bg>`^Q(k<n3PW7nJ~@{t(ckoxgA2i%E{3o)9cRJSI$gQ9%kmCaQZI6M;on}nH2UO
zHf-IK`!HFn{2;w*c9cU!vm^ft7?++A7@mW~B@_iM^8gi}o<0s8c4WoJVR2H8-*o&U
zrl*fZk70RgVF^}#D8c|;oWcdIni&sN7@!{tTK<~Xt`{Fdzvg$N!&<BKzI51XwQD=p
zXvG-q#0J9e+)jTJM;n^~Gt?=aeY&?RyTtzK`UzI3Q*g8zWVyP;=E-r>4s4!2X)r+t
zC6>|-9xa&^4JJ^PNzov>D{KlxD2{g1NWr2e^|>8jk{muh)yA!9kkVB~M++%k^~r0L
z(pBHQ=66q3?jRVXPFdNh#!s+9m>t#Ror3Y{B(~T13HJv#6bgYgn4g0JrMJO|sQM_v
z`m9x7#Rik1%7B6OS!<R2g7rB_Tor7Bs&6Ii&q2YmU=-BKGf4B(Nf@4jy?(J%!Be<#
z(EqF4QV3gj3IqiV&_Uu#o2J9#Nl`A(eS^!l^09t0YLzFeL3^*VmtcT81?#5Z)>pSd
z+i?=cW=4eEU5%m}AL0fFYL)w|!ChKQo><d-Orvu?TzJ)dxNu7Ayg7j3`6038579Rp
zX6K-A;c!4!`Ow1bT%3d*ht6H)RBIH@GTvZ%4hlIz?_iYz(26F+<6bl&o`RwYLApSB
zu6Y>?<I_o)(5eaX1%NBAu4p-9iY{y03Qtp!Y1kl>i<FNBk6Ph%M}tHzQbt;+-HVfA
zGB7p=1-yW{=@hj6EiW=CVQUVGL2ork;vz3#n3jW3`Iv&o;FMU*4O|K9GS-N9!ysde
zZdJ_POhtw$Oh>20mRKmq<)B&z!*Ni+1%obJq~;i;Y&m#D48a8DkUX?qvmqa#{uZe|
z28U0PNo(-<ltY5TAZyD()<Du0DM+vwoq{Ps)|NwVf7^l?_;c`I8dF$?gFs&4BDF|`
zqSZG@abzrRD2pzR41Sg(oyy=;DY{BB$j`DTuOLE;tZ9S8q)62=h|sc&SI~w_YF{uS
z2MN5wC0da>W=%^cuNs$Lpftf`tVIf%!KqO;F%0st$mt4u&?y}cf`}|q*<k+-3U~+s
zS)|1o)Y(E;?P7+jpCYRt7T=)oMTASDK-DvdzaodO)iAY-)IAt)PQm;j{w@?Q9XzG<
zD^dv!?t~(D0xUGAV8%r&CsRY-j|WB5)8WWpXre`0WF!GN0kg;50x64=g5h#C!y+3L
zFr0Eu9t(qep>#34o*Eqtuat9gQCCX3nZmIe^pFa<CM^|am{VdIu)3TQbFPQRN=m4d
zg~}{!tf~xXgGuF-*o1m;aO^>a>0eUctrTV*tvJ=vcVP@&DZyifZqWX55*7ukz36_k
z?w1yY7?tK4PUzC)Muimv5-1!Q;-x}6EYhoCrwj_k3z9lPa!S|e9c>H_`BS^b)=qke
zMA7AIr5uwBs&);X6pqY|Z2WG~O;stzCc*~Rac3Kb&Nhdp^BOjQlfVe*eG>(GUy(5Y
z4gW(yD@+45yC-pQ-(i?vC^de<g8<#G<fR65awmZ)6kReeDn-{!iBsnm#}X8djssIU
zI8R5_;G`6dtrxp!a2_ET+C}cXS~Pf4ICz{Oe-MV}nJOAS=C^8aw&O)pP-0#AQqLp~
z&11G|=%ip|p0brK=Xg0a5Dpzwx+{g_#GxyvhN%(!SWXUuQ&-MQ>(D5WHc*+a6eyxH
z-pZk;icqlkIFx1Alaqokj-iRUqE#ac8>h1Dmlm$OiVVT{WG+8Q@k9lKem+TatLH<&
zz@9yze1vEolsKReh8IFGNWR&^ca)UnLy9IiXnbZ8)B_Bx`iTe;t5bA0S60n7DK&G~
zZ4FI1TZWlahOSg7^@Mf%x(vH^{URxsxvwo;HW!Ne1V>hQ87B&Em&C@^zR2bUZM$yH
zTGb^fNY%%Vt~ER1x@JZANgj)}<a0#XFNbX{Uq9PnlE>j(Va}mNokk~nr3y1sruSoU
zLg8x#zEWS|i&oE54^GNHzrD+#%!JW4yk;%}27v>Kz;Qxs)Kga1OxkB@GzdT2947?W
zpl~1<goDJPLK4<<*ODd*M0ZD<Uk$eVGD+k?;K)fS7g;|j>qXYr6F%7dL=4jPqcJEP
zdjmVSul}RW!Q-3`3J2di3H(}unLR(2qUd88=al()`Pm(m{-e#YPw=i&>?Q$1qIr|n
z6<btERxobTNx-Hiy%4J8AQ`kOo<f*bO^0q$N<c}aBtATYazMMmIW#GyJanePdCE*<
z2W1(gI%{l$K%JCF$}X*{fjipxJ~thps)3UtofMp@sgr^Y6&F2HWj~}#t7v2#jY5T#
z=b%U-#rI~Aq=$nEMI-Yh6sd*W_#%}QR}J-)sf8A;DsFX%q`6Hqhx-f%R$3#2M58Kp
z@i>2&IfHUFa|R_Ys%0Gw(riDCHmw|N+mRL(_T)&53g53mf|<i@I;gJD>KhcARM?jz
zO{!2soq{=IXO6U~unotxB?F6_a_smH(%2moxDL>w*8s2IvCEdn9vr*e1~35ziGBm@
z!LiA0fIZmcH6X_~c?||-2~vNhlVG%I%5x7kxeem6T}}h;fP6)p_}%3&A-}u42IP0w
z%6C55r<ER*K`NLrIo!2ya=2;X<Z!&6OZs#MX>$8`n~o_Q>!ZmpMUGN_?MN*d@JaGZ
zVS<)^DNK+8Y!?S9z;=eW4H6wwWFmb<yLf1FOp%B7O8?u)D8u)8Cj+ZIa^zP1njL+k
z&1I8U&?s@Nsyw1(9L=gjjH3KH#3))-uJ12F>F{HcQ6(Lsm|IDQ=*cG+I5ItsHb``c
zl2H_3hZwcWBT7cC@`$=E5hVJ4@e9LK$f}jzVe)F#Y{09XVJGrK57Hj4Y;b2ku?O^J
z56a~19?jSS-Qo`tz4740PBBNvdfh4J!u3Ad2Oi^$S)9bn0q|j`kfWP_P<S`6^Etd4
zK)}`@aXMfH69#qdP?-Vf*AkU!db+l#JEJCbx54~ET!4TQcaJN110T7rQ7W>=mb`1J
z%>UATOlAI-E^R6kv2?LhkutU9?GN)AbwN~_-lR*U$~+}qG*#vtg~h*s6cdUra5vQ=
zUhp!qh!xQ4bS+kQe7*AStTO4Q7BK?>iMoViawV_nDidSEs}Zwnnh)3AG#{RdrulH;
z(D>qNkq_d0cnBKiQ_+gKRJ|OGBB@$9d_{Q^TA2e<s}_!cL0zd13h!#UaOQ8|W|qmG
zd3RfP-bPj}+%z9-I4>h**jFZ1=q|Z3g+dq3mH836lxET>F0T0?-DRKb#=Gpw;p0M5
z_S4P_Nn^H4WdZ~4+Uw3(5g9sr`I_$QnOB-O`h((k0lM|C%pFi%z=tvg4lwOBV+)XW
zitvL4lnoIH+&G4YNK<EUzXBa9gZm>CA~IYH9<ymE#$n)mA~#i07tBq~z>K9bEML(Z
zPKhWJv>2&^B{AM!AtI5!8gVA-#6T6SXp2Wc7HtRk6oD$Ey+;%ZBHEbAnxQVtWK}c_
z6Il^4LkdDw4jco9zkAqCWuUvla+u$mp*zfPRd`R`po%I2s4|dU5kj8t`eFnTb6pi<
z<dmu~qy-d48R57wPF>MVBL|g}<K9p}E3<()uo*kW9N3Jnsu71?rG7E$oKaeflWN9s
zF(EeNyqFN1v0zAueJNh7Mo4+Yi*X5Ev*QvvqubC@*c#d~vqLY;)*0Hy*;9H;17hqr
zBIqh(#}#C^Fl9C)@hU^b8LU?sEv|UJ$f3=UKhL2(5sipf9<kwy9P}jG76FOmKIQqT
z6&Ui16s1@h5{@{=ihythI(nupVix&&+m~V`7Z41wkX!(~e2TfO4AYhtfK1s4+l-?C
zZC9b4gHq?{PtTl<fK#+qgt3wd%rR4hX;loizSNAtF5*F9#3^{-5<25ttHQ1I30AnZ
zKEaB%W=t(|YY}t%X)RMkt|!%=#}u^7G}{d9WtwdU|2oB8LkJMAi0IZ=R8iekGlc|K
z9I_|g;<301a*|KgqBTW2dm8R}Ou^7j@kh$j*iVM>%9DuHTn1i`_8ge)dAWG(&L0?_
zN*xA?x)}rRl(kNA;vdQsNA5|wh-wch%B<ZCNB6AV^PED~or0%A>U8&%D)60oyb&9}
zkkacEKVKQm9pf^@S`G_^SnInHA=b+j#?Or14E1N$Zl(h`1<43l<IaqNm>J`)^_fuI
zwLT0T(p%XJOzK6710NJK-qDH$%PNnIUS&}*p_h3Upu~CIb1qY|hUfgA$CS_E6rU^e
z^(w&5kr=X&<Rh^Q6I3`eI4hKW!ld9#QK=sD9T_T|T33cjP7fI>IlWhA%Tz{zGvo;*
zALvADj}#ux47xk>b&y5;%A6jjL}n1@1yx>|LCh-7?4jC~E0j|UQ%p%nOf-%prOFs_
zB{4DUScy)RLF17NwSa^~r!W2_k||}nb!h)>)!Yzj!_2HqPR{f#r}$V!Cm$9;E7Jrc
z#SXGOl8Iv#klh_$9wnSP1rOf&lMT=1i&&LZhi0rm(mI08l^RzWZr)_`bl49O>$rea
z=QO;^0CXklG4VN*`D(9Iwx4G``-fi{fll%t={~8)_pGHfhRxAZ7#FzM8l^EjK1yF?
zrnE8~D<jsM%n+nb*VYy^V}E3IFoeBH`W9t)l21jsnl&QYmnoamNj|8IiM}$wlbeOF
zqVT3G0Q;6qEoI(yrk_@ZzAHtQnb^o<CB<EuN_HKjI_JYOH9IqAE5qYkpC%N`-lQ%!
z*hI?DW&U>N@G^fp^L%Rye-(nUm!QP^CRc64hgJ#2O!3a7<3VBe@|q8d)$h}Un7*77
zs&f{!CxV~x9J;X@vzPa2La};Da0ccpE1SvU%G{15?$~;{E?byqN&&BpDb3Qrkx`y$
z<O~1FKgEycbo9#jer2pzM))hM9fM+hdQ6?u<2lnzps!2<P?9|tIA!7wE(A9us~hv2
zC90V%ptOH-bHWC2mJfCaK!BT&AOlWW>jXr=y_?Vq1}X41)@eoogdq9caL*xV1fG)#
zKfw=^&!|i@3LpeI!5Y*Tfi>t<CZfZKG(kS_ASWt>Q+zfO(M)RSRTf+zIwk~#zcfBQ
zIi?zHR>4^CT_e&(q}|6;4m~BfWoQvxBWFT%jgW$E3r$0a9F=(zfb5`DNKg-_tnrYY
zKMAx5#czE``lf$N{3O1JizuI(Tt2NQD#^*;xR;?z^=0aXz)qaf;yH(&6Ks<VZuE!>
zS;a}O1Ye<?O?(!Y#XdnvU}kXibjd(q3k+rufa-GSF~PlUT6u5}DzZ!TU|-7C{z~8)
zeoYeF#=kh{@k;y~e1n!3P;yA}$?58<0d`1E5ay2b6srx+Z6WsX3z)Dz{*mnQ<V_EX
z2XonpD8zflmXJa?dQcR5N=#r39n;F=EFQ#*n@PF!VDT}nJXm~AD-RaK1K|&P0f5PW
zK-eK^wvDhuayK-h4)MmL84NhVL4gFkC@3rmCsmmqv!z&sk{Z_WLeiN2mU0n#tH7;h
z%Ap7KgvbiLEFjn9f`HN`sIAJ(8=-N{6#c@NC`hkCaxkuvTnOYXc^9DnC3M(Kkpx6Y
znn1{?NG4F(hcW?~v4v49(bQ7-Ridd~TVj3{xLV~iVzV-$sD&>`sBII0oQH}o&^M>F
zLoTfEWg<!cWa<$S=BRro2;EH4FP2y0*byTmvF<LElfNOb-l`RZDZiz-s{+=`u>*9i
zYi!?S#XTeeP6k*Uba~E{Z5leZeVg_mc74;G<wWAP!+9p;!V85<cqRJbr{xHX{?8&%
zMvj>jp0pyEMv9&yOh#UJO(c$qDBvySTv8}|!r}pJ<Z_{4<6#1A$22%8Jas^g5_;t_
zlMbySj?^&?9u(R14aOAVG(lKi1l$bkREV5YJ4cBlc21)N$mp6TL=l2$5wA$$Fn;9r
zbsC72y>p3v2nAJ|lrlYcoWngOmIzJLi>M;OrdDRm?PYqfpUgc)R8sPkgokLa^Rowo
zcZnfbk$atvL{KcBLrmFaYVu4W-dnh|NlDcR4%t0bBbuj}1x!;R<j#~F$dBsYr-6d9
z<(UtQcHgF6PLNlOd4qe}RG=L2`?df(U<^q<<WNi|M?P%&Nl-3}9-)haG<6$`I{M6&
z<FaT_#207fp$zgQZS(dVDSM)oZ@h2jv0b-!iQuaFoCGCL7by84KV8QxIwHF7IHs4?
zkLfXq3KCK<jMIJ`(}O{vYn1QIF^h$uOhUk4z2lr_OiI3s&dXUakn%$ioa?j#Q4l~J
z^5k5n_q8K9aFS2wEEY(~cQtMn&N98MF6ho#F1UC+XTd<qMed$?c`}joI**fj&T_&D
zvzYLMde(V`Bu(F!!Oe3P9HgX7^22&gq9in$bCxB3SWn|8@0_%m2w#;V;0N`z>qm4^
z)a&%6J!fTxlvJYppq_31q@NkCJCW+FDx4{tM96Xd{GBboX3#*+S(PE>)C&B-oqbZG
z;&}BOI}+{B{!@!O`=mCJGHGnS>{)jSH|seoFL8dhNo|VbvQ2~e@t9Q?5Vqu3?EE&3
z6+6FQTa%6yyPgupmS|GHj<EH9QJc?wG7e%__sJ}YUELLHB+@aN2flBqm%#6R9$y!8
z;heORB&8h^yLL?GK<wH%nFC#!18B!toei?swAmnwO`8p}*rCZFi;SQ1r$OfV5VBuL
zNyB6O+9{f{hf8=~h2}hV#d9xc^hR!m%+RsALAjctBb!4nPuQwXlI1-9g$$4%6xzw3
zZ5hp2_Ciydi6-%zF>{lB-h8TxmU8>tvsW}(XZRpp&HO=0>wELb*2&D@&UkPd`Xj`7
zP_Ax=kzZ3ZonWs`i#~k1HZ9t(|07Lj5W4@FJKe!bIsD;Rv9+<~6QhG^fh%TE(!pdt
zvDv{Ce4HIj!N=Lb<Pv6((!&%FzWA3saj9s!!OPjf6uj)Zu7WdbkkZ4n_ehD-bAoe|
ze<>KJ+-3UKZ1r%Swt0$Gy8D7{+w9$I2hy<6_DKM{F-Xq1Exmier4(QrxRjoy4JQsl
zjIPN+Ap19PX`kj2TuM>4fh8%*HdiJGWpcQ#@tmu}b>yGrbb?K~V{JS0(_)P~URGVO
z!u2~SWd06TrLMJuSx2gqI}TMUTRYg5HrNh!rM%n0u5+GIu!m;Z4(6QGeBua6+U?*L
zh226=yp<I{aK@B%nu;@~@ER2ke^2$pn|OrYFi0H)=S<NxDlQiWW#>=EktvFf!M%tT
zsHAa+VI^Hr!T3R`d_?zVPQ&?8ie}*lbP#eHzW!2j8hbn>rx6TL%NJi$9v@hK<uu|O
zH3*!@iRIJ0iCr`$EH1c<vLa3H#OhN_hN5l7(2B*Uhy=>7DT@wQXO<apxTP^BuEhnM
zWeOTDZ7g%gaA{-3risLYU2NhC$1*<)7lxLZR&l4ZIEfdfYpgeeR8}l_zATLe&zGeh
zif?7UF6|ipdR;n_VtJ>$Vw30FQeStM2MIT`R_5E%Sa@ER7H{Q^@(K!XN(+}Moe+0N
zmI*buJF=1iF9j!C0WXEil+49#k}>ZEH{O;hEx24VC9uT3IkJ#>qaAD9+4A*ez)OwR
z<?`M#nWR^)FT-7GY@_`82o$i)3_&n~Cs#8F;4Au^8A=eVlk|;{1?6ai;_K6ODIy;%
zQa1RYSks|!i8!hm;9}S{h9@HE!jyZlFfwDLoqy|E%QA-o0Uss|AqIt5W=M3StjVYr
z6z|Q92n3*5$*>l~0y3(_f=w354Y&}q%w)iYm?>`|Vr4AT7H~mkk)yyc9$!?ZBsf$f
zfC1RXKpAqgVW0!ytr7n-00_8m(9<%z05L>BEf|F8kYP$LNR3GYxKML&1Vua5F0_Pi
z-LP3E2;hbdunThxm1Vd;0<8ew5Cms`hV~;~%Mi!EjBqZ?ApQ<rsAhx<bfKCNE}{Bl
z#C}KUnq`1K?&VCe_qdj`jJ-z$+n`*d+`Ncn*K=aJGRFHZXpQd|L+LC-?Qw5swYgsz
zmv)ws^}t27n!+23Mn={n_|FhWj|as9GQ@C?qmeO&&?FQ#52#n0!sdYoYZ*2V$XMc;
zeDm_pGEN?$iVlmi@+U44EMwylkLj>2qI7R_!uVR&6safnVB^PdTOD79LCW~hO)=st
z*vptf4`8(^+#3<DHpP46>y+`{#o=-|NWmbIgb2kAj2#B>cH#1TE8^FtsO<O{WKebm
zTNVDX1w@lg0oIVpik*f`o`R=qJT+sdA%8E?(=TEgeaB7On3=6?jg^>`%K+9ERMK}|
ztT~(#B7BGTVpH&Ss4q4}U;Cx$Adn+4&ux{Bf~z)wJALz7ZD2!X5W1h4DFEAr<P?34
zoM=;Qb;Cm?y>N-<6b1M@?~OWVgyIA4ioyAQq)ibaeyKK4vp6@HhbHlcoB(6U^`d(<
zn<A_?%!UEhkY7`Xb;vJMp3+A7Wz<bQ@4<1vI=gT#nNSgPF|=IHTIM4m2g5Sz8hIL)
zQP;SAa|#C9V{Rt7gWI=3;!f{h@e@uTMvzHHMo9$+R?|R7tWa_imvNS%*+_D+49!Lo
zjAeNChNvo2d^RrV9Q$o$ua4(r+K#_h*5<Sw0LU?I=fG3Asu)-KNAXh0y%1M*PQVx^
zH*rosBG_F}f=zS!QS70#W?bkwjvn7`*a9X&i+m}<?|mz$YEYOX23_B}-bUnRSq79N
zf6KxDR(9L)Am%@Y9*+R?<y-fDmJ#NA2}r>>-pDm`3dSkHD{9|+A*<w~^_(_B7k=wj
zFn|rel?7)RfQ~#lpdl_G1*@o_BjJu1ir>n~BhKQtZW0GYE3DW%eTR?%Xc@YWEJ1=g
zek+sE5Y4_Q-Ow_e9T|yE!SEE&`z5c@GQxeAc-99E`H_UC{8kR7WzakFED31&oynL)
zz5G_jrbQS$GCD28;BmX@l*Zr0Dat%2<c>N5C&q>zo3Zl9LA8vPN1kfncsjQz#^u}D
zyXM1%cg=?j@0!nnh;CHCb5iGnI3F$?im9pP56L`l1l|&>G)OU<%=F$c8(AsHD7K8n
z=d~?iQG>MMK}<u&T;_CUJcg{G>^_x<x9^(IK4()~hVbvZro+<?#nR3^?Ql@FIklVk
zutD)toMHY*4=1W@Q2aEQBL9(RZY@*0;Y@0o*$qM6GP4^A{Ko76q`g~a2Ou%tDVPp~
zbLI;m!QL7X{h5VtEfc$4Ic>VXL?S;Sd4n=UUn^+D7pzHDIo4>!EC3%s+~02^3|OOC
z1`Gm=i{1sK_yrLWAb*?UBmj0`OiutDf;9!d9=Pi!O!2pX6^Ld0E${_X4g>HRtjWRy
zhQmTk<Zl5zSkn~-z#xdE{4Kx;i_8ZAN&tJA7!%G0sZju>u*`<=pag5Q8WEFVO*bJ&
z0D=+r`I~4MLBZ5aK+)eq(-@SFb}&G&X9VRS-t@PSJBUa9Ep!iS)XV??Vu(sxzJ(G(
zVC!!oiCB|~3bYZzVSfve#G0Yy>yrTsOcNq%2gQ%0?v??BLKyCEfu$_gX!auP!ZNo5
zs4K+t{uVHcWwr;vTYv(-fE0`{!NSBrkXi_!7($7E3rfbABeDo@#*`%DfHc;mDFU+w
zsO6v>nD9jL4_RiG03V0&=RpaMH?)G=(k%hR0|<43>;%uHZXTh?Hks;(3^66B97jO4
zWA=!oy^@08a?ApF$eQ%igMv`L+5?!d##EQ%(7;z9Bm&8QzX+CerPP=|btD9n5Rm>G
z!6eqG>LQfHnp9mtIT6)<co7g?k|aVxSxb1Tl^Y;<sui2i(efiN1sUK}SBkTLMyHA+
zpXgMDM?TT1V7*@`u?LJuI4S+)&;SM(DgY3J3!@W<jKWW<_!+Il7>k!}ri8iDx?smR
z@D+8;n(h-%sFoKB2j)JW_F|2LZv~uODK#b!&@l=->G~(G^RFb1%xyJ|%x$H#OA6i~
z)@Ar+*vXX;!*6KCnq@*D=)|UkCj^~XlVyRR6U!7R1f5(dK5`fzfYggqCws&p^{mkx
zK@7@;z>#@6P?ye{ES7WA&=cj1>G61M8agR4H0A2KX>gvIO`~_Tx$0<B)XA?F$cM`h
z5=Txj#Qvkrfr(_dYhax++(b6T+MS0+PYRcfqjqR)B*1uR3af_1FZQ1Vj>Cg@YMi8K
zl{|T;MoLONnCI@~NJ)s1_P`gV*xJ#Gr3f2-4Fzp(hnP^Ew{_*mC`pA6C0H)vMy`~2
zaGXh7A#8S<Rg4=!eU`*9y%6}+IH!O@O~OLBRBM9PM>xlof==i0N>tXF(x_t!#ed}+
zJ5w-t%&vc3Tl{%X*x63PD`9A@shq%iXsStxJ^-05QDN>%vGekjLY;J`)XUJg<6W+#
zI?cbd`QLgVmW~TlQ5GQtPfRSGPfUVc_onph6rb7wRy=KR*|Li$9fu8Q&zqhB!hShd
zfvG$lJs{UjhqLTjPEz<#M9lNza60#a2RFSf<<Q)cf+xR(Grg#JPH!qOs;>m2kN^Wu
zeMf+sLpbb|8-&cBD0Q7=4{r6YgmAb}q7k|KLf|MN1&IKDrBH5f1adF>X5h5Oon4A$
zqLE)IeUkUfw=U{Z-t(f49|@wPXS-@-qLJe^;zHrjIH0v^=%nzgfg?*Stt*Lx<B$S7
zUY}Up%U#+Wo9DFJSANL9iC{l{>v;`#rAR|qJ@SedZ>ekW;_XVocLc3jcfkeQ@`H3h
zp~O+FO`0hw@MlSxLJfgg<6@zKD`nE#Sgas5JJd4(VF86>^H^;fo2O`#Qk)bj#XXBD
zNIONFgY%4R96SjeJC4XQib15(%&WUAg#+_=>>3xxVNczZ+rLXUO$v2WZa+)|Eb!3C
zD;IcBFXhhD7VBuy4&z2sUS&OugXcZ#VH`iKAr=BjBMP-bWM;9P2<)&0B-v_c(-PyB
zr6o2|V9p_*o)u4MIr5?}jZ5C^r2)!&y);r$e`U60agBE+aPZhRi(#=pMlV!Wvalj!
z7@K58_9(W*DDN6t^gCcnc!`(RKQHmpMZn@WS4y2d4XmNF$QQvIIr%GIti+Q(4OZ((
zzXwbDIAsB$V9I2;rOyR3w)DARekO;HvEq?w?clG;=|Ud2S9*kaPnJ%jxF(w&OS}~e
zzY}XHrC*9SVClQ!r5F5Lti>dk7r04jM<jn-YNaoY#i8hLTfTLLWm#$5x_p0p%pSf$
z@{%f&3fkH>dj?tDD!qrec#?mS*G%bvjB6&iC>IdO1#*&RnObnel5aH2R1()@mZ@H!
z?Q+ACZ@c`k;2WJ#D&U7(o+TZ;ywpiAFz<BeC*~badXiBN4bEoPLo+;uoI1WHk2SAi
z(x*Kr;S<-9J81r>{;v5n;$PSbRq`{4!BtG6QinvcZ{350_a495@EEd$f>5RXjDips
z1#uU_YYKl%qae(}ersM*#B>@3VHWmV`6*ImKPrE`{$SC*ydvR>^BRT4|CYFCAxn7?
z6O@QZ$ijZ`Qf1Zm#%s|N7aKe#mSx}@FGf{rxba?8h5Z^YM$fo><ExOjRD7ZGDvR%6
zUU%_L)|J?z*FEpe=oZh*H42-!e50_+%Q=X*WxBzmoYXa+q-$OUQb^}@A?jQ%)14we
z2)K6CcO@?-`EAO}OMcRD!O04roDa`H(|ow_rupE_U}lE#?+A)erM|}C78T}WPK7RZ
zsQ~5WuY8tyLreuNuaW6-<V7<T%DjrE4vOpQ1tiV~XP?n6vL2b6psR7J{gjAHkQ#30
zxl)*|x`?Myl$Z51$#|cit{;l$@f%)@%3fkd073^~2WM;n4DdPpAS`<YDA1dbAq*(B
zn^6v|#)~M3U{(Z9aDfoO3Z-Dp-wd~4UEmDKK;_`&g}@Dv7&pSLJQO$5G??N>PWC$a
zAik}q;zqctQ*k3av!~)l__ChlR!4IVdtqVbjEpfvyqhW}!~Qm1LX7IqCa6SKhh}sR
z%SUJY4r@$jj1THiPjNu3Q=PFwtYw|?L@0Ru%9tb8#9lHm$q*ui)c}z!gPTxwJL8{N
znHv#O3rHD7^{w*W8EC~4;2Dg?I^hb~T2xHjgr#XHI38hN20XY73o}HED{{;tHhhXL
zvxp5>^qF-Ean*KWAUHzUtW$zlsSXVC7Wyd5wr98;O1o!79jm`nU0=RYAf9C?zg0qB
zk$c9FZUy(T5Pb#!ngX~HBZ!js8AUh<jP@fV8E443F+hbO1IDmwlaA5nfJf_$PLVo+
zFlvQOT9;s6waXODQXV=5vuXe{u-Zd7Entga=`El{oUil(52BU^pde~#03AXafu^H<
zi9{WQ4PCf<dj_*whfGzt>!4Ic#4eyjFe_`>Dq{J_XEH{XTxT>gB6Am0G_pQrj7HX%
z49G(Y0X6^+Wt8xsc)Wlji47=2a9{)>2GXabhi<BPWdraKBAR`X+nSNkAua%zo3YV`
zh-Ass4R;0%uwH_6o>LUI0U{_vwG9BjisrVhyfWC^w!*M}2~veE%hCtRa7LCJkccz-
zd{9D^W?}iQF#H@XhR#DoGS*pA5*Wz{lV3oJ*mD`m02<1G`$1v!Jl>cMdT96um!KFT
z@K-%&4*xe`4`qgcDULcz?=g^CLJo*TOhg#%n6C`U4Kj||47M3rE*ZyY>MYU@EbC02
zun4Bkg6x1TLjJ`9QcM^E4AIp};xI;6GsnXT7=}}6k>f!wL5;04wKk}+Su=f89t)?|
z;1kIT=^OOgEQh`^kA-uCo~zR504PTW%>q&!@0G2wnyg{YsP3#`&ZzFJPrfmcB@2`T
zEGe^s1|_niWTY_CJFAUvoq2q0My8jn4F-BMg~_(AM5vrhEa8CHXX{FYqGZ^V2*s&D
zFlR0A4T8BGQX>%_p5?m%dY|cC1`wu90ka4gSCZIbj2O?d+Z*)jEV8|YGdJsJ1F9(#
z)|_%iLYg;s-7k3y3#3eCJh^h_oZ{;XWqdKfJ7waXF~D3ks5iJovf%W#D>sj)dxv{6
zOGpC&DzgO*VdzRIw2i5@Ql+;Y`k%5AZ9AB@7%k->l1a>~m5R(T^(?z)8&hjjoHM&t
z6^}P&*UFo_MS5-1CE^C%KdTNilsyXuZ%nXF@eOMrO8suUWXmeO8xv~j`P`zxX)u`<
z)onL?DyKTM8}n=Fn%tO8D^(TcHX@tW7!RLSItR4X@=`vox1G~<nn$d)Y96uD6wyqk
ztw_{yijP{Sc_5*9wDynbq10nzC_R&t2LUoh+9lAknBzR!HS(8D4?!9=c)>{fB1nlr
zLMAm@{gsK>qaEA4<}_mE>okjSWgy{u5RgPZ&4Y>Lng{d9i=Ki+@|YC@6_lH94Blt@
zx)a7sl;Lhb`C<<IG6<1fFHaG0zcQEJDd#ce+Z&+3GAG|36xsF1G@Zz=my>6QG9m;3
zV`_j<0{lS^(Qr%?BKSZ~h~NWwi<vzj$O7BzjA>v%AxqqYK?&waH)Vc-@Dm25I`)Qc
z?3r<}N?qOIYZFw1Q+#@IkL<4XtW1<MrX;MAwLA16phkGR9TTpE1t3~NPb|iy1;?c@
z;G+q+A}Br&-bd~>L0=g28P?8#ra_7mr2D=dmZ5Mqj7bl|;usX*fY35zB7_h<oZ_>S
z1l>(QAml&1f`AXfgZhLpVoaV83dx`Z;~HB&U8%df0p7x<brU|Nv+Yx}Y0(5v$wkNc
zvXlz#m6$BXWDMc93`+1)cPLEJ5dMo(TrdbEW{{kjx&UDshoEMh;uGdL!N(#Sa}O+<
zl!CY@S}6syZJKOwQC9cPi}O`x_fBk@by~HbNhzgF6%mAwQ(P+*&W|yBL|{OJLgb%Z
zH7Q&*;-eFJXpjPhNdga8z-J0PRCN%@(M;h7aSu%4GbJ8ShlQu)lwK#yC1c4q;4&>&
z(xyoVFcUo1yQ3lt|7o-XaY=6Gy%UNpMHvv71vX{C985r}L2*>96lNmO{AFpoGldxd
zq0fC{GAL}F#{{fp`?e5zE1DBBm$9~<z`F(|Hb}nMi9(&3Rr&-K=9KfC;KXJMIg4t4
zXU}a+6276p;yzPU0k2ySXfs9I2#9ZisSU~ux0Y?wgab;e<;Z~BYSYlM)r~D*wDh`(
zvWZu*%juh(NXc~HXSpJiP&E12cgxm{f#;+i$ay<wPvAUlv?w{QOZ&v+BPoIVY~NoA
z>=!NFu(C8HkO7wqg~I|Z{-of_HcuE3=Fb#dJ5V2mW$2{yd?n!FOyL$sv9xp5NL8SU
z3n+2A)@dYBG+#e(0&tuubfB}6CV(L4wrO^L0Es4<gh}7>;%|qp)YRTIIX{vDwwx(?
zYKWTSm=@rN^hi;Iq5{W0J(-l8uj{vo*a^}E>p3V6QMygf0ilUkflw;s;w1IyF@9JN
zDK$wb+Dd?wW@~vR%Bis+>d~g@1|_wGV}etSR+Y<#HC6%0nr)tq|MdEg%h2f8&pbXy
zXs`YAoR7V-?nfJ@-9P`+>t9~wwSN9L{{Me|FS*NMIK2J20r7iGXU<o<?>V(NVaVI`
z7m3|0ciNBpUZ({|uXQ>ez6K#1FA`asybk;#Y<>F9_(pGSk_-V!UGuO4O@HG<Y5=LH
zLf|h_*U2Q3{XS`neIQ_@BnNh6Z?i&wo<h_a6u^e|6b`5-bEdJ+;wZX9h80>Fez~!%
zhaw_3ya5bXTjcl1k~-nlsTsnt;VYhj5UjpuQfLB6eVJ-x8Nl1C@|jJg;#}?TC@o|D
zSy6Q}(*jlAOl;{sGm|hx(T0jEi#8P>^a~q@HlJMhERE_qLT6>sylzDW7}VJ`mSo9t
zq`dgelBNv3%<{9mldtmN67~`Sy?!+f@Zc(qw4pMzu0kx!Av1^yVw**&7u}&|WpKan
z99&B;omtjv=j~JyY6NxE^m|nfoH38A*Dk%Gvh=zl3t6|TNHo<b3oe5PzT8@5;uKb?
zmRB8R$U%w7alDm9cZcv94GIIrE&d+UEkGkquh6QR+A@q*oO{B%(LS9BtktgBx#5M0
zFk2!BOeR46Ce3x|$6RzK$;59EmbXZSs|o0K0z0)R@$Li`Y*B_BGS@1dhzq~FHF3%g
zd>)7|cHmvURHTpTD5K~g-tAPs9rCCsNB=;5#!Kz+j`PZda)hGIHNIKuTFJ*@iOr>&
zvs^NNf|$v<%5fI>O|*^ZrmDJ!-fu#nu<-ZB!-X2Gb5T~-pUzUFn2)W5%kh5`bOdSD
zH33_u@{a^x!rW}abAoV8=(?T75(#tV+?*;5W;wmYBJ;;iMeG7%c&-Px2zK}Tl_l16
zh_X;v!VShpBrCy$S6K*>--3p`)_L+LPbHL8#)v?(S)pgbyp881*s|A(!QXr$J?H=m
zz7%1J@3%q==ei-nfQ~PE*4kjvgDhs@T-|_#!8CcIzyv9DkOaA8=>d(ydIdIh>JIS$
zD5n`>A1g&gwhLN*Xg>+PPW=3$1VzLOGM|0^krHr)n7_^QpMdIFBH&2aWx|~&PA8=3
zS;eUprXqQnAl#NUQo<s;KxMBpFtm!ooLNVLu*O;Lo-t_`s9<;55Y#vRoJih8dKFj-
zlfFECOQ)1BVxCgobqKFifSn0f$qN(a=n6tIQPGJ0C<w;O-5FlYyzEOHLEV(j@OOOW
zH(no0NFaPb)ed*v^5dXQfM^s^#401$Rbgm@z`LLZKmbNExd|YU_nlMGU&hhR@KOiD
zkrHPJF+dZZ5s`lqPKWV${E9H3M+u@Z4;BxE)K`STl6(*oO%g!FZ?zK3<X9D&+^;AY
z$UsN*v%ZQ9ujdDkapVFy*qNP}C<mFh!E|{>6=zmBQ?@eyxiafMf7J9Ne*QCWhB>8-
zwa%Q_li3rpOjkx0E4-1(n!G(-nU}Paz)1E@n)u4BU3vCa#%O0g-^x5pCeAV2eM;VA
z>eQUVsO-AXUvUdO=R_W&7=pFys<kUMj;XxVS*s}2M>CO|5ixa>0{`uA#5Ku$PR(J&
zHwT*1HwrNmm>Q7z8w^gL@(VgM4j4<%C+|3qjAc<AyzH*Vu)qw>&gf`{MiQmzV34)K
ze-(Gi*GEnd%0<)419MqbqG2sfZ?kpAiD#fAL9OJ$Q`Fow`i(ac3_?={cE*1(r0f(B
zV@5eeG)aa7;Dc?n+7vjXc`4v0gLg83hIhJM_^VXzr(g^Ih@l4=C6SQ^84z&r4xZs#
zyvf##c$=&1;=H^?t6%O%ku|w0JZ-vl%X=!_fRPdwOWxSvf=T{sg80vO9(&v;qzB*K
z{`hxzNohLnD4pZZZMj<ue8F5QUD;*w;DkPM&W^e8=bh7!hF*Fw+HOZRA9ZN(dhJ&~
zmJomj$(6waU-s~9wSFA6y*~f2^JDXT{;{v++{%q(E8Sy*jqmg!?z4B&f3r&z(w&UU
z7<X)uBrgk{+k2hd-JuYsYZn~H0rCg=hHOeImxF3Uhj4{8-Iv8*C5d=(ry6~{032!p
z{b10n`!OBBgKjN(vD}w2v=*Kf)UoM#`+!<UJze@RkbB0Z#VPQ*t{Gnueya?PV(D9X
zZoz??0)Im~cFjD?4^vp1<6B`{S=l;b%4#MedCZ(E=J;TF&|j8O_YlSKaX}dQtTLis
zrk}ih-D{a=bU3{J!pAi5uL=^>RBK(48UUtVDz&r-r>+?(3tgRN?1*(AW^QH$xQ)F*
z*2l|MHAxnOtqS;ICDM$VM7_$Y%NHip4O^b1u<Wbyr~DBsbHl<B05=uxg9>j73~_eD
z$B+q(exL*&KEABsP1%)Y8tx7E=)q>MWy*brN4+S8qCy@OW*djUgjvEU8&fhD7wLJE
zt80Z{i?|Nq2P5nO{z&KnY%jy07KKbz20Fo6G}=w7Qvn4BZ$0%J>T$dsn0~Z{_eWO&
zYm=)9x}D{N;RZvsEENVI9Em#7a;sSh;G`o`=u!@DlRQ~?J?KtEbV8}6MB+cg?X;$<
z9F8iq-Axs$I`>S-lLwpwMMlgK6^e>%y#qzG;6Gic^4COV-%mfDSOc$_YGU#6y%09t
zj;!ul<>5mdM@@`xgwa%KAa$p^_kzpna@b$WbXK|jxN#;z(cI`a69gp`mU@9?_E%K?
zaUwm}L?njyBO!mo{bNEo>nHtLg7ZeX@I+??mUvZO6|m4<QqofGa2llrMh8}+A0joQ
z3WE<hAgt#UrgZqY6y@lbA`tyxCMrtQmW7E~CO%8HfWv)F?-MkHOG)qWG70uwwYTS5
zLGoE;xt{)-D<!jzbB@lk$XOr{rHQ9%x^cZd6|F@z-5eSPXXj#Ndw<QfN?E=2_{v(W
zp`HltlGWw*EJBVi_il26MY~h)P{q7`s)h(Bm|j6S%H*S4{WEotzhzTlLrRWP^WrvM
zs6rWhGJ>Yys%+?xeoo4{>JEPlgP_=~mj_GELlR<%$Q{ejh#EP>jMZSxKNM(#6VJlT
zhKH#sXs2_Rp+3WPv>}XhDyFq5tcxeX&Ahea07isV)?k9gv+iG6r-h-1d~0YcWT^;N
zBVnzD2&3iO0T|1vk_!u6WC@g}7;3!r42_ovLPn5(uot}akqnRpDVRo+WgwUUBZ$n7
zz}RZMlxAUSqM3x?if%o9RGByf0f=C-y3gMH$XTM04gZ;mQJd$1LH<T6nZQcJ=rUdI
z5FJ`O$2dh3UZQ}CCDw)cD<4Be=*J8PeaQaiqlwae;LEkbgy+YNPKI>;9|r#x+*fpN
z;Fdy=m-?6;L{*!BV9%d$tS58I<y}S;%!Dd>60cO2q{k_p6J|uh$w8u=L_Co;zOJtc
zeq*H-pEw^Y@qAhUnLuX0-p3IxBo!V(Pl6)U0tIlc6F#L}Rf0Itjo}s5(r{n52+%~x
zTGElr_BEq)(kn2nN=Q*st_0X5T~GK&40)(+V)l3gh*d#=mL0$oa!~<d_Vq1K$_%cM
z7`&-O^JoZ@p}mNA@U2u`&!&g}YFFC!grLyl3=5yYrOcEh&8*SPJSOaTS{_YKq_jNX
zXtK#)HD!Xn!k~#4Pu??R2xn*j6LT{gsM9f&`G?HdQm#yAN|f%?nW9-Uwnv$cGBi7m
zcg>X8Q=%}PSs~>n4-=#56+p%OwZecBWRPXDiz&M#IJn_j!Y?CUVdlDTNjVZs|EXyf
zBclP9**2A>V;<f9Gf*AX3mE3j%!&-JX32n+y5vGXR)*fedAcfRAwIZM*#Ci8)r@Sn
zj-b+vpK%{m2J-MeNoQzhRnd%Kj(uI`*g8Y7RR-AN!vDyiC8(?i*^dBZ#B9x8v^fF`
z*ZIfALvt`{XgH$&!qwD&x|)u1q1<*n<bR@%ie4*w?$|D_tTE#H!?|_Skv_2g(<>%T
z?{>u5RTd*&ooBZr#?Kl%l5z=L`-_ftam9^}=hZoP*O3mps*a=_&mB2poVa;J8tT7{
zxT+&5+jB>|coJj8t8ejkME@Dwi|@%P*`GVw#Zwt0UVWFhBZkqlPiu^hzc8m>JfU&O
zFTT<H*D8Ltsbkm9K6b2=qcz5x9j~{eg~7&7-d5niO{XFk?mJ^Z-JyH?8o{gU9oTw!
z3+m(+o&*Hk#LoiB4b=DKTi%~Km5al9UJqT+zpQChM|rlNJHqG;fA%}C7wF)=9k0O0
zjcy=p?Xg?AILjwNB=`BV=tI@D_vClC=Z@>e86U6A)jfavlE%-vI%dSoQ%8o8_I*0W
zSNH$zG1CPAI)bu2zX1pg;9UY<oQd-ElKRi8I+Aicc8v5?-BsYYU2ZS#4|ors5j&P-
z&O=8A<Kiv^C+>1Pa(}@6XRA7rvORXB7ZG<YaR9EjFSkd|e+I;#_jGO39y@M4nc)$L
z?U*SK2O#`@J3Ern?YZN2xhjegua`%+BgW74c97D4c{}>$Dk`?)dO3A_02(}*=txRm
zpF6h8Rab1s_44cX0L0IX9Yr~xJ3=+aP1;-O%z3wVyB!A{y6i~G@!ZjLQ|F^i_jY$9
zxg(h!HfP3ThkCjFdn<uH?*nf)Jnr;Pb>u~2f9_bO+r?o1eA{@t*>U5@PH{!qo;$76
zz2#dG{OjX~GcG#;p!U|~=ksUUi)->iG*~fTklwPs`~3ksRWRbIQ$KXoDmK`Y>Vdmi
zs5oH$`p^NNVqV_{3$7Qsx9n~R=VeDy&c}`bMB?>uu;O}Qe9QLuS!G92j^~cS5_~we
z^2)pDJGT3E5juElf9}vOH`>9B>mBzk`wOnQ(NUCVvDO)oUHJMdzPdb$0A95tN#s3U
zzPIO&<#Hqc7RprK(cdx$*Lv#6%YA$9hyxWD{%`j=O@!NSIKY87^;YD7F8uzwn>)`C
zO%Pm}f(vdpq5FL%y2LB~sB*Vs4pInST%s0kna|r)bOXWG$I*60KsX<!c!)ceE3M~^
z0E+XmL!hOP3*4BLLM(2V@4s-Pjg5z=<EvjKEBbn&+%FtIldKTsSym`bsZp%)7FBT}
zHy!huoE<mq>|@7zi86T$zcS-aZdqRtTf&Z{Y|kCnIf~`Y2+|B|xn<4X6~6M$Xqf)k
zO(8Hv{rZLSz?g{2kXlQMklJoWJQ#s9`m_wkxfv&Ndhqker+N4};7%i?XP(s4XO>JT
z_>_w&_SEUh?J|W9-7g#%QSXQ~`ejRzi-Q0p%xjKFx@SS=&%HB{iP?TP-Eh(o+~iZd
zQ0^IlpLKQQNiWYG*GuqJ%=8*gb;}q=?yw^$f_eMvj`f^^vtpuiu+}YO;z!Wi*nT`x
zyxuQ6rk6orx6Fv2H1B|x!@}K+u+5=lnAl8tU;=Xw(NUE1xnsLTs=alYm9cBL%s8fO
z$M+QUc0PAxj$seh*K=w=F{VeBWOQQtc<NLYV>h}SQ^eg(hsdgAhluNX?66+q_TEC+
z%t*dlCdALAOp3BUc0{5s!UErd-c+369V_rFx+_I^RDu*%2*+BrOT67JQ@W4DPSJjL
z;+2ijj6S&xZM<WHj}SjE@wPwxyiMVeIi>a}Sg`oQPH6AXo$4j<^6hu3mr%^Rj*Qrp
zvM<W^+_6k?oo{8bFwXOqA@L)8Qq|rbI!)1__$ZWqp*%1pekQ$1lxMwZJuVTcnCK-&
z^`0phksV2S7NqN@6&>LUnc`%R2WN<wv$CTo+jGYzLCUGF7s_o%%3G~*&9LLgjy4DE
z#!N2}ytl0JUkPo4gzdRonWKT<0+3Ur?=4&6S1Y?^#`sgW^%83QR$^HOAKx-XCk7oY
zPt1Ksk5g7CGbTC_9@w(s4MaB*p4Nx*m-A?Ljhnt_%X!YDk?=fP*Vham`L+Cr%D!g`
zzBkb^Df@HBc8T$R3*#)KzHb>5Kch96lt*hY5{>g47tmwBeB&5+Ueu}o{*7Y}CWF)8
z5wCU$SHI~<-MFe_<|sUML>_3W@r+-|aQJ(s^gxtgM^YXQhX|kF@W~w5T^VYBGg3$b
zc9@YzZbsOqfPGBtl>z+sjCc_Z<E^Ow^SM)pt{>C7)$?P~&7XTb>GxiReaa|^iCl9G
zZWm2p4t4}Zc-A)^%OzvsEvTx@VYunYREMUHpeS|xrsFziM8r%lDH6A=K~4<21))C1
z_KdKYIo$%&oG4F>IWLEmlv*D<25=a%Io^nf&Fqd_rgUinZ>EF@#QkQZO?e`359`XT
zk(&;uq}>~7CXe@+m2qX2S6Ynv%50Q-CiEg}<vpdbJYJyH-Q=`8IL#l~E_cj;J$tBQ
zrjI>#L=*~AXWkx4HB)Xob|E3LBa>hHbH`P#Ceu`}$vU^pp<|03NqM{)0_cHKe`2cF
zWT0E-kooLb<wJeyxE*2zJGLLmMmHlCF`petd2|p}-txQSyYhzr-t%2~m+!9cY~7zt
zB97G^)5_eaTPDO$T=uhN_ws+^`?l*4uNTT~N4{N+9Z7k<3aUssX9ia=;+oTS%kKDD
zS4U9nF^q#r6vz+*V`j<&`{QSllBC$PoZQwq0qxBMjLb;8WsN)2^<`utn>}{x=bYX4
z7PjB>HI$O#c-@s*a!-z%iuy0ONqfI^gdVTflyS$4yiCFCkE88#US6=|lBjpP0ku!}
zlp;KOE<Am26$gSP6X9V4cn+hR2v5GOiV{XlC=8xlQw(pnAb!T%o1{Dj`&1NSV!~qZ
z<(k5HyAAO(-U}w>@otb|OH7CaZzjsqR`}1lI)b8dm^U4{WhYIceq1OI+Yvw8)De_c
zpF5UIJ|~!S$?&}2jx!<)*paEBzr69x^Q_@;bl%Jfr1zWQ<DKlrywm>FtuZLgCdORT
zQ*XB-ezvM3DUTkS+KxHd6^xlF4_gsGE9ywfqZeB#uuaN$Z$GkYZ$~VMEn`Pgp4I)v
zGr~aF+>QOwpw;F#bp)k9hTc|QMk5#aEuhuR4!%7AJSON!N-xhH`<!bG=FF6b?Fgt<
zMrCE%@?%_9W*iq<ZQPFjY_{nD$VyaJbbIdDE~(OQZ9^tc-yVR7gOpmLtn2>VkpayO
z!Et&+`(t=q=5QBvBxQf@Sm#u4FlVMbY{yAfpd%^IUn(y^&1uDW{r71``gyV?vJlqa
z);8y;&l~^CTfw82Zv`mZFK<P;<iNj)&^Kkp-yXI2nLgj72&wsY#LTge@#dWS+tK_-
z9)S3s67?UFC4{)R<%Vw;%EO@!q~}u|LD_yeV(SbJ5CdM&0&d6iU*)R+!t)V}JYymc
z#GYTE2yPFV|4K4~gyXRrM`MV!Mth8~*29~+1z~@TuV&C@U?yO+iSRI5{Hn7X2>YY?
zfr8Y;V|Xj3IuROf$7B8tI}+OA@zPH~2fList^GiNxP5()S)`7Hj(B#HLmdx135=)q
z(`f#q6`k0AxCzaXIzm=+tj83#e0o(!QjW)th;=3qMvQoc#<(4EL#7)$l5+mGe>2d=
zTjAgdy>UBY{7jx>QjTW@9X1Ll1|fKX_P7_g=Xqfc!Ds7J$Kse8OdtJpTl)n#<gZ5y
zbP=Vm5^dyBZz(hx58i8)tz9U09ciQ<MIA|byw@tVT@X$_9c}%Ad2-W{&?rn&66JhM
zvn-5;Ihit47!4y#m79);eK~e@BpAzMl2ReC^odZAf&vJFY`N(MV3*@yHzK_}1)UV4
znxDQ6r>S*&yb$qqoZbPg^IonLf*sS_gP=J<%-nQi5;wg)LZ*52_5hiba5ZoD;9LQ0
zZaR_?vNT0`wlu9=;BekD#uFgtrXz85iaL_=c$llPBvYyo<wE)G^L0vz5akyw;+W8U
zpfpbCKKDwhN*TQc33NVpT7?tjir9o2bf<*{W(qo36f1lFTqX9<TLvPri0(C6|IwD3
z>>7pL9@Ux&)d*%mn_!Oat%4S(KuQ$xMxVNwrj$0_OnI>B$bi&;uK=j`R%A;=ruT%f
z^!%;~%1Q5<D8G1h8W5ktMke~xt##~>88nXu1jiH8XZ)yl;*bkb>elLypP5u;QqJd&
zWHPt8*O~C(Nr_+4!AwGVK2&7zAxB}oP@Y_OEs8%<^I=uj^4yVSf%)a6cPi1g9=%g6
zubJK{uTA^(X0wbhY}DQ^SYG$uw==4bb~<~`Qy4IJOc5%W`!Xktusc7dFPk0eR0{c)
z?R!@Y<2y0Ko@0~<j;|0U5}qTJ1kA5Ug}z-V5B}izSye|;o<k#gnNiZh;eCNkyY+X+
zuZ-PDcuMA?3zraVG29iD?RLEQneHe_sn2(m<h%Uj$JBnfKLA1zIz{_2A7U_k#*TYW
zxNy&r6$G8j=nBEmJzweL*2$El#9OCCt9!h4A`E!mI@xnt)R@?eefOSV?H-LGf#wyN
zUxLwl4i=kOflt&{FO-K7$$YxVNqPRZ@kCacn4A3o^ZV<L!u%`hNXoNOJF$Wt`-O5l
zVltl{NqPR5AfJ`cgKvS!BpBgMM`9LAn-t|)pWMm}ZRj2M3+1*WF%fe+K>6(ozD~%A
zZ+CsoNQyU|0&Y=PN71(Ds4W1PnLe=Fc?D^_>4s7$`n(d`@%ihzdBK74`@I1A@#cpP
z0~bqoJiLdA%)pWF7vq}jw{VP8r!50OqT?f~MgZ;rn9|3yseRWepx0_fOa;2-bG%gS
zx=DIOIc9s79e~M{<UspbZUAG3SeoxBjMQgz&708(!dcXjl;`V1){D1{liGivciwa)
z$Y;h$k@6fT#Y*U=7i2%K=%9BU2_h<GO_b*sl9jt{4sX1IkKS}7Mk$jmlJXoX1V=ET
zOyBMvyMmkEbR-6<!o5jpk61yB;2SBPZ<aO%aOzD5Vyn7#!d82XWS!wx-&qaFo<9`A
zZPllVl=f_O?56-Xaj1`eq1=vG@iX~bNomh2Mif6Xx~V*rTVS#`T@3Fvx_Glay2B2_
zs=}pz>{I);6LeKTe<ZT))8)Zo7r5KEiV`OP?oCJF<eK7Vg`E2wKa1#Q6TS<JG}|-6
zi*R^_@sh~A&sTS-H%zqNw~AUPe(z03V0GFdu|VM8_S|v5paH)l-Qj`{{MQ``BaExH
z_XI5bnE1(pbOgYCyPNEaKYTMHKf<Rv61ezTEj-s5&Dc9`7s_o%!XV2+7Uh>j3%;TT
zi|IVB=*c(Th_Sq~8wuNEH|`kj;!t((`E?R}GhSS^pYGzK44__|$Wi*Yyh;Lx*2^o(
zb9mml3vJmGuqN!~zw8j8)5;_D)^l|ANpxjivkw>6Ot~E?VVBvFl;@jv)LsJY_1k?|
z7aZ)H@rahqTwD<z^KsWAL6E77SCs9Wj!mM69Z7k{!9zjEdBpQVx$Q`>?;MeoUq)=I
z%EwI7^+LJr2-Ir{+@$Q!9VcA!lWDeB5b~RjXRZ;sk7us&sUs`&<%sqJ<ovHY3JYB$
zit@{d#|1JyGJ>xl>Ng`6om6%#I;xKyDX9S!QMRdl+lew6D5h#Zfl`!m!Fqqo<Cf^}
zHysHQFC-jMo{?}$Xj6hWF6Y#~?Gym?MV+Gk45d8nQs&@aaqDk7?%KD^!{@#|cFgao
zAP*+OZMRe3*S(V`_`E(NCCmu>ft7H@-2dy2g63ClyeQAP@#WN4t`Z620_lG<Uc&Gb
zY(XErr*5-$WOe^dGxB-@(u$(Gz@tV)?<7kOIAX_-A_O-byNXe=BdZrY`W;yE0I-<0
zzOuf-O@}>n%ZUm7xkFc#g!fbv;Q>2?6$VZ)0M%FTJ8YNA3xODOt;KNDk**M7KB|br
zvx=cf>4mg*q1<)k@-3l(ij<mP5Pqi05wF1bnJKp;R#{o>m}M^>JC^x4**=x2xarVT
zg5n)@Eq*z)R%K}ucjx#~{^F)%m+j4tUAFgQN0T{5;Hhlic7pL|0PC?d1|K@H^eg?y
ztR<U;JZ?I&-Ut22qCBT|7?3kj7UV5MQFTIYy0MxFm0l7;I6h2s@AG~)n+bQ_;)~*b
z%|@>5{r97Frh6w|R77rOg_E1{Xq#4btm#mC>bPF&r375vwSvk`M;2O13_wzT!2ryn
zzJ&7Ie^h9>>BvGZi2+E;uNZ)IcCzDfq1<+)PgG#jEsHNbcC<@5nbGmQP;NUy#8-WJ
zRGH@a>%%w=lj*`Z4SNQ`WmHBL;I1m)JR3`G`^s`SZ{TzOatVYQIyHsG3HSeFr+qH8
z<73%{a@Ua+dUU0eHG7@`(Rn^l$LB3j)vWAuGa?HB2}qk1RkpunOmx&Iy7vp^c0?8!
zQuz^5>{%)3Fv6+;(ff9x+;(IEBfY?+*fRusFLRwE@3>zmw;fp^$<&dQ^SPs4$|$|3
zdf(3|<Ep<TlyOm>p$)r#Ud*$^EmC7g<M!u!{DR!@#y!Yj@0TJ_@2E{aQEofJ+f|qt
zll7#Y%OCVj5ezWixB8>()J?}zF%9UbdR5Qv0;J#&Z!boiDGwtubcG_2^{}47wRj4P
zgzjcPs%HIlM-|uF)De{WEarhGZ30H!+Dy0|kKsC<-HJjS9=i2&D)9AoMD@Ag*UeZ6
z)S*SaDRAeh(>j+9dpk`0rIy%DH&h&}>ITANnwT+$fxw=OV0a2qGe#>Q7%tn7!0&Y`
zc=mQ&|G5C#O(#@Iqw&r5qwS3vHY}y~R?&zou6EOrVUwpivMSpz1r=;6)%I3d43=)Y
z9nF8V5<H*v-kyL6$?8>K)qTBCZacDioW82s>gTWO)-E;X-cx<JUy4PrI9-;f0Hr(|
zzIeCRh=;aF)M81yn=UAO2TVscAHuE&yXVq)Z?8#mEtYrFku~+II7!MQXuue8F1;5c
zUW@VFju<}^)}<)VSeF~ZlvT{gruJPYk3kt19PET(=*LdlY+h`jZl8(>-j2l_0d(Wp
zdb~#2jxQA?d`G#ztWS6|5{m}!JXFDnCrNx<>Kwka`q24H<vkWi%*uOkRj<#L_cr7>
zo+|gT_Y38AL?kty0v-g#feWAHf8=mZGwn0sVLbnps<e>s3uD$x4aj#CmYXQI9a%h5
zcB?4QiZ-$}Sz|IryjGpO9kE3&(o~iyI`-enGDRwu{C)d&p*)NjSzRe;nbq~|@8e5!
z<SV=VD4KaYV*G5I1O&5q9y>B!@R01>e-!1s>B!ohDRi55_OWA`OMJ$Fmztlq<HfHm
zMTLPgzX*%2`k@$ZraX)nKg%MIq&%h?8PT&2fy}B{=QGNz>Y55>R+ML)*}bUzX^fV|
zP;W<ys*~Ke=<s`$!K{_aDuch(N@e2nJ_}y#V|HA>&b1$(8Goe8w(dv!{G+#0_U-l0
z|MdEc$FksR&WA-=iEQwpcng(~(PBwk-;rf1yqYyuiSp@`wNCX%lfnu;C`PzU^;ENT
zDlh3i6i?7ap=7l9>nu6CMs4pTb+m$m#QK{loGHLmch&L^%HpxB9G8!!`8QLpL#Yt-
zM44vCJnnojDfwWQL+wA>&bP%$jugOQyn#G^6<pkjZ!uGHh1kNP&46^?*J*08VQW75
zS~isw1n`1@KFI}Aa@U9;z&!?K^AiV71@<1t@m37M8mTHnofNbJ2jGZZypnc4;{av?
zd6X2Miw<OqIKj)6M6PurL~tp>emFF_C}X+j*nOF5vkroPP`7;=+NHB#E@le3*imbG
z+o!Pu<6)Zy_YC@N%fU(5v;s%e*uMI5ZF2)rKW@v{PPI-it*&>h;r-dDB1lYbSqD2Q
zS<o6F9bB{sbM<PU3(H&kk=>fso0MHYaj=&*aXW+#5K?Rc;mB5H?>JaZvQNcqAt@Ir
z!<${#@06d*w`uu4lxg5WSYAY4oEK|4Z8`eS`KXk8GQUcEbM!jR2S_JBrc<Zs#NfkS
zaj6`>)oD7x+<Ix1i4TE$Q*t-FWc!uUjtPusrsx-Vtm&~U9?Jsody6I>ffV~~6;qNz
zo|r25@<lK*ZWUJuZnI8oiLuu_wZiAS4y3u|NNYZJoDXCzO#}6Fo*yV14}aiHcFI8l
zOr;!zp4?BKU%<fjb7IZrJ0N7I>~-jLu-h>)f^}+htnRN-&kwvK8uyfqFcdml0Y<h@
zi*|9<cR%@{tYxa)J18|ErD8#>*_%H|ihi;BymswL*knCLC(FF<Vhf5j^i3xw9Eg#n
zhV=#7)h0Hf_)p)&CLp!-O>BZe8km&}AJgYz!F+I^1|q^(4iyiE_*|wZ_j#<f2oNzS
zHJ;2ZK>^23UVYZTc*5nOXZZQ<5}<*t#&?9(gD;ddI$#f@v|LY#S_FHBQ;CWNy=hwR
zl;|ly{a$x*(#}4?0Mo`7te^T9z+!spU&NHN{C*UnoQ)O?#$GuJkoJ4kC_u{URL0hj
z(!FXFR=ln{UcgJ~RmY13iHo+}ol8-?clq&??Y#aZr$RKpriTOzAR3n-twkx;@uS)W
zuor|t3|ptkux4{`#%<|12Ww6z@BreZv%;>x46_8XWZ?$UHAu1Z8;Yq3SI}!|k2d}-
zs69O)APrAS2%-=-qJ$30SYLxw+)!z>ozpak^r%^c2GGuF8rL$+_>og~^qLSD-6wVi
zCL<;WCs{i*ZbVBA3dTJEt9fWx0w^AA`Rmwr&B7ggjjE%HGVjwouGO3eh4_?|INJeC
zR#{$g=};94nbn1*I&O)zc|iRoAaj!l+zxN?P{6EJ1fo-VJOm<X3t^wdptH*JOz9Yh
zj3Nr7WM+V?EiabD2FV%T$*zDUZe830qF(D?{6VY{y0nuLXqBF7qJsn_7R0~Dg1h)g
z(@_wpxVNf`-d5dl#X391=h4K<V5)#CgQSYwSTLbNn>Yt(<R*o63!J^kX;?rBCP>_R
zJ!;c@VJuC5hi$|N*tnTkUWqJgTVl=f7cAz@a|yU>hM8t*@)XY-447tYtpV(N=ozem
zO<pF2oa^|gDW}Yc2d*?A-jO<d3^)fxTG4P$aZRGJ87q`}yFnptRAz~>ty<B85^F4>
zEd?nyt%x&GG+V~`^oyLFK$X`J^kJh^<%=0{!P+{_FHZNW`FVqLbG>wVvFtQ&s;i<S
zad+wjObxnXlQEAv+-opB2tZY4s|NrzXJr6qKeb~PrKmAx#kB0ysIlFH!cn2YSxRtd
zaCV3xQRMfK{tV;Bk(N3i9AMHi`r~%iLF_u8OU&*uwu?c46<f>~Dv@FoEsPr{VE)j6
zY!~kfM7`~rOB4i$8VkhB(KbD##t+B?!jSLDdz3`5-CIEA5}dk+6!gFm$B6(0zPtfp
z4lPdN#GuYtN_Ex`myciqDCg|f`218$A&y%Q+t^wII-Go4qZRAz&?h{Ebe#AO<w4PF
zEbmTfts>)$He`g(hY~Hqe>t-{KH(<8-0{U$hP%NgswVdV;AU$ie)B<5w;arXkyMQe
zub|DP@OFG|jW-%7Wu8CSH934)5LrTS_n^e&B&fqITAUOc>}F9lc`b=~ZgNBbt+yKU
z4Ge}73dS!at${3$CGAl$T~EE%P-o=Lhk{m!Qj;i$8I?5}oZ@51OVPb#lSvsTe)@+J
zN|!1D$ZesT^~B?1uvJyiT$WKU`X&Ynj7l*W(1NQ19#Li7ir5B+oJkuGvukk@XM?Yk
z!sncV2WvLb!V>WrviMl2{<?&EXB`I$^^Q-BNw5Q2c~D%3`1Yu}10)_No2rg52+~V!
zVCt;ResUa~hFay7?I^V*NzPjLm8v$twW~rMjo9+_l+^01%gi5iFL%L-u&~UbgTi0z
zJ%6x7Ws=4|HGaaA11Vl3XnnL<JBC{Yp&lWU3rI2fLz9Ofukvwpm)dpLI|-|lby=1y
z0MEMdgHWT>rpLzYq}F%Vw!!BhY_%mylw-oMOch~iu+;{ovR5!xdVgOrU0z7QT8nBm
z7KWNvQsE#|A$kTL*QyT+3^UeV35uU9fz3o*ZWS_5mTA`)rm?ilCYjnG%T>V00MuU<
z-^s|@DkL2X{PBu!$P)3#XZ$31kAUPX#bf{s928C`YZOJFoy^yl2N{*M%GHAW!$GO+
z)$tTCA6DDqB=7=ujY3G7c}I}VZ>GdnAru+W6l>FMN!z_ij>9ae^3t$wyzC2L)j0)i
z-$!|ET2{&82C%XZKWhz!M3wmg^K3wbq8VJ$C#!YVR?-RTs{h3k1iPTZRT(71gSa3_
z)~fFqVcn~~V=%$IdKSL<gj=q1vcm`)6s)SL<`(zO_47)f`@*!!Q6Vb+T%#!4sc~Z_
z`q+7Cdwu8{3zS!SH5y6^$urehzl)wJx2wGJ7&r~Ry6WTTcGcn(a>O(bJj4IZ4X&C6
zH@I>Z@c6f?S#X0Zra{*57cz?Qi=xF=em3}RZIuQ3Ha(=^AzVwe;^)w>Yf0e{3U<|Z
z7Rk9z!LS9>sC<awAzVpW=D))eSals5Mw1gTC&aU;tbD)?eA){d@xJK#6p;4<vGe?x
zhM!=T>njT}TG&WSkYW~qmahbvF;vH4!Fgt5jW$j_@!{*LQ*RWea?QbR8kArF%%(vA
zgNRjLW7bQMHarJRfhiTWD-C8;Eeazb7<iFhVdG0(WDOdtO6uYRsauuN!Gz}VdU}{z
zNX;dS)H7|zDJ!2`@EktIrFuEVDd?yXnZ1B?V7}xO3p>jiwM`QQ?=}=QJY^!nR;nnw
z9u#r{$H!P;n3IX=$$kyPXo=E=U|y)HMP5o{p<O9Q78PZw9Kl$s5jwws<a@7*tOIMv
zE7oHWR`8S!9CfvvfI%AU491uf2g?h~Vv`^wi*zMJh?9!X8myazc-7y^-}zA3a;{0i
zvaDd6Jz_s_NFh2eU1Dys(9KlhmyBdN<XzrQ;905Ey}@|NnyVJY)M}AkZ!G#vP0lkm
z<0p{HRy7+wm2=^CKv^x)^#aUmnQ9UnA+d`b1Xi?gZb8A&+yF?yk{$!tAz7Z@jCJ8%
zBP6o7TCp8c361`OBAwAxvlKIhWK=zKPqp$Pq$Ac7!)!XHNGr~w<b)y2!r@j~r&y{a
zlHJgY4>C+TAEXN1c+jE2I@)_IqT!amvRt>W_9~^_OyNk_C72FQSqmSuV$SjE)U3Xa
z*P`xXGd86nzN&0!^<`?rrph&5Dfy%qS7?kyzVb@h*L4F`Df{GtAq;<^_FO6HbTL^s
zjoxE<n+C^muA2rYpSlK53dc6wK-I3nalmVcwz(a9O_e)zZ?B4t+0hp~k($QFTY)az
zF-pH21{z}NvJ6=xAxEb8o5wM%C@BRC;s>?1%S0&pWFFMe3zc<2VALO!cmZWF)Tk^x
zw_}fFK~ze+3uVP`cphNP7x~Aa!d@w{NxUwutctE?Xn#e<Ng(ZB3FXH#E`O$=YbhE+
z|0^<YDn;K+X_!1;ad=cgS%SooDL!C#Pn1=|ceF7!n|-+qvx>Dz`SDC>Lq90)JK}Sp
z+05-26)zQZjVp!2P@5_7gE*q)(4Zn<B{-nv5EqjY_wYrINqo*PlxW3j<7;^(@Tqh<
zlpTw~87>rIZZ+adk}ZFpOvn;--19!GPy{Jhvrv~x3MG#0&O(V}GNK^_Kmw)4U~w{W
zzAl9LI}U3sdvQ|yz%(%T3HKux3Pyo6Ebx()G+ay7$m~_WuAPczpOnJKz!z0`;$=t|
z`0_6l17~o8*OPldrDi=f9k6OWHP}R1>&)}@$lpN9ul)FF_;vd^p>-pFIG-;5BqgGe
zrd|}}Go|BL#O|$4GXx=bi-%%0b>g~m1Gz5yS1YyTGlbS!b3Soc*4$<cU&VP5%FO1)
zGiQ$LAzh0e!_g@Y^_=qa!6oio=f|x7>cK0wozKm)k`#}PonEzd%{eFKy3RG<Paldf
ze-q=qh)J8-9Mwav?dyv_D3=$1@k|_UX$TP3VYyN$Y(r>y{?3oKzGETw2!nW~Py&bi
z97#Epxf6wg-o-Er(Od{Iwt+X2juVAL<ATP2gs+={JG%t6DEvBj3y};LO2h{0qe5`W
zD}^7{jy4C5Z`q(sU)7l1HhmC1r|L)B_=N{2`&CD9@W}O|M~q}3swaB~f!c`(<SdU_
z({c_nu4!-{tH!~3s#@wspqP}z61oIy@T59Ne9bH6swEBzwZz)vyqdH`9EX|;DJEE{
z6((W3XxPYG3dNTjS2dlaP=Dq~oD8?JYBJjjepNQTRWvznT@fF+QAM*$ie`tcDjJ$w
zRWvmBWwwYMp%oTe;nY^yhh+FFqm2w-Wwa%QM%#zsOHgPY@`YPpY1ECJDH?2G_i@r(
zOadGvv>*p5egfVelwLE1#v<5zoU#>R&5r!3$x;S|)?zU8pg5z!Jt(tDz6^qFax5w$
z!eqvKq84}uF?qPV!T&|C-M*j+HwZT8*wYn(mF)6*U~i6Heh+xfyp9{35pnj9T`m~x
z#IdE@0~4p&3UA308DDUqkolWDALJU8ik(cOmAZ>*9oIhc5)Bf^BA2L&?BWtGGz$Mt
z{~NSlC#~V>BXdxVO0KezO_r`S2XDsgIV_R|reSH4^6zxVaZB328g+8V@o+UcAvv_%
zaoiGm<PL3#$p<-jynF*~J6(#SU4y`*Zt_9$s9UtK{t8!kIkaKamJaS1rQV_KsaiGp
zRH>gFVpOGH7%h5*$*3Z)Fd0P)^vpdh@)PHe=qD!Y!uxiTakvJSBiRARYy5;~nZCDE
zoSQw?UI-IjZZZ<_$ntwL0Wy8#fu5co_R;1{$heggfl);y{&4JnTJH1*hjv~A^BQ1K
za7}^pyHo!0f`O$t{SIQ~V{}o``54_(oOllZ?z7tSP68a+502c?)b$7^8&|@-K=FJ;
zU9y~f1}<uLK7^Me;Ml(Fb_5*Tcg=(>+j#@bF1Q)t!P|M)%fH8!W)WL=B**9yidm3(
zZB?0d$eXLm>_C+Ts>t?R@_x*V(&9Pf+s4U=QJW@2R>kLR$=kg_!rk4WC&!%@{_K~7
zTo3|Ds}dJ0vg352$WjrN^_K>rPnVLFiEp~Nte&8@=vtGdbMxY}?uhrS%&BBeS>2~r
zrbN{$gM;}^y0)#%U((fXW!iK#EwbrqntBLRxpjkFnKi^q=E^i7-9uOA`^06nOHrob
zs8ke-@#Y;jvrYXT9BqybTir=`47p+60w;J6EMpA$GF4_(<iae|MSdiwj+=k7p(<>F
zGJ$bBm){_OfFGQlaXB)On1E7c?d*)qks-sJld2fJ$|Ms-I8^4YSJ@dme1Zy;sLUa$
zZZa%EDR|DI!59s~b>L1!ksXy;BDG7GVG@X9Mp!Vrswx(fWHa=HNwOZE0>fhDT~w*X
z8)dK5V&+}c4XutS8SF!3RYZ&qrb~E@iYth^{fxF@5pAc$^pWwfWF!yLX=~-hN@YGn
zr7F4|nhvMSpM>hDA4pSVMnmN_787ti(g|FE?HzX?c#t>2N9G+Uq6+D^8FW>dWS|;V
zphS=rXS-`MIQUF55Oy0=ay=-FW4)$0vdWwR1)Cuqw^rW3){O#M8W3aq5$3i81tW6_
z&{-8MH!^ZZi*uy_mU6?u{d(#wPyka;VVr)IR>DC2Dm?^o`iqDDflv_DM}AWVOYLCH
zeU;j=Q3$8rv1RNc$HKLV;S;|>mYP24$i;QaU`!;@Ms#Dr4<cr=Xonz36^2<As9to)
z5KyCVPA1}d6e!v&p3A9JhHq+*7`tBdp;7R<zM{y(Rs3mX7`nct3PZ2V0H_K)*OyUo
z=J+xqsWu~MD}v0cW{13lYWy%V%v>Khg_-MXrYLiM%@{>)a`+&tHUp2DRIAA38i0lw
zyv)LN3UFSOGMiD*6)=1mDeWn<y=Js^4T!po$5sk$Rk5zBSaN+X5KAr>6tZfo(VNsy
z1##1NG?Dllk3Q#I8DK7Vj{?kjxfnGomno>-({S6txOXMtjy5*2LqeJyDjf-45k0?v
zRPY$^x5GW@;rE_~>s{msQGmJJ9uZ(3G5nm}u4I6YHu48BH^!Iq3!w1wE!oESa(Nbz
zt9zv|+d&UjwgWz~eP_0VCd{bwUGv?PozdA|qfcz~QWc3#SAYW1^%+1Qx;_F5MAt{4
zZ!jxNrgPtvN}|~@m89u8u>u*!eS1wQE1naKfiO3CAXM9nNy61mwtNg3rkz(K%AOgd
zI6xBdNExms`K{3PQ-_Q`Smp9mk6k~-6(&{5QtWVCG#Q4GSB#9J1(e9ElF`@U%0OO{
zrxr)z5~jxdC>m_NF&A(ZSMVKaoJWlmtDHt8OVNz#_^L#pASQ-->fe!?9FG$>kQ&86
z$I5{ER>Tjc$Tx}c&g3YXJIGef)U=AAdS$O6ec35=!UBudNu17<6;~OD-(<KT>A9*(
zR3tq|4j+$2RSuu&IoB+{`8V7R8VAiZnW|L3oDg&Uaze~q%n3#Qgwh$AQ(aYBpfZrZ
zwP{ANb1BMe<W}+>g8QaPO2eQ~ie~<#>#c!_(Nd%D5p~c~cEjb<q|kTR98C&+<Oj5r
z)MZLr)nnoabRAxJ!&RA!>D;wRhmU;j<@%#3iI(ZznR@H#-M&isq?tnyDZC3vzDnuz
zz;<RHFerX1<SUM}0%a4c*mY(cv%Yw3`!pR=ayraYrtyl51XcI()bTT(Od$llp{00U
zmAlRDT$dMXmw%e=RQ5LBI;J)>$>w${eH$meo%kF!Y2eIdxctb_ElyiQe!9Gr4bf-N
zcw45Y7d;}TPnFy`DOuf^dJf&Y9ZWfv@NP^!KRF4eo=bEyc|xi9T*IPt{Tk^MO6VtZ
zV!NXqhy?32a3B(_2yI99JI~&?cA>_ZW%fmvXvU`1UNnn^@6C_DcReGp3M8EIM4VR~
z47~RXNJM_X%fpNg!8jo69%2auB0YHcF-Yx@#QWCSrJxK-e<kV!&wK3@*9)`vDYxTC
zM7PKZ65k>x7@VYkXyN<D3i0^S8V}+gL2c@mGkhiZMvW?VjtYWiuu7gCr2q39`z>iv
zyA<rU3FCv31vmlx;DZuMf*uo`kzj6{Ku&1(Fb$<ktBwjpuES^rKslMF6MX5CEXY-H
zjSAhMZ1s&TA6g=p=`5XYlLl*Aa4!_}2?<kC<)L;7RKO7=unayI@t{Kw8cWiR8k1rK
zVw1nH_2)0>6hoCESJL$uLhfvO3?X-t4S?J^dCH*+cF9u!BK-ffy-lwzJB}qbk6&?y
zRf9^0M14?G1MUXwfzjRRk>N=<x(paM2VF+P_P_TQxz<wb^WHo6=6O|_K;{+C4vA7I
zM2cJ_H$_X4+w7dE{eyQI{XNqK4fT=x&>y^z;*U=9Z%{6~;szt5LQGHRWK&)xzK^CX
zO8f;<D3Pzmd`PlWps?S`&P3IMmrqdg#)`SX-xilzGM5S4&gpq5<R!DU-4A9mIU5w)
z$o^1spu<WgW0TvUoqSo`8J}}%Asxgc?-tdrFe0$$50;oeE$)0~wW>^o7rI@{MtUm4
znue?mjp?(_S$HVgT*gFbMNcv98D8rl@U=qM9<X|+HhSznNy^+~(m@}TC62ocO4-i0
z*qFQv*(zw3N<zMX_Lw&*XWsb&8f|wB#Tqgzi^2)y>*#06KTak*wGs_Tz5Zm=ds4X6
zX~iGXGY^606<i-!B>u-6rKp=+YMF)^^EF@s;JxJJ6l69Ir5$_{xZT2mFy>?APFw2r
zWLH;t@irfmPTuBY(xf<i(PG!%m_J7uS<_K=2xsKT%;%4RyG+^H&W+=b#m<l0&kE$X
z?My&$Nb9i(vD?;T^+7Q8o0|=`*z1inG^N~s>kN*>oowwjn7WlW#+OW)U0eP@6HX@w
zb^tC=v%I&|T|wm1ln#dr);vlZte5jBZHIEkNteT{dRy#B_hmf>qvxZ|cY(WHW|_a<
zNJp8<+nutvJ_zsKzO^qo?%q4)0YgeV>kyr`&!e<A)?%RkTuxBz(@3%!iZayeCGYHG
zobg!yO!unG;Da)>*m)zE`i@~yp7Zh6;%k}n@z!EnPdQdZS+e>dw+&$d4~lD>-SL&V
zwhY?!`S;khPPMtvSnXWkL!nu=3=TvEvM`b4CdE7p{6+y}iUoX9@^u%+<T&r0q+E%&
z0wIR-XE#CNZLd@&H|N**q(GA^6(Vr)rgbO<t^ImedGrB718+dqZc?siq2+DiD}55!
zMknC@5U^Vdl=naiCSwl@UIDFutEyYJN8$p?g0W)71FHyncv{IKa>o<9_)Y=TdXwUS
zTihy73f>j*g^PN}lafHdf?Vu@(#)NVxEnw)-wD{2z=XaYI;~4c&mY2rzV}KBwmJ}^
zM3sti348j35Yf8YTZ1PhT$a(rZz#B&*Blg|X|$vaF-~pC)AFETD(UjPf`rc)UeEyF
zVpv@9m+pNJ3Z{~Aa=W8gRTOe0g7=+*)7EeySh_5V(sf1Hk*!M?MdQoTP4PkLXeal=
zvzlI@6e;8DlEKdSx}-?KKL30Qg8%s#u$+&_vPFKgMP6YRTFR0^D}Nxj@A`?78`NNJ
zTGG524Zh}SUBZjwNGBTnt$hyoI11mMAcfZ-2$MA*5-Jau`4B;InmlC*2#9u&SX=Wc
zQseMA3Y=w2dVj8xKQ;DzgZ{Wb<f0snj%76baaAGZsO<Y-U`RnyLa?p%xV(hkx7NA5
z#I0|w$Ka&ss+jNWTvC&}=PfmPS?Br|U;Fcl8lsi46(T7h1C(ABwE@a<MRp`5cGo7I
z+hfnR?w5Pj7%{Rb`9&aN1cZf3J=AuyWYt|BCXM9p=#3rxm4{Iy`76idh9b>(c^Eai
z!eG$uMWHfD*>l;Hd~??!9o3Rmuj<3BmD7@kodr#A+WRh8pBT)OzsY&khg~b@RiAdP
zn3p|9$GRVtG^%3W_AqPZyr_Z>OyQXJP<8P(xr!RAYtiqXsbEg2rOK+Hw+{No0!>g`
zw_Pz>T!p-~ML-qWxpF$LVTX($EE!MZoC%V;iGoV}cXTNa3=FB8Qu&jdoRW3IL>uv7
z8aL;{z=C#)Z=F$da;Yi%m9@ZRe9oE4X~GJo_jnkf^KFhdEBJ2H<pe`{l%-NP9UUJ#
zc+T%!fl(>+p2Ek$Zof%~pP2G|u;antIaeKX&Vw~R8WeuJ>EnhIg7J5tto5j72LD4u
z?ZH(JC&VU^9n{#q&)Is4fOYkg-S8y=9K1=cZgT49XhrF`dp+3UZw|{Fw)g&<Tnyox
zSS<Hm50-OzbRzdVYor|)SZ)HHzi^Ul%JG2}uy=f5DA5-wEs_#jryTEhy1d>gs_Tbl
z&qu@?7OT)3j+)rzesDLllgVE=#yz~nl#3=9pFlbO@Di;`|7gs%$mat0V-`C60pCo9
zladG4Po#kn4x3FlUd<@X$bZL}Ra+g2t~W_+<V5R(joA_Tn$38%r9QX_akEKaqegt~
zaWTi6Ey6OvpBz!S$HTl9<8&{O@<mENNBVD5a4DTaR-QiZtn0{7M0nFJ0-GyK>z??*
zj<T2nGO0~3CZZy&JU!(3W)IrQqIJLnIb*5gi7&9C<YD1Iy7M;&xsWgKV3|+_{)Dcv
zZt_Ws@cdENWBd`<$*>5=|IMP2UAjU?&CY>FzUJfmHtb(IVtP~I)F1RzT?iEiA(r~U
zl(Mw0LZ%+S5CK0BY6<GpiH8CX#ZHt{AXQ8WSm6E20C#A#EdG3Alk!q+$`C_`7>mz>
zf|2Ml?D@!nyX1--uQ-amp9mrN(Cownb=)cK#QOjUWGB1_ZZ$j6JaDVo3Fjfk$W8<g
zJZ)AU$fbPE{$MfZ$&qIkg~b)({P}@W%4LwzsE<sQa1*ALb3T}*k>`t@=$G`~F$Y5u
zVuB~Y1^zrc@hpIZU3P+1;H!I5X6A#)f9GPKz!L!2EaOfHgxjo~I1}LDm~`R?y?IJZ
z@k7o$Ca(YxF4kH>A#m^62?|klY@Xl_Zq6?}&-4=`(pk=3ns#KmwW>4TH7?nOzEUee
zh&ig1Y`FI9M1Zh<ah2NLQ=Fsl@%4#x5S%#ydEV0vXea2SLt8=Gk}FBMc!nP&|I)(8
zjr1u$<o`2;Qt+>QeFO46k{z-}4AZ>)kk`(XhLHtnOt~E4$Gaj6%@2WXO&KDA$F-_+
zcR+L^J7swJ@CemUm2zfEAUgI;sWR!@GlUIfQQ}9`01~$_pU)3@`c8p$div}UBvA4G
z2NBZDE0m0}hPt$1K&nmYLgDr^WfUbcn-5(-1mDi`<`os5AK?Lz7)q8}N6V~9`R^3)
zb)Gkgi}52CpkV~IVgwzE@Z;G7(hm#1A;l~K@Jt+)lpOc~_;K1Qw=JA}Oh|Qsw8ws8
z_;c0YF#OT+1H+%}@#wth_G5yqAM*N{F#IgfelYxbR8}3Q8I*7Zi3|^Lrw9ab$Gw*q
zPSaruCty(c0%qn3L!UT2O<FKwEKETF`L68|1OV8BDGxFog~n9L;U{c4@QLpLZzsGX
zR?doIJ;#0``Eu}e;s~;M_alq|H@`>FfI~JaQ*=ck5K}g3Iu1?wrWtNyCnO*r(5Hm+
z?-4|RGx8C8@c0c@c9CDYM-dBTCfI6}WU)u+0ZvKNA<nYiN~wJ@F3FU4yRtO%2~R*x
z8D_xyArEBa$b&g0t1R1z+`Bb8;??rDV=}nIFUj<LKNz63mpqPn)B&;+(|}q*rU(Xv
zhA}bV4|yts0wILjq?^Qty7CR;?-+;7=Y>Tv4--y9<~97G=r-m({P96&r&(hw*7|d(
zo!MI$U9$fSqf7Qr7#)sglNkq*e`b#`IuzozcESmh7fsT{kD>|14^S%zQ#57Puc#kp
zCc%g5WoEi`z>#VSpt$HsHD&Z?B&D603It%D#~7q()@8UrB<K5M`7-5H%@TM)=p4(@
z5BKX<kQkT&2d$mJj4YkVq?|wGpGDrzABb+XN0<iUUzz?hDY*=~?jVlVPN)XzWg@BQ
z1yVsrCl1)q(FyuBbi~-<j&26fb*KVrstCaVW2QX?1>KzZ=-ehlmix&QTW*61<@N-5
zAR^kLTt!8FSUWKv6B0T|;D+b3?pTP;wi5+1c}y!u#DsgvPGHD{6_0@-kB3gAc)U%y
zCngMi#(H%bTy84#5#i@8f8iQt=1(|hp6mJNwKIh3LN<9|%bhWCVC#Z5VQ@3TRVI&T
z90e-}eD;|uc9Kin&khmke>(KUu$gM0M8W`c!L$T7CJJT8Z;pEM5@4Dqb4kIbJ=qyx
zR<e_vfd?~Nxj&xC8PXbNZ;2OH{^%rL$QeIUFD&%KoE3S-UUouYJXK&jsTX+8LO*hz
z#3voY;}=W}QN=RzF+fSSlaC?oIw!Kms~84e%q?0>*Z?Kjq-AA74Lh+n4vS5@(c16f
zvJ;9EDLFWTl6Jfg0<O*&`3fIdA#nO)6c|k&gWxP~0!AVciJb@_2O`*1Lnv~Wti_Dk
zKa}vqRCs7p7W&Cwz?jkQv-ElTo;V?g<w7NoB3lbMp6tfKFb^)rX{$O)J2ebut)+n*
zNY$4j!Ax{i*a|)Q?FVtz>IXSvUF(s?#+r0XhZm-mlb;3WtSUooN=%wJf5#!KYEqlh
zKegkFWKQ%XP5cJ)gV*Ho6dWUuhfomdorFbDM^J~GbYF+ffRR=199!=ZCW0pTs%H;;
zi8v%rES4{gi`R;ncRS%(zBDdh>*C0Kt4jkjG29)w=pRX;EQ*0KX_TGFu7&Hr>W6Jg
zzHz~57fe5<vSUnRWeNyeFy5blu!W=aLCIZn1u1z4RK-r%*n&mA!CDR|(6gNjQcs$;
zR9Bk-ysKzvruVAvEiQ^udjUykD%uu50&85>D%K7qnKQJKH5E<=;D#j)l8~$&3QXNi
z#(m^cGr01RrY&EbysSvdW~@s`6po!xIiPSf7En0sN5e1l!{Hmg)-zUGl|{Iie(o`P
zn2=8h9w0F96b{Y(K-<HK(*x+`(Jv3f(@*C}=%t^Lm>jQj)lauv^^-J^t9~*Ba%lSO
z0b(&!2V@dKYjUUn!SYVwH2I7s$)8M(eJC88TX<^dL&-T&F+m1KkU-(s+}BeRC&e{5
za)%%zq_IpQ0Vmd;nI^fn9=Rvup@tSFnN7HDPmpBdO5O=M#>rI)8z({kNx~r7n{bqh
zV)y;%Hb5h9BX3Hmg{QRSeLn{R<$WAtM4l8p!L+D_6Ut8_z#o`U<|zgm#1sT-H;=AH
zw+hi8EX@+RQ{P)S3RK|cuBVej$>Ui`m4VoJFk@O5GK1^y8>Mq>=8$DCWT%~OFnBxN
zh|=&Bc4`1D@Yu;|J9985mF-%sLt#IuT@nmIN&+B0^*i)#4}~k79bbeTJja^)5tGP%
zYUwpFgDm2C9-WkOxDf@LggJ`qXNF4(?Tht$e#mkBP9ej2U@#l=I|aHkQ*XDA$G^ot
z(=a#9_)z@uCa=gN{d}>{ALJsG{@yx!HJ7c>zxGDrxJc(c-WuuxpH&&>gI`LV&25Qq
zvrK)AB5+sY6E8e08&jXsEBQDpGF#v~0n3aQ`amnJA?HvuWb1oUmSibYdM_QWhk{j7
zdhR8`ErL@T<hs;b9Un@46A)H!4TarSZ=K`VTJ_dYhr+R-U>TCZ9f9@y5w=e)?=7h?
z*gcuY{`y3sIK>u%%kD_~NRbcz4ke9|s>oaGTjNc6`XLY9CyKNe77gg1eldR2i!>)J
zW_{P3E_vjRdS#h9?I>leYVb~pU*O-k<*-Su8XKy%kE5f~X~&{iNuh@CEQrvgLE|_>
zwlP%BO2UAyD+2X<<R-ET6&sW9M}-!pKDBVxxv*2?I8%sSpPr&Re<<^FKmMto@$u0A
ztq$?h(dHU(I}R-Y_ukOBw(#<X7J=JwXcf5m=36II1M`W=UH&9#Y<8mM$DW-UnY#^v
zVCNRLU3zaV4b7eATz~E>9$q!4$6GFc%^NOv7InNQg|~g~H|Mvf!f6#hz|@v*`q)T|
z7kwU6JpT&am@J2L?#hN*o#!sivO4E#Pfr~vSrzEk=((_VYcQ-^c;b$=f^N5C(YRPG
zC`}&pu^p2Ld~6@bu0lWBvAvk-v{TtN<7vlMM<=IST9Zz<G$-*}hPz9KAGx<=8=~Xt
zn2)lQ(=jkzbW_0!_30t(ZL4As8~O26zJln8cBsn1$scyInO2Lhz_eO?3Anl)lN^g*
zrOA%Ys$)2WZ|a!+w%due%BX?`O;rX>I*@1=O<&QmiqbQ5EUEAVrPY>e&}3Z1HiZ91
zR$KaNj$xO+ny}h(4IV!Nd!0sEwEDxqOlOUm!Z6{SVZFN~&|=QLLFWoR_nQK{JUl06
zbgrnnxY50WqO)+sJlo`jOE>;9X?n-f4e`R2o5xm9U&%4&Zweg-&|cv42ojcP{^jW+
zFr#1mluVm+TjZ{|=mt3?mhLm9$>Q_JA;K}uR6`9Yqf-jqjw6N}j9wM4qsuYGKERyu
z6}njADm^_y+;>=<AK1IciG<yKX+eMJi%93x{(RzH<kTDe)~66|DvfY}T|aaJ9KTuG
zu8(Jp2aDWqJbT`Ml7QAzjsV0!JHNf9FRtgm#Rqm!qXXsC%`M`C$9to1Th-cI5i9tx
zAd2jiZ-?}<EZ@$M;r+E>(?DX{so@SWEB_~D_i>R@3Am0MmHG)CtyF1_AC?-}@zqk5
z!x53QG_jK}y_vY-Bu(sal5}sYvIDhhGj>AXHmCjYZFhD;-!>P*cmndu-RRmrHG1jV
z)^!!PH+tiF`+GR-dF^Di#iR_l>?@xlH+<Voj(<(Ei5(mYjpy;RcyF@vEZ$2Tg|>Yc
zl7id53rWG5(&_yy-b;%0%8r1Yz(?HZ2G>=hjcj4H#wVDEMQF}m^i!G_hR9QgK7(vd
z6?z8MoGSE;ph>ZPfkenj*HFU0sAJ(@uv%02mkcnqMko0xs7qjz)X~P{o2?Fz52rLC
zGgM!93OU3XpoI>hzn<FmEf3sBfnEBsPla8axu?J`kK9vHHvvkV2<<v{>g6thxXAkw
zjEg%8(Ia+h<mOSWKr(A|ct3vv6j!bQ12~jK))=lqMA?;<&oMTp#OMr@&Xv&_CjF}O
z#Fl#1Z=$=TmN7u%?MDfNmDa_84B_SsNIXBa=LN<CFGXNHFark<@O!)6fbh#%U&b&C
z;Q(2|UQj{ngpW$gLX<_7M%8I3sQLHAJ(6#z%~k3X11KtM&?40zFGg3AI>3>9LzNKA
z%7>CK6`lQ^Uw|!DnBB1tO3ZAGYp7H{7}ijweDp9G)Tt{lgAuAU3FLKrr#Skp?AOsR
zAlcRva7s=HIhDS^Xad1pjnM=`!fr~xbi+;p@wT09bc@fFp##F`8bb#X$D4C}B7Kcv
z0RaTIPK>H*hcY5SImm;OC{UFF?TJy92q*d<AY~)?U)j)&=>B>HcE<s(OzS~eiI?Vw
zGl;p?N)oKk9PZW=k}AR42}zZW7b#z9(MgJ<Um#{p0DlV7!1v2EDullzCgJ=Ijoda0
z#WbPvQ5&%5pZVEARaR+%pv3PbzPfYepQJ9MTDA$f?`+2`B$(a-_sQ7-({on<OfNAb
zFue>GdZ;kW@bT18HwqzOd*w6aW+9}2`<0sbDb?PWq8Yd{@Ls97h9L{IsX~YKML;&i
z0<uZlDX)%%UJuISH`pskOC6yf*esd4+EmKKkmQTSKS7C!N_GqYSu^nDB56-drOpQ<
z_tt}-41QV<eiRl1_W}bAPK|N~8l3v$NEpU4p-IV@Cuc4$L$JZAFFuOGf$*gdhUw{w
z$^ZnG2)c~%2dWOv@PkteeAG|DNI{9k&?R(WgPyP_8;rYC32sIusN%LEnfi&avQZgB
zsWY5`3M@5c$kTp;xi)1!V#MMXG4?4fJs5qb+u06yI0c~@@1ROz#&`$SA2XzxXVKE6
z<f7|lHBLMpUrY$DQ-^sx0_||zAS^<~+6<}C?38965L~DH@nC2j3(^_VquHrSJYW(k
zovm0&oydcca=hydxI#@8{*3VztZzFqa!x)nMr1tx&fn9ksz)k+f#}KypNOzTYd+#J
zgOGPJ)ukK^v$F@Axg0pM8Psu#tPV!inNHJ@2K+)#%3uVYt}2Z3D27(fO_!3PcslwK
z81$i7S7XozqG4@x2FD)G7#<7f%wYVSt{Y>=&m~I`zC~tl#)Bw=*TzuTFTY2KV+8^m
z>Q+Rku=>gA>CDfVk#g+K3>r~DvLTn;rW|$<<$SnNm@_V)V<<MdfBMN8Iv0h8RtBRe
zB-_S}XzTo^BEdN*Qyu8Yo(cr#3ZxovBfW<)Rz>mVhMabrQrSty)k_I~{DfEZF%d@3
zLxCw1&S}k*3FowC&IAS_U51dCTblQP`}UTJkwGxGKiJ8n39=!MNSrVq%w$mgInVis
z42C<9<~~O`Q!UJMoVt<{aPL3`Qn~{}#Lca9oB0{0oQH!68YX_ATny@>M|-k|*_F=0
z7>aX`bJ8%O!Z?E>hlG}61+0Rrfl!?LoY%Y#-{;6?3Wjq)BjLh1pP@e8Dn^fRohuS$
zsGpqRlak%=RlqNFw+Dl{QxpXrq+sWq(M-W0y?HRb!a1jzUZK&ZF_>OKnldAS?l_0%
z9e@~L?|+j`34f<gi$O!TY(<mF7~~{p7||_T(PVlC)2(Nw(soO|p7+VqlFUpfZOYtY
z$cGrvAl&RSK<UP*tJYy9ms(aI1~A?7NzNO->AOC7$)%RQjWDOXJXp!K*HMeWr|YD`
z2~x~JXDy0V0cW)d*+)5j-~kAU#{>KgR7d6eF-BA|-;W{pBa;SQAjOoVHfJ`-$UdZQ
z@(oCBMnNuRF}jkpG8@uTKmFuFG8Xz$x+I%SM+M7B25wy+tQZZ_S|?AFP2`@E)q_RG
zl<nzBp&N0YY*a%t$i!cA1F?RY(oa2~qTS)~*!dA31BdmI=gL?oZ9Q6<#f$F<Sw0u7
zAFQ>uq$wk|Y*YA(l5(-0bdqWpvN8#o;!2vbC__ty>JCe>zlIpKKzeElnOBSp#kOfu
z`5MP#piDKp2Ad5@)->sStvY2<%x?9^DEStZPWMUTQsV{n$H>U%_SR~Tf#bG$vfSCO
zvbS_}qQ!M)mNMbFSfy_%s?S)<Z^^d*pzviF)Bf=!0YPa;HpOCgD(udpflGSsgVNbv
z$Wf@FEz{Rgtz|JnWl*%pje2q{o?q0nCZcHP^P#ge***)CpSP6OLqQ9BLV79-CoY=A
zCo^iwF!7+AaYt_b@)(*wI;)$M`#ILi%$#R+(b4@_-q?h<Ru|2)xVZuEv$iAv!yBai
zihMnmmy|P3>`PydS;Z;hO1=6ZMXP1R1!mJ2kr9pDr0!a^L!ql+B6*$5PWzy6)sVi<
zrB8}7Wemw2xhKEsgFtR#8@ulC4@wb#p|de|MkK}8fD(%|&OAvt^9<;EMD08X4E#w-
zS7^{_%dg4Wp}QP(%0m(G=S(MiPLM<4`G-XG-X2Svg3Rqnij@?cPL%ri&CJZX=O=Mx
zdXXN@9Ve$1$(>amE0UD^Nr_dv&!-I1q|@R*ef)>3eC+@J%m4XN(r@1<Ve+XUpak^4
z{MV0vzV`ONUp;*O|JT$1<6o~=`}N;{@{bb7=SSb)Q+@SUKK}Z*>woy?f4cwaehu~4
zf4=_rfB5S^mNx(4U;g`l{m1{~umAJ)KmGOEA5!<%d|wkNYuvl@HeUakAOG>+fBd)C
zbG!5W-~aNrt00?wkL~xjkAmw=$9CK^`$cZECc+oo{=@(Jpa1WF{OkXfTspdXNtFH?
z@1+Ob)7!RT{2rSu<VZG=-RT=#hST~>F8{ax<==_RwwJQ)CA3w`c>QDEuT?F-%OulL
zkx4>io?QO+p|Fzck#KVT<be@CX?P%7IC1}ub!fYM=GS}c-~D6n|M1^`{P@@_qV2V~
zy~@~c?Ddb{N}1#Lmn5}UPOsJHZu^?w-|a5Xjt-yZo_=)SX`%i*7GT?+=W92-Hr4i*
z{r+C~r>3p&_j3u5%-#rbPILv5|Ne``W2lvU9#iq;FCR-w&3THJo39>fD{lIF2<@Ld
zlySXWd^Eqg_HCykpTEEM_WiYQX<|4N8|xP)2JhW@s`tkM|A&tOg?k<oEceUDfR;Uv
zDPPW)k0CRimS36bzPJ9{cku^%zy68!N1W1`oYK~QH97OV_vtYbe)1SJi1XN_ap%j&
z;2AoPjq)p_AwetO0NdYu1A(LXgD;?b{|ylIbS7tX7<@T7Byu~CDYM&`kKOarX!rbu
z(U`PdkDV;;Uq0q(HsKp!`|nd%UeA<S+(W0lfBy}9+~0o#EOvb+H)sO*a&kyzc^*@3
zv@aja<P49;Z2ih;b$lAFj$auqyfIpT_-4Mh`a9_B_fMdYKe7McPUN4T#wG4A=K=3u
zXkd6`J~r-d{N(2-XM7&%bWMEu7!ZqGYqr0++GVGO{)4^#C(iqVV1+X|WdZwga&Us5
z$K)0N@-c*rp2zO?3!}l9p{Hcr`0AmV9vLqGq=V*LtN%Ku+8=E7KcVcvyRCT*`-OP{
z1o+Sw9~1jyi5cqqLtx@o|MkffmWju~1jELc?}`J(s;|c|fB%-RfAK%q@qb3UKX(uk
z>O*<>)!XR4rN7vGt^fA?|A89t9X64@{je!Q`ARtjUgbO{!k3RBnb&ztgfAcS6jA3f
z5x#t^zyWriJCtv{gzYW)`AhiD2fB~5`)z`U^7RZ8<NJ7ygs&fq`0dA2Xn*}s7Povn
zMZ(vQ&F41B);AWvZ2$PrSN}V*sbra}2a_axJ+YNm<;QcPeEDE4>9#lz9?I7b)->Zj
z9u(#42V4469}kN1jdxLZT-MLu#dowaCJ}#dD$3VW1X$wnpeSEI=;<eUJSfW74<bR#
z<3Ulre2~bOhiDMxTe9J$gSz$AzIq$qyP+WN{AozDUpeO)3HEqUl&>E|?d->cqI~@z
z5OR+PMfv){>7UNtL;23z*lrs8>D&0$jb)Wj((_QhoMOBCC;53OUq1*0?c+gFzJAc`
z`B1dJejv;6Jf0!p8}DEn*4EG8!FOaui)zIWHqriia_PEzJVnCSkNNYA$kvw+bQsUh
zLx=M9gMh$39u(yp>)$v0@#pLR9ZjhtF6Y6iC|^$zsV*K5it_b?s8s%VP?WD91bpi8
zpeSEIh(wZ)2SxeL+t}$!fBrW9#2rVMu=gv^kB`qY`PnW1lfOoUZ<<VB&;OfvY)bj;
zvJvHHGt9ItkLRlW+~H8lC#MYwKQn)Pa@&ybv&Y^YH*A0RCEWiuuA6eBEc9b~Dir<o
z{670{MER*XseT^ums~h6g~>mU_)AWlawGTEc^9RB<L>l$89U_UU-9lFMghZo%uvA0
zFYPy<Jvr-_JUQ#LCujYVCufcF?tUQQCy$}_p3F>*kil=ggtax=KRA{Cge7}@_T-T8
zlgWMd<g8!v<Sf+bdss>5FE|7o*+li2tH|${kA3pw_@DFS_`i)O$3J^={FgjA-tF;7
zx1aqyl69O1kay<GN9uSy5Rt84{`}2r<A26$<Nr2Zn+X)MCN%|1{?bVA{oNrz!q05`
z<<n@h{K{ybJvsB2JUO#9+Ue7k(AvXJ|98KExji|5@CN?Gi9eAG;Y?1+5x$%pYP6ll
zRJ85O#}Hw09#hE0SC0*(lRhqwb^n4VVxTkw-vHa+d;?=E;QxwuAaaSaPG@q%er0m~
ze)qGG@RP?rtGwfvG~V$Ur8IsCr8H1kRBu3)M!)w4wr}STzJWh=5BTidc~QQ0WaI_#
z@!+9+<7&4HmZasclz(N@UqPX>2dfX#Pc8n>$Flh?oB!)0AL*R?a(;jL&OufYM*U#*
zLHdcY**<T82kAQ&_16Vt{nAXowO#Lw^Lg&qL;8t5Ht!qHM-S;c_R*cOr~JxH$9K$g
zcSdVH*nN<G#RB<!Qk3u5Aa@47Uz(?XXPy}_^2Y5UeQjMrg1N_|57Kw+OFJEx{rnXA
zj=Dz!(v#Uk`g-U7Mv{Cww10g3ruSc&cg*>p_Uw0bcFxsznVWpspQru*?O8v3HRCVK
zs~6iIUVorG{^9@C@_Yr%-`3{;=MUwI&jsx&qY#1+rW;Rp-)`qM*;5hPg!p^@77@Ol
z_{L4i6-FJRO~`8(N)h>Fs0>0Qf^g#(I}evnmcWHq&1a^2M9Cqa471LHLp~W4;}vsq
zR=x0wNfG>mun(UM#&ZK(L=|QgAD`4!vWU+W6tI;sJe$z7Sz@7>FwoPBv<VeI$PN*Q
z?rC`N$!KTK=n<bx5ac}?7_MV!6FBA_Gf?y$ZX`YteCHht%h<bgPWvRj3o$n?3y34N
zkxxe3A^gWDL*5V~<da$HvTlw~UdDZ5@m226Cl((D%Pf-PlhJOdk>iu$ZisjC$sE$|
z<csld?pRyqjdPF1WzGh7tSu56yJKlpCfyw~ivbp9#hg68a#q9?12*E5R~26wSnZQR
zZtKSKGvN)Q)_gK<7m;l~@AJsQBj9QkFmh*OGcgEGS~<86Mg^@5*!96wW(z5deK2lq
z<&1nVqs_`j9@Yp2d=at{J8CcuLWUAvL5Z^f<z#jn<K;bn@OHWqjqoC5BiWsdpoGQ7
z2O?=-2fq)-$7Z}{5WrjmKQs>^>eDmR#FZ49PtalV!}zn67hoSu>$x(N-v{%^EL85^
zlspMg-^B-Es!`s>2lIHrRqq3-I9GnHK9n$K<p=E}zf?rs`e1IDH83#(>(@xOk>+J#
zem?kNqCSg{OyUxSS9~y36=hdkusl><@nH-aUK1=aP<1(&$~e`GjrKw09HOT;0W2cI
zdQ&i}!&1f1Hlw+NkY~kO;F_sc*24Cvnb8AL<USbVA93bBXc|W#x({a4DmTQ{V5zKf
z-((DN`6Xt~Aku>9`%OtE3d*4P$dIPp&TVz`#44zZ;+dZ+3Gs$*F_Ly1?+hX>H^dTB
zYQ47mChb-2OG864bt0!rmP!c<M#@8P6F8K;X4hTgWPGA`*AyYlIz0mgX(7D3I%z2j
zUnDd)V^eH2utD_crX(MejO7C;1X^y0qdxPGV1aneg4`S4hnRvq>O-UUl=OXQ)DFh^
zeU>}F%NGT$*fG6poDnnW%yY2`v1xkOFe$?~rC|*rq<T{~6U?>KQOc>#EV2a&ST=?I
zKvMN4b{*_CW-u&B2lFD~2fI_#z>riOxsx^_xiyW8T1K11fg!NEY2cJtozbfW$e=U}
z?^YbWz4Gkbq<rU<BQLyi7CI>9jur+*W}i*Lpyf`*&!zsC$QZQSc}nbd&W}Om1!;!7
zBS^MnQJURGWOYG?BbTCHkOgT|*l_{-w>pNb>o*b@mXa;b2GXwM!!HncGGlE@ZrWSp
zB2j|(TLY)iYfIy15(96G6UsAk6Y$|@3ad@%7uvyUb9K_Pg@uJMY_1+44V#1cmfucu
z@daVmsN}wGC*WhM-xN8nh@z4i%dQ}G5PGz@CXjb+YE2;V8g=E@?d{bXtZw;g<}$W{
zE>j+R8|pMAUW019L94sj|H4*8XKw-y2H00N1y7{JQbnYKJbJE5Mw=3QrZomu7o^{F
z)ezbg$7ARiQcIP3HYFF$nBQ-c;+t;zj!TFx6~Ec-5D+W_Q;@*WRf(lUeVjeZ_(JO*
zv+~D~S}Lzmkl4{%MJrdB3hSm|&8V|(Qmz@Z+7x7=bk&tCNL1;nVzDVZ0g<ahMM1_(
zZ~S|%>aC$6!+;D;N^Wn3w3lkp#8Fal-HKugB~yEbLyBGI?MsziHz9Q*l}{+hFzTvd
zP>`3@ZK0KJE?2LRX%Ro4T=i(NN60kQ5hxXM&0Na^xuz<>r9$y@V>4K%ccLHztTT0g
zK>(C1Q9tdYn}T!@o0PMg8aX7LDmd?Ue3(Z4xB%1Z26gx<71uRo#xGe9CMcZa#EkTH
zW}aVHDeX<b>UYfwqK_HrHzDWHH53FN($DX9j~0vtn~*c0BD^WFWmSWGQ*usCBSZEX
z^VF8i!R*QaUr^G;k?*~ro{KBFdqFyAS1$LG^<1tXVQhPeKb4a&$Y$*-IbV=}+m$GN
z2PGwMRfnOabW>vV0(X}i)#8HED{kp8Ehw|H+sWKj49#3wq&asbFW;1WtwqB?mMJ^=
zreLEMjFXbgq)a2fyBl?BB!zb?8agFePW=KUml9$XS?!%E!e10z-0Bi@bT8urzk;-x
zsZx#c#=S1}19`@r+XZC{yh=OXd+iDWzIhZ#aKUB@s*-qhjWnXgQ8Hbl*Q~ISlvvy<
zbsAsKi-K0pW@^-wZ*^+WiF+n<T^E$t@Tw0QH9lNfs7sb7aV4QHsAu9?VCn*ip86k5
z4dPY$F^Yt{QcM>V0pAqPe~~$9$SCyTwQJ}QaJ7qDT+T3?e6^lO>;+P6rpiQ41@(1;
zlIxh&K3wUe3uK5#?&rcfLtZ6kTZvYlIgnajr5HywWS6V3pdQDjaKTWJ<3&O%xn%OX
zf&x~Xf>H7sSEUwbsf{a092ZitN;gKKvQ5DWgPLfYg5%;P`Mnlt<fyB$Nf;S7JLQ2c
zsG8xmXk-Y_T3GR+WR*Tw;^%^j7+$3-r@G@z>0F=?xgb1+TGJ-wPxAL<9kQ}W4Mq(M
zXA<Uu3KpJ8m@kkLC$iXQ0!5fkuAnxBmnGgIEtPNi+N3y%i?nBGmR_VmhwkY``g4P{
zEYP1D5~^(i$A<VUuCXU3DJ2_aC0t>orNPR)Nqh{VP$`g0XzgBxxP#;?L;OMV?F`5l
z2+57aa)aP2)S6q$y)rZm<Q@|qUqOnES-QrC=qp`gFDyC)HSRjQje{sJL|2e1f0HXt
z>vD-}l^0r<3u-)U3Pwix1~2E5jlv3EOpoDSSM<rpFtjhz)8xt=TsqQQI}-&L+*w_T
zf(!1n9*Kf?D;cS046JrNtU>mbs-aW%DKl_E9Rx4b+dC|rObmPlDd$u1gE#|<6!+eu
zg(DJ{1XqsV(ov(vi&S*f7VvV5GYG;W4IAc<O*v1caab983(P1UNqS3viNRYcc!wCg
zrGvvL6O^=cZc;4ty)-Ul;k`6&%EDV}I_d$uDAAhuew2Q9lVW~1?9Q7I(^K}{P3h6*
zurP4mdCtJ_<;t0hkVC(zgac9Kx0LXnqVuN09dV1vsJ`qD*(u24rX;UJBSCaBFYYF6
zo#d7d4ujyPkbQ{HTOT_Ni+<BCT?SIvZ4w4g`=sB}%8@PKZ))WO?mXqjEy$I>DS6N!
zGyW!E?2!*}+=3ZOCm$hX@5V8B^;E{&P0IN|0Us$sZ>iP;cS<F&Eyy+>6qtdKTYi(+
zFGT2V=-1-k<QwwyHt~*R;;wA9o0Kn}cIyHFhAUfb$&BxQOGAfg{c@zMElAz&N>95f
zHJ{<w5UID+_5qoB7hQn{geJ4fmUJulEdw?j51T?}AQ4eEd>=CKUidAYdq5)IG+{@s
zaKB~2Mq==(bg(5;dS5}};4@k{07l*vCv&|P<jI~&_FB@lGg*E;DVzVf^mz}*$Wo_~
zDtdzT=zcC)r^iZtYm-dB*?-&=u(EPsY12rb{G#j@vLDYiq@N<S@g`w@GiBOTCe;#I
ziKjBDmdrSu6d3uD=66OW)q;e+Q<+ptChMI_q*~xZoXVtHGV$&eBpe7c^~k9#s3nrR
z&L!0uIa{Z4p%!Fco#{BcKuYGAL%P82`l6r}%t_WFU+Jdg$32a_$sRq4oR!v%1e%+I
zLw~ktanKxoQ{a&=NCY_-wd_fNuGH+zwm6m1v>+|wWKPq)`W^38pWW<ut<tj7MgF45
z1U)-;Pobe?cFaI}^&HW{*F6VjAf0*+ydhbn=SWFCmG@(la#GZ@=g2up&7K2uf|fle
zCUonJ07zkzIQGOwl{!ARJe)3Ne5QeSQ#ix4piU(@EkHwTN)DYSt=;CV9q4B%+A~dO
z)1_zw$T3~2Hn1Mkp=t+GWGahk0hDC=)FCk!n3JV?E-)ucwdc__k=k#!_uf?+)2jf?
zvPoDdpjoCen-<_%rV^VL09vLJo4z_Kn1R%D&-Xr&$8@(158-G4EM+QlY4NNVu_^e_
zflS$y^HefOz1r>7kj9K;q?<yu6wsATVz2ofP9;3ulzeYZy<&Y;sBn{Vfu(ulkDG$i
zAfMj^974%QP_jf#LEhC(;R?qS`LEdQPVLw`wu-FUfS|l67n=L`vRC`SaMFf-U^pqm
zKBL7BXWsKSI4YaDSTa^SWSGlX?GR!vZ8{Mun?P$U67If8XvNE)QkG+@Po--u_!xqM
zRav<i=0YpD5DIEjGGc%_Z+^LR`lE+fy{VkR1>gTBVKs0@%qjCUk|WQl?=Oy;IR(oo
zK&os~jt!*BCSY(tRW=3ZBcLjqLVY;_D^sAVl6aICg{m;%D04~|UfE)&z~@Y%s5Z&)
z2zw1lIHd(INWv*KctH}*PD4L(X>SS#h9Cr<s$@Fu-Q>U!g_D}_RRCa_Q>yS{T!+ll
zkfn1{J$^~rDTq~JTJkxe8UyAsr)<-Z=yS?8y%<g+{W*~?bDE4tz`9I9wF;81&nfj8
zO30kjhM}j-c?{MsMP^Q^!V7|LN*9LiGbdEx1sOLbf>%~wo>Q9df|OJEO97;1P8qC`
z7=KO~tk+B#I42C&0eqPPVHF@>=A`zFto?J!ULB*}a@;Kk^U|i5W3~191Ew;E)L;Nr
zCXiQGl6nx%L&3_BwHjLVWM<F`-FpsNtLvQ}z$wU8g#y1Rd6ZOW`J0kM)hrgV2|3ax
z#O-7b=THz}gDUo><fI&}oY2(3CFV0JXDSdbb4>OL0VjY~1y*H_Ax<n?cQOj2>l{Om
zKzfaVR;>N#V#BbEUGs<NVkxI2Ej-q+kPuy?YwQ$Vqif`bmF;MyT05GChHN7Ys{#Tu
z2X*dx_h@m@4({9D5fxYLDHvA8-F*%dR|8C#*cy1f`AJ?$N=E9VqvWKLwHXbvm2YH@
zD%NIR0p_S08iG&gstVJ`9MqI+T1Vz68hCPN6^`uKSw*8mHjbjvAs>a(s)2f$X-T+1
z$X9r?--S8c>UUwQq-I<*a(#|l+@b*B>{NSefk5m~dp9AN69%gm$itpmZw<i8?1C^?
zAXa9l3AzHYGCNJsn-c7I*T@iu3Cp@b+FP)@hQ`gWJBCh0XLg#PD-40N(*%80SPD0Z
zgI7$FHt33CX0uOq1PMs^RxMc_Z+2?A6$aGVhxmhd>*FtcCb`k~4WsO)q;IU27A>4I
zz^%;Q#Tvw0?;024t#^&v(x5nn*{U!a&)zk3!;*K-2;!}Gjox#?8)aFA1$*|U(Q)<b
zyjWM%6rA0}^8klNV?j;8%IqcvA<?>tK}fW2WDo)khUAx~RZ%x_1}Lir>ScBsp(~0p
zZVGvWJnL2CdbEI4tSAJzNf;CYPKc~c$=Ou2GQ_lKR9xwL(Wtn<^`f~!BzCIZo02c+
zemoV+K83idHLqw2lBg*Cxhdcd4yP9dtq5FQT6nmuCc#w|#Y<;f8U>=Q(Fk4P3!5m5
zeI+S7=D4Y4Og#{@5gw}oDl?mN+?wXsP2s??=$pWCahq$dVe(Z@!L(|6B40<UasgB%
ztlSiKWWnv!x<M=ogtaNj@uW#*lal43NkA;N!AYc4Y(qmsDmJL#SCDcNRKY7exU&t7
z4$;_#rnS568n{F9x6YAMGSAjEG{h%RUlm1<cbntp{jqh44Pa?DiQ^7Tv1#m)bEFuD
zJAD!ub_FS?*f8{rf3r)7(<VU<&`eNn{w8fbjmq^VCI7}wlY7&2U<qxeWrQ$IOxOid
zZf2UND_}I6!ofqDwyKeF+iVphLk4XE$IdSEjHoF|Tlou{$(KHNR9xSbEJjxY+%X%i
z(z~5QQje~vB0n4T=n8nurewcY1&(AkSfy(sO=hE6x&j?Djb`Zzbj-A+!4c*#g%8^#
z$738l^_)$?P`F6i(pYhkG})>vAURWzv1$;KCPmsHBrRwC5`Q)|CNFn3wUm&5MnMcP
z%oLET0=M*{pcU(AvQ%$UETj!h7qZWWhECaM64eIL2k^?3qzt$p_(6QbCguA@pC-i{
zIG8Cw*QTVxWm1{}KAXm`%^>tlN;B4CniOX&*fou~=}j7VjH?3CXDwR01AUJG-)+hs
z^$JQZvuRj}Ju?jp(PvV}6D_j|fVEe^Wu_oq)gbzex;LOP)1-d~G-jH#Zv)_AnzV0h
z-YG~|#g?BYWxL&&19k0&B7jr5t~V(-mS)``AFZfk2uP!0x}rePw42s~P0C47|Bl08
zH!&vwXC_cx6{wlr=Ew!|-fj(zE22q9&ogIMY3L0m&`Nm@<jf`jB~k&MnH4HJfHS+z
zvGeuJDjgk%>ZYLJVa3Tig$}E6G|x)gb;aR5t5kHH@UuciPZaPK1dfz4RA8_Q?98mv
z#~Vawof;`c=(R~43No}#4AtY`oMB#EC-Gtx@S2&B&I_d2;&o_X$j~Y+KLzltQu14>
z=Ch`ff7J#FD%jbkBxlml+l&^@8o**Ug-`IlS*e}3lzvr;cZ2j39IQeonzgB82*1=y
zE|BsiHg+7suQsi|W3xzoZw~fp$9~N*f53rZePs%@3SDwmQ?Dr^10z-g*)l83KUW}I
zHU)<jkS#Atv{I;5+OaDX=_%CKrsS2UN~6wrh*^s|g-omYXWaTKP1&20t98q0(;?#o
z<Jy!SZ4L}WXbpWESCd(mI>kMaD6ZPuZsfo6wF`C?8Fu$@#r5MoT9Jm_8&1L^9T``#
zSzHr`cvDgPiYwg|?yBak?>b3eDsG0Gg0XS4Qvv&m<ZM#~>?;5-n*tYU?IW7_xB+OH
zELLBEXPHGRbK+TM8S0c`QBbYgAr@7gzUD=IsyKZ`sMRb|nmff}q0-zT6;*nEQ*r`O
zntS%ZVIddG(U>~~W0A%T<jXA5m^%cckXkjdFcW3wucX9gL>>7GTgWU;gF{f3ra41W
z7OK`)4Xeu(+N%QiGF2(QjyqaC{|)A)F^}BH*A%p?rU_{lsmB8%Q6=8%fJj6_stQQU
zZqw=mTh%0#s|LtrH#rOhVxbAU0^~AP#r@i(+{#5mLnIa`+lhpk!gp05VP+{D7$rSt
zDH<CB5oV{P<Q%1u!+<!8H1dI(%~LqBO$z>$6{iBoG6nOh31peKG-&`?uBpQ7n-t#~
z3$It0QKzb^*U_VeV+D5DnHAM9kmBXuGHk=1yD1zeCD5i|oHQd%)K9;Xlyk}_AkA)B
zwnyFv@2Lsm_NQ9tHOt*!Ny56oTzX5xCfG%&tqQQqJsuCGx%8I78`arg6trTOsd#yX
zS$_(kRbl#{X<oiSay-V7@&_CQ#?!l_l?y8^J;TATAWi;;>9II$N<0-hsl>-bwed=9
z%q@>oCD!GZF&n|~Q)sJA$z_x+8#SdjCBrvrR*c>Ru!0)SQ`NvLiZpKu769I+Nxan+
zq-0U{?8MC6(y)n{xv60jGIPtCO-I<gC94UUxutXiHgikoCM1S+yekngS;sq<t3@;a
z+`zrG>2L?mTZ%J0hGR){o+vRt1kb8S<uFvSyCT`cK*jEw$smU6byt94###~)K*NkB
z^Y-jWdZw=#_?S)M*dtmT7Xb;I)Ir#9YPUIZem9%KRU1gQCRI8e#bXH>vMD)5snV#B
zGnRDaIWYn1%5(o&DscM3uON|K2Y0Y^r%yfFI1=D@A545((=k6Xn*RdDgAp0KfqWTD
z#%?4+8B3~kCQAtl{aFE!8B5wU05XGRv@3uHLuIt9->(*-*1J3zW+(~nH)bex8=#i4
zBzysC8G?UpN{=>K^8!|6=Ju3!gXOC?A>WWBGN3Ro3R+vE97}d?z+i^TS#L_Nw(Q)Q
zI(QQ}Zk{05P(|w~)f@a*v~po(*>;QB$gb^%$&@oc!))}m16Q*X{_(M<6o5D+yhn>{
zbgsUv+Q`oGqM-G9z@=jYA~Xoj+JxZ3g{<DBSXEV^j*`iHjeKd~*qfWcVRQQq=L0d#
zA^27Wpk}Z%bp@Vgs5Eu;87&T)0&%!Aex?FJGX&^jf$HJXv)z+3iBorQmYVjJq>iUf
zKgpd8*zRDD>bU2h$?L+(yJRv}XH#%GU<HRtPFG-UhKf$td=uAjDdRxf45uy*tj!R<
zs{(5?P|A&E$akAsWk78<0V4xgGhDhifHgyyuU#a)#O^ruYE)7m4&^&>i^FBI2DEVq
z%vAw@94?b}LL{#saRwC}L*EW$&2U+)fvg!W{Ts-d;m2YPXw7h0tZ@=-3dgqG57NkS
zo@`25Apot}1P+e8kA#nHg5wz+G^+)_P^}j(n?rE1it}(&&_~Kcm)eX|cT>n3#NnyO
zU4fe!eyd~1L#H8ojcAau)c?km6+2NgSCBX~1fpPL6;PT@!7&IawkaGLarT>pp%dJ=
z2^>BI;g}NN08VcT&LFg4(O3?Cbp;1d=0!mZ=}gHNWS`2_)zluYBw>OOep9Ay=pio(
zTCvh|h^t(RP2n|RLH125;&$KB$`Ah4!YU55as_GBwou8gpyVnW;4(v4Fhj=iF;ztV
zhLj_U%QBbCZo_b3&`!ss$=aa7z9?wLn$c=)(1AAveHxd{#0f;&G|dlUZK_gz1V8LH
zhlN<1LRT9QGGkT_)v!mZMrt{ss(~8zh|tw`Llz3!W%quB)$I`@GN!8ABZg!EuoV@C
zUdQUB=DZ2XYdJk)rD?9-lw|(a${}gmCSm9leS&crkTql8f8h_3^;<(j_RX7`uK`yx
z=B=?`(r+w{n;Uls31&diY)VHvB=#n7oVXPZl@u_5Xf}nTq{2Id1hc&0jv@4j;SxNC
zYl;w<!!b65<8Y0%vW1sH={Tl_fpi>G6H4h=?p3v)Qao-Fnmd{0y%eZwiM&Z#z7GIz
zf`YvO=uMEY#elsD5<jEB-vkB2!+;SatXD~!=ZmB*Q40CKPgjME(<8A-$-LfhDd1gT
zc>|y(NQoD<v<xMQ%-3L4=y-#DDM%bHC0>yDEtZsvFPdw>6p%r}`h|cD0+%l(WRSp9
zipZdl1<UEVwg7BxFVfU#4KE_m^%rPhYHDFRnW8(v5>OKqY!?7(f&_Ps0a6pR4nn>z
zsa#eDnwVV5$0+fENL2$4CukgP<dRe6GQ`UUse|BrDApu9!rX9wG6doVg&a&wt!c7p
zAPQ2?jwa_pWWB+({UVuoa=Zg#gA4}pAi<Aez|;f{Of9|^6H|+;TgBDl;@0!>7CGew
z%3#0`61b>$Ho<wlx#Sg2{Y}D(Q=>9C3SK0dIa!}ONRW;R(+LX1v;l+@w45J6I6=Xu
z4N%RCbc@SMwv>L&5JaD}n?GxOlATrZb)y+P;jVloDc^%MtX+jJUxQSvC`=cePkrhD
z<OGR_OF(jh!to7zaq^kmiPEtQE~y|P&4s~nl{Bn*%dI$F<2StE>1gK5oiu7*Ry!vG
z|Hr2EY;(;z8Jyy|lgWu@=#sBCuUrN|O_0#>0DnUq5A4&UhE-fPgGL4hr!mC9;8b|`
zvO0IOYkWj-1Pu&K?1!VVA!$vJ$ic*Zm|YCuzzZ5qBBcFzk(!=#@=0fgRW!-t5>ry=
z>LORv=PG5X5cit|rt*qqHAPGiG#0lhuUTdkr$XwRQJhYiQq2$}mb9Bc>q!6yc5`xh
z)!GES0$#PuN;at%S;0p+tA;O}tqumG*gVP{;0;O2`=MFN&3TJO%FUy_8RaI`H>1#;
zii0zw)SS3<nL%n!Uc3xwkErNGHj!WbPA!gI#bGg)I54~fYIa6JDn!2-1?gD0I2keu
zWd$j)&|<zvw*#UlNF0sgcQ`MZ2IS3)Cgsd1NC%x4W+R(8yo`c$OdX#{<P<clQ_9gX
z#UthDm}r8-p##P!MaR(C6r-w6V+Jv*5C8+*CrFSp!21LV=YUbzMj(J0C9NU>EQ(Gk
z48RiLb0v*KIbXKEc%$eQuHS(73KBcZ_ZK8igrZmYelv>R(bPR9@6e^sfK}bJ-ELd#
zs-T87irqo@fi;TVp=)2G*v;tl3pDIo-TWHluEGZl@SjbJX5pr-l7fwrnb8B*D47*P
zU;+OL0wxc<Pmo~wvzE`~KRGQrS2hXL;-#QLB#)vAApK;}I0cI2A$`A5BoFEPjUt&5
z1DlfX@YW<Kk;koRP%00p5{*)M=$1f~PteE%q_Tnw3^<=4frW-0(wBH>INuRpU@gUR
zr>5U1l@%ATNy#Jv1FS*fc4aW%Bn&RSz73A91EW#m_NmS(aW}jmyPDa;;SV%VkhmTc
zxLvn{MuFRv=h2WwGH7IAVsQ~eV9oLM^`QYBvl|jP%{e<=5dhVW5_^1*5|=Rm)^IoN
zO-Fm9H0_MJvrcK+(|&55vb0OF?>9MUJlp%t^(ENII)$l%1vUxmOG~TeL#7K-r#Myk
zz$Rfic^&Ayymnm&IxeqW!Fkqsd+n0=onlyF1Dk{wBgMW`!a|sK3RA)U4asDKL^df-
z6$)UT;xtfB>?`@yH{B^s(G6v3CwOU-@Ct6m)LEx6?YbWH6sG;w@QqW`2i+-5BZeR=
zj|7KpX*679n=S&K7ulwZK<7QSEgiz05?GM~)(0ko_fKitTz#jwWuU+nl;m2m0@f*W
zn`<Hzxr!gKPLZ3Q0PB#qZE9+iw~ZHpPI0RU1M3vGZJw!7<|@p<I{M+@j(yuEnz=s|
zU|=1w$U(#Cydf*dz&dWoO}7Q4vknr+UOa=Fw1mux9Te^)ifP3fSf`j~tbvU?TfDjr
z%HXD3z@Q9PB!LaeV1*Lcpa{mPo}`=$ffF_;f)Pz%gF?9JIx#4NThp00D1{YyU?Zil
z0uMF;?~QkiQTW!*`7(GDZn_!_h+YK^*x+SYaRW9ec^eY4+sI39liEKhQk&HNL6O>u
z`ld*2<uJvIF2W3KK%h1mg9im_(*<IvV(Pg-WI*PNbc=<~<-~OXx%Gp<&QtCp(%|*!
z3<y<}J+wiIYEtkAB`SjkY;0L+u8Hb$YLeb#Vr(OjX_I;q*fAxgxjN?6RG|enC_GID
z+d=VZ`rrq|r|C{G0ICWax_4|7lg>Y~=lo}`s15#{LerF3(k7*5gbP?+x?U}5=#wH-
zF#|R!GA+;2D`~lhO^W-Z%rq(P6HnpGpA?za(S-J|&;y$kp(ee4QihuJ`Ux4T=mX<D
zchk_u`;*c>^U7*c*(U|6;tOn2pxRN{r)8USGEPGJ`lO6CLlbkT8r#yN5VZW}C*-Rl
z4s24sD(Ju_Wvqe@Y&OkQ#{EedYZcAtSz7$0d}S1ZO<rHE5S?I?B3F?KHYs&Y+Wv&p
zHR%PDQa6JWF3_+)sM*696ckRFLf53)BOyePXd;*?c@=+PlY&<f2sSBr8G>Mwa<{HC
zLkeC5A#6fSMnMQRDR~uzV3VS^9{c~K?5(o@Pm12kTfy{f;Y^v7yof`%Y*P4E8UH7*
zzlu#T)JzHzSHL;lDgVu+_*H;{P2Oy)RQ^euvf>NO?`%@pc1l*o7noDBBEVo1@}sQs
z1~`Oh6_{$1@}1YN!6-+o90E=`s?Y>;iqVRMc82^hLBUcv<tXD5%qd5!Tml}=##|BR
zv^iG@cBh=Jx;8j(s#V&*^QM{s2N!5PDL9s#a<$r{E4(OP37jIdo(q6CF0W1uZ{$-K
z09XBRxdR+hv?_SmfI<lxMx<4_>f+#(wUtfGuE@gRDQc^367cE-2_4g_tndbNUQFw;
z{KFfSG%V-j__F*vC2j;Un5VR548s+aT-_plADN|s#1)~qEi(K&#cer;e}}v+x&b(E
ztA!8cek-#4J1xp6IB+E`=d17tbNqy((|%kW&3uVPvfpVvX4J!`U=mXH7bJC&UcV@*
zi*);S(_UXD+Td8q{i2j+Fodm=Ee=E>U4}&9qMf)%vtJa{iiWU7L9KWQTM*P455c~2
ze=;D#7Vo->h_FSIbCD-tQKA<iv23MCFS-FNigZOr7!Zmtl5PNtBAhu2l7=bbTv(9L
zigU0<`CO#RFUsfe*<K)lb@>Yx#WO-6Y^8uM@)j%#=wiA`EQ;tNcfq2BF1iyeN@#^j
z*n)&kSM~)G_6qz3tMgsSU$8nREL_N<$WC8+_C%SjkO^Cqy+s=TqVQF?gDr^K3~snU
z0$1`GEXvw~OTeO_ExH6O3fgkhSixR67A5U1hryz#Rg{DUsyPUN<k_O6y`dj0%2`E8
z*rJ$an1n6bqEW!-N?OcTp%a^uY~H$fEM9VNS{ZhEQm`qsbh~+nRro`@A!~2?4BAam
zs{n|0Q`FuQ>(nwMX;5;hHU(@=G{Mr)SQN9s+FVJ?SD;9WcB9F`X-mFw9cedB$&918
zf`+LL{3Lhf-8DMyyb7*pH!rw1uO3&sDX|qy(QaN}?<N)-dE&iclfaZPVC|;pz3C5V
zH$`v6O|%<g_cpOfse9X5B+A{J_ltH@?%pO2D0^=c>nVDfX(=h#n1&{{WfcRI&NnU?
z?WT0bs$NOU_g^(UZ^w7lWNB|!%tb>Y<QGYJp>|WOGw@<ldbT+cifjc{Y!X=4Wue`a
z**84{?WW9T@I|{JvF}@pNr`<cr(e4%wiSfYZi?;u788`(3e9Nu`dA3dh=oeMV3RO>
znyEK|!>3?hh{|X{SS^KRv>U$3wRo3kab&#+xFYQKp2JemMMGTILd-=g`ERaODPW8q
zgN791OTiQkFsiktIxXOBCJLq{glZ|=q5(m*))cGx_SfRwp+PdN#jC^BAU>7?Ga53h
zFU4iFOurtKj<(|&4sKU8IkI7n^cyrt+_kzMY2XgJe+#+2mV5>cagJ*>F_IE>Q*a^x
zF|{c;w*Z*hlyr1%is318)3Ltv7c^)to5E%2xxhw{NQ0uZ7-P{8S-KQs(E=K^R#mqH
zQ_yE#;1S*=J~Xl5+1fuZnxA9LqWL)nEt;Rlpj6=-$}7AmXyuySV!^RyjHPG=R^GL4
z4ZL!n-x_yeqw@~XpvJEVr)W_0mn%z9dtC&UQ`c{}DJ-X|-*BB+Li07`6<SW6y;WEo
zmrKOv^<@c^w+V))*iSCtrhr*ogRbSY;y2utUX*C<f9ab90BSij`UdpVLSE9nAAo*Z
z3b1GZKP^RAw8TFxpBl7chWse62B_0wI7I`{X(^<l1<YwFo}vNev?&}2S+SPTeXX`=
z;oGkbGwPaS!<0J5ZD3z9j++$x>$9y5{C5qLQgV6MP#qI$I*xJaU*0%Yj~O-1uwzE4
zy*F4FmN$(ISk&^Sq4RuM3b|;Bidt@(<iOrA4m>bPS?U||J1nnyY6f@I$Q$xQEQLxm
z*k~3)B^v4y?KW9)j7&Yd0pzs2sNdYw%ZvJTzQ=-&^Uquah&7iy2H+_uH-EF4S1qVb
zh!5UVC2w|P+4OM(eY8|hyjh7BzSOi8UP0m`kXj6QXla^Usu<p2zFbpZF0e_P0({LT
z)qINmCN^?SXTOj~lNR|+iB)6a@GD3;0cqG~(c;LduB|!QYpQfhrNx`&4R8eruLWLc
zu}XMDHlQWUTmyb+MTA2GbZ9BU;c76OFNHWX*wxqUT2~07*)@F#BEjXNqgdFkp*t2f
zSsPf?rl~_v&8Cq@Ub&ZQh_^r=Ey3*?kVPxPBpMtPYf3>*C&rpGpEY2Lmf|EDoF7Y3
z5e)_Rmf|9sIoLI{;<~(qpWCGP8W|<A2|bz|1@cWn5)H1PHLLCb1|c`46$5d!gq~~Z
zPg=8RXvjFkQd~jF%~v!!q~0tV9g<H)$6LFjg)g*0yIqWvXaEsy0(wObucfl&4Suzy
zP>Gg#zgBvHE>MDB#YQw#m0W{rFA7gCRU>bxPPqW7yIRWzM}g#1q(lRRXem-+Q)1f=
z*SM%+w^)_DCCq3EUDx0ST?mwDKp3sz8XAIdIBh5m0HZZrV;g2DS&j0ZO9;Kz8u*)M
zsUX`1Ro|AW=r-Xzl?+Ppg&TT}!KH#^8`6A{7jF%o6oD*SLz*v;MQd~o+;OWIT|?&|
z*XSA=q7CKBTY`_4V0H~|`%Qsu0IvN_;n*Xm*fjLSgrrg<ci{r&?n+WJBV8D9p(V6j
zOSI4?;5Y$RXj6j0D@ggKs4pW0&{A>ooPc!Ww!ll(Fh~HqM%6$e-A2_qEUa(kC}|&B
zs!zTtIiXZbJH+20a(+`{HZ+wtz+V>2mp4FU76Edv=>ZzFhNNgBgO)&T4Y;5+Xe4id
z{=6t?h0@TMIDz!*Qk#)vbg4Rd1EOeCa8_ip((H&sTeLVVE@XY76(4k$mJLMFN=(R=
zl$c$YmYsN_)um(uEVR0#6(53-aE)n(Hi><tjM@}-(xXMLAv0Cdd{dIw^C_cZ`07I=
zL1=br&^<+Fmjc}(GP^QrHXw$Us+zYBx!I*c14gvE)aXDFtu7_H4^EO=G$2H)cMT5F
zs#50-0HP%nT}uej>dFz+02o@mX{?#Eq7IFvUMhy(kdAl(Qn%Z&zoZ`n-nhCHWK^tQ
zEOp+10$QEs?}n=P*Curkf>{&y5S-n#auA%|G&BU~DR$nl@0Vb6?e$%(E+re^&FWCH
z@nx+}oA;)~1Znc#gn>u!^$!TiE+u+ENOpeRWAh-hb{i0Z{T3q-fhbbmfXH1!z%`(K
zRtF0HY6<pP{T3q-fQ>fo2B^<!OY?^aRFU#F5UsQXiEB89SEK3;VDoBAW4-Qv%{310
ze$CGuarqNIt_=t~RVr@)^en;JT1cba4o<Eh#Bw(ots&Gl1<XOVsW5p1;CuyutqsIr
zuO^H2fNX0+%t5v_nX5<2wkCu1$m8HztY6*+q@AE^o02mcXvNpvWULN|&~8)5g-)?l
z^Sl8Lw3-anNEWo3)NLdST21b$2I$XfQn;Z`Z3;Vr{A)5>LoItz(At|_<;@!cB^GgL
z4I#0sNhL?b#cHxwBP`=uO<H=Qh*p!54iM3bBIphHp(P+&1A1tMl6QfU^OKrB^9hcM
z>!NC>Hz?3cu(mb<Wm!!cISNs1O3rZReNmOsHz8S-zC9r^+c8j2h|DJY^u&d+Q73=h
zM^=+Qj{C||ar8Eg+f)iUa6+5Hp&>P!%+iSxS|$x0AfaoMFfuHmDx%(yh-d*6*8mS%
zCM`V>Ld%pcsNt@+OiFqTOKlvN$0dMV!v%90)Nxd0S>~sMJg-zVy#enN6s$f(rpZ!0
zdDXOujzeOa4AlVtER&%c*q<d-Tm$xJnPBY=7xiV**YhsFOzJwy;4Fik8ijI}YN%f=
z<MI|Ec5TMp61C79fI3T<xCU#+GFqwA-0^yQO>98+snB_Y-DC;x)_~*L6n2b&$W6+g
z{f@t51%TmMCKI*a*aT9`!=AJ3+{hhwMx(|JqtG&0s520BnN)D3<ygeJy$*F$f?6tV
zzA3p`*osAzl^TY#WwKH;6Uk!H@|F>{OQ^G!VYr)uR<4=M)TnQ@>^}2@oHLoJy+w<o
zLe7~qaG-Er6twbysZzMpAi1jaZ5S<A)z^qX=cV%H4YAPIB2ujRh`;j*2)HU;8HU<T
zA!m?rRXKbb?7gcxTEUsVJ|y5-l{RVEkXMy{?I>uzsuXO%a#od+9mt%e3g->DoF$A|
z0|sZ+!Q&keoK>Y!Cje&?I1p}ts*BzL!C8QqT}hhx6o+z5N*c98E><eki0xmhgMPIr
zj<<v)Ybc+$s;truNmyl-1}0}!>C+3fTUVt<ogkg1Qs@o-j|H$<gM(zZF*Lj=o5Hgg
zu9i*0*lRx`l^d>_#fs?-@SIhpawj_H3KD-Z@C*kon2$7UxRh4a$GuWoRz;~dr0&`z
z4h3;pp=85XwNxU#Ez1^`1YYe`W!MJxW>p!sQH63<8MaZWa#h&16P~lGs;)M`a~9!g
z4d9$rW!eTdXVqInH_RsuXjhU3e#CBaLOLe^o>@g&c4B9iU}$Xt@U)67-ayW*LbW^m
zp-a`x8$70~NT-HZbyH~YhVONg*e@hop~ZXUr@9H8HzXShoL@=GIY>EQDcg#S-pJ{<
z3RQ8W{aY%5ezovYuRxo%#Jnt4GH*b<tRnpxfR`5qtytJ1eYwLQzY0y<9ZvftAXtZI
ze-&!bJrXePHf$>$Wp!U9{5e;V7Vb^SMWo8zZ%DerPq*J03AIYoz_5juhE{TK>NQ(4
z2TdUtrOEpZsOJ)HtKWtJD<4P!SE?9*fGbrDK*$x@sXO2%i?zvvl6+Aw?)OW`m7;+m
z<VxYdK)$R}G&ICsDH<B~Pt_~$iGf+de05-3u2pXK4C7|G)p1+^RnWWx)w2Zd>i38i
zH17_q(7KoShbX)kM}Z`~mqvjg1d8kGS+#q&HA<cp_Y(IIhWFC4;j(wThDPbSB?wm!
z$jfez#-GH_yHhRhfV-^QH8h0dEh}{g*k#?Wu~RzUyi0drUDiD{vSX5y>6|-wUn*_h
zF~23eSC2JW_fR(weK*zMs{<joNgY2)j;RNCAng{hT^+ENn`Y}?0RLS#?be;ZmYZhl
zO^LUE(`?<56KLJ3QTLL+2a>oG{Bn1Wn?{*U;J_v3*EA|_fGT5tbs!g)fMJ~omD|J`
zq}WZ9b$@-y>oz?>DRuyRK!m>&>b*(1F^$YYWT_~5&(mQEwbhAhxvP#q0$c8?v05%}
z)kqLpcjZV8OA9G`1u3Ug@q?UB(a1eooE&a*chMMd;xD1OIsq&!Q67|Betpo1V7c$d
zGr7HPs;M2>eO{z!%@1EoT%}g&Do@^lcXr{fdO@_~CUMjhW}CusLzry>jz#2{cl4TH
znlC5XqysABgl2UhWj28$?~mG-YuL1q;dCGh#s$slfVlXY;%k8os?WXNV1?@Qro_qM
zix%olN?u^0?xCFcqB_0XBNmSObcaUc%u$%6<d+8O4%Nul(BPpx`RW=vw}hvPv$qz|
zF}}J+FPNu<G{7+~z*eu>;=q+Jv2jKfGmr#MwKFLB3rp6Tcr~!5^wk}~7%m`IM}>$@
z!6AbZ5}T6!w)i*sM7f_$BC`#9&@^%iNEcMAL+AHZHE_)A@>Ml(!^^K2xZ~AV4c@T{
ztH$nl^OaFG9W^_A6%9V{*%Wm&z%rEK9(S=<8wp#kpd>f9_?zJ827eRWQ1k78y7;=;
zZR8*DMJsg&)Wv;?xfEIMODmIN%~iF$XWf-6NH|+?)!h^ho*$n3;^6sZZURS-kJnw*
zpE}~RT(!+RipjVTVVja1O56hSvMD?tET+6EU=VhLO#y?jD{M+Kh%`M;{MHqu*nB?Y
z2m9BwTX&TEai`t7qa={~(5PF!dFBMZK*$B>y?IlT`4O#@3GQ9P)SOAzD2N_%6*ccb
z&A97}Mg*k0bY_5JTqvxb8F()DCSDA@&?ensqk2)$3SOi{!^GvzfQk+?n7e71hGjJ|
z*RZOlfwNZ*ifqmvHOxDZG%mze2a?8}>NtQj?$XB-N8?_JZtH-~xJsXQKxbSqt`75}
zyOis!0TvW>G^0t@Ap`}|+LYwCsM`sCZ_NNnE8VGnTgpI}_6<v{yTmoDweHft4Pwxh
zQ1d^1{D*6A+WYnB>u0m}*RwC7bx&{hx(ofsfB*5{KFY`a`fvX4fBD-5XqW>K_O}l#
zh|koE6He!ZQ(>36N^pDXtCvseU-*7qIG%Om86G{zb?M5{1R3B5#<8;izuLSwLI^vH
z1E)6dYV%YtP<31>Ys!s4W0zCDWc7sCBp51QZk*8a^Ogv~2tuxN!L8zQ)fz3hCb`mb
zl&o9g%8F4?W5pZp`USvak311qP_S22ld+Wj0L;XNib7Mh@S4)c<*O*Qz2?Vg`BL+o
zaN`xGPzo3;!1G8|9CzW#XG)e>fXs7MODjAIDiyhcZ%nbTh5J0k*RE?19F{ZavjF?#
zio+~$8+oN%EpUlBY&wM)8ZQfkeUJ07V-#cs@xm)n0er({3n+k9ct&)+*aDit3qR3<
zm+!il7P#bHH_DQpaK8npFW70W8Xg6%VOM-e$)pReAdUhbso#WTm&{FYeN06o6jl&f
zybG4OTfCnY*3nozstf!^b14v|%<*c%a!`PeoXVbBPzPZ$1!}>GH6_xD<Ek^A*RO(1
zoKvTFL1gLlqTgg$7N=*d0QG%MWymfIwM%BYjtX?KDd=NasMDxS%mqokqwsyq5MdPW
zrQ@?IeD29d)pe%He$-3{JOs7K--?%?!r{objU2*rsIU;~^QhGI^{6+EhhRc_mW9r(
zf)dF=$?7;gio6s=lFhDiEiha@EB2zuOVcc?MIBnCHLoaV*-oX5nwP(4k=Cq(3P#}*
znN6h{jP(gs?7)!SdYVcVWYNhfKV3!j%U!Y(6Gn24DKAt_XXrf140a*Ic+-!ng{b%<
zuSyi_yR-Tpe}hV4H46JQ_*SND?-fvsM^U*RC8Zt}-%zu#Xp%rJ&2kE$bW|&P6d*&D
zJRLC=Im)JNh84gQ)TWA#5*#;+a@dc28}nBE2w)$cm61?B3{iGbZz&btskpQ#>C>{T
z4i*`(+)e4x&KflQJ&;UesbIuRi7}Q6C!xX#_5%X=pLIx1xsT3b9;p*NOLJsB8AV&X
z)uG67a32|n7r1_}x<bx$2wz_jN;`DMJQMXJ+M?q2zti6{gLi&J<77L9l_m1ZgQD#2
zF>@qYzcR}@x;bgf`OrxXj<D!w_H8DME=<0s`_&_-G++5M>9dkIBcx9%KJp+(Uy(%R
znMxQD$j@ZI811CYJ*jRxGrOF8vrGt^Y*$9wo;5P&5ufo3LsHO*bd$y;jVE&_gPKoD
zOok)^achPoRjhXQBNH_)<Zfgdyvk&f3Vm+OC3?~cc4kdGSwI@|i3kK}jS<6LS#Ubz
zcOS{*7#-Vno3JcQ{}D;hn1-$^=U6h)nKyw7pml~awxOh>g9&>c`K%aFk3!aw@F|vo
z2$smL)R8AC*L)ykn=lX?jD0q3qsc@dhPe63Fkj?ajch@T#We+uPe!z=qODCPD3m^E
z^O3wH(k(EJd>qi`%n4AH2<WwQGaW`Qv@;J))qZt^(7mOIU?T66w_zc~`jPUWGF<&+
z5>SrGa0;CmdL_(XOtB~@$Rl1{hyb{#u87QLd}$^(kOBP>zWj_QMj)$jQ{j=gGUOH%
zH~|=_N+bIc=<X4-32!{o%dd6Z(x_><WJo)ahkS($`(q8H28*MD?XI^Vw-Z{%Kr%);
z0rRH|{xgD#09-{boiL<~Cz_1=$uN)n6Ch9%*q%q!%Of5oBQs7Y$%*G6pu7M8FVF9Z
zQ^<^D4GBe8<iLI6@QV=hGokM!AddK8(mR6|htMp5xUMd5abR>;m;1KEQ`Ut>#NSp|
z<*$I%CPEfS!ve_ifwJNmLC%5fUrJwi1pqT)kX$K5Q>><GB4A{L0)c!gMBWYI?9wUP
zG}eTd(G(bhyyH)_7yM@gUBPa$Oet-fTLOWE>Jk1%*qKCx$cK(%SF6fZoq?y<8{VS`
z`#>+h31PtBGy(zWRZs2pT17tf@S_SNo)P9tXG%wn!lfdt9km$Y2~L+G!pBrRwBG}s
z$n@DcJZ17T-0-&FGWBm)*>>=RAr948m+C$qpV2K}%z)upwp}?*q}m=2hrETgz%))#
zFH64ccSz6#D|a|E0TpuTea9l~zcJJD{`|0pe#mBdh56ARc0qzs!a5h$F7C=ScD4Tc
zP5XHL<8|nl@%qP0>0P7z%+|I4|IOBwOG#@Njkw3$^&wN&wsheueVDq+XH!=$;KS6F
zo91Eaf@v%AW^Gd!tYyd4g&!PS7fd#?b>S?4sq4k<qI>0O>cah5rY_oo{>akhj1ahv
zp^FoI7`k9_k)bOFd04q<(?YFh7dV?{E?n9lb}sx~cCNg>l<oE*(Dr&WbAbn$xnwYr
zor`wzW9MogGI3pD<BBn8;WBC;vT(_0Aqy8T6vx7)yY{hhHJGbt;j)jXb&FaD>|0^)
zf+4M?qelA8)5-+{kgQyJvK|{(%uNO^8cJy2Dil)3zI7~Kuy0XH9rIS6>(|r1bu3=6
zZ|T*^zQx-T>|0^+g2(&Vw|HGj`xe!VW8c!weAu^W0~_09#`9eUE+s!W1}@%0j)jZ1
zl81$haEN2!YBGb-!lg;l!lgON!ljBS$HGPXnoL}Ji!yQ1*LqA`MrYPBa#81ikxTU)
zj*)Bq#>l0x>0{(lJ!KiWWE7H-O9cpN<YEBbt0P#sblW;sF4=`-<x(9<TDfEwI+iZg
zN0g<jeztV=TV^W@yB9i<rAu{{j-^X>jIeaE?6M49njsBcjpoaTp-aUBY3Pz=Plm3j
zqbDQRF?+$tWnxT5uKL-?WvEFk6IU9%Xx^Ims|;NIHwG@%kcNRP%D&RLRW&ghx2iB(
z$GGLcF>Y~}9^;l~C*zj=#<;~>xr|#yWn5+4Iwi_!+?qULj&Vz~lyOUC?Pc7GdCn{Z
zjh%l?TPo@()0XNUhiOX{O=;PZ^;ecH!R?P_OK%UBtw&8-TDH<aMXT1S&sf6k^C)^M
zvzFeU%vz^#C(K%plA1{QJ*Kj&%dAC9gRELg6$q=AifyTMpdo3eY+9$(AZ%KbZ;&>v
zDNU8d+$NLe9*dTrnuBT3+V>$6XwNFjV6D1d?Nq^$O-nJP$EI}(e8{GCN}!}oE3HlH
zY(A||vT4csM2pstiOuS<M#-vm<=9xFW7bmY&12V+agdg+p2n%9Us)p}-;S(WiawQ9
zOA((BtJblGP1-cN@&F&JRwU<?MeCTMXwZ5jh|kr$p6S?W&{8(#W6;WHWX+PfM#iiY
zt#qte2ogHhtdq$4n6tFnvS;mY{CZfkw5w#zI%$My&U)nIr8O&^lGoFkrBt-Xm?fj%
zL^@Zj#j$1GjE6i1ErP_;o>f#DNcOCvni@WjSqeEn9`>x0JMxxkikS>)&mxo-=B%_#
zh3fGzY2C^fN{g0q?L9173Q~YYD=bq)=+mO5#8Jc|FWvWH&|2#xHVlNVAZyn#XEEwR
z_AEs*$eyL}0ok(@S;v&5kIYcCXQ@=R>{*JumO)EFl(1)AGEF@UTCzdVpmp-!(4aL>
z&ZyL1uWh4x8njMc7Fx7UdK6l<l!`!hEv4U;U2B}oI<RZ;<T_@p{@JW$N|7VGR#ip`
zra^eOY<10%maWcD=UBE*sC}BT>^EjC#b~F^s=e8(a1p#77OO{;E-hAysFT4;D<^|h
zQI08Dtd2Pf!EV&hV6qBp6oVXTvFb8#%4DT5T$!w7cLOeFnW9c<#;Qxf(c6qw6-_NO
z)`^dz8A}N}WX4jWjbp~rddiHYXjPiA<g%0*OJSMEjHT2iGG!_H36?BbkYvdc>R6Vn
z`!|-XTOdAIvZl;mv}Fl6E?ZV(wh-dJ1?ZAJi<&C!S-uoXAbXbUH%{oS(73W^0g^6j
z7LPhvvjo_dHLD2XPivO)**&dUKr<d=)<OTJF{@LReWLJ)1WSV!v17-em48oz)@$uv
zKl*s>?6F~6uYdGbHkjkr3|g=ZF;|zv=pp2V!*UQsGd)dTxN4$Ks4I&XHo8wPdg9=M
zkmm-Vay}XC=&9vC3~Kq+df4`1&3pW{f<4L*uV7Dga$cX7tEMKd;I4|Az@d1g^7@VO
z4koZE2qxZzGusz(&TTYXe!G#B&gJ~Xm+Z>y<w#oT%IxL&d#pzXe_d#~WRKtdyFIZ3
z2Pnaj3Hn^=ypY1rC$&HaMp4<iP#V}LL6|VGx^i{BTP>5YKY~eDKD3fes4#Ped2<sA
zy9l<nGUkD-pNMC02S2>D|HdLpfUm1?B{0A)QJ5%Um+uB&o==!JGtp$U;WvP#*>yMh
zt=$zyMb@eWn)-o3yvf(rlVPp#!An)5v3DB-05?DIVJ)EM$0A;MMeF1DOuqTeyTtl}
zO;9Pb77S|xwWe3dbXUTxm4~IP)HvjTD_a&I@UB|p3vfPHvMeMx^^uzR0=E7bqFXfb
zJpx+hQJ``m?#xx65~eFxaZ1Dj_~4}?<&qO;^?`tb7h#`{u<W_&O$zUcr&GOgUB?#8
zqz4g-B#}O7Jwpy!AH2gXAnRq}g46V%NO9B;W$#F{fU5{4;yS_@-(j84g{L_JS$H4j
z`boz4!9o1`pc7?zZZ7ILE6-Dxrx9ZAMTo_6yf``le&Z2Xuy(V=WS9tjP}Z!KRuLck
zOc!wU15d}1p<0p!wpwQ?$xR53h1%Mb<e4|m-|<QSj++M28{%aM`FIy@D*^bRhq!Lf
zo09M7R<HSr_#qd-o?et>3_?b!w#p5c#nSYEZzXoGAcAWXkYK*t5KX8fSzuG$ZF);A
zS}@%L^SS*k90i4mT%O=f+PtIA<nQ@tAfP%0YJuI$yMhomDL$UgkAG8kw^Ks{cHbu_
z2#rcMhi!j|=5Y?i+YwfAQ{q*q2IZ!tGe{1k%p~H<zExnib7tS#h7inXXhuNZEBRKr
zkx9g5|0tnZK2g~ad`!Mo5Eto6zEuFt^{%A01;Lb07uRomUXXrWMtI;l9CZw@B*lB9
z{jA*ZrXu}TLC~o8rhY?Cc7nNYBxG_`t}HNw%G*|;S9>>2DJ3Jaag}n1CoU}++c%f5
zj8RJkvAK>cS|utoxb9~K#T%a9yqj!gGo_viP!^aVo<Mhmly$-=HzhZl#B;$l!qG_$
ze<8<!c<ed{3gqL%r^uKyRiZ2~kGOJbZOUd=DYZ5sm{pa@0%PRmN~yI;!EKXU2w~yQ
zBwM94c{3pek<W0S3ozYm(!{T0Z>Wr90Y1P5!zd_m;%ep1rRjTxZQWTzvV>#r=|qJ*
ze51tvZzwBU%7_MEHR8+~(HI5jC~x|n3&f$oAtgbs>8k}JDG-|g_AuUVO8x)>u?-Ck
ziP%(MHhjP_zvBW96u$~f7TjN5btN|?C)nkTPO+(cTm_jGTy-T&f#8%Kvmix-3;Vn&
zVNP<og-U_=JU;2NFb9PZl!YlYjUGa_wX^FN=Free{!Kd{a<=i#zg^$)#Vd=~rtDk>
zt}I>!Hpi!X9GAK`N^aqBGS~g<`v14~HNCd%Hg@y+6?bS4oRlO=6sG~w0g^$`i8Bf^
zNzff2=pLklM*e=b$hB70vEMs>eH|OHuXuKqK1vcvX>n0Eh)DT#M64E$o$30tL+_ey
z8NuhVO$-JNr|;XUrO>lRGrm<Ct1aA6>(H~h$M5hgl!LM%XVw;}S3_d0Z3@rmBd`DQ
z`8s?+6OG>yRqGKm(g#2Yx2h?{EB>wqoVZ{GpXmh>mq*k(bgwwQ8rWbqDZP#$zm6!q
zjwH`<j!02D)g__n+Zm@J+W~wxo9N9%I3yTh%ib!IoHynHs#a%S4eUFcNiG|1LpM`g
zUMZT1lfWj5#Bp0hU#&y2D!=7HR}?hDH93gsV8Y8*R7G2{01a$LTclkLIq^0~yBdz^
z_mF$ukX&z*wX0?Ry;CHt1ODbvEDW$>M^ZIkN0jq)OjQld`k+C2X;$%n9YMuBX?N+t
z56Q@>`iQT{sVrfX#*OZ16Tzj@uH2UwL^B1bV?ZP81hN5tLYNBTzz2`8+Q7N&9yA+@
zcxx*)W&=6b9@;}d;I)+-^GF!=#qDcAX%EGljh^@z)(pkXyqFD{F1PYxwn4ouR1F;4
zAseKgeutKIbg`@2QtYEKP;Nl64*@O)ZW%`-dME$Q7eH;lusp_w-Gcipz<t=T(&Iy0
z#DE@GT*^TN<qWR#zYC)LfJ#f*aIf{o4Xuom!-O5sx=1Z~%B6FaS+Z5M-tJt-pwxQ<
zk5YYpDOWRS4PZSV0VX)s{E^_Ta7(*DQ?+qy=9|1yk|W=>t`YvTm2tAwu5|>Q_kfXg
z-i}-iWQDtPVPo?Hate~_<U(m?<RI4?UD!Ug;Gkgp1Mz}_?ON4#D+Cb}zY-E(M}ifH
z8`-TG#hh7P%iN%DyOz2^-JZ?AKwtF$Ll~iOJI@FjNGwxw^EWdCAu%f|zw=eGktu+B
z6%E*t^m?ZA7uD{em%@$h<3h2TDaHS>4|dmTh5fL*q7!lJvW3cTMkls+jTf|Q=S%YI
z%L+jD>?5gd0{OLpdAlI$^9u?NvE*H+39!X>m#F~O)guAP+!0j|we)Q!lnz@KK+Z?v
zj3ymG+dcR@bnpo{t?p@OFaQA`gdSAyO9C(V!PYc`Hf}N=U?Lw0T9eAS$#j5~y%p_n
z9Z^p5rv1g><~ErR$QZv{XcT}{Y&0m0A?GhtVQK6pzXk5dk?>1HV>gznLrP?OMAaku
zEw(E-S3QEhZaQcHK4B|6=G8!7yp<iZf!=sG`6}g{y&#bA-*(f^R6gES(ZInU<&<gK
zn+$hEjeFC<QdTFqHO>0)*Fjf4c*~h+OTs6iwwpGi3AHUcw1(KAloSdRXUqapwZigm
zCB<xTv$t|$Hn`%uDKG8;d*&Q&+FmBklbg1e3B3zIDCk*4fOaIc-H-*X&4Jd*jF_c{
zo2-Zl*EyNe8ZLr&6U%o3Pjgtb#Y}k1NM_lJ(R_>Xtby}<D@WyZ(5m%8hz@Evn>iAO
zdBb6D(Ek(I=BC|Zf~szd_N*b^Vk^^So9hcG7Cy5uYYm51yWK>5H=Jy3#c?*Ae(lB+
z$~qt0O|%05LVhG!0?EO?bwUYjO~P?eGgSVqgNvCeU)e2Bxp1{gn%!pU?>kV)hQ31B
zp}KGG3Y7$4--6*zy2iJ*i3!bpYoEZG=f1U1;7s%d9?nzKQwD<W2nrWW>jUSvTVS$=
z5Sp#blx;P^kF$hxlUt_<3#2QVlk${KrCOy3*4|1;c_g_I?x`_baB6SfG&H1>*aFS8
z$~duanG6U3`bbc!jpvrlfW#JGxdEzoI#F07ON{x4GQJhY)o?$sZ{8p`+#qa$caDUV
z1NBW;>0<_-T`4IbH!O<<r28$);)UYII6)o1aNWi}4iu|5GA&lo9I&@gykCe9sx!}d
z0xoy9@>w?A|7^V^yCTzKk*9&C#adiS58NDTS7?HUEH7JOb`959`({W^Tb?BzDBv3G
zD@#K)Uk8#4I`-B^uyAl(mnBz8vIn}W0GP!Um(y^A=b>XvT=F>~tXGN({;u61bL)6$
zH^5b*2M;lE+2|oRWZ@>(L%ztWKYDBpaX#;{)$yw0h1Flxh|5K<)+z~+hxQ2MDRO~s
zTO~6}2~qxllg49DAO(^K?TJI}kVVD`+~}t43E<#e`7y5}N)WLUWHtvF{}p0TFm~~_
z9YOVzC!dbMb{BP9!wt17__E;++e5pQSBVvOL^{l;k3GA@dyH4C18YH`z$^NpqeC<l
zK79mwJY*@<^}UDgC_u>LAZ2U740veIal48{1dT2A?Mk1SVHeqyC+q?-3tuF;m%51D
zjwq)C!%vT(rUSMhum`!g+!|saJd{<t0af8jx>=Mauq2S5?HvLF$b0~s(0s9F{dq&R
ztO}lAg4dPc32^1tJd*knw+>SQ5Obx}Yyh*kGHN!UVLU|B16Bej#;Zix;VtX`6|nL=
zHs1j(z@j;6)vhDS7K&HxNV0*6LvQ;=?1~on&dtdMrEL3V3=EGOfDv*f(0n3iSgNK!
zaWoltkaXi$6|0>(d_W>ZC*RtMyvb(Bdfy#!H)1zEqKq>Tr5fUOQo<J_)a4bxGd?9*
z?i+E1zI7OgP-Pc|S_5C%k?^$x?Im^5wra1E*8WnU5Mpe;NUC+F7uQQjo&&No7wK99
zWXO}(p%oy=w+NGf2y(?+Hv|+ods?FUKu^RH;$o6i?Uc?-b+QK>o0C$l717<563ou+
zSz@J*R!VgvH>!((;uR%@V?5A+yyK>z{E!0kl&j&oZrsp(yK%}V0LhgEvjKwSTgn_5
zBp2~TLmaAa-7s!Yfcn<5tySd;QfE|`ZyNSktFI`p3ZM5a&eS8RPU_S!pywFxegxSk
z*V0cK$5W=;5BSm%F`f*1&gJ$4g5*NewWt#7MVPe<xZFTr=}!HcyQ#bMD;O}{rC$}c
z=9*rh(tJm<K^wW2bEQsp*C`>GV;o`q*Ae7uaa|k&pyWj7H9(Y(fV@$b;c{OB=&lq^
z2=W8HBI-&NiLUMlDr80Xfrz^C)LIuL*?3dqp^6-;G$z_ERT>j*H>v2DXuZt$SQXlb
zdSAhQ7__n?T<E@5mc~^PHs}%JsD$ThWwN}PvK%vRpj03Ixf0Ce;_fouk$&7o*_UC5
zc!)3EUxE-Bk47Y5gYoA={x#T#F63W>5$P`1zBqinEURi86eH1p4ZLXXTJnm3<ZGex
z9HDeK(ml9RYWA|pop8VoJKmRq{3?CDFWTW9DeisY=($2IZ#*@B{Br0e;t9V<a%^F1
zXD}wT;i`&D6)r^=0-p4hwX9mZ*?b1BE-wBj=(9@W3I9B$nre#<dIx*dk&wRW9%!gy
z)<ClDj6OJmz*FGVy31Dd#0j3#xxIGb1UqowE}-BqMWU9zd`o7QD&1v=-|b65op8-P
znLGMjN^;HTaeO)Y^!<jT_)8>jQ*T97=PM!>@sZ0kDHaEwn?pzF+>z8EdH$Od&(V0r
zFCyIWNEnBCLwPcYBPF>~l$x^_2I&Y`?-Q<@J8B0h{X2eli^z_ZL!XLLsV7j$m#E8%
zA^$4T&7ag~@91HmPhAy3RW1ccBC_096O~#8FDaNf1!C2!<~4YUi#G$EL5IK@UL~qN
zh{-L1POkWt4xrOVf>KRm#Su4ve~+lbKyfB`1guzr&X_~MLcK$u5eU1Uh+2T5d}?0-
z7V1bC>0E>4L>s20;i*|s)=<<!8}>Xwb>R(9xx%Gs`5#GsCBY4QLvE&bZ1x~YA$tYA
zEW}|4Xv!4})PZ@rTzJ6_^1EN+HuTqHIqt7GaGYX0A%wj_`3geVD_qotAUuL<;Zjx5
zoKwem9q1;XWeN1cE%~J0@4zj&l5BQdE;zGn_J(j#SI}h#aLIx5>j_(Oq5L{hu=v#K
zMwS+z&+2Zw;@nX!{KZ$~JM<)AejUNEF232`kR8{B_3Mc~@=5Ra9X|g&RKu@;dH|4o
zf)*0a;nafcr6s4<W53ZfMUms?%yCt5mB{NU%phFA`P72M1)bv^P?CZG9?8)guSowU
z-b;k;LuXDcP{5IVYJ~!lbh&7Fdts8^^qEkuQ`CXD9zDbYs0y0Ybh1w30oDU``l2Ej
zpb>bHa-Q#Fp;`vERom(#)GMKc9oNA}z&=8~T7d;l`E;l5-7ZM7Kc>|RNRr!D-B7Rs
z9CqApf1ys8S;X|h^|&(wXi9P_Fx_VdNXeD%v-iRSyNNsiASE|(gyO>AmGQF|Ccu^O
zvjaD9xl(?1fD7Kd4)9q8A?(P6=E4Vdq)WS80Kr~3B^N%h1E=(b8@1-@!x{lCYIG1f
zpc*dLzMg1~Q|1%(WwkBzdY+XAtY_1<fS6KehR+Uay(8c^fl382V6Vt$kXc-iRA(N3
zi`0w;$G!t^bOd-QFfvC{zo=wNu4J7Za3WW(&JH-yn>3?|L3ZdjdE)5?JH7+pa|D<#
z00FttlJCF?xq`}jB8l9T8n6Q|<VI5-DG%Lly|<Lyi@*b(CDLr3a-DA|&t@N%CA<>a
zZAg_O=c5aM*O3=8SwSuc0uOOi;3f)gcO=yi8RBDQ=^+-Wi6N|Aa*f>e5;P9yoFY5w
z11=%xNJ{mMMR)H=a#{?nIfTU?32TPWIJD-_1RqLE(t!#5h)~K+M3MY`6!|YJfu<Ac
z?nvr1?h8Y3^=7hr(0*g8d*vezktPE?bR-yhxQHSU==k=o9GV@|!v{U-BdL)UpH~O7
zx(}&dWQuiW+U&)`=}NTO0ZsMfD(K8b>rAtmqH1ne&7@bB`c6EM4=Hbh{;Nep3YqE>
zZofJpLf}${q!+m|G!-yHPTqtoMfKIBYe6u7BzQ5nV}^7sHk5~~CV4|#=(&zv$_1Z0
zl3E{cTIcLQ*Sa*2a(b6>T+pB+z&Zmo=tw5Yxu}G=>i`BF3GNQMk?Tg*F`z)+rGB9&
zoT)u~;e4E#JFk>fi=|u<OYdFEwUSV~vUhf9Eob)5PQF)H`pypR_t5*mhwL(^&9lU6
z;WJhym<ys}2$E_A8s|+Blv=6J*DtEt$vCHu(1s(bmeilw3V3=-w|OMh5^2z~i>@Rh
z;&+9n>hhb*xbiNq89*EdPg;jP1~#J$qM|T*h_>PRb)KO2MCN$s@p%U_=OaNW%^UAL
zQR{%^I8$<Vz;e73_|glO<6Q*Xuyv1wJK=2T;ZV&`U0rK9!*E<!x(?&r38lMIR2)uK
zap|oWWfPpUFOr)5QnVAqG;d;aT;%mzy#{|;m&KhPjg!zM%L~sKsn5wsb-!L*gC}zu
zK~f-<f+VS+f^-c>lD#1Atply&%F5X%^dgcxbU<}nu(v)B-<vRR9mpJSTF!77U0FIi
ze9C0EGXCZSPrdoBpc;jX>xg%A0ppG&d!$WZLJc;i^5`INbs^vS+*#sFp$ePUH~ejH
zTH_PUPH*ll=t6<qdO>zv2`@V04ZSUl9IhIhQ1u;$22O-q$EkvgnWpE#gA4H1aaiGv
zw`NygcNQ^SkW=N&3I=W3sL1PV#hdnkI)AxRgw`+kh0XM0D9a{Q4v>#G<BL;QHY4X^
z2hhixj?Vz}0Yw=kIdz-NY2bXkJ?g)JKHjAL0rc@k?Z3LX&oFd=`Z$hX&Z@>?TIK^l
z?NG5zCIAlUj)Zlk$M~X98#tt5{?88Njtd9Z7ZVmpnXk$*z<Qze+G9WC1k{_BK8{J>
zsR<?qls5L77|)wAksVBreoLD#=tkk%`YPQhSX;+2u;0AF?l>xb)53X{_zIk#-dpd0
zF1%%DFR(@UtrK%#as1|qc|mdf-uiBE{O<ZaoW5IW#5!>}x2t9-*jx5G4(&-{SCSPX
zN#l#Ei)o&(^GBVCfj_{>+0@C6dFw!IQNP|g5(5E_3mn&hz`2P$>BQT-nDk1WUSCDk
zA)rxu;caeWQ9AK9LdSLDZSE;uNW6{kah-UZTSkI|%kh?*?O;T#?6g-&s#o%=y;ZMd
z05}NeUTlEyDsd5UmLE9m{ML5h(9Oyk+6#qqYcn7W2OzobNTlt`8rq4%Vb;)249=~+
z02myl5$zz^I1-+-;NFh(g}CArkgmH`32!v?rE3TbXMwj2i@cU}!RR_JE?uvvFQ#KY
z@BsSFtN9Ls62Ik26otu~S`k|Oraun~6h~lxjy%*jngu0(%M3XH9%1S_=$Bjwy6(L0
zR9eyw#7?Fl?YMD%vpbd(yo8MFm8on+$c_Ow?DIr29SZZ-eP`+6i%d2}0p7Zka#8rU
zBU<+tQpw_ZU7`KOOEIsI^A8lzwL-~yaGSqE2X8<Dt$=5c7@#F|TL%W{NN_y{BFLp|
zQ6#uTwHx%1AtM6#g%=6t%^u3GKrXr!uq!H8-4a)L2W8q4*sTL4v|`C;1ypD$N$HVP
z|KyY;_+!OX%?&+-N3xMaX9*D3kqPEa+SxG=<fs(FXbB+KfiSvOXb%FsWs#t+7XoG}
zvuOuNW`(w(J<v<jvD+T#rFJE8i0a61Cj+Obs7|?hIf(M?03EGRVx~RN&nNAUp`YA@
z3YfG)en?@B&TtJBlg2Z2907RJkzmRLrnH2m>w9L279@C$R%pusOzF*tI<td1Bn03p
zC2*$!%gUTV`ICjtG=11ry=fZAa;BFOSM&{UdWB96k(YBRKWg9pg`3sUeBBfPzl2mp
z7etng(+S3Q%ntcB1!-D4)X6d;7Sd>3$pf3yL%6<PxVj^lC{Fx<_0--2>evlJt|iP~
z-;pJLtvVQ9#OrlbwS?E}7>Ko9HZt%-E3=t)jNMX3(+<?*5~tab<QNHlcO<n<2!D4(
zRX2SLW^d9#J!Zs8p8t;d0vg;4qFg;&djw!gYtt-An9|xZO8`?^Vtc$ga7ssnxdfQf
zkzk+!Q(9YlLM@|1!ON;ao5XxnDXH)E(DV*`ueYT7s9gdJ|5{sjh1eaAgzYi(^GS7O
z*-`BhVdyC7y^f^%Dbodr-?d@7h(%bJ0EK5-n<#**1JLwl8lLD>*IRN;ZQb$5$`U>^
zu(eBIzBgAfe^TvwxQn5zzeuW<TNs;cmVA?dHWn(cLkTaU@;VgtaycRiDtc2SchHs|
z31@dH<0TMY2k>YKhSvkvu1hey4m;yWIKS(a%lSxl$hmmO$8uR^99+fKoUMN{a3Lf6
zi@h0|*J(<Of+j7eC2<V^j~4PL4#1918I-YLMOuR74G<%}S)qH{5X+Yu)6p2EQi3VE
zoD2F$vNhr=29@LW&Z`C`=~%%epcW4;Ebk?x-hgcmlIkL*t}}oonB4$)=twYFm8^|j
zd}yr~8aw$3kxlDPHT5dhD2aUchE8(Y@JDi1kIRG~017Sds%D{G9q;{fI&H5KMjqbb
zmmgqeh;|sLpyf@&3XLTE+$dDg_0CQQmE;Xg+31j{lglSQ0#*&~a&O#}-|XKU252cI
z9vE=aUku@Q{hiY**vVV-E6~YX69L-HZ_O{Lvn1vl1sYmK%y&VO9bDu>254w4E@d*6
zucfqMzzi+8*H?+=7cz7Dx{gvgFVv8u!7Hz>w$hi^<EV=bT@h%5NFVywgFqj#GmgUb
zxK5S_fjvIdFhXz#N(FZ8s)gv=&RRy@;R?<<i1HDflRWM2O2Ag3pe`!MBgl3A=5i;2
zrsfW!P`A*TM>3OW5!0lRL{oeGz?t9%U~>Q$w1w9kzy*oF5iIf#f8!`v(3KR7n4&nI
zd{fPrR*Six*PKyHqGP;gWo|C+IRFyHRMyBmS&b=TZ=Agz3HDkX&&I?R?KN6yx<j7K
zwt><7#d$9_aIwdO);dKQV^y;A*EbzFFh(gtx9}eJskCOMvcsX|z<GAcIB`k|RmMBC
zfJFQ{9vlt)^-V<81E=n!>rWAR%mo}6IIaJPluNJ$`fN&!dSr_~n-Em@L=!anT}4!e
z`-c+Msn6(Qx_|Ork|X|=K>*z9lLvMKV5Jn{#BKntbYv)2M}%Y>fH0+~7Tvj{sWKS$
z1~5!1WAzPO>rWa=<usVmuw6MPWhIYJcKcWAgN`0AUTF`IJCx|=ud>H$@Id6`OsM{>
zfnxPVe3B#4ODRC-2HL&2fn1}LT>q7Mfvofk?!YL(QVK9P0a!XB6w{r{)C;WLFeBDf
z#|(2qDBpn_$P}@DP^+a34VdiQ)bLhngT=qsM_R7gHQ8BzhJQYt#asrGDMg%cOTESB
z0W4Exnz$gTHNKW+_hNsQtg|on_Zc{^UT~-Cj#;v%>Srp0C)0&<LOktuc5i77g1r1o
z%lFg02?0CD;oeW@I(oOC-m%^L`I>CPe!eD~9;)gr=3qyj5ed%r=gons{dx-)bKPKM
zlK?=dsRKb{gYX63`9C^;gjeIjV<3UpmmDGY(+@1?ftt{2Kru3tNSzQ2z%^2YHCm94
zl<>`s9g*!jm`dXTj*r1C6t6@jmAYZkLPjovlwbjj&KY32k_+3CTLjh?sH3=RK%}jO
zeI43b(iSQa+MQbqGRuBRnqt~~s3?#eA$J$BT#QUoTU*l2AE6(zx&gsTQT26l&USLd
zjDdX0OUCy*Z3`ykU<#5Y^*orrV<|Re3?^}1O(V6c$kAV1lue_w*gFwq9vRk~)a+n}
zVj<4QfX%REEf3lZ>ruvoMgu8w$4K3wB-4Y|z@+y(291FkGBgIQ0i}f)gVw+dy&C#6
zG@7&p=GN9Um}R7L-W0Abe}Nr-&<>bNm^=dAz@_(9vib(Xs~=H)0s+>C-BrZwHW~+$
z#Zeiqm4S7b@;n2hGwfw5U{Ts*Dm;>1`G_Bb!X8sW?UA`4-@;@rIEt_p=+xNDRzQnh
zrUL8lUyKQ(NdU{?Dw)xm!0NKj4>a|n!A4_Cw9@y0%U>lygOozqXar1N=?|j~FnOgv
zj5fd&l4lsKfT{frD6SMWJ?QumTW)OmAna)vwLWQck7QPv<4=`7wdojD`W)IjjVgW0
z)i<j2scpxg(uKSqMwLF1UvU^!x~O)CQKio(Q8`t*=y!)5l|B_AGmQFs%AGgn@Oh<p
za`sPqj8UggC9*h~pwKF9C`MI0<!Bj-9P;4exlzR8F{K+bDq`{M4&c2?bn{pFHHDfV
z1?Q@Fp$uO@+rm^jbmlRiRJy{%4^RnT@0?b62E&TDgO7+OW&=Z&B34G#Y@(?dle$^B
z_amx~$laUN&4j{#hLX;Y4&2979(PBvb^z0X!Yobw%ELuf4RYNvapshgp{HuvnoJ{b
zH>C*Q5vw6HdSUraH~=Zb=u)Q}Z{NnGE*2nu%u>asRbPw!D%tZ~%|Kw_$AsP$>U~V=
zT^sr=lh(iK5N}fP3i&=J_3kSj+2WAvoMbLduz@nV($y6zS<@-Ugpz&yRyg)od8v93
zGqa;87Zqz@!XM?g+>eV&ziU$KnilS)(zT`rDHk4pQS%SezC=M+7ax)e*L3<ep>!X2
zc*^;HPGTmtF1T~YlsB#|V#*(<fwAr?HF&y<Dp!#Ev6#JY$PQW5x`VjCv8Z+vnSYfe
zyE|lrEIQ~S%pHqLcQC$YEGpfxr7IS-u5kQgmF5+Ue<1cSMH7O}hj76=7Rs!i{`uId
zp1N3A|FNiwhk|UzqJOS*c<|1J_aBSunt=bYsIAAdyDYl!Lw?<&8!r;xu}ZCrgLf=y
z^|1(g8;d%eth-}Tg^PH1ENJjo);{|2V`}?^N0Tyap9@-DOuJ)Is}u4+7IpfVvXJ3I
z9T|$~oT&k&_r<_F7L`210Irmwb5CwTD)~VdX+g&iQ+KK3$B=Sf)bffc7>in7K?P$`
z%MUqI%d1F(ebI4eOu>;1KExJy^-i|QqSj|lM5=rR8jM9RUXcbTb0Rw1)g1WoqdzU8
zBR_N+yl5(njv~6%R2vd9vL>ANr;Jt6jeqhsE?N&ts5Ta@hoJ+^JloHA>Hfj##t+`|
zk2)Mq$wV35(B9=Y70lq~<#gH=hcLWVu{Kkut<Yt=IBkU<+7ujyLDwGSGz=7EFr1bF
zqYQ@AF6bin9!}!`q`<?=G!P~5aGD0M<d*c}D;A+%G)~!7`@l@=L>vvLXOGZ>;j{r5
zdvK+!x~4NRr(fS)y`^v8wFNnS`~Dm)ISq<V&&JE1=(2m9u6>tp<1{C_qK^h(Ybk@S
zbUOT9mXE{kP!z;)+8u~bEK#lHE}zJ0c61%@;65`&SQbvRBh!ao5TS!gubU(%DZp9*
z4@!!#UT`s+B5uXbV}Y*S%4xB5?p6+iMP$Omc`9(C9<D5-cRDL}-Xgq`oYIErva@_w
zF_-Uo5sjEW)E?R}<RKnT6GlYDM}+QnZJ*A>v|YZH(~c2C@o*Y4UHg^8km=8U<+Nm;
z9IZ}6rpsn?nlfF7I-4d)f37;WGRbPM*)T%-{dy2nLA%eU5z@sDIySA4E}v`D2vHct
z5lueX^fI*d=8JH}Bfo2-h>_YfLc||DHm!>m(xV#&#*?O&mV*K%#-`=abQ-hEa;SV7
z7bNvf8$s4%^FW}{5!<vJn#>@uU8RVp9l*(aNta90p~({3Fdak{JT^^-_T1HM8V}7;
z%x9Kf%+r9T&1KV2z-3?N^QEECw7F~=3a<>luoM(2F*Z$rOxbdk1fNbO&t_I=21krt
z>RrJRM}TIUjPp$uuYAErgl6j8WK+c_+3(m;?;!iVN`#w6o|$Z(4T$b{Y$|*a{*Fzh
z-=6E~ji0b`o);u3@G0VB%jMcs_)mi4jllXp`B{Bz?G8KGRUN$`t$K<k1byN~(3C+V
zK#>$9c&yNL@)A5(5b^LJ%isHsHgFls`gySMO3h4TL3gpybYDsx7&Hu;c8{Q8@LaS8
zEdvE&j8K;8o9ZUYG-$dA51Iyw#25g3zVk(oD)DYIXc^qHae_w%H_=WbXe``vy@KY#
z9oj(y=7Ok(N6=g#*YF5h3t}4{L2KdOa*>19!Y$J$%3Kg7@d(-hchyB3fb_#x%5o7X
zc4GvMfLq78pxjImU(FQSVmli_Bj7=b1dV`#iU0xqPP|Q%0N{|TWJu1<x@Z$9iem(A
z0>yERpf11XGe}hCw=S@P%KVk;dsmT-rY^rHia6O5Yw?lI5}+H<ytko*cMg4KD&6}z
zpbctW1zXrnt$Qo)_f4g%SP8qKbe~uWyQy_=ZUJ^v>)yz2UGWIaUJl9NQ#cH@n=1G2
zY64a6-P8nX-MgvnC}K~xn`-xNsGpwy-P8bj{<o4w-&D<aqYrO4RI_M^?WXVlO1w_z
zU(CaHQ-j}6>hPN?{DzxjcWH2O58F)zp0N~$&l5od!*2Mxq40_)?R%*5Qr$tKVMDae
zJ2QM~=_?dMVF(0@*ch~<EJIwtr<|CYP>yw^kdE+YHXt>-f+Y-Ky+E*p6;$t?lD_=-
z5MS_Rfa)F5xcQ?52?ZCpAwKIP`B8c8tMN-C1*V{21cf07c8DzaNM@D|-`3F~Wk0`>
zY&_O8O_8ZPmPTe*m!<}0qf1j$bff)snR6L{d7*#_yX()KjDfE@RZDI8A@*Rq5kC`Q
zst0M;87*-H8&9#*fiCf)#~3jfK^w*@sxU%X*P-t|5|ru#ahox~lOl+MHei?{Xueph
zCs=Dk50yr~A!~bR3u=u$?5e1thcrU0VlN}K{{Z9{;2}0Z{Gv4V1yRf9(f~17C!uJG
zBdJbm?`a)fdiI)+O@(5W&?js>Wt3$ZUm2ELkkZ)7y1P<>U7$?BQ1FBSz!!1jwT8CR
z2(bk8MbH8<0Qy345eEETAPnLoD4iUNf;f_FEzH5IM24r>fmFXoz!%rFkFCw6)yg;$
zui4&8R~`xLD)k$RnXtm}ZAOe5F?@TglQ^*mhE*8Cuw!qH9Z-FHqjaY6=7o~Mb2$<m
zh#LHx*xHc*=L>No8_;|~Ze(lc9ZMZX;@2a>;BItJd(CmvvdrmUu3ab!<4CGALX=qx
zv~B9KK-=DuY8$Nz>vxtgvB?$?43{uq?n1#4R*<_;Y=i-E7YdEA-Y~FAesDy+p2AcB
z<3VhmX;|-BszC#0F2s3k9hn9qNsp~?aItx=a0Jy1MqpbXm|I;<9XYURGaJrHV)KN-
zaJ~||vG<k*_8i)CH@(l;rltXfLfuUbheq8^eYa}+t%|8)_syE2VfU@tC)UNS+9xK?
zt$|NHyzgh&p<_u_Y(Tk%;v@`^w(!un)kKUssrlI7R%d;oC<*J(s9p_$MpcxA;iU0M
zuw?5v@=6iESgKUlnnnJz@U6jwO7;3Xw5cn@fB}paF6|F2+L3Tl*WWqzP?oM0*>Ncz
z&J~&5G@-x>1A9#<u);uab0kA=six|H(*`u36ZUApoTa2*J?igh{D7Wwn)ye9#!VFS
zLy%v=04xjFas)3|xD@orD4%epHZ>3veMBf#JGB&X;Si!JHrz^tknT3dl|@zyWtFIQ
z1G+4PYPSNH1wrkWfUr*y|4tnl3XL#e!NQwf0Hx$jZJHRZrqO^?6=WMel4^*SBk)_{
zQiz$s@@u(1_x*fID31(cFkri4$=0sRy(3`Tpgfi=?Ez}uP!xlKe=An#Q<cFSODhd`
zlCc7%Tvuz$jLwVBSg^!#6B;5LHe8kl$%d`qTd{bDV0AZprHIXkGFeh|z;1=;gbmQG
zAUM_R&H^VHfLoDV!UlG(5SOq4wH4wLHr#fHn1hX3VM8cY1G`*Gs{LT83n7jTOm?w|
zgD?Z?FMt{~<hc!jM$M{(T?1&W5PPrzixo>r0}Q~c5F4<8Yb!+kYv9@nQU4xEwQk6;
zKpNs$a-Wf^I0WLh0#wD4#sj1y0GGTBV5$(2uYoBsmTXsp(h#+;CEzNSmYxA?dqlNX
z0k?`J;}u}5STJ6Jw2CF;wSZQ!1YkN6!!xWIibhPohHTcc<S--SbriJVf@r3I-yeEo
z-LKbFgKw0wu~W;nutisj(8co0gq1vkoK#b56KJcLff6H6a15TE69Ce{9eO1EUS$}E
z(2qwlE57CCFKXxoe>CJnkI7P?8hp=rBQ!<M_bh*GK3WpctROtn0L%(uAq~K+jEh0J
zx~Dumh6h-089_mSqXBF6MR4Y;@QyaYAsNCv8nAPr_=zLw^%MpG47ec#<dK}VUNI-D
zf_4%l(&oq#tAVdIrD*}Eg5-jzdL-owJXMHx*b1c>0#O=>fMXI5ZooT+SceU4!Xdb%
z0hJX~IyymFA>LslCMyJ=JfiBP9O*f$RFfL*jwz*$?#2`)l3`3jWW<Isi%HYFMm44^
z?+LGMrfO#pOHA!d6E55Asu@aFgvLiQv&?E4cJ(;gh^~sMt!XmuN^W(*yN&>xDbQU3
zh~-tHn%&r(YTBP7_NECfJ9VCi)e}>W^`xIR<ys>SEhbO>4alt!;L?EH3JX1z>h=l?
zHMusKu+V#;ZY|Jas8;b0+h-?3u&`m93*jscTVW7pc?2_yn1QQWd?c8Gi;C5>`79__
z)84b-$EkFNUaZ3gn0y#{(+oKJFzqYAV||rW-&}2}5<bpCo|7=`H9%v9$%+RUD@;~A
zpjbzOF(?Pomh=XoSOGYu0f-d>V;W#sAuQ&R3_Jr?979;eM}!|#2X&%{h^`<k)0Sm{
z{Vy-_3e)zqp#4R4Y=|5Q(_REDR*34@3W^nF1zeC+2kE^7i50?i8VsBOtkYoroHF<M
zw2(qv#|9%Ri~t1#3M&NiG~{v!VLWZY4+_v5AA#W^Yyk`E-?;Ovax;YrJ%Z|x(umoD
zg<v}PL!?&-7HYs>1$mM!(O0L4`!WOiDojTMFo%zXlL2Off+7v*s}Q#Iva+f}$Wnvh
z{Z&%)MSB*&SYfiK7OaRs(4?(EH??Uk*b@qyJd*0B4600I5_S`%VF;!Tz(Ec1wqY`r
z3Uu`mppcCpWJECnu8ye2(pwhrh2U2m315hlSz$R1XsdXjoCa>N7+Y_x;TPMoA<aw-
zc`}H%kIHL)mSSbAiJ>DsWV8vvHjgAnUlh%TJUKDw?OX;oHN@O(A2&7x;xquSf*4M7
zm=8mD3=TMU3~f??PsNaN1Mt+5;2S1*>Xe^ns&VrfE9m{f{p75Xq5TAB1z#mKxY|6t
zkWw+Uc>oI)LzWDnP)CAlQezL9C;&ahcuw^IdP<S;E%nv%WC3WW7&1}{?Gyr7nmfl$
zCkvI%>Ihgf^!1QQg0xtX;K@^}fmTYSBdU?+7U1b73rT6fG=+ea21L`5@Nx+#q!299
z0743pG~2$jgr<U>D+GtMI-R>xgu&mbp2gT~$YT~{Y&N7i3o$ku(xDwmsaj-A3t=Oz
za;k+Wn++hOAQIAmLOKFK!faO&^Bf?gBdK}5p?SNOHx5%j5|r{nJi3gLLMTO-BLvQ^
z=vvylkY&-ewCmhA`j$1mp?JHj5oFDauC=|Pdj*FyoF*R$UF&UGWYsvs?ONLaG#v^0
z3{5K>r0vQS5M5^%KrThs*#&S*(RFr#WA*4-{u}HiA;hC4z9|HEG{Boea7P2WDLR+`
zURj`3gG+%B&hbbFo?yk$z2bc~TsB0VGxJ6H;j|;*(juS2EQIpKK&4jgI*TmK)0H9)
zF0?Aqjt0O}h~n9B9}`LOY;|1|eP|`)PUna?)KI8jBwkOkDH}~6x}L%<RCH}CpzI2f
zJ{zvCJ`$A9OXcQldgsD79#QqLYoS8pc3BocIfa;`Eh?jMO6t|Por?}aCIiMPIw4L5
zh*Na=LIEGWi+sVNWf4{d@J-QSQ~=x*Vw<*rYVJHQ<#lCrc|u@(3*jjZx17<nJynv{
z5GK+B?0iRrDF-^b5Vy2}vM!p;4IrI@+|m{!3!Lo0IR%KN4Hv>8Vrj#rafn;maH*WX
zDRiI}!YP_|HC#@ABw2zB-?XU#+Z2uVN`RIx#64|s-dJygN^WwMz-)LV{5EjJGX+t$
z30hl#NdxRC#13r<Itqay4Va^7>-9|eb!3M&@ODL$mjm9eXtF{8o(Lf$4G4=X1dTML
zZ9Wq0ww2d8#42sTdql$_D-a>krks3GYzCo|M^L@gE|aK|Xu>W8RCS|e5}TdW84HqN
zN7ES#GG&LrmR1;-5Y*BDf%<gPP|OM1bie}SOb}>kK-YwDmh-;RMe%V=0Dz*=w3x_M
zek9epSum#~sK!m8oQ?#+zY`#*j|e}gs%eYNyGk`hCy-2E{tg$cH8lj<yEQcgesgPT
zNh$EgL)i&T*JqgO@6g^No|#3V8={?=VA)N{&7V|X?q`^wz1yv}Kzp}aZLut|AyD3p
zJIK6|GBk*coWw5)961aB7D7f&0GdL;$VoiYt&|fJ++%Tv>Vm6$Ggf{U>`7GDr<^^y
zH#ssV$fM$Bgxb7UmiR%Sy+w6B0Ur!fUC)Feo-WeLnZz>*4mpWwx_OK;Z+OKwPf_O0
z8`#^`fz;slQU{=&?>Zrw#4p`TuPyz2lObdhzjQCXbmI$5y|&czJ=FoIXW+zgvO_)J
z6IDYM-&5^Rb$n0NgIn3#R8L@ExJ@-d9p5|wnLscd$wWDO!~>8?_|kP<1z1#D*CwS)
zS`Y?lsi8qix*G`rk!BDW7#fKIL0U>ex)D&iTM#MfE*U@?q`UqZ<9_#k_xsOz=FIH1
z*WPRIwbnWF%=?}>+dgnv)hx*&i8~I;=%h7>s^74&s)CZ>kjx?<FkBD=k>Tw-J3wN>
zpe$sD_R-00VtE|OYwZNcdmpZw2l$E02#aB<qO?J1NMbeODm4@e3{*>@YRyj9yrI$!
zDPIU5l4kZ`k!acL!+$XcrFdcFDYb7HU?D9zY^G-I;N?B?BwRQm8owBk8--Efs0z=1
zy~`HF)Dr5JjK(=X^8{)*Lv+tyt5ZIJNMZK!t+Phy+f>?J%!tPZdm>V!@2j@(?>!*C
z=Mh}<Hi2ErP`?lBNvnC~>Oq;i&8<y(-o=ai5*F`JO^UoRqP(nUZIaz^a$BYrlNr{6
zQYd=a(8mcUf%a9O$1i5i+}QbBYrd#bukf>}S>nhGOH$SZ<)$KW+B<2gBPG_<y|*?9
z(F@ZM!R@=h7yc&mbs`2G;>)~MFVP}G1r2Qn%FWY<{|!Y^EvZ+e$`9b#hrdmGU$9SP
z9lqYqK!RiA`ja+Mj2aLQk?`U@JGuwVbHN-k-(%QCgWR)sz6Yg|rp3on*9=<A;7*dM
zKy*_l$rK<D$hH-LZ&2@VZyr1+FAqjysqO@dNqn1qQ-TaUDsx7{y}uo(td5jd1BfGj
zT&Nnh@%DQ|oFXcm2)OH+m)p`%6C*zCOY=#kZq|@wgjoFijuPZ#q}-6A8!K>>O!x?`
z7eq`dj0|~%B2YTE>ncN?lw+puxz2G;>F#Kw^l?|!+F}X1Oke2#kg-V?AQm%Xi$f^P
zcE-o}f!RHpWKI#8m#DKLG$b{|WnM~VK&k#XrmjVC$C~Pm_Ztt3sHzmC^C~Ql)MdF>
zmex9DKh!EVh1KFKXdN|bYPT`a$agK0#PbdrvhEicEz4_+$K*~(JixuMvAHW<v$}3W
ztmoyQT@xKmob<k#v`XAbpiUMj=Hy!kcK~w4jEu?vcLg+5Ak(CFFP3;M`DIEGCwikS
zqnHy#Lr`LBP{zeqcKdszeK#wDuP5-Dr-vG{1P9p{hpd+(Jit2`=GmTe1b2>>6BPY(
zRwGB@zX65k8#etf=o26)?$tpBsiBQCQrZLU#>TAe3AzRZ+U=)a2~*}Qk0n{7a+4R*
z#UDM|yU}!oSuHmum*Sy3{?J@5iHl|l_UB+O(|>swxGZsdHd}lxbbDQJd!FO}w0P0+
zDW6ug*6qfw@71-dZs&F3iu&#C;aThX@-eI5&1LX)4rAK>+7s*A%~AKu{Vu<zo8yJs
z#hZ@n!tE$Ozw60`>;2RIEBD)@LBG?>+mkN1Y*yl#HQvDB=~<IYwf?DR<Hte2t1iC_
zcZr+Rwfe)8i-p_$D80&=5yL+1X1}Z9ZgGu(&3Uk$qgBU6&8ODOsN3t?tDC6X;(HDI
zC5t}3wpVtaYQa>r1y_kr!|aOHm1C@TtnVdP=`RSvmmv>s)s)`BeV^t}Jv@7H)v-G`
zRbyhe)}|RaBkWjv%!?;hHgSfd4Fmg1tnJ>M)7~t0fhw#d9m%R(<&F=dKpBelzV-c<
z`$au6GPn6me$S?SuNJljO~N!_ulWWtV%{qh<~I%82E+)}WcjtszC*(Je9&jILy#YJ
zQXF}G{5rsC#k(Sm^~KV2VUFu#jJ`TAv99+QyR^j};gjZ~{bwiTA`_D{fHUQ&@h>H%
zj?Ou^^-+!)AMkJbXicw3X&1lvoEE=idq%ZWDuLNvIQc5Bru~#)Df{*~v*f1LkI>z?
z6vOrM`1+NjdIosd!}2nYcG<(N^?>`r<d7S7(dzZS1G?))(QTT&CZ(v_;)9F(V9?y5
zHBSH*pWa25767J26$mw1{Pgg8OkTlbs&rdvXRTEd+P}V$x*plGL;b@hy~_o3xMMD)
z;Z4)HapHG6CFe#eCilt2!*1cj$5H&34=+E;b*;Tywco7(`+1UH)%o4v*tLyh3}6-9
z*sra6h{aO$g8kCRK!d2=PB%OBKFu`iTU^(o(`0-TuxDrWG2-N6t)i2DSESDKPANHR
zntMK7)cy{G=3(BKC)|L@^sc7sgc+n|UmD_)%h@jI%-UIF2&La9&KYv;Z7=y5o7>e_
zAWiB0q=42T;W-cSs159+*{*2HRnP631&!Hu^g5ax7?<d(t5OG7+kv{T|5wW+w#I%F
zQzVWyg^U4K?Y7!9RMPFkq&m}9pKW#3Z^tR@-_U`bhe<=E3*xU8oPGR7p2c7HwYG&;
z-^BCp>764-bv#hK9017Z7Eiv4%DwHwYea3EHGl1sE&+wzMm_xK8l5Vt>J!?sV{ynO
z{c1_wW%mg5;VNL^bl2qitK0<DR6=@wi_F4F8U5^+%VGH=VllDv!DYeYqk??45~YR1
zV<Ml~QU9cv)10VvW-qU#V(Uu|F=L5gZPbdT@wvqH+4QHK=uH`KzcXKW2GGueH`i|7
z`7S+MnV*qAvX`(Po@=4?3H8k`Si|&u)7pe{9Z@gn|HWJIgvdw2`Bo+Fswe-NK;mY5
z=eVe~`G)r0!D#}vrGtgD3&hgY9`OlmW{b@a00I#2002NhP#6e*w)ZbN?{B%ND58o>
z*26_!+r`wy67WlakeLGE1pt?{B!C;hWo`;Tii;zZe;v8xzz!~d)3)LOasUAW@NTt!
zE5Y@C8{_%Q7=TO1)6o*ZrD1Aq319?p|1_>)3bBOu#r>x(m#U=&$W#jK0WgG%fB=4B
zVE{J|5C|~-sV)sS4A*xC@cq?59s+iC{M%rD8TlziG=Xni+HlhlQwL{9gfVl^KVn6I
z3&hp(Pe~fCC1dFZGPl%{mqG}C&sEFP8SDx%w{!*|{HBHdpQ#DL%LxA>Jf&jkVC`Z9
z5c+Faav(bwO9+5V&JONb8B24p#ZODW6}bU|Ji-EqzJ7<yBXvjrr8miVvxK$p+Sl!`
z+vZl4R0mTGRI!W%G+0<zXga!tD^DWsMn5-y^*Mwk@p*IsNnkADV^kE)ju-Jz3ie1M
zI%L~wKnUG<0*piNX%W<nD#lCGPDSk^1y6tGvi$bj;I;RUuj#yNKE8vyyQz$C3A1A?
z(L($#K7cG~Kh9r>NJS7}#^kGI2u`Zgg!a)hWYf~=yiE`jeKC;f$&0mbmbUGARvwfm
z+uKH%VA3hv!%LH_yR<jwdiT;V%D$er>{Ge1fucgL|M7Rq%2m#!>h>G#2@KQbv-0WD
z0wTy<@NuL**E@cDNlHW3!A}>p`lpFvHyYExl~Vm}Qd!IlNd~Qlw)(84(zc{`iK{Ai
zL$2;u@8{j6r<9+a!ML0AvH7DIZ@UT~YN(YND}CAu;jE|T7|Q^-)yqhY{_Wc#=MgOs
z{E;<3m<<`^uy_a3an<`H6pok@6v~as^GID;P_(2li<b+^zXR0Km*1mOqqT7dKuZFJ
zf(mqOCqvY0xEn`>L`o#NC?;Vnb$&{`<?gNgxn(;EIXebc-yX+0W$h%Ku)9B7tqavA
zd6lMt>ziFBh?l>`kQTud^qq(&;{%ft!;bRBP)oEj^HAfCy9m>$)&-g|8e3sb2uUFy
zQANKUIQE?d(<+pm;UVPn#wc?G4a|SwaA@XTvtgjkJ`o8eqhZ5fCB!!<H?{(Xv=lk?
za4ZnpPo{edvyjTdq`Q?4)Z8@DNY61sF4;!Bv$ZVf4O7%u;mdJ0l4ht_!m7-E`hi+@
z|Cznu%N067xyztp@|j3=E~>>znHC!jj?jz*V82Ohw*paQ!7~Eo?RjQK=5#CTl~vr$
z(Ztmwl31@kr2+e?-X<E#*QE<|;)IDbLgJOMc>^#F_*=dEZN9xoddAu6@(MGyMBa%t
zAllJop0))W?G5hNqQaZ$eB;BuUUKHs>9y0_n*AOzvJC$BIpy62QFb`_GF_jg-VT0`
zNJ_0F`Vzh>C*NI}9uqBttD2o$nurWZ?aZugGdsAUGLlN_t2wFtCgrPPzGI*lvq%%P
z&qZ>BZofy_-I`bPLD3HGW_Gjiv!<zDn;;^xelvac(|*Ro@62Ys=4%%TabfE#+<oSW
zmu_+M<xE9f&@b_E%6AszZlB<Wso2CHxviZ+E?iEkXq%1p<Fs+es#WV{#BzQ_k?C!1
zZLN(SOIwQxTKV>e#4ux68DAVnxhHgnwgw(waUV#K+UwAN%5+ByOd?rQXJyEpxobfi
zjaEcuzkJUKy_=r#6J5}byvS_n;Uw8Af$+>43VB@E9p+?F=4kr|SpjcIxrTzj<(P}W
z9~XDNo<DrQU@LTmINnBYoCTbA^g!_wrto(rx=XLq8J6+2FpLaAf!=kQo~(C9bu$h|
z1G&wNqmI_r^{UcJJrD9FW4#RPtE~DaKAz1s9E%i%y;$&JF42r%3)gkJtIgK`#htJp
zKNO-#_YghoHD_-4`Y738ZCH;TD;pDM1Cx+exnhx`QF7snz`E4@@H*=JdC3n^qgflt
z^JA{|fzo<-*@sGJdD;?oLigQN<Nc?MzUEOS1oBm37*3J6D61qG>#xu(%Xb>$W_|rC
z%DelTKF64%W^2Rio!>B9A5RP$&!T_<x_s_LpQ%tRweTD6nfV#CE*;k*0qtTJc4s@s
zI{pBe^|=xeS3R!HcwDQ!XUX!XQ|77MB_y#baf}j&hkS-b_l9DREnbGv&%gU|kn&0q
zzdwe@fQdGHWwZW-?v1E*I@@Sd8X8CgTPhmeQv?5@<SeG^Ten2>2<Hek8?xw^>tZ7e
z-PY&c6{3po>>AaZ)l+iSE65+=7@u3Qa>QHNL<!M4k*0*(<D}vkJ+Y{6&@us)LUe?S
zjkw;Y9I2i>wf<PFR$961^aK77mEDxJuMUTFe2zbI#T>*_N9^LQl&P5PydfRt%QzLp
zon`b#$QNxfl)Ico_l-5%m|PqJyA-B;gR`zVWsEmnEcVnKvU!2TNoGDmId{>uW8XV0
zDfH{`+xobuma`UtDp~3If;6q@TbD+TV=dx#1jjZi=4Q)yct7Z$Gj;Zg-F(ZL#+6xn
zCXqSjS7O-U^UPc&-1OPUC^t5$_o`;6tlCvt_B6(yS6Q8_3#K7E=rw6#1){|tN8N_?
zrnsimEQ85Lyzc=Ao~TA4bDb7(d)+%)MCLa>6?r`(O7Rtgwca*8eS-qk{Xlb5Uu>O)
zAr6$KgL#_Of~{#1H!dZ%z&%?I<#e^nr-~P=QUf_Q?Fy}}yIJUSODSow-e}x>kP%hd
z8Vq^01f#rY@VLTN%>jL=+cKJ*tx}9g_@WeJhW}CSzKeS%zPLQDX7^O4c7i}m0R>(_
z6k2`1P2-R!GNVhi7+c&^v$O+cGkQs#;K(VB*Q+qPpih|DOoXrQX$6?Qm#kKqFDa6R
z0?lL}zVn%Ot<T%ykuY9xN<OW2@r@>==p!SJv$!KxQ9`I4tYjVMr9W(8bfQ)}92zqk
zmZCQsRg+fr;A_iO$PUq6j%-vGvjTGRfs?0al+!q0m?Ac6S5{V6voQ4JaQ8lm*G?Z;
z>Cv-&GklbG2(;Rf{hAzbDN9H|Np|F~)TX$iR8X&*6D+3c7HoUCPRu}6Kl;L7@7dtD
z^&j%Hs)F~v!2iTj+f?Tn_|D$z!N<q1gL0{vV@HC2*n1uHs7ios@14&OgIkps3NZ4F
zjYn(1ewAuZuZ-8nM>h1H*UENK=bEyP!05^;V&Xy*i%4sp%w1xy^t*Yn6iv@tm~4d~
zD+!cFM#RmPXtn^OY4Ez}aa6bhmv_b;+wk)7qS(T5I(-P;8Q%~vcWgL<>fAlpcMB}0
zc*cBZ?08ZJ60BZYcNNJxYuJAK?8rc~Et`Bzc4cKv#K^7`#Ia*nRZElPdG%?7R`g*>
z*fQV8L*gPnMG?Jm0g*h6{1#8|q0Huu>vh7SVa!KbSBvY;mnROD9uIfL2M6a!a0Kdm
z^3(MRcY0sjl$v%145XNUI{wJ5jujU}F+jKSVLjXNggr0&lKs9CdB~HcBoBF=ks$9T
zo4e$l1=*o*^11mE-jooZhTEGp)@4i#W9-jUPV7s*1*dIGKJ~Ux0NzX9;j9+!ZJZb<
zxisQ)YTOO0=&MN*;XbLgwlu~IZo_$RvOKl&^}2JvZ%KL|3c;4Q0_%5;@o?p;Nii0{
zve>9NTduY%xeN=p-er|?h$}WUs&o3<+c;Og9X^=0=19tYshl6$v1I5?pw2cOIi|tW
zcqvLP-&_zq7*H#;9jl#@L<rVqlub#BCX|pGT_#RS)ERoXTDYex%b)T=c*vqeHFEMO
zP(Nsn>V@+|0rg$Y!UXlIYLmx1Yb(aJn9|-p(`OeImv`KRTOSK)w|koI%Ed~7G#wMv
z4>!awk@&)Vy(BJyu1Nwav{sYXpQDBupD2%y(({N?emm+OI~xn+^LuIrQ3}${(wkzV
zcEHJERGhH5zYRlTu4{wZg!t?4l?(AR(%XB?sE;J%b0`}ok|{ODk_8d+1$({p9wUB7
zD2~;uD42o9JM_x=&Pw)LdoosIf$kHrI;XSYv`Jry<8Jf3u6z!Y%b|2w`r7SL%7~BM
z*|)K=fB;yMjP(W16T=f`#^!f%+8%>-S5P+3(F6O^FQ=cQ<f=aLedZ({l!y`N8N*um
zZd4pwFei{95O~qO<FHj{t)HpRKGf<Ey{P|2ooPOUP%{#SB1<Ib=^h0VsM!`f*lOlj
zqMlihb$XNW!+WW>P+RZ0>RME%!9Ja8K@S-o^PVpculJoxo+Mk|`mdzg3BpMcysX}L
ztDUf*S5oo9mKAt~W(}4h6n;01S7j;f_#KX;HmJ(sgI)~14C7?1c?UYP&sh@*D&`sI
zd*o-B6bY0MbI-kls>1YU1(Z_kGZddu>Xh`B6Ml5W<733u@-z`P?y;;F)f>>{*{NN|
zGSwNx`g8*zsieFzwG`*7EcNHVqO5;fSTotK>seeu`%MG>9MiYAfdui&d%}&MZ`n;=
zfzKDd`@&DMNfw^u5OQK$rZf-r894(z_Rk^UhKhydg2tlUbK@M5LFHX{yzODq-cZJ@
zRGnBdm%bEzp^>Y(FNFc0UW3H$mW%R6kVSIdH>mw#VI}l76<TO)spYGOT4Ky4H|dU7
zGvQ5D8MF?1>_rP0R3wp1r4*B&`<mGSlT05B_oQrXx3mQbZS3STO&`{}z4#%Yw8Plm
zfI|adW4Nc9-I5_f!S$3j?GYoInKHkbvMR+|Y|q>0kU$k`Qn$NdZ{dH3PLu0?HvY01
zY~S|H@L0A>{tUoPCjjjOkdwFjh7ldn>g8n?1XT^`7Lq<SzyZg^H=KR(D8wvZyR(-W
zcT^XRW{P>>r9fcCY$dDYT3iD*2?{M*7L4*cefvUxIfqu8v&8#B!)ME6b@MLpYf}sp
zul=Dca+60a9Ck`S=v(fZeA8oSx#}xe8eEj-dtf!?4*ek6G7)&L^nlXB0!SESl-Heg
zc0+f1aaPSL!jrSzvmp+y7|dJhp@}*z`8=h96T<$zilV`Z7I%`}x*;?ay0YH0zCJ<9
z?9HgMnHEt(>tv1;5Ljh3KajRHu`|Q!#%ZG7aO<J=!EbZ={?bhKi>0UY>&I*f;Hfh2
zPOpu$ncm)+e$x2rxa-KiXSc9dlZpHnFKLU#oi|3_ZJN8x%&qjTnLQBGz4Q4(uR|?~
z54m+8Z5hWYHZM0tEq8Ps<wE=7gNw?et=;9pBZA}B<f+ES*^5^H!1d-TipxZ!-Ke&k
zrrk@wv#h!<gQv>1L-uE{OIo}3d=gv2uMb+^ZFCyZr2=y`+abBf?p>|ZY)hB1mlu=g
zKH;w^&ZMK*QbleG`<=B7m?!-BP8<z7bLMX)ZkMx!b3-$CA1sZ<ak!9AD3yES*97Lu
zRm6(=bI9A^JX^UmpXG!ErMAb!=b~>?!f&w<sJRPyt^EBV2jJ2%Qgk!R(_@s*4rR9M
zho$N^?}XBwO2|ZSn1OKr>%=pQ794GwCi;5#jW-I!V)DH`l4sNvi@?TL!ac$^L0%9d
zchfpwoI)m73+|DntjZoO_>Fd4HPmY#bIBH_rxwC=y|4>K6!fA;zk5C(v8jkmmuq?2
zEogyGqM%GfU6H4idn;5j9(MRbQJDUUZ#*RW!i-8Q>ZKUPz;dR9#C_k=%tQ_*^jtN$
zkSDQ@<jQ7^>qIl0U;rHi+ZWdvM&A(2SUzvZSNJ0ai6qX}sBt2hK2fU)@AX3G#O8>%
zuF6)=+6R44!b#t*CCt+~=J{~y_}Gr5)xJ9id=Vvq4|B&hBk4c(>L>UgI-y%)K~%f#
zy6Je!tCF@EBXcFjqHT>>zm|$7`Mu(;EsKg-v%RP~!UF|~DBNSUOw^o6$QdJqJdP1Y
z4UP5n&5^{8U<F}*<L$h4Fg3gNz14!>&C}}tT~LVZBBi16u%Jx;*;Jbk9$^`O+2fHe
ziLrC1Ti@k_f-|ZHxp^m_am`Nm=d+(#^{Z^BB6f0qV4fPJ2<#!<d?67$D;V4>70_kI
zGqxAytCGN?&pdiON_Ds;CE+xGz^}OOw4rUyWYoCdd}6xhVV&hgR;<gs!wq>m$xakp
z_MpUP$|<UH&+Aemouz6>YeSTEvAG?DlYdWzR{6yq$ym5fMaOqtm5!<NANUl?_z=PA
zzL_3sPf^x28c6gpW97MgE>S55vp$C~-AYWY(+_!}+IyqPTbFbGg}7Lo!4a7#ZA$P(
z>pc3IoA6lE0<efC1kgrJ(Mnt~1H@G>340xzt~~>rYNN^7MGm<+9s|DC-W20IlcJ;N
za=r6^&rEmG{9MuBGf&~Ff(c|$b}52<pXSUEsii;Q1^-?oaSNH_lQusL7#s6d^_>zl
zSl@W<As4z)i9eTZW;5!|2(lm9-nm8{ABs5f9*E4S2^eGY!5>FxuU$syR`HI+0&<2$
zTNla=1I&o*Y8ch;y?-T&IHbdm!=E=8c8VhYd6AaWf7IT6e^fbhhg0adQQudoZP#qE
z7Db$JuLZh*Y4g!Pj${8S7n<PV!G)uSDO5A^y~}$~je(lfQKqdFy@><Hf!um`FCS`x
zEyNCshQ4Cr(?j#9gyy3Ld&EIeFT>CLr5&GB&fdyFce$|LI&J_j>5(qcnx3IXqC6uW
z0>H>oP7>M%)Alygk^HLBPR1I~(~-s+7fBf|;_;_AV3x>@XxlE*Y0&#z!sl<;J$kUX
z5*}j)2iiVwgxVYKc&9)=x=mFGCxco2`>XFPP~%nKY0CU`h>~9Hw6}&fCiI+GZAJ%`
zN>J$hi_R1*&|2jAb%V5bGt_ll)_a~#zc%8D1Tkz}R^z_KAQ}vW{9+Op_5%F_B~o!r
z|9GwR_`@_k&*$;@@lzTGD5NZfVMrhN7Ohcq*#*zBk^59Vl-hWZmC?}}{TeK=ZVRD|
z%CMfh`bMyoaMUt|HYsGBRNw;sA)kj-+Z;a2F0@PJxf;e>tRxPY1e$09W)yZ3=nagQ
zxt$)xirqiBT<al>4w(@pAIC$Zttv}n4w+yoOQG!=B_Eq5HG97uKPmf@Pt5RD3wsj#
z^SeJpL1-i%rVsefKC{$KqMk-X!cH-}Cl?)%iG3~huuyz0+B}e#%dAtO<>t8J0w`ZT
z3!hP-%89@@k=-ZS-osZ%Z&N6gpq)mh$N#jm3}AU)2c30rJ)9MF+~VN$Ev9myT!q!5
zH5voIB1@xx$D-hw>IimegBiUdIC<>wX22P*d)QP%)ItRCB6FY;4R?%=S9<Loe)o{+
zW50L;U}h`!bwwuF3wp}of5a!KPVhLHN=q9>^w>=S>v0Bj;Ia;oDO~|&KyEgU4)JDc
z_+)~Db)PVb{d3~uR8(&k$qeWeeh4M<uzn~R;S-c*4XtK0nWfxrn?3A3%n(A@7i0%y
zrUTnINak2|N^PudrcvMVk=>~6qtJ|@R?vrSuRH8eNC>(a+sfjy&^?e1B>|gMMw<j<
zNDrU_!?E$|qb;}OGzYD!ZLK~_H~2H&8sL9}$p~cgH<--NBf$Fy-WC2g2Fi`VZGQs6
zT>lFM{X6Dq9NXs*2*i~=J;&xM2q!8<&c7>Flut$G^S+7}DKtxgQO4h3@3eY(SZ5Q(
zJ9h4cac3xJzq5G(UbcJdI+-8^(+km(zVR1<G+jMK4CuTYJ2lvTV(x0P77nMb9rfiM
z*+tmd1dogaTRRqe*u}(IkV3vSNlHu;;hQAt*31+;O9<u619V;S?qJxSj?_;&$b|%)
zPf<L|sJT|Ck?36eK{!&T#t{1qx1?lrT|^|iXsPbCEro5+#FdCLZ~4)yn;%U@TGAsz
z`PoI=BuUs#OsU)j?X1oZQV9#nJ<Pw64<z+<wdsTmwp%Y5U98QuzD;L5Wp`dots~@2
zQkQ=Iu!`&A!8)U1&opFsO>!Z;#hNn^=frm3b|4~_Qn=EFXTl;j4%=jA$L;LGW8k!Y
zz4(+bc8{W+-2*$W^YW!rxH){8Ol0(~oVI_5>t_&t$BUO2_$OT42%!BBX8j8(M_~Cf
zmd@r7kfRG2f&jjM!ux8b_He9T{;7(xj2fGarLC#1t2P`$|Epfk)E;E#31InE1whoX
z{;ISywT5HmJb!6Q{X+9OxPd%C00*A{4}e=xm=})f^YZ*g^%Y%A?Lg*|4%T*-0N~Gd
zlFsG`T0j`SE-Yd|i18uH96Y@IKLygJjtZ6_Ya2Lo0Pp6fNZZBIUKb$rt39Hi@TY*7
zAv_Z;c>oB+{_hArg0lFxH-2^JYUc8juF!#V1PD+4luDU8TmB?J{y)!vAkHq*Hl~n2
z4p1@uUFPQbMR@$v-GH9~`E|0$I>1Q+kb^aVOAq8A>EI0dBlu}q4`ktD;|ym-c)1a?
z_}@FP0PuIc0IvYxzh7{Q1}^<`{NFvm85cnWZ}e*y;Q#YkQ0PBa1>ngg$cxCN|Gf+F
zBG?(Y9qvD^f9dfE{-+NhfDb-(et1S8#)Dv15L^#j0)PFadf=1|_=y7u!J7aO7n#3@
z?cYg^;FNylrZUI^;Uxs^r1ckR<cgq}{>I#J|DBc6fPgJr&EZ@Pi@7NX0tRq%a`SV-
zr^sUC;^O#-3r>H*rPdHrM;nm2Gbb2g&H5|RrQuwg3kd8WgP_h>WFGMVd3b<AJVHQj
zUVfk;8<2+?2xR@c(f{ynf2c5NQ+Vcst$zmi=M;VuVgKQnJRp`<*gya`A2#r>4FC@d
zFF(Kv@JlAhCnNxOEMfyV{FVs_ar69J2IPic#s8rPFCc>S4;h>*6ov=zA2LBcKA!(>
zD<H(n2T!Me>hTH!;nVzY8PC7;__z^C@=rZJZvOusvml=^{3`KZdi+2>ct-qb>jE)_
zpWBe1ESxsT%M#%$#5F?;42B2&7iWhkD>_)gWBW5Ne(`Rm5SO3c737CsnXnldW!2@d
F{|_8o{aXM4

diff --git a/source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_01-mod_10-low_error.pdf
deleted file mode 100644
index 608e403453645f5a6cd7581c3f9da443e2695c57..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 76717
zcmV)uK$gEHP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-knx%#s|o=dU<Rd2w5;Pm)^!
z#sCJq&}eps7lsT85c({}UP%7;K9v~}S?v3=TJzi)%)C!UpJIJ7nU$3pnO^(nfB%*~
z|1afzfBon8_OILimD_%uub=<@=YM+r`~Pcy{n!6@ORxX_`M>||^MC(s`#=8A&ky$3
z|GlOC^}oOV^_A?A{{KIZEA^}I`PJI~Rrd6Hze@f(n#$j=|MdEgk1hT`|Mm4B{$)G8
zljkd4U;QYxoS*9DtK@c^>Gdz~?ce{GzwLh;ZT`!D+5X+%>i_aD|84tU|7A6d$6l8H
zb$Tz$SHCU+-p$8qxo~i(2H=-!`!%K_YI%8Gsb2jvj;Mt4FO|-Wmh8VM{^8u$vwa=M
zU(bE{^SQ76x)03DzYMH3`*G9)@JqFtztXK5fM2TR^G9m{eyNrkTl48h`A_FRonQH3
z@8^GD{`d4_Z~)eWE9d!@>KWAt{8H`s{P$K3z%SK$`q3JIU#iuEt=S5&{D&)0KEkU%
zyaDOYSD<|Un?C=I!2$SXaCx`?Ml}GxRNIdqtpQk9%U8L#M&Orf=jS8QLjJS-Z(4!R
zxb}3U^YgE>eC>a|0<ZngS0MNP)!HP;3H&m+&(~<bRRi!#wQ~Jv4Zttea{tj9fM2Sm
z{1u-7Fa7E4e*{?jYYFuF2loF>BL6Op)8{)heJ{NDOO<2VxTEmP&)fM`>)a^-zf`OB
z>#8B|S^mS>P9I@)J?!;=K;Ea4ehd!4FM~@52Zw3^eyO(CAFTmcSG)GF^P0px%IiwU
z@l~!6_9*`0?0@7`ec0;%fU?ueeOxI2rY~|_)EB3LJ%2I3&NfSVFaIW)zRFw)<zLo{
z4cV+;Q#1eeEuX*6haLZqX!mgjA&@8K;eWE1<@0g<?D_PW|Nhy+4{E@lbhDl|%h62%
zX{DU@Y@h9@CSY0ZXm+xRY66zkPX9zjH37?NY4;OR)C=Sf7U8<S%I}NtCokv_XZvk{
zfviXP*%;Ho_EV3*y4vUCaI1y#y3*%6ly9{Ntg9XKHu2IQOn&O;=SBT>_W$JDG(O_@
zNhGiy*k?bCkI7U|$g*Ni#r_->16f!6=v>#W#X!~->+ZrkDhm07wa6cNe*C@`f1;J;
zR_*&T^;F1uh}}<sQ$-=`if6LV;8an_y5iOBJU3MovaDG4>&F-a`J->cM+ZGiyXtB+
z{_KSE`3B#`d?4!~;)_336tb?^_Me|kA?u2tq2E7bfvhVY=MUK%$e*mnQNMEebv6Fz
z#B!w{U(Z06L#$(m+=dv)x?;M1d_V(PS1e_&WTkb5+V3)0z#pu^Fsxm_ufd;uD{9|w
zUrv_SgByF|R*S&8+BwSzFD)xH7|)_oAnS^sv-SN`7RVpWe@mZMf1m$9(Ue-getbIv
zSr2jSiTe<RtSh$uL(B)Vu6XP}#C#y@if8@tDGTIJR^xM;EWfYDKXAs;A?$wS`F{Nz
z$^T5ht<QfOz5nc@<eklD{;J(hX+Qh@|BY@>-@=bRbbdbIAA$3c;&F)ncmG4fOM5%d
z{2C{!tM8-v+CTqu{PhU&Ey%}33xp7wb3cfc+=}L<4l8y!%uulz#2>irB9F6=9ajf3
z6pn#JH6jU(9OKvHK`n}(QpI`PkUcrFryEkHhK3#PuoL!nN8B(n06TpjWqOPwd3wwk
z`ani+wi_}%XPoLk$n+c_yJn)<RJy{22N7}uuOU{B2Yb1wGu5V(FBOn6RkYj`*kcBw
z`6JLZ!Nq2D|7t(VDJHAfgznP_4Cxo_Q3Lsi_5qw4HUMkL$C%8{d#NRsvw$(1A0TNG
z966_UK7ZQ`ik6ZYl+S5QwpTw$Y(65|H&)7Rn@Vifj~BTgYBmsVhVEOnAKJWzYzDDe
z*Zu~=X8n@WkUjlCxaUm=_~`aWl!kRYTBf}`S{9-a*v9-IwkPgTv`kBUv~1h3cday$
z=7R%d0Jap1(X?&M-oE&E+j5_B(Ey51RMXz=zUw|nH0)cfYBNuW29Rx{s#d;ZPgOO}
zay0H+s&dzLY@g~oYlh0S{=R=ov~4A=fR(uH4btxeaoroXOJTDOTcc?5g|K9!%`N~P
zvYn7Q^D1-d8}>nnqlQJNINA)d!DUT;AiD<OtDZFZ%~m-@(=Ka1NLTlLozqwQQRdV)
zEOLrD@D)ul_07e`u9<IG!Cf;SNY?;-O?T_|2FS*=Pb=U{xNHA=L!ADKSA37sXMpX}
zd*?fGAee;e3-$rH0KPQ`!Ud?dMjxPX6)WzoF3rDh-+^%cdD#_mulkBK6MNeasA~w#
z%1w{4SFwfE^Y3PM8<uSce=`OW6ET*c9n-*V!dr+sS8xo`$XzbCV;Z_mcneWit;Avb
z+cgjlyI_X9Pd*^)Uf1#$%yHMSi_dYW8oU~G(X#=n{%GvIf+-H+S8Vn|Jt>$yNxA~L
z)k4@6%wE%|U4a-#(Q~ptI0iocwGAjn?h{(I;BIjkNDSQPvuYWNl|G~PxyqQnP>wQY
zFO;K<*{d41Us5(-t<4eMte$#~&tBnFWZlMgJ;rxq`Qk6yX2s}>Z#_xCjJYfN?q<wg
zLCNNA5`Y;SF-JFi+Cl_oOj3xzY$Yy6;(Hz9FJaoU`jIegNvn~3l9Cp~Png?)x}M{c
zl(Y{MW+}9|gjq^j5dWJ!C_3abm9#w)rfQ!$<WsdzJ;JUE-7aBz_Nhm{t3oU$Ojw9T
zZ^RzNJ+fnpLId1=it433;yp1$5Ar#xmwM!V8%WcGY>w)s9t};@%6g2whacqAoehx9
zP`#%9*nHG;>d)9d^_;q6yQjLm+yGhQ=hPjWjv69!_mV%P`*;U}x#<^9DD`A#pati8
zurosqwzd!U28wZ(d(1%WO&(CwgPN6#9^+GSO#QK)QIDxV1&!|z4E@5$`_v!X8MROS
z@u}$1A1kpdCtjS|)teK0KpG{K@`127Ck8H!($)0wpvKKSAZxp+H>V9;2g811;BD%U
z54=gk?I%XwrvCWAC3|5VH^g7|j)QHj`sno2iuew697?O?E=~c4?EKA;4;5;s9||@D
zik{+Qq~3{B!T^#U;)ARx`5rIQym4q4(7|W;_#}pLiWmrg;iID*-ae2QF-17XROz8O
zX$*u*=0^}%jvT-mW~~?w6E$m=>|ju{RtyJ&D$(4b_17%zsCR#BC7nAo_$uk#p`BNj
ze1J*oMeVy%TkX)StCZCa?Ycr)#qnj7IWJIwYm(II4Fix|#+hbZD{*F^($;<Ijt^j$
z^`S#Kt-JOQl+%h+c!x6jDRcio*{nM?H=Kh8!j*$+S$CG;`oy>1^ur<n-7B>Ca%s_^
z4$3{M_(5p^Ts5eJ<(m37#<L9wo4eZIxnj`k%Egj3AyM63fh!c%+dxb@7U{M)T@8dC
zGkvX`>X&cvfv{h;%Qu6#oeDaCPMx#GC~U?SqJ-%7U2h09?+&%9gzR=Ds)Xc*##E#Z
z<Cr#((Y?(fuY^g1hExvq4GK{?Q1YIJ(9SO72gC(T=&o!59okIk>WXVKrE8-6#n=Xf
zzCckaA<11)83=bj^pp~U99l_f(%E{#goiA*?|W(Zw?87J?T!st`SR{&q!|Dw+c*3`
zINSJY7dkqXc3~PMfE&Nlg%a2ga-)nPHhhyy<q+G2X^<rVN4tS=hz;N1Lb2Q~e`V;c
zIRNi5q%ux=ql|B9<L9+VGB<o)OX24IAcsE}`vXV64}y|+HtUN4Cpv@lRPU_hw4VhH
z&{Ms)?zgxNV8?^mT^MtV%$ztb4urk+Z(@<)ZU?>^g+=eKj0`wC8ltCqZ>427w<{J?
ztv4XvUC8ow*uU9ReBX*BJC2eAVNW|g*Cna1_?#718Es0+<6t=uY}*FolsTe!x4M<M
zAMpt)66iP}<}3q4bK6Ijd~VIZJp<zK{Rdnrm?SbxsyHl;GKY^(LcUxS0@}S{j^Dlu
zS@OD7b&c<Ve*`k^5nI6lazN}p&inb~Yk&iOmJn|^yJrdU2AjM=1gv*b!0kk7<(*Y*
z^0S1xA1Mvso+#`cO5QWsa~p(umXV`Drsspb&+M6`JdT+IVfRgfk1|T$Gb!xN&#?K3
z*~gJJ%MQ}AdPg~w)H}|9!o-DT1P9LnaR^CH%iKW8x~Gpr!#OhJ<FFZ&{WlH2@b2kj
z(Y#siTATzkKNNld-3;M?cJ+)K$`7C)1SNaTbJL3tp`YWs(QsPJw7xW))pFBv>|XLV
z>V*Y_-ML=&CXO-|1IJK98tXJGXIAm`)AbWhp@v{<RmgHx@x_zjrk+?lebR6Q9f%L5
zp4?hGQdAs)vW^rLqC4YE0T0Ddu4>7rs7igVCniY-AM0x6(o{(4tV2h2DV_DntCZ4N
z-@IyfPg&+597qk>St<KZFhU$Va*=fkhfjl8-u)+BAKXyL1-9V$IS?ql6^Dqdk0MT=
zIqR!fab(Ckz~J<mbC&$V>2p9F70v`%-%6Z62ZCYYP>?hCAdjC0p?M1S{KZNMPvOEr
z|Iac@!EN0T2nrlP2gH$9b%)!NqFk2y3X^Z<V{K>TEK62}_MUZK!U5C}jGKa6U)>6A
z#~`%LhzOaxDn&Ow#1#hAEb~`|xiqKPu|@qUYMuSzz_a?pfm2$?%>fRcABZJ;h`!l4
zb`FFChXFFnhUUl4%^<8ebnYypTBUH-;SER6fp8{h9n4YyYEp-|-IF@RU69lvNEay2
zIWA*y_%sL|+SMVx05HYn9VMHXq|4g6!_t&=G^~)xNy<lsMJ@5Vqe3DlDI?X@?#&?Y
z3=W$E!Cc_DX$Z>pmM0x3an>A2f!<mmiIc2=ezY7w=3^2bgI!X*Z<rN7UHTaDZWPGa
zq+69@W~QWrD2|SX_>vS?j?+oC4hP49U=|8=;UqPuK+2|*Tcp65Af1wj<xp=p4^V%T
zRG$KaPtuXLz~Ylm35o()n@&y*ByEy{gcGA7=ptloI%W1R-6sQo_W75_<R`-caISEX
znxsPU)HfjCGR1EwlP-=5>?}z-Re@0@=_;u}ex@Vl3L-S=G+kgYNm8{6L})rRSI~x2
zXkR!)4hVCFOSB|)tW*u1b5%L?1f>Z_#+;;}6&N*A*MvbnCK+9E9yFxkK@gEiDjUv!
z1Hl|ZKqhH%1?p^~sdg&`S3gOoew_FQ!WR)Hi3C-zK>Q^cbW8T5c9Ob>!<!-KAH?4c
z;m|RslzvGnVSzaz$((=_njz?M(#ScfF7L;KylCNYoL^|7Nm`@_0T_VZ<8Fb-W{^*~
zOwBlv4FnTTIVX!nfq5Y{O?bZ4Iwm|*&dEfbDd}c}ZB^(Y8FEcpDvn`>_%LwlGQ|6w
zPqh_@tCWe#EY4V25zqxkDnon`^2x@r1{p{H6#8zaFl#9Ju9m)w!_Xb^IhN}N&p!rX
zP&l<G-EZdOR-zE2(wyB0ovO^JIK==0!j>UkGPJ`ay&C6~fl$04s1uMOO|3VS(KzH!
zZfaXAX)Y2;m#>*}OeUz@)N~+hnG0F@-J+Q)Q;bbO$JB9UE1Hfno2Ky^X8?mR5zzZ4
z1bSc6VE`Kb2SLe?1}ZiS;^4aDV17fg|AZR>x?PG(4d~<sVNxi%biBwET{Ggl&Q2Vg
zBWxWTCbMzwj;zLsB(<#<JE?JQAsn=m%y~Jf@j%$P?;v{+n&+NMYTo;|t8te7MUzuv
z-uY6`5S!*U+tqX+XqmfgXUS$fU1|uM4l3OpVLQI*(xqmyJ3pq2&0yE1>sC6|3ZxBG
zraJ;fREM{8>Zt+})*hQO9eQ#g_~H~4(N~nRM`2@ErsGz^byw0s&_9{m56GV=XVA|l
zX)d*R2qv&a4JaQjng`+=6vFTZ_yox|oA{0r**=gLF@uHA3_vw7fmuHh;J!LZcXMf1
zZv)8@yIywJl%rJ8bIQ=23Z<T~_pe*Cd($rhx%GXoZnC){s^c@V!^$`zxLwjT?&XWq
zyrEp~i?e4{2?U|~SkXO4C0y6+a6gG{v8Q;BkmI)5_Vo3$>_>9noI8$lC{d@;&fclQ
z%*gb9Yz8F0R+v}nD}2%Nb?L!@9P`_|4P*vJx!^T35ikHYB!KO>*vOYoT{Cpd(r5rb
z%WTI5*g)724uk_@Q!WYfb!bQv0@2-2=2wH|woMXw0Bkvsbd&W1*>AEwU$DW(Ct^VN
zkH$dQcE@z~ulA$N#(kd-gpD7K0Kb-)%oZO@A^KSQK4m;!e0B%Yew5kvg}G}Ky8%E*
zR4ejy#S&GL9TPX{B$%cuy%4J8fC{uK?m`@`sy5xElmH2(#6LU(IicNP9~LR4+;l~a
zbC(sh?Z`HuJZo$NpiasyRc@uMh8xQGK38p^tcC-TPKueyp_5`7GA??g%6_0*DXC>_
zjYNf%`yfdn#rI}F(!((cNiB0HB&mg5_#~ASR}J~nQ41xWs<_lHlIAjxIb3HLu;Mf_
zARelG70>I(F=rt6W6nVQqFSe;0nO*9QRXQJ%XY?z3Ttx4i3;DZ0pXa#Wjd*@@YFXD
z9;vV{XB??q4K)OP#>$*=rou9u_mU1+T$J;`caVqOfxvWt60HV!{mw&Yd91;C$ZUWk
zz<_8sz#5!gW&^B2m(_qX-eoly$mURcg^^&Cd6efGbeRqOu}ww;u7GSsUGv>!FyVYR
zSq(VfO(Q?}Wb0N~PzIFHW6p5Xz&XQJ1Lq9;>$!zZXF!wL$I3KJVOyV7b}7y%<=27G
zl0ly&yA(QD!Y+jlQh*(rK?<;g?rj62VTzMTThXC8EHX@S4$CX-ZzG}%-{*r9m}QaU
zY~`=n&^O8)Hs=Z&CAL+TMU)fAW7VmNqWn5FQ9M<dzP~xrV8`S{r7(!1Zz&9-7oVJ9
z$TUA%hiDMxL{Wg9ny6hCQBKq@i>RF?9HQ+PzbJSLr)sBlm~*wOH<+t~ZYQ!s59n}H
zHfHCzum-ec4`ecSkD@PuZt(|1YdmJ+pqQg!Js%WvZh9Z(6OXZp*$m?40OsMKkfWJ@
zAiNtm_#9phz+r1Z><*@a0fV}B$czBAYl+M-JzZPmgI<%m+hBYlE<k|z-Q&)=fsI_(
zC>c>>Timr|#((KPCNq9Zmo}M!Si0EB2$|aA_J{F|x**C7Z_*`FW}K2PnlfXK{KUTj
z@(y_wn45CaT<|h7X)2)A=~^rw_<F_NS!U2pPMQojB<d25!IiwG%M6ThtA_Wksy`fe
zRe!iEs`|r$L*w(SMLvlA;U=i)Pe#f6lJ#=XizI8{uocBkXl4vZ&Kfuz26d%65Z={t
z;EdnE%`AgG<L)*eyp7Bncu{|_;Jl2~!9FvnLU+lTAr!iB&Ww-Hr8I*^adFKD=`Q<X
zHQr@sHt!dbIzJt}kSvUL$qZn?U3)(0E24wWk-nz;dd8K;js8IFE<m^bnXv=%3-}<D
z;{d}>!?yror*J>mfOL2yaN+10B2Asn{c?23bnbUo2#;`0cuZGQ^uxgZL~N?OE*P5{
zju~5~TfV$E3~?_Ll<28~A<^GnE+QVj>V77wL`M~jsQV)zi~5Oqaz~X>KHLih9&L<d
z4ObUNvdSBVfvoVDAp%#G6Wf69@8))s>F6%E9LBeX>ki{v<=&G!R8e^VWjeCUL&)M?
zU-TeitgC#C49Rjs+JMl@2-}T*>hfk9F{tbu*M<UGkqwN24c{roz=nTSc0cqi^^0ET
z^wQc4%HhYwfY|W!VnA&8f*~OGC4aH(F6Hho#vwHIjzehlZbM0KYbblqPQ5U_(Y1}e
zr}UNvMBj0E&}I6L%gJtI$ZUAxWx9&fSufLDT>g9>LmMuC7DIc%8xgNOe8c5AXhF2q
z9TGYFl;@X5P!L}vFU3rkaQHE1IE2g5(IRc(v&h%Ge92dG15n@#$pOI1C!fnqH*IMF
zh?I4=P2UR8cIDbRkUV>TTI8%doT9YDjg^zY7&Cd8X8B<2OHCi_q&Z0RIK>>8gbqK~
zEO%>tg5_?lPq4hL=~Ii?TKL?4O55a-YeBWwIXUez%r+c*8D<;KzlNA;2oAy-9^Lwi
z%Bwr8r;y<CL$<(MJQg=W23c2&mnKhV3&Xw6$r;)Zd!#Il?V=m6EQtusrQ`J|&yLv^
zmy5?9{6WD}sly;pH+;Yi+4JNl{y`=`atqRhSG!A5M(u_>x<&0?*W|Kp2%ZY5)67yT
z$9Kl@x^MhOq~*zfKGU1q+og-O3>I>+)_22QthdRHpAoy^>d&a%2nR3(!3Y@R!H5Fy
z8U3#HnULSLJ`4@gThR*)>P3hHALKngQ1SumRPGVIilSgZFXJqL_<lX2FH^9F#r$69
z6whIZ^_B5@8D!@O4A}@-ORT~G74{6q3PqnVC^$k?viW>_gbKUX6rmE`Lxf6n?-kK9
znO@*@c>-h&T__zM!o!|HcW1l~qKID+(_@H72C-jI<rNvksN#qo%1yCC(KSDcDF}&y
z#vY`U=_9TnCPp1A&?(bt++(3OKnQgD;!ix7Qb)H2?Z58o8(eJ|nH9mw5x!-JwUxB<
zaU!T`>Y#_%L6&<kv5x|>yWz{DfHOnz;DbNucrIVWte`p+eFT!$?rg5mxJ-BRsxwc+
z`N4f1H$Zs~!^?C)SD+pPpCgzrw>(ArS=6(A_!SXoko`#aNzK1!HKZ}l95sY-f{CqC
z8pGnF@I^*SE5b3;W4-Dag3#$)>xQDQk4_zQVXu<DNfDl$r=(cT>>lmg6wPUnHLAlz
z+Zo@<#llxneA5|(eOrW<GVVIUPcvQL6{5;WY{an=F_Wf(T?drscvyyJN5pKVdwgwE
zhkV#w>T<=INb$Lh-;Nkw#&1WQZ?0~yf;0B!h`(<#)mD6H6;R9&?+7{`2&0$xc#x0&
zm^#Gp<>*kJqo6Gi{PO3}j8z%Ed`unk(My8UF<(*H3>H`9wg++h(#v#N{dlGj@LU<v
zEDanH<q<}{@t^#Y|7Z?J&-CwC#CoQOzoOdFD8{G9<T*T^J&geR%pd>-*>iwXB>tEM
zpAE_C$~b3<YDNnv?4PqaaRb<tkLeJB02d)h1`OHrL`1-~o7f5l<a`_Z)FUTCkbJJV
z=MXgl_sPVcV4KN$l%^gz5rT|h73zz~8ni2e(cuG4ln>m<!3trB^+qC^K@BbI1m}#7
zK|x_Jjdf3ksfshJXe{`yk?F$2?)@pJp5n7rP$IcT^n~mhE(L3MO+$<vnQ;=J?4VQ#
zQV&CRf5^d~I9r7Lw?2@*>E9AR!7pMW%DN_#Pi?_Ua`882WoS};8G0eI6GN&$=hSn2
z+9ZQ3EuvypG3XWKE0nXr&tkIJIw%Ru2#yve83=5V!3+SbE~g&jv)8AQ`|LqQHi_=j
z7qYdzg1ClXli;?oFV1zog8v5JpzQ^g975JPU0qes4#^0@*pU`uwZgb9#vXnFgVx7B
zlFgso^&o#RhaHSUyl1RIDTJ*DMX`m%1jo=hjokO*NxrxlilO@ypVP>Fimz$pKE<#=
z*n?gmV6q>Oc1W6SCGC*R4VA1zyz!_72RP9|0RmqX6qcZq$_$U`Ar_&e`ssKhG`inI
zE<$e=xz&uEdQc0BEZ57Na!n=(C|#o3%8a}b8`q5J7dAvudJV|PxKhl5GjGYd0R1nh
z!)8Ph5H4vVA)_K0L}edjA~ItMt!A>Rh49N{Q@fWm`B~&@na}XW3Xh`dwji;#O#o*e
zD!NGD45_C~Sl`<ON&jT%5gF#Fdj|>KjOZ8JD|qb4kr7;XH{{}PNUXPO1b&q7A?~t>
z^`dPjU2AIF7Fm7|0l>(B69-M6Gt#G~ecAi82EOWDca{^xWry)h%!N0ELwE)I;iqH_
zi}ueXQbx8J2zOc%O(R855+@_CyC#Tj!V9>EoC}1q$4@+<jofYs79K~Seol=O;jRN~
zl-Mh`89Frz-%{t)xFb5#R~)8DrwL$tk#N&br()!s%F&8%v1@9@Nk;cLLL@PWCe0NQ
zHe*}v*r$ew9F0S?O(?3;K+^Qwu@8@sSOTiL=UzpkP0fs$JJR%E+nGm*s6b+uxP|D*
z^RveU9}+`2MIL$D5{{I34moAFsmMJAe{b>91`?_f46;Y4Mm(OP7dV=VA$LZiA=|1)
zn;LSY$Da2S?a`-N2FNPLxWOaNR6tJHeXEll(1#=*a>^%@EuUrji6gf`57)&3P1VMr
z&Nk1=c^fnk&5KRtsR;6b`n)`6$R01n8*htw_WSZ~?p!tR6Gviq0f`6M?mB1D;og1c
zIlZj5P0vYG5D39AcKdlw4+cQfDBqcL77LC{Lcm_V^O|~0B;G}v%ULiG`5_3deHwuf
zI1sx$x%TOOZEy~p<kK~a1tRgT`pv?XrkB+O-8IVv6OY#{7>L~D?iH6O6QtL9?9^+P
z69&v;!Zzxa=MfT`zAs}ouUT*q37KS@^_oP9Yc$s^OKh`Vg`d1@(q`O!Rf>RZ)T`V-
zqMN*4r!Va_D>FnwiL#A))%lZtg}d$q<ylp@LO2PCc5VM%HNIxhK(1MpA#!O1w&AWe
zDN(+?TD0wf_E-C<MO|%Dn}|#rn+<!`UEIui&B}}KpFXKgzFqp%m~D?)bpg<0zI^5T
z)RwROaW73elCOG5n6i11`n9{Qx0~909n;~!SM`{VCBCYMe2oO1)A7L8E%XxDy|44@
zc3ik7tt6m0hxn?U({aF8?V64QO_2jA`(B+7WWH$gfy@_eK9KneO$RcM__=-_$SfX0
z=NBSz@EE@~L|ry_35%;xpU0|L>;(_K9-E<K=osBV?#Iv(&7qga&#DIL<UIa`2#_BL
z&&i)<8ATuV#-lU?P5d{b=SAo9YF(ALl%3BldPSYJ2_Mk?m_Lv>eRu0@o{stb@(0I3
zf4Ddg<ZgBt@ij@^@#!topik>=nFejw{~o3@fM$Q@N;gcU4E`{zl)bWK9ixG1gDGYp
zVPGoOvDv`n^Eexrd>&^5lS!BXg@wr<e6ufE;8Id|eJ*DMlh0+-brp<R0}2b%(L5wd
z&+(a?>`Ojzie08{t?cH`Q@e#&g}KkCt<ToIdLj%9W$OgE8y&KV>tWsVSqcHxF-u`t
z>ez7*Vl+(-fYaYGOUKj~pQR9G9a9pbteY}9kjdb>`*ZFF*Aagf-SKJC9cw)ppXOsc
z@UrTH6{g>TaPkjKRp?p=ChH7!^1!AFW$VCn#To3tbcMV-FkRQ&BcC1~%MMJ=HTB20
zkfhy#*`l!9Xo)Xr#}8~`(mr*?CMNM36$XC`^~0NZy52CL2Eb+}=^7Q63j;a$ld)xz
zykl@LQW8{Bzr!dgOi@1Z1Ic_uvto3^<|8Hb!Zzptq8m2;l%gAlKP0;06QGg}K8HL$
zG5pMK_%~_*?8t@T^LXQ{SQN0h;V!BqX>u1vA7auK?UD*gKKKxkVEHYIqQli$iHJDd
z(i8@+`2}2w5Hwucl!zU}rA<j?>WB~6#3rtAO2lX3!mvc7mEY-X2JxbF_wk04%8mig
zm!&@7`Lfhp@k^SoOB<TMUzd)cSl%h`SmgP()W+RpLBh>!N%L)~4?HeQla=B|c?ZIq
z(!^m(C&b-RiGUj19hDRgF9|za4ljwrl+49#QeoT+ZoEr`wBT~7D1gQ9%@Kvn8*Lxs
z!IF(H9A2`QZkP8Zf=OED_`=;K`!dR|4@ZF#ks)v<u;6Ms0epF#D_jYDbdtXAvY;4k
zAT~Z-m%{U*c*q7H<YPMJF5z1>99#-kjqZtXx+sdh*yx!t!p^^StyLn10uCQV971#o
zDG?#j3S~`rwIF$KL`1*=rKE6cDHuR_wG^MG;=v8L5GxVMfD5srxCQr>DG|1S3$o%d
z3UuSKK}AS{Q8j`XfMqlkE;k(wop5h;|DQoXz;%P37SRRpAp&c`0K7uDDVZQG3>v_N
znvo;O+bK7(C4B3KtwewTZrDJ(F#AxIaQBC!73doru;~xie)ww@`0;PUovVZse}gWR
z!@~u-P!10lSAD``zrl5_go8fr<%)doaV=NE_Z}W>1G#&-SrW;n=XiH@7;lHDHNIbT
zr7PiTk9)h4tJ#%tX;;Ft9=xa}hwz4?5uWvM{wwgK$Af$T;bM6B)(9U%XcBUp2i0qt
z+~&atTf%J~l(FP9`R3(c2|szbDjF@y&Yze>DB&9qe@vro5z?&84&!T?L!@3<gU*j(
z-;G~}PRjVuO+Ml~rk6g0=D=DecW-#OmdW26U#IZ*PDYo*MiLs4B!nxjbL`N8w~3eM
zTOPk<^2+v)K{#b+Osm{Kx>Gcj$-x>@S-#Vd$&>SR_NRvLH01Bid-_FAqi?@S8$ByK
zOJgKO%B2%)iz?|mF4l}r2_C*fdnuFiwW}{>^1il9(*bZsa6B)&&M3HQ1G&>Tuhj-O
zR5+pAo|zo5O-N4O*NBNO@~y6TsH7Jz(F~D;zs-H2&griBpu3`TzHR9uj}W_58?0IE
z8;*xX;teqYg)Y~d?$yfVVcpRiI#@$~O)l0hzl!3NI^|cPZfbE4#sk(^g?)*D3hzrn
z$>eN_cqGJNl<>MnoJI++YuvsWf`$(7Tanzs?c0F3(#Mzogx$v>s7OY7N(CcUQ$weZ
zP;wHNaV1={5#&<BH5)-NCET++ysC=)vvEOZ+;2N;H9RN6cI>?>bq?DBfgHnjPCSL9
z@^%$}<S&)X3w~8+0NS{?h;#T6$?hESX_~{2d<~^F<3i7P^!Rq;EKnq95idphy>G=-
z4TLdb(Dh5x+lbh#5)S2v-!k&Qoz*%X#P~<o<KbYwee2$@gopW&oKn!YH)72UK|9Ik
zirV*)I8`#yT1*?M3%_+M=){KKih?WQfQ~phupw@Me5$CRBjAo4ir<RKBhTWuZW0Hg
z5oWBNzC(xrEaAG2C_$1sek+o&z?*$jxM2x*c0?o^g61ipk6T=02@m%};#nUw#7B~v
z@>?;KC7j+7XGucK?+C^u>*cp1HjBH#Bcii}8$50|4XON%@1lrvLhPt9aH4JKvEeI^
z7}OHJ@`zJ)9#5MsigDR?j;8)_;7$GEz?=GW!lN4*@C<5v5c|V{LoqEX*+U}E8;-Z+
zDs{+v6OrB>z0oNJ5yd5Z@p)}aT2zNR9>g$Y^koib#$z}Yl--vC@s30NIp%2U5-$A5
zq3&?EL$NGZ>~<Ka>Kxilepp9r7l)fa!o$fb>xk`!BF}%snU@-&-7qHAi0p=-t`XUd
z0RF=00EE4lhz>wtydmfggmc6TAi%y<GWs(LztjlqHs!SH{t|)wq~vvEh`yRo@Gn@E
zs&ejL@?L;GfV{uoWEd!w$1-pb6u;=*0QoP-hyeLp<tG8MgTn9x&>@s6=hqW=-J~i0
z7O?`kjK4*`P!z)eeuh$Y!UKoHMo#2!5j~WuD-4i9kV*Mlgb~FfA3!Jp?qzaJ*fdCu
z0x3m_Xb5vkD3zy1_#~97n~>89!ASf3O*RZi(6u6>=x?!U45Xp#6Cm0%l5&u5`diE$
z<fHx;yGN<i%s>EA;FY$0izS4_*56_hDOE>Qu#J!o`&*18r52QId^*5_(}axLj@Wk8
z-7<(!NW=XtvXre<9(&<-Q6jbjtSjX6{uVJyiD(ayw}1tF1LPA?L<{2^L24n0Vn`+a
zEh?G97?DkUGetonMo3etG(~XMfVCXRi4ISQeaIrR1pGLpKX=4uyrSf@E!`4CJfKh~
z$&Syt)Xmcs*{Y*DJVS~CRL;|>+R=M>(%vDTZy9DmJXEUm)02Www%QY%u!W&6=c$J8
zL`Wo(|9+7y>5gRYKXoKHlaP@98_p!9Qq_ekNvTqGLFGhN`(Z_ZcS%5`geo=Ysdg@a
z=&5!rLPN>6ycA@RQ{54p{+XT1w|uZuC2sj(r^4y|hWHxLBjKX-lR*O<T*v@G4lcA#
z9x@6)sp6NHf@92Iwi)r`N^PPYW5ajWu~K!PctN$iA#9lIc$F7(9DK{+<c?(TJV?hV
z?4;{oxX!;rY?;ei)H0Wq(k>9ZLCnkWO}CRf;LUfGe9SsR!0Dt+0Z(u`DOD#6IGvOT
zfr8V?9kG`E@BvCa-*q~V7^PmRJdVHz<p!{2?hfRoD^(|!tE=e=xx9Pa9$ifb;!RVo
zUR{lI&vdokQ0Az;Oi?Ghnlm46KOnXoWQgrYnGKW4?oh+pWw?o~^0m88wH^qEjjeX7
zZ3MuWYYMZ5_%Dv10NdflyVOn~8YOq$rIrHm2Xo(DY$*V5>2Q8gimd}BABwo)cUREn
zvWp4jdE0k>i~>r0D9Li+H*!b(!M-QU4q<cfSVg}P<Yx&E(;L92`aT5}Y5*JQQcD%J
zKHNF(2r6CYD_B`)q*BKei~r6yc1F;+_pW{2OZ<5Y+Sx|n6*RP^DxJW7s;hx`9gxf>
z&oFmK%5{56qE0#^`PMY<c(*&0r~aop|632l&~bq(WD`U1G>NJ4i2;=R+N2hh{8Kx~
zil+rmJ*o(4*lb{X?s^7*<F>DyQ+e8YV6K}sXF4>TK=@F2%=6-K+V{=}H@z+CRNn%@
zlV9SQ-c-D%Hx(S!cc4&6U;;0FN5GpyI_!`eq|Ba>yic+Rw|aNL4K9>uWbVEJY{jJ@
z8Nlxd<#s2Ld(t-pyVdXPLM)Sw{EoCq-f!Q!s0(?|i#mQJ$c`T6td_|}j@yVE!lto7
zb5_%V@T-9>OD?TD#Ky5n!5yzpEbirQWwy<In#)&w$iK;8KYi<Y4R=SRA?)UP#f!Jl
zHF)uMNAMj%Y1UnE!M6Q?PAHVvin&TNB?5bvlquv8m^CgY8n`2q-o|7Fq1hpy0e}q%
z+vc|FYMZ;LODPV7N^y&13erwdX5-u=os9>;wtb6iBN;>}&Aht1BW#%4<50WU4oB#w
zT>eA4X&}^1x%@a9V1TDu-Z{XNdMQ_)XR(G7&tY6>%B#qSadN*$K8*9nX^4qH;t+*g
zAv$I;oe0ih8z7z4Q07UDOBN@w3Bhp=@$}4i!jmH}`r>fOd%ZY-@?I|vsmQ-FpJZ{3
zcL&(GFI(|uu|9=XsK{hdk`BXIq>^+V#gY`tyNVL+4p<Ui;>GEomv~_!VDg(gl4nZ;
zbLeccMes&W_KFuX@q|r-*?Pk6!IVCRYyc9v%n2`Hb3u<w*j&)RB7;w1#-pOKV}6T_
zE}Y}~3X2f$$--#l*JQI{iML{IcVZ5uuuJg<ENoZ2^n!hhxtL_~!faC7k;xyIT476L
zawyu{wr^cwmB=(+nrwf3%;B~{&LveOCA2MlwhS`4Rag&k@g(~qubILC>DNp!QEmV@
z3!F(F%T$6Hmh;AAnNs2w9m|xjuN*SNa^4QvVKHwsLMeeCZh5va@bXe8tiZg}p`Dm_
zIAKXfIy4xYnGdbtDV(YEYqD7LDkf~&196+Uw%p0%kMi#p>xTaeOQB4D1!8d5BvGkD
zAlbL>LEL(e-*h~NQ$j(g)P9A65Eli07r|=^drYMujKqF>TvB*<Dg|LA_S^X>Qf5CY
zf4u%+(!RJN;fUiJg~|Umzh~i;@*>6&_ehAuey~zS*7wS5(F+$F+$JT`z*k<3D%Ei1
zy{HoVRbGr<e)+~%A#SPoLd8`U-@&-<;+w21u}!ag+?&xX9+ztrHh%d=VHKBi5O3Rb
zgGV{3Yd%TWxC*3@j_X3?x!k5ZMSc))?WpfcTuk!Y6qlF$q~U^-89vz`?t!ZQaNt$_
z!JEOzjKaUeDMFe0DxF)Dn2#|Py4a-x6qmoUS;h@96|}fUrp1vL%~UAkDw;YduB$gd
z><{)ny<2p8WNd=2#;NvGB5n><+{|;NIJW8{o`<5itml!8_xWM^p?Ds@;l-%VON<DB
z>j2Kd;ah+M`0Re*Cwn<4(3%h~3`n&bUJlI03oi(tEO(sX03m?oO2M4J;cmgaz~PdC
z%)#3WjvIjJH^QYn<u_8*nEXaA*1Gs0zO9%1MmVZVek0tom;6TfvR<66hT`n@!o<ws
z8B^f#UX(Ez=kKCRh>`udh$@lUq3NB&^wHtJ!yMD$<AXfZlOGWCREMt+b6JN!5fWa%
z!sm!NvA1wcDsYj)XuwDo&P~X=9sW<u%nc8z4N!PdeJj0pI9f3UcsOG*Pq-YmHYF1;
z;?gWgIPPv=1$=Pf7FOUbF3+*zzTuN^S#jTRd7qU=A+Fp`bOeVBTWOTwS*in_yv07s
zwC&+8ht%%jQOE4>RM)p}B#37k%5SBRm*-xgOShc+n20_c0E-;B;UkEY_u)l20DAjz
zBI#$yzR^L2E(3*b)kQi+n;jlYqj!qb3Aj<qZL%~8=3T2y!7SyWQ7|h9FdeJSg|j$q
z5l(s=5cl(yUSLkt(g5T{Ee)VSNW;-|ly9D>1L&y2)jPtOwKT|7xw{S|%OiFJ;?Ath
zWh;;6GoDEwS<X7Wk>Q!U6?r4;Q$}xOeaXN)Bp2WU;-T;o9*Fr1$dkB$We5fg2fQJD
zN}B7Y@>eb(9)d@+4YKdy3GLzngt_4xUEq-{nc8t@KnLs1q3fEwunQ=H!d1I~;8)(<
zrKeXodzYT*)-ORSw`HC5!7?14<poT{;e9?37p0L{z9+h$qeRzvh)DW6OG<(x8E*0$
zAoo4jK^a6t;c!0?de7sH>Ci*nKDaqj;DNvEIkWqJ0ryZu2o(8IN9sK~QcK8zk%)l^
zqwM|FL9#=}F`A+D!YP-Gqc?RVX$O~egiaK9rjCT{pe;iD#RkYb3;_o3Y6Wo=dRH^X
z!vHkHu2hfl;4DFn%{ppzsIieVy(^A|U8}H(M27SZy*ARJcgC@>Z_sm<`Wyu1h@ja3
z`S#vf8l#CE=Je{09Om@uj{M}Efh>`r9Arrm6*Lf!j?y88p5Bpdyf?=2vFMRrI&IL=
zn;}f4Hw8jPXM6}JtUkRd5Q>taD-eoZfnbhY-W`HDol+y=9v<ntL3$tIT?Hge5dv1+
zVO&9CTcO8zq}}e&uOrEJcVlkk&jwXf1gsfyc|e*K58W?W2?L}|r9Zi1<_xj%xiY>L
z&^txoU7>@ya!_}eL?YpIKNOqC-F?7387ZW}02R@K1#ajHC@h_!wo;}00sT)=iKU+m
zTlA7*5IISVtCfmOH}y!nRysp#L!2|ZRvC{wqibc&?H*oRb&1%a`$yJcy0S;Y;LZTs
z5Z^crc&gvdOSZ_;+Zj+x%V+ljyTM>uWVh}3R8DzlJL79<n(U0Gm8yz#8y-zt=no%R
zItR7Y_EJ2qm2IZ;)DItPRzG~CA)*;fn-QpEh_#xhejuQDl#b8QL!rlouJjB}9sp#F
zv`esMF~)h6v&SzNJp^IYm<xK^Cs9fa2$9q%wO0gUkFqcG9^LSf?^7?_l!1Wn0U(Hc
z>IVbK)epvzCp`s$<lZYdDkwI+(0QNX>jsRTD8jvf<%==!+W<VeUX~*8enl+3A=f#@
z+ZRxQMNGau$fN7esXHEDFC)(ZWkd`Bg`ojr39ttlMZ-CDh~xv&A(9W^EoSt9C=1Gw
zXHJ6x7P8<y7>G}fbW_F`h(BQ<*|;}!W6y|#UFzxqTbrmF46*LXJaU-UvolbxFeG7@
ztUaIyfi=R)^_+MmiW8y*^~6>fv|zjx1^j3tu5iTq!TZRgOw<>J@eF&TL(_nK2kE}=
zz{yZN8-+m+;^G(xctChEWFUkXJq)qlNrE0lL?E1hSOq~Jf(NyUVWcp4LM$W$@rkP}
zS$C!G9tHFkWg0i>QyR<GwK5Hw<S8*|-(Mx9LVX1%OJOjEcv}YIbE!KNhG>ZY#Sjw=
zB8eH0O{OkD7{(#08AGhYY{%y@>5O?e7fnb(Tomn;f>AE&tk0rO-3KqucOAPAa?|Y7
zsBKS5DP^dLD0~bttyDZeh0!A-0~!dKe`3@`IBNJu2lLQ?oP|jO4_v@k2s~tU5XsSu
z@Pl|br|=aL53IxDQ!=FGiF2ti<r{dJwma0-X(wia#riN-Wbr?ZvNJBp%zQLbv4toD
z1GC7c3OEOYkZK^tiWS040FS>+ZFhw*10nQvOp^?RrR$uCwaU>qQg3;2V&*E$ttaxX
zf%pQ+7CRx-nVF?eRAGi(*F+~aBb-@e`@32!V?g+Zf{XhKQ3bwkQJ~F;mJt-+B2yd4
zOt%*0q7FNiR*jZHw^gU6eW@!;HfZT}6Vf$TzRF>noS>L=TW6Uf14!z;uX~Bo%z<Z6
zbLPB*y(e*=7FtNOYtlYA`3MDZUpbCf5c_#aH>^wz31-0UhOk+%#a|R$QRWT<!~7M3
z>j3McxC{-tu2&Eq&Ip&-lcim|TFN3-+<^G*+NYL;sK2)1MBq3hG@vt+CWs*Ca#8PW
z1CmWLfJxu7<Zq|0)Ku>3oNY-FTh54{>Z0a6rvca|JwwzWsla(mPbL!mHT^aiI{{6!
zo&zz8(mp*0K-FA1L#ddH18UP_Y_pzHY63`FN|2OBX?q3BX<<UtvrgT0B(#KcqEq!!
zmdS@XRzb)bW$umt^!kt6(CGJ1KR#RN$nEo-&v|7(&N_~E|NKv{e|@Fb{`p`3|Nr^D
z#bEur_>Ofyu6d+KOg!2>`m`sF8ukbU2-z);{CBm|v=sJaaTMbP*(QEu?bF_4=Itfw
zZ4wi<>LSbLCu9o}aeXCw`k^BP`8pJ%iKu=c7S(R-6??k<NEed_`QzK9uiKn9NoJ5>
zHl-0Qo|98KDtPoFiIgKIcWS(DL=L$ubfyuRO&>=S7vHyREIGW3`tc&O=r^rJgW8Q}
zT97Q{@K=CMFY^){Is25hiU#0ZCd)TiPUB9rA(PB><Aw|@MPICjG?tMnt|+^hu6U3I
zEN*Mslr69@%~aNj&n}j>DKBJUVxcS-?*<;+Fz;7p(=5z5!<?k_rdCc>-cCnKT3+u*
zBHQ6W6}ftgh+Jg_C7E!(yPxDF-LsriYH3D^BmcKM=(tj;{NB70jm+zI=@?1idHa^b
zc2@RnN*hmy#+>A88A<QyMd|AirmM`X>{Yt~7W)CwlM;-xVMfB_41{j-o(>3xD0A2L
zZ)B1&AMWfq>_iC}GQ_cFmMZIymz;o~Mxw-A;8I@p6A#dtX~!pOLa-@Q?9-hY>~(_M
znW0^Gr#rKy%du~d<{{}lCM7CSd5#`Z8;+(dM9CVLUndkpEW!)nW>zc0<D6zXDL(B)
zCZ(i6tdrkaZHWP)7JmZ`UPNbzXT2w*_iZ%gxHl1)tlb0Yq9XhIfjmnoBI6?)I0LyU
zx`LUCC#@-)HE46Q#m!C`of)+ap64H#i}!p>1spkf$*{td=5w-KZ`vfVQK3ZMShC<S
z6{|*t3!z*TKR@RWy^!1&q9Jm3He~k-9+`$5T*0cMB$G|lSuVB}Ag4r!3U`XkhE}S~
zG-xFg9pwu4IuJKU*!YyDF6j3B3l;e@A=kpqnklbx4eC*56gxx|d9>G@V#_z-lt8Mx
zF`X=d->=BEq$ue*?U7G`^8ZAx4fJbF7ppN@&djQ8+p~#$9qZVGEfYCLq{1oNhM38e
z8->BNk&nZROjZ#jt;uz*9t6tZ@=y4)bySL1WElu{aAsea<{#M><|G2Pjz^>-vb?WH
z<R;^DCz{fo8tVLmGdP6FpI@hk_%S5NxS5^d6bFj9{ez4Z83S$%^?m=z9B<zqJIP{d
z{iGLU!z3_|qyd(7@rq<iqz0EGpK|?NL9$<NmM^kQ7ws>%a?LyLBKI(%VDz0f>h2ca
zpt8MS|0b_4gU7)O%UhTrN+sK9kevFBNr(tiUpBFWiPtic3yP#N2pUNR8QhAzMIC=J
z{yDJ>PLk&H)wfcx<YAHVW`#S0lgc?^9FZUX7UNx`HwdLE{TIadf<!@Enet7;9mq;;
za@d)<w@A4Z99Ruy(6da$PhV|viJN(of~*K$k@z5yK&S^Jj#p8-!ikfH-?777Vo7|$
zc-`PVY1`z6{F7`X!B3lC?D91`$&WI)BH)4fc_m*nLB*l)h#(w5a7R!FFocLP+KB=C
z5qr-797fkh7#9PP>8>BKzNFTf0<sVN=<nioJ$jUZa|(TB(}!Xbb_O=M9;RSRs%rGl
zKPJ7<{mgY6zh8{)k;a|q5H3?{Vo=;1{mI@<ahwbx<b(P>G?&-;b8zJKQjF;oDyZNk
z1_VcFAY(=%(5`6#7zH(jf-%tO5V3)RlNchzV+H-!Wl2O<aR&Psm)q+eH^R6K#tK9z
z2hSo0qfM-&=ucVMDoJ!?#Gm}+ajbIp#c+u);*p|hg^cmD*K&c|Fx^&B!r|?bA1>W{
z#pb4)_eO5C@amLLq?g?9RenE>j^s&hFpb{a;p>O4O|E$KiPLEu`S1`XM?W;WvrW!l
z=0XHtF?nCn_W|pdb>B{2F*zO4Z6{53g2P>X!a;-%Ea8aZh)9qNI0Tcdbe-JfJahJm
zHXCjh!Pm{eO<iY)xtAC1=0r5z>GGz!<1%)-XtfdIc9S1++4gxYR(=?N?3PP+Ab#OC
zS#cY0tm3}q#GQ?d-)>RXDO^_sIGSyfJ-mc1%x?g~%mv%smBK{p24&qDz%F^lGh73U
zn`E3eC)*}c(VwzsA?fT{W=pjjad~s+*2vn<GuPMWALaTS4?q7n_H_01V2r$E(i~lQ
zPv*zC0)vtFI3~-gsp3b(@Zvt=sMF1XP1Pa00oUM2(}jzT>frU?rYoR+PM1P<T<EcB
z`YW>K>2j^doin`9l%SAi#Yn9vt74C<0i;D~@~_1?R*by9U;Pjg#z?5NO#uS#+TdK$
zUi9NmQQWjMHd4#`mIDmA-M{6m6RC*{55&wi?60w%h--Lvy)q+%-AOG+uxH0DWds_M
zxizw&mmcZhY0bomDZ-cF0h%NBr;ooM;VX$lMv;60^Kh1i7G_877!Wn*BD>5G#yoR}
zgLj^M(UFd{=xQ1V&pbI^gXb(~Z7F6T&y0`oQiR#y7@y}Dma$@)SsTOrs4GUMz6~E;
zCQA+9S*AkDamm1JVBw64FYIKwL|j%5M^S_k4Md@+xX(<w700)7n0QzXmh&Vh8-x_(
zL=%dI`@+acMgdGv_#7f8JI4nk(_+@;)seAy;s2MbESsbhNOwyoa(PXLO>h+ti1Z;y
zP@eFDr9+0eAl%?Dz^}oEE1l3_4m3k2%$l^-1wuoi-R15y)XAQ@AMBgHPH^NIKT6Va
zWtsKf;aoZ+h-%Hs1Tj8chno_~;X`|!)PFGl#LUo0xyAhPYc?4iFQoZRK}3aJ8TlD-
z^STX)rw=5qPdWgc=Z}p-LO0mQ4FM@_j;sct&C8LF;PiZ131&;%!ojV`O?~=Dnaq(i
z+LQb;UYCq-k?sL9KM`4{E4t+9K7lN+<MqX8Kuw#2WF5|UIqNjlFK;UHOUP~+bmx3m
zgPI&xvWaG#M!;PrQQZLPNC~F!$tDT!{2?;=8+5Tm3UTnU=TfI*y{%mE1A7EV4)R=Z
z<mVFkR~tUWLBWa(xLlc)!M`uE1|lOwu3<zikx=>j#kB3rhXq@ReZ$D!kEED9Rw9iG
zQ{m8-Y13IRSuXuHFfxeYV*?`%7NkW=7<v;lrVOSXGtz$2ju{y&-S<W}l}w(Mo4f#&
z7`#WuMP%!q(=q#d+?58Nxv!h%UOA|H7(Z?0`ypGKKP0jxnPu&WENh_E%!hLHKy?X2
z<?e6d!M>&5VCuwrB&7WSxASHYWS$<A5Jp0i$_If9WIlM?kPtA4*V!fu%w6N9$GRnd
zy-r=a6jzhI{|FAn?Z~(7%;u_g*lt~47k#a=1kNelXr-iikvZV6hGlgVW#-oK-yhm4
z?s)U}>8*ULZn5RY0L4H$zo{j2kGlUK&4ga#?{W}DwzRg>i?HKGp{pwf(!$G@CO(9N
zE7O(oyzFtKK+B>mRUUVzgI{J8oxWGf8A6ZzEmC#F2Ls_}Npg?|$0-jDo!se=uvrFp
zJ8UZ<0b{IaZS(_hf%x+<ogk=ZXit@Ol@T;?k7V>cj4~5(f25uOy+c<1#?G8snRgEz
z5wt<COw)t7hYtpeYGOq{o+Tf|?hRw-f%rtFA`xA+gtz#io9vKo5exEmbnd_x)C>Bg
zCR$_g?REPrukI~Run$FYp3JgAc6|o3HR)Z0I~ugBvefB&aFKyapX!SyE0P{xq`sq&
zx~fc6wB3ruu|N$Xa|>;ir$}N#n<DE9Z<7<*d{60Mq!FTeSAWpL+Pk*r8*-9*LSBM<
z5U<kINV35|^4H8+TN3H~#B|GdYogGBvOOc@e$*%uO~OUC9x<a8nJr;>CfO62zj#{C
zf5$k3bI(L3lWD7!`$gsk&>36IM<mZ4?}B;SPfR2}6G0L}{v5G#ls0WV5(0p{!Vf-7
zZgGlN<-D2p?L@V^wK1qZ+-BK>i-g=6!4JTDi-^5vz_C_R+zN#XDy`1sA^M(31Y~BF
zIa9nYO!QWEnV;aRG=~jS;E9NXNw>0``x<S8_$qD@j4Y4chSkdoscPpOl&Vl%IZbrr
zsGmYD84jy>M<(2n)s2Cn>6*+7_E89$jt+PEbj((X%cHjx+SlY{@;yc5DK_fZZXrk5
z5GhTz6R)9N#Q-eDwiLfq+QW(g=dU?913^H080r{%6ZT2Q!(<+)6}6(^BW7rpLwgPt
zLZ+tzFK!oD8-pT1bZbAN<`N#vP%bAwVJM*T&;2~8-F#%B!=Kk=K5L@D_Og3|hRv(d
z6SPe~^1EmHJ-fLwhZXNdhI_YE{)H{F|FlJ(`G!1J#K|0X)M3P=S+lGw)|;(!w7CDU
zem+#Bk+iX*{8Q7qV!hc?y~VqA^|3|&S!G4}-tOy)^=7L@i?j81(PBO2&GVkjzSp{9
znN7jI8aLbU<MQLE!D;}0nV533GkbG)%kyJ<_A}UC-;>F@tt;l69s6z8`MYKNp(5T9
zINQD_lXzWMEH^v3kMV9fe;gxEiL6MIds$a3H#0n1ycy=7TZFeTD+19O^0CF)%<nDU
z4gZfV`p>E=0y%yW8%5U$*4lKb@YK?a$=%+#h4@8G<lEJR@09yx#p6!#pCwf!a;z)D
zAmrcKcU&CtD&(;}|JBZF1p2aCx?QVGuI&9+F=#()61=*hsq2dAc5U;X+|&2<D?~5y
zLlt=gRMr*u+qIByulq&O<A(O1byWn?^SUCO&T;EBy|lWAT8oL+RFPJqw5*7L0N!f7
z<D0L0uICL7OByQ@xt0}qy#@Q)JM<7)+#Xx>pJi1faxN=+LOC~X`07uWbdQ@2*K}S5
z#bZ&0(E-Sw>kZAwqAmZ~u8KtZvLd1naF^(7e!E<J++^_XWVM|WvZ@BRNM2O>^xv;8
z9~a!CEu{G9&a<p5_S;41wBU99{^<r)@1Hi^`u(FVzQ+5PZpdQs{bzdrh_qkczdGOJ
z`eNKJb|07Ce^pRTz_qMaVbipRbYc9|1}w>M+%BK1AD8*c*=PKA2mQFj_N%070FHGv
z`a+j!y6-pKj|<F;3RWc2*A?Noj_dMy#`97o<^q>X6}jYXU6C7M=Z6w`MB|p_aVfmT
zLluj5%d+BryY7FBBqtmI9$WOEbyWl+e&N5a2;V8X6THP46b=TD8^C|oR1rvB3%_>K
zUBQ<^rRRmW>oZpH>0ec7$IS!cO<%6bC*pDX{bxlLiL9rew=nRqc+2_{J{OPE??20|
zDCAsM<SOZ)2X?dY>3Euc{7gqZA?vdq-1Xogg2|bY#d7%1c2*S9*A?^40mZv|cS(7i
z9KV&mRFS?cZCx?T!Nppe++Chpa@Q7AXwyaSLj_(D?>wTx92jmikJG>7YMT}5e^b^K
z_nTAB+k7hTZaNPY>CMwsky0ivD=L0a=U4c3h8NJ|g7ea!6?w<LKEJ{rdH580H^al|
zaZ>yz_HAXUEL!L{Kc%-=Kf`nBaWed8l@*E5*!)zHeiL1rIQ{U9dZ<VTs=|swu64y4
zepZ;4C@-cS{vKY5<#So7+#I-kQtmEYkIUdcORCuA^0BO#Zw_KUDR-B#$7QJSaA8Fv
z$GRf@RSHErJlVq~?Qt3CaK?&NZ{n&Vc;MmShOW-YVsaRK$cprpYs-q|y!p?)brlyL
zb&r$do>3AJa>c95isiWZ=e=J{?+`9X4=uuV1tFL3$<?o}XSHiNpv*C}DzCLbIu0gj
zfpR5WYk`Qhfqx;oIwOn8@pY6LPp*n<TReRBrwvf98?u-j|5;bXu0Zf*MLPV+2nA=S
zaF~3kNWV%M4~gWp*{kd~_sh2e9Ks><adP};O%?fpNz01h7lwQ1TM-|bk!6olLl;F<
z13<Toht}>Mfp1-uhL7Mwd-OTg7m7$;f1xtx@1SS|uXZ@AK2FSu7EzIit}h=d(xFnC
zeMvWDH97D&MMWWN%^u9abgg}ht2&FJ^Pyryv7@4pYh5wlJa^x^a1LMI$I0=Z$x1F{
z{Yrs)*FA&1qqC>*<HY!nV4qNVWuwUCcxW(n=RO0E)#$36S&hKCs)k|HA=f*3cX584
z5dWEu0z!^u#Y6#Ise0vdLlzU`Khw3AkYibK^0xMw$y52U5}mkVTvd5xT?N$wJ*VGt
zZV6xN$4T*@B~}!&zFbO0W6Ae^*5$HyjSkhihPSH5w?M5OGq9MJes7Jyy0!i00{<4{
zZ@9oePKy6b>WGlOtO#n+xy5!v9$Vz6I$9+1ON)9N(9Lk@f1DJ&1y(_Cz;g@z78c-L
zy9Ww9PR5QsiHdt@Ys-pN{3SSmOoS?{1BfPLXGJ0FYo49UTWLz)uOD#^kCRg%#aNNZ
zv93sx9KGrL`6G_vp(4XA^rj10zv*;7o?7fTWHCAZvuLqM$68c0B1()1X0Rz%WMu}^
z<j8&|WNAMe-b7PSiTCstW%4*R_A6aR6Ik9wlQNPKD{t|iMhwg2#Q4t=Dh9GN(;B<u
zb^G@1`;Qoz$BE(B)++|G{Pr1*Bld`Yrb$Zr%lAF_gpw+D?V4r9d<*D#i)S=Kd>$%N
zam}jObOK&hOt*lcx0pmDgy?ZOM8<@QRVUz8#q+uaB)!E58X-!LlS4tsieXn+Ra7if
z$17#DpA)i}oS8xE{R-q-Ry_MHp31v=kFa{29FlFJqLAgCyE*IKPG`~8<>@RYho>_k
z>(iOh&P?%OZ_#T0_F5^Bj4!f~yma#*^$o+#-r}%{0JO)+;Q@ygX~AFK-42JpIh@VA
zdJk}WoSY6T0xJT^OE<FN@P}}@w>f1hcJATlh_37Qb1&p)`Ep#^x;6>FZ{*u+b9$KF
zsseq45*_czz^N#|=YiAG!-~5sJ*$dzL9>uS>*Otj@M$8Z6UlpuJ1nb8^%jiyRxr~q
zwn0TP$~G8rjZ52LhPww2U2jHzMD*k1lpMactk!91Usj_XDD$&Lk2b|tK2)UL=~6{r
zF0^&Uq-j4I=4ApF3&ABuH3BP_ii}JWaa9s~r!GaE!bg)T5?Kq^e(A!=Rpd<HJH?$o
zE=9t`vtrg2*Qz4&r7(*1tth03Ykgb_|5;W=BImMV?^Bd4dO87%sj*)bRwHn&tF>DM
zu6OeullwR^yZ}N)B1$RuP?6U1Q!VZ{<gp@c<4r9BDQR7?+#-m5ZtgL~k4wP|JXQo!
z)&c{uc8E~^F*(bMu^g<(VCSVvT<+->0PT}=4~c$U4*x2gs>oRC<#9D4rSmj7_mJzy
z<?wesmV>d{YkAtPTLAZ4LBA2w{kR<TXkf)GkA_u6_>dw%9FsF6i{+4$04fq$+F&A-
zTxTRr&iag`<<J>P$oh<=NOhebdj1jd{<s|eGo2rVtj`agSCaAbJ~y|3`p3n{O=Qe(
z#o^cG9mH_boP+b{i8<F5kJy!H@Q}yUvSPVS!@pr-{%$FVh!6XrBE39!%u6s0JT8IL
zx*k@6)CA?ZLb~x4_+;D}3?8T7rOBa+q&`@`LP&s1J_MhPJ43?b^f$QRv0{<0>9XQ3
z?f`3TB42oF$%fAg#e5=H6%fftrUOj<jnv_Jf$e8W6^X3vO6Gz}iikISxPvm{aj~06
z|D%$Zm(D=!2*@XV)^BVSkIU@8s;mZ}?W<~)wDCFuAY7lwqCNjvQ$-+cedr*|g%M}?
z0?b4jj|=WU>RyTEmRFV9jgrF`;7-!<xY+Ksda$C{J(kAqAmhkrEeJp!TXIRrR=mPu
zO!Y=1f_0vd)wZhcGLMQvmfkhyM{Pf=U+uQci<>rWD}*sbd2!QboVy4m!ON*-UfcXc
zoFbc_khRT^J~T~-1X5JD^(kQ@m}W&H>vICwqVZ|*HNO$MJZ>!eRZ}$w`ZBte5+39*
zw=K4GiHnWgRS`&Ex}Z|9QcZhHu>KMbB+?oMAO(%h@=8lQ*PY&9nQ0sP(iKOfIPFqJ
z(&Q|?zeIW6X&tEjPNws?+5A_u4hUFU2kL$!=6MJCOJBP22cu6`MIvj34WDAf;l1@W
zUI*p{T~J{)0@t$IK9LIHMN)b7;v%GxO))g}xe|CoX#Ma_eJ3z_e2utJtjKWOWeA3G
z1BnjlO;#V#BR#g(6m$6&r&3u~DiME-$!{~TY76nmsFoFuyr@>L8;O%Qcc*oFY|nqT
zPor~W>Bux_nkJH{Prbe0S)(4Rx#_v<6(`x$@(oX(6`aw-?^i+~-#VO_#8rx47L(P|
zw=*G%4fIx{Uh6mHu_9lvQx(aSwLIjGpUv!9qvG|0PwSx~X}5M&B(hw;)JT^=qf<g6
z@8IitT#6n0m=%dE&0J|OH}<bj#r^uh2lh~rv|&vZft*XtHi74xMtfh58Ch%q|5;Z>
zAm{RkmM+rqO2efaz`53N>3DER!xazOTElg^a+0IH=>Q*WX%E%FsU|xffn}WOh-3is
z+Itu*f`;uuEG3&U{5(ZIx`&^anab^LC*2#j+e0-n!11I-;98!vN@rF*Kfb$IKbJ0w
z_<)>riA4EYdi*k97YXQGvAI*yJ*rZk#_v!?a@nm9@cgn~x)$J<^;(9#>N|Q~sz|Q9
z^+g1u3@*BvGO0{Z>OE?GJEnpai7Xvkm89k3frh0;Oa2q;mR?#;hB*J;h<X(T;G>@I
z2|44VZ{8qlH7%$F{lqg<3qGEA$ofMi&4~b4`WDqqkQBZ}Fc`FjkFEL7+H{_C=A^W)
zSZ^eVZ-ur;vft<P>Nsm$hxQ@)6xSwkoX5el6vuH9FRf4G*U6P5SL4d*(%07s9BED>
zo#V=Eb-~mE{>O!Tb0)Re&S*yqT)$?T$VUqeCz_`zBFkvUSlTKxS-v5Q7P%)-QONO|
zg$*5}y$hw4t;?t2wxyN^q?sqv?S*&d%two%|E#Jako3z2K5smn-r}8^^RY$$S=jM_
zq+jfK*Ua<jCfFPC=c5JIf7MwHK+4N%`%EGVEB1^mtk_PLcBmrxNXxq7e&Z;8%NP=@
zrH?K8t9+^==}wnHet4h3f%=BAEI3gg?**Do0xNmBuPfynyQ<%H-1$}??>iEvfE9_X
z{Z9E#gJIHJyz#j{x9C61sz~Jg<x=5B4(qo^ce>ce+av$kbcF$A?Udw+VCm)mCbLnn
z(LUafWv3cMH2`^i|IeH;;RDvw53bvXijj5&6_u51?E{8jax&+7i+3*F#}@r(eQMG3
z(5$VAN+3p)8JMujG9*lVz6?MMg5RZqt{r0i_50%B0RHO=qzQJfIFSY~S~$fd{1zXV
z^9nz-K<eQg)9t0jr|P<~6Tjv75PZcCEs^C@M@b=T*HBPJfc@Ai_8an8k+jMBehXQD
zzx|q<<jQZemEG8uAF6?qSzcrWmV_TR4P<V9y8}uPIX_f!vS*ryQCxl&;adYj=(kK(
zVu*gIMjq+PY5>ae1?lz1HvN7v7i#cNKU5@5wH(2Tl(eqs!Ukm4Z_yTt-TI*#Sd}vm
zMFh&ytmzi@5^h6BzEfvERC5mN$!Q3r*1z}+9XA^8w_DLB<f$V0yR%#>#OS>Y&ZmWu
zG~aKT7=!rxp+)e6=X3I=^NMTTq+c_QxK(U7<grD3_{B*QjO0sB61w?0OZnSORWob(
zLnTt1!|7J#zN(aG{`0pP2ycYw57j`M9;*&u?S6BV8@c-1tb=#D^@oaNWtV4?khN#h
zQ77{Dw^`w4GWUl{WPHz>erBp%RN|iC>w2acc&x_lOgn~vrEoYpDd*p2_Y?p8!_V<D
zSIoH)l0Uol9LLOI|5ozMHC>RX@2jfqXld=APX2H@<p*8<Lpx;D*F0awdcNw|OuGMe
z<LiVxRwP@0Q$-*(tt+M*r~lid6ei@cB9j5ge~ZX3{#!^tPU`lz*;nsb1Rg3f*+5rC
zAa#Agge1qzN$~b)lL>jO$Ycf)R{*50;|fl4^n*5aSc7j#5FV<5DZkLzt=tJKl2%3x
zmGD<X#8COgU+v@vL;h++e(_g3ne<iB3|F}!PZgQyp~wWH)DP=uhVz>9LA*UiEr7@N
zkVc}MtQM(ISJn18*~HuJ&H+4DE6PEDYD`+Oyb`(6oXNuK9XI5$B2+|C@<mdNUjp!o
z5@o#2^cZO~9x5=i#*W$W((@VTVvY>)o$mXObQ}*AnYBZDp^)`G6e0nOyc*3AJt2=3
znH5A=F+zR`@uM&(unN!+9qB~=vSMT%*;SE9U)mEcJJ`Tx|27k3lpkA5$fUtaUhd2D
z+jZTto_GxMJrBx5YfP6C(d$HhiC#~)tSWD1gZ)J`L^>AHE(tl-6*HDOT0C#aV?}PY
zXpzV-Ei&7*T1@+o%rOrYnP4VOljF!QEyA);MWB<?4SB4{4BL!b3S>>$v-ew?8|OW^
zC%$>8$ox1lMk2qA@w}zcah{8NVx7OPsQf!>QOGYXUQ?PLXRDag_B^zfk@%gJyu9YJ
z1+fJZ0KJ@xV@4h;GINl);e@OSkYL263h<T@_ZOug5)%a%2az=w2Z)d67OxxfSdod3
zqD3OVv{-NXk(@8)o-yg6A`>e~nhIIU(~_9VozAGk#x*046`8n+mnwlQ-Ct?Z_ViB9
z_A{q@`s+%{3ALjV%Zs!5*dJ5ks5dQLkxA;It;9nYs{vRu31&)6W-`eAo~G)d8k1Qu
zlYxL`CWB0A$<W4<j~nt>kq7!q6`4J28BB>J??n*_C7(0!Sj{t=7cr><ScgB1PR;4M
zoI~uM!0VwRO+A;EkD0&Lw8EJ}LAfDHx*?Ahc{&m;pE8TBb3^1VQAnP&d_x{9UOeK9
zC+(8(T~>7CRLI^^XW*%tXF)59-XidesL$7wD(wxMQKU|LXv@AnMOiP9Z*86PqVTXL
zf^_f{Mq0LqiZ~u3(OU2nmR~5@OP(wR!`AYPmB6#Y1><A;%{ov@9NIudRIVHHSdkg$
zlt-Y%DREhm$F|djEGWa5X1hpc2O>O{hxgZFGO&R~^I6jkd8|lNSDh#@_2pYtJZ>5F
zz=1j;PZgDlPX`Vnzilm~aEnE!htV$--b(c+(r_WaY_aQ>5b*sX?QWz9d}xuG1obfy
zvW%0by1|5lZ>bxRg7BeY(FFi25?OKq#6FQuU5^{`SdnJYAi=HLa?6TE%fY>R-H^wM
z%(NIJxLq4yS+U;oF}{se`ktZjq2i(Zi)``G23S^Xw|tLp<ITQjfPAQkM3GrSN~t4%
z*#Hz$A|XRCWn`Fqs0bmL83h%oDc7`TI36-z<=Z&VZy78fDl*aKL}Sj>mrHk1vSl+J
z=G*A!?+G#=T4WwgQMM8(>&z6DH~74w8!Yno1e^~o^1fc8gUI?)upmM>t|1E|gd@S{
zL&c&NS+S_aWkotNz!*J}0o?M3K2)Q_1gR<sl$Gh5jP*=K`nG%u_vEAx6`8|Srw<|5
zx?;VhI(;*h>6HBRp(1mn(%UJJrMJ^a!N63iZ%Y;uiB%sexaWm(Vc6U+E8vuwMeK_}
zj7Zq}P?33E<E16CrV^ee!<QSmU6c;?ud8vY)5U5r_p4oU%&BGH%3Y&evyZLO8%?cw
zwIzLOJ8yYw-<F)`p2_y1Js9+Zd|D}R%le(WZh3LvmhtAEDfgj8Ce&3jPa^r31VsCk
zch~Cm8F;LQbiGa09LVdBN>8_(zHiHubkFkpP_fGOkrjdDwRVVngUA`|4NkzKJ^vL`
zM+jKvj&MJuL@%r2j!0>pHUL?Sm8JmYrGHfcQwmZYzb&KI1Uyz_hUA^q2&@x|Ri#mW
zTW+vOs{Byla4Oh_WLUmcRu$?kHS;@iDyJo<k8(Qi<n)Ow&ua==<dS0Q=l6>_BqJI0
zLq!}o_SnRy=Kh!TVsmO~Z}FaN`msg-nY0EXYd7byx=LMb?d7TbSjqEUM^>u~-pk8M
z$1NxJTPY?ZOZHz^R5ERSvV^R;=(X@V6CsUeWZ`~nk%_o}Y_)xTChF%cr}x`ag-*z0
zi%bT-PYdtJnqRq}>gvJlloPOM&*B8Hi`9~5X7!ezb3Sr!?UtbYu{Gl(WSmUoHD7*R
zI|BKllWhhbTVsxNr9{MeW<4c+ifXD#u{<G*_7vw-nPyUPPU~$pXKH_Y`r!$AtjHAa
zRTUkvNUl}I{gw#+9f_;2wOv9P<Yku-vKCCF`Mbocd>l9Au_EL7B2_k#bxwgJ-4fY*
zi}%#_k1hJol(<I7G7iJu9Sb|l`c51-WYMDMVZT%n$ko;rJx&#-h2vD|u|hM?Bv$Zf
z!({~o^q)F0ALk8uZV5lriJ8c?J~1DRq@|EQr}CmTkE~^-hRE7wB@jEGk+b-`A&b`h
zXCdB+taBD084KN}(ap%JMf+KvM(D^d6T^_)iq=?KwB$cY6n$2D&R)O-(WkDVm|6Z@
z-$N;nye^`Moa>vYk#+r)m1?jJpX<ZK$g_Uv+%ih%Y?=CeYxj1Z`SnpJ`hI*S=OZ3#
zN}nJ8^FO`*;&F(vJwrf{4}qSL<IT4K;e!$3Gh)~Hn?t*EA57H@p=^@~Ie4Bg_*;fJ
z!-E{69ovxINeHHDd(aYm-)h;xZ<~I^&%lfn4dg~D5&%7(ZEZo7!PW_&;A1M9oIp4L
zi!Ry>if4F#i$>5zixLkaax?-?EHa)p1AfRT2iZCD^i=V6=&4SN0mhK+263hEuKXp^
zShg*Y)VLv=L1`DXJE;nnAP|2o268mT7u<kPr#MV<=%jl7K)Blw2i~t~phQ0FfCpJo
zYhb15{sm4T&RrmE#3o^LUK6$A>{F)(1ir0)YD9swx%d72yCL?I8<D*~HJL;XO=h>!
z$;ID9&NKI(dY3J8bN-^Dt~#yMF-`0Tu?L}OEH!-^E&y#wAAX-UJCV;kZ@2OHsbL>(
zpEfEHt*8Ykso~9vN4pKKsaX;xwb-91-}a}IQ(fp-K+_7_jMQnz8g)+nv0=e-Z0`@a
zyL+7`pGeb#ozJLB_Skp5SIx<%ycv-6BG_x$i<USL&4Vv#ndV_U&*HYKM&MIhxVJ!X
z)64XtI+A199@E(H=77n)XAKeAMG%a4M>s@KOZ4o!3eXPjugV{JV<<RrP{=Ffuk49q
zuKw2Ko-}A=r|1+;q)Q9oRDItj?KhCdI{DjngF;$?VX%j^LeAwL;woxMEJwBWqf&Io
z=X>Xp1mH_DG-(SDWmjB33l_hEFAjr;fsAQDs3j14om)sfav5G)fZ-dJ+c`bh)}Wo7
zagZ{(X?P>loW?MoOQh&IPGfg!(w*Z9OnRFmPUm+_1GUL&p-6xiWd4nnxF)t~H-oq+
zP!(GUKO{nIhc;&*SOeGboEKQnF?PcP1t$UwX_!S+$)15T)L9xgK=$Uhu643wLF-fB
ze8NM)L0X&ELob2}poPf9d8UQP%s#(u>L7SKF<Eg65_9ELi?37EivIYbgfz|m-sIMz
zKUQL2U?6EBNs+Rzg(wAcO{?+lkO(y-XYw_uc$siAZB<=KScS@kH21a55DGXWxD`q2
zDEpL$Y(?J6Rx~fj2h&PydmO}D2v<_67Rm9bmf}IEC0XNy*e#Sjq!ns;njD|=tX&Pm
z18z_4{qZ8VG_q@eE!q*E;SjfAZERU9HO%6hbI@Wg$j~d9ODfk8xnSjL6uB_N_|^Uf
z$mck5U65k0g@On+u@)lN>GY5Q+%`VQyc@|03v|5P7`bK$o`ZoSIYOh#XvQ$o4rAaQ
zv};v5V+UDbWg>RB0~_6I<u6RF$yGv@HoZ#Its%QVCb~l;=|P`?Ze%(7)@6oK`sz8h
z1w_nTpo<!-3ZLWjIoMdxOpPQN4{^b62p-~`fmL$3<K$jLFf*M&l^E_$G%X?Ak!Y(*
z5cl&3W3^dVv)5{RiVsp}KxnvG-sgoWIpih&K{hY?w!wAQVCZ3IaM-L=OgqV{rI;cZ
zddqO@EzpcdnNxMx5aAm;iUrMZ(Lkg(Vt_U)<|axp|GST_MK^qKP3v`l4eQ(Pq5R7w
z@6iGIYVkzcK{-{MMvnt#<==f1S3jFL<O8ehg`E>?RUdHRt5y9VM>%I=%)$1`^6uxI
zS(aO70qN*q)8Z=Nh$8Rqar=W2Qf2MXxvNxG+z@5>Xpgdwuc$XLNtv_r2Be`SE=?2Z
zJU1+~WrZyovL_Os^Fi6E&?#Jyb+AgWB_CwX+Ol4QONN;b+WLaif+0J9Wba&l{Iica
z`Fwrr+MV=nj`*M{mYK*y;jRNAjePSL5UQ}8e(eq!O;H{|KdniV33arR8hNABL1Y6c
zehMKCumiqKQjT#5$u%T(f%aZQR2OD5(DXqoRN@Ci{Lv_Rs*Oup)&y}Ok^HQLpoUgh
zqzvOYlRb8E1G0M}2R6-AFRbAi96}_!`cy(9XFp)tZyKNB*+{5T_k61XT?xLhc7KmX
zXdv+8k0EFl1c=IUVTh$+;M)j|MnU+)F~Ex4ETD@n2bzUyP^2R}BXllQk^Q_f7$Xn7
zhu~Z<eR`<3Ds@-cIJ%l)YL<d;e6z1?q0}VjYmr!N_<k0O#pVf9Fw}P96%<oJ0gKZ>
z&<}9j<idQL^mQ3XL)r6>aMp2j$wkJ$hKrZNV8?+lMGYStX>vL&4PYqB;-naeO|67V
zgODo{ERC6gT%Fq-s&&r5Q<UgKvIH9W2Vu#&rxSG>g1wM1csOV=r_8rGuKAvzjDfa3
z0QMZRsw8P04YCSB4c~G`%wk_DuAW=AqKiNAz2oZO=8(U|={1)mVW7ZglE@V3?*m}(
zifgk<QdK~5HV}5sPP|3Oak386TdzQyM?Rqqkk6{r$5xnh2qo)mmg)%azJYLKU_%Uu
zons0)$t24hk>$r%px$Tl(G=!_aktnFkWFQl)Pj2dLHKuT<&4f*iLXY2?KYq4s|%bA
zk<^k>c(I>MBc=m?gTS#skd4TmrW|aAsVB1ZN}L7;rS7+Rzxt%HWQ&;(ZC<7llh(;J
zGUOwo1ML8~CtLz;S)POjS*wzD^+JY0nMW&56<K;HknLX0=1JNs&I*|xqvkj352>ud
z{w16%aZva`DEVs2&_F6wrHC8uzusFaynaU548gD~lM&8HMJ?>V%G{;0J=D_=Ch~zC
zNWybCGu}Il588N^np_ViwBvb~w4z23R&X4!WQW(S2EPFHP&!0x(NSk}z&9vdu9+>)
zk?arQP>|ds>pOyQ?9CvI1vwIw>ycpwk#cY#%uI(}i<tFoq{qWYh{*`DzCjiCb@7eS
zNq-<+jhXZ_2(2;Ks%#(?N^{1C3QPx)hS88cGe71As2Px1huwpWz^UVdpyXYXI`2o0
zO*sd@Ev&)2Rx~2mc(d##e(W#+<MFS<ma{&ZcJg5IP)00g`Rg*?KIfv9D{2|Sg)F{V
zhL(ziL~=MKC&56ta79T{scBb8d*w}KSVpArWW*L&#lIB^Ie^jT=8*4_tUU_dG3PH<
z@;$4sKC=vDe)Ts7QW=Cf&T1TM2~%2@S*OBoCeK&nz_DA$EK3hbvvblCQ)EjWsBW3c
z{Ql!mfHb^5U;YS=5n5zUT3pu}vy_2Kp)F-#gxYSeNCRsDv3LrGxU(Nz++7`sIy;8L
z>jm<C>oEuoot{%Jbp|uV6cxyAyg7vK;0L})I{OrgXmY%M5HIbl;pWk)3M?~I6{x6F
zH8^dMMY4b~eTz)bjLS4+=X2OStN`Min9_HI5F$IZ&(fi;U@FU@hOy`DP%z4zwnNP(
z+<O(sTb<I%p=Pn;$}vjzFBmqI)wmQT-Q^*!FzLH=DCee67pJ2uH8RHz5u2_r{=yGm
zqC_QG(?GEM5U^wj#t$1rlEuzR;QT?@N>Im>Ziow0#>=Yb=aa~<UXWXGWHP3C2FDhI
z&^lyjl6r<yOQz@b0KD;2;s%G3$gIsErGaoGM2dMnX2)ZEb~Xl@Mc#WxsSbn#E$R*j
zifg3A<EK3c{lO2sFFKEctS~1jb4V;{2xcPVASX|7gYY0s1(Vq8uDd{qo`2H#gAIUv
zVU%gT-~?sJ&bAYt!r8;Q+>&0~j!)_fH&;?;IC~JXNg5%}Kskk%OZk~=9#PNtTI>$D
z<gV^uNAA%1k~Gu;(|wY<iGxs1GM^$OEi3#0VM^NvLCH6b%&W*TJUs(JX45lprWw!J
zyy%V05Ahu#wHASWH^fUm1x|pvIplNTya1V=`vnJ<oMdkBF!Vc+_!E4=GV_beY?0y8
zl%yGFSdbIU7N9_w%WlaMYcqnx27pC{(r-v(JDi03Z?^eIU7hiTMy%c)z?iV`nWC}l
zRG7Qk;;MD^Cy*VZ;yOb6OidCiQ#wjthhA<7`b_EAv{aOiP1e>-X(+Yc<||4Rgff@s
zs)o2y6^G~qD|)VKnPs-ib#c=}lHV6}U?ASL>P3vEs3U=}BX}L5%?<>MQuytekR3na
zGG)y!-p`yhxq<jiMUu@wyFi=E1^wf)WsWfbjM2wOS=LZ;p|7)wD|}gDI|Ulv9r3%b
z#ES()KHUJ9syg35shW{pZR>s9**KSdSL0lE=#aPHG(H*jqfE&*SIhonyw(ZF{2Ov&
z5DjH)umIQ)HdMOQP9PjO>u}gU|LN4IS>;r_fpCo2s0qjO6gEkGl@0QxONWLO2z!jp
ziVqEtjS$-R-TIN-Q-Lx_H$V`LcLX9(PD?JK?f|>12XkfsG|dbhv+Px#8)}*cKDI_B
zA$@Mh2#;#LHC;7gKDek-AQ~keTw>b?<g+QS&je%N4e>|o@SHNv(?6kGH5lP<2zJFN
zA;9cY+EC<d;=SJwzDogkeI4v~*Q!}I`Z7Eee=hgA-P_Me*<1X^CvK;;;0{%7Izy`7
z>p<##^X`=;A7Rl(#7n_cV$(y)-#w(<N>VH1Avqo*gb%^{h+wH3GQHA!(yTO;IVTV;
zd(s1h%+hJ!so=~IMIk0}5`{w8QJ1=4nRH+S!iHUVj{qY{d?A$hHcLi-NQvJ}pbm&l
z`EHyM@9{wH!!mBoNmko~&ROWc9JvkDVv=qH9ms8<#szu%;0)mBK##v`>G;{w;T}DA
z=++boIBx(2S+vA=4+_o*tGRzy5wdj$G|QOM{`d3VW8PJb{fTPokPvogyxI033RfS4
zUplGK_gRM+Nc&NymH|t(K~Sy=8f{cO{2j3bX?QM?Dy0X@Sf%qc{D8_;L(`$uaZ`m_
z7l=72NLw7pUB5J>o_EAbSk%z-{LLANPmxx+Xqvbblr}R`CIxwOhz(zu1uBExO1O+x
zsY5a6+z*X!3r*cfd~qm97%h*mJOmhWI~I(%A=?T%I#`ZAo<K0dq{a)zV^_(yG7oc5
zLkvQ9xXMZ0VM9Dxa8arG;n=k~gx+vfclCy=x~nOy+Rk$p*J$UrN6>lc!I=N^;!z!?
zHvRi{Al?kZaU9csUOJ9r`p;9xaZL7k>X__v?IhoRK*waCXP5_s+-(5^p=|<ld!Dc-
zx+y}DZ?`fm6PWDt2r~(WaL_8^YWDy*ZoC}lp;2-kkFb+q+=r|-Fs~RHHy-3G1a|KE
zIbGesOLKN~$EBB1db2xRvM%cxUW>EIc*cbZ1imU3bVUP}esnir4TJ_Yu3nQp4Xf7>
z3?W{K0nwg@SL1B5sB!hG3~F3G`-W_^!Wn5ihQ&Fx`;c^M9dIK;`=8OdV*vctoHa~~
z=t~L9BKm?ml5}cHsqtRCoEwk~n>!zLH*5~X4Vx(VEL>Wavfb)a8;<&!#$L`g^{<Pw
zP4(-d>SrN>cns&3BJa}NW?6UfnA=}@v8_KR4WI8xQb)KLDXh#FA44lMJ`-nBN4UY0
zI>P0kz3$TF@3i=%goDMU_1ZP!sNz>qtm0R(w6KpjJ->&Ns{*4C!+1XszZipq!vOrs
zgZBP`R6M8P6L!S42c{G0f_bmNAi=nK81aAXj!PXS(J%<zIn^EC-N=|6Hz5OIcQ7>`
z_2^eBn45#w9IV3YAkGaA#=0`f3`+Eys11;JCTWzso=zGSv_su`F=BDL78_8)gD|Q?
z9pb2X*GzvKL-x3m+Z?j%v#izQ?Q_;*ndsD=A@i*mg4u!tCvF}yW3Y18n7ZFo`krUJ
zRL)wY#%^HCGcZ_}qD)qPM;h-|QO3<KO5UlW6@spq>BpIIb<Cm1?J|e1+hs}#&_fJ}
z3pn2{XGZ8S#~O3*#3gq2=o;K~V*-m>=2&>UT-E!cOLqvqgSLWPHH5-jcD{SOT&`L^
zcoOM4pTF6DK==`d$t&opHKoguj$#N}*}~(1ndx)p$;RVR<hH<oQbW*ohG&IuP<j(J
z4SPbcj3}W=-d8s*V}fT-(<IQtNXLeQ*VQ;BFhoN>AeoUBZjRmn(dXk}t)0#$YKaJ!
zmUq~lH^7Wg4X+lamN(>LwFb8w4r`Z#jil)Q!^0*sqCs9b`Jh;r&U@@$@`n0_+2Yj*
zv#@35z{?$OM)>#SVgw|^3keg|d4(-Sl)(k^Wn!Fb_)Rg+HT!MI2FT|{iY9{xvXs$I
zaV{;g^U~T>#?6t0=is&M=1gY)I_MUr0Uh*D!}9cl{tndN=-@98H6}zeuQqhdueqg&
z(dXapnKmNuVLSB{`mk~CDe1ig0e)#>833N8$RJ?WJoYZu`dNv7f9yS-hpw3WF0Vrl
zfX+j>GtYFm&(ceJWB=^+_P|=WNaF7eewXYU-A<)0Ag(r?C>2*5ewGHghoq*vO}?7B
z)7g}I03GAYPM-h<)#jqFJ{{wWzVkhtO_QGN-Ai!nMoz_CqzcgMT|TQHgiftiD)NNo
zwl3zhQdppqFDHrqp!!Vr;w3CO-Osb%CK~|PUA91fbbW>8kDm2Xn6wsIE5dC@zY2?R
zP)>R%9h5mcNp8)YL5M_m2Jnf8_F5`R?r5t|9eu;~q3e)+@TNw%>oz%DXZnxpTO|K+
z8P()1uFp~5&F`D16{Jkf;(#?|b`EDqZ1|5GQoT}znuRFYTx4@XkZe}|zk&ER;>Scl
zm!+Ux^oft|(BEC%xjDQK#7fwAjaGs}1BV>bc`=^hnttHl*}d|y6v&Zm2&6m0XU&)2
zCl=we;oZ-)vh@FFNUb6S5K?=2C9GJ3XQrYGJR5Yx9WcapL?&Q&wId=T*yUpiW?)Dy
z0v?E1UvOk@o$(J;w~_Q(F%=A`jj#&_)MgP)TR^R?-=z<I^BXJio-==UW{y7w*ybWh
zEO&mKD%<~0+Z*)ivfEl>^ZFHg=r^!a5+zZZ21qxM41(@<MnNXs=ocV39`p+uN&bC4
zk!vm0x3BL$$NRo#1NIU3R}!UCi4?g=GBJdbXfvF)s@hs5oL{NEE3x|#)xx^Th=aL6
zy735C3Z_&=)I>OK&&Rlr8D4as#bSIBPg)}O70#0ZwzaVb#_gQH=Etm%AjI3AsG$hA
zjX??*?gSR`wYH2+N~U10Q1}wVaTVcIJ7SD<UqW~;0;O_~!hE6dtD5-!rgND1{-(2-
z0Dnb!ZAwPG=}OcYb5svAIUSw7h~KSEhb=(=S7l+2*HiI#zAfnNDwf43YBPOeRRM9d
z_4KNkxHELVK%L<T3yuiA#^2;?l+%~N!Y9;^!NLp%tVop|;ez6azd*{Eh$mjz^U}l^
z>3I0b&8urb2L_>a0-+-4IQWr2p%(=_a)lC_(9W@ptAfgWphW#4RK_Bx?g%22BbxJ8
zzcu4M4}W=1H7WFrPH5+}hNx84GDa`gChfi73<;Dyy5EXW<r~C(qS0F1;puDVguVg)
zY&@bNW1ByQVi>OTC;7JgF;L7i?;{9?i11%^!7yVn!YJdzNPY{GF<Z|c;i339zGOyI
zG@i~3rf52yGsrqZsnPTdwJz#{;n|g4<of6wZYN$lkCewx_(&Hu+qr)0u$9ZV9&DwZ
zso!WKApNk#cyzIqq5JoPtqjz^#g^Xgj}L}(pQv}N61P?o7;ulh*^qpL`#4FAxo_$x
zyE!8<;(n-`jJPk-un`!}uk!~t0zc^_<eb$C=7>J886lGA0v2T|R{^#VBFE#HLOY}Q
zb>KEvvI3ra2rfT~60pyaO96z8>z8`VV3VGfmkXr5FS=>)?Bop1d=SnbFdf7hI3-|j
zYzAlTF>K956*xN(zaA9zkt^49gL{(L4o;;sH&2m{E(Vsdqm>6umo|(FSyV2P;+f#X
z)JHCvj#wOBSM54v5jlSnh492X*+epwp4!k4os!U)E|8eYq^KKaGT}xZ%4E{iQOz7F
zfOheeh9U?;%Z{hI$)$6&m^OyHn8D~u0>jY#)M3#M-gLe~q?~*+2=0gWe1VedDUFxE
zk%s&D38#oVcc0AWQ5nS3<p+WgJlT1kl%<aLP&_v;%F^1`W16|-OViB7T#sqyYOcpL
z@l8vEZA=q&pLy!W_CwmhNpys)1iTwwpGe%`OcO=rv@uE4tyx2V9SYHSlFsn4qN6;9
z&pce^FYGw8aPfq^QteT8sng_?nUIS8WiqOB@-g+4Qd~jX($)Q)qER9pRecPTS)`1u
zuon$`jFUN~WC(A}DrI`hOd=)SGAY>+cU1d08O5kiDx(-vH+=d@FyC_7)f8*SglOap
zI{G;0-l23{n^AP@Bu!&Rh%f?aXi~V>IeKTFM-4A6^APNG6GNS|?NH|7Id;2J&YjVv
zFfy8KjK^3#O?4V7x6443+LLk?BR3In5~vsmE8!;!6>i3;jqz9tCGWdAc<d^Fa0kL+
zFBRP38ap@9Z`(ti=BDzqLrBp1XJNh7D#@0+Te$Fya}*v5k3z!p#?c>fvl>So#64+9
z9XtfCEHiiwo^!ZKjdQA{A9~2Y3WDE{aWa4BxrRSTT*xrOxjdT44O0D_SfmujOY!<i
zuf>ly3cpy~zPvoTCIu;xc(dJ37Vy#woiy)+(`%P6i0z9Gq$jubSO!wg>L#=HWH#2@
z?a6Jh*3jA;(9c;R!s#LoK5z2ih!m5#a}T=?(?h^_dczXyc3RiR$-i1rpn6l(Ckgqs
z3QXcmih2l@ZpOm2G@knFX;Tv|$O@)6^`PL@T!p3xr(S$0T>8?7D7mVKk|Q(snp1xR
zN$%tq<z|LiIzJADsEwfHTG0yuQX&Rg@(2Ib`OSkemwpo;@VvDcxR*{Dst9DAy7q_y
z@q7dNHIGwWB;7@BT$`uNJsBPtsFcqHr066}gLs%94@!GH73ay6U-m%>{%kM$q?Or<
za791ljUe{uor3u?q$^=f*C!G_GdM8<9+lq+?8X~-g^{rxrt5<9AVG*QR&q*leNf2I
zKtggNr$oRC7*zg=OMVzU1Lp>2vn?kULTRsn)S(O9(dSYZ`O<YMe^6XMi6vMPF(fUi
zp2+kQ*gu>-@E0#_xd%n}EtZKmXZNA-?1p`5mG_p;#)9u=(bCzNFJG3<G+_pkvX^(l
zIVwZMtt#ZsgQTN8%S_bADNIT~@^;mS7L|v?st?^JHsY!e-63|}vWM<KN|h!MH^OBP
zZ94n;jmEj28YlZ1Z<=d#G>_^UD=KUS_1`7;(vu?fejofxp#jpXSCe|r_8C0B;H7&-
zEN_3P)v0+be$~9gtaDrLiHz3GE~nfdcQjIDwty*r^~WVGr#v3FQBlriFWM<9bk$qq
zagWQbIv(tha&B@1{n9wf%jX&oc49L=@5UsEnK&QUQ68D#dr?`$4g1l~S^L9=kaP5h
z#UNknLwh9YXpnjPU-M})2xjKfWDqZQ%ArR~!#Yajp~z-1(a*7IO!OmF8_uXTA7+i*
z6Gs{KXkp7_gPb`MdaU)ZF6A<;V_nKAuZMMMQy93BlwDjbV>@Un+N;3$4^Vo2)JUP-
z%I<T#p-Sg{eClESVqu=sKIa>%ecw9XSazs9W*H*-{WohV3g(@1xbyxfB18M$raVo4
zJ;yri&6rbt*!)(^NjgBwzaPtJ9D<DLNm7qC&67F9`Y@H|6m>^W6Kuo|9ZPAjZ)haz
z_OOB`=XQ*s$@n=iXPTfkiEFYlq6vMVqS-C&6}f>T4r=i?`PLh4-ucRpmW^7y_qmd@
zyp^eood4rOzOVr8!Aq`yob$+w`iYXf2uy->syq6NuWR9T9Z%4mA!PE6lshXm(a8cd
zD<jW-$ZxSJ^h;$Kzgrp?TpuhMb{^UhZqFx<ubxlHSASz|b>^}jYXr@~fs%b34@|D*
z)7O(r`R411rF5xUaQ|!)nMsB5ostXVPk$6TO8zeT2sY_B%xYKQ-w*i=Hs#$vwkgLy
z)^ckezkR{XbP#ve)S3^5avD0C(_MFMN=G}lh|Xm={Wit<liVQ3b&nFB_oCY}7vgy7
zD;7dt`kIrLH2`kQP2mqPK_0_BE5ohFpfS60v$aPkG7a=N8#V!;B6w;y#neSiw%i&t
zW~NGV+aHWdgg-u%5<0>@<>4+E_CZ<M2j3NHV-+3Q9eCIv$qOE*K+&Nc-jCgG>L%y=
zbin7Fi>~AFxJRu<bu;g09lqyd4@x{$b=67VN>IdLuGP~~9~-0S*zQ?`@gN(pT+(+t
zi)2dO1q@+R$V|g>$!QecmI&jeU!0{FkEgz2PWBkx^C^B-4GWPAa{Z8_#>#Qjqn=zj
zj`}<pPpw8mKMaw|C#|}b<EQVKs1EfWI_vvSa-KA=Ty*-_iH1Z9NmF1Wt2m!HLO6k}
z@b9q~tn>%JIdLJbP=2@^#MSu;7c_r!*@^Ol=g3ZUULP3{E?iKq%Q?_b=}rN{P`vdV
z>L~wxBHZ9uvT{!KC=$s~wLUn-<K{=L`4gB1kdi602=o5ii8{;5z}eA(L*;vOy?^L>
zCzK3XMXfy1T47PK@`P*UBo17wcE$SRnVuDR$LV+F*g&&}qsz(@yp{W&zt6Asfz!%8
ze<XmXI&_NV5?N*^;HhWPSn@UT7KO3}U@Z&F60cUfvLqxSCqsx_&RrUK&nmOBJg_*0
zm4niP`gJ0E;52(uQ1Q7)CZvS9>;&a>R)s%;04mpsunEtaop72CZK@u}7f^|If@R=r
zV{Qvj&@m9Pw-RRj_&|A(YiHG9GkTO5KxJcPJ0mF5lzJ_ylJu+|EfjH#W(r(EVqmM;
zXL%G<4tHBj?BHI3nz0j~GExCK;V5v)8N*Qqi_pvYk9@{<;!Q^066{2mq?gW4c*$V7
zc0((d(;m#mEz>Gh@^PxB{}43RPUuJ`Z&q@b9|F``<}<uViuIvEIZGfbO(I=?c7jKc
zMfy;#_)*O7pm0;asFDkV1>&37&kcNHM+P;B6Bh!np`Ex87OIvI7>4&jA%INX$iQ>)
zH!Hg#HaGN#6BdH9Lsr>Ez6^zh3;@{dM1lZSZ6^|Bmszedwg8oFjQK#ea?6+xBEs{9
zNN6Os+fIZB;NNy4JOB~5M}&v!noDrN7immwy5Z_}qBP)iv=gO4%)2oSYu2B7Yvy!y
z)DKpxr!jX7ye*eq3+2ckQ5TSC6-WPoJbQ#(3`~Y@x<Qdvb=Je3$n0031bb5Xch%~*
zAdBQ}p0JUWI#s7Xyo*7>JA|M@?qJ4Yn34-$^e?_Y<o)fLg+BO_Cl-#EhOA6{eb^&1
zV`6KZ$c%|itWeb~PhNGAV7cLp#85;_%ZDn5%9T5@80*87#hG48dxT-EZ~!w;T2f*a
z5Mu#hpmfq1<CDqP^gw+4b}T?}TiS`bKm|NIK^KTFvJ-THqP%7Y4~$YQOc$4w&Wv(s
z#~RoPz)UG&k3U~ZQ}_J)BRnc6Ab+P9rM~;|!9sy%MKY4r$WIss%IVk%!+^7t$@qRK
zbj<94+E`@VbR$6w+D`Mw@IBlyl{y`MIy(v1>8CSgWl#T~DQ`RKF(T(+w!JGS;SUDo
zT}fJeCb>KDmpIrTzriVfB0U_}l}$P^iOJrHs5GpOgkZWonUFCFk)<L?m{h}3yvIzM
z(%e_nRExxqU>QehCWmAwCI{!M!7a)p8&LsnQ#c9SnXE~tM?pF};U<pj&xtq5qMh$Q
z$*qz<xssGWLFi>#%Og={=QEzaV3;LtGK^yJu@~w@SmH)v5~V13XeX!zg%<4uwIDwC
zvJ=%3A-vIE>}FtoT$Yin$&7~RVdNA=%yBj`Fpg^l!gwCmCl1DOAutJCkG$HE+?35&
z_|wjFN_RGdP}_-;L6~(=xDjwzo33)G6&n=rg2UQ`xIxgj*+454R3>muQgU;GGI261
z*alT<nHctm{N0zG_#0nXs1uV3D=UgrL>t|3-aNm@IYnV0Rjmt#-kTzM;3H@H+oZ&6
zb^bZe2Hg(l9W7>3fN9iDl95#LO*uwjvCK%H3#9x7b5y_{X(yiuG<-YhLU4NXCs+Ii
z9p^wL{>@|}FhttP3sT6~BWprv-=?%61&lF60uOFs)n_3a%zwaRdom?NZmg3L1cty9
zTQs4u+e!9Ov9XRGGog^5Af#EbxlV2m9@8hc2ao9~ku?o(h{-)n{BWsK`?izqgQqr?
zn~OO(OwmjLFEB~;4`CO~KIi*jYUv+=RLI-F33-}4%1^QmXvcQ)b?}sa{w7uTw;$!3
zI7vNtN}sGAU4xyBDaMXY%9MN?C#?t1<&(Ih<7F^!2an|w`}+6^7yA5Yh{J`UxG8yn
zFUB3u)VA&9?HF1gE-Mb_4Ah!=FrPTC2^6-eU{R#a!HTjE=P-ORIE&FK4&LmQ>3L#;
zZ@tDAXz~&Q%V8>>6v>131e>hXNGD_`iVOgcpkU58dK;q}Ce&g+bbTP3(Wj>-`@t-6
zvNqViGmny;;Iz!OlxxM;wlwua!FuaOF3o&uq;#b<nZ*GPu?%7ZFyypy%8IdAaZ0u#
zB<aF2c_P}7u*wwChMZOp0uIS0t#<9rej?t08rhVSC#&Yb?9wm>+Z{u2rz1g^oj^Gx
z@j{Y+P;w(2O4Y~|%L^x?;_DU;#wJ}FxDq=dcfgjg=)jdE&YG#`ELtbkSq@#%iU~{c
zUdBD}B;~Nu#eqAqMl8$<>%+5|i*k_HK$w_nvjt_%HwrY}6AK80iM6UTeKn1JQrP9-
z9j)9c@=QD^C-Yohz~4v{-D3IsTLYhtJQ)l2{B~T>3ukAOQ4G)&J5h;%ro2-)@ZuDq
zwl+g6C#-wK3jOr0ofFi(Vr3PucS^3dT;fQP$buR_gfMxhq=Zn&B$6?{5pp4(5B=sR
z<PXT}O#8^{9zTdVd843(m4sFLjUv{#Tc!p+6pqZz0;Tkgg2M_IthKZ-Y;#$-qn2LD
zq2zpM30q6!oXne?Vx9s7l$>rhrFIc6<PYUj(GTGx@01C4*mHSr!5X7DRw6;(DLFDS
zO5Z%#lo0pkF=pKI0rJ55A|viy)$yTZ$INhBwK5134yZ>==_JOr_ZAjP^>Ki~_(aKX
z`Xs__?=5W9M>bpV`lRFsdvZG8U1J+2)YTDF&vrd_D5I%sc9hF^MuWcd=z5&rfa2#j
z?8tw^wm;ea_#wynJLNHargDa~JGrSTLJtKt_cw~M=QPBG6F65ow^A`ZbSQl2q-ma5
z#H3vG%Rb&|Y3BgjKqS90QTlUdz%lxyARWbvgeG`FizftjCsLNaQ*bsR<15{lk52*a
z%g5(Z&KZ0t=qD58(mDAYYUsly#ovZGXX}Hq@F{Z~Ki!JLZZipSna{>KYA4f;Pn~#t
zKnI)%TsWK;nf~w)E;<Mw2TwUC>7kVO!|U;zoa6QU5odG`+(YS4{+5<s1WG_KT<^n-
zC}JkrtGC8El(cj}8qgv5Y`+T>LlV3vrRbRCu~G|9dVHVtoXGgnDo^Co=Ex}{FRMj^
zCkc+i_owEke(T!<^$3SU;<iJrg!(Sg4P~^B&`;kW)r$)h?m~R?)gBrNU4f5IjZ31o
z_Bux~EXiqeNi>F5<c!1D0n;37OdJ);YI~?$bm5&AwK#~d`p_Q_iE11^WmKO#>L9&u
z?-Xg<xo^X{_SU2(%}v{-NOOzgz&e$aQM~Wb&5&lzZiY14L$OE4SCXjF;%lwrlXeY%
z+B<<Okz;$#kKckHB_E66Qu4V0{r!HC&b4f^NDP;SJHg2YH-c*oxDlpChMy76Gm(DC
zd6w5BtMlB!@K)!iI~d$xd9lRdRHyD>SbyC9!0S4<KQOy^?;QMkmad*$`t`hgg2KBe
zM$whn67WeM*0}@IiDjq8G%|<j;!KBCT()tx+voc?-Ba%r&KfI@c$vKBXBnmI)89GC
zL*XRxLacBcv}kL<ZHaEAV}791C@7e8m6-*v$f(BLur;NVD9jr9mQK5|S6W^0M&SOT
zLB-5=i9nUIHIuysXFU8o$4V0vbiua)-CyP&R`@!0BzkO)nagaex>?Mv$%sbvI(;n1
z-bI(nv8$y^g%$aJ$cF+`+z&cTu7|mf4w7Tiqd(-B{a%#!mMm|upTHkNTOyqw$J$8m
z#<57!yKxMe7kwFKkAiSCE^^JrF^GcOA%iG)-vCnc?MF0-o*&U5%EceDPD2``OW}H$
zf45WNn1|^_I3{E`4P<1divWh`3#9%qUen@F^EPbx$0SZ`{xO@w?w*Wcr6$MaLQPq~
zIpc|OIp0b9_l0II{wXI%N6#rI2Q5$j1uij|W?@J4!yN{&yc`*<2YH+$+>dmHT-?OR
zUBXX+brOH*!!e~`qapV=doF%&=?>yIyI(D4i7);5k9af$Mct-wFckx)>*iGcg}!(S
zwKsa-Pc7gAu)LjO!1TvIA0vw$Z8CVCA%j#zA(oC)j-pL|I~os<YmY)TD0gLrRkDL^
z0twG=@rSg4cM5%)ylpl5dQ`2f(buCA#B}wj78x|Tprpx|S|Z)0)NjpB4Pp~J_&l14
z9WDlOQp#z_+ZyXfZVFxW9WA=UIZHa|8zZZDF+Yyzth>A0&R*zr<{TUS;X}iwZ^Kx7
z_;~9%Avn-6#AiqSrqEH(3bI{{@jb#(kADj@fKRCt!oZK9^X%hYtc{O@O<<knXBR{G
z1+E28T?68fMV;UK8E-fU7KbKMg5{$rWMfmfz!Y2|dV_fFKya5*avGzwg!Vv@>_mG^
zbwj9$vzvDu35#(b_=yplk~5qFm2iJfL0&KjuH~j;!xMlPzRpPjcB&8SCma(;fLZ|c
zaBfq`AX@oQ(0r3HH=gEFU>i^KQ+t@FdBM5NSSUM{hL`X|+@L)0PibKu_*4-uR&h5a
znKi~fDG{wP(8;6%?yx37s8C}*6=Vn-1R$BzJH{Is)VqFwS(rd4FbiG|>j#-t)GMK5
zjn5D|2JVq-Y^(3cGj9woQet3ZBoT85Z-N2$#t9VR>39ZqVtJoGBBYMfBv2PB7$bm`
z?l^Z80e8me9>Mes;XT6f8Il_w^q+NNY^U^g<V}44(YzlpLPKgXQx0g`5jw&uS~p^@
zp#d=*N7zN{MAJ^q#>5=ok%>842pBa}*@<^uDU(3#C^uC5U|G^=kujC9W#|iVqLyJU
zRn=iT0j{hd+Y_v+EpZU8TrQY4iD=z~u1kBiiJ~<<l4tW9X|)Hi))2EHe6BHOLl|CT
z%tmEtCd<@crUdcUanQa|fS?AqI3R_5zN{ytnGe8QE<klqRwALnD<Py3RvqY%gXT75
z@j4jrP06=Q3Dwh>StVSM)C*YioFWdrDwAEN7q(O6UeO4$D<N+&aq(A@h^8ky3`n5t
zP&k5Qhr$smgF;R52$C1b{bi~}j}*>!YSA+YLH3S;!;3{olk|u<FeC#r71#($um`(?
zViHcV_W`S@ioHL613{!{1>M^R%mpy1UP-DMyn!!E(F!W4u6PAqycMs2YxWf+#(aRE
zLpb~(1_Z5)G13V<3ZrXy1dsA5WW|u{g=I;TlHoMEz9Nhv%-lGV7?Yq78)E>1ii{)v
z;1m>R{6U%8p~zWgr(F23M=+2L1}o}jhv0*^pBO`ku&EhqpdwC|u?DAlIAaY?t?<F1
z!&ByaAjD7y;$Vm&4n&3@oHE-x{6Gb@2UOG(tYr*9I5nyne{hOYBhlH346_V3$T+aB
zjxx+nM<)XiPT^+;Ae^$!gC>zvvKjf&EGoy@V89{oEjwo6R7)O=HALyXO~}2XV#tG`
zhOAmV7)Geu$Y2y9|BlHut;r*X5NiUtaO(ADXvE+D1>YY758H!(&!@O(j4RZE%@~U!
z*sl%770Rc_u!~a!buhM2C-z`$VV>AmP#8GMNien$>OUhfiVo~CPG~9G2uzc*k4$eT
z9@VmBL<F&_mz-wRat(%0>cHN?8byjb62WZ>-XkLqrI!yz9^$}a*rDvq4CW|0m>G0<
z4rWIXG5?O)l?NXT2Ck3a1c3{npRg5N-MYCBS75dHU|h8(kJk>(dE~$O7MKB|=rCp!
zqO@crsmpNhM@uhdGNPR7B;!kN*)SPja!dI|TDu54S3lWJgROKh`@}h%nQTI)L{wE_
zf#0M=_6ZsQFJoAWNI}`lbk7HajI}3&D_Uf3F;&LYCkEHSeNJrLyzZ&BOSR-a=XK8I
ziW~!rzj@C(U?bB|oa32kDEu*YCKymOlrdE1mKuvtncKCmnU_L#GX~GxLpGnmyc9a6
z{m!%wIRl2$+&Z8cN^{F><#)OlltIE=86?<>VToxsM%vswpHU(R=#2}co&XQDatUNH
zVl2+h6Z-L!!$#TwZ~h=ws6E(V<_@vJ#2rIj<od9_vE$Bo>!|hY0ZcGmg$`K;^xQgR
zov5I9QY@+rF^+T<@|hz+;z^QXhyuD;={ZTcjyh>QeA&v!Vhj|zb<8@`S5%!ej2&X$
zm*;N|0lyfUXYNRNA5qNeB%m>dA1OhNIkRBY$7<zzm&ei|JB+-1UK1sSPM8&=JQgP3
z5f58DK#S>l0?+3QlEuQAM&o{rA<C`a<ld6@i$JMc9wle84H+d+MQl^J`boKz2gwj!
zby6igDf~s`tW$m^%W7q7(M^jimnS)svA~%UI2mHJl;tTYYcUhl^@-HQu+l||J*JC#
z{AOj>w05&D+oJo!P2fVc@?T1z#n-_!Y)7X>92fzPpsXbfWKuFemOK^@ir7L{+2vvj
zYprwCk*{+3TWdVn+ch%QIYCV+$_{f(NOqVbg_{Kz-jg5g{HQ<1%6HZugXIhAk69uS
zpS0PGb|Z8)3HcJwSt$xzu`G&wHU!9R680(c+?~VnP{<22-{ocCdM8!(lkf5znM!l_
z){;)@sByi{;m9O+_86HI&KX&$*EtJWzhxPlYYNEyPSKq6?Vn@sPym#+thBi5W8iF`
zVRL`T7T`$R{YHu6c1z}A)OcLwu#zvVJXpz>1~v52rrO|4_9rv1DEDKa{8DAJjd9Q4
zJCi9=4|OK{JEtRa{hh<{P&jgD4#aa9BK_Z7kHO;Q&vnKk;fxh;daiRk98y=$@$#pv
z0S^k_3sS_-by}C=Ig*sQLZvo7C}*BX7OG*g&6Bw+d1w*;N%6DZ$o=V$aY)Jd6=UJi
z>5qPr0w<&+!J)FKJ}ETmqoC<LXO0Muq2r<cn{N7J=-92ZeeR|`9%5?Q+CLFaFR>M8
zyWX1T3r2;hX^&Ty6n&sbw}>dU>q$EL12QnqqeC1DH_Z58h2v;t9^V}HKYjd%t9<PL
z{>%UQQ4%=N8OsUpa7kPFzx>yaf4;VUe7~mh`Tt)}|BrvYUhUU^|2#iRh`x`$V{q!L
zzw+_dzg_>sKmYmu^Zgp?um61g?|=I1Kb7Wx`j`LyU;pX<`0M|C{ZD_rwh^t*SzmpQ
zvc|nTZ{zhJ|M-vp{^P&Bp4*-0|NfW1T?Jsz9%aw}_EC^hAlo^!U*tBE(R{(}pZ?eX
z{D1$`U;nS<a-yr39?)Ooy}tO{XS34&E}IoD4zihrsJ_Ex07}2)@_+kZ{++mNdnwyq
zLR+<r*FXGzt!nwZOw#^BCIhYU+B{D#fBR4XDfLLWetz=6h@Uh(5Uq9pqwCPN|L5zy
z_3!?v_dosjA3r|!ifDT+Zm%--8+-kuw^CkT$KPF&RAM>3R-e1=YkvQ3cWLqJNJzM+
zAKiCq*#E!+Y*VqncEf8^ZO_!--wS_k+6w<Tm%yIvjS$C57Z~O5zgRqmD$eIIm398|
zvCP+Zo?`yKuO4cdMpq9trq%uOp*&l;_>D*Hx7NPBWQP0SUwixh+PAd4oQbg>!j}_6
z5ufvvs``BS81OddF=1i9d<;oj&ST2r^5tU)qtNn~{ut~ZU;md_s=u@M>mOKu+{Vx3
zbUpuSayIk+r^iV6$z#Z$aUOGCLB4zpUas@lD8Diq0496`Y=83&1XAI5zJT)mH$e31
znVeF9d^x$AD*Jh?QiuQYF<2STV=_B_^;lfko{y36lgCg%fp6dxRQN~KmDe-H%S?sx
z{`+s><Np2|h|)FvagdYnlgXiI+j&e?+`fDac+B&dtzQ`p@d)R!I(}ue2sG3Bm--JY
zi)Zz>)9vq{Kp%f#|G%BcKR=Dj?0<R4i){Yn5r1sl;y>H81=$(TBdT)t<zq;-&$VXz
zo2y-RQt;o|>wn<9FQ^ZGCZ~eoUrr95>+_gg*<U_(w@;(p?H5La#X?WXg7MWu$OXjZ
zcLJBcwfeiv%kOOUKcMWuU9Wi!`-OP{Lif-Y9~1k1i5cqqLtw%Z^7Y9Sc9qA$1S9pA
z?}`J(s;|c||M-@F-TZ%N$Nv%S{@g)Gs1N1gS8t>Hmi}V%wf-9n@jGh3ci03#^{^>I
z`ARuOuFvzB2wy%1+s%1QgfAb1Iqp0r!k3Q~c(cxPhw_b=u)QWfe+l3DKnoBu4@O1#
zdWLpCFSf7eNcj4(K(0TYLi_87GOO_8DH6VZ%%9sNTi;mxvM~rhU;XdMrY*$Z7m<Xo
zC$<uU@OVy?FCVOkwm%OZ%GVD9T>5xWl&>E|jNIcvQNHmmb|EYO`MdazR>tza4^Bn-
zdWxCA^!cDDUq6VPXpaX)`TD_?cJs%BqI~%vt13K1gDBsU4KE#ZT3_v}xADCj3L?Ir
zhBW(?bDj}aj|WBh`ax9tcswY|*AF5~@#8^JzJ3td6(0|Z@}0M_eT??gxACnT3-VMw
zI2Gl~DK=y~c?fw?zJ3sZ*T;jReEp!=^Py;c{Xmx0emq0MH{QWEtgWBFgYU?S7EtR4
zn`nPMx$rwbpCaMw$L8~l$kvw+bQsUhLx=M9gUGV-cu<sYtbgD5#-FeMcQmD*iKU;M
zit_ao5rO!4P?WD9?Bmlhe<)u+2(a4YK~cVbaJEmP>`=b*Hg-<apTCViaL3Ul?ET8~
z<Ky#8es;_M<gXFon<mpz{%t%qrF?eTi1M=;X2z7qbF8KC^<$r$HYEJa{PD?cL&DD<
zdw1Nh{oR*v|J%53%01S*KSh+E&F{1SMwFkLlj`RYf60aOQkdrF5r4^vQ*J~JoOhux
zf^WWz9VPOwcy|(`NIv(Nq3RNTX}|gG$yvYT$yuL0IqR1^ISUa?=dn?K!TqpMu~BBG
zM)csfUc%ZM?eCmQf54KxK6`RV_{roxdvew<d2$wt?>(%f{tFI)380-Gn?l}w`Pe5<
z&irGZocV9#$(f%$IrEo1IkVg2k#0Zxd1PKW4<HfCmygu(c%Y7-{rt^qGyjO!X8zlF
zZ5(K1P09sN{?bT~WZCDj*?++y;J}5S$GrT?XrDbf{!5-5M@|U25?XuM>Hpz3;M<e)
zJ8$3*ocNBU0B3T_67c2ZkjwBqR{U4ID@go#9#i$zuO1snD1BTWDog(5WA1cC#2aAy
zn{Qxj1^i#}4n!^yj(H|G>{lj-BnjuSe*c1_Wqek7$1iET<1<QW{1QrOASO(2Krv$9
zdjs3I^E=<bAG!y8cJ90=Upq4L0{D3FP`+`s+htGE@>j~gvgxnXjNg2)`XK$(;{SXs
zo8PkezdrJj&bcq=_m}S+WVIx2`oZdh^b=#Veck{M(swNCJEy}h&GcK__0D*o=YBn;
zpV(vbzVUqYkiKId-I;jGugr9O$2^BJ><@Myq+hW>KA#ljJ2uFjE$x@)IlnVc6c%`L
zdq`hfmylZS@#ur}9sAPGWo17<g}$Ti(SY=1_K?2bxxbMlpAPLGAHV7SSLPja{_~#w
zj=;{j&Rr5GU-su||9^Yd4`0pr%bIl-+aBKeKzaP>|JCw*1<c>p=Ktq+<;p~OTZomt
z8D50fq-Og1rZYYX#fYZEu(PL-aeh~{qLb-NQ-W}Y>5NR83EG*??J_f#Xa>4zW&r1O
zh9JS8HXR{IGqD2G8G$q-0CGC9Kqx0P8SomEoB}gQO#=&jbJM^A<Ai3!u1&ws6A`95
z2ZMyNzE2R6uXGsgHu%_X@i`bRiNZc}sJLMk_6Z6G*}rE_keLVN97qY0)qA3ic_a73
z9GMLXm3wv*BZeb-4yN{)0~}Lno+*-NhWKAe*~i_cfTcuO?z?E-Suz%A4(e|xoihjX
z8%`uki|cE)Js$v9Ir<z-tT89pVtf#a<jhPRaU~_!mN^3FjJ0Jxz&WwD38<SB3(K(W
zi8NH35+=;KFf9fXWpSK2h<nSht{~v|vFC>h1t7+34#rNe8$2*U1tQrtA+Pc4#^N$T
zMHZyFf)Z?HJ(}H2u27I>4(6RkMVd{(s0DmhhM}zjR+*uBWdlQ2>?&lYK)m1_jD==I
z;T*iBBI<Asrl!ca#5oAIUWWIDz~`(f6K&+zf|=$;*^T!42h;hi27ZVPTMZ2H(_9S;
zee-i(G??7k*vxdIw^rVFXJ;0Om0^Oj6REmTDRy>#sVn!%CSc6Hk7j3#9z63eLN?;H
zB4yN%>jR;)n}Q*8C(q7L74f!HS9p|XnVsRr3)RYJM}f8-KO8M^<Y0l-YnOu!&qi{<
z%sAJYU;)X(G5~rv!BK_^&d%6igi&t-MnpLFreMgN@h0TqfXXSeGsOZ*r))xwy0EY+
z863gnv(s>bX!A|Ls0-6#z(Khoj5^Vm<-W-ovmul_e~@gI8#1U9qqr&g0+0c06Jl3&
zm2lZ47}Wm4pTy3xGYD4M#2aLhz|+?z#X?sNU9r;qWDCllY)VHv*R^USyQ0Zq4D+d)
zp<zD!NH;h&-$l_=jr*Kt>P_0b-QuKy6Q*+6l;q_GZ~1#f@)l&dn3+5=3CYN<G4kEc
zw!|6)6Vf(bN!n}Mmd4F3v?<vyWL0D2?54!tYKuc7d-JAn>@9L;n;JQ#)TVG82)M?q
z0R`n%Hl=VUI2d+yltQezRt{3EF<7=B|H{l{p*c$kvgVou1X*)VA_Q4;%>a_D4Gle0
zIB(MI{83I~XmH50HZ-jiXl-cdT*+&bFm|4Zn@}2m6Z@eJv|=wbCITqsj#dnM?Pl(V
z#w-AvVt53@Moyq;-~7eEGZ?hooM3R3xr%0M>Jvgx)pj-|8E@(pVz4Q(Z9yib8I@p4
z+5a-l15!}6K{h4!u?m%JN(w^N_1L7`7p8Gj6sjIYLE5Mpr6dZnO3hO>Y?ESoP@YR^
zyOI9_Q`CGnC7CMvaSo@%dj)yFrqc440(qyD`USyTQyKF&C0`S>;g?8CHkIpsxAQgK
znmpv5QrExkYth1SlgZSsa4CS>A(sPt4QVu$?Y$tC+f+r$66xV)L^oe(2O}!kSzu<F
zNP}KViZ<mdFUW^Cm5%%>1=7v*0hb8}h^yZTUL5^Gx~X_;DNx;~O28IWs+r0oUZPUX
zRNC;}j*k^tx(hN8P9~pEQq5=3YsHPss1lb7k*3_$r9z~k!tfQ8IC+(*x}b#2RBGyi
z3Nll9s0$K7P9~n-9YL%i&veNIlT($MHzD~$SbagB$|<MerlgQoap{5#m{WP5OSNd>
z1yqPRWq96{oDnO@ZA$Jb(?EGsQz7n6$oD9Li*%tA6}_({<$J4|Q^OQ0=LF%XT*?JS
zU#4YiUsH`raj6iEMzwfT@(mTu2eMJ#j!g;uV_M;`DH=^5G^)Ey%Pt@omFbv<)oC}c
z00rq@rwY%Ph~S<|WxU(DGxRkB4E&-*%W*YPO5#n5=_tAIro?pW(lC&mRbO}(YPqJ;
z3m2r-ok}QNP^slbK`WRS$e~2K-<f%UFA#$JIyDTge9HS<DuiU68U{kLvK4Qzx+a(s
za#pC|1@oH9>RT}PSzQC?`dqV8RWGj<+%1fX+|VxyS~)pt>IIpuCo1$@N!s6=g5(PJ
z%dGwJRI&z5yI73|SwNMiO~RRCkZ`rD*NWHI)GGuWllB%kack4k<2&1={Dpyi>EfAL
zeb%Ot={lzJZKx<Xm4LU%*DSp`GvfyVbAqT-mfV8+BiAN%5b_bu5K>IZZVL(z%v#j#
zh}PiR=WCcqc3V&<VYfNIfn}4Xjgkyg$!@Qb^&e)vHLznFK(U5YnM_(6lzbx30n6kq
zvp^$8osOx@vIUhvHbsww%U${~3Ukb&G~5N1IW~z4fJ>Wl%@#=GS)?QfOkgt6>=lGq
z*)lmcE^bOTTTq5$D%!4~=*BFR!dJ<vH?v5MMrgrgBG`fg8k>NQ+aAXAU-@z}+v^2V
z4+1zx(WOnnvY~F%reFj}z(PIv#TF!BBz7%XmujOCa8jUR?WT}z2*4s$xKRKqy=y@s
zu%P7HztqGjP*#B&IZH<?C#P&!1*+)GJguPQ9+0}6CGn=xv=&sWn9wh;B*lap{+_H$
z8E%k#MappN(IVF!r;GBa7AW}JHl3~Hvuee<z#(}CWF3iFWH{cG+^kicL)Mk5ks<3!
z)xZ#SrJ@zzj8y0bImaxj1w|vKvZxkZwKj$0=HY#95(kFxQ{vQuG7+;#&u+Nx70FbD
z!(E$%vm)v<Ol3ALxSGy;iDif~qBINcvzwr`f+)LjIOL^x-cqA+Z=T9xT2NVGDvRm0
zN%5ZVsj-ubP06u)GCFS^4juCBhWbtGz`SX9E@3>FH|@>^28XG9qy;q)rt*;%lqHxq
z3}H!%&qb+33tD^xx43(VH^{gfx^~CznzvMIm|^BE)w)BX-Ce^#rrljbg-pBV-8B@9
zoJbW~P*h+lRp_SVj9_!#gq%;8rJ=uWf47u#n7HN*+1eo#1y?B@7q?r2vv-)=m7%i$
zkGd)6v5CjP%7_M605b1ZP3i(O;Joz(!%{eJRuC*OCT<ExPN@fz*OipqP}HhXC}1l2
z=BDI^Vk>7T#rj3r-?VajY(l;;s?4YyFmHXF8C=MhH^KR>gER{O%v<_#horovAtV3)
zRAS9dNk(rSq^JP!BH;)9!<RJXo<ed{$a+f2P2s>uY3xfX^GGqdDHu7^_-_K{2XnbE
zKCpZ9G|*lk5!p8Mqs^8t8l}s~M>uM#Grpuj50oc#CB-aAlkbZva{3W`N%@7RVN=L!
z1$Ta-nVd-jMrwOsgPmG5$Yu%|R~pMr3HygDkL4!qKW++#HGuu3MQ2KSUs9qG!+vcN
zMs8U8uF+dguxs#!3F<>f9(P|yOGe&yU-*(Uce*c`sF5k%mrT@1i@qt~Wu&!XQ}D6F
ziMA>HNskse8Q5^LP$O0OrtnxD{%T6iMrQJ$U@09-38fl2!*`p*cvxpPg~K?eBh@>z
ze!nPEy^$i@l?8HBu=i!5&J;?nERdU!%PkW%GF3a$k(G47?k4Ri@X>Bk9uRQjZUV-E
zqt~ab)W{dTDYQ~YGU!df$VmRYDeN|8r1Xvjd76DvC3pD1d`c<L9LqjsrS`nt`IJhI
zbjhxij|JZI%cr#I$iBPV_%@MQ*OkAqAZe~o=AtdghwD?hXbbY(`lQ0`mi$TIMsnI0
z1+C;w=4hsV-6W2jqHa?-a*Gz%DRt3J!JujC+yokMk>m75LW>|=4jUIlSI)?SgrKgR
zk;UQa^C^uR={9{z>qaKb7bRNb^)D&Y$k4bc$g{dh$*GLbKEP;Gmjlc;w1QEYpM4~l
zV3WwZgLkRi?%1I+KLbeWN=>;b*|FBlu?GyTeE$;S?s)%H!+m0cRpX}V^+iD|KBXy*
z+7~#bM(rW>l(llVlZQf}!zLvo(v^LI5!s|Cq~1h+*G-6h2%Gd3lzewGN&~5~DL9(|
zSJ@PtGQg`iQUAN6<ilM`_k{FwD%~^h`<sA;*;zWHoqx~b#O~CTCj_5MQw9)aQ}P!U
z|HcX+ov6Dr0eZoUb(dC*m+vksH8zO5v(sE!qKvN~Ej+{}fLL=`sWTy}yHxAh08WSM
zJaOyX1TJkpz&;`MT#EFBOmj&_AWk*~_S;Ak>n`gvjto}>PQkh24$=8Kb=;)@PtU#X
zPSf*rESgNu69UX-d7cnqF3WSGQk+NErcCSr>c{|{xJyqC)QP(+&48V_pix)JgWsL%
z?p)wS>Ml|UyR#L1NZZXM#8;4THXu{6yX?qFXY4LJ@`Cho>ck-({a~O91n7%|R&E=a
zk%3Nezcp^bu923!3O2p8WFS;rNU8!v%8P<lyv-q{cx8*r4nT?zX~fVoTtKQ4nurgn
z!wZrQwJ`Rchx+m&#Sb9UhUDi;p(gND0Z7G%6ySwa=su(YBh|ML*^rSA{6&e@OQ;PA
zU|?B%u*7Wvn8k+-$Uw9BkO3KJ79Ucf6Vl?)%wl$F`gFmv%IcV*v}hz}_aU7a3EZ7X
ztKHFvCOd(28`6lOQ2U@l3^m+`^xx3Zub|*7hbHesw&n$CHe_pFkY+=+=7q8%n}o4K
znvJHlf-nOHtKb^qL#F1He=Tt8;4<TbDm3moE=*PdBE^Rk;6S9f097R+DOZrrL%F$9
zBd&K!ra@)5;@0TGOjX=0JugfbNby=3*|-T4Pi41|N`t26P03YLW%f<V2~cI;l-=#E
zp_2(8H@dCZD!00Y>>ALID{lGTmw2;ib<7X4s#DRe0HAnh@rR0XAe%zQa@BX>5?O<=
z>eO^AijjC%@rQ~cCf=upPhr)kM#mkjPfj2;HisqPwbd)IE#6(DH_Vb>Y`uH5@{FiJ
zu51c=g>!CGIH$bG1?sB8s^oo$(*eeYSRLSOXrUnTgsZBkjPs&I>m~4d7mK)`Dad$J
z^7h-ihK0oIUBg1+30PGV!s5MaRLAYN=VWnV>rF#LBKD@CArgDj$RQHD)Z+?l%8L}O
z1@29qE^HiArx1~ys&5U;=M@w(j~iX5!MVbM>Jjl+VPAE@t}2iyo03R^8b}oHRCFtl
zDBfvrt_4D|)84!(Ih)F}xE4r7fw5{LR=gLD4WZbfB3A%bycZ2#aA)d8qeE2oqR}hn
z$j`r`2ATI;Pr+vA3dE`jG4XzjLCCtc#33$mZIMGrx+WWQMKv}DB&(Jd|K=bNc5R6_
z2)nj4F1CfYseu`$I5}{tf-Z>Gro@`JiE$z7SnN1SdxmXlY~10RYaob2LAENY{W)qv
zUr9=Cs0P<WsCXNXr()-|A^srT+5mqPWNnC@kYtUTafN%!Th};{Wvy$V87&l|ss$Ib
z)-lS&>gp3Okai9B<%;D0n*cXt&3clqbe<KU7H>_{$rtDXTvZ@eyir@O73Gs%fT@~(
zN^i6}SJdO&6flTT@J&euYf8Xow0~C=1NBCox>g9mMxDCC&+4seY{<ZLx?LdkAaLxI
zvfe7khUKzR5wCCxd&^ek6pIE<+h!{o7pBWr*eT?u&{q{07H_gOSEQo!cB>x?W^XMW
z1ZBI$J_IGfR#%Xc-CJWpP_`Sb&8;o54<Ttw<2Gox%Gz52a&bYjDnKrqf@28Xa#Y;=
zEYEvj4&0{3g&4J|aXX@ZseRXkEo{R6>6Mh&2{tusem<MRp+`=Ujhvo7`8qf~Sf^|C
zXs|<wQgd~PyQ9!s6~GR+!CQF+`onFg*JOTZHn4u$&>}*Z0zDA#57Ja9uL_{crf~F-
zrq(qhTrjP3Xn;XCg@dnXabO5s;lws2nWJ7^QHp$1QZh!x^W6j+2FYkNPFGY?-;`to
zrPp2Pt*ZjavPt=q6pKddbOnlKQ?LR+v1|&5rd%{ha@4AK;kl|+EG6`D!;R6ZhKd`b
zRa&4nA*Up%jqY~jIgTEKm^A6%K%#k0Wp7h^2|<;WuLdD#G)`|y?kFhVhWnn7S2b~V
zSCA@yGw}?LCgAnFF7XB-SeM358CaJ@hQYKcIM$}b*Ue(?74R3YQqt{pBdk);4dz#`
z($KMmU2v?5uf?l0Yk*r^SgK741GB40`X+TeM)n{Ut7~x}7FiX&+KdL}1<nEwFjd7_
z;i{2daiDApM}<(V($Rq}^(q}5Fd1h}^a_xSSE=X#$#|r{r~t@#?K<THA+re_7k9=g
zc?~>_3#C<ohjARK`;@?e@5x8vbG=G51H$X7nqC3(-4yl;yXz)_`v!qo8(O<lspNpj
zIPqB(2pO*mj;O%Mcr^`-Yo$W+Ysy-$($OJ~Ulg?RcoxR1LZmw@p;t)#O~7H*4D*wg
z-ts`XTxHHTsmD+7Z8r$iDwQ0%jI+#nO$dyi8s?jl+)CSqO60YuV~9%?G2fKrm{984
zdbG$t#HGrWS3qT4$gc{x%%*T;-aM<6_yo*&kq!@K(pjIpLf_m34xR#YL&$Q9FL}rk
z;}s|u7w)S9<gzLJMGQH`18mhN??!Eqbi#C1Xysm9{X)>8^mh%--izwWZUWPJZ~;=C
zaG}0xOjUY%!=<r63Fp1VRl&RF-Np&?s)0&zRNt-$d2yk$Do`q3XsoV1C79}DZ$fMl
zRno4w(Yf$fH7|Xe0IXca#c-3r3GQ{OiCq!v<En{W5e&2`z{=H#7jnV0Du63qs9yuO
zvI*=ruYyJDb;4GzAmQ`x5MruLT@hF1g{|F1dHg<CuE=E5A;C(~DnNpjqUD7IV=d}U
zsM#?OKbSAP6#PBDzH)11h_fP18g`OR;lSgHCP#&dQ<$s@9E(S(=?V;s-%^_s!{YZk
zv%?ioWuz-WEPhLCPMeXdjPxcL9s*colX^adA7m~XDbBD<Il))8&uHLd?h~?E<)Nb(
z+Fo~+hpxc7xXMFU1R=gCXvOU0bgDqU_)Vo5z!z6-=nCMAt2T56?#0s<m9q;0cuTh?
z_(hq$D#0%|ZPs<%(aLeh4QqjFJa1C+E}eO#M7*Uk4@g9nd9EW*>&sc^xx%38x76e?
zxw^1g6-L=j;XsgqcPDV7!n*4!<y;Xp>n!D50f)JzYZDFwNLL*cf~w?P35dCy#;%x?
zH1c710~FDNLQqJsO6<xl@e1t9EybDGmAgJ3$~{>jA_nA{$|cv4UEpjW*hQt1E3q!B
zlw3#Wo0P2^q1t}K){RJRzolyrh%=(PD&oQYRv7Un#e`(*9<Zg}P`3$p5sa(C^)gh~
z_^Roj8Ny&ypjS49Po-2Fi;6RX>W4Cg)vO$U1&Q;X$P*=18AafSiWJw8f9E)PI*i3i
zofTfLv8Gl$51Fx~Zlf~$5H71G24-Zf;`kf^a2YHyT!C*HDluFG-ZG-Va7DfFv7{6`
zG^4?^pA{JvhA>tYIT&6Pw1NrQu93rGq-!dsha%WRg@bFBv<?bBP86peDjZw`>N3_*
zlYw;^tK-iz)=Z{r_-Ho;ZvtN2vGi$r1{IAZUD}!FtD%+ePKvU(Xyq4(0>J~tq^>0O
zAdu|_E~OE}@jasSZ$-`9Av9KXKtl&>|JHDwN1JS?kQ_@2F#s$>wSOyWrH)nU{@tXU
zjg({`ua*>KAYBG4{Z`;yhARD5M}*%dap-{!Ae(i9U4}qj6%d0>;lPNH9jep2NzAZ@
z<G^RM_(+Pgp%T5D670=I`@W~>8>-Q}DZw4^S~am6yQx8PgH9T;uL^j}CUNZi<CrpH
zdv>rXSgSq2m{O!2m+~>8NqednV-h1>=N&C95{kTzDOG#kn4c4qTY*~HBtBNan!f1(
zsf;P}^~@7^QxM(9inIe2dv`lt(3Iwk6f1-1tePoShAQ~h1iS1B%AySf(WY?h%)T~>
znU3<fvE0zXr(r^!XtXG@8#AI&dm7fdYix@t%A^eh%$Q9lJP<HLK&}dS%b2ohC%`2r
zI3i|`7N0<n!zSTK1d41^z+C@JK10?zR$KZuR%1*>0JG}xn6hVMUB|2%eB^@5o(<^S
z$TtzMF%24HN;CsYGbUR(KPm3hqs2ktM%*M0;`oB}HDf=HDUCa7N(X_grZBsPP+6PQ
z@zm)jS(EV^^{ro&XubZ1Z{+%+>e!paVIdX;$ErZqYzl{kSo9^OG~qRy!eR3Oc~N!?
z2h4Ek;6T<4!n!J9rNgC&2ef9mv~VD2UX*AR@UAN|4#!QwQI&^mWQNT3!8yDsU=-){
z5M-+YZ95V@7}En(W;k`|K*|i4Wg1AC;j&BvC^KA2_JRj-2-{VGpV<@+9$S96v~1vK
zhEvH#j+f!e^-%$z87|QdxbqN1tS-n%mt0<ukqH31qA*H~Ep2!~1iI|gP$xD8+&}`l
z)Z+zP-6rKvM*N$6K>oRm)4;+EmvI^h^x=w=sKCbzmyW##*q4sIAORibYG_~sdQMEy
zbBa>Bmt%_hx)(&COJfF7e-QJv344PLmw|dgz_|?6$k{R+8Z%P13_-doATpZ*ofMk#
zrjVJ1q@glUBkEyOQ1AS{qm|>@jr2W3K(9@T<z(61O~~A&v`$-MX2zh_ZNSWoF^Q`&
zz-ETPUWS{<7_P@4;{?_++-S<Z<Rq{RQVG%x7E{T3k*Fwb(#Qv)DQ!w*S6_vuc*7km
zX!)DmL_sickUK3%1&rr*3=(dgn--nlVj#D4lCab%?}C)WHO@|`cuN#bkT_gk2a|*a
zkCgojy>xIWjp;JnnS)mOD?Fq=z~DTuEyZAvW;(<S@m4|OCK+HGdebHZ&yzPM1HvXq
zDG3b_n;?;e6ooI+*#apKgT!U?Y(g_K7%zgxJ?hv1gvT4qB0=G3o*N*ur(GcB29PRd
z_vGY;HtNLmhQ^zm-k?sjX_((250i80n%>GLxA)>yI<JHV<5bW%+~V}Q7I<-foue&G
zPjPDoJkF-=CcrqaCU0N{L{5+}TR?Jx1i!rnC?_Zw9;lokRdzo4SPDl&sOF1gr>8=`
z>7uX<`V30SIzwP+kl0rx?-r|6D!Hs;y#581EK)>m0+_5Ct8#}|dK3(1*PwAU<0hzR
z<_0KQH{%A#<K+qx-hUAThM5(O-?-idP0WJl#$^D~1dZ%;jL(~v!5&_2VdD+pnjoc*
z!^+4emvvybIWJP1l$*_$x*oBNJ`YC&>qvELQ*s%lZW)aJLE>Z`GjU;pECa@aL>3%}
zfIEA4Y$bQ~KC_vBPXYQO3_dZjVVw9M1B50>9fVwZLFFxj^wAU9SzN}U6<Op^-*H)F
zk@qO8_myohP;ahw-lH}FYfZJv;BE>M#!sIVy28noUaJ>{w<&}7D@YxL+)3Wl`4(zd
zP%3|eS7c(kl1UTam24WiMvA4N;QOx>uf*Y7g?JSX-zuf6p!mD8TnNmdkp&7^sbW?s
zV4YVjt0`Z-iUUhA9yG9E+?7>4P~<9`zf}rdFJhsE4izLECP3T-3B5PI@}k~5_t>r8
z5z7=b92PZ2uK@a+fDh`{bSQfL=6J}f86*x!$s4eJtB|{b?OUbX9ZNGwsdWX73{dcn
zB?c&XrRP=877n3Gu{%<B0+sV>PmNA7e3ZOOIXtEYM*{9ULH*eoh39ZRImx3=fr=*1
zvr6eXoCY+jl%B)U1V=+mQgRNS9u<;v48|~7rQ{sEl9^F@3c7Db={aa?HKX(#BRaB_
zoWkx~=Ko1j4sVp4gJ>bMl1&Z`BX7_+5QVGI`v$<xi`2v+#pIydVv}O8kM?*jx1*{>
zn^8^@q;E!%I3&1{?<q()bIiz<X*}b4n+Akj6ujRIiF<>F0UOs_0^KM*0rB4iOs|TA
zmZ#pRVxZv+7`zG?MXXT%1`JM+$R)0#FPc7Y8`;FcVU(!jR!4&@LCLq2r{k#jMtM4<
z;~NF)(6??BsC{X43e@z`U7*Dopr8OtP*0LN2>EgKrB$NPRb+q}rLIB)EUHN<F2DfW
z2~r0kUu{>)88eFFE;Zj4*_N7b3tUUfw?(d9_cNm`?$Y#)vbYnCWJX!chyZJMwn|$3
ztx*(rA``4p7<Xy@jl#G~^GBw=AW?&D5XK4~Fu;9+1O^KBZl^8Q8YOmDzGQ0@+6pAF
zK>a+5l^IYzLE?CLB*wa|QHFOZ42?3pcQlh_8d^66EK8+tlFePmN26@+QtBIJbA%39
zOS!Db0c*VXb_MNOqhRhP1}K=jj*~{gtbhV*xD0p2&RXMbI6?{x;Gb8sii3vP>SloI
zI!WT5pbYL(>KkP+BLb{JzzXbdjRLlp!xC?{oj<`Al`)`Exb~Ypd$w@0HAt|aaXlzt
zmAT#;1#H*dpgHHE%RzH$4h$Ty##?P$8WOkKwlpAbwM|!s2KQ;ua8@;n*d|TCQOq`a
zPOL$wwkft2&v@bgty8ErD*v4_RR!2K34GxK&~I_YtdCJbn9qUHPQlt}owXcmX!ycq
zS15sX3RXl8Sm%|s>Eh6FWmPPJC3*-waWLLl6;NQEa<xg}@4S90Aiz4H_b-|>etZ-`
zBBvC#3KOtSVcT#oh*ZkxiOd_mhQ^CQr>JdBEKt-o69+9NSkTBqi_gF5_5j#Xkk~h7
ztjj~9j?fV}phRxEK6G4q6?9;oH{7P1LWj>fXgFGMm<EX>4o;AFg`QHm=?;(uU$3O$
z+~}0bt*CQK<yO==r7{B!ECdm{;%q3Cn{<gzvD|c1=oHI}La>AzT}dMo=!gtV2!O`B
z0}w|+!8rlQ(Y0x4=T1>5f+gxGC>(rZwhBeCPGN3KrmqfZu3!Y~l;(;^uufra(e>Ce
z+H@&k-uR&5R2h`fiZ-x88Le;w8<f$;riTJ(G9nMkXVc|kP(YhbnLz<<E(QvByuuS~
zq<~g*f+4~FCZU<T&vfG$Xr^1q2BfhKw7{IM2!mE=1{7>c&o;Tx?bmc87?iT68^NHI
zwWiJ~Wv#Ju-hLH(V1q)|n%06<Kuy}gfS@(qErxEt3_-9#OSGAK&-<`R@(;>lMIqQ2
zWQzBJLCI_S`UeFsLJVwpHaLA=S*;LAw`t%<pZ@UVN0)&?nQDdoa%qdSc(^Ts#_3ba
znl2FoQr7g@58i9{)$jrZTjtjE@dI|uo34TnZ19F!msoO2Q$`Y4S`&hR=bXY+;RFW5
zM38u`aEj9^v%gcER;d4uXK)N<7K0=~HBEF<k~luatKt&ODPXH^0}cUO&t<@A6jo${
zIWN2nL@?)lx617AX%?=>>hHYoRtbHlTvkYexn+}M8E1D){!W?9kc3UaR3!2pm)$BI
z-zk8r5Lf0D!Btj&rwCSXf;sQIl~#XG0bIMZQKtmf4=^(s{hb%$Dx<$s{?=pkcL?CB
zD}vMNtS|<1-kT$6!Qgp*HH|O<gKafvoEk653REypfvh+MbKa8cQU09*Ibs#eDS4|@
zeaCfJp$VG;rYpnP%qe<n)o>KOidWbqZ20UbI?-*xCnXl670fAit6TuiJ9Cu}0I6q!
z#K9*uqMB_ASw%3I^OjpB(&wE`95s`-+_H4qO^Q&4AK1k8wMbS^ipL@qe^NZA75xG&
zUt^(Xz$Wjnj8@o`T-YMVz@&WK@e1r|@-duu6HSg!hi>7uVA9}>c!m8IC$FMK3jIt$
zS@dB~UPp^O1Cw$xJRQ*yWnz&&kGxSq;`%l+rEhyaYIyVHoREq|o`A{gC!!i`(r#Sj
z37B-^mM%y4r06WV8O#)&Mc0B!_iTZ}KWQQ^O>$x48q3fIo4k(}DelwB6BKvg*Mh(U
zZ&G+Nm|;_Tw#gx7r=l5bQhKKMjXi;HN%KkRS)|HONY5foe)5i5Dh*eYwqu1x*rbdt
zGW$;o*&?|=@e7{8lebs~KiH(LxJZ$oxYrhR!D&E;zdme1<|^7@Q^2%z_C=XnsIxCh
z+@canwkUEV48qoaKrs-uC~$8n?27_dQ4p3e&?{*iof21(5Vjz3Zz=4H0{70YQ>}Vw
z){2F&MFD)v;J+w=Z|U|cC9nb_Eb&fP(l~y_R236pi{kZ`-oAL{RoH_q-f(Z}=!*hY
zaSpa9UvEbfj7v*jy52I@!Bz^_duS}m)?03YMfs|Dh)u$2e#<YgC}8h_X6zBgL)fBh
zWjur-yJb*-)v`>186=L+tL?3ez@ostbrDz;oVRj-*y2@IK@PScJr&Ymi_-I!Z(vb)
z-o`7<qVT+><Sz=(8|Mjo;ZVG^0$>wg4&~=9SHXtlZ-P7pi_-Jv#Q@0upind{UR-b7
z3>GEoEl<J1tyM7;ws=Lo&wXLh;H<!jcJmT?Q_XKTFQE#0Xg37yee=+3Hzn;&cR{-;
zX%QRIGO!}r$>*jRpMq%Ew9d!!U~0&`yVep1DQDMO;yhab;I=zeowXLmPHkwdrLj{G
zFGg52;HuVI8aGq7EX7<jywSBLy3Loq6j0HCgj&nRSpzFl_%|uJp}ya8^9F?-HL&C4
zFQo5c_{0^Iz36KV@t2>)rc6w;gJWv{4FIZ5iNUWR^&oKU6!43Y7Y*>KwT9NFW1b^g
zBh7kCu@^0oQ)_jNJMb1eI~`!3pLav3){AnXxqE0@BnMkfj5_$D*1jppS7WS31MX=>
zR7Fe3(^61H1LA2d6Q_B;uVoq;*`d~=R^K2hmZB}%y`sgrEWCC@E8n<a*bUI9P2#u<
zubdiwL;2UGSc?WZyE3oc1yZsLWxbVbfGxx~uEiW74O!)16tv>pTtfIYK$$j$J?7q{
zRlfnpv=l+n0Atz|z>hX5_uj3MEA}2$`v#3@DX?NwVxLTceHubVmjWwVv1oDVT=XTB
z;HCt7bLxqf>iz<<uZ32*6z|XwQoE*$k(7UHI#(fe(>2eR4E=RYN3UteTGPc!%Cn`Q
ziA@=J2KhiYX|L}b8oOfxRQDSc_=Tv6hB)J;sEJM4r_~%9Xkbc1lN^{5_54;G>)-X1
zW3MaXp_Sc96DJd#&^F(2+gY=Lw;5|IHN7Fkdl6IDQ2k@gcE-Tsnpj&{TVq1xmX$`<
zG>x2!-<pPz7p6m#d;`R3F=nDA!08GK#;*6PMWw#s8oDW%G4M@Gh`ff|>zb92#D?N4
zYZi4>l3QM^HzBz#>ZgF;{QoOS$uQ0E4L9>m$tl!qkbB6wS<s5_Z_Qi7LewdUqQQo+
z6h+Yz<h16kK~pce*1S1tsxC|Dy#|2OiWrIpY}4|kf%jWku1MyFL_?dzaq}GB6b{_7
zg{6n|R0Ks!3(d7jXl}-Rsz*pgq4gTTOv|Twg;b=aBT32qL~D2Inh7MLyOt0lQAoZ<
zSkoqP<dm07ffg<8X-jby4Y;Nk1+927K6Jd-krRaK-fBoiANY5&MP<9e(6|^D(P~C^
zZUR|=z!NgB0i(2>T6F_NX?at}$nC$pvFH3dXAgPjO_PVr6K-!)dbFwRA-~LG*hGUB
zcsaH0mRV{RAbZVrhn2sElXD4R*9@`^u@1W(t4GUuLpGnK`rZvz_2o*H*|G-Prm)+J
zH7n>AVoSjg4Yl1i1)+SKlzUssw7uk(5Ooc1f`w3s20y}bDae-hkfpNV4Jnb9kaG=n
z^Og#IH{|nK#Je@%gs!E)h6d-#Qe;De3uX<56E|da+7vEBimq!3^VZUnvkCZq;q6&t
za`Y5GYfKFeSvC|~*Z?kCLwa+di<VGx4XB|_LBFX9Z$kEawS){U6$@`b3@w4=8a!od
z49&p7u=L+7<#+`NV?pMrM);;A!vn27uC!lNi`*2ReFl*?x(0^G8(jlK<grY6OEl3U
zIPMBc&WL}HeK?v%hP)e13zz5d8d9X&eMJ+a!j-xNu4@1cy(nnKz8un-+l{#h3De;H
zU8*+T;38gv)wOgZuOXEguI7aj8&{HYMus0G?~=R?t$YhW2yF_-p!^$Eqd@)*+P^m?
zXT(lo3rkJ|L$m@`m$QTH8$}~S_Kl*EA^(O{ZzLz&6p9%nFkAxTHI$WIDmcC=$(_FX
z1paISGDkK5e^!^?+#uyT?BSab{HV-$i(HONSh>b@kE<_@1hLka_`^-FPmKhr)+a|w
zq1II(aZ?%|;x7gs;n*qG`qap&ATJgmZw>i*R%arg2C&ako$;1fpCznY1Jq~r@pve7
ztJR@82V>HS0smQDIx&)rZVEdM!PPshFb##HHwj&0*}CQj(WXM;4JE3Vz-(8`GS;ip
z=-q(zSsj`*fIdr=##_8%s?h-Oyrw3NH~~CMc(jJ>KdVb6?iGwsCGIKi2+m1LuA;Q!
z4vD8S;teRYB{W(CQf+nR#cbW8$&qnW>y;ztQLs7<+zrs5rOM)sCDNDhY%R;EuP!|r
zpq|yKB4fdpYLB;A(nYo)G`o~!q#a&eN^<Yf;xa;Dc4^3&+V~0*28F;BhOKqn_4<w0
zX1hs2M&bI^j*5(pxtdhu4r!@U<eL(c6Pm5X*4}N332c8ZA?|%`YGg>$HZ@&{Q&lE!
z0Q)SV;TnKFo5BftPAMA`yh~`~^Ii#gyFlteAnOp7O)4?6bH6BPC8zr46R2|qDUXVT
z>8wU`b^}UhwIS9aDcjJ%kd#d&Up6T=fsk%(ysm~#+Vy~>Y}BrCXs<?q`=-R2(Tv>y
zpk69L-hi@RLdvxPp{Ek#ZNPc6gl=o2MvII=@--84uyHmj(-4ZQDUDu(<Xph8wM6W!
zW@ixWNE2@meT|mus{sPPTGiNw^`>eLHDC$Q)&?YBgJwQZgmn`*c#9SXhLu$H$TuY?
zB!e|l{;#HZ)dpD35*)1sDrdF(@ld`I*{YEZXj3}cd6jEY#SsXxRB*f@T4FV+;s~i&
zCPQ@wUR*)q=qdPYX>iy<4Yq0&Sy-m;eLyrCA?*!VpJh_$1M0I(>O2(brMl$}u%1O|
z+Ut}6VrQu=c>`i+2~gI?0y{ER4@gWX*U=F~rcpT`Au-Lx9t5W9k~aiuFQLiWKq<OS
z!r-{(YzhWX+|MRpaRB?-lpGqMpJhYh449u4z_bRq&oZg&UZTZ83tl6&@PzSPLBSb?
z5UUp@S}8zH8aAT2mP(d41bi)PvX43hs5SKp0cxRl`%8A3bZ)?OmdQ@-C_}eYuzZt}
zb?Mx=NpA{{pS)~u0!Kv|x)&*$4KKWEXh>I+q{p3pnKbc$>ny8u!fnF9LmW7MkpIG5
z^l8I9v5ZFSFkoCk(Bt?{WXMJ!;}R&X0g<yzwroe4`%Oa6AuCO`Y`}3gg=+?Jsp8}f
zNraXiM-?DC%Vf(=gwCo`$zcdul`1)mMGKKy`^(AL(4~Uq4S73Om6{G%&8o6yJ0v9V
zYR&UtSXJh1*wa>(IU6>&#p>b>$xT+3dd&<dtHPW;@AxzLfZ=aba0H_4)uv$FZBcx+
zl_F#ll6h(96F0>QbsUz=Rb|OeL+7fpWT!3k3K9o`$P^r{A;@`E>EII*k(jcU8G%-9
zvh*M&&?aFKU>05|Fy7K|yo42Nur04jEu2B%tIC><q&}<4nvLpftD4rKMT^72&{-8x
z-T=$lBn*U$VU^`NAvvo`O$Q=pv26KkhXIqb1SM-o3ba&~yv-3UeD4#ou1de214m6I
zUVM|1JK3oxE_szo_)Jl!vg8d8ju#~-2uW9^g~I@UK!CqXvMC%HlCDY<4`0h}Q}_Uw
zvsk*k0hY4_C~E-ayeQGaHL^$%pRkgarEy^sRk`z)*|wJ8Weo|rHig5ath`<%H1`8i
zs8Pvr6)Dsx_PB~n)4<)Va!k|6j`1R)wfAF@Z5kMyMMPNx0%sF&UL*qN3KB*J0B2J$
z^2$dr6}Ssm6gqEkC$6Hj^bJYaR-qD}=|_UVVR6w^Ve?H1=7(Hg3zD)($zG6@g-Z6a
zXpl|F!6NN>Q4SW_ui>X%MfPi?$=ek6ny*t9Y+!3v5s;(-TeFIkaKLL;X&Sv@0#eP9
z^lxR7gexhz*fMLc9<AgguZ1j4-cTTR2|(5o3UdXigOE>fNXRf19&f<KEP=urU;>*$
z_a(pto7B-ZJjD4zgq5QCLWZ&K_!Xp>fHdxfYhQsry<jXYQl|q!u?P`s3jz%F#2YeU
zE&;n55G<RbM`BHHs=WP9NxUgI-g^Q|f|N_yfj(IRarMBbteXbx4hYM-3HI(cE^Id~
z*d1V)b-M<K6jMd<o_Lofh*!UPr@Nsgcj8!XSI4_G)G0)ouv|T{LF;BUr=B&lgTgK#
zzygoev*h-=yLy25y1V$I{JOi=1oG?dS{2AIRuk`ci$=k+LVVq^;X4s7chj&CW_Q!D
zkY;z&s42}@Zu|;Ld<r*B)182pyP=hD(=<+8_HNTCor}(IufG;%-KGv9>~7OsaIw1$
ztz=x#jSkq{B2cR*u5R7+3<17rm+r*20ErZngRr}+MuxCMCn4x=e$t)zm%DIS&yBt*
zL(k-PC>j{T?k<{f+DuigykqZQOR%qww9o6lH9Bs6sz<&l$t|zMJwD%+-{A$qW_hml
z=w^Q(o05|#Dcz>(kM}$kCb3#qP&R{e(N5g~dYOxM>W-w`bJ0%Sfn1#ncIvB_5-qG1
zkTDZzu8vc0E*hzOoQrc!jhYJ6HCcbW1DQJ)mFNz%%2a*vUMyR=YCx;ZHFykflEs<~
zFp^t!uAzZLluY5TIuI^%QT=^QE(Opgaj2FH*~MGKI(7`yu!>zXZuz-P!n8Ie=hHRz
z?vp0#4uH!<sqqeY%S^eL^BY)L6C)!QmiN{UsLEV4Qg=XA<}#kbFHK}F6BCYQtYXBm
zidFM>utv?d7uX@^sv6pJX{$zdEN$fqOe}2G;JG7a78k!j$~jVt?ty}tt7z;LRC5*f
zyRdhtA74EIE^`(9J$LjiUKd!S5xOHtVzShDuehO3p{_a#J-jGry+)W+eRn&Sep2<_
zlvw(?coo^C;9a1r4yArhs>40i{yCS%&6~lCf>!i4=hV=-HdAHBJMJJ;z^z`h#ZmJ-
zeNiqnlXq8_6}<BU&CAoAE;bEZsk~`N_|A+1<GYny=>rBxWzNA)TQtaG%D!vPAwE-H
z%{eq|1Ls4_lk#s0p4Ah}GP92H1xmc|**S8mxSPPyQy^{%2hXp0B3<m2q>jgMqSOHn
zn;skBkjidP=*cEP)9bj{&uLm42SY{<9sEe%!h$dX(%S8QMU&$=UZaUS$7?jLjbjH^
zjXcx7H(5-4Q*usJoHwQ6DgGkYylU*3b5s__P02Y{jlD2O-j_SdAkA6C@dAI!7T*)P
zGA9ks9YvVtq~Uo}^1Y;@+>t|Ps-F1Okwj+_ht(~AkD~}Nn$u}>?kFEMeQDeh3+_w9
z=2dN?n0QCT=oAX8qbk+(#Ze*Xe4Y8l0Xba?I8ZTDCCEE0hEwpY4$I_3jqxi<@lph?
z>KS7@-5*aaJVgc@_;JbyOKIoQrD1%XDl*<-pq(y#+8P)f8XJYjH;JS7XmR9JdN&12
zli%4?CGrmB%!`r}gh+HL;fb1=E*%_@nCTR|0K`nEihXrt*O@M*8n*N4QmW0PMaCf{
z1<LA%tjn8(lL=Abn}U-Gq2n(KTEVMSYyf8FDPG<UB2u`m4#doKTB85c$A7r?R=!`4
zzIM0Q{vyAm*X^@eX&?Xb-+%nKkMeQ9{+s{%U;cIhjyRD5_irDwVCcNCPHrZCF7w5x
zl7R(Ob`F*K0oZpc{ZtCL7lBuINa8u5bO4Dxm2xRz<*(%%)Qh29O(hdTrRk{zK&Zwr
zyQ*Ag{pQ&Pge$4i&#sE`xSve9xXYcWuBn_U<;E6)S9e#SzEcoRd0-1}&{GLL3a;r>
zl{`y<RBZ}vEw2|c8}AS$!uzIjJ`|K7ohqnUVC0%c3v^-4&Z#<u1;L}!RHz%Zx~8${
zJ?ya4RIeUZ;A@%+!=t9#l!?4#Soo}}YM$2qDeG{78)8=FdM}oy*r}M`f~tj6rqE&#
zcq*1vEH6v5$jVUQ@0+SYRj_ok@SrK}bqSCWt3(o$Sy(5$!M-yKZ;++s**9q-DGk~p
zOe6&<cBX>Q3W@~Jd(huofD4(rhZo>c=1twZASu+;HMC?|>zQ#ryKFlv=jgUo0CMuB
zjW$p^jd3L}3d%SkkZgB^Y;mrjjxtcEXwlnL07-PIy~R=5m1PoM9r>$YCDJW{4s{{l
z3xKRXRU;mUxeK&j9O{Eh$0$hd?vpp;f`7R($rtDr?z9(`iO<-P#j~Wc=1PWHGIy^7
z!&;Do*ok8;3q|+5(DGPtjc}nl%R(8~k+;>dQZ@83^b1rZB}nm#lJ&8cZw2UMEt!q3
z?tvf0+oQ(Uqf|TMCcG=%Jgh{!C^;!9a$TUR3iAP~aA(|Sl&nTZ?~F}-t2K=ZLyyYR
zp$$K4H)r)7W=6WQit(LAiE}bA&U>S`roy)nWr1^~ippjUrGP3j^m)_J$V=dIp4UvW
z5S3a<L8U9pii~&GGYz&PxyG~1C~62QF-Jv0l2fJ=wT7zd^caFno>eYUTlG|hL^7Rc
zIYtz6JGB(!A0C&pSo(&#ol*Ay$)TbKU-H^e(o2!&6>ue2aCnrVi;B~QRWeZb+>2^e
zApM%dv|Kx@1*!rA_74h>1#dlzd|~g6JOKPwG0lO(buvrtI#jWcVGfMqQ1MOcEQ<<F
zd(mX1+BK2(-^S9*MM}}Eg0u+$abH8`m6{*xSQ<H#&kor%DiY?7r6l@*{f~81XRgk&
z6Q{BS>LMvqc!iR43Z$Ua0h3!_Q9NY-cqp@Ul;g;P9l3aOzE#a&27SF}W_TY`sVlUd
zXK991vWKf$64ad$s$o<TXjvtIl_gMU!+C@n7JjG4&#2bab%s#ob|VS(D$2EZGxk_<
zVRkd2vtqXFW+d)Z%0$>CGcov;$-5U4ZX+DJFa^U@cx+)dp{aCO1*vTpH>Z`Ig2y#@
zVQ{|g309e<M)4R{8ISHK*Fa^$(MQf-hF_ngyh^~SK=#U5<dLDkm3g0sl0q0la|4xb
zhI#@z{mqymLg?trjL8^=Y7CgN`YHb2n4Umb;Yd%pkl2#BG#ZoONETRQ8n~{cEUhuO
zB6I!i?4!LXH-A%NPh|>fOnco<;w{D|3p;3?Wfj^<X49D|<B?#lGqISGD|RL~Jju=`
zGsWFX9W$7QKtQI*b4AigDTP!_Cp#5$x0w+DWP>5-Z&{U)G)oy2ok7`ESq_}}uB$FL
z=JuCQ$#{_BhS_?UQi`I%u$LoU3yjF-$_t^iDuu}_lw)-=&Cnw~Nn?tZllf;dgN}-m
z+H|G8z*d-(Stk^|uFNivbP>!IDsP`H=15UhNLx%~eexVIwbqSV;}N~T5S`D|3(St8
zc=-nZUPPfY5WYq<@;Z^~?Ja`4BMSF~NGqB-T5zbW6Y+@Y?Z{koQs6>g0z?#s*a>4$
z;9b_4*HSOKmg+jRv}rGupK8#Hmh5&7M&30Q;{?5EO=SXmM&~gUvLg^mKz^76mkI?n
zXhzF*)p`bcF*2w8CF8OfPm`fhjLB+<oH#*E3^7*;l?F4#8Uh?ZLwXB!K_E^>vQ!0a
zoWKsoV=x+~Cm3E~6bMuhAQBqV4k5r1df@+p8>EW#33X3!{6VBA$esqm>j?-aP#X^T
zrfCZhEv!Z)WL}MKo|bCT^#&I{cw9b&(B-BLfOTBTY}f`sD1jms95m5#feV46w1JU$
zuTM~;u!1$Afr8E@;6Zil8x*A{bdCr&Ayb7l8_aau5LvsF0PKm)B6JKv+g0DTfJ?mI
zwwWLv4E-6kgTjGNq|8C6;8o^VeI>#Jm<>Sxb<{OzOHW7!kbTO0)0qilDSu37`ip}a
zfJ<NA!Q(e41b`mw%1^m7Rl<F1s0Fu>EXPomrZnS@^hEG?Uf~@}FC6|ZAJ<K165UZS
zK>{!~Rco+UqupNiUb#YOAn8zl=4=l~Lplj$?O!kq9V0x==c*kd8@1fT$FxjC<+0x4
z^8GZc=7Of}^7ZA-+CE<Yu=To(zW(7ap*YIdrptW&57TAXDUabY-YM*s_q*LPcBibC
zFgHJpmaz^Gn`IuA52Gclnh&F8K0=!%PgmJ2!=g!hr3^W=S9XS<J?xcf!H~I<_m8K!
zl2%WeE9pbLj=7S+ny0xkdwy6eX^f<`vdJ9TUXyG5&W^PbtjJo)UGcP5_NTS-MRD0=
zAJ$4(rev+;b^DkrWkZ6wa+*+9GFJ*tEOX_QnGxp7W51-iQb@U{xpICoSMt>#b0t-I
znJa5r8eps3rbdPi9Al-^9BE;>M4zx#J`9y%xkRd+W2lt*ke15A^ZnQ=slgswWwwy?
zHB6VVLDEhM6T>l6QiYM3lCFH3Dd(x!eC(9;eH}X`57=X;q&9oZl%0zIu~SmA96M!|
z84`9%)mTe2CC}F|Q*MK!tmd*)Qj{M%Wml*9ZMaHQ!A$vPxs;t!?gH8=={AI!G7OiP
zCGC{1NzzbB1Jf~8w$G+Y>NT=dvJTC4OqI?%%rRE-@_3Au)N78da?lKLjFrbyNe2@x
zl>lkLP#LC6*sWxzTqrFrGo@<N%S_4om9kW-^s_9L@{Jr*rOKtkRM~0tkg1Y-^RZOY
zjCvhgWfZ`cosy3IW2Xep9EQplfp^wQXNJpFBSWR~V;@5$ONxfAQdS=rD@X7oOQot|
z%2LUivouvcjF~B!T>%uZRBq#?su;^uNuhsCl`=QcR;l{-v{f2KvkaD1bt!4E6lDAu
zELCS2+PIfAJXRQdg;YM)N_tz5y;22xX|Ghu#xPeFMV=jd<&t5M_DUKSWv-NU6>7NO
z3CX&S!II*Q2Fq>Kq#ZQPGLP!@P{jQXvo7p$Ls&OiD^=fB*2+^Yoz_a(&S9*)wviLB
zk=Dw^TZ62XL?9h=rRvhlTIqU^Fjt;}&S~HLWUdrM1m?=DCj7KkURetG<7up<U^~W2
z?Kv4NRcl%X%Pt!hEtW0|0Zf*zoVqv4(JB)p)SZ2p!Z|^M<r1{u*ehLm#i4``7S5Et
z^2Wh-9ed>|Un6_vsfh-Ar4m7;xpJIRZ>o23ej<D2IAzmluN=>sWoZD?9U10I6cEBp
zWUy4CfMc*cRc>Un>`F)*x(}+ez_vrfWk-fZnJv3g7|UvTYLOU{=7fn5<H>B<@ChEP
zWmAGo87-SqRJY1Zmrd^qR?A~D467yFNXKM(Dig?LX(#=-Y?db(zigJKnmRIB+HXyk
zrql4)EafggMoZnUts}9kV$6;evrg@LnK3JkXR=~e<>ZtVv#M;4jF|Q0z?BuVVsVZQ
zQ~O0W%yQDTBggS0H9B%0Gn+JRnC0Dod6NAe`{hZj3vDoLjQAR4!MtVWqyh6JbCvz_
zBwL-Ve{riiA`O@~(iF>lc{7vnF<z#9Q-;f1^JIXC@>9}sxl>D?gr!XPh@lr#2ue+*
z;ZpezWw%tQc9<>8Z_Jhob-ev#%41r|sf=~ZyT%-83d5!8@{u*pV9Fpg@R%;^yXkVt
z;ZDn?)A~lkrK_TzESCa$$#SWZmB(-?L!b<oGQS_oWp+ZV<;ju;qvgX08Ai*YC`+?U
z5`=VAG+H7l2tMaEWb&28Qb{yqv6Soom@E}nPP1iKY9^X3<%5^ma-2*$FkH6Z7%mm<
zFT14ziDb6~MDaR?%SW~e7%m%Kmd9>+GBD6?$!cE5ZYdiu?3VT2ZW$&?rb>X>Qdjpz
z7w;1G=-4e4mkN#P5#cSf<q6R)*q)EbXxc6n7fIWtf)8Q3tV)<8)1@n8n{1a#J|Wws
z0@P%>R799emm&MEr|I&9N5XXZ3`)#ULG+QP%SS{W!p5*8Ww_Mo0Hx_^rKH_bFF|%o
zxv`JoaxxT!fmZ$-vn5T#vRh(9UdM1LB(MyZ&!89DEg8^q?3RMf({QQaD;X{Y;)KpL
zm2UP#E>QbHjKK*Fpmmd$OISA_;Q3?SBq0A`-7La~)4EAB>9KBphCm;9GdxXGi6Ecm
z&4aiF1ebtYnKw;HQ-M<vZt_HpKFpi1H}x9+<MkrP#$>+!(O;*!k6$!z0?Dkxwv){A
zut!45DJ^=Ik88K`bwCEdK3c#vfp{o1JypjRwWtFLnnuYiSUsIr;dg^8;mhg}D~DLB
zY5U)M51=yllrst#i%sxPpwo(Wa>DaE<=r*M|KHl#?Ci4J*m+)8v4{4+C#7GC(*WrJ
z$sp*&83man=nfFL2kD@Z+s`ZU;i~%1&-Tf7Y{1^)_g0lyQjrq1xR}F4=;a_&qj@H<
zO4P!wx<tnJB^-P$0LL>I)`ZDdLMoV8Yv$4=B0IaCu-Mq~Zb{5#k`9)98Q{4ccIF|3
zYbQ~`S5$hxY$NKN8`%gQEkO}Do?J5{depSvf)UNV>R*DdLA<*Kbn)kb@AEaz^zkd^
z{F)<IQEWID{+IR3620CcE}86lE26M7S1gOVUput!KL-dKSDZOL6Gez6*n$&Szt2B`
z?vsJDRH2qd)(dYOMs2A)t&@zS4VmABYiDeQei`kLtQ%FO1w^w{la{sKJ`NyP$%!pL
zsAeMSGj|ccJVK~3q0%gS%?ZW#Lxf<d?yNWFQ|tgp>{>G;77%a)q(0s1(Yl{Ai`S6_
z2{kiAicUVwOuyir)GiU}d8E^5i|T}w^Jtf>x83HR=infU%Wht;m_MSz<7oc{^(Kc#
z>oO;WW~4oKptuVnJdcbT(clqsUZTNs&MH)6_RG=C<)qS#jGAr$!fDRDJo?O8p)b0e
zI~XUVvsC02Oz+APujE)R6?kP&@)1NMPJ(#66S!AdS19?{$gMQTi%V5r3(Wp23%!0l
zU%HT->7oPmEjiP8==9^p!3;rqIon(VAZEGaf;^JK!wiM+$%$PfKgdGf>>G(+atNEA
z{PWW<l4V9N=E{w`A%IaLnzLf%eIW@An>s`G%urOHfZrNbZ-L~}Q8|zO?DJ16-vG{Q
z)SrIqTn_J*6ny1wsh=SCcPt`A!M6|dVonrpiw7G;V|osWMxsm$i@YWNy#fUNeISTm
zQ?b}BX&f3dfZ@ng0k%+9WObe8-FULB2wON8UtLE&Hyl9E(c>14)6UmIZjFk;ZpoR*
zU6^<B@>d{|LrvUZU-|HGgIz~FH-4}K+ortBQa#x%Ii9dDJsMZ|Iu^wjqR;V!J%efm
zc7rX++=d%p*e!<{Zz$BrK5C7=8?DoEB`n<O4RsVt<(;KXUZFhC63t!#$*@GTSIQm9
zCme<nIas3DE097g(d-ot4&P_KUrvGJMtDN;>Xj&Nv;}Bb@P&QQitfv%WQC;F^LVR}
zf7)|tTuQW_v*$BGd)G6*oJL=WVu)o!g4!eVYeEnsoFV2?aG-F;ULmS+Rp#m7M6<Z;
z77Q-R?vT9N8?DG?Q_M0Fd!D0myl7UBEzqGX;e-m6yjCxoT)#MA2Tzd5$r44wzGMu|
zPwUqE0Bf-z+$)^KER}vOKns`H^?vObAK%y<IM<e(&NkQh9R~@w-ah!>uQZRscKf_h
z0sTwH$zRw2!11do<%2?TOXXV&73Nl3w4xgd3T)9hf_(EZBZyXSOU_GEV0cT;tj`*)
z*UxbZ`$xfgv;|M%Rp^um)dF|Ymax$+oR+Po19zeftHt`f)VLrMtni&pIW|$_FY>!G
zRSV}SG}ysVoXZ{z1*xW@+bfkM`qgrOTp|XtR26m$LMMIO6>r%Ftx%`SG*?_@R)a0I
zokl+5msk#brOLpTJa=3IvlZesTavFkoMjU%fn(a0g<>~IBqpwSI1Bi+C7!-5i76v2
zM<rQRc_f86{Ax90m|GP6sjnZM{#11kmnpKn0;ps`ws-v;wZd<rKe+tE*0x(s_lS|r
zZ$1d#t|NI;_hSC)!>4%Z(&5CG#9P1hWXrd%1h9(JY%&kQV)usB;4|B;84^BoCl1m)
zDhgw`B>|twmBXRaTUEA$3b88=PA)_N!f`zq$68$v#<A+~`)7EcD<lESS^5m{uJyqr
z;aydTc1zBjrVi}}1>L8`lc}rwk<beL1hF{jMoUNVg_pkS0|8-VzNS)!f*IN?jPMc>
zV2N3<AOpBU5()}b)9}A}zO)6QjaCmWS_x*V;MPP0_zPInk(_U$YV`mo<*Fl}Q!^Jd
z5m~LG(f}0IP)I3z0e4tcnW_!ns}Sy0pxs=;*cZ4t-w-Xfxi3jSEhc+QY#wxj1?#h_
zwk=qwB}{9<imfUm6h>|Z-C(H5X1B5f`4z0#@#0n1rQyY^_8(!jcjvSLX){{rLL9Sd
z1Jc+MS2iFmHoUcJYxgS<H5_{_x-X8s${aOQW-b%|`1Pta2q2U#Nqyjus73m)JFc=v
zEjc8r3{s0FLX|!G1%eI^i7zR^7MCP;uq~wxV+-N?T>_;PD1le;%<v6QPHm*EB+H>y
zv^?p!^1^lkSj|$w*)2IUuB^Q6Ni5b@qT|U+9^Mp=TfU|*k2fAL+;OpsR&+{VcE=az
z!9!uWxr)B*pFs*Ke7wrcPU3uv789L~s?rWi$M+Ut;{q_W%JXGIhrKxQC?McZ>NTAW
znuttYEToDqfw>RhF|x7q2cb+Jq?JCR#n0Ks7Of=Ml59!(X|^&;Coct{*GEFjA|pKW
z#qrv|k|VBMUUK>uM1s40K9ZtuyifAX`6hr*tx~m4>Nx45ubM6568~U<t$jg1xZ9m;
zK)aNVi+;gC@yJEV^qpO7DXG(OxH@Ut?Fc6oWngz4Zpj}+XB9;FCD^owvn}^CDR8#X
z5f<PfOLT;#<7&&THwD#Fxdp%_3b9eF%*Yd`_>z%-Fs%>D6=#~Hg@pjgx-()}2%#+1
zncb4pJ24a%NFbIt3d^AU-%4az89@cW6#f~!7O#0{Y=2A60N$n)f4rv3&lV~@Eag{~
zftwT_qC^Rab(@?b2`@_sw?Zk3l}T9#?R(UDz`l6No4v>AfdyuCMi;RGqciZ5x7Gmz
zFR8k-TM~gSVKugBe`WX3gW*>KeOG|EuUiX&FF522$@$7|84O~bAIWLW!?*CTD@5M~
z-yLx2ZjqqP(RUe#!G8FpHJ5;=zLC%PP}Qj|10O1u!z~ff1MTRxjKerC^p<fLlw(@S
zYgmXvuUnSjmzZl9mhLM3@Q-)Z8w>w<E5HauY~6}55@cVuj0Jh7i*w{FM4>{_)6cH@
z)~;mWW$)aTe1(J~K})RyKw7L@He}w(fRU(iJTb*=3s}z;f$9rUOzT8kPdu?I*_Ihd
z^n5IsO;xeolCy_05gl$(pv(o=56H8*OvtQ2)3r*NF+7(+ZCI$EWTH0wH5hz5EoLAk
zne4pRt5CDaTzd)1I=vY{0JkbBa!WR#*JVLwaxJ(v6QE;E(9|tC3L1@2?g8h=w`J!n
zCEolvt-Rr&=du=a(0N%4D1gjmEheR?&2!r@10L^+N_@=<IFiW-=3;`=Obd{~h3MdU
zT@)-7BQw{6V%pCrQ3_WuttYHarb4${6dFAF2*&Hzt{{$X&1E+@+`UYYhr)^QmJHgV
zfy~4q95I)fAaUQ~$nQcF{4iB>+ZiOqC8kGb6qlIJ>x5MEFDHTG;H6zV0V>~_@WutM
zr!5(@$Cs1~{Jsgdu|?56?F1;oXD%CHg=r`o5UKc=xr~4n<|0M_?7?p5!^swKts?*&
z*uw$w^Q4eU>PCV}3IGWcM?^W*3~eQ<wHRgQZE2}t;jL}uQo~{_Y{_s~Ba<YPQTA81
z#J*9;=`hhTo`jXH;45P#e7A{`vA_$qCArwOewvxm(ory5p_~i}<YbnVjm3KAw`eUA
z`6sqyNGM)uhqAF4d@W0-7cf>><V0VHqU$=ouz6a1QDnWC7#a&i7#|6(69qcCIXq=T
z81!W8%;>0A7#4PGOF}t&Qxjc?LKg)afbW>Vl;v;>*;1szNS2}GZplif?=&G2BeLjj
zp(3g+Ei;V#m(^*VzPD#aEIO}a3KA)8i9X7l-s_mcoZh!*M)*&0=X|h}o%H5j3Waj*
z0mb1K#Bg0Da+wS=#{!_ploPPiprUuV!5}sCofnndHKO|1qH)?ycZtsBB4QQ3EiEEo
zg0yuj-~z(PRCl)o#K^?LQm7yN%E`hBC!OPG9lqLbo<HJFMao#HgltL5SSXfks*YPI
zsC=0@&6Cje<b2^yEl)t;2r$zpP8!CR#1S*RGp3yXvf`f1R+vZ4@&g8sv;}+xE2_De
z7#+*PnTmd<07)_x%PnA%Ox1GB;w0Bjx!iIvNhUVO0t136<)UB_Oe8JkV=>H#OI#=A
zEjmBrkMvxhcvvM9Q)2<AbR@hmcC992#$V>m0Y=(_d?jI*&G>@DaGR-Wc7bfylr2)I
zfNmxiA63%L<l-UBIg&d<u{a~~kKwMq=I}*dw9XG$kqOOLoZ~+ep09u`GRwn5k2F9`
zq2t&D+1rwMa8bC~k7qM|d!F=aMfc=Q>f2+HVJf716=<Q&^z8+0v<b{z03dzMNj&|V
za=cEw#%7)f1cb=M!Sid0j3jUguUBF<Xo2Rtkeqob?zREDo4zQYr}ZR9M%T2V_nBQ&
z*bcDKJA*Qu&(uf8qS>ZCGVn#0O?_n`jBM&F17-A)&>ANz^U2dZLo^@P%C5jvRJZtg
z5;=DZeKOp~u0vFHM-txkP!|<4*GwgKOR%`x)Q89($r8?204mwk;=9IP%x0!gf-BmB
zOaUcn?+}F4pgc5Hx~(_xG@I!HD<t{vR8+hS7`;kbo(ZJ4C2?B<#Fd@zi-r&Pp}ecg
zj(SV-E|tDkj(;i$Aro@1f)KJ9t&cZRUE2ye$Yzl)EvHp_!wNvil<l=8lgoIE_@SwM
z*E<~1XIjNQ*wej|aq%HjX{mSc3?^Y9n>Om%ULiVjB;k5naC#=Z-j+oEuK$$3IC;2A
z{Ja6anpmqUAtMv4uM$==C9ZABdG%T0b_-%dEo5JXmCiu+RcdsYuzmHm$TjA<?CQpP
zW~ZUyq7}+0TQQ<@M}WTgo)`7vN`A)tp0_B}QLg9Bo^BYeaZ;XhR<NHNxu32?Cv7M{
z7W9yfsRu(wC>ES8iQ$>FVi7Oe+e(Pml#x<__1I9labS3C<UY58;kj(+lLg3=<dR<#
zv_ldjksOHB$+4jW_$?}2m2{Ihry)wc6YVyUlvU#4mH@r$h(dw<j0>J<RB05R=#?yv
zCsJA5S}4F`3CgRbpKS6>9>-IO47e6{QA3|Crw=v+)2SR$SQf?Ig2h#-Qm6lM4_uk5
z;?@#TPg7Og%0Y?=v{$L_Wa2EUB<#J@-*fLIP+kS{W1Vj|4v$P#ZY$?Y);+t=)~Snv
zyn+C-o{-!M0?4|uj}HRKx<1?z-<M^fTX;mdC}+but(*z?FV(%R6znp!P|q~kabVqY
zW`zIh`j`O`S=Yy0*j#nXjZ+0zWP<Hg4iKRYIItoUYOew-vMxpgC!{FUUIkWULhV(K
zDNU%o8mJ=cq8hD%v%WqenxUS)ZjM<^puNgbto010*K>MnT{z#$0j~*@S2+Z>gydDo
z=}eHkO76e)PRe}1g-oS#D{!F~bpoDKoG}%|kO`z$D+PYGh^bTCX(i(;?z89Kw{n<n
zg6LJs`&k#-zET75P1}Hb6b`ROEkWzD8k8F}YS&*O3LUBjiJh9jdKD(DkL0w*VTO3f
zA|gc4OTJn>Y%h8&F80MIfr}N|uLiDS3vw|7_QHC`*ES19Xs881#ie%HjSAIC2kg5A
z(Rop|R{KI^fd}n3t<(7?vy;G~Ez0+bPi?Lt3!mCt3gRwXw$6yQhm`i9f*$q^5I|dy
zcL;Kgd_6eECeI&Oq3ek9{opH`>;<SJYiTb6m1Ir!0^rh?gqx=F=$p%fonDsVtw4ZG
zg?Q_M0GY6XR|W86LIPF*Kc=F)6)=wp>Q@2tB>OQyS`*H%f;KbZ{3?jFEy>&Bgquu8
zgRsm5{oA5(+RTE67jA=A^uFuCxa8Jzds2b-yje}cDGU5p!Sa}D@m8=r2GVbTf&AQ*
zF?!fhPG`i9f{Rsk-7Sg!w9`t4VpZ3zQD)dwT(|Oqwj{@u{iAB>*3WzYw4zt|-xnbZ
z{<mqp0K~?G#H&DTjPfE^h+>rQ*JXpta>#I=FRmASCs4d|qqs@F0G#K6;nkLOE&6Qv
zkgV#f4TMe5$K-&8_Y{S}rkFVz33hi#XWZYMGazg(tLt^y8I7v%6@al-eXkvkBURI_
zJ)NJ*=~nERWjWm~I6Zv$ZE$}zKSoTb1qkv&bgnu7#;w)dHrK%2ya{sfYcB@y%F<DY
zxQbUXA>t~Y#}W}&spW1}WJA<@zf4>Ym7?%g^(mgJ@g_`M#dlgwUyXaU+O^OQ7yM=@
z$Fm9GRzbp8)i)Dp7^}}hyF<q#B-&;Iif850y9eh|l@IN>oLcqlnQu!UQfC_{e#pvV
z>P<0Zhd`Y#hxOW)z^IOs5g4t;qR+ArZY8zDgfgq7e~7i{I-<kNo}XG@^z7DrSoAEZ
zc6$6d-<nvLZklHrtIBO9{l!$}c1upzi~M7x(O7Y9BS6Bu>6CCYMPJ&ulVC|4@yE|R
zShfl}#)M_7pkoXyTP0V>ioV3yxtPFfHFr13<W%T>hQPMubYEW~)COCUtW9{G@~pCf
zx*S3%T^96D4@FeC43UvkkS<n4xln<+d_?@<44_KeR`#ftrETkH3u{Fm;Q$P3MIRyA
zYo^j6^(42wiK=ixg&U%YfbbPs9m~qMo7yVgv)o~1;+YU^6-0|AT<tod(57q9iDH%}
z{pJ_KEF6;nYc-)S24bxSvc-z{r9ie=shUW*F5%N^BsW^A3GmvI##Mv%;F=tC{8q^w
zHW`#AyxLWPvRKik8Ys(_<ckSEB*<DNXk<dH)d(zINezZ5rks|;gs8TJK{*?_qSY}-
zmMt07Mqp%Bn`7QlP9bJ2iLjQ8HkDM_Hys&E_AR1k<l~xnwd+aPH38Hr8NH?wx^=Qe
z+kvDD!I@#VoGS6i7x7uRvRfPI1g+fJ3d4NsOHRm&>gR6BdDVBuw<}4`cI)HL5UYuZ
zqMoSir_H}ZnTLOk4O^nqD(I7Y$~q(j<(Ah?2#VlmTN1t1w+_vgMND#AhYeG?^|2>R
z1?X8#kjksJ1)H&?z^s|-Zi1dw0_dA9E=MQapb%)4FuVzYR%b>t6M<F}l5%S|ydf#7
zs#_D1BGUBA`GIBe;1ETBwHr=IN>U+J5Gi+4|A}axTDx^-H1pQ#IPobj@;h9oFlbv6
z!y!jMbIWyW2|RIrs+D_K^iJ=}>$1~5IdU*6m)!{_sfkfht=yUz71heEiBS=ttOiQu
zVSK8FI|NWx6QgqL^G=M)Q@JEDDz`AHTNJ}^^MkF)bh&&BZD*F-twDIP+sO=A!c$BY
z;NA3rhiuRD*lSA;C7x@wZ586WykZ=>!E`#DB+jh8TfwKiDG9^GPuJocfXd`_=n7Gd
zJLhv@7xZi$qCnTW9DvHq3cb~UGfdY`+WKkbQ#-oJV!*2RW=rfp1$$x!t~ke?f~9Rq
zD42#MO8HFz(<&&HnZUH`h@$^8BpftPA=4^n(Ql^4d0P4Iu~hHcG?RItRYTxXrVkqN
z=Cx^#DvHy)K4#A4-)xXZU(;wnt2o6qwk6Tk6PdR&t7Jng>+Z;gfKZvL16+ZqOw|Fd
z#$ND<?);HO<(+)&f`U@Z2tX;*b8}$Hvskq=Ihd5`EEzzgOxI~!lzw^F^I7+4Jye)y
zwYIr187j(zZAm<K-RSesW!`*{)J0l%D5IhaTN2vH<N#}#!mm|uEt@tnA6-Nw2@796
zxRxpSS_RjVT$2@8%M^UA0&973dDhsfQo;z)o+<*cRoL9NB>6rmB(${h2vpA&#EJo$
zqbdAa1qn10zgADR*f)u2xbC@f9dcFhFk8g@0T46A$5a8tYzg-bCe)=p#iCI4y8=^(
zf7JB!@b6Qc^%YdiTw0B+@s;8<KE5e(=Xx+;^FY=r2(c;1S_MQlv&!)1NZp4oQxLTZ
z-QE;L?eM6M@`Xut(o>bLTJT~{!PM%f4^tSmN)IO(wMwz%sq%Rhl+2b;Mhv9P6hy5C
zQf3OHRzb?l)%DoLAos*{*BF<nQYDq4n<`9P8Qv{vx=-l%Y)@7e);gwVMQyBnvyOhU
zJXEcoDpFh*Ii7RrL=d#ii-k7OHdA$qD`=Z399#A9&DSo)#e3ijd==*cWI9*wM!=!Y
zrI>>k`ds8wz0hd|`W%0+A}*Cu40B;#!V=AuE1Ii%Ru_|b!KBS4^Mc8nOW{Jy;#4u?
zs~*caRm->n-Ff(U@%XA`TtV*4#J^RCEN!Zuadnt=WnOR>lUl_UH1iZJt^#<T2NriB
z33lFmPk3wbq*ZECJ`BE<iuN-LJ6?xB_}C6h+Y!i~X|f%-+-Wi$fWxQBbT}1}-ZaFx
zbiv`O&o7nO;`^Ri+_<ucn1O`55S_6<NVpnALx<RyNe@lv6c+A~AM=}hPSBaY>5y^z
zS=_h+=ASBVTmk%V#^lsF-2OF1z*)~dWMEjnojP)~LmjPHSOiX!fnlMzCHdg+`!+O9
z@%yIJL&%IKxV!5}&Quogt^yO90Pl8ta814h>H!LPSDi9&Q^>paS#eLn?ha@4(NIjv
zH*0|}EYi_Aoeeg&6<ZX;)(%o=3U{~LF?Gdfd*il~NAEhKn7gWI2b^eHRe!^8n~J=#
zTbfCMw*|4(vfLuI$OM|=)Z2o1<to=j{?L}>lfqtJZ+h&;2bs5N`LTTq^6coW=`Dnl
zjxXjyl3!Z(4VNsuXiJch*bmzs^$qf+41xoqj%{c6eGsJFVt_x))38SN*g=re4*22B
z729U|4)`G-%@$PZDDW8Ad|zDP;kZ44sX-Wi7&A?E<iHfUDl)d)POH#2m^lx4wcP|X
zUFg+D?w$+2+CUk(;H&M1a#tkJpp33BJmm|H>emNwtm3I`m@_KLwk=D{-C`YAW$;F(
z;}PYLc6XyjBK_v?`Sfttr(z=BumLv`bNY?9_6(P|l9e@c8QM+)=u{p>%N)^X9eN1Z
zxhTf6louO&Bg_}I;<#y&Y2Va|Jm1r&`P7n(Z|;clF%|0SJ0pn=NYW8u<Qt%*Eu%TU
z62T{rwK(ZoNgnS(b(!nPf@^zZYDX){>OS<57V2=0rCv4$^rZb=h{oXd*@+ekkGv+7
z6-QkoWGuS+D`cVVGsjBujX!g&1m(KQ#x(#-OrCS2kuy`XCvv;r6A08&i0=GRC=!9X
z3t3FfsZy0C8P8Qyu9X>0K9`b(NoRk?ZT=K&{4`=jgdyFcP(vWnRt!C+O8#uwQDmx~
zXi2v9$q~YqpvQRK3N=PRD_Y6Q19RvlahH5UVVjQ@+&CQYt6;#@3S{T6_mfobv+MDy
zOWHNJJ-hvSN3H>&NvCB`IJr8a=u^GFytB#{{7VIcq?!kf+iEiI3y#}rmPyqFso;D=
z#@$N{V&y)CZ|zkYA(`D@zhPWed9Bro$;etYjnl^?$!BGehneS$jf2dn%L=i69CjX2
zcA@6`hiacg(=X*3S`LW7fvqMB{geT!LBB6l?-rnO{vB;^S(ciWC}x5N8tA4Y;)@A*
z(~<De0A`8;5=;o-OkavhWJOOQg&PDc#|kn}IFUZ0fUvfz@(?oqV3NKRsF<>Nk3<$P
zZ#5r_m-8;`E~qMct16kh^gazU$r1)ionsl9&c+Z6;@c>A_@!osrS-OF_|hK>_uDG|
zSh(L-RkPP<qR33lN2}?KhgK#v-SKz|8}p0Q)tS+Ne<?;BbNVUlQM0b9s6<<(6va^a
zgsLLKBJpS~>ynJvFEnsXN5CfxvgwFw{)k(j45*Nx+*4WPPURj^i6$Lt>ESt8y+Vd^
z6nSV_CPiGLt>N}ZLJV6=w?9P7(^~p{v5B^pet$e=n$zv801A#@{GqMM^JkffCdV%e
z*5voAw3Xj~%5}7K{4#9tk{uCqprw~jE7s)bt3KhDo}NKUCqEK}xJ9Uz+m1#t=-hN%
ztz|Xrp?ycog5X2us^wBZaOT!>EpWPgN?V6wPmP#d2z(LoS=`y98LfQKOfU0PqlOvp
zh%ihoe7=}T8;H6i${WW!KO#Q(mP>(G(VAQe2n^jCD*+W@XbofVE{NS!gC;sj;hVhe
zVrC2G+(2U;QOntoD}kqEPObz*NZJ|;0hNGgEf)gao{8nDh-qdyipadRTpM&%ac{Xa
z=$7lwmTQ5o!rT4+_N9u?o$ASy^{mB`z@LzzUWP$hR~_-(z;zY~U6!k7VWy3LzD~`c
znCV@cEdXCflpQEclUHS-SXK1#^e7h=eW*vdu*mWmt#g;`PA)1se~sab8s{T_f}&5|
z^;}YPEoM6_ir)3?noFUCPq&_HidQkDTt9Rz*LtiU1fOo5vW`c_`1f2ybWB@kZO}7>
z+UUxuw3I{Lb07JtzSQZtYKiw;2PB<o>$waNM7jl%?A%Hlw4O@?6?0-?Ak=f~xiC<9
z_?%Nml*6JT^0&I43xlqLOx>cHuf)>6K!@7kTRMUqm0UdZJD+bkZJvTtCi`-qHcJA*
zpSL8`5CFRMToyFh7NBR>k>$N}S<vFDQ)6mrFmg%Imb6Uw-@u8qp2eAjmTsK|fzZ;e
z=YpWg*o<`l?J+ImPDNx|#+`~-yvC9K|5a-%{eKhstK~IxU}QD0mW8lJdi$1Wur~1a
zO_{`7M8`9l+D3YN(WbVM-u_kWE1Y{9k8<hU+mLeU-36a+BfWc*-5BZJTgFiv`AkQY
z4@~dgv<QN_{7b<x9DYdhUZ~jBuk`q;tkXt%{U)0-((AXbeudj_S}u+B`c1q2kzT*a
zri}FZfzOUxrQ2^!eZcdJV6~0h+aDly8@aD<H8T!(IW=^tIr8Dtg}Xi#*P@d$C?mJ`
zttPH_%jl)Hb0eL)aN2F))Wy2mMsDw$Ql#6+-F#B5wvoGeQLVOdE|Sq1>FPoEUm;^6
zJeA?n)r)<#jr8>mTQu<WvEaTCd0v*&Iz4^6)g?TAb@eK@_?2_uEeTCtwdw9?^1^3&
zbpgHGOs`%&@fdBYz?`;nGrf8RgVH8my=o&j)2mn27u&`0Vir{G<YszyfyCQP&n}dB
zo8j53X|+$H?UC`yXYTz)p1MW!U18~oS58vh5YbiD=S#0#WtL{{^u?*#W;*IBL|dET
zsl}_h1u>!t5pOeh@xq9=iKnjPc~|MGUnK&2zV@Nlho`PXL)cT92;$A$)T{Puo9WCG
zUEXFo^QutOjH;J`F29h(*Z8VXI8wPsln%dknxUDB{I;3?zGm!cW*k5@yV^{5Uu9-y
zy8GIm*KN_xhg(kRMiaHFbhl8eYSvh;q(rs4WoSz9Y2xjx&U|Kid!g6cR775Mt6PQ|
zGDI`IeO7Rs{-u$VSV>@Qrn|2)N;3;j%HYg&?xI(1mYe+w(zQilr6a(PS~~kgzHiCM
ztC+)<oAe^O=4R>31zvB4=N5RqSvu|_+hOUri%1-rg_{Pg-Yk7|QMlaFM<@4cvlcC0
zh_zhliG8(M`e)IvZV|oK+Q!m9zeF&FoC2BI?{KO`=UJ9cwanLb^pX=T>$xHpLu<2i
zsjuRjxYVNKC(F(B!MiuWY}YQ&sSc&rP00I}@U~@GEH~3awVz6#S4eV{((_XLGrexn
zhR4$BimA03sWwN((!lV#MXM7_uUizbwsg9Op0#l@d7V<D`M7h1Li(02_f?EEJ#Nvu
zgd@<nQ9gd9W*N!>xo{*ob<*bw8Q;vMoD7BGbXCu9OX5p;DxzBY;V+^!@?O!2bw`U1
ztaQXhwq&IvE;1zm-mW9#HLP^R0@k;MCoYOnuk^$vS2>I7g-4W~NJsoC<(iII;Q9u&
z(-B$T>ns+JD7#fKanQoHMT1XZ<rZ5Q`z=D@TPu&1-uqVIXXQ5gcD)xI`crQ<-TCc`
zd#-foFv_+Sep+z-wlX4r%T%r0P~T6H;g#-Op#8SepWoOo&{SUv-lprm#Zj?k(Qz$v
zR{Czy$?i(IbUY*5D;)Fv?6QEHMKxVsXZq?_f!*}g2e02&`ssV>kZ$3u6S3b`x?BPD
zcb#53G--0Qieb8rjHA`3lyA7*Tj86Pk@tk)x0P}C`w25I{O+yY)Jng5%Q&s{u>$6|
zl|FWhLN$JnGcY&Rx56$fJ@2hE(v^<)e!|QvciOi$P77yz%RB+$Jffo<AkQPnwZ7ww
zMHAaRo$*uPIGwR@{ab{(57@<X?=5tHa}L*e-=6MT=k1<bZvZV<$U+ltk<&4nuY>h`
z$m?J|A5_zKKBx2^{{1<lcNK|FljJouP{`R^M&53nfO-0F@yBivdSGmv-Sw>qkGG7w
zC4+49++2%7w!!!5qLJN_JzrcjvhBd%E_WS$fq!#X90>f|DLC!<n|;G~3F;^*?9VO>
zxZ5sDoe!s4tk`H<@Ta=SXd6g&hl}=VfZbhWv<*c3mZ11VCoP?JA=fX}uxFS}cdevA
zyt%5tZb|5*MH3h}cS1x50e703@P>|-eThi5yLM+F;M^681_76~xz8;9TB@6h#I9u+
z7&v!UVdwR@D=6(N70jSC@7P_DBgVmfs3VSkGHULj;d8vkn7epv8}s6;Bve#riJTIT
zS#h0O<EIsU=^)_T(+YMFaIQ3iP7z-h^X--#%$bY+wg(57EAgO{SL2y@&;ioDi=3BG
zvR|}9!3<4zzH;|0MSk9q3O@tpaitV&NnojzQ_#W7y-TTACjVO!UCkuqe#4UMBpUQ%
zY+Y#t9eeD`BIwv`&n$utTFxVjAXM!1_^IUHdD}(rt<zyuat;98srEjyVEo`q%cJ>I
z68=j;_(2EXlIYKUS~HfRE(Y6vQ`X%z%;4Vyz3Pd7TdwEEX8Q7_LgS?A`Erd*ICfu7
z>*(_;RUcm6A6nZj8b^?Q34`I85zxW5xhQKp)cY>9|J6aQ9g%)?K8R%uZ2YzH3MlNp
zRFwQCC(V~>>_d59Q)3^F`$+Em&6y2r>cKFW`wG+1qcHbr^Yn7Z0Hih9f*1gd$rgl)
zGlP~}6e^}Q>44!}i37cq)1oJ!;kJZfE!461HS$3PjbteTAoo=e!z|MQJkFP5&mDN&
z7Uk0`W8HZTR5up|Zf6(dNr8K9$>N%Pc>A<elD;%FYSK8Ygs(ImrKO6h-Ci0xwx9AR
zN5iJ^XlR(Ls17F1msqqrkT_Qj@D3u*lN7ffJlt;PE5NZsiQ5bB%U9Jqz^`YnK?gAB
zD<jyQ<noV%*6F+=(4FnPiz2rdT=<e{DY)=ebXR=%5}dIUgm7`>b|MwN?$j_G@{+Lu
z@#gG5KTG!x<joIHZU^n==6Y>-WAnV}I*lBy2;yE_gzcex&X(k3k2^Nkc;RZ3IJXx(
zZ6>INX!qULPx*@g{VqKQKPx8P4(iRtrh9czZ(D?!s2@jbx!LLvK6ujYZowHoL8E(M
z;I1Rep9Jbx_9-B6E^u_Ocv)eiJAu59<f3`B%LDf<_zG&?k}sg<BS}nii&K^@N>Fo5
z$XZ{R<_=sgFwGsP+yiOufs_N~9AgDi&XsV`11IMuyF_f&m2uF)$z5(~ser_}$qXGt
zoQu}C1Bly_)VQIHGADcO*^CzI$S74DwdHaq0^F|DfnFhRaODnkP;YKcH^!HX#kYfb
zb8C6y<H=2d=w5N<rgct@m-vy;ib*aD1ZZwcm~4@hwgoxa65F2H*PZhS&kThlIVx7o
zw(xkDD?y=CJnkc*70ML7g5$@Po3PuVOv!L>=a|J!W(n-vmZZjbdn>fgq?SPn%-nTE
zXv|_jT*95Bs4dA)#TnC^*5{tnwFIfL6WgNa7N@6E3nGrmwuJHIDD6nNQ47B=_Tdi1
z&1ae=0B$~W|J7S;s(r4+6?fok5*^7NpeZW@c+F>88IWr}Wo23vc=4I1>m9}_pE5J;
z<6Y;>Ti{&Zg7ezulnv#;c8l^S(bf6fGP*kT4)B`^iSCWaxK9~`12Xf#L!VZR$J36{
z7<vd^bB;XV=unXP9C~T^&Dr(V2EETy^xp84vp+Y&RZguzKn(cQI^=-KTs*`bESV>S
z{5qoOv`hj}vMtFe#CCV4NeCR73*_7rM)ncWJd=G^JsI~pt5h<kM#gPA#CD!E9w91R
zmVLp;CJcHD#%X3(7CL5t`RbraTpY$*5<1E*05Wq?827-KZ9&dUkAAtZ%^i+FpBYH*
z0K<H0=>aaxg-7n4>}sF-^g;Ug$bd`-4&);PGCeRuKJ@u_iW>PK&7{NA=*sQreYdo+
z0l?&$)o~<e_6@~-JCH9IOK}JB<**d@fP1+}ihIW~j%NV^5^Ia{)x@&Zhp9XG%3;zm
zrs0;5pWUf$?SoYa^{-v@#l82_%D&($hZZFrMs^?CGf|A&hxSY`gZfCb638$YeQ}3g
zbW29ODBS6gRRKHZf-iTlV?MMrfrQM5uzMZk*cPQqvG*NAvuM)cq5I$;$Dp;5=03E{
z=xlpMl-xVMQAEjG68-IZFfl9_dGZ#G)6NIuG7ocd?|4fwCwI`CKC-S@2l44cd!4|P
zxrmcHkTM_I?EoKhh?1`m#n4yHAU~~~J&ros+H~jjv$g35GqRic6r5@Tk~?(6Tacd+
zK6Pl30VM46;c1BgBy39<`SYe_7l0SL5W}5o{Q!n9B%x3Sd^?yi9}(~E0T}a<$4ec!
zm<v;Ubvo|C6!*~0yKKu~M+<B6ZlBI~*L~X+O|--3b}bnIgl$Pa1)tlOG=wR8i{hIK
zG}vx455R)Cz{DLWn0FZ$kYL`G1kpi)d6#iHKrk1OxPt@pF4Mx7u_fvJMqGly=hJc_
zh&!L3ccQpkaK=OM;Vn7eoe;zws&W^AxPu6DktcWTgLl>^SP<_@2ki$m=3RyafS8Lb
zxdRV75>#ZDn_S7)5gmh?5a1qZBQ6l|7DRuwVZmf?N#2-O??M50jK2#6+>du~L4Z5{
z!xI492YxsR9xp_p!?7i}Ef<|~56|X818+g7*z}F0TLuf<frEKhm}K733WWiKxq!hP
zXT2rq1b5oe5%83Gqs&{fxM<K0Rb*RcA*Pu~;vU5hyvw$bUgf>0FYJDMo`!c8Dc+yJ
zEh`xZY20W0n-@Rv@?F*myqI^bTxM>7MYr66eR<c?g(aYiOS!X5+>+<2b13djkrNi2
zTN0oB?5Dxxr)-7`Jlsj~+mf9AWJY?E#Q_rLO%^8*VcukLSVB8A%b)4bGTWOh4v4U?
zlDJE1&HlD2k~;y_y117+a4;A5a-S2ma<4NdT4}E{!--!mC~=>7@n(8_>~aMq-h$9d
zF_no2ZjZSD$F)UFHGFPU95#?$E_US(u*;KO`8uLAzQPB0U|lYH<qoRL#jf0`TI0#D
zd>v7|=D`n+u@J%XmW<QJoJ{<%*p;`0mo5u4@x)?W?rfgDX|)o#FBb)K2ln-O>78b1
zsPzh4a&H-%WgqWN%N2_Y0BLvP04@sWPORXoBqp$;Bm^D&K!>}PR8N~EE2yU}k>Sgm
z;v`Wf$(zC?R#}U*{Co6W2F2QGVN3|xxX{8K=-8G-bQ_e|7BB-N6W;|C?qut`u)>{e
zYZolI8+%n3EVy-D1y~ea_a~)W2@zRh35kWJrKF`(8tIOOrF&6OQaVKG5>SxtkdTz_
zTtGtUZuY<E>-)W5{AZpW_MCg}J@=k-W*(m3Z)P^WZrkj|4wl{8a?nmkM`O<&Dlx&(
zG?4WAc=(jJq6Ze{**3hrn$f)#M{3J2WTRg_%U_rhtoj)u?nlt@_WtLWC0oJxHlHGJ
z>(K$OS$@J_)F`@ZuzdQ9lh~|uU)iM+IJ1Z1)ysXHDBi+ZGAso%2m3bRf=6+1efgB7
z4NpxYcbJE^o^4XVEYh);oY>sQE-;aoK)@WqBuDCxhX61|pWAEub!eHACznM!Y>Ch)
z6%RBw>8~&H>Z}Qi{Y-MKHu%)P_GROvHnfHqJn}g@z=1TTF-;sj#iLry0*K<B?HpA!
z`^Q*R2604dmF5u#(}KH2nij<7=`rx;?AYi|@5y`^BaFKg%-P!6XcvaA-(Refx>DO!
z3?_RlCz)<B>CdN?;H}4zkl>vKSV?NV9xI&L;M3vbGV>nSBmSs|yq(N{F7VkFW<5u#
z3@tAUxD>a!b+!sPO)?iap3U^c(g4L3iluczlGd_vS=?4W_VuU;!2aEWvu%rGdeeK~
z(v$E}Q!k@S%n$l+JN7%;S8Vm?YR0FTX2PT;U0D<~PhC@xw`b0@82==#bp*`-zp$>$
z6qBo2J+HJwwOo@VJQe)dY*@QQ__e>&e||~cHP#r?^P`1d!G1W<*UbV`4O&pShmeU#
z>b##x`N>~ZFKxBZJe4K|#VBQkaI8P*foF^rXR8a*`?p=(%OQ+o!__!y)3F`JhiATX
zWRo{`a$6r*itw5p6wl58R&Gm?!d0)Ey1z>YEwf3BB<HNrqc1!3M`(j!omYU+hCn}W
zb<1(Wk&Y1BolNz{?sOD}!)!G?7BFZqRt2EnX!8keW0gUO<Gt^&1`yRk65I1N%CI7n
zuP4gmbQ3t?t1g-3d9rgLHU#VZS?{QjUtM>ZuUU&i);)i98(@%e*xdY!YxM}qhL@Q$
zaei!Dr4eF>9sc+H*9eK{BC5srntaq*C{%P??l}eVOkjTB{=(*4r&}dFS3zh~^HP0w
z`@P56zVOQ?z+yF^W)u}cO5lklzD~cqgM+Ad4M8v8OrmpPPmZu^U@lkOn@{iN%<}Z5
zZy;?HhEp_O4IKBvf~R&3OYuX)jihH+o=_X<E}&lQGt}A0B1WMOJyiM92XCmm{8dE-
z3{OAt_MwK35|w+x4vvIR6;|F%WUHQ8nEJeqG4gaukfm>sZW1M(POM!dk+$Jn-X^J?
zh|Xnhc83MH2L;FhEUtHa1jWuH81JxDE9ituwwHKDX*M@3xQl=C8x>q@7?o_#e*;hG
zTx<ennT{3{7WfH>R=LXhT3dKx@Nbm}J%5>QWn-zBT|lBwm7zX^V9MuvVgpgnqIIa+
z#UCd8I<t$>L6F~`)R7A5h;(uBj+PD&>+@yQP{J@^7&cozc<A}6UuI1djf3gY?))2h
zzk-3Y-OGuJ{l(L?&F0vc^2>>KbG*RC`#e{kao)5&%`4FH)(4(v%Rr``pl5nJ8fLR;
zt0ix#l5BBueF^#}NfkUzmXl2C(Rpfte&ne1vuMrXD6vLzcQY_q%7O29P^7Cd`e<O?
zNhWnU2@XcXBD)qic@4lQ<hkpjuOtOkOtQ|kynFJ!?=aIQrl34{god$#{R>p?tOlsH
z17KLwZ-rus?N`b@C%doGlpOww$5>IAz~Qo02=v7bE3+J!veViF+V>$MN9%K+;YHJ_
z#^|Mi_a+sjp=noR_E(HZbzbo>q!hoCFdKvNYvn|anl#78RW)utBf3~1tK<KmQ;tzf
z!{|v9=HzyP{Fm0u0dr-un(*VDWPxw_-glaRHYwi`OXfjGnLa4GoN-STGJJ&wkw2<l
zQ{;JUaBLVc01ntZ%Kkn`krqRf)&K1vo0^>|BV3CJ#k>#FL>iq{$9HL#(FEsx0Pjqq
zte2xpDv!(dRV1I>+d@7I7nbcC!&nzQG#}?OBUJUY+pukgu$(^`UTXkNAbsG8LSoQo
z>-eNwUokqYbBXlA<FmR*oN%CPGqa0F^pwljD9IjuRfc=`1<le^qOdRy5)Y!2FZN-Q
zZZVG=I;NU{1JPb8QnaHL16v93$8kgQ9(nw3aYls%X%@OD;T&8IIVYRElsYD6Z2NWS
z2~(tHr<uVMq#~Zg`?X1XbqsCv23+prZy!4Q5}C0n&Mmy$=+l2uj~`=Uzgl9WD2e>x
z%ExNl+p;t^EDIkcFl-|ZOv$Pi;?xxHyfPU_%jt`Hqpw^<o#ynx@~GC9lq!eAT*F03
z5oK0_5&~@XfDsxL|HS0<=?`Z@i)?s15e@jRum732aE{a|f|f%4G)elkA{ql$%4guj
zHY$??4oDacr5aOd$%BV_H}})S4jY{j2cjot_O|<|3JzgbzLijYr5xGkr{!~N4(cm$
zen<Pg%S*`DFC}}62~>~tReqzws7dA!r7U2t-WhIVedloJbGeM)A@1-n$;WM*?W=dw
z3f}|5l6;Bhjk8xDMzPG3=Y@M2s#P$&xtH{$0^KUECU?|#v}?3&30F=yQ$mmF<(Il{
z(%n6{pe0FOv*ca#;7*&BD`DD5W0kwxa3$+7H?PXr`zlewPUkRt&&>@1-UhRlW@!o$
zSSg1uIbG{yQf4Lk*-W{J_I<48>e+L{D-S<{D2oB0#kP%yzMm^WhT{yXOLsN!9J{eL
zOx?}d@RVfu@l4e^m5tn)hci=chqA~_uXjd6CgNy&xAedfahieXszKY<qXUC_OP#F{
zS44|9`!lrj*WUeu2!!i-%gy1jZQ#vi!SSal!qWh!Dt~{P>fRc0#OQJ9&A#es#?D~-
z%~kYd;CXunLbv{UDFd-edvj)txY{iVJY2VLINRqI&3HGke7NAbdw58Dc|wcWu0b5v
zIW3CboVFlFpP?8gLYLzZN1v2P_3`A{3>p@vmwZgn7dQ84Z`uPdk#Ej8L`1&f+!_D)
zW{^x=F>Y2Hl83NUt*|TcQK)O8{jrfna~U9qIBY=(yI1Z~%$!CzJny@@YTp@b;Aoi{
zlnoO(b{$<vo13KF*pMZ^G=7T~c-qB%vj+-1@2i=&{DwBDr?wVQoDmp#^ETmd^727d
z#@K4dM??u{pp$O%b;f400PtDkllU`lve>2P9q-N%drT)q6JjgX%&o7OuP;7a7upX6
zR8+LgtHaBEyXpCafWxDU&0N~B(#=OEGrPv*Z*NNbz{iM&<oUAKew+=in&;PjW~e#p
zwXPC}<}aNC$pfrf#IUy^l)=;vUlc_prdvvBw~R{h<Sst!8c%HwW=w7F`q1~+mf~$*
z7^zxxT}6iIDhD`oov;o;@MW(J?z|i!1rh8TrU$6D_s5U9t1f@{1icJjt5X6BHT&v4
zDSMv$ZO$U_6dZoA#$s`ag|&nt9N7LSk(L(S`uvQA`Eld!Be}<uu6j+zGuLaD!O|Ih
zJNQZdyX7+8{6^JUrP~e3pM*2C&AZ%M9-jD8&}7($C*HfPy_{@$0XdD1ZhbMnsqQqe
zm@{WnswjJDFTRL_U5b~AIGR+tC^~ePNDJIvFW?Pc;0tjM+)~~}A2ZI_T)cTz=hTst
zm%#euTC~$a#$mtCA!>5uN&ti&du(X6dMZL7+p!MjZbZ(S6#wAb`Vvd7m7nrLKo$=9
zd^SNpvBxrbuyxYVdrxt-JhQ5)^732Xhp9uue6-5N28TA%oIZ^`9Zqw_bOx>}8AKL|
zpiEyt`^*&qUM5cSiMk5a^TlUxJ_fCW^GN(o%QHaU>%02<Dy<5GmXaX<Q!wFMUbM$N
zh%%C?*N<BE39ghcVb<;R^5+XLVp?Z5+vGG5ixeKhsTDJOH+2CFc?j|PO0<mi;$qOS
zXCnK_>iEzV>T$J-V>-!IbAb4DC|$8LV{`olslQIU!g$JQUi1bQ@23ocPz0xPpiMn=
z;4-~5dZQtgzua^oSuC4&$Za${`oNbrO+3>U3-jRTj^dG#GK2e0Ut-)9ES)+2$n!^C
zfV3(hV6n+xdU4z}=J93y5%2<4Srw)J+MVr)p|1&5;b?wZ?&$jMC7$X5PtJ8Rq@~t(
z?&oeP0?(`Z0VA%ZlZC4r)Y8=P_8Y{^4wnzW1-ShS008)fxcRvL=z0Fqi-_Ddfn>bg
z<TTw(-7EpW6}LK5E~EeeNl5^>0U&cz<WWrQ*7)}kBnxqJ`-im^2NwqyfFC)m#$QHA
zyT2v@{@WP<q~+~w2>_{?T3Z5u0PbJT)l8w5$g#Np^aUwfTG*OOLc9P5NEH`=Pe=&B
z4d&tk82vJrLOMp;y8?Ls?jQ$+xI6!2GQXYt(%yDKZXivhYpAJ{tMjchbMHTDd4L<#
z-SUqlg|w2k^sqIz)R2?BRsOYB4NF&uJJj6L6>u9j4cvb%O#mt1#`iW-N|sL6ZZ-hH
zzo#W@>)>Vy1%PB7kdc+PG>2IH^7NM>H$VXS8>Y8o{gpDW_uIO@es{;4#H|C?`?vbH
z%&jV@52hHY<A6jDad2=jw6uv=pGA_!n3%up2xUn&i7B`n97p^F9ZkL6J`qOA9z{Zj
zYF7mar5jIzbLi+7!OW;*ebgP4R4(2T=+0c0Ar=O&{dW4(dDi^{26uPg0~3g|V=Xa4
z11~<>TGD=+zYvy;B*Ko(SIH2VRDBrM$H16POQ)5PBr0M*km=2Xvu~ER<$YEbk|)#K
zN}OceDb&OBFjaebZ_b_cGBDb)j_322G9x|tr@2AL->E9rI8&<HZg3~COq<Tirbi1%
zpmVQ}qjW)U`5Yyv3|I%hT-4~ECX3#vO>?c5>TcbW!OoCi)Ocj4%UUXBcaM~;vSK&%
zil%BmkCcH*ZgvKXH0M*(CsCd@C0_I}D>GJxv{m9+Z}l;j0Z5CFp$bDn!jS8ThAn1^
z=?=32qbv^3Ksvtax5%eQOi546j41N%xwD{YNMaYS6qJ1jsA8^sK!1SI%KZXX5-b=}
zpk+51s#?w6Fe)fqA_1bDgtOEJD)5wfw(#YC-cHKd*0Wl866cb&opi$P`FyQ5O!Mx`
zG&THy?9T!O`J0SskxU`qNx&H&nG_he6)%RGV-%T(8n!)!nMO4(FpMzR3Ufm57V?sm
ze{+Duy|rLkgRwI{f_D5EWv+h+4;nZent9t~5Nxwga+eBdP(N4!4G77ND~F>jM-4q1
z3&stU?%u>Mq_!~bZlSYnYMf|b;25EhXeHa;ToLet%d4&O=C~S4F_tgmRAlRad?2&`
z+)==Hl}<qRGNhPdCQ21Vy)-G^Y@@~zmXXBu%{Z?6DM?hpb0Wp9d1fGUx|Q|n8vf7G
z<h7%_aXx(t1CCR@jSs0_l`hhW5hp(s6sv&G>p>nu7V10^`HsTr8E0!NtIW9Kc_-F@
z7-zS6+GbpgH~9TUg*VgrMu&a96wIg7>!*n7{T@;B489LJW!(kQ4tV*}T^*7MgWn@l
z-dB)(jaZYF>#j(TjgiJz&Q2{&Muoob%&ciOJGh}XluYTXKB-xd3{W%Q*3*eydKj_~
zx_g7^xJT99l2`pv-T@hAcC(1H#;IPL5EAllX1eUB$lK1oGn@6AuU{m^hi|NM_n9YO
zdc@C{F%^MeUlZdM?<~q9p5ccp*(4r$te-(I+)gTKn+*5kHSx%+l<TBLb9SQ1bv8FQ
z*GG?~tVIQ^0=|XDGGkd8T^vVyCUu6j1Rq~<ABf*`)MEIO>4_1Xa(7vkl`(gQ)Pgn!
zqlnsZ<-Q?iHv{ksUC6ea@NDVfB>5VV(9Aj-MSS=j=2Q{p7)Sc77jN!?hF&k^m<w<I
z)H~nEAEqhT3|l2jw9y%7futSL%YVTZ`p!gm>2o^6GQJ*;l_9|2yCL0^_13U<#>sFX
zw+T4vY;9eqETzyxpDz*TV^CLV)i?3!Y_|SbxG3Cy(Vw|QJ#jrk+l5q<?b}yR;%|gu
zP<6UTnBlKDb0aoJ$p>q~dmLEVm^ka11U1U!i{uSc3+;nz-{(ivKFFV!_!vE!^&@qD
z%-u0qN{1l(P~j|3Q`|w2#zQ$VXv(lZk2)!sw-U=>>aLrjQj(GG>cbVeP6Pa`{(cdj
z-B%1bMwHc?KYZQ>4zu-vW7)t<{Cb#jxf6Y+f^iRo-f+*%&tP<Exfk(k7Q3;#Iyl$z
zy^!9RD-m|r0sTzGx7vH2Dt9_%{+_$!Zk$p)Q2g+a*P!VBP~5SFZ#cvJ+ns}VFXaip
z#e(&iXtP&;)}7G35wT8Z8*NO(uvNpAjKTC)BYY$=i|wA^k!&968p&ou9^<<qI>Oj(
zeePE-BLCK*LA6QsU9M_5#bZ39b1PPkL@S$UL0Xr4?;;%W-s2fQv#6@qFt#m)Y6%q^
zf<C-EQa;hQ{#2||TCwZ0<HDD+`)<A8>5z`sc_&xYN$mZIL!y-;HIsuMwB39Kubiy&
zGs6+;MQbe8E@u&qk$NkWn^SPt)2V>hS=XG>MnByw_Eem*dAP_@%=`s&NHI0zJ~%Bu
z{ield=kKOm##&@s!OFlJqHe{|vOIDeXA!?GF!rN-ZuT>n=cDd9Q)jQ}%|gyJzV!NY
z@yxNn5`%jG=jKWgrq4e`d$3V|P&PYd)vVNTd}!3M#_C#CFb&<ttWFax5GnpN>M^V{
z1)5T^d`&*$cb{wEnQ}BL=(LF2=l;<WDxcA*@T(CK%6=@?I=l4rAC%~x2kJj{MK@R&
z<88CFuurp^an+6E$0bD<xo68@obC?!)QO^%Dz?szyMpT*9u~UXk_sBEH)=N@r9~7r
z2SZ;j!>KOny{_<;b8J7>ZW>O`R?0^veN~7xBm5*w<K~%3C?<!m-aVD6nZzGkKuPc-
z8l&!;O~a5kD$uP;lr3K0EbTzij6p){b<~vFt2H=X$QSHvCgPX(HC~u~kf>6cFDa6N
zahb_Hdh0*!UYEBC7B^aSNj<G{3y2}6>?0?Ox40u(UP7$-TERNrM|ar5@I<9%I4pKF
z{GHBhbah%KeSh;+=r#!{M>aZ(Spfybz={4D)imB$rpO;PtE+2kSy(!<_<LW(YNijY
zbQstc3?8Q)a#?N5^rybKlp!XfB0maJXq8`8D5%rUc`d5!@!IZigN%{7Zqz<V=lS5m
z#*W;qvcUbX&C?4tjkVsvZykN;KRtOBlKX%;Zshfjqt8K)vN*)<{`m|Uq(yPD04vYP
zXtWv<SfQeSg}kG3<cE$)jZFK4TvOH&I9(ZKY<yU9(Y@+tbC<ZQ-#mO+il*l+j5i~W
z75Gb|BID;u)SJ0t9ujmh;3<KESGLEUTM6<BqS+$wI{k?~fp3VI+kZIQ)_Que?-p20
zfyV-79Ki1elB|5KyNYC7)$A5JoEaZ($)sMBUs+j`0NE8nIJO-sYaXU}Uw!#OEApr$
ze1-SZAz2Zxys*wVzi=K_ezUjVP-fGQ>kZ<fVeH2mS4$hNmnTjYUXOOg1_$Tv;_=t@
z<frQrZ}+~kDK+hUG4Rg(%kd{}Rh;-($^p97j~m&}C+vCIm+UkO6rs<Sk*|Z)8VT`h
zv>~PFEXWRflh4hY^rnRDG{VuWp*CY;7;Ar?YGPj^0g|>Qq3>t$l<R)#HfNPkZ^Oj+
z-AhAWmxkT&^1kX6VeXR}YfB@7*R6OTj8~>s`>#9q`<A8lVNhH-D~N8_7#NhRA_**j
zXR%RpHeYR3fD8&Z-)5C^h{@MCsB#84+PGFE3?EEebEM?@D&~i^FB|v~sj^K+jj4ef
zE=3;5H5J4RzNiu0iqp(UA%<uIW!|O45Q|HWu8^f9YYjbGE8NqT;d}Q{Xvm^OIcoAK
zST|&j+TQgMzv`}fVUlWPmGP79^;M%9Y$-qg>9dRS%R3%IEl&hB+q_M8W#c4m)t!@6
z4}XYVqVR?X_=sO}xu@_e(OOMjcSH{ZpDB)yGJr*>7LK~d&c=dy1NF_I3L)BAI#X;9
zoba-M@)H&`TW}QS+E$oNXprt+nIIpK!O?3*btEaDL(w3aT%jS3JcO9{wU4jg7};B5
zF`Qm`feZ|up_i_AR<qaJQgIpzw4aIAx||KCO$LY`cbn&R<#QNc4yD7>*AYkWM*JPl
z7RJV2ynv@jTVLQkGdN)eHocA4^ct+ag0Xpz9ypeMJ?)5=t^C5<!AUkK9?Rb|hO_wH
zusE(@jz5Dx_@aB;X|vW^H&c~;sKqH}N%xH^(|iW8dK4T@hD5;IGuoEFdQ0?Rvx#H*
z!OWtJ%bScHzvbRSO&t^E_2^E$eLCfW9&!Tay#O$e-<?ZviXBf~|2@qlp_E7-RzK1z
z7aZ7?WTKE|IYFUWy=5q6;0^HV^Sd^}cIQzWbj654AI4tBadOtY1FcyT)?}jcdEk7H
z+zgXEk>X+QxnD?SxXvuU!aK(d`R7zxCB0?DpPUJJfw&sp#zICtmUSXJ1M1-IniU*V
ztwEeGH-NhpR9B{!VxWrBAigWAI{m`x$u@28;&R#rwS^$h1Vk`VqT-%VLkEK0_$B0g
z@p}OBB%5Rbr-o9H*)gSgsm{pi>9BW%Lh8#GR|*=6a?g!&ga;LOJqfmk@AZZOv)*gP
zk-PQ1(-j=Kn)_P#;>#;rQPMIIo=Ea2P8z+M9SbYLg!iyQBTJ0{9rO|-knE%<LG^?m
zbw$XA?Gqnbz@YqHiT6~Za&!He?Qn_o!3b}vmNrW}TfraO`ApM?H6Hdmaw*%uwtBpW
z05-<^%Gu2s!jvF=+O)?&3^PSOGeu>}^|+n{6KJr~gL@vN;R#aB-D$Gj&&Pe6AdamI
z2FEg8a%TW;I(}FmfP$heAe`igRwpmBAf$3gyYQaA9v&n%vHt9<S0Q%U`klSZ_@mkw
z3{&g_pQl7t%vLfA?#0y*<B+hT6@lo$(*%3nl^j}4&JsWR`VPxfRr4;$D^o0EpZ%dM
z3ggEt91aRQ49%p*3p$L=SA7M`gG*Ap^j1@zu#XbW6T#;S^i&oWT*M)UdEHrOH*}{L
zXH~4i;GC_VA7YU5!Mx?3hta1c9aBnpq3qu)DeGNm@h91>>%+oes~bHV8x!}K{eVh8
z(;`b~UCdEl1Xo(k52S5QY|pTIa2l)DBfL~T2L7C;S)Qq~U)G=BIA%+NOnvt2^!brC
z)7v}q?OtM4{B=~{a|Hb5WHR4{FKw}y>yMGQKh51{=2rXG&FDq7?{r+~w5z1>qPFZ~
ztl+uC<>kIp$sOH5yU@J&=%(~|b9ZI%i0HT_b*iCZ_M#;yc%!M3@-o?QH@fwvarZLt
zEUUIlPhYWS$noq|NlVwBe{yrg^+C(qADxDD@40f-+n~9}o?R`|Y|EE%mlu=g{t>Sz
z&!nQ+-V5Ipesk5-W1a})J#p6S%$Y}sBUZA6a>Fur>6gdiIov2F6w15_tAlf8%i~0X
zIOJ^bp08e-&vHUT-nYdj=3@S&$}*SduO@}QQvCji190gaCGs=N+iR500d2Nx$5MHV
zXF}ml1$3e}Tu<oRtK>6_W<1S@jSO`p;$%<BMCE#WB+ed`FL5=z6zUPO3GsoFc$(G*
z;1x2tTX2soXI1oQ*p|70svoR>$|YZ%o>~mo_Q5R_eyS5Q`rX@P#HKtdUA9@jTfhSI
z?o&mQ2jzJhxd_3M@$f@?c_D@?-to|w3o~ksXkSsvft5^gahibA%w!HG%v=@O&}VVZ
z6pCgI8zeKF5C9z%Hvr!i&QKo*ESq=WE!>Gkxf^e1*f5dGkgU;2@M^Jh;^&B;w$f(L
z`bS-F;>m!nW$e>A=J|*RiE-^IYkhYPcq2=KALWkyjAHoItD6*b=z?j916A&J=%(W-
zt4!GfM&*i+#n>6L_LqvJ1is{{`5Ya)Zg+uvm%43;@YDOOmdWZ9NjYQ0&?m7%=wWdI
z0XY)5k*v1Z3p||&CsQ*-07B!KI=m(5yMQ41#k=~3!-CJc&!<}b35Y-QeSR|1B|diU
zf(TeSC^)08mz{U<A6M`6G@0#S)vdIfirmiG!9LY{$G?Yi^YyO4S;635DZe%|fsvyK
zZ>2a6L*~(wQR>4@NpY9?13vi;mmiweOok2nO(&-7Ue;MY<i*;|+uYEENp_OgpXp2d
zr(B{d_IxhI(^)EqG=7M%E;Y5;;^p60qE)otyE_)4Ro?zxTd95Oe20)ykq{~{-8a+o
zz*~fM{UJ2w7+7&GmrGL0!K}+6M7J7S<FX?sSaW|gb@OsAs1P6L=j+H!v{nW2O?j_x
z%#8%BX)ka{CXf$An_`r>W4{nnx+Ly(ZoKvmZmfx+U>82*=6C|=uem8EbiId(nG1Rw
z^nsb~qRB))$UE=pRXLNb-sekURGNop1}M$nUfA>PMUgd=J3ng;#DcRiUsc^H!GQOT
z*BpW{4NHPRc9~7+HzTNl<a_68wY+FzWP7&chK*dY#vg<51ozsc1rhRh#1~OBELywJ
zZW!T)<X6M!fgge@(8QqafgC|Rui>X?VjWAgoI#_Gp8KPUncJL##|^px3az_lOEqX>
z#Cy%KMQoc-LGc{>SGlkxFE0?D3btVN$oDS4Jr%|W_nf6$OEDWc;2fweq<i@=V_ZRY
zcns_%6R!@2R|PB|{k2y-4E-|VEJ(`PglZNc3)=<ZdbHmFd>K$KF&dwvN1;6@8v?*7
z&`y$C2h;X`rlSN_VVsOLoTsCVH7wm@yhtRR;(%MCHehVINu|MPKtktl*u8piKuJ%q
zUkBTnG{77Uw*B70K6y-)3#CF>gT7VWS$sfHb*C}&%OP5NvCG~%#+aZ9naYe7I<<h{
z`B$wec(Apw$#uPyUlYuIT*hynPPZoVnK&7ITt<z?Vh{svi)ufK54XqsNQF`y`)#~N
zYWz`}j<-o7Vd9jU9@;&Y!f=$2yi3+-+Ux@7xTt-~UJ9*XR7FgThQN9Y97G`us0i;N
z)is2#MxcLw+A4{P_nvE!@Q~L_vUQG-Wf#^ZY@&jdfRn-j7sn7u!j8sGv3&#QVQynU
zvtkc=U8eB}PKOFa%g6IlYpu*un?og<%6i&*jh2tg@;-aNjW8wqi+}9!RWo}Ey9w!z
zh%LrlFH?HHvksQpN%YgmDEKLM_vDfjDp`QV9u8W7MXML;%4h5MurhOeF@ChK9YSZ6
z=(56aPE^l{)(`h<rCOgBiqlS`G7x^*UIDO})WT+++z)3(oHsc*1B$7gsMg>$7!5{T
z{isry-*G6xQ|+(aTH%H-iB6t4y%}&N=pHsz6R{8m*k=w@VBn9@@kp(|CF~wDeG-^R
z#Fg2CdtIIh@qwLk1Re1Ts1iL%rPk0y6FK&Hit{7`HgH)B$doFFF`_mZ#f17X)qgQY
z!=WLLX75OT@*drfMIr+>MHotjI;<N;PW%k5Nll{(LwY&4+hz}U4?C0?{uR{;mFd9l
z4T?EVtwJknt7-IiLR60jj?oxKFe})j)>rKgXm^Rafvun8voO6-4I}_RsSSS;jiJ!P
z_=n>XRY#i<6b}ztlv`W;mv0DX{L~=-4JO|rn}31Hd|-Z_Kk%;5e`BEBx47*uAQ<$&
zK+u0;o<?zfPQhIGGN<Rbpn?dJQq+7>$)bE}<P#*7v?yU&Pl3`wdV8l;E5lkp(fs1(
z?2S6ZIKR1?7Z7B7wrr3KP%_zzl=O|;2S4oUDPqLr`LSJ%8z}0Dd=A6u)V;l~tUbF3
zH=F3Op+HOfQV+YR7z;}1LZgKEGzp<`vUc@Mv8%XX&OAWdo!}0Z-RVf(q?2sui}NYU
z#~IbvPpic{*LR3VKC3XsJ;yI88Ql;T&MsQ6ePu^!7cy}rtjJS#^zvq>u}DK|L@+<Q
zXzOkYt_#z9?t(T}SNiwF1!Z353lsw>eO;|up@VJK%Z3;0b1ez!z*BbDrT4YOoGGeO
zCXXsX7xWuIgPv*V@VdleM6)$#Fy4vXzTH4%9F<Uo4S2#LE*{r-X4~WJ!fW8PZlm~=
zH*Sxzjok}3zVp)8CBj_iEC3a=E2s6p)AcI}f8~pZ=Wpnr`xa>bgIWJZ%5SlJX-ijg
zsI9Xb1bPd6|AO~bOdXL}y_~+1qO=N|w56S?w!0=0LjSv6*3{9~!5hHxy9sdH#`?R_
z!PFXwm4pAbl>Ck6b8vHkxd0rz{9pjLfDjK7)#m~Kh3d<@nL5~-OE_6OSOU0y^^<Tl
zzoi9)z=FTT+xgwf9AF;4UkWKx=ckso);37y06EMrm8P4eqc%YBcmG@A=^x>Cg~&>@
z1Osjn`+p+%x0J<yN8|T!?q+Vk=n5?)M{padUs_31SIb}I$Nv`@Td1p>l#MC$PXLrm
z|B|`EzX^|j4>#afLVlktGEPX6z}Cqc0MfB_l5ldh{iFEhS;yAG&BhhUitupXuHt|1
zJp5dLwe$1v1OD@aq-c=ZKga()0+MkNxaEz0@BDm!z6%Kc%PT*!xCD4^E9rml{5-ep
z4AKwxpWeUizykjogA2fmTsj}JB5vn%%dFgTJxC4m^NZ?1QZ|rhPPVta3E=i3^Ut*X
zcM;!mO22DU(bnQNO1HF=#^0oo`z^)v59WsZpRAM`6k_3Sj^t`s%uQ{f5CAtPHy<Z*
zi7Ym5ZqAQENcsz@wT7BH+t`}BazdcitiKCg3dyy(*+QJ8Z>cjD>BnF$FqlgaEXc*p
z!_C9R#sy~P;$r=$(|_@9f2c4iQ)J~stbZl=*Ao6B!v4iEc|k3$aJc~7ytrI{ZvbRk
zc=!NTfZsX+e(u{q-);b>zjXXUJhy554;`2vnf`y%A%*|Z7tD){&%fCT@bL@$XJ39H
zJ|SeH|J{yPh!2^a|I`WmmmMFE;D7tz<@(P#BiAN~ERBC3j~^_AETlg=H>fG{+=l*Q
z;WTZ1EN^3VdlA!sK#)oQ&Dq_`@=jLB-2SSI-@KbC)a_Sv1^9W8+$azzqbiI0f281R
Ay8r+H

diff --git a/source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_01-mod_100-low_error.pdf
deleted file mode 100644
index 81dc12e0c98617dbbcdc0a51400d4e2ceef72d6c..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67290
zcmV)#K##vAP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz0IyAy^bX|kEb}p_MozZ5~YZk
zHefVhz=Q6tnc;!aMmNydIVgKz`|Z6&uC=J0_vXpEU!hP{DSk&gB#M$K{w&(p`Tn1O
zviJY7cAj7V_2=;~$N8g;^SQr%{r~^@KYsoD|Kt4n@BjB<U;oehfB%>F|Nf8TfBWCx
ze{g>NpNE}a|LfPkd|CWt{@?e{x&OFN`x@i?(cl07=a=^%_xs04czyksum5!Xwp;H%
z`unfn-P(`G9}%+K??(E6{r9i`@XyDcle@oK`_cTIZM?hBAKu1w+t)w;JpTQE`=|4t
z)<^&Oza9VXpX|r@pZ@uO9RKq_f5(8|4%Ft4vCS@;-_OmT=g0KBI+5^)Zg=}}ZJ$E>
z51r=tagVn30^twc{0^>*{UrQj?0<gTSNHz@>aZWr^&9s8b>@3-KkVFR2f`m_XXA%G
z&(;lu@4LOl?^BdX_(QkbD9Y#t!XLU#Pr=Fs$mU;^{ywiC<2TZO{#&HK`}HZxB>Z7+
z{rnJRwExh_`ll$9@O`)TOp0=LBjFF-?)Tv~tQLTTe`pEb^J;e4{r>9Rf1H1R2Yj7>
zeF56+pQ22{A7<zCQ<O>gL$~*i{t#sn{?N_Zenw{V`!4nj3Rbe8gnx7gjNAKLwCufA
z=kM76Z`lEM-5;Wi_8(?9?NgLV_(Qk%|NjtW68_Mw-4tbX1K|(d%qUt|0ucV<4lwf{
z?e8B#U;l<X;PFpMM*I7@UDu}^qy2rSdG1mitv}o|{g->b|0~YMHX%<qc4mpwKP>g{
z-Ff{+=>JVh&+{q0&%Z);H$9L9`|hB6Z-~XK>L$YbhW|&;f$<)vkN17?HQv{#|4tG4
zODuWs_puEV&2Q)SKFa!=Vbw{5Z@bz1++6>;`W5B-j&C_w`+e&u%J&_8r1D)IMfnTM
zVE)zu=le8xzF&vGunIQYFJe}d@27Y@zX)1UzVG<VkA-LZ+fMDRvV1OmQNHi^K1V;-
zz9@fTCEELp=+7T_#9zA^+gk_x6t|*$Kgs#|MEv<xl<zy<p+9c@Ncg_n^Hx^RkJS+6
z+m7A*W9`}g3oFs>{4wu79{+A7{*sE=yZs_;MfrYu@5kP!uodO|j_=3i=gJr5`;PA?
z(dWt+<@=7${kifY{FSwM-rq`P<=eIRYggy{jrl2TMfrA$>rLw)hj3B8@90l-*soqv
zzVA3^FmLN9%J&`bzITe&Uswl!pTPF#J@J>6#^?D((2DZy)RtlAL(oL{zFY6Vta?$t
z@A&TUx#~svzT^9?|GDZ#`75f^c;ANek9*>;=}vDo^%p@a${$4gQxE;rF<)Q5{_wwM
z$}!!4S`%OIoSbL7-#aa5|Lc_hzct_O7;it$yWQ(TeXD?FYW#QqulQo;xbOD<>U`@8
z=lcA6TfKSv_XYL6dD_xM@&y*H36?C&U%U-2+VYCxc*rcuTda>D<zo+|HzidLP~QJ~
zQ$AXTS7lJvo8(P-%k1$BsSOa;Q{y`0$3F-)+%=6hpXmDfI(CxlQ%mbwl(gU#1uyC#
zy#Lc8)FfkEi&T?*3(uQ!#TPy)HSMw5+rQ`f7ANTO@S;VeC}ZPG4`WN7;Gitty(w?D
z96QA~#`JjMc?>8iZ3LlM6$Dzgf>Rcp>OaT?bJ%(G>7=yclLepJ#-}%Xjv$Fo@0Jyh
zqDB4~Y)K~`tU-y%#C|$RTC;f{5adcx$d&v+8@G6n&$vYyLq8PDI&N{na>d3a`L<kw
zH^nrfSb{OvNBKj+@i)meqTu+OVj5Afa}4pul6_+&k3fnMx%gwjw?!e3&fIaMi$}Qw
z7DYTdlWn7kM<;mH#G?~DYTQsKSd^=9fD{8VNzMrtnV7Z=67K^|EIYxV^9O(SJ@g|8
zrV$5woEvjdmi&2b%lzX-F^zZq>#gSBTd&~Gn}Tjv3dN$J+x5WEctJ|9JiQm8Ke_eZ
zq;+!OwUC71jZZEF9%o^%9Q@(ngip5Kb97n@7a`d2reHfSN_?2cvqgznJJ)0>An)%T
zi_|#U5DAz(l9H3|>UCq%ot<vX8D}v_!ScqHOoQPfU?JaxoFZ+4i;`2cSjr;^(ZoVt
zHzs*<Nv<19i`9R(V~Xe2#ny?}`m^<k8Fj7xbw`U!c;$3D59CEyAL(~3VJz>Wa0$~P
z(E3%KVltgJw?&D~-LdXRkYbH`Eqp35i^7G!ax3@A)>@!Gs>cyc{`th{2V3!TE<wpp
zEeZu?=C130pqT^jTbCSo-@4?uwc+2C#rU54{YXk|sou6;$#`A7S6(%XLgC80eo>Zi
z9YG0J>*Boz#(Qp^I?VL-HyxJzl)qz<f{*Q?*p6gnyQ^2UD6tOXzYgp-<yzaWUFwm1
zU6kq->}%K7E7;fO)+^7bHn(m$y18}B;Ys_sJX-8Q-$cyo04b*6>d`Sg-+JZnbQfP8
z%*)I804ccFw{AJSzIBVmY)v17a@KOsA4y7wO6_`RM9sEtIU*hU7Zj0}hdzEN1g@Q1
zw;a*AbxVdxBZG$5?9ml-;fA+I-Eeu^vvrFRSqTR2WxH!?xO45MIN{2*YwHy(vJwv5
zoo`CR5r>P?N;q&Y+LU<X612%r;m$K@YS+5Zj-XVh;D*(OaK2l*3?}X+)5$P#3z_R;
zpQ+-!NoXY(`qm|xAXR(mwK4jht#E@)$mhJ}8RMVltzgpE-h}+3bhdfptEmYcNy^XK
z)-68^59^x{4II7m!emb#@~Jn!Id(qmkv6eKz_l=OV4n|f6Ff27DV<=Zrgkh6ekT4i
zJIws>DHU(x{5>TU69?{jX(LaZucxG9=DDya)h(p!q*SbshsE79rQ%4^V(%%bfF{2v
zkcu}YC&}N)36@k0T%f0P!kI#}C}cmJI%n6a;b1(w)?gVASKIK!nvO|Qp`ZDhT?DRx
zM~lqtV5ZKF*|~}a?)UhJw8h!+4c#7a94`ua(xZj<%*^xb{Wsbvd1RTwR~BVNn+!>L
z<~Lh%ES#|<MT?v;d_r0yygv3^k}Hc(gajTS^zaz#X)seSS{8Y-<Af8rgye*ud1`(+
z@8xLb{L<i3uIEK*BM20d+&6E^YK<rLJbUzT7_o~M0dpLAzAg&pI36&mbB+V*=OW>U
z<3EFs>opY}8rN>zV3S@I<Hp#V&a82RQT&4(xz3Z3=kua)tQQv8G}bGhZT3jh92bTU
zO%qSF)#i9J;KFWcA^B(v3hfFbPxVCtZ{L(PjyEM+?|(^BM&A94!jX-9!P_lS$rs(5
zqQhc1y6FlTxg8gUpY;^2Hwn$P<oCc{9F89y+=~NV^?OhNNA7mJ<8uc{!Tg&KijnX4
zHz8ULzoBztU~}C%Cr0DI^z_d+qroPVgdClo7Xy3h=JRr3OWmOZ93X|T;BlUm_~8--
z!w;7zocQ6Cgd<70h7^SpD|qtTr`&6=utsMH1%pTyCFH>_Jvtn_<I>IIdF$9Eh1BD+
zwD%JLJJ;8pv)a619kMS+zvE?UcsDFcUPX54*g!CorRINt6s)==FP{4Bo06^fzw`ug
z$oVB<as1RGL0a&XwM&K~pBS4Sq&^T`qPxaNPR`1{=L2KYLE>SJT7;3!_;;>_0$7^l
zz*8GG=%Pu<vB{L=j<M<XQRIv1m5WFRyYzf{Q*vxFGI<Bzq^o#;w{)&}i#Nrh475kI
z8k@PICt4w%P}LR%au40?NK%OBltSw{8k<sR@uprBO6iFZom*;_rzW~clpS0ZQ|e65
zYtqW<*z+ow^~&w*ze|w%jo_dVq<*0_(8{6fV!=DuX4g&FC&sRuqC;$^Zi=2e+J=tO
zjv1%<Eq@489@<cNQreJJwLPHBjS?do5dwPz!SE-!W(_kO6RlXm_c6`?8f!RoyS6KB
zdxn!dNpBtwr<AmKFf790A4Cg0&+wT=pmNpn&2EDxR>#Y7Q6Q`>Re(hSlUk|(i(;@7
zw*gLyw{3uv+CF%2+K}Sb9BgaUI~uka27~M6ectAM(>i#jS0Emri$Xs2c;qY!<gvZC
zQkeo9?vf$Zt~GE$F9EznEv<t&Lqn9AG`@zr!?n#CcF>zL(2h0thYz_1P0JsxVLsce
z42UiDD!(<pGg=s%Jvi%J?+43mZ7vZtTnjD{#WQtL2HL@UzoZkrNjZF(91T+Fx&;h7
z(I<}t3nBE>PnM(`?f{pO!l3h{RnjK-MlHgi+qkS2Hd90w3Bvn+q2`ANm(>P1r>g?*
z)<qd;$5MN}Rn74&T@;2h+_eV~N^1&HTa;LmPIHqX3ee*LYY-`y>R}C^kq&ANpV8%E
zh7DcTPBTm?yFgKQT^xq9)}@Nz^|~lLu<(3+lUD0|VtFL&=Y!Reu%DC+>8R%o_0dl>
zLoUiVdO|L`oEv9YG#7!t3eC6Yb#tZ!S(ljOjk+lOjW`+?0q4Uxqm}37Inu6bUDwK)
zval#vs1x^ihm@abz*=oc&4~-TPhHSwo^@9C)e{P8*AwaN(Sk6ZSa4i2Nx|qQnmMwe
z=^93+S9ZKcSDUlNMbpdog6F4oiFiIi7a@n*@d90xfp&;U=dpiuJV6&JN4qGwejcsV
z7&|qkMTql6#@$89*J|$=ZhxR5%HF#u`7_Dt)lTNq{@b64DW*D;l$;?q%AzFixl!Jf
zXtkUlE}u?gP|twDH8um67Afb4i=#iDQ{=s|2suU5S8xu5O*zMg+oqd7)nkUIz5}(5
zA^ZJ-U7*w6cq~%N`Kd1%mh2R#pp3~h{iZ~VJUMaZw@2(hb5UuiUWAx)<7=Vcsbe)}
zt1Lns7O8q1AjPa3RlI)R3X~pb2dCN%fm)Q<+6@=b@g_kSTK+@`LgPMN?O;>mZPf7!
zHCe<LCEo&#uaZS-`8zqod#Dp<IKa25DW<-(D4HT}g*G)symQ;c6kVM-MUR$Yv>oSR
zo0NpRgZ)Ea?%+SSe1~7(+R%r2O0<D5H+ABdEf;O*<4{uD(6^yhH0NWbXNcdT@Y~SA
zo9o-Bdc~(NJUAPzF~=gYQ{&&{O4B~mFG@$}yu<xwjkjl~FKv;q+83pRo`OZmPLSq{
z5~9Nd4^K;9!U0lt0v`|qVvR~?hhHct_!%e(E#oJatir`(t!Xq4!P1cf|4dL${tbIk
z=r3jv<h-GYHl0HGx(ot-1BQ)8(?U<T#t|eArm+{tV(P`Qm_CIAJp)h{0ar(d6T#Z4
zg@UHpPK_rolXh~U=A%w<&@B>sVXfxFUJzM47_H$sx(Mu(Vsk7~c8dQF<C^KXn|Tfd
zCC4`NEn_s0^oa}G<do^KiJR$EgaLd}IJlv2VQ?uChZzm_i-ca$f;7mn(-ET*6pRki
zU^lHQ9d>6k>NAVNZUb$0!qU==Y{;EEf;57F?LV73VGGhQY&Tl#?=Owju>I`PVDacM
z9lw#U5pDcrdcw_8ZR+Du5BRbdDb5DFD1`%8htY@G$E|J{D=n{fNib<^HJ#Zbbw}eP
zV-e!WGvs?LLL8HLIxIeo$xfI9Eu=^~U2XOOw?~?yf`Tbfb)eJiO^F5s12Hd)f-?uN
z={F@??|%)le(;(wT>-Ro+Tcu>KBPMV!7pZf{VdArbOb2~rcRuSsT1TJMoJr;2=>3p
z@w-SVk3-9ILb#%fKM*Xs|9U)RR~rkH*2W`AIYYnIDQB4GMmY>So~c2}uR7k4D^UCZ
zA*IB*kNtv>@N(*o^=3dqcdobNQMM?#;`CZ~=Zfq8!h>>Au%aHn8vk;xALClOLo-lz
zW%rJ?khV<wo^^7dbN!@0D{HKa30!vFiH>vLbSt{?sOn;aVa0S&I!w<7TV{7|=1wv0
z+|F{V_0H|A+q82#_h{YVuI^Suu>>Vq(P2^!QVyoW|6%af^^V8BHL{{Zzc*?89j?el
z0x$4NGGs@tc1Sl(N4@iq-YEm)<C)cYO4F0vI}d5y>%D_pe1!Mjz^$g8gBbH5VHSAc
z8FQ?AzBNov>Q3t-C`XdO!}x;}(#c4dMM?H;lxSfM+CvGYb90fBokh8op@>y!u=RXU
zmc?yRa-E>8n>^}0jf)@cWR#SbHkBKRc+pOSqS0irD28v7GLli!cxXHX<w#O8Dm}Kn
zxmd+E8HMF<+=V+OtUhK^rCJjsiqdj0kPs+hpOkb!niMc7HXFqrPAWGcZD|{UIitZS
z+IEyi8o4j$-h-B!BHUUdY6~#C)Hu#dyu|R&Db^K*W25GO4sj2Rf$x9g=jj??QNX+$
zU#Esv1o9F~eRj=>lvaY5@^Ll_9?mNG_BY9+G3A3I!ApLgR)PnnpS9sq>d)G5*cj)z
zwHl2n+FXkwp(1J9Z^64oA*XU1FA6wCLMm)W9tEq(!z)jZM&rpwnL4}j$Z3&fhePQA
z;qx$S&)5$$P<WPwSS<pNvYx)n26Ktd%?6h}4p&fk9XO^0M=vQyka!*Br&`?xm_n=D
z!1ITx?9g%09*BZ&mG+!E{kaII7|2C9#X#`<PW|S{D{eJ)Pv&4~`q0hUX#6mGk=jl5
zwZlx*ZtOwc$cxZ%k%L(`^;cf)?dGmbZ{)EEeeC+co3iN(?H<xHz$ltJsCT>xR7-MP
zt{!00y=gNT7_}KkYo5Duv?$?Bkpk6_H&IGfgL|EdSP%?a7dc|&yo)6!wJ<xKQVKca
zQ(7Tsd`c@!^I@YAL;7f=4MR$6yB_s|AY_zrYQ613yl$z*?V_qfBTTyx{6Y1)T~u_a
zfWIkUP|$N^RD4p0Z`V`@tnW3y>KU-oSNQk2ni-tBzb01p3f}=(zl&$`M62cd1<QAF
zd8dwui)%bNlg>_9ELth_aB3G<cw#QljOz8(Xr$l^Ehy}S2~l;OTA7n#F|{;&nQ{j8
zGR5LdzEb$?T$JnsCr_J?I$;L0UZw+WzDqHId8<zxJ4fWmuoD(wUh0Mgn0%;Y3y+jr
zgPjOd(Sv@G(1Q%0gS|LfDnvI%JJbbt;>wai9~_d?)rW)S34Lp@Jv%*UblOvJ+D(`+
zX)8e%O<7ZzMN<|RCegqulVdY%7TRtin}!A-49?VzgTv(<CZfo#NlWP|Uedq~GgGA2
zWDgE+(7;V&)uM#*O_SCuQft@^yo3M0EMtqpZ$U8O>_1>*1F6F>2L{qkAyZvLL_nGI
z8tfEDnfw|}6|xI9nkr;FWR6am7m=g0ekiAv5<&Z9rsvSAiQj-k$j-UabI^&42RFYA
zra?)=ano2DdvPduAHg<zBq@98<{YqW>z-t!mCV3xm^zIN3yB;a7@WCUr@G-BK@v|H
zrJ2Md!}SrQQKs$YW!eTWXvu(qyrm&S2K45L2`MXkW0X|W)#6a(WUX%uiIPQsrR&`E
z0zhzms@p)jjm>k=81p3WLS*%v@<1FQ(T~B8m+ylgFW(2hUEYt8obt_C(rDhmYcDD3
z`_QTF^nK`*_C}A@MTX<(kbkE!PDxInmBe$6%}=xlxz-nh2P4tvq^pTZKJrB&$)~(k
z%<`c>D^h&I<|mieA|>~Ac6PkI<U3nQJh=dLueFZTST4BMVdU1~*e|f3p1cNE^`hjh
zNQ+5(=#PGrHs4_6_=L}t{=-E{PbHm<E3xMq<%VqOR6aIW<szj&UdLBQJPwj*f-p9Z
zXruWgy{0)dde4ntqVHVCQm5}+4;T1<>BBuT0SHc9ehb0T@&h;YPhW8mQaI#IUIffi
z8hnRv$SEBeK`|U1GW~>`nyZh8LNC=Be%SPnH%52Kf8J<xk(2#RkqdsM0;TNBOWztp
zDCo#<4DjkYC>oRtMFg}oxg1;2K%@taJ+Oe;K^b_kS`i;GHB^LeW$?lQQgWZs4GjlT
zML;wfVEWX6;X=<Xek3JD3Q83Y<O;`NYEXr2tQ?;l4#GNG<3XXYkA~~1B10lG=-i`6
znDtWuCz14%5g6KRjo}kgJ6a}rW?;)|Wq1=KUmDCfeoBv5Y?br}#a2mMFx(u@RtE8y
ze)WbbuehCN_ZHXFpr~ft&uZld^k#?3jNqXIB!mj-M{?;Eg!CpLKq(S_BIpM;;>L%H
zxwZwKKNa=V@Pw+!s6}DO6@)e)eFs9UlA-{th8J*!Xf-^oD~zk*4UbT-1El<n-b%1d
zC}!+UKsZ@TV@^ezHRG}1dcYVSn~GXnIX)Tmq{j&DZ;F14%%Hd_{L<toF%bC^dWPcc
z8se=OiMQH_=Hm<OguO^1eT$OIBY{7mkt!;X*+PgM%pZdG!SKRGm}kWwu69SXAx8%V
zRZ)z`$_$FAP$t7h^3WCxiPWKrmt^Wt#Z*S>P;6oaUAB`Ep;CoUMubZ5Jz>OWd}o7+
z@i6?XqCq)9#ONr5bY%)<M5wGqG&&CD88?P=4cT>8IF|xiky}(TuPsfGii(ZwqMV=X
zAScXJ3a?$13@mlc588_&bR*{|PILwFGU=!yeIx0}Z^Z(yb~0|s`${Of2Lp)@P#AqY
z&}Qs$@+7i~#vZY}C>dG{K|PdKWP%<rS|t@9z4C4{w4ADc<lRJQHuU^Mi8qMGjz3~(
zx$FB3Ezc2Sh7s+(vR*=?t#I%~isPQ~;*khb;p8jzWo!ZGksK4Fy6N#+q#U{?b2F-(
zir}K;$oXVml#a-GnC=%TgivrD%&Dn>`^c$@nEw;4jQ7XObrDjY5YNBTWgh&+jTxs(
zr-Xn-7+cDK(fn6%B#RVNyiCK#5v~M<MTsdYiD6M<r(R0IG$6(x9U>^OBr#)x$vI4?
zSnaW8TNo{e%E&MVNGWZ@fU#1k9R^gBO8+p0Oesgifbmg@BuL-cl1&U@RM$jfFiYhC
zA$dm)h^ai4?_z+fsGJxB76tNV4v=zXwXtq!lghs_+9;Kx6Inm;F~#B8#mpW)FO0EQ
zN(eGQDpb-Ce-b%GM^fT<kae`$nOP;l0&qbkFLCgd;B;8VXDJ1WOi<#K0YIQ~s|=6<
zm46l7-7~Z-)Bh`r%NVZ}d0$2oDAU3gA^u*OV~fIsGYA7?x0Hew(i8)MuCNFL8EkeT
z`JuAjjA2~Lj9ZkP?X8hRZB^2pWv=<L<>+yfA(1aBTcRHmfS4Q@dwG30(+3ZbBB!#}
z26i&#AsURPm8)pT1<zc@I8qMgI)Z>yM-7XKnmWZNqKK7OxhU7DtV=_ZcO_;nN)DfQ
zB6Eo<!E;e^_^z{MGGTL|m06X%{T5|xX{K>r=ihTfO-2|#uwlO`TRN-JZmX2nMPcSF
z#D<pK%AGZ&ZC84&(YUJ=+;t-*pCktpPVnch86u_`jKtxuMBqhfW6KmanuL{2Y!gNu
zq#P$DlC-IXnUb_mEh3Y&O^X;CDDs{Uv?JYLxzVO9ZCwz`(x#3TxAv(N>?0}pC2j5L
zND0^8R-QHucNTftx(+6u+m$lDNSO}q;!I|05Bxi`v`bW&r9E^7!h}s7^(9qB8Ss`y
z?aGl~gq$A^fFnqOop4@aWr9&DA%78)mr^<=fFzXIe*~2EnNR=&f08r2C1Vyde8hg>
zHVI&0Q3ADr7zB%upbe+E5Bw!z8Q3IZ#K}$sj8KTEMHFC@%YU`w)AFG&N}^RXts2mc
z=o((CEZ~jgur-7aCcMLH<(CQnuqa~#h_FohK7b&xnv2zP9~vSJ3x#57r1?!6UJZHR
zK(aVMN~j82Piz1?NRSv*ZH1a)gQyXcA+Vtk`@NxW7~BIw=rE*<7l?;tP-EeI9HD&2
z&)n5%$Xt-^9E-HiaV001qqzuieHAjvn<VIxSLpn~2Em(H21*tJiXpiiC@BX>LpGIc
z$4KO&K-yvfvMfR{MW8LmdY?1}Rj=1eBF{8+$s<f20n0S?4M8TJJb}$7<Gu~T_W0H<
zfoFW{mM|~A^-7R8ncdebERko1x;dCN)Xj5<bL$jhP#`?<zT0qm41Siv@(Idm8{SX6
z8)JYMAEgFoOaTY2_ht^TBm!6#tt0~AJr7K&HVEGHY@HG+=h-?XG!rkAfumI5NJqSl
zpJzi*GWdN6va|>r1`|^~3#Tb4aiR;%iO=#Tv#ufBwLqa3Wo)ofs~!C8ond7`it##H
zfg<Hwj|7pb^PvGmDhH12{sO=<AORFY7K{)Hpk=@XD1a?P#4SL$4v<Cxb)~7}xi>H`
z8b5^hWk9GaNU$SFeiJtgf0Tp2*$c<J(8mnXy@gI@<0SKG><o*|`j~Leg5tM;&<qj5
z1(jxSt^rQ%04b&gz%?5L%B!;g*Mtm~v?dAJ?Fdpr#7XHKXTifQi&V@=2y*7c#ACF|
zq6D%Qf#_)1DzG|pU=az=E{tLEU8xNK^g9X|Z;^72ldaP>Ts@fB3VLr5a>@#9Hzz8d
zmfv^Kzp&-SH)!ZKcpM8n5ca-fgBT2>V0`J>y5%Z9TepNn)Ji)bC5d=w_-bJy(*9Ve
zi9s1VvZ4Vh0`Q9mNQ)J;$uSMNKpYKIE}+LnNyNy`$i?g;4Zv}K%9>_ytrqO0A#A+K
zbY=mccx?EU29S!vxD3j<<6s(Gv;fN_g>ae&2+11hb`A`_GLFG04De1+f-^U9#1<td
zsu$r#c{H5h);uMjd7=<;G=6BJ0EWyz8-@G<rk`L<Y20Si27V}*NPN^HNR`h>dt$5_
zWWHcnK{+<4RvOj|%{3_Jj`&)XLCMK0^(f@nAZ^&PY|9SlQ+TwL98xaMFIKKhgBzt7
zm0+~@#wb!YMkPM&U5rY?voR|0X=`JOaBH|>=PUeQ`Y8$`I4FyE1QFf|#g=fo6&f)~
ziB@b#eJC{JqIgYGkjMv{QhZR#qHvW(xqE$5A%tuV1mfv)_uRNc%EpZ~<Xf+BQ3SW4
z$=~-TNu+EXTRgm<jbk7H)QoHKoEt+x*u-Eh=wrJWfI>qUCF8M841&<MiH3kZZIc61
z?p<y(BGx_y_o;n0qE)+WM3`*}P8?g0(;KfH_595qd$v6m8}r$>SnTI#?7T|SzR#j$
z&c4m!n0T)JZ~>*`)y(texwgY47;$gR3aNVTjaj55v))X<BGB4&H-wNp&vqEE|F*)n
z>o6vz4&xB1UiJ~3*ef!;PUE$h{j}{gUb9&-=XDy#(k)WmR_iM(n!RqT^^?7f9k_{l
z89W^6GK*B#)g2=m+jVuvh{kqZ-7%uET~|+zXl~d286%q8?QSumYrEZ(N7r_{FSGHY
zkVQ8ba&MP;GUVPa^EI@UpU|a##6iADQv(Wy*tuye-D)?cRufqd8eZ^XGf+T3>SkNF
zU`ClJ)=0`c0bG@?ICW@cN02TmjTWD-8!yh0uIOwkfL%#mR1jBj6DbLK?sr5mQ_<{-
zJf<?*6-P{kwKEF%_)4WVD5d4*tmmg{+^wFVXSAe8C&zl3BT^6S3U8%~z9@WlotWdT
zXH+Ws$0G3^bz+X}k~5Sk6Ay~6P)|NOdOOp0k}r#{7)?H1y23B{yy=Rp<O`@bp?UI|
zv`8OMsor!D<F(Zl-pCi(qC}@7-)t*2sQSbbDF%^GzuvU=`7-Ry^^CH#oGeoH$~m}t
zHOxV-3OrLgg8cA~?P-13-?@=Ar9L@>sXik!ug3nI?wj!eZoIx(9~u_n+PdW;Y{rLZ
zl?@?Ik2E|SBn7{pPa{JAusnpcd{`brVqkeFdqtP&0Va+9VR(oQuo)hbxtsC9A@ZB`
zA#ch~q!3zR`eu8`gST(ChqZTC4j^3VF!%J{w?0??Np;E5mHELjJTH@BzEKv5-3ErI
zXDG~Ay_b1%V0?8or$J0vlP?*~BC}H6Vu*A5R;+Hn^xPUV^EJ=ic-MQK265O#+UH4w
zUykM8I*lU;)hC(tY@K2x&(<fIrRUDLB14t@&bz&PNkg1ri=YlU5SKKp*IIYmdW4;b
z3A9OC<M38pf+1d_fD3c8M&Nq%5{6{PqENtb8J0-`ufLTj%#DPb%}Y;%ZF-To|B{I-
z9hu!8aDs<J-bqdk{eYD`(wuoXJi&>n9w8Vmg&TJG?$_2MRR^S8zhu#8R`yF)|6ZmG
zcm{fzF2Z-v18b7Lg#7rk^~sORe+@51_g@?t9j2k<1!qT4*eUP+K6G7#$D|K>PvWyf
z8o~ssRv&U+!!N@>X!xi!ymamKGGO4njAZ=-q>%MNdsRN5yJCjuXX-<;0bf+d$rOGi
z9HNR5qF1XA$woZ97c>DqLO3xI4kX9fB5=h#@D9os7m{2i4|wMQn(&eX55NisNI659
zuiy#n6*UBJVITB2CMR`h#MAx=3VA>9A)Oj{?DxTYBt4sb=o-QEzYm2((?i;)H2!p=
zc2pjvmz7u-FL_}Bh!HyozS>11WAe;g6fgz{QW;U;7Vfi2#P}kZ@_50)+-FBCzayLW
zjQ=K4!BI1NO%RHAnN-3L&PvzxlLt7-;E%+iGD}bp8rY{E5AewM$yf+D?faaXAC%N7
zV`sYldzArVctD@JVh}<An3fkJnR-QFAt<5Ga)u&up--J6Y4YfkXow7nSQHEfMvz5e
zEXvZn6iS7l3!>Y+7@3g>ID^p}aY$bj1;%q6i-aH%Xgrq|9`z0SrG<}Jr`6_2P<#8*
zm4R{$1OrM+{)!&<5snggLW*FCrDeIQLqRS5lJOIPFa2U*Oi24B)d8_Hfq=Bf)*K0w
zgfHcuxp)c$pwhx#;*2LoBI6mtd=`Zsc7y`;OOM6~7D^nbm!gR}Yd<sKs9&|ph|23%
zEi>f*Z(^JJRq->pG!@&FCV~XN+M}rYt(OEst@^DC0^wNwmI85~s<8NC0M`-NT&9?=
zVD~Kx4?@BE%||7o#fSp-Qhe1BP+=!YAq%%of{098Z3dm?Q{$F!AhK;y7^i~pw?Hw&
z_;6p{1Ff7gZ9oXKTLebCb(|Epu8@e=3(Pe}yM?gdIu#J`*KgT`U>O9M+a5Sb#J88C
z3m1jF!$ot`N`xTAe&??aj*WhDL^}2|2}Ud=k?LLy^&*(vOYxL}c!#%D##{!8<Hwy*
z5n7mAf8<9&P}rh~|JVR!Nkow7qA*+%_MnGKD`HI-As?a$N9{5!B4l;p1yX|I2B<);
z`$>SoJtX!>5JJov$8;GHF_8c_%n2dzc0nW-C3w^yT^k4$3v|YZlpMcq0E7ZBl*gPR
zqJ@tIY<ZEgI(eDb5O(aR_7*~uy~2$UD78R1$#O(E2T~^nokkMEc~+EkKz=$Y6O_r=
z`+Q^uPN<@`vzrnU5VakEqaTsoUU5bY|8`mB5F;Kari|=fZ}rvg`ipA__%vegdo&UJ
zp67(0*H?wHFC5jz|D4R^Mq)JlqQE81SSpuAk0JH0pd?1!`&s!113akwVubHIFh>;Q
z9{{qP-vAFD%`h&Qz?@BeK9dQYp-V_M@URLp86f~`m7WkRFy-%_xOfPCTWJq&%5B5k
z7JM$(Fz4p793sc!5XNpLVz?>&AXHLMNRCM4@WRbNs)t*nSTY;L3%mjbPA^~zq?LG~
zOkmt@Dvihd6bBjvQdpvWkq~@Sf~&PeF2-k3*uo260XZ~YcnTPk7ghq2aTby?Q(ll1
z?gBb6&)U5BkSB+Rrsw#~)bt#mnKixKTTc7{;FtvxG;($zTrz5|<R!OD6U=0XMZtO^
zC2CQ?q6?Ez>J7507K$~021(q6x>jyh{1JZV#*CEuiS#b7M0xznP1g%^$rcISkZZQ^
zywMH$XkH2H4YH8YS@}a5GU%064htvY#b3&h^GYEHs(FBt<19d`oma+qK%*zRd9D?r
ztQIAc@lv8($=^qViPIIv#biORv~465E=r{-#+Mw8n4Gstpv3C6N}$B@DX5G2klreb
zGS>PCBzepT_es;~jZDi$X<IgC5IEe281_u|%yp`iN?bQ>qLpi;oJwSjdgV~}2)cGy
zX_<7o+88<#Q(cx@WUmHjKl5aBlQ&g(Vh*fV&NT95y>h0JOY4mrp>y3Y#vw4cYE>0r
zqHM<$nTLtY-Y7(XPdR1@3*dna;YGNZFr2F>gb8FB`<5j=a#G6E?7(*SEh&0JoRt(k
zv1USt=vUNTAgA&e@J>S_^QwKzlFoC$w=C(Ht9Ri(z_!T}564Ss-oB+t=My?gL!et;
zZ{D>ZJG7Aw?T#T=i@-Gc^=MgbCecGgdi(&A+E+1i$e1IG(G^UG?06PDe<^|9D`^@@
z_O7I9$GOle8xG0(-uYBvLjR%=C7^?y^l&avfYr($1)jcF5;b52Tp;3%!17+845`O^
zR}!5=q4F*?ApjkCrB<io-kDtuKe+b-W|->21a5#Xc>ficVO0U)$Dv2`0%o|;t5Q(|
z1Y!{eTI|Aa<0j}#OpV-2)*5*+Nb87#B*YD&a42OJZZ?;dpRgB;@_~(!KSU%GQ#WE`
zKty!P0EWZm93WQ5;ljiRp2s2pSf!(rZd>F^I#a#VXM;*Ci5udODjq{{ws_@!rz^#K
z@C6={Rp<p0Kai8`$_)n!$|7(aQ@sY-`4MH#BI(gPP16KriIOt-6(|P%K`VRc%z|^k
z`=bTAIW|Gzz|QXq!6ep<cUm%uN3$qgAXM-0%1MU-J}4<O34RlWbRaSS$8m*n0zl^o
z62N*)y@=Lh>Xm<i^P+OuVd)ME?wmAidu6x7jLq6VFG2^c`aoz!2k9%*IW!_m0Gx;=
zhF-)ka;GJh7)S0>X@G(hm5Ojx!wl>SJq5s0P$1ul!Nej+FF`adie)$*ah#kEB0@by
zAtn4U-W0CW7G_JYm{!6{EfSHA9(BuY5a3j+$pPc4aKTtyC^F-&138STQ4}hd38qYz
ziFyf4%UwVhz}pH6G00N$Tcj8Zs-e0ZT158pO8N)-*P^7$8~|ZnC;)&Eb9uptGv*%p
zUc!*EIM$0OWk-_m8D|f|kl}K0o%=9p1_hr<ed}<=`x0i&UAMt?MGKf?P!zoI;jr5i
zk|5cH?e053T#B9^MrqAl1Ww?ARORh)yaYYxiZmuXovVxuA?$*ZlY(*4;rKg<gy)5R
z0IWP$yfOjxTzCjKmsT&c8<<Wkm-Z5NpF86#6W=dttYMxv*H-U2Sosc@-;qIp?!=G-
z)S$cWuY0JL+e=V|o`G=(NbHh7F|ks*-2jp31=;`@MQ0fHA*@ArT2a!f=!NTmBu;ld
zEpKjQ-HA8Cu2;pnmyjX7pdjwt#kw(X?qa=A0XOMh+B+~Q-FdG9w$ckvBJG3jx@b`e
z#9dK!1jKZ?Yzdm_M4<qzrn?>mPtSsVIogEbJXFK)C9qB};0geGeo{Jy3)sy(qYqXG
zd<jj|T?Qv0j(S000G0HUa_2^72rltXT~23WqJC16f6^HeSJnM4rbDN90qy~x)tzd^
zg9o1rfe)#eq#OwZ>#mX~0E+#jOpG@-G682@PI7?K9>0)oe0zKqw(Z`|`Fz6TI^+2Z
zL)V2CLY&=C3OPl9TqmaxQ%*czcVY+<^Y@cN#sD#QiV=A|5MS7p#6S$<Ps)`azrnp*
z(;@}tY<HDipy}*`!lg_}TCmC=EsYL`JAj$D-)N_n37>8zh8Beky&(??6ur#}SklEB
z0NZ^K$UI_bJ2&D^BKxpXfL{8fkfB)L#Lzx=%G9(7t4-Btr+f$>Z7!>Qd=c||lU4+b
z?G$Y|NPVmQmOJAh0Qt6A+OInfNaj1G*A_!UApz2hL;&?V0f@3*rv!l5cS6I<Nv90~
z-5tNtemSy;3jawNJm!wCf|9SZkZ|*^NE%|&>jWiiJrCJK(DrrgG9IiBYsQ1siOz5^
zo%n~4_IW7~ieEPg@%p#hhM4|!Ap!UQs7s4=0qUw_?SQ%tSzw?pOco(H@<wHmg1UrR
z$e=E2Ry)vD&Uh|ozR8ObU8NE*qN~&fmRdk@*`Rc3A9-Zax*>olR&^+qg_R#lrRiQu
zPIAVV$xm7lOG}jM#PSoRUa>?)X<(fyQK@Mtby2Dut6@mnWAqm4-hx7<5sxJn-Y7jX
zOLI`sWaW-hMLUfdQdgq@NREw6c+?47a-7mU!H7Y<M-{6Eu-Qt*M!gajG8jvml&a3M
zC(`B_vgIy^9)q^(MS!5Kpk$|B4-0&$*TZ78tR~}nCvXz3cLG*(#BlRp_-oY(834el
zR}$;b=pn@dHTBj)I95H!Sm!1v2MFxL!C&ly6&ciTyH<qyZ6{P8EA!M7lhu3b9m)zn
z^;TsWAU<Xf6$+{cZw6rLO{@T{dN(rwtKQbAV03)(N&Zrqqk6VyA*6cOvsO~Q{aH`R
z!!F7iOeuM)3oyHSae%H~9H6Tg%zmr^B?|^iM3t3;b)?b=!ZK53Bta>vG|)hxQLhTt
z7Ess?;+p|gG}*8)7K}OvNbG~L-R#1l-ReYU(yaXu;sRy7$_~X!UuCRfIj}NlA?&Jb
zUI@F|4P&f4R@O6ACo2OR3z($=js?zOpv&rIdCoHfy3<Y}J0EMQ(GrMaYh@}#2-ap!
zWWBaBIkKo*nj~5Dtt^%-43|dD92n$4vDB<EN7E>4(3SC&b?RhaJ+hKr8DLrLuB@~y
zh*y@}ESXoPUKG{a?ZGI$w;7EyD67oMEZ<kAXO{SbdHMh;&C0rwXvd(Ho5cjn5YB>w
zG?gDHN$5(sXW7ECx3jci+2m3Eu*~)-ka*Cz4^oG@pWmjF14sT%4~Og9^l&&IiYV&1
zc_UWQ$MRONC}epwST?e}9w;q&$TPz7ljS#IiOTY=u#9E-Ur^|B^U<IhX8CbgFtc1e
z46!PAP?p^+f6>9JoaI$w>CW^zv9xD-r5I9Gek;UO9rA6lh-i7gP-nCpWGqEmPBd04
zg{SQRDHlzL;bULrty_Un$;!QMD&2Ltp&ujrb<jO|aBPKCacykHRB>&{CCNgsN4YIo
z4YpjHtQafrCu+*dJ*uj+aG@R`^|85GS-!SBv8%c*U9~S&zm+!^1#*wg<I5_#<rQY7
zT~`)R*5WPSGOP8%|D0okEXYaSk(5a{cF)4V<>qGH;BtklxN!Q)S$(*C>8wxef-*-5
z<MPL&%JES?dzL~jx4r|@s$BnBKDmMeSYR0e1jkoZVXi0xlxf}~5m?GOLls!~xgr@*
z9QxS89T;<#mFB;)%JkSGBv^&I!YCMB7J(MWm#SF@A$O}YzDm&<tNe8ZZ=gCh0zAG{
zK>OIDKv-qFB1Kq+yP`>0&AWn7RPMVXRag_eqFG$wPrT<@XS~8<P>lT8VrLk(rSKZh
zYE~71!+5NU(m`Q#M)Cx^Q1eL9J}j{A0$gGd_6iYVk#>d=9V+BrVMeU=&d?-QgLjof
zVMtX)IH9ckv4ugg@_a=~u{ym1saU|ig01+AM@3{gYOYk&mZP9bMRqxgrBwKrqZG<f
z@nON2iXU^7Fkyh%Vs=I=bxjjuQ8fY`l}sy`&5dFq!B!*`Zy^U@wpaPQMard#A8BWW
z+<6xBsGvMVLT!<I-hgaV;e8>^=N<w`iLWq0M=_0xCB$AjwtzzidQ}D_u9hR95u<C0
zdF1fA;vJ6{kARAa^v1AF+7i7nZc}yc8!YV%z&vz9Rg`8NZ08=y=>WGvxMxrpw+YWc
z9-$ex30;%tZbp@QW60*@45y-2IYU4dRN(3&A#jzmytc?!&k_%ajs;;be)a$%d7$&0
zfm;g1ja&0HM(cudgMyrEUeFcx8@Kq_LxXwKBYt>MkZXz<;{&7&f@OSXs4u}NzBrwx
zMaDBzA!f*P>fRYmJ=JL<7M!;#p9&RT9S@8MriRHRA1O)FrtW(n_j)_62zSMLduOaS
z1H#v9FVm6~F&@v#7#?5Me4i@poDW(Crqe~Ak?RL2^W3A``2?>Bcs|<^CJ#!6v!7Z#
zkKAQN+rz9-0r~Eo5&PLvz&_^ehzPI9e;QLNH-JVNr4P`8lj#LC`egRO0ZJsAC_{lJ
zsLEn+A5y`i#asyvd~je>qaR9_;OHSe%DJGWuo5$1e>^IAgJ#Uk?QrCFR_@2LuOc}l
zTi}`N%7d-2l1yk=t~3<duq#!C)^k3kjwFpO2L^tQN|T`<rgCZAnW1C)(!&YreD_Mx
zp^!2~2jG>y@D7mm<46rfUeEzj{DP8)94J?nVB~3UR92EBc8Y0BJ`iORkLa8aFyboH
z$(hrC@%8V>;aA3#GrX$OsvIDA%DZxA-(P&EJM-<8tL1~)XQQT>>1R4-2h-2;M;&96
zXbjJ>Npl!TBC6!GMasM}NeA=WmBQwO*=D-+#~`zs<~`6&N6kt(XL_A8om?q+&g}6^
zFq95NuFB<Gln^PV`}qLS%amd|kbHv#!6QkrXJ)NFlG2oE=u8Qp5(r2<vlEXXW$LGH
zWtdhg&(V?UN<&>zGR=|Z9v^$^qz~p~>iA%0w^A?{B~ma42M1xV)J~twz@*)MQQFv2
zL>D1Pn|6`a&Rj}aL7Z9IQx__;w3V*vFyK}?>!KuMI$C4ThIM9TD`nPEv%b=5eIkoZ
zxwt-os9hPm9yZ|0>2-X9S-%dOaHR$Ndqi8_uq)qM3Y_w-k$&t*x7LegBF{}Z%!k8>
zT#3%E6l>{X6ZeYJr#-k%lYX{y(=ZF$m0+!NKnd2mHL$#u?7b+Velj84m1A9!z#Qum
z1teL!_<-AJY_c$suU@i%oVii50QH7>@D7_c-7ZIxl7nsQl?;?-GOsU+26nXa^?jm}
zV`cR_0`@w_4vk8f01j}s!VPfj&`xliMY;=nz?p+Bc!EVqxCiMQI0`yF`il_8fC57B
zJU<F6!C`7IJO!W6hPU8|5Cka00aAW>Ru_C3&r&97%iHLvH6ehABS;A|0lB!&4Pe5V
zu`Lh^&qEbJ6(Gd>z0fQiM{yxuI1{_&wepKd50nXb0FFY}aNyV%0*51lQ6L?QkX*2>
zQ*uEiE*zc%p@A$y@<H0^g|kLJ6$ffwccRev1rP|~k~m@`3%kUbM=p4iMTzkc0wsSa
z@mcPzTMS50DvJ{Q5!#9){alDF>xYm|Nz9g@<cM^0Fe6<S|DZf~!NcSa<%q`CEfHhJ
z)-7;a#`dj5jG^KE@XLj0v;F`|v`}ySBHoT{4k+wV;5mzu3P+b{K-m@q&!Xh$+SV&Z
z*Q!qr&SVdY|1PES0uV))P!McK_JNCFJLlFZg`MW)MHw4-kweoefTKmZMnNDsd_5aX
z(jp}glpZ7(j#XhTIkddOV{&BX!^V3gC73Cbu0vZa@Fz$45`sgmb`DtPS!YVWAg&iB
z!JvjZ1$Tv0<=3_0SosCW@dCSYIHw8`Yf%z<t8d+M{C(?{!XWgmMal`l&9MjxzC{SH
zMG2O-txt}hUSB7`fNHGzb#G{5j`-d}9CJ9z3YBb80=Xor&#qQtqv=6`h~R=g^LRKU
zFq#vqfWT=-kP;cKj)A->tWE(U-sv@Q5#Em0n}j?#Hncat2yrKi4MLFx7#D=+*)Zi6
zr47Q)9iYVeSX~eWaYs=Jd?Dc5MQa!#@IXn8#%kFKa97I?e7jn7;@fG_iEpRsc8e6d
zNXUME1ExsGe-0mHp#uiR?;S$WvocP>3@$=0?YZ?zPMmD5!3fH5QI=#V%Q*;ZD1t;>
zl-PJ><0C-CNh`#iBiO(e9f95j$mm3o5NKmiVmR9Lw-NX;Cy0x+%yICu7KEfDe!O5N
z7iF>K6dbG*n?iV%ju(1iS~~o-g?s6VUm;}7BM31ZX?l437sjTetWe=_I$$pZ)wu|X
zaU?)bkT%dyM-Y4ggE}k^i!#toY|*Fq)i$V6w#X--#tW`=Q4)KUeuo6#I12WZqzxL?
zVG=3$RL{Ce1+XfDiuW!`g3s!fzJYpAFxMi;2?k#{Kw)zs8*pW%!-=9d{@s8zJ3d;b
z!Nw_3__ZKy7`G0Tk;1_(iWRToMP7KiBo*ea!*^e}ygQ|9xC@Pzb>TiJ;!J?i3L|)@
z41FoY<-Q5WRita1dq|K_i+4&*G^C0JrjDXWJG%RZoSZG1M*qv#e>&DaKi|Llp5oQU
zoBTfA&g=H~;rjKT|Kr!ceA(Ce{-6B6|Mlnl3sDFMC&o`5Cyl!P%t<vlR?^;;05h+&
zu1C45v7YQ5QSw%C3MeSAJF>GPZvhuPs1uexmQ2V(g+r@cUX=Q)V!7DnM27@K&>7Xl
zRx1q-M*tKMl@sL+6dY=ZE^IgbJ4VP`I@k;#>qmDY5#gnEDU+WL;Zq41dxmvV7%`S=
zf94c0{#M}uOvA2FUuBTNG;yBFUPpv3{pg$XLiWU`-o<!J&Fx0zJYkng0rGL*&EJCa
z9_d0$IDcHHJ=1<8KUebZJ^Yj&`;Z=>+Y9Z&0U2tyY%wfQUF#U${wE7NGe~a9kTF#I
z4*5}T+=H51M61YT!}URHrxpZ-A$uXTpc?FO0!rn9Z8+@#8yH8NHDDoz^f$!`3m9AT
zG2snYr7^fFb^(eTP?h^w@Tz=Wts~$>nNKhTMYJ1s$;0?v#8q@fF(X=IUKzQjkckm~
zLpng|=s)=)qJjL<V-bObT_Md>oK;0>NzLDp3*Y79Io0}YhbwdFAV`-|#(viUkA;-A
z)un&P-fzBA6-CB}z~0|<0_Q2kKhvP`A=kg@2=UJxl+{riVtm^X>%d*|GtJ;1`{wU=
z<o3ct<ma~G{M(KwJH$=+lTl;aw){;;lr%@G`OmMS%<nqVk(rzPrvhfU>3`D+C&PL=
zzdO}Q@y(+5%sgJl$4}bj^DOzzpX0Qd@#ooSzm>yyqi^TY&rHVnIHCT2M;>H&5&Yba
zw((uZhKMnocdH{V1yX+75eFrn96z_Cb9~zot_2>aKQpcR<ADA99eEDhrH(wA`?nq2
z{c&9XOxTc*1N`rI)H!eJNXqqH$A$d0T?an{hU(*f`1{|}En@6O!u3rzA}#W+`5FJ(
zDZlNAOA1f=pWC(N-*$wHDX+4hRcq0{*>Af4&Ig@%AAYmn43&IvN&XBDe%zYB86fV~
zu5KVa-*!V`r>3(~wVJ*^D|L12tgOrY+p}`%jQb6rBmKPdf6JKsGaeO1xxZ%(d>L^~
z{Y<!DwST*Iuv*}PRD0MrooF6}YVtEdAU~9q-*lu-GuUwh&HScg;OlLw&(8pJ`&5R0
z(~&w;Q%6$nZ#$-$m8#Xxz!Lh<wSIH5KqKqwrkLPwk3ie?wm1T>56W*lQsJBG$ZVqa
zZAZo!hgz7o!>%U&_HJOh&%n))?dO}D6`X{^`LmJ^=XdIj^wh3yAUxl8n=Wnk=W^X|
zy6tZ|T$v}39ahWj+YZm%H00Dtc8&SBI>}Jj>rbiK^Se$J&lfXKt!X2Cqo#!!?0MJ?
z0sZIrt{cO9E?&b_3ro}gRuSz$8~*tbL-Son`2G2A_?ceBkC()6I`YBM)sd9v+m7(=
zm`0jWK7V?s@Hu1bM#9dR^T%_pXYu<n{60pndp(bb+bRS9uXz<;3F`q%5b6?LWh^8`
zp?yTYB{GRf0dPV~6sjU!^0SIk2DzE`&UVozhw4gK+rGX`URPP*K#;i&Rh$w-`}l=)
z>eFF>yUuM6ps=;B)+smWjRb@?Wo$zws(EiyB&DV}5=2K|840t4Sf9JfvK7OVGPfzm
zD{Rhf&ZIC(`9{&TAseFzHRpIdPT%Gn)}*Nn(2c}D2sS9H^hP<e3WB+3XvsA3Ws81l
zB>Ajcg*-|RT$`}SAq=opw2LT+cR7Nz)_5wc^3JfrHcwe2QABqzvH=-K1fNPu8gz%k
zp8`Rd7*^R1g>fh@|3=;2!Ji1mv)INbi5x*;-XV{5hB3AwhxLt0y;*MrQw&y*v2iL`
zJrovsk7!YrP{_BUTW)~)v;kigAf;EE%tcxAAy?I%wSM((b_7)d{_G&>Y(z*)LP+|M
zgYu4Yz@r>h(AS4mm!5;OtxqxldO(H0%C=s?sM?mO7(B`fj+o9j3C-Y=m!ry~B@1+N
z$;(THYQg}GIFht@;N_D-IbkoK6!dm4pH$eQy*yGtoN5)Ff<V&d<(2xy<OuIwQ`$H^
ze9Z;pM>k;eazUnDcy~d@vik0Uyz+VCjATFoa^GE$v5LOAAcxQsU-E@Er6a>%dISn1
zy~rpEYg?~4L)^ArIm>cAXF*;@#$PN7OTTl>rtf~|HJdF41;t-gh6m2)BjGI7D`c?m
z&gYm=-@VVVM1A)@M<`h9oBKJ2-^=@)MUmM9Wm~&E&#2nkD{3|G=|!Qt8Z}ybd7e>`
zwd>BzSb+o_Wk3W>a^1IXEh|UUUyb6b$i{Sp;5Ox6u3(4sHFV{)AosSxp5+;(+mtiu
zfEa7al4RV)q96hRwH&)`opQA2)+t7-qx`}h(@(`}Uo+umPez*rciW>bxFM9M7%?hO
z)(o#+d0)4C>lVXP(qRO@tl_n5>$Zm1uB}rZH|^Sb1wR`D7@_2}rVIMQG27%VLp*Y8
ztQE=_pjH`x7tYMe_d_hvf*;nW;`~4q%JEW6QlJ*IS6~{W2aBgyC<2P7*E!J1t5%&x
zG^<OFqiubHQC2;26sF{ot4EU^;ACti3hBLUB?@qzwsY&WDjVCg^+}8Lvvpbnsq{Mp
zwFO=^J4H+5g2TL0?GQcJtmFW7&h7fa_`0+tUCLEKpdKN(^N-T|IMpcx#ilkMJbINf
zcV*R%W_2*2I=SsJiz5-m6?>RW*h3cc%g%Ha#5pb~b4Ib^7O{$A#jRnAV#O6<TNG<t
z3D&kg^d*$9?ia7wyyS(=S%z;RS)mL!M1lwCJGw#HuXHxVh7&zLeke3(W3U<mahJu9
zfy+>HPpR$*=xr6cGI1`yNoX!XJaus(aJZdP0})*Orl1u|e+s|I0o>WnJ@7duc<!Ok
zF~M_-e2)2@Q^EETE=`-#O99ob0$YIG5e8qhb9xo`-1B|WDy<CR+>25X;Bow%x=4U$
z+R8DTapOmj$jpwfNoEijaOw?^4veO7n22AGK1~-s5LX+1H23f+odN;!i$ZQ9rsdRu
zGBfgRS>(V?!)J7$01K8yF_N<40V-A|0c5{mPggR)@(4YTIFowIs?t&E0bw?O6zYWH
za8b$Q)DKy9%T|;EVOC0xU{NaBVe!i<fMx{jkUdJ6NdaC2Cd}liXHO-}q(WqmP8fjR
z9E()B84-D)kQ!Lq?P1{Sq6DK9`U*7QMdAFAJn|-?HKHC0(`+s<ME4Br!d3w_1B%EZ
zF+nE$e^0sKC&sELB$8<CQQ*{=V6@fPCWg!0o#eI@P}GlH6pj}@jz_o8$U1JTpbW>G
zyWDO>R*gK9QH2JS5S0qSiO1M#^TmjYoKfm#Fxe=7_SVvO{4gV~M#t}7y7*C5)GBNT
zwMgyOl{C`yZnwfDk)g0COy5PlRl8+8K#f+rrHKHA%5Fu(=F86RitIq5f>p#1%GKH}
z0|H`N?3Q02kG(}PM1hYJ{HUZlcxi8i&;4y^1`;h;gercBGds8G=ZI(!<UFoNqOnX9
zc1gn+kSZ&ySfY@pTT8Qu0bV)~P!!lMy*>s~Q{N;s*A~09#QE~Gt1>X*Sii1~4>89}
z#iksFM!WPLLB64tIS#L1yOg^O=tWCi`T%JJVW1UKdMO1H2f(E>0{N15ZE2XPNm^yw
z0eH_U*$xnTR(3x?(Arh0m~rMEtUmXGJHW243C!dkRaRiiMU}f~BLv~91pLI=k79b9
zK|TQN(#?a1I7{%ozKG3cnX|`S*<{|S8RRW$m+Tbo(c)-B=eDVn#DU9XQ(^T0Gc#Ej
z0aNxSL@O0&Q>q@4NNkpB>#6&$(u-S?@*4fr%>z`hsOX3p=3H%7E)H-BZC18#W|mmx
z>)|zTm9OWx@TO`xze%cf`C|U|BA~~@)QUFvlu%c!)R_eENfEg{-^na2nv~=mg`wvk
zXKC1%(2Hy+n$3ZBX_d_uPhXbAjdoVqMJtbqq5Hb8JGD%D0Pu;5!Gn~zP=+q&mRc%{
z7bhixLs|6rB|si4OP@ki^n^n<R-=9i0N}78Jq*udlhqCwJ*c?-64-#1*$yw^C=d>H
zC}0e%lF$<8z(&DPTnbfu2}g%D(O(6nV3n4J)C|^Re<f7TnxjjR2V{dOR}B?+4ug}A
zxHwkUKICgG3MZ7;lX)RggpJW$RlXMJjS0%t^W|(_7!=8N6AJ30gq(X}Pyn>bfICXi
z8*?F0;3^V0=%R#>mI)C>kKoxqKpH{d=u&|#8)L)16qcqVc-4rL8P2{O9L{zi+?W6@
z7dA;8F0KpT5MWY?at8IYa3=#BB|hbZcYz`q2$2M{u`){<t_;^nZ@e-D?&xr4nXnw+
zly^&lZ8KMha&3?%ulI#foMgW;9R7k*bVL!E(}rOq8u@RJ*M-RiyC^v|2|iLlOlXJ1
z(Xldg8qaw~!~$z(wfVz6TKrK4mMH-XAV1b00>Bao$U1fcu!5`%q<CnX&;|iHWSxrX
zL6jH+c%UO0#L8ZZ(r$}FG^RYk%Yb@5*xf97;)ox#uCo(3N+vKs#yl(v*5?H1xK*Ox
zxw^;=hR3#*-4$<b>)IXX1-?vO`X^o#eWEoY{*D+`cscaK<$~n&0_K7#(JE085aA}s
zzBeUfy)X_a2%UC2q?lOWV7Z|5_k!iZEmgK%fSjAq_Z&#*mgsxL_sXR%Xs(t^E#(PW
zCyP=@V!8G*_54j7^Mi}13$gUUjZ#Q@iH&9nr1#tu1tIA@42%<!9w69^KzhKpUu_2d
z<^|KGZxQOvI<s4W2Nx86X<|uEeQ8FEQQE+!T_k=8+F$49BX*s&M;}5$fbc;P&Un}c
zrH7T2g_=-$reK>MSthGZ#$jdK&1?>0^qGv<ixRwP!az@8zePyqVO<+{>_K=yYl8QD
z)-MRm^TDQXLfS@#iEYq&$QEBDEd9+;R$=P_0nrLw4-hrh1aE!csm9Y(POQa6Ab{ho
zPGBC2#F_$}64KF{(!DyKyq0i#c<!3AI|&@QD3~O?-;07t-Y^1M6Y?_<Xp9Jaz@IT0
z<U67ktraw<gWvMk5i@g<2p`$8POh(aEQ9cv;ViV&PmZ8Oi=T!@(F&UrDuvQb-;`)^
z&ZvTDP0-57W{Y@Md=>^U!uWOM)GPu72+4r&W$b8X4<RI{v(e~2=odvpFr61gL)cTm
zps}XY1<pBZeD(M1RxgNHK9;Q+Q_nkI%hq(}pftA$Bd{ac*8~wr%o$^{EDD698^jKN
zCKGC4XB@1uYCHTxh7y*qgq6u|I-B6wiL@g8kgFR<)YVHP$}>af)z#IB3~K7c@x&uW
zfQ9`+rk=@%5<tVNlL_JYGIZi<!E9qYz%l!Df)k(U1X$ryeIT%S>>?2+90_Iu5}gkR
zrsEEEq)g$ZM4>TL@df}^n5h;+<_hHxF^g-@z(GjN{%M@@L}O&um&r!gQL1bIu&Wb4
z+}Vqt?dp_K9UV_pldFmFFlH*k08_XrBbx9q24(q`U@#Mr=@>FLvZ*}6%pM%>sSX@2
z-0dc4$WD{9D$I78m`#WJSU(~_X28Li6@V%p&}Ka2M^3~{<p~Bd-At!GqGilji~zwh
zW-3NN!>=$Xdq&Hc+-V)bGG?kiFc9OjNSr{P;ig&xG}_7uM?4ra;k70n%=^eQ-5{e^
zx&tN=`%|8~PGc)`)B@>+eYkB#LnltEsS{_#{aK|1m|qAxNrJ+}X=PPP;7oC>QUWIg
zt4ax+>Xb_rZ|frnSSnf*1-;qvmNq27cUlgOKnNWbP8Nl;1h|?R9){hy;3_RZqo3)9
zbFR3fm1bALd3L;UO-{{Dlb%xVJI!^bYtWrC(KRQS>r5A;b9Dh>?YXu}@^h|juQ}rI
z6?$j~+P~4E+G&q7!CvQM(@=AItt72)$}sH+oOx5C#ht7Y1t@K}C}hKVWHaTtb6?ZZ
zLi83R+5o{@%m`OS?3SYvfqG)bo4mgZmL-|1LI*U)AunUK4Ws2n5Ab#~#uY6}{w&TR
z#Ee%$(2C5yF<yYh<2`0_Gj}|`f`akl9A}h5;Iv@8EO~>fj6125!DuCORdS*CXo1xz
zG;C%%0f9Ac@^=HHB`KH?)N*Df|C$(jB<YjeCbp1riY?@S<x&l_BWh0sniGrrjT^cs
zw?qsp(r$?u45n|=zCi7gh^45vOA-dcl!Rfy8q8XsBuE&RkaoZi3MCAy+6E8jB2^L_
zRu!l$JEfC(Xn_kXY?Um~vbPT*0FLe^2sFHXP%u9Ug25KDQJ8=y(Lnw8PYSMTN{co1
z5@CFFIVHBDd<ZEmE;W)9yIbQwxtDi}ZCr_ZX%im?V@~beXla+C#T|+@I2|_JowTnl
z0Bk=g6f8&tLJdGUK$<)YQnFwJ*$5`dN&!7hf`u~%@amhGpJ$z2qI{fP=UHc0FfD*M
zP8=~s;x5hmq|uauZQ5W+*_yo$T9)+VwnfslkO+24-wu_aY-c<YD35JE%$%tiwTw5|
zM?Zf#LKY?PQ1=N94Q8Otp&)Dg86QJ+Ei_>i9@k29^!=AxDk?T&xL1CsX<64w9ZBNC
z-WYGw!U6-~;qlwi;_Xh9hm(uQXK;H?-R_3LoVwmaf*Nfirh?)3Lr(F<y^uF1ln?Ok
z=4q>nwD-NKD+`!|J;<y3QWtOr84RTgHMsaoU0PTjRG?sWYWLWbt_FjL(b?8$@Q~it
zZYs+vR(=CKQQBU+sZFVj?Vb9RirC)Nr(8^+IwccnyQxp9(Cyu%!9qlCQ@0cdW~M^z
zJy1Coy~qeD%aDhg%Cc(R(#&ClaS07E0;Q`rWDOeOH{OIVX!~DTFLy$@$Gk5hkRT`Z
zP57!OM7u6^!2B-Wt9*#Gix;b0_wAzQtRlD9{CxGatKLeO;5GEXLga0`#^(!*`8)Lp
zWByJ()Y?U5T2X9F=`o>mWkydu2^(Pj^lEHZQx}MD27j6`zuLv8Qk18a8AIi0FRuKh
z;d5VK!rG7}L&avVQ{5nn7x%R)$<DNJ;kA7vg}rhD^HC>2b})Hg1z+ba13|9A5xGIp
zOT}E_moK|QL-1so9@?C;A`Je}R5!2~agQ={tXv@W;s|+23mYbFBWW*!oFHMy6k^MS
zAv2n{SH4iRa-n8dk1RevyE<Sa|1IPRz;R^&%N(JR)~%6+#!a0#$5Wj!#}hU)&hS(h
z%rGPGjx_7#U?NPw8Y58)K!B#e1~g-9s?<Ji^x<JOZgs-o#-&aW>5P$6HIvoOK8+9i
zl@gSlsO~JvfW0-(7>2tE9<VXKt>N;O8AP>Lm^dUOZKD~a>6WA!B+R@GCJ@+xbBc&c
zqpi3x1Wo4TmWa4vagJtF500a8Xu79HV;>I0WMzj84wIFgYn1NHrf|fSBSa%R*XUF)
zh}}5LG@rkNfCI}H!~s%T+6P+Mg-(FxPq_#h>eH4Np*fFu`5GGj04zY*fT=uCLoHHk
zI<65WU`;804fVdQvEDeM0>V*(PfzvAzW^SHj$H@br!^h3aQRzP9dM@sTPLg2fXy1-
zNIg1C)t8uiRBoh}HWWFU8f_?YMm3kq>p+wKF37&~m{5^w1~e(Jqj`C}CRt^4lclUP
zcu94vn$r!YW6miW4}sBEI+CeAR_hy@OLjrEzi<WS6#F9wBBmG-P2qM#tHYCt8N#)0
zosnY=bukuYpdHNb1vmz`dAUCujVzrlI#u}@I=XeFF*#|Gz)3*kmbbQbI=Xd)0UOsk
zUx2M69;DpD4L)sC6}HBREY)dS=}751*0(y`Ougx29n6Uni6L8EDtU%%3BE0olY+ga
zD0c=zbgc*iAwuDWOSydRturb@x@)K9yt`KZZ}7P~ZlW#)5=Goh8D1?hc8>@oNSR_p
znDW9JL%UdHupzR`gk=1tWP}5Roz@%GH*AekMxQEko~-L6V5C=<CBJ2)SEuQ}!PjeD
z`V?`Ox^{h|BVHKJt<e)t%?MstQ^m=K!_rizk~vS-OQT^hS7&<eqU;eY4WV3$acQ__
z7#Gu8=gMh^((co>LvhoZpW>EP7!L+)j8c+j0X@Z3WtDkLrrNAcVO6wtG=sn2R6Djo
zV>4BpU6lOkzIDr==FN*#r2v${s3TV?BC8&@TN1!7xN%Iyd>iy}^SVW$*Bg>e8_IK;
z>&Aqa#8k96@pVi&tj!QOuL{Zy?={7wHM|7PCtCRtJv<aiHJQfW@H!^$&5Mak6+qV_
zluGi;P%6gYH5#QErPqv0uRF@P^p_@w>qP;94d@HTi#|yw!VEdKlVOB7%PcfgEETj;
zhxZiuOGi+!oB-Mie4vMvju=Ud?PQ3ju9FkhV@(;;i<A&g%%W;1<34qLtWYbZVXu^>
zYXH&c03q80tr-0<jSP}CbSa#Wtf4#M#7dfy#v5&iDv=OrP9sB9iF-JNn`!!+4iHZs
zcqcr%Lk1KSA2cPpGxf=aqZLuCt|@x7a)Nm^4T=02n#_>3fN@!h(M9^x@l}Dme}mZA
zV3HhY#NT515nMd9_>og<Lyvx%CWmf;vjUD?6b2jv%ke?Tps5~*F{*1^`XfZ=4GMT<
zHF;7}h9c`H7H@K?3^lrJ^8K(feKNAV>thI=6@Y|2+=A0LQbvuFy>CjygePn5$@_W^
z{by{pIk9+=#j{p>UT852KIOwuPHTnAr-(<!PK;GkWQNWn-6G}i`SLZO<}M1RxGZ&(
ziR#GLu_=sR%h;uhAsefmc@?SMt#;-u;04R%9lH!IWK@_YgA@8<G>ZYX!!FavVd%RA
zCVMmfO~r~V&@W8&j10!VOA87J3cI>Sk8O2zy7!C$P*>*!p!{8qR*uaze!L=u1QY2&
zIX2e>I+9U1{5<NfA->}tzXV(g7-PFeF~2EYCed+$6m8f1!FJ|t@HxZ`BU9n3!){~<
zU1A(`%1e6)xZ$QES$0>75P65HzlLI4#z-qx<1&CF+x19Hkt6iz(@YY2_}DQZ$=k(i
z!2tDOx1^2{S%P0SpyOLwLXW=%lub%}>;|4JiVoOK1-&qgySR11ex(dArY}_%7};$%
z48}}eifl5p^Sn{MnW27o<)ke<qsmz`nltZ-R*qsKn$99wO-RZN(o*tVWHCkmODuwp
z!X&&!$b>*0BNv`E%H?BL6OI#5ay4%8wdXqkX@rL4`ARh89;{?ULqU~FSd5LlrtsK-
zW@cCFpg^8eB}!VNBvmdY&k&x$$4i+{Ovzm5P~~tk<*D*K4f*PE`a{^5=N5^fkrNf;
zbnyrW^rJff$?27V%DgCKtsWrd$QZa22Xiom0YHY*W|bq$;~Z(UM^ciNv~MiR$Xwi<
z6K;jd*EPnS@xQNpTG}KGaMhI!9O+j1=b8^*@efo!-cDQQF%q!0^kid}yfT=LS@I|D
z59Y|9f=e<0MOChJq-dRcKJ}smNQiQ-dA}|#1-8h@<2seNjX%n->C#YUd`Bxk)Ww^T
z=EKS%f0MQ(b5mA4&jMw|>wZ8|yexFKWyRxw`z0&hwybz;DIl6t>5Ta?E53w<S@Cd7
zn3Cd4RucK*EMWmqQaejpfP{bQpqK#S7o<RFQZdbY>y_X-LMkwr$(!nMm{Q{(NfuJ$
z?NqPW=11WsEK1^8oLjF%v@o)rcotGCfXUU&m~8qcZ9orygEx+##HP3-n}o#B0WwjQ
zq{;nhlc*TfAZFZ2O_5=XkU$VFrV|q*(Nt^_6Jv<u#Kag|pTxwVR=x586NF;2RLUYH
z3I&a-Hi(Kbw{9UNijp*-jJ5PC@rMGK<l1^AJMpXe&QD<&06>!W#s;jJO|^C`Tn<gu
zc&MJYsMcedvESrSF_dy_O?JaKX_+$OUw|l*ivtM2P3{Xr)MjI_b!I~@!%W-y5ErI8
zwS<nTJ~3+{D8DH*)Z~}|6{xs&%gTVQNn^x=rYWG_;1g+x!#|P~OVGyFEhJi&cZ27o
z$<A)T382v`eh3GltmX#yN|T9vQLe-Z;<o@9g1D$xKHk=!@E3A$_tqf?cW+<G!SM^Z
zdQV9d5Jg%^007?liPkk}t^^@5n@-7~6D7;gBw|x_NyH}Gy0oDZ5lKjVskV<SA*Pyo
z0e7u;b;J4Fr8$fQB0~J#k(3;;Z@mbLRlNv`m8S(z4_cR_-qH)zWM?&m<~CYY7a>PX
zq!lL4HW^KAAgQw{3C(~y(3H1kC~HeA{Y%yi+VPVz($Y_vZ$c&;Xy+94^h}@F@+aV|
zg&}28U?2@reCVlO;m2SXBdQutbc7Z+Wh^ET_(6|J5@HElN+W!4&FdU6;>4Z&S>nX;
zQG$Ho=56Z)!0hUkSa^CCAgH-T_9*O8M>v}(ou`oSC}$_o{B-Was0CLSC~+OS7XR0}
z7{IA$etir>4?dX2;JG_KhH~#84ldl=hjS==;N?gfE2yNIE-TnP5}y<7)?;9tKwFd&
zIO6sj=hi1Q?k0;K?SF09)+xXhWh6lM_42=(xVZ*)z)K5K!cfX80FP-?IaC@X+t3k?
z!5?kt5YIgBHgtx=&AL3(U^Ai6W%i0x?~z!Vyr3idyA55>h*%F_x`vZe*Or72H$3uC
zlGF6s%IF2u47&P3Ih(=(Udk(Pqc&l1LN9N}JwBy*Z4~n676d9;b7v$^o4R}vW#3dh
z*x+bxDll9Wov}=6Z)JiDRF4(0VH!`i2U>9usai4<;ZZW-_=Pm|o#5~s+r)#zla`i^
z0GLe!(!Odyi*Rj>2#K86#)nvyxwVdrq|ta|k><UzB`MFwmRPp3+9l;+U{6pK_fsv3
zPe$-Cc4()V-p%kBv@*+y(#R7iU6+igqTp0a-$Wc5myShIbPjszY64ynfhQafs&?sq
zgO8(K*EYV8pE6pJa+{`3+~cieP}LpaaG;;vH6Bvx^AjVw=l<JkME3<@Oug^EB#R*E
zSq)_HMWKmLBq>F32es$?Y;B{BWf2$@D92ZoXftG|sEk_?S}}C11jiOa4(WxedU893
zOB7<NdUQqcl9v>B!EhPyXImLcM3LT`{;r6~)u)3n542)uK64YN*v`+~<S8k7;Q+@6
z7614{ad@ySU=i+3=*CuC&;Y1gwFeJ#JTsnW;}j_pX1})zhm_^2f|wg%uawALQ{@!7
z*;bhM$A0W8!N@Heq2SNQ=C4|gYm`;&k;hGygXEcol94<@Ee7n{nbfNGWSyy1o|5M-
zgX)huudB{wp686h*A=jp%H%as<uni8E>&~WQbnn<oV=w}x|0`KRrfS!Syq(*wHVv8
zUHNOaRYjDSY*raHXN6WF0pnV(N~OHIQO$I_@B;*2D!_=8h-BPBwV_+vG=N}2nI^ny
zw3Y^NWsTNB9cGQHTi-N-;DKVF-|A78hW${Mx&n=<QFXY)U(&j|f_|ZxRh?Qojkls~
zWWLQ0#@pOfr~LBV7?)qZHpb<buU&VF0;6T6a8|^<w{9VGcK^a}YPC??dZzv!AIyEW
z1qkLo8~;PV+PU#Rb{Y_253slGI&Dm;?K*8tso9UQv9j$tZirTIyOJC8X}gXa;-ZXp
zD&f8LtygU3u4H<u_g#UDd;;|5dQC;6UQ#)J*Y$-*P;aB&UonHRb&3VqY!)a8Pk@Bu
z3wTYLVx=cd2>fQV$nvtA%>pIjX|wn`=)mudZ`%;6R(7g<h4#&Afr2~j+5X0}!u6w9
z8tcQKXvNSrLq!Co_RUU_uZ@)gC&OHiCVQkov2S(?7K(41?I4bh-ZnEp&uZtpp(2O2
z8!B>mzZfc*DEN{s<LH~A!j*3LN*l@9n2`uVjBadZlpNjAg$i>_FDnJ>#Lul)4sLFr
z3MuSqvOba$%q#O`ezhxZE6hute}hkj0IrnJ>H}WgTc`XJb;+?jTc2Rmv-QZKJoRv%
zk-^FyC<5<tYh{*q_mYL2Y8Re-SpSeY3u#EP?`~VCH4<-IpBRbjK{b*+$0D&8D_3>2
zVuieKU2-U8vOw*2_dKtlm~18s=os!>m)K*TOoaO2W3$^v5q2-LB~$~iBOq>lpIe_~
zz|^sUJH%(5H8(zd@vOn6;g@>hict7dShnNa1T{!dy(s1-+jo9j{!P{Lf_ZDA+PH$D
zY{FpCU0NTW%)Klj=?3U!2!W%3dF(HG6Bd4e9&2zpARqoEuS8dTlST27KFS$}vvQcE
zbfQL@pz#(ZxHrlfmI_B7<qV6LULPHe+(4t8VK@iNbb{A>FVo4)OQ;X|!+JDmS(`ZL
zhI9;MSM*WdupSenFAN9TD8Fe>gF_$XIQ3|eiD~2QLzYiKGWIgFpd?=(^&*&g)pb@A
zq;s#2a)de9SdOp(Hr`CGp&N05PrT$}Bsj%Oh?0Fg;v=ful__Q-45Uvz60%-SQ0U^y
z9n|M3)+7(Q3ev#Cnjjox4=Pkmz7FRVupQ(Kj*+R02PO`{f6&=G7D5RA9V;|TQgCd{
zl9c@Kl#(05HOotyJF=H8CliqR9GVK$$T>8V)Dl@oG$~7lr>-1iI(6ZEGTx~R3zWd7
zeb#Anoq^4Q_zvi4Qzs3OQUkt4fdnBLQ>VmbsZjRG2w#Rl^)lrEyR}E<CWb&QI2wF8
zw`9gGFi;}qb7_SU0@W`q@Wp~-TwsJibwp1cNs7y$0;qsryC@GsND{_J(IWXHT{A>n
zUB6_YLmWyMgf3%Q`X!wZ{|bbnK}zoEOFR0)y{SkhM%h#uH3s7JtJdX;79GBb-RTv^
zg!rC*=~0g`sIEAsUn)i)NebZ<VzMP@RKF^=?i6y=D*>9<XYLcNIRE<1bp^_E7qqhh
z$*SMl%XjM1x8fjR*9sUcOz?*I+%ml){;3OV+K_d+0JkcPY$PEv$0I^2zOCowohq#Y
zqwMa9@um2-;A_Q1v3^j$^_;+e?6;nqNUZHQbDRtXkorwc6X;_{zu6oCWX9;bEIfDX
z^@%!C{gy1DI#s`wW56)0eoO5{!L5Gl48RZcTQ3e+{{pTJryg>Wdqr6RtF0@_Dl5A6
zJAd>Fh&T=&KeR|3{)Hvgsex>1!qFuqSG2<DU`P&JyOX3`Q{5mpOdu6<g>3F#ro$W2
zI}3NuL|Ws2@FabfuLi(<FG0`~+wT?8STTdAGYCH-wia_Ao&FDwsImkCE^tw>Ziv!a
zD28-2KDb*S`72>2>=o?vz)<#R;;`TOdDaglpNJdzQjpT3FjSkhQF#$A%KC^`<%bAL
z@;jj|@kfR~s&MZ7$f7WuJNF_WGV_P>LGLoDEsA?m8UwB;{)BPeIY1tyQI@rjBr#6B
z<Ks${My%4JaDa|UAkXgfRA-%WLk$R^eqLzh@Rdn}$fZSL^!C!$fO2|(a3zJ&{yCxr
zmAb{$pGm2Z`hmZJ+oi!0=%><t5zMrZS}Wo|*FYJ)=LI&T5%y>p2M}O0iy)`KNTfxH
z1+Y`oj4L6KWih_RB~xAvzPBhG8!C&MvU5)enkjY70CMAsRciQx6CkDG8y-j`jC*p$
zF0t+m&~=%_F%p0`2baI)R(U!37+4s-m12_Pr|cfAmE$lYHlR>=AvM6_=mNH4ER+|@
zg28s|1)*RbE#{XvzRUnwmIGQa#@R})$&c3nDCWW^V{DWc+yG*uT;OQUW*{tc!Wnb#
z#w1jv_`4|$0R@p<rbt#z@=E203G(pD-nSbQs$85KKV7*vH-7q7uT&onH)V*z=C~*W
z?VM8Ok)6?E7TJjpKT32?Bp*RuCnZ;rnPn88N-Q&c_8}4^s$;q8Sv7!NdP8a_;-(1M
z{ZinR6HhYYqJra<uHI4!a2P#V`O5`(*?=nQvV%6*6M;*9fD}_|O1DH(uva=aQh;4X
z&xV9wz@#5Z3H~a8YsEadfJ+--=L3oz?fkAVJTm3>Nc?t;7so(TIwewSz3u6gAy$=o
z-C<VnO1(}CVo;c`iW1i<&Zg4XI^TQl;jCZ`LXKJalc=V*D9iv|8-AhT=f9Ja7yZLg
zu`k#l;EA3}Tq5kh7}4aFFb!j&SHg5h?$d(qXPW7N4Bg_(fD9?S5~-n!LbkxK>rJ}?
z<qa2wU%N0z-4lR&b0$e=lv9rA(bsOQOC?I<V%QR;Z!oA5rQtnrWJ>2tU{z7zm#~j3
zQyOMOXQniO@qEjaMhd4_rnFnsZg^$M$}?I@H%~{PSC(`JJsm+}zIjSZr_+#W>nIVC
zgy3Ws&;y|CJ&n@`NFxZC9uNp!)@ml%M`4QOV<cs|jMpj>>MG>Obbim2Y0snHD`h%^
zpj_DCQLZ#Q=pqELz#{R(6TH_Y26whsUbVAOyrY#DSl68vb8&t5=AVnPH`Yp*Tnyc%
z5y2Pem30lbo_9hugy45&q5|*11>Fuzh$Bf4|A^f%-E_h%0%kiX7`he_Tz7coWe*63
z&XqyI;AJ@|7&N7{LBW`SN`XJZD^q(=FsNI?m*A>LngxHoU-)-!NW~};`-62-k}|UW
z@GtTk0&jq2a8bCI#zZILc1(5J@JynUPNxVN_R9Po7bRBrHA1jleul(WaixMc*s@)v
zT^nMl9q0-#V7PeYh9i#Kdn^qs(q5_J5kS7$jkqxwmyR)502hU@JBB_4u`zywax$Cx
z@SU=3zCj?uPF}YzAIJ*UicYR9-mu@UHU@`Rk9%R`xcUsVb2sfEJ-KByMcgJ`5yiy+
z*{3+vi_k|?-8e}e58EWCx`F=yE%GSoOHd<Mor^`ehDrv#B7iH7MptDF;wA0V&h?Ah
zL--wNd-4|{r0ZA|B1xU<MJTBgz4+gANu*-IHi$Y%2T15bs4r75B1tv%B9c@rzVn%K
z5a!AYHQ?&%1SG7EJ{)~l7mgl)YwiurI5J%CZoqcA%AWw)%bgfP*H9k{0}#U81<{dd
zlZ!CWj6=|st_>(Mmj~@2UYWBx3n9(C;0>-zy*MH0{^556YT6M6usES7TbNAlQ5PBl
zfZ1HZ#YAs&uUickMK8pJ%zZ>Ht{|9t5pd4b2|?;D(?L<v>m^J&cin`*t@DCjxVh;Q
zWe<=_t85t2=5o=cG~ZnGUr_df0+2l}dx1CHT=&A+!@3vD-cYZBHoMR!a!>Ywh~8Xy
zCB)xcc%klb+4UT~FRo&t?%~S!fmSYBLGC?Zzo3=?sED#`2S~ww=FUId+`8f)Zf?O(
zJlx>8^AABjy6Z6vNXSJYVkJyWPJ0odC7r(6LjaUPO6I_7#}afe;aCO*Bf|6DhhB@w
zhIDy(7h<L-KnBn>tCgJ7vmAh&?ga}2)J|8aC_;Urbl!__pr3@~lOjtRD!2p*Lyy~8
zC8_qG{q<MLM_&2`-Ld^_QSxUYbPwM8E;9lOvN}UalQb}Iz=1wk4LUAY{9hZt5GKYO
zi;+=-4~CrUv*Q0cI6*927$r9fUh|PP&`-Gb*z8ylA?YWo#7@AA&}jqdCtid}IY7!K
z5k`L+3P0L8WtC<*v4Iuvw<r^z0{AUYWf8K`!J|i`FG?JwuB?a^fM@uPqU3i|G<rbN
ze6~4M+&Ud5mi<Q_4GrIhd1R-U#)o1lt%;eypKis=WJ_zsN>I9HV7Z+;jVs09#)DVO
zgov(B%7c#~dA1`DZCh{Tp+P{}+@%L)^H>Tq0kxqIN#JOE`Jh~5ms<cmeNrNtZrcH<
zFtk%1ZO6oyZVz`OIQ8tiF=5Zo+K$O7AYRp`4#4u~{-Bt4UxbqoE1kzjhcQM_Kpn=I
zPYSzWjXHcMH~>N7eg*&E57Up<cBJ<1x{My;)(_oA;5MF&b&Pks^_;0i9ob{N4UQ!7
z@*$rt-8}`YKYnR{-bKd>yW(Y(U%GV_<ptL9_|YvFVOMQzS7YyhjnMVk@i2)SHn|J^
zo25{b!kY=q1)$zhmv^T%B`){wJS|n9!rP__Fbs?O!jYu;Y&u1E9-&k_I%))#YSJBt
zs<fBxJXKk*f@f;gtKgBU+Dn+KD{N~~M(Qr8<S>5G$2!E(eXnRi)rvfsFcNr{w77CP
zs-OkTX;K{-c;zaYh`=i-pa&=u3MaX6V-c&K1&>wMv*4lH3DVog8BI(W`C_F)_i;+8
z#*{~?$B=^zPEA!Ea|SAuEAx*rRHg5CKtQ>xKt)D?9(p!(1bDh|(mE19-BtVm;7)v?
z^x^6QrN0kXCr-=NDVKI|@dYrS))B=H9*msw|DUz@>Afw-wZrE7Q`}*{L3bqT52>jE
z+dwi1Y<EUMCN}&61h)r%fsy3f=ZIWuom1t$zpA?ZP(b$;e@B~?wzf!7i=;vz$Ku;p
zuKe<j=-4*s9T6sREa$O}uEVjo092W3aRKlQITjW`*Q)}oLPycDLY+8-!%loHxWJvN
zp||+u3mS7_P*#U>3}QF+!XS22FN|UH!!K9FGd90{9^1$6>V&tjO`Wi~kPqSQB6u!1
zs{988M!o$D1E4lIA(Ar7Nl_E<;SfQ3je*1xZ*Rxg>%-wQKD;3{tsl-1OzYm|BEqBs
z67_aFjqM+<tpV8A9HCLd?ixWy@Yv;L!&})n3J+E6+jNVn_EWj?IQ_uzr|%8~{vOls
zEn77xr;}U;jyH9nOx{1-i^J(Cm%ZS4#X|;ymxmIo*o{J|tRG-fQ)w!Pk8+mc0YgkM
zyUthq*2zBPs-+}T9$rc^)s50j^_qOp`jumt=&Gr7ox_*9QKBsev?PLMJyd0hPLUxc
z<+blCeJJ5p6M*sOJ26)u4)P0?LNC52X#8}rCz1+IdMp&@HQIn{VgPlOZu`dHuovD7
zl0;2qQ6;46nL|52FjZ41`4RMvYEzGn%ZcJ0bdKuA@uH)2p@DYYPN<p&{Uo{;xoD`m
zo={qvOR8?#d!wuXUce+^3imj81%Vq;mK}}B>j`bELH}qMZ*B<MMT0v+6YI^Dt_=~8
zC>8+!E=bgT*B+(6M2UbeWxwyg1~5zS3$lxF%3Dfpalj|NZ{8B}gbO>kEl1{<df(s;
z<d~XDg?zzG9T$i-d-R`J$f!EyDKon06Yi9^nFtRX2%Vh9tNE-%dg^);d)vu-LT+P+
zm*LvV4zI&iwC?aaTqnOXY8KunWV%}v>5}DFaa)UT@=V><l2=}tm}(XfNA<o129E0E
zqWDs3W>ie>)ODItc|U`$7)9_5dSXnLIsz@H3XL9DIrHy@&B`@pvX_tR5*@S0^`TAW
z;DGQhDSBuqC~f+nS4FAS$EgLPum5m?(A_$T>$35nIevi~xRjg(`h_nhtmc5O<V&fS
zZ3rVEl585i)~r%Il^-94jNiZp);gZ5<oU27@+H*>5?VG3{lF1m$FLH2Lb@h-C$H62
zqP|T*Gx8N(gxHm(^LxC6f~W9<oXB1}`=Oqh2+VvVNhXp_O%=)nXzYzhxuCH(S|uT2
zg?3V1Zep>7gP8<l_0PiG`PNkEV#<Z1dXE#4nNt-WFA|G*9&`gXi)Gfo6PxuUN{HRM
zkVLsYFYaop5XuxzYUvqxlNBoYfK-fl-kU;7)md(S;G{4UKvhlVib}*(6=JWs6i#aB
zp~Ok4Ube7OxKDtX&j-?L3M$2Gj47xTPbf2?QoOzgL<*3z2NWXN@Z|vh^aip`Afs|Z
z!3X%7u7cQn%lT@+tdxV|W()n4ZxgKm&JH6y@GkYH5#m;*X@z%!K6&Fwa1)l&rBpH6
zr`Fpfsc@JK3!YV;V>W1*`yJi}{+*Ju{`+@*+*8@pCMsy;x-Ze_?rT&Ylh`Ui8K3V2
zI~D8_qM4wa6b%>fjh5`Cl=!GkI#E%1Hn_=Oo972SbXKtE8$rq~nHxk=$^qW=MF7||
z74DrdrW}CE$fKb3RFL>&4eYEQ4{^7^vRjk@pti&XjHhvV6S36{x95p-N@<KgA!yVz
zOc&ml6!`E_BrRtgvDrr}29O_Clm9LQn_Bw2pcn%Qgr6c20gVa6abzd~L!Mv~+)R{P
z9(h(#5O~0I)Ho6w;Dm8_%H@G=9DFSRCymS?aS;U12%uhZIJ|9a9+_*Nme+UPlaJ8q
zhl_30g;&luj=c$OuQ`~EcOX<^!s|v$uqcINcSeKp%6f!$dH4wubl*rRggwn6dMQvR
zy&i;E-{2xI|H#O6s^ww1*01w#HAY%A@b)}O!bIS{mNnChQe))Fh!?FxxkTU!dt}3Z
zmp?57BOpJ5(SrW2^7gTY`gb}JUxWv(dIP+trgM`=kni%E@{saf?${B^e@M@7MvFkW
z4dJw3*KHaLtAB@QJC9IhBGP|9l%JQk4flA4MT7g0;j%8^EPThvJd-&tT(-olI2_JX
zD0+wU6pG%#YsO{!a9Iva{ot<ILfnJ9mTP?m{$6DDK|EP(eUVggL0jCBKf$%gj^dB-
z;uz8Ix@edvWXz)NMX5k0nIw$GS47lgWPKqYo}yIX*TUaRI$0Zxhgam)WB|OPvu0wv
zo{tc&xfo8SwaEB(=YET9_V2i`d4t(q2jjVZ8C_Ns2A5$KEe4n2kUMY0xnkJn0wyFQ
z-403h4B5Ghv1LuuUEfIt&rJq}??eCTL~^co1m3LLQXgS@6Y09fhDK-5_lDQ&rLGnu
zFSVB~MqWyRFGgOz*8;-2Gp+kvs8lkxR5e1l$KHBlh*#TN@*-YsOFu7cpO>^iV4S3$
zTcL>Bx)`Rtr^JQQ*n(foipo}y=44d1(%(-c7aLn@Z5@?~&lcX|Hoj%V(rs;2NIo{U
zHmU`cv!w_T2AjUve9T5>l1=BvEMM=~S}q%(nR1s+hGbX#_5)H*RYRj<d9_DvsG~)f
z#HD0NG#wDLqG+FVTGtSfoc0nh#EPpOOUD}pUlV*d6@2XloSclkb`208=F*0Q;ss-A
zL#k;;W%;|KqM89q%io_Ms%kAw3%<>@(5jejDYZQ+7txYZ+XGLXng!^zC94e?jK?DQ
zer}vfc^6Wo#mkavR%EvphXSs(I23T*iPoD42p)@zgW=ZNO%!t7G<OWSM!e;dq?|ly
zF{FbVDo`>39vt&%#y2tyz{x&0iXHP3t4K@NT-C1B06G9~q<8R-F2!1K)d>XR5NhC3
zklo-HU9@?qhc=JRfJ0vJUJ7$DaLN&ZsN2zrJ#7dKH4E*CyGTk`+^6Qe5=*d0Fck&f
zQ79ROe$N~V_R*=bQJ6YaItu&fROu+RRcvO3==_k7IB34Nio=u~?8BrGO|P|*LU1WO
zmymOy<fOB3nPZ%fK1>b*MmJ_$cPY~memH~#o)y+Tbf0nw`7H{AJhQOI5RiG|c4OoP
z$OB3WvOl_%Aleta5~|b+b!=)wdxBSGoS`d*OUW4->)mN3tl-_H=3{<z$(J*x1cL!G
z#z(JwIYQ!37zCFBMy9+sfpae^0}KTYBqc{^?_R5l(1Q_k^7M}`xr@miK7m~wa(+)3
zGz5NJ3iI-4Q>e)KN(aPlNX(-Ek;zzkJ0IOvAysPiFt)xzSRRtjDa?yHF{9DDTO~BA
z%dv@q4FhN5yNx+=T_}=gBGKY7nU{`S7xME?fNrxqJ=$eQ+xqB~376(apAwHygo&G}
zp=ha@Jrw0SQ2}L`oK=qFvyFEbOefU>69%9_=u@O6kW{s6I{Uj%O(wIV%t|Ins8tcl
z08_Zy#1+}4K-D>R{7gzdk$!S0Om3o#$LK<#Pu!}#NNio<l?r{r?jLXeCr%XO?d^0X
z>FBa2>jY8h&eW~)s_l<%`9}Kw=%w6h_*9@3`up>DC3WNabtQG<QuIpdrlJKC^<xH|
znM|ahpwCNLAL-^MQgt#T-E`+5$43`0HXI}T9SSa;xLF*kCqBJe+;!j&QE~K3sqxvn
z2gaxUqtX}lPWb9{#LvH7nI1~i$4No@LWTRztc5e^rgY@5y#x-B*$a=pA|@}C3kC<?
z(R4_0ltCMEIr=+&A=ft)-`maTl@gIF6?(Awd!-_MVMcXNl+YP%Yo(T=RG|1J<kD_(
zlsne_P!RgWfqpdU4rE+;djdVxYkTVsoB`UDbJ?MA+k5%o{7pX~Q1YX_S5K+rW^zq9
z4&+T1CCUqp_TD?7x1073IJi_^WJY_kiHQXoe>80zfmD7?8%H2%RBLRVlXza*a~~wk
zZY2XT6<N82`zKQ&mZU683htc{24F`P!v|$aUS>A!k~cG`a&GI6{7KS!6S9rT4J7hD
z(iwp=7Du+@2L;!evw{-r%=cW9@Se>~d8>*$pA_J>CvNQR*vI6M@}8W?f%B`5rmVLC
z7t;rclhX@557s^5_0=6|(vQAgQbM6Z6WLho?LqyZV1)r(a6<%q{ff}w*bStQ4}Gwr
zXnU^&FpOXLAP81DQMt?BeoIkgi^I2PF+M~t3ei;cpgWn-KA0s%g}MIIxBu|;Z}-1{
z`9HsPfc_TuR@mFU*6zRj*Khy)-1XgFU4Q-mukQcmug|Of`tQ$CMaI^*b>D-%p4Y$q
z^>5Gr^v{28e{L^cfBom@fB(~8|EW*^)4%-p|N2k=$6x>F=imPIx!>Q4u-7wpKfB$B
zzm7zE`?vr2@4x-GSHJu4`rrTZw+A^#zpYHx{I|??bl=26^5#3V-zn`4XPaM1`=|f)
zKmXtV^w<BZqzpW2xUCoe*GAGj=1bxIT`?_<X-R3wGWHWvj>?Gpg_Qr>|MKr7<-Ail
z?-Y)6GbX$~+4h>%{&$7Ew$IYs{Y~ivKc)O1I{}TMPKc8Ix)adWE3*LoP3Y@|FZK`2
z$IMihU#_u#_fKp6>A!#f{_W0;mf7Jl>-)aB*FV<mw|3j#o0?fgo;1pP$MjxyUkm(q
zpI5f`LLBhxfpxSZ;Ro}^Zb$)o<tQ<f6ZDU)_t)+^+rG>4qT&AjV*2xId(~?C<Kw$o
zI6g+#_m9^E(a)t>-<?SKjc%3K>fI}F==ieJF0cH%*QT5P%Wl|nH2qU9qCYbIuie*Q
zpID@W|M(B4|K}$^!D{Vubc3eSm!rd3;oVJ#hp)N~l$}$zp*nP5c7rl{cZ>e9lz-T5
zPke`Ri2u>uUaS8)_J6RI{<-}ls~=9kkFibv9ZUK8C_a}m+P~2Wr?Yo29oN3<cFjU8
z<pG;(e=Ox6c7x%p7eK-vQ)MrD_gks<S}^VJe*xdx&%XdePSW@2_V^u3*$`&<?xuvc
zUv>k?;N8v6?^w!JrS9DcMeDxm(osS|)8AE7;g5X*Fa3LO9kW2>kEZ`0`2tWvR)bSX
z*)K<j>!Nor-5-6~4VUTfZi?~wvKuniyt^rd&6nNaJb1qXc@uu>3+Vl2ApZSL=-WS_
z0}#%u!JYX#7BU<_>ZIHCuR3Mk3U%4-w-x>Pm7X8JV{f#L^@MF_zn9Y=UiGi9(|@q&
z{~@F2{Brf4-?4T->_8IwR~r=~S>D}5;DyQ`n2{T;G}lXCd|Nkl@{bIWpPG_%qrJsM
z^UJXzr2O4UgfF{wq|kf!dsDvd2n_m1M^V1+h=BNyj-vd;Yv?zKYrl4b^Ywf9iMPNi
zuOE_%^7Rnms{80D%GVv!{q)fd?Jqms<buC^^>5189dWDk(NUD2coUfp@BHQ$@pGDy
z393G173J$e?q41e|Mu-o`MP5{>OT6B@O3vp`#<`L@@2=mNO*T+`zPK+*4v4(&iv|4
z{FI5vnjIf<it_dF0ABm(D9YCzk?827qbOf@MCRv@j-q_s@x(9Rya+$@F0OC2jFm6n
z#m}kEzJ9gX-jpwgc+a%+7n|^#@^wc<B7dr0Qoinp66GHqMftj8jL%Nl`ib|D*E_%c
zP5hM6h%6-^Qi}5B(5_?W7Yj{<ue%}s@1vh6Uw1@VjgO9^eBBWszK@Qg{EX>z5oY^0
zzloo-ovw5AmkaGp`HiLhOFQ(JHs<$lzkcu!H@bWky}!4Q^r?yP$IP48OqIK<XSt&v
zI9%q>Y~>Ubalm&g&$|~<ertr8%l5OM0mbrlw@Nwv(TzE%zwFk|{v|gMeybZjoOlcE
z)5H14UqZW}`5#y|;~#hlZ66$rHN1Vk)~DzQxb8<s)!Y5L<FsFMoc6moBFF4UM`fM;
zx+B8H-tR*3V?X&aZou3RUWWZ6F9X4hA0t$v{I5oM5bdFUN8uk|c0-8!yPMD7!wu-%
zcemZYa#XV$%0uxju>F%S;au?kk1j!e{v90TSAGv}%-=IO1cAQ0DJt~KZq4D%Vz=gB
zd9%<hPT}~}jfCImCO2@sf%q9O@M~PH%*yyz_5xGNy?-^hy?@W(*7)d>rL(^LdB$74
zJB;(i^(VU6{^(%)w|)*sG3NTiPyEMc`Xa>s6}^p+&<`)hFepFql?#^L5U%y^rueNd
zy8(py?&kgXa08tG-A(xZFS{W}6z8AqpL_#;A>u!H1OLE|?}OKA9NhTwI*r|s0Po#R
zwGF=Ph5*oaH${Yg)oq^!(-hrE_>FD=D)J4m{gZECUwG9IcAI~|0NQ)}YH<6@i#T>e
zo~w7a)jme|!*0JedH3(Kc()BXJ*u0H-*FV!06Xdp2>keSZ{WtP|KJ<=ht2^Xo*7cU
zJTL)h_tEi9`H55EMFH0Vz4w1*uT{5#DSwFiLHZ3}?k}bW&7W~p-}s-6TdOZUK|iyR
z-4ZNy!S>+=7U?%Vq`z7KAEcjg1iua-=XZ_tr<QB0XqC_P`X+tt*h56*XV*9BXPkRC
zh`0Zqk?x=ID<O~Vhqxc4-|%JZU-%sU_U%pi8RyxJ>G@sbjGywKRbb1fv~SXHxWeMs
zi{XRxQ@48aFKhhvF7z|z9vw)Z!oEqr;XVJgCi&H-{r%hj@bup^?i}-<@96J6e2q13
z5PiMuUl05LyQBWNhTnfVVbRB{_l*URQu@>XtLga)mU?fy|DPY~l|U-}R4aEeya=yB
zMS;%4nYjf(=x{i8?hxFVQUOroa3bJ=2M%WnNmP*x=W;<dfES?}H*PAN7;4-h1OvB`
zFFu?(1gflLsQM_1Nro%o3-T6RN}c<FL=FXV$AAcoyQ-9Ex2+zT#2_}&$fz6{8_qQ3
zV2Dj%c7jG@Gn5xu8)7TDSd_=}Qo!W?p7DE88)a-@QBZ^OwlQv`;|m0i$HF<1b&D$B
zL@<v0^)E<Fqd7_?C!yfwz<$T(aU5wdViRu_8JH8B_FEL{B2>&ayrBJge66-u2S`=i
zV>5LjK<S~F^9YEg#D&Ow9|}Uh1uU}(o`JcoXfhPDjLmd0l}zMGO1dzCm5<G!(>OIO
zVsYZ&3|@%6C@=MGBD5b_-eMExei~#TKm-X=V$(-)8YY)0*n>n+my%+gUQ#eN4O!u0
zGYSD=1hE-%f-G_Iu8fRyF0mQCc&Y)GhE;`_g=1J%#9SWZs^TdX0S_T~)2WmFW?Hc`
z@V<~w^$bYe8I=Jy&5Lpy^Ysr#Je~=8m^lp4pV<5~&%{Kln&zRyq*dbzvxr|gb>5A|
zkhxQrm$4Wvc~H{tQtC?ubR$$D``mRDiz%4^TZ@Gs=W9hSg743z<a=H8%AQ)uNvKIJ
zU|#45e>S9Kq~$^K&|vNF8%>ifNaPTKxtLIE;6<oLNx+!g2Q^49r5=|7JhusnDvm2u
zvmD9pVi7}lkZvbb<Q&QGE}=Gub1=0G?L&!yODL`f6T7G$GF{$ngX_Vtm`4=p^Wt5M
zy+Ii*)$FY>s3%D%NZaZMC00j~)L1G7jCur@QdM#rlu)Gwc|d|g?JxXEuB`E9f>|Dt
z4Z3JC1I5!T1yn2(Yr{;dwlV6eUdlqd=GDY$JlQ0hf$^9|I4~X+Sw>dAkX_Rm+?J$f
zAYIv-B$<$e6-7G&2ri{$tKTDnuQw>A)#_8fgc78QN4?vaN1{P7AzRH;q&v6sh;J>S
zOR48VS4~y4ZctXtd~gXV)}@g5RXHJ;`)%iHnjt<=a8nhKk?`zNI#+^2VAq36iA~qc
zL5od>Pj$pW2J#F&MJkb1EVx0DvCKlxG;X0v2)CUdgbEp4N-F12O@fZhaG?OfKt8|v
z0v(~7p`sy|a@V1<Gj!yfdxGUkI%>s+>Hu6yu7^zO-;v2Kl&`<{maSy^+-9u?rP;rf
zfi7U1v8kaH`W=O3L+SA^1p`c}dg;J9^-L&1WuWhfk&QX^RH(s92l0SZ($8$&e+`WT
zT5vK1up`4_sC3b#lp<8YqmF>yP?Gmc$#pR_7{j_4*&0|A#xUkyNfLvJ+Iye3QU8Ka
zw0t|ll7qFaE+N@<CY0$N>Q1T4U&j&fq_Nu(7!j)9)sb29QmP8+rL1go^iX-TY4Ff{
zN<#iRuVo9{O;xac@=5{HZe2O>si}=Z8N@qE+J>@-_pEsmDol6VDTs>Kb+}nBrP!2e
zQ_;Lj$OWUM7Eebl+)(wsjs&4GT+a>2;&?8!+i=MS(>;c3)X;Fl#XU9L(D&PGAH0-&
zEXvu&*xFSqNopvWcSj!8P%XrcWUMi0(q2j~4y4R@l9D^`SRcJ=@@Up}q=F3P+rE^N
zZ?Yy+N1lUADv?X44SLNxG9$!5eTPe^`JG}7gEYnvZ|J!(#Cv25F90cXL)khy(l*3k
zwEd;jni^tMC$(W>Gw>dzaFMMyQ2FyIQoT3Rm?nn6Qu7AosBol?`noSlw(c=?&?xRm
zTyZJbQ&7StloX^Rg>mS%qZ=%vO9I<cjjF2JQD`_uJpzhxG%<!^9F0eSj^a3>#3DT_
z@!mH1ZmbM_&B*^8nLoQTL3AjAc1IHFP!-yaMAM-}Bpu19F9lzC<*R-!g^Zv&?P!Eh
zop#Vl;RSNIlvQmgXoHrt5E~r%EW`#%(n4&YB#o_ngGzSN5eE}YvE4DQP>Su2v4>J@
zcg)Wd%CX&FGk9Cz3W#rHW#f+OyJ57{`{<CWwD41;`@I?M?2h#kwmy25Xt1>VuxwBS
zD?J!0_k2n9`j(z*czsh(g@R+6?2b#^s@U{^a?q)MF(AHd@k*@|N}Anubxh-XAW7w=
z;M><-v+U+7=Nw9t-H{9^%+#rd@?6pap}KH{&|)St85L;5x*of;wK@0o8Uoe9JL)Zj
z@?&?@WC)X`J)r1RWBln=Z8oflv11v)u!dF%rGDwDcY+DC`-obfD4E_--}Scf4UfQu
z`+0ZCD|gw$NCp)>=t=3Qz7ah%0XVcNV@!uOjxHlPVFCfgdQ}7}g+veX#=%WFwL9{*
zhO*3b)Fz2eE&TK<(i*B--%%>%QtH7-n-wZ`-{)oH^{;w4UD+-#X(a)Yqmt64VA_zq
zHJG8MqbyA*L-$K8XuzI^aOHBnXawvO6Z)?&i46s)oHl(@0e0EKsNtEEn){cT7y@N=
zn2|3ES~WQ3!09kWLn*#H?A7Qpm#d`HC18g_{?~wg`4lM!H1YQmUB)mfMuk$|^trM{
zsgd71lt`z;z`wrfYL%R(8CwE})E-b7;iAiN+)*ejx=C{Ax^ChOUDr*Fq3XJ!mEVj^
zXjE6b6!687uy>6Oim!L^t<C$nBr=Bb>r%@T%CF1L2EIPJbSjE;KbM5PVx}%r+VGB}
zX|yAep~{HTWbTM)=RH?YWeuA{9g3sLjK;b7Qpgy}tR49(CbU@#@h&NXd4KNRM!tfk
z%>nre0}04Gy#vwcckbyth(^D2hr=Nn4f2kf;Yq2fLfxxqs-n}8P&Slpyrab~IK?S}
z(52*CLhkX~F6*kvw1yidDfRvrG@6nObtH@o<s`q9n+5k$$O=x*w!jK5PNgXC$W0l{
zOVm+`JesoA^z}OZH5un{aYch}MZVb(T%{wQY&0p($|w6I2|EDrsF(8Y7U%|1b~ZQz
z(0R?ICg28)rY{(t!e~qa-Qi4(X5w60uPJd_hetA)8NDOtY$zX6N6OJqt41ipx>A&0
z0{Oz**=RB&(P=b&oK^ITFE1duDs}Zro*GT|F-m|%lZA|wt4YCgpeS3@Mv6qOky)2|
z7E$*jiy4VsFNLC)mh>Zwxypz=Ny7HCOHH~mHT6n1dkGjH+~t1Q;XchzXn?y3*|zng
zE0!y{Q{UBvT+5ts<wNKdt$9V0iHwr%ms0yf-6Qys@r#>=OQEa=>HI;nB$EZa4U%m>
zbYz2KmXf&?ii&cTezw?_W_0C`>VQ=EkrkbZWnTmt(Fja?{LqTt6H~v$ebxY%m`@B)
zA3E~E`gvQ)ND1o)UvlMobtR$d$o1;V;@^?$^->_qE^mV$eeAeIyA=LpWs8z*EI4_n
z_r}}~ZL8Z~O_|x-A-wEtBxJpmg?3G(+|!wk^+^iZIEEwByXw)uC^Ef~@!FOAs_)?1
zmxsD?rMij>^h&0k6i&jydV(cg7qGWUe+uqsFR3;NT;uwYml_wn9`aJ7u$#x*OP#q;
zF9Dp93)KT!7lrRVWRiR7H4mEPjyo_{cCMb;PhSLisl85j9x}<jPIn&qdU1RHc*vU0
z9Hh66ZxcC4T^YSDrQ~B~wvLRWUbnV6Sx7nRL4&*UuDc2#bYvHOQP3*c<c@aK*1RNg
zE>-6tJKSfsI8SAZI?E+=)S<fsI&hIR)U$-bZ4rb^ws}DGkPYs29J~~=!BwA!EN&$C
z^pMr<3j-=a_Um6Vrja54QjmGLBi-gD@sS&XPCar%*ojsOD)+PR0ux*kWp~IflN&iP
zU0KsQfTXT64Lvhn-nQn<u?7ZO_5P*AQKi5cl#{8?vV)0lxn5rswDMC5S=4?YDJ|+u
zuIM3C8KKu+`Q#puN)Xw~$a&}?pEOb$dLWHVuk?h@gm6z%>fOmH4Wx>PPSJp?xQat`
z;8mQc|NEel!<AaDBl(>>jc%l<bC>fv3-r0;+mEVb;7k>A2`QY*QU(yk9hUOzrMSyW
z9Z+kPU-SVfmzK*a#>;n?ml_Mi-T6=?!+@9iNzy?lP65=K%S#=l)?B7_RrE{BLOX4V
zOW@R22R;*8&t*slbec;u0&(J5MB)MEK1JSVY#FWyoQ{3vQc4idf8&b|ueE+jhQDLd
z<a!P$Fqh{!pu$vkq8BQ~xpiGiU<J@d2I$0Hc5<RlTxBRaU?(nU)YEI@zZ5*=Ko*(1
zaUcs@DTl1xIM^Fp_U?i9a`}-Dw3o||e4xFYHgRf4e`BCJ6zGeDRxKO3k%3OR6!Ps@
zHL{XV$D)^&41|gcN!5W!@vMo_fkyEyqxe*d(+)t2Z&}2!Gh9Hbo|cGjnZqb_cqtuM
z7BF94r2GMN+Lr#Tx`!_CR0l}Kw+!F{sXR#{Bg6}A`H&A3+pgA2sck7>U|GDf)jvha
zwW%r{9cUKcav%fE;;P%x3)14S%yM+)`gFmvdSyI)QDjA*1zBYip9NVrlXdsAv&n}*
zyKPy-FsOagAch(4TlQ~S=}%JdmBW&E6#(f6+HA|$j8w3$k|39o_Sz+ZS86kr2<gDQ
zI51cp#}MCgHJ|!x$E6MqGrnm;<E-PtWOX1?e9Hh%M2ZVg)tNHaw|#V~#Z?xuwbD$R
z#;)Pi=)z1HPL{q^Ho~gRqi;qwUP7Q(Jr-JN)75+_HET4PA44TbSM1@X+{ZStE+HJr
zjSMI4+va1TyEg1&!ztfYiNxB-*24Ips}>Di0|3R>!Om_d5_u^UtY-ZNE>Scnt3^xq
zQc~EZ;$GIEtX7D9DXSIYjx*Q_4xlVHXUUT%NfkEb;yy7-ezDe8wrY<sAXhF0PsQcj
zrEpAjkW18+!K>sdh;k_<*p{dpl5I^CRGx5Emr{c5Y`qlTS`rcGGX)u6N}Yb!5?g4z
zwZs-0PrxcG2#c>Ju8!01s=?yGwx(D^Bd#gdP>E}bbE?E8^Von*d6BYpApOuo4;IeQ
zL!lxUO<zmT=aUo)j}zUZ!`a|L^^ABl_*Y%9D+3b67mM^+B2j$N&@~`YT-9H!Ln$u$
zn=hqCW890aLn{i5WrbMr)x{f1alu4309G!6%sb9ZtBX5S<?7;Y7$ZObODPGPdckMs
z3dFL4nD}ZE5V}r<WiBNJnuiiX(@pu94Vf7okSyyn|4k-PcJoL!D7$&Y7t6wDh%v(y
zgN%{PO%Sb1$vK|^zEE}LOn*SSBb*`LIKxdBBd9|`wyfirhCD`3kxCkx!Bz+rpZlX%
zuDrP=AC%kNkdKONZi$ncOm%P!*IPc9_&}G<B}S1gq-(d1gV|i*5|~|m;vL#<!oO@t
zeeJ5G^IQ^wK*<-Uw>dSOdVwy$l>xEhs-|OwS$UF#ueR<fF9E$!w$vxR&W2F%ODO@X
zj_GZ~|9vSnyR@kd^)h_YrZ(KO`ZV!|4y;SJ2c(q*@-8jw)5sg1%Sl7ra4GDwTE-!E
zF)rWc?BWa8<?MVY^rp~P1`LZ&`I-&2p?x+zXQZ%AQwK#ko5Y8rB-rXnQi<Ed3yN|!
zw63%&7-T49?c<2=goUdjLI#kF3zB63xm*giAv~5`aqb(n-ve{tBg7YKbcFaWME%nG
zwt_8OLRLL2O0I+vVq2fjrI7WmA+k}!(<g76!-IF)%(KA<LX{5J195f~ddmRp@UeL+
zH=sX!Y(2Gv-x>|PpJQthp-h1u$oB_rDwLN2=yECKp4wD}k_<SPO95+uK`({OPqxSy
z3RgHWL){=Bw5xB@xe{(x$*N0O*@PGano)(6E+yCFfMtCNxf+GudJI68ORArgS{(FF
z8&E8lf*Amc<x<F+dT~gTqso#C&t=0fm9WPLPK?9EDo>0<wWBYgh9s?x$KA+tY(2<M
z?nCxBkZ4{*xyy9Cl;CI*1WItwIejU$qF{UvocDyhvVlrRmt_1+pbxet;Pu>&WP=j4
zBi^M0O%*;2b%0%PtV_wS+YVXbNN6(B$LmCBGSCOyuWqu?v4mZ4EW_90Cd(S&78jQ4
zQqsZf<{#Y_x=}o+MRQFK)S}S@ACV2}3+x4+U@F62;VM04*ibHoT%i<AHaf7SZnDt<
zlX2VR3N5J$RtAuaXZi~RK*nupmrsPuC6F)9j3#{zJd6vaWx&HYYhFD`sv#}>;O;ag
z)eH!)s|1z-=6fl8D*UdO1nE)K_(ehMK2#<-ATmyTmH{E-rr-zzM#fc0%b-YIA^BFi
z)=f4#)bWdgR&CG1co|f>v-Flh>t6ykt2r<}S?RMjl;@JjC>5%3Uxp;TZZgSX%Qy>m
zSwUdj1f{-|l2+C>Od?keF9R~ht?9u~mqsYH&6O?64|Qp>*a4MsA-@c88Mh|RJb9Xo
z_yWv$mkkeN@=`D)D9nDuycFhzkkt@h`modT2Fk^S`!axBE``5HmLVD7tA6L*unA2k
zOqanb_wITw6kT^bH`QEMVW>-BIuA}jnG-J5m*r4pr=wo7qf~?O+;Rz=)pD&8=4FXW
z@eX?$Auld;mI0;Woz7}orNKJA)t8V<q|187iOz+;vO4r#0<dz1gW)AX5}fNgUDk$J
zA6MBiLom>#04rx1FXV!08GtL^X<q}katVBH9R*dJ%nG*hBnhAYf)eYpj1gDmovr(b
z{_*>oxh|K@f(BFZvP&u1x~3NztkZa2rND@&dXiGp+wu4O`c&=A-~+i7P66~;mo2^a
zlTC7ki&K~^1CHfIL90^4$ZReQi?{P09gcuadKDlRR}D2QpOH5i&8VB~@PIr;TGb0b
zs9ZEMoZ**pg0E~vHt;d8fNpLfu26tYMl-N3mx8?!L5MF3S~)shIvJ2J-e@!f_~OmQ
z8OpD@7()S;FRDhD3b4txCiq2}y^P?OMxV9qmaXEu8@vUo|7NJ5?1FDu6;SpjlNkk=
zy~$|awOc>lXf?y3>P=>Hx?EjYErV0`QpgB8uq^^74BlN=T{%P4?4^KHslX;%n{XIF
zx@=Pkwkh7Gq(tOx7?Uh=6ol|b6}_nhg#<HVSDMr-uq&!hXT+{F`{-0_(x4(X^jR}W
zQ;)#jK(I@b*-WfU>teI`Cgtl!sJ1uwx)I6kO}6%iIwPvf5D$I{H2-$#vnF3RYMEaO
z`;_$B0C4rPRi5Xux}Vv?U>VRWm%?79)h-3XlnUF*6lNQhR4<9+4&;fFsf>ET`^cBQ
z>+j@KyTd*~or7DheL^!{o6J5kw^1B;3zubufw=?(xEKH~msBGFzU30|;Dool+WGG~
zyzL{S*kKuMru{TzSlGf?8FDbZC}^b+@?9f`!>+5T93JZLUJ@n*1$eg*R+mze%1}<I
z%WYFr0PFH1;m=vy;mCE3JK9UZo4_sZKKeAhf{ON$E$z(nHPNbfCqvn1w(1M?3AxK{
z{S;{>fnrZcDT^2v-!BSUC8fSt2Q+jaTEuyEo^6U<N^&0=!~n4DBeylG(e7is{<W$;
zn<VThzF#dF$UwSW3K(xJMER^85q_6M)*A~zKI;OzY=OKC5Q9r0V?@aABb(S=8P>2J
zcw~!RN}cVH_3Nebb{zWmQ5|)M%-^bqnv{k1l`YPjNiEQz6Z<j1TP}&b>yJC+#I7Qw
zNx@uQ20LU(I}YVLU`eA2=ni6}En2oPNvPhrL#8%raqhx<<p6<Nxg>V$5KZ57f>d_M
zeI2y}Ukal8E-BYwz;uq<$#0vo)o#Cu&az6ea@%BMWk&9hM;i#DOCj&dz81txUqVec
zZ15Nu&>|Y`l4?YBYRAA_FYz8ZM7gwqfY~v%!vg`c1>`coTehlFS^->=f-NFew%7wf
z4wr;25h$`tfpF_D)rX=j%(m=p%*GBy02`)khy2-?*BvJ2yCz)zY(VFBy@`B{<<Qt6
z)eJ1n4z_B1GTg(nMW(n$+^S?|0M2Y-xmYlChb-=hl1v77lrnp^P+6C>(Chu25>3wQ
zfM$#|!{hZgd?U~IDrI`-(dD`hs71lCSO9gqY;b(|8&!kxpiIFi?=?1%7v;9F!EBce
z4rI+Htjh>1-7Z5sp*7oOg#$VBqGYQ>b{&ziIc|4uRkg`xX2_Z!?8BD=L9tJ7LADHN
z+g<3v93G%D+i625Qf9k6(?H5>muDJ4ne8&N4{i{*uw4fH%yyaCg`e3jD;xNk?KHBH
z<7K;YeXzprC6PPoE(s!b>++U_(#r=rvH)ODR`*TbvW5>-pvylEbK+7U4K$$3JU;N%
zT~hsI=f5cj^q<Q)4J^!dIj4a@->x_b13qTEZ0xfkzHDsNs@o2CH7u|VJ12+eHAETR
z$1y~G-3KbrWibP(zlr&>Q=ZN3a!?;AIG2MOIa{{FVn)iAEl8IEB6BIQNnt5p3WYgH
z8Y%}hq8=`#c;8CYw^e*cL;9XApw}hkbZ!{gS>L+VGm6hB%*@`jx(6^bdk1kf1F)Gb
zu-CvzWN%kD=s1D3SdY86qf3HOK`KdV5V4G`7m0?_CGF}6OX*TFyZY&L#Sfgpl2*T|
zMU;dA32LP!sYCEuj!D9)v&xUZC`|&?k}eXay7XO=irwVsgo+=9qDd0j)p4*$nD9*5
zfAEwA31u-o183%>8GnUNdIkiH_iHOPn53u+F&1@C8W+ii*sz-}A!QDpm<A9wNh(b^
z0I^9DMJQGHBE6SD>BA&(+Ps>uj0T(+N#h!IEC9me2izh_AvdoDP}$QSkZJ+Q6dNr#
zxUGd67~U4Y;P5tWqD#a0Hf0EoWodY)nq1z8Ls>i$4mhWhMs|n8Tbkg*@hx&Y7@p$R
z2JkqScAEg>yqY|L4IpxogwX<$lO){Rj|Al;1?+*!Ns{s5!EU7-2SPPpr15@Ir`)`v
z7!~xHl+twrfuTv_vy8HjoTYA*(j>V31(hsHMO^}fH1RU7aN~`_fZH``<Tkhn49!{q
zUGp}$0BU=Al7#o)CBVSQy7*7dcSjSW;J)z;0BMp&aTfUVq&46V?@ieF0dP%{>W*Xd
zT}@8w#%gmOq%Nrzn;$)T=QMh}CEA!rnp>Ar(<pOm!0DeP4%RUe7ba*_z<81<f@2eK
z=hGca$z4y6YS!ONfxZZvJpv2HiT@dZ&?ISrP*X3c{HP#(Jc;5QPUF^$97?F~xF3qh
zbJVc*R2u?V<80SC>Jl*5G^+-#o00_nbti>KVdtt_s~3f*se#+CBrOnXCHd6DuTp!G
zV*CwW(U8zaA&2BPiaGFTq*zJ{zJH^7B@TZW)T?m#!>C;a#UF<Fwxm%6Dp;9f!>C}L
zN3CI{U)?0ZC^eomh%mS+O)^mBDx3c>DqZgqVWth0By1)?+$0H4pM2$APhVVPO;1NG
zQ_`?mSgBqC^e+J)RMT*%dcBb!@@giD45@h&wm%GdSFrtI)Vup=B&D^Uq)`AW-hCth
z6|d|(^J-xeGOFEOx)Z3JS3AU=YWQvB8TIfEF-HRKR-pcR7?tOC^$g0WUBJ-9erD93
z+vz|XM(w#BO-QsQBsJ&e?qSfJdozY<7&YhSk!%cVPeJ#`p!VGKwT?mUxpzKjl;#w6
ze^maTA{F~V&AEvd8lzW}tl{KM8W~Z!3cWu7xOtJLB&3?$ytcTcT<d#&^sD8#hoq#Q
zBuIY@s>ChDjeJi@!k#k*r5fTlINw7Ip%(@39|MVdlLm&9^DTuws67GkzXS}=B*Cm*
zZ<_>|*aJ3?0)r}6DE|QrPLe1kj-oG`KJT%siH&1Wqwb~$ZHfdVf0RDmZxeq|pKjUs
zg9>%)TOU-Y>xerQYTeO2pyeK*pny@Jo+2#}>f>5RvqYt<$bd1Zbrl*gvYM3Q0tR3^
zNm?M(t6fStGX_=hl9@ja#g>^r4y2ZqKMtjKozDh!@sg!KsEZfTNMleJGa_KjR;^wh
z|1qhG7m*2LQW-B<{*%gh$?`|0y(H0solwRK9vFc8Bnbj^tldRl?3mQpOZk$=q|#O(
z!AR84N3pU2luwe#4_%ViGbVNTlEE;k!`DKyM5d$lQXsNS`YGMKw0%tK<|U(kQa5Ml
zz?h|%6*({_&%H}Qdt*{DuOR`bn3uMbNyV&yf-!LzUW%O^lc(VfDHs6%yqYEnCPu51
z0jld1iEDy7c*&@r)WM7h7!wLsVE-|xU{`;O#FOpfPq0Mg4471|tMSQRE$nO)8Z2p?
z4=Pw?t{;;McIj*|o#W8qU^*=a1`dqLQ|&xriBs)7V#rhN)RAH0`ZQ_St0q<Kl%+qZ
zW+!h>#)MLxA+Zkkc;WxYqEekS{ugzs3b0)g<iY`9HA%&+kC(RD4}vZ#)=BT|C|+Ca
zJEvWt1Y=RLB646X9$BXj4hu(C#S)A{58+8<#xtt|3dW*doig|rkDm$%7z@z*7flvF
zK8hq!QYu@835-Q$J8>?^RLXb~g&+7DCJzRSs&-C^Kvg@3B$%bal133`e*ROZ2f&V!
z#Ajo~Iy@BW2oHh;)W}oEhlNA0f)2*w33uwGuyALcG;A%{Op`>8n*-!oVU<>%Is>fD
z^MoP^#-di9T@R;Lo?Q>8R%XD#NJWH4aWquQQ?|sSTAn&7EUINiA&i0>Jw>Ascn}2$
zD1gbc0}w|^!9D@V(Q|2N*Gf?+!YI^HQph|oT7@EvMP)vYTwe>?T)_xqQJX6wVJs^1
zk&oV2M-Lqem^VIY*i|-lw4x2hrjAy)!PwN%gH2BZaL9?gsh@`q7n=%tXqVYk(8DD_
z=ZaT&!q}yt6`e4UVE>ZPtkpMk;@D``wbIzo#$%%e;dDgU^g=VB;8Iq#DTPkILnnew
zEjx4~*wnIP>fzL~WAfoV{VMigY%19?H5aS`I%FMeDB7X3#n$PUAqZpB6Fr8WUgzN<
z&A+LO6@@VNrcgW&Y---2uYXhVBE(>9uLg(DBkSk{(p?(l(Wk$?<k4YZQ>Tv3=W=Sh
ztaw~oB#pzTmK{1oY-rh`&wle<dyj?>C|EL0!^aQ!V4idpd@wdosCFchQ=2l9V3ao@
z3FzlkrV1w*a7-kL#|o!9HM#wr>eOKVJNjT7sw@UYf@xalq#}_&)vMwXhEu_sP6G}F
zYwyE=(<!XTgyB5!G7w=n&$}kKzn5Fs-d=y_dDo=$oqAaz3ByM<$!l<QZ<oJQCo?4B
zQZN*$e8*weWaB#(unBQBoGRGl^>?aZ1t$#WdDrOm_fo*NWQ{sCuzrA%$?5Mr5SyI-
zPW@|dr@uo1n~n%hud~7!hV$H<K??&n&#&enOklvbnluiLhhzmR3@?SOIECRnCEMHh
zcPiwJRTxgqYclm6$6<vgTndCXhOrH&>NOKPs$Rt_ToM+1Jt!Zd(}D*z7NZr0Q|+3r
z0GwxL(;Wa(&m@V=gBFohn@Uy@48wWKHL3Jy)x=g4JmvPI-7cs?8GbMV$JZ`h9aN89
zCVo&omKXg2tzKj2&A<qrUm2}%DK)WO7Xv~4c;glLq+mDfcY!AP^Fp`tSP*nLBVOUY
z#o$r2%b<@^lwBWo@HpCaGZ561dDD>(qE76x=aDxmNu1wFq4aIXM-6Z8oB^%abrTRg
zej=)21pUTcHvz#*+`e?t9aNoNCxa-}*>x-kUe9(I{6QCSpVA9~V=O}(M({k^Ww?h^
zCK&F(uO)#SUQl^5nBh`ZwJ9NWr=l4~P<z(x8=nNZrOkudv&)nZXwNQ7K6pm$M#ojq
zcdXEe5!A6=ZvUW??b7>!UvLi&o?;pNFoM3~E<-+WuI+dPhXEV@`8E!8uA&_-1wzYa
zKh(LMHv6H*?JA)(4pnZ3L5y=dC<bC2D%>W6{ZQd53Stxt^eGy-Q{yTUVjO7PCWHM@
z;kJ5onN=^#TCou0PyshN{0}v7lWl)W11lh66yE768u=TBs+fpzs9u}w_QNBu!XC!q
z3Af2cKUA=aa~OyEwK<v)Tvqzg@s_a;<CJo3TfC@So2~^8^{e6`E(yDN)4jl<f^8ek
zTqBBy7>Bx*@el*qEt3MQ)~FPiNg{t9ZJQ1PhYGjpAaJNSn{t4R!=tQ%9L9n6R7k@(
z)SgXu1Bc494IXI@m1mQYf2ceg_7gsZtaxYzz$U*O>d&UDf(yyN1l<%IYR|@l0g(Mk
zp=vlhxHg;&4mE1iO~JvbRWTIf@QB*p=Y>OuvjQh(;~})s%%6>iPz62A21VN%H@(@Y
zX&bK#W}~J>Y{aa<ifoshmonH3s^QWWyVb@tk$Lx=BMC~+o^vF5wE)1KtxTPB4tSR}
zbj}g)QpAT578AItbB_2{>XxIJi-|XSPT;Zi(vJcvCXi6)xFnkpMF#&Rl{B>XXD!~O
z@Ie#eIOR+2dl)|PB;`)}Ia~78XK^WkVJ=8a>wf}3bt%dGNzzIJd6$AejJ%kDPo1+h
zHw)w3+1lmSJBq!Sg`7HPiSNc+Tzu$;`24&lLbYC$2hID0sY!B(H6^G+E?VuEQgThk
zYE0msPDWMCf;=4sRZJkB&KZ)l_V;s!I3qjMIkf60RK-!W#cU^A9LvFLA86GZ7Yus>
z`gBR;d+^F>;ZKx*J&LuM(6guV+C3nZxG>gduLi_IeB(LH5i*fg{zXA6_st`O-vpHD
zQuxGLd-Up0;FyjgC?;S`mjd|FCDqz%;%r!ZH0>uWqNBiyOUZQ-1p7>ciXH`4%s#S3
z)-~xzD8Wlf@gme?mbrg`?3-y-9>qIMgw&pJ2~zs+gmV_kHa+qFl3~A|a6GmASSMVf
zls-EOnz)pWKF9}pNq2r@i}%6+XzouK@CQ*76LH2zQ4^PPcdOW9v@xWuL2e9*cK+;+
z`CsbgSnG;-nEgIvN|Jyi^vzG4c1}#l7CE;v(<ef_4>5HU)jv+mHxEqikZ1>UJD3o8
zR;7^>L!8U-J2AldU^sNiPe7awV<u(+oSvkBx3yP`M*YMw^inWl;G2#Rc@wAC6Glkl
zMDdjqT@UIdEf3b0P||iir$gTQ|EEYLFx~JIC-Y0GAy_piJ#<}kwDS8q(Zm+2PC*nC
zK7^wvidi716HQFZE_qHgaxK&42)#D}a5@=7F@bG5e#H2`mE($Jo=7xwN#tAm@THLP
ztQMvo+EWn}vph7<C82o*_s|oe6@}KD05csAJr!D!o{l1w^nuoWsB0w9i0+y~s6-+8
zCSgsNM9!rzj{+@b`O}W#EGBSGFA7@uVti|Rw_O8-={_yBqHp}W#G<i1;b=Szi<nlC
zotHonpzwsuo4_a?r&T=xQ93^LVC42cKKbPOJ4X+F=Tn1+&J%9$QdYKU>><C*Vc5ik
z7x*}>?O9oB4j_AT+y@$ejZ4lWfZZI>ZHRTa?VLS&&L^_@9M$)p@TwnIs?1q6*e->S
zHOyJZW1+Sb3^7sL?NSiRcS*IjWlWEk-V&m2;+o(f6k_5Y;kXRsQRk4OvfvXbk&cja
z6Ls^B3Vl!H^Et%3P2hx{qrirV%ax<ZhKVbfvl&i2k=5x^I1Qz`o+HfLtec!m!1s&W
zp0k78OZ}W3Vh&xl6<as~E;?IwbE1omP;(Qgp-aJY%M!kXdhRm|GIUfdd;&3a1d^M$
zDLZ>>1P*~^|5ho-CrRK1ou?Y%mr??6v@Ty+zo-^@Dct)8RNh`<43)Q+7(?Z;O!zD`
z(IGhQNlJ}~f6sNer#M63?Wu{Y{rGGd(z89;1Xo<89)as707EYdTDdN_Z06Z879n9K
zZhw!ejZa(=AHnKoT_c|@lNndd2PHP1BGrfneo(SY^G>wtEdU{ODda)@w@qB2|2F;K
zmr^6*LvjgAPXj}A5>{8EgYMg1oT2-67iZ|dEz=vx2``0e1_=z0z<3j7WseGuUrI@*
zufBjkmw?QX6TqLdWH(P}xdngtC8RtmGd?qy;}KSFGTq}@N1UM6){%TT>8%haXtfpO
zR7!2BK;orLbmA{Ix{!CNwH4xA2J&G6@;Q;8=PV}jnE?A7)fu0K^*O@2O+bCl+8>?L
zwmJ)@a|$M#81SF7WD_IF=%w(Xskqjn7iOYx^d;eun6{<yLA9xn_(X~7BQV=DtBmzo
zbb3!<ea?a<4WQ3arSX}sm}WEpJg=e2A}#>W5gu(K`_EZ2iI+hTn#8Nr9l<$8sacd&
zyrA(^MtlN=c7#ToK&qXkyqI&1Y?3ohYRkyEwt}<h;GTf~990&dERlYMXPZ?<{Vdth
z0QH<j6B!eBRC|2plpcx&rMYAzBkk~6GLqNI7N-#kbIC%k)W%Pez!VBo7`C}^)>{p&
zEB2IujKcM2zD;B-%rj*oFKA1ZBEOUzoX~7Dm-cN_O<?(R3UTh6A<odIGc;VNQ&lFP
z0Q(%F;U<7Rm%;&h4XGLd*`>7cd7py3Js_<lP;{uuDU%r4xnC5tN>Y9E1=M+xR9i*C
zbk3wZdjh3%=9cKtlyi$QH04yumrKe;Af(&eucP6Vb-ke}C#`F2+Gi5reknO;bYo8d
zsE<mJPoS)ikaBZF>8Zr{+_=0sLbuIr*`i?3d~--R_&6txX(+`rl}2wua~@#WW+8UY
z9B(FAkwdaU^-X%Np9u*3nI_%?^G(wnX221kZEk433Cnz=2<s(~`OFp>!%M1q<d;$d
zlEWG)|Ibvs>I5w32#z)rm2+nM=u~e+zG`Fxx|D@>9p$D>aRfpf6&#<4mN-+UI6^AU
zkfXW+FP<ckdnvwg#2kLm0bezWES#b5eM2=4LfR*=K4-|FPpHosGUs7PAJr|Nfb|?g
z(_Xs-5IaX@$tMsyM}V@q55$qPdP8HvxXuSbWeytWJ2mETi3f$Ly5tjq+DB-zxlxMl
zlE56toJ#@o!u?zVCI_&eODWa>{hYC-&Vczj2~3-S`<x+j-FvpkwBt3>3NIMXlN9Vx
z2(fxmvQ-Ln$ihZ6*HOvxiGZ&&ru?H01v;jl3I#gS?)I1N9J09q(>X(aYDXEmqk`p^
zRHDn~#!328u>I6w`x3|%W$0d{Y)-sz6KiPKAx)1n{TZ^v6RvZH@e=M5Had}U{-FMa
zvFOu=d*Tc_vD1O^BthNroyd`mK*l3b+5{r!4EeGhW$rHtPflGq<jV#e=TbOlP?suB
zK9NM|jQ2$qAUbErmt6>*V=~F%2s%cS9L}PHNUi(jRBY%`!Sac`9miy*16FfP-fV}4
z1YT`=Z4Afc&W1njnB3X$xgAy)pGa<UOy)H+pd5ocJ6ir3a=`I-DcAy0_Ucl=_j(jx
zZKVjggc4pBdf=pJFvsD^JSI<eIXaKYlU=^hCrM-kl_@ydM3D0_+28?<NKDzRj6lbx
zJUvJWbV-;5xP=c2jL&i$A7RBNe9OmZg)<2Jn7r9Y>T^uqY*b%6HZ%`2TVxAIrzxU*
z0+w@0V1$FA$#Y$hoMST6fyg;5TmD*Mz~mf3$tIEl9hD`Yv9pEmJ)rAM_H}G*HAcMn
zC6#pYQwI)tMk72*)u}A`#0AHTQUiphGg;xdCAk!GhNd%F;(6C{+f+UP<{XwTpMd2Y
z0m>#oIWJ1KaE$CS!~<T^e#93(QI$KNm2K+?UN(`C>r%+3bmj9Rp?N#VphhLf(`8Vj
z*yHJPO#^px`r9>)>=-W+T6aBm`KE!vIYg9AAaE`L`$Zveo+N=Y063Qd&ZoLyD7Y>>
zS?GM?I`MR+rJqQ`b~=slN<WeWvc*ADh0QM|h2OgRI?$9|M)rZG>@>2^$OgrP9_+H7
z5A|S|{~GtSr^|nhG<lc8r`GF~2OHR$(*-1%z}B2DBOLIW)2Fyk3_zwilK!1alJFFz
zCR=Xpv$9o^)UlAI$tMcL9s$T^L1CUGEfA^)Swe@Y@c0BS<_Huv0TZ|sUS9%Ca7hd8
zfleGRR9NpCFLW5|jz3At0m$M$IQDhe(+AGdE^|5&6o(M8d7!{hPkbU1<`J-K0>N@A
z>XLKXX!5RBn)p(%y{`h6B&nuy0ex}=;#!GMIgJkN1qjP&1beTB16!j9djSk{nu|HK
zm@0~|!n+(nyjJ6xuE9!P#IZEjgKul=p-^eUa;?G!oyKZTt7>K^g^z#&OFY)9lG~>(
zJpt;gEy+dw)t2T2`l~I?3iKDNiLW-Z(J`%1Uo98>BEqFjv4t{gQ*5El+7#E)W-K@U
zBqcwEM%VNrpruW;>TM43$-`b7;<7mD{PxysVon=+Ae3Dj8Ve3~ZJ<?x3%aoYn>z$*
zt-{rvW^Wddn||p<YzvS`IXEc0X5tKGhlix1Yy6}a@h`2Dt=B@ol&wCs9J&}o*|n|_
zm(Nty$`{uDa|HWZNc((R6L*~YRFC{pN?IO?SAM>yzQYHED{`Fk@tFI4TuKe1mv#%)
zA78aA1hHCAQm%k;=%-!)y~LrPdLb!y9QvsjkgIXvr+!xN*}_}_852NrE$n)6=%ik`
zFUARREraO^)*oL$=Ek8By?|B;)fZoVRI6qUXq7md+wdigoRbYfYN^KAVw|cZguhxq
zxWu9P`x;y+pi3gFSrfS=+r&IBFq)Xfr4i5iT!JvIOR4cJ@xITb%X$Ie5-2sk0B?!X
zi#5KDi5(JT=fv{dx&T#)LnrkDR3*;fF8s1Y;tUDlm`0Nzj#)H~-ys?;-__xVjALT$
zHMJ(rj;S@yKwx4`%xgtN6&HU%sxi`vUWtN<)5W_KRh-V}9;_YO$ImK&OPr3s*NSeE
z^*}T_p%;QAf~Cfn;e;AOT`d%Pcu~-LaR{2ex1CcTG<`26r#=pkBA1l13v{($)JM=9
zUS;-29PzD_!Ha@cJ}n}|y5=TSW_;lc5&~{5s}{M|e)^(3XqN1*M;c`32U>@x2$z@x
zQmMS@LikQ(f$`fasq_H@q!O|D(3uU2Si0|t*pjpKRm2wC3CXvnr}SS4p0x_g5>?0e
z0VQ8}EOIUr_Y%mx6yl|jd40`+bg@s77P?_au?-2Qx@|~EV|Nww<Pu=%EgbA4hUUg0
z(4d44d8BXQK?s1fZhJl1Bp=6X9ForQ8i(e_u>wt;qx^fpV&a!lW1``FDHFZ;i<)y2
z@2D{<3*)8K7)`tn#>n&XLK&opE{PB1Q?~e3(3J=}o)?NRMbPnlDfM2;P+rKP6RIcv
zEF{qh;;`1J-(xF6jAl4}&I{$E!jJg&oNzy4TSv7(G4X|n(GUu2p(<7QAy+6mKkxD7
z1{p2`9H^L33GxMxVF;eJ;F%267=MbCFGb+0RWY{V{?Y587X_S<$EhDiX*-uK4d-j9
z$oPVTHeB}fm=JJ_Hwuqm61lHzk#iZnmx8IO?<`b_d;vN0qSOGP5?w}kp=QEmg98#1
zPPGd_OgK&KXCb>zxQuG}&ckI?56>0_hmsU1YYk*wz9j5Shzh?H>`Vw9e^Jm%S!H4a
zFca_M<!eAi3b(a@m<gvR`aga956@l7?bY?Qy4}``{L)^{V~#$*{l|a*?Z18N-`eZH
z`rrTZw+C><Kzg>neS;|zD&X63=#0q&d57CD21}7w)|=Ou8>^zbeRC#H@0D58H6fOf
z6<KSz+9)mLQ~Rl*V4TZ4oi&D9)geN*-d%IyO(m<GIj0YC95>nUT{GK1l3gNk;yaff
zV{=?tRR&|E*E>NNZm2)=Q8?o{OtDYFu-5)Y(Km*aD3jByszrwyZ)Uvsh0zf~Blrd{
zHBHxqyzy}Q4C(&<@a*uw08d?e@1p~D1;71TH*>xA<M~=Ia~$jY^$&0T?Edw#DckU4
z*{Fp3$Fc!M%SM&tCy?>M5>8l2xsd9WawYwGA?1t1LSmKc=e>}W`&#ShT}q7W=v{w<
z>xku>98k<H6Ysr@6z2I}M@o?JxsI4cO_^&{4f<mpDeCaOj(E)ZSVy`$u66We2o0h6
zSVls)aoy-LU+YE)E`Vi^DMI(XaCGX>!f9_ikL#wysdaPOT{y4h()ZnHUjJCL_t(Ds
zyVecx(V?7<fKZ13r$AW;@TO5e#=$3Wz+@gr<h2iFaYXvmP!30ASPf-xjDnzrps3NY
z`O*;|RLu0l2X!v(j=+i38~5uN*}?;GAXUmnq^k`kY=k8jO153L-V@5s2y-x$n-L~s
zC^2Ky_8dyf2rDx-@3b>`AcRmwbis>IjkHgckTF&^zzo`Uvxp6h<4dSDjhKko+*A-X
zaS65RGOQw$fiZA6kL~YAlnD2XfYi&eX*JZRAI!6O+qsf}2zZi`OG!Bv>x2?Yu!z8u
zNI)s#QbLGQl<Ihb$rVw_Ba~V(ccD;fMdZGY#EBv|c5Lnifgp%WDfX|!VJLATHkMG@
z#ER-kLUKpkPiz&RIXFfN?TPH*A+#sT6oe8e;@lfbpO`1(D-><~gA*iEC!UT;q@xX|
z>k$4E$M2}LiFYxaYJnxrk4%_|P^%EGv+CZ&E{FITST}-~z(En4elhqkLa7rGM;1z)
zh)}aY+Qc*OTcmxDIJFSg6QOLed994{K%r!bs2~*YREej~jY^bwaB4)F#Dg=VfS(6P
zM!`PI|ML{3;U_E2Eb#ob0)^k{MYxSJeA6l`j~!|k1R<iQPLeVg;2ev^FZAFTxzH&2
zR3+}<2uX10jhxID-Wm>&i=Q*XFE0TM0X4rAj5#1Q4YsU-^=eZ!A*eGJY#`LoinR%+
zLY=KxJolfPfLOfBhI=v=^)g~qWAU>+c#8oj>B|Z$F?g5NQA;cqKi*3zNpP2S2_?v+
zPw|pUl!?dI?@O!>-)}5g&2SILn&M0IXALoidRn~1?&XUP;ZHj%9b8KBg?d_pA7n2x
z{8Gr<Fv20;I7teB+TpMdRH}T6R9^<wX|M8hvAV>AVp?7DK{Krm`4EkA37j0LCW1+O
z7S9VoNjvT^US}Ce2Pf%LNc791$|l+3&?rD@N1%HUJ=z<z)@tHY7?_wxeCld2=Ftet
zdlZwZ_fm50&rmO92nyjpdtE_=z@C?o?_lyCtRoRY%%Fg!v1ZT%&{1U|Fh(e?>EePz
zpa7wll5;y<j5B%4C6I4<4=x3K0|TNi?zr=dM2PkV?KTxO)$5ip<`&;FL}G5Sfp=BL
zc<<19b1}nD$A#r3;X!$&dD{>l^#VeG&r2zBd1d|lozn)=ZhRbDD>X+5;n`8TG=%W%
zoi0>DJUgnQUIMvS3ro2hhNN$;*Zos4DQb~&B?``YDfQ}&d`c|}&3Os+=F9Hw9ghp4
zIeTSN2?07g>Ij4YogKAgLx9d+m+vnPIlJZo`c8n(UU&E*L}$k}e+bdp0R^~}^?*=s
zvPqm&aYAo)q_qj5H+$v2NeaL;{dM#VK{q>q4FTw8N6~>8N0R`j>VO}ucW93gbh8(N
zB81)SC_@|r2g?raH}q}dbQnXS$d`1dTQJQ_$n`V)qgTEFqBJid=YJ@vKt~Rw5KyzD
z-arVb*^y2ugwwo~l2AznE@>r!%%S;+)4YV5-K~j$4>e($-5UJ6!fEzG_=KRE9XO#N
zRI>w06hdltq^F9Z{9l(;qR<6$DJ9F>9RNKhaAr4XvIJ+|R@$lpXkJRq_mFhZV!~&3
zV6Z~?%u6XtTma2(BU@yP<5_|;JF<v{z?mJ1#-d!U4@mjN2%Xuhw0aErEez+eVQAIs
z>v}3?D+tK!Iq_XGLZ1nY*-=*hMM0~iYD5BFQc2bH#1g7WN@zDBF+1>nZ>P-jcl<P!
z0Pl6oJ(^~m&xES%$mt(;-VcJ`Q@*i|l>RRYT30-i&IFb+EcAjAC>VlfUQ&u@A=XfN
z77{p*Y8K)Pjc4^G8}yw?k0PUC5WCrt^)SrEw=^CGbw5CZf-}e8^TRNjw|%s1)dP`{
zF^nhJp85U5HsQ*bP*T#Cy_6D^H&`9XAj6ipK+)C9eu|QkE^&gQGpW#lbDp4_mr{dS
z%&F6{Si@u~kK2-!44+yUtz;mP!=^X`t{eb+c6>2mvXm=JXPET#Fbq+OdX%CwCJnlT
z8j!4F>;Pe~ieGz3n5<pwF=0}`M2QD+oJp$XDjkfhrk8?;mZ;Le$c=g_xZLW<pn6GU
zj>Dk9pqEk$R$6(as>HULa}Ql<u%fX=hslV3?crfvlLkd8DCni+*)FW93(kPVabCiU
zZI`V(aLnsczzAHp6ihv?2?g8i1FEu91CLUaUHTVlHE=<n<HJ2+*FD3id%~`7e?SR#
zn#WN3A<yllTout>GYcIk@McG@<LJD#>PUth3B2sHr~8?jYvSD2rB)}-ZSqlPp8a1m
zH+o>VnTT_Lk+NB*u`Y`i$)%&~b3_K}5D4>9@^kFU&Us0>1bVT3>99UEO6ai8d#Xz*
zvGpyM3Hv08e4)p>v~n4~m%zc`fY(zg!+4H9bP}jk;L&L@&urAcAe6p3SnNS0X0JG}
z=qjnz5epXGBmq>Ez?dDm(?ej)j{NFTd32tltZZ}ixZCSpgU2zhOXp7LIbkuMjw4ZY
zS<6VIADvnj+2${Syh^ckY1s)sO9-FYCsa~9>IJO?h-ROqaM}^)`sAVoy*3>|jM4NN
z;g}i%WcCS6OM|hC#QA}f;{6(tIX@bKSeKF$+8FR~DOVbOYB-xmb37LJ^3ixf(Cd63
z&Gl3$BEd2Hf(~h0ol1#3(R3*Uoza$f1BB9u#Om;4L?aZdFWgsLyy62wO2ey?j)2`D
z;<6*A_Yx=`&QEP>=R&=TOCs-?E%Jq~5$f_%a>ej|=@ROQ(xw=dYH345glcK>1i@hy
zf?jq6LqE}m#snNn8|1Yxf+1E=C5gW5Yv*lSa3w&GG!qjXxteJ_IC3=;*Nr!Xdzhz}
zPw(R%4{pJL3^;H#*~2SUQR`xhgI5T8*;nZm%m#obt?3C+DZH`j<r|IG=uYeiv5%%N
z6Jhuv&}E0uHX85#I^4Q13R<uA<N{oFc!iyS%U*utBvA4?ce(EEI*Ro?mjuRjjd=;+
zyGwPsAefhOr^gAnyo5V?KgtZych4sI)K=z4wsB>qPYS-u^u^ycxd6ZJhp|nUR70YD
zyz8vy$HmD?e0}}fAim2u+O>xKxOf>xB&&HFhD6JGk8EHnH&Qw~u$&#&AGb}$bzpO$
zJ3DW9kL>8WXYnH>SjSb2pGCeCL)4anBp`ld0`FBVOzom<+70%Cbg+MMo8(94ZrwNe
z(N=(hUw#I$kA0Wimqb<@?^PD?-gvLDfN%blY;jgL-zv8T<ZN+aKKu4pOCDj|-T8s}
zi)w0qbpP6SfT`TSH*rn2u~{IujUV2gcI3Zt!Ze>=d30RmZaXe9{V+<Y<DSz6)w~q1
zPJAw|+MQ6%j->Xk>bD(vemvxYLM|W|UbAPmAP;2>=twB!EQs4t#?Ms|w^yk@kAp_e
zt7_VIe|?%lF#zN7i$B*Q30k^&+3l)!+i@H2p?p3aH|DNlw;h-2&U&{m%7C15SyjzN
z$L;A;l$>gozrBQ<X;r`N1w(pK<go%&$(cRxr8s<M6R!(+C}%<2jyzT#@<mmes}~^~
z3-4vg5=X{(7qsD0N;2wept~*sTP6Tt9`*Nqr(H&}Z%n+5WYkFakgi4@byvOG?(ipi
z$VjeKVXktu9TnRz{^7Q2ck__v${oWS??vTUcXC~2jZ#-}+uN@9nR>c1sl8hAOI5bD
zCrKPnKzjM5s_v?XN%nxKvaeCU_3<z?OIE37KM<9kszf!qiq&@D9z8k(yE?Fu9x|?h
zpY)JJ3m8k!yn4Ohm#%WQy}%+*k^m%YSOBuL0T;Ox%o^|_9#ZJYNdLI<>UE$>T~%>A
zkf*N1cpb10SH;^)N%)aqGnbNUR26S8B}H_B-=N@B?zZC%UP^6$uNUmjkcbYnh^x$P
z2VCS*C@nOcOF;)xP&iBBc4T$D1Z)S${OBl#+mRd6T`IfMN4mc?HogpZ>1TXB?hLr-
zfQPus-ge+a+*Poy7r@$8^tK1ooXXyI;Iti8Z#ys~t~`2APZWu(yluyh<0^04k)PgO
zS~)yhWCA>&qx@|LaQ%%cyObJ_baX)Txm;2OE^&YBXaGnYiS#<~Be%`xrfPKE6rn7-
ztL|-&!s<A{P94zz?(#SxMXM9>)GLdt3-Q#E=+#}J6CK%LU7)9q67eq7Q$NsyNWj;#
z(7X%t)C+#{B+2-TT3~WH0f6Glz}JC5aY3beX?=e~r8*!cPBc^p#Ke_?ub)>-;HZ9}
zK!uL#2VfKzKB}LB2Fhc7phAU@>Ih?TX7TH=e0&Rm-C-K}K4@Lp1(NCjtGJL-9cUF-
z{=R;&=esiabpTeJ8T|U0*}(1u$jXa?R<6(Ox-<o1#g)6S1G3`6U-g2lTmqSv(dvX?
zy>vDrj$9b5j%?Dd<b53pr(M--``OvTHhGZT$Az=%z@~TttvXD1-?~#O%iaa7>M;Jj
zuvInj(4ku%F<@3)b!<D18on1=_o34EOb70p?rG$e_br!LGL<(BrzX#&d>vtIj&niI
zI~3v8-BG4Lcj2o#&?hc{RYwMOC&J1aZrxmvDl0^as}ijNk>Y|?84xMH=>)Sn=K5B?
zc|$0n6MJQdHgtin3@~5^{OY!AM06`ZmsF1>XK2RV_*5uH;javi02k=W8WNNVn`><(
z;yZu<hmu?TUJdXQU;JVX=o4S67I#S--T2g+UBRjh9uya{%HU*ifTx}!-3ebI?oetg
z_+T9MREpMGcBp?9CeKw!)~fP?3k_w!k@(`LWx$cVC}`!2Sb|hsQqH1k$X-gm^tCl7
z(02kv86uZ`=^n|NXOny#Q@zouY37yhrPMSpu|*7@3qxgvO!2kE7TRttv~n4(si&r{
zORv_0cD<H&5Ws<4Q<5IYHqk1%h|aKbl|D(rQY_`ShUA3uQ)yW1(0!^5dnqNlibEOP
zvMzj-B?`qCKVt(5<x+|@Kq$UwYCi@L$|aFG)Za2OFZH+dVRvXh7LK)!#Ph!N)xz`b
ztLwprG4Q*!UNIG21AxA(O0o|~B{IKc)Y);Ns0_t;d=-?^3S#0*A2uuc_-YyfRGzBH
z8c-)bkERbAPp~TMGh3T)06K3TFoxEfN1UPbR87`!wQ(s3pEIPCcR{lZ*DjaBZqRX4
zpLTy~wCR$J8g06!1sV-iWDTGbR}EQ1P7Wug$_jIG+pr}JrKWst$p$5-3bF=Ziq9?9
zP;ymL_DRC32#3QTY;*x<sJV9#L@%x!f0UMWCfPGo+;Sz^v#QGF!dw|pD?XP-3{^KL
zU5|!~L`MZ#t9wQl;_4D=-t<jd18aWL)^f{m)rB>rf_J3UGlNzWbbSMOCCk=!Y-8d~
zY#S5Xwr$(S#7-u*ZF^$d6Wh)N^Y5H<&;9O)zx&y>yWUz|SgX4C?)6qxLyg<RpMn@*
zRZG0X_t$qyxCqq3rB+FlS@eTffjXM>7PKO%K}biy0uBpX1v%mDQF4B>#J6l}>@VIX
ztd)RZ!9T6gfu#^e#={1hj5zNH>SNUtdXO%9CB)syq^1#;Bs8>FV8u9rm|(%YwDD`0
zhEF>cEi}9;2h_vOpsAUtf!6jy_cQ4udS^aiN{PS(oA@(4L)B3p%@pyYtFXEGnJq9E
zI=Kln!G(PBk$1yU-nFm0wH9E<iuE7sGvlvm?bU(E41?V;@ekza(^1t&{(2>c3-o2$
zvpUq+fKEFVxMR291*?|2`pqlVF*VIz2jV&cb=kzf<~c5=#oP29R*=r~xiWu18(km%
zWnLSJPAGzP+Sn^pGoSaEyrG=^wEWi6zq~b~6FZlR&Oa5nd>6!hwKw8P*j-~sSsRER
zRQ9I^@Dh-c1G+zJud+8BJ~|xdrS>x&&P>er<Mt}-7+xQs5$_o(8zcKksh{1(Z{fUy
z1loY9K>R+}S54aK=bZb|PqQr1GqNDYSSZ6CKpJfJWH?lJh9O-YX!W61&Mb|N3Fqec
zc{`XG<{|hV34&AHTKg~|rq%~U^)pcd^ctN-<%k0^5$IoIsU@;^K%GcOnY}}Ff60n^
ziZ)Yx*~kpmASFH0u(*XY$=0#Bwch?co=iRsBfBeTq$5a&N>p#1w7M;5jD<v=s;Ekh
zL|#4Nk;1QxAvj)Z)2@(eXy#I&b=FphE%4H0%Pm4&d5R**vPF&6+h%)js3ZA%U;Fz#
z9QIH^RXtd7Yn%#%aRjWUi9c|MOxaK9q7q?G2$e(0LbDKkhrB8{s4tLfr;I@A8-<C$
z`VNV*5WYW?wWs55mXdX@>XdI0dXxL0?Du3E@_ajS-t<(jQ8AKEQN{#G)2So?i=sb4
zSCwpdrYg=UNKAWDwYd6gY!v1Ln>r*$gtqNVR-4t9b|#$N2)sNN6~_PB{65B1=;xN0
zK({{i>M@PFkjr$A6-Pz4l1vER_!P8sP+{yLDj(riHU}LoGLqb9`6zp&96G(_;TbkP
z_3hL}M+Qq#*DF;bx)$n6v9;ktR>A(uxngs&$EyU2aDeF<Q;r#BGu=bP-B6J~{1nND
zs5=${9bIthj`LoyvqrYBEh_Qg%LwYU37o)9H8V>s!<I{^C`}~ng9&(O8(4i+(~~yJ
zvn$}y$wR=6GUW|06wAsIW6HzD-;;mLj)YK4wHD(_D6rRJ)kPHI@@EIjasGTg;`cye
zZNrXp7ttqMY`#V#_Gmvr`}q?B(4x*W`>4V<0P&Rj<hd*)b>V^^wcH);iDrAtMIQ-A
zflf{}4&(2*j*Akb$MK=3g%WSE<>IJ=Zm{KS9}+o?qe98l*kKPCyX~}CD2vgkJ%8e|
z$XtsK(z#3ften}a*;!J7hAFR=k{7y_iD&=YlB)p41>{@GMamyh=`_NIcGxHr@v6&<
zEP3GJ2C||yhi?^e<h&FIbI|DV>8XlQfC=0uOo8&)i-$(Sd5yG(WnIBH?HAhk@S2I?
ziN&bLLl%{^@X($TKy<|2!sfI=R!bo(_0dB4>=cS%GwtOWx{}|=(SW%hlCHIW2<b!k
zUi&Lv?cK4n5|wERN`u|DCu#ee<nfA>A;Z;&7Ng{k)4>$|z=x4py!V)^x$L*cQf%yC
z&<;hrkcCUNIW8(LppCfuR&6>~PX7hmSDS)vfG3dMLRZ+?>+JRvC2X$LlO9fF^bW2C
zH3m9R5%qE$rudfRyS0O|m5jC2EA+DoPCBiC4g~Hvuh=2Ct^H$sBzDU;tya4A#eRea
zsYn~bRyxuq%&+n|gS>>RX9^kqbkxe@st7#P%2JB%+rX73u=6JVP3Od{@ap5d)|+8t
zFmBq1HoI+b7|yRFD8r;%U;4-GXIo-BH*}8*0Q2lxjiT06HV87`6k4Y?K+H9C-EB<`
zX#1zyv=ded2x)D!Gju_~C*+KoSGN+A98MYcS*|rrd_cGALrwvcWghz`XN`CpewO{f
zM1F+T#=9zbC!$Yn;nxj)Jy{mMF^}Xvrv*v{o^+&4vKBz_S?_N6*@YRN;v<b%Cb89P
zt&yizFQedE#o)UbOXxGtt7DDZKU!W*Bd^6lFO**@rD0wY;sTusHthebQ?T(%m6!K!
zgoN4{N1Z#IlEt5_nO|46H9{sl71-k@z6{(xWfG-SF5%Xv45A!(u0F_;hmckaTpm6y
zrOMm;a0R;=<yNE7+Q2YCV0FUF*uTvBV68#0{@mSf+`r?T;A0>^sG)nXw53)7bP*=3
zUSsS20U|(Xb*$8kAIRnq@DF9DS;!K{V~g!HOOqeg7X2G*VdQ$byQMf~OS0lL)6oWk
zPca2vJ2m)kP{ryRe=^8RV`|_;bU^5l4eZ-w)HSRg)`}PGiK(xr^>Pmf{lYe$t69H6
z73jI%bW;XXPN?>ZaH5Z9w^<%&$zNqdveFRPbb&c%P)Eqn<ZK;IO$%Q+rb?&`s%lbz
zbh`Msvr3{j3{}(;AhRk!8*NfAq{)>>=@$MwGycUmjMuD?Z<Q*^GK6P?Pz2t6w?Tz`
zF|OXHLAD(H&gKL)CXu$3y|8?PurX}sY_%LffebcF7GU!ZOh$RD=A4)+c9T=G76O(e
zTWX;yzy_jQFX{reU!{t+Y?`z_*k>+OU!52=^KZ3A7h|<nT|fI_QfN&UMWr})$)&8e
zdR(<zni^N%(fGhPGOapRw8z-|RMlPraXzNHsT35mLgj4<xj5vi%G(4|V{LNC?61ZK
zn}c0Ty?%fsRGzF;Is#e9Pw$wGq<d+8+~rnJ6J)yav2<Pbtp%n6n_*rHictt=1O8hY
zaJA$5^A>a1Wg;4rCT5Z>5G2=a7AsunNYOUyvVYFS8hV`Uvmyn2W1*EAzvC19V5$n~
z%f*!r@Zw>MlN!IkZ`zUNq6IW7H6Uq|S1+~aKUy8>x>}Cwtyg+CDa?@$nnVwMHvSy^
z^-!78sse1#=Rg5n;h@BRd}78b52NmfQ+HV_{ysn5NEA+Olf{!qtc5B-Ts@pDRDhgJ
z6400G{4(=H9yScJ%jU}cIi{2<YhxlI#QI|)I4JSe5eF-?_5)l7zvmeGtXj$OU|;|b
zh(xrt@~~?+r%CBD4h(ryiKcAw%gyyyLeVQ#GJyU%ARR>!gp!%<hqF$lR80%GV)_Z&
zP}m_|*DuSdCloTtmEetDEch0H!fe*0;q*-ewt*?HSlz&N5BnUAb^>Y4I|AJl{rnp^
zyI;Z{D)YqU8n&)ez51Tk=_*o^>}wY>HqyqMj7XVRAT<u$Op?vLEtF;{PflNw%&dQI
zEY)5z`(TQk#!>84nvx(oZr#PMhuK)U3^E&nYb;g6>+dn8K@D7a$FTcs`CEf)Ege!R
zWNO*cwj6T4JaUf@2-``i`kWt{Du==JgSYF`1J$gYBIh=Qoq7RO*kc$3CdYKqb!hh4
zU-IQI=j@%#BQcsQ4JS*&-|eL7DBr~b9ca2F1W1pVr37fvXOVQPQ4D-RHQTdcjZCru
z(*(i7G$oOYP;Fb#b|%5j$V8gP8wxi&!SWZe!`Uf=AfUK&h)VsrGbs(vq6-w3WT^Fa
zr4|-d3odnRT&VQek^-y~L0acy;M$Ewn@F~eu@DjAGE>8)ssjQNiMsa*b_%1gF>{!^
z8}fIIvFNRC>?MO;VDPul6u<}EAAS&q`b4Z`IJr+dMsdVls74uCfl69PnH;prLhCxa
zw<rx_;L%+t8I)tLIfk&{xffSxW*^D<m=x|8MrFx;a}42ahV#q;nVK`^m-RJ*kC{N*
z(dzx)k8I-LkgKVBhD1bq-sS%$iRGn*`^C*9R9KjP7V!GEoCTt=X-xyCi0p_5T}w3+
zC{!n5iX|hZ86&H-`y_?g?eoM9BPg#NB1@!9-+HjhU*=Go#LM%@dEqDIN7GzEX-q*~
z0h>-mP+jDGCBDH^0>3zk(9Y&HjiIs9I4S#I8XjbQq^Vp_g)t%sv)=*AQa=Jc)+fhT
zI9Vt%IeK#|v&i(j4S);FpzM!^J`3JnED{#Dwp0v2>clpS0Gdz^CmkrQgLB@!vYZ2g
z>Ks{al5N#7{LmoZ;tjCizH!|w=j7<sN=J3{Xsb46?Zr~|-G4SUe}ouf-&1=Nfk*V9
zsYzJ8HWddoe1fw8I?mQg6axg)u`@g#XYb*bBTho#fiD~Bohl-kkQ(HU(?wI^8;M~*
zmY_G3>O7HU_(W!)YQLpI)R(a#GQ>hz%CX8`AG%B?2;6<o+lIsy-Ihv&k==m4vR^$q
zhPrYR2kw8xRRp@`4TBJKpJu5!8pYc2p$cwB-Xh<##+mh*Lu00P&Y^RLWG6F`@6|-F
zh#$(k0a}QX=QHTmG4+42kRx8u&;lc_l*<lIM_wtBW@83<WkD$P_el>G(9daHje(-~
zPr&?vyh1J~G6{9wAO*?)dXAlY!|5W({VYeBkK+HRK}wI;cEl!{pZ!gg(TV6+Weo6^
zQicVwyBwB*=y|rB@L6CAwTX4cG0!|&L(rCxDW<z6<*u;w#H~C`5-|>GU!c|Cfr7~H
z?M!#C|2WaD9)zaiD1%DIJM4@Am83$I!A}gyfaFCRQMfPPe<3MdhRaueoVc;>qsh+p
zuS<a8D`6uC{M?)7-(e+Q1ATr!ptXKBkp;uQ@5Wc?q6RG?5>u>+7<oP9*RFl4K`}7z
z_mYoM3|0Yi&Px?nzvzn49?YVs<S!93t`uSY-cNM*75Uy+ncOM2_W12k*Z_>1l^g;Q
zC3@m}ANu8eAY4r<8;C9@jc5-iV_K50lcBu>)e6d%04As`9R3<OVCj=W0C+ufkx5)J
zJKFDhbliC7CdiOqf)7kpw4;Y|TqV<msxw^G3|+nZn1QMd8KX84P?i6bfvSbY@*vKD
z_M($HbD9^j@x9vcIirTE-b-^V_c;UA26_2VKMB<~s~JT6nbP17OOTHFmH#?Si>H9H
zkV3DD(=IJ>wdMn<xf>DXZkaA=Q2PBaetZL223f)_h(D+QeH*a8EXg7|5KgdSiQW=K
zo^qc`?1*~&9!{_<%AZ)UY5xgQq4@{$dqV!ZO=;w%7J<0?07KQC2X~xcUJQIh!5r$F
zW_ZDz4o$NAwt{dC*657Zqjplepxz@*R0w}LWDT1ce;1)TUSA}HnuO?tg%V!#3D4BP
z-T`vT0RsF$Vvl6F8u`SnM$@hn4`jqHi$gNA$D3qAbC<De>F`K89A7jV&nA#w;=ErG
zInK%9#2O2Xv+kLM;T3j4=H|EF@cDT^@1QK&(l@e$QYyeBUI?V^qqyBDcaNCE)5w^8
zfLLwLpivNQ3e@M#VsosvREFT>4D)W%7RVT7yuC68Sx~XbCn>;tyH;0PXf9S){Cqi?
z|LhBdOv;)CBRi85PJ^{4#+fnIlM~7*duQOK^t3*+efJn@kjn_>C@|oGw$I=Hs?bDI
znJvtbh+#X&O)c8B!)6@;0X8$bRc@mSIw(Vw3~fjrEy8$VLv-mgmg`BFKKhFd+8iQ0
zE0`H|u-~{%Q4~Jhj7-Q2WG3lxiwt-YtOFH)ItgC<y3<5$T1Dhh<hs7N`^(opTC{J6
zdJ-!bv*Ta`iOu<&$65BKEo=;^?xrA{5*%kF!0RNLE(Vu{FDouhQ)H9F2-{iDz+sXz
zXM-COBY<F>jIqY<L2lwq>mBsIJ<bE=j*0B-B>{u51~%<1ik!5lk7(QFr9WP_h)`q-
z94nOCTG#p2b#>uDkrFv27M$T6F`F(u%14qm-++9OPBTo0?Vc*?TqyJxk+`eJ&KH4t
zL`q8)W4)o0I1cCJ5q0Ru0U}XByndrpR9j&Do!e39lIa%MMhwD+L~-j#x?gm!?#QGa
zw(Bb((ymG({l=-pwt#qE`0zae6N0bOkOYyiYunBj<oa>=7N~d~0peKeq+pntoAp(=
zV!hHXbL~e_b9EL5FQq@d>st#vS)E;Z;jxj*##;JMg;7q8WwG*}Hm4+Z>qNfI@<y%v
zsr8!t7~2h_o6Y9VY^zg|qGqrsNZL>7xVDkv>-+ZWkmebkHW~cu{8miDOKpl^@N5?|
z5O(XuSZn(>>kL9T^l+;~St+Serq9K9Ej-_AvBT<T*gmpg=D}=~hL*?(*sDM?{5Og<
z$p~6TQ}T8f1g6Pw**TZlqG!msy;1WrmO^C0Z4Cui>4+OgTbiL~ZTLaga%HNUWKbLH
z+f{@b1v4_OpyZN0j!HocIxIkIq1U5@P1eCjWTqNq_-!4tZ3OER;#Z49R`EN$P!lrP
zz;WU#32K|6M`cRvGrpLdG03nJwpkzob!$aDlYA-B(ejs3x1BzDq*J$D1F`OROg!j<
z9*55e1fUmKU-jE8+yLW+WtN`FXxME)*$mn?`>O#-E0ET2KvMSr@bZBj00th&sCPHf
zt^^-wtp~!Zcbh~L1L;PD`wOtBu&feOk=kW-h*S_U5FO`r<rG}xMm~~dLlUar7|{at
zwPZR9fOV(B^%8*n5`4~GeoT453qHtLazmr~6?=mxeBhNA9zUuHRY3$PS!qJBM*O1*
z^H)83;8OAKm}XL)hgIs=`=PD9D(ucWH^5V$%7Qv<|7jJx58PC~e8<WRW#7YBSfaD6
z6jvk_JB>8~<*q)_W`feKF?Lgh-177EFToR0xK;wKoevg}v)7lmnkiJjd4mp*s(3tS
z-a0+7Q=s=6;Jm-<{E`_fMF76HO@{|5ozu~r`RHtNip_sC=8`Sv2Q#@=hXpyV%FGp@
zR%wBXdIC>dyOT1ts5GS9es*B^R$0(D!wOO(8%uz}7p9Ax$0qgCG8pTkLFD|}dnPC%
zIR&Oiimd|6$8j2F`<27i7R>JJvkrJUxDY#<>|?mBTV4fZ3{(#wL@-qXlj3AE!FKAT
z>+66-P*pm<3<z35YxmkFU=tbPxstGsP)|SZAJyMhudyQnw_eWsQ0~ypXp(<kA(o7W
zz7&&(nFrr~@*fJ)fv5Q9?s?W)f~GKX=@Com&Q3T!U!j7K%g^S_+GjU74ZA60Ka&yY
zhT5rGB0r)5*+gm2-PdOop;<;3eyU>sz{4o2_6ydC#iffud@ppUE;H<shJ!;gj~iB(
z07;<nNiZTwy1NXA%k{YP#?+M(Q>8x$?%P_i?shv2;|i{KF;c*!fEmp7GA<NWd&9Q>
zEYzGOu0D=ojR&w}c!w)k5l{3RaT#>AAEyx5SIR+UC$N&(Nh3yjU&Zj^!(8&8DUlm>
zi_rB8xZH&+TE7W0D$FfoB7YF3tR1v=VHuWrG|-?&aN7DpoLI!H=Mj3Qv!{jBX%q}K
zEL1JJr$DIFYsaM@uKa))V8U0hu`rS=W13;ka*bJl77J7<fp_Kw%!jE=#7HfNo7j(|
zLq+9e0Y+V$H92Ad+d?@nu0o0uIIATSWHiSk6FdL?gll0<D(0x|h!B$I68BvY*%VJX
zUp`zzOgU!+sbOoXzVf*qA(5)t!XD?&5_?0oOGc<-`GAzN3Z!9c5ip}%#|8qe#N)Eo
z6tvE;24%4UB*p8-M=(GiFU64psgl@2!dmeDzy+QU4SvZ%i4PNQ$>9ed8r-9}<s8)X
z7P1sI0QZ_kQAKY>H$=|d@#Fw$)&yz}q(g#ar%2hx^3IlzTP7YI4k4)7;`wuURi_0D
z?%~2=C@7#CTj;En4jSetJT=ydDuvG|2KAjkN)57v9Bpq=;N&~$Hdr1xQp+<9)95iY
zxQ`2xr=Wly9zv};DjslZiakq~shZ>pa-2kfAzmH3;jHx|%rtU4_;&cVLkP%Eu6%DW
zItUKIpx|m?TnW~|WEhJkqwk)(+vmX`Kk+5tCFEhQj0jXKQ~j8nleZn88G_uPaWk`t
z^?x-ThSFhhK=I^_gKte!m1lq>h{|o71_Vu^O11r(PsQm}+qQ=pp4;RPJ9`ele%IVd
zsfNcDpp?5DjZb>~Y1yTy*bZY+WddCRhRK!34T=ybOA*kFvnv=@jf|_n<4y~5y&F~y
zjVp2LRgpD!7g0pN0pvo|+y;EQ^uFW>zcV!ldtfiJJ!W`P!wnL{AxOxT5fqQA)M1C4
z1NQB}{J68Vozx!eg>tG~0jFYyHh_2((ZTV_W+fL7+KZQdi?ZR@?ZsdvK7{i!Oh95$
z8f+m<4Rg8tuFbH3D#dXHj=#Ki6EWo?nNbcGCbt-v4Ju@E+-uSus#5L>@hH8tG%NeQ
z1U%y+Ze@0wCThe2pkNz$&%hsTcmbh?yd5@~a6^L$`mhBHzT8ec5J7#}hGiA8UAu8Q
zl;t^SKvWhjdxI=VP3sPo*oN7hr928@b{N7hA2QyPzDK`iV2_&fDmP=?1@da^by;!>
z(p?v~UvQy4MN3<W`@)fAFU8A^08dXH>u39%Xy!|J9Mr`>_QJoR5ij*!L(fcBC+%yw
zN@3|21`cwSatF|CB5cWqTOZnb|Jk|WN(kUmE_UU}Gu}i15uj+T>@fR2kBA^hQGXu4
z|1`l+e+i@-68~U$HYh*D1gS+n$m_)5AjoKlC!C4Nnq5CJq}bCciUEV`CA`SYKB)Ul
zKDLUi+yi0+`9}KlJkZz}>lcSOGvRGo&>l*D44y<cF6ggSETZigV<!4+>2S%z?YUr(
zJ}wScLZTmP&pFg0-eo}UV{JO~^aWoSd4gV=@eKHkC|V22Z72qXofskoIa}~(ejxcx
z#KUp%f4yq}MRe%*2I>%o;ZE>w7=?BU){f4Lg%R+q1|pt_R7c$ndhwqn<4q$DaE+?2
zhF!<^T><p9dOgTEIPF@cYK?_34jQR*a9|rD1${i03?#LQzFt^|Zd{fwf`joy8dUr>
zN#&(GGzXN^PR8DYTLtuMMZ|3s32j~a;batVD)%74cuhPzjprpWG}rHk2kvS$@|re~
zVPxVbj`HS$J32gAEIU$oz-6ZytpsD!LLQBHdN$$Z2O{Y3$W1W>B`Dvjf)WZ`uXdDv
z_pvDTE)i3Lle5Yiqgb3JIbB4M*k&1?kZFCXP^7SEHrjzHntaq;kLi651nv?Ca-s<*
z{GA#UhC1a}6E-nmlJk@-au1_u9}aie)*4oC&z<rI32_1#nO=fQ1qp?Y*#*Q;_=*d#
z*wz9S9FH+ir=)Vb=EwFMsgNs3Z)b%BP#RIk??L!Ud2=;Log?vURu#A>!2c^qwIgxM
zHX!4#z{|ATo*dn~yXj^>e0l)$P?uzLllwdIp?UEM%q|RM<2`}X(FPX#rl3RYUE-Yj
z@%0C{DB`r&ovzR%t1bu*gF}kJo{JaOcu(?_wbjIk09TXRa0)}5?RuTXHxpNt(o{li
zsTN_DAaq!484ApbAQ4o!q0^sf(1`(D4*2M7tckr;;94%%CW5o7c&~T*jVi+`Nz_TA
z>kbB_(yG+eO}Nk<a;=I)He$acYWoOxiJa0Z7xMdpZ-ABsf;dq+$7@q#3Kuz}iJ|0-
z<y9b8Ns~y{9eTI{p}}~_XlA9?u3CiUiV1M&oH2LQ;7D#c0x?q(*}8$*P$JoDxFwy5
z1Kl_ZuTZT<KbK@toAtQL!ZpKcN-N5jp+rKt`EQjwSBg8Tu)UNWZ7O5S(sabycCbJ7
zT(tdRO?q565&*{!;2p$FKxdTMs@xJd2)0rTALRo($S^&p_7TE<8<N+V!A#~}zf}cK
z8t^Jpi2G6zzeqW+#H9ueqDZD){4{_*7<Ubhceg8+)fL>J(=*`@E!9C_R}No0uvZZo
zHiQ48N<mav@<crr=_nvijD#5kf$CF6oU5gG3U!>Ko7JE|3nNWIQW*s7MB?rfVB>SL
z2h!{U%tib=xYV%wiY8CbUN6QtR~vM}G9a>P_UDcLMmKzXPiKEoaH(F5RVU$ND&PVZ
z`QQ=?mSS!H5~M@gxvJkKjDa0=hqAedC?GRPA9lsY^{yh~@tw{M9g3b_A_cBMp<k~C
ziCwHe#vsw98qZ!j49cL}K%X)0EII!?tqd90IvFW)TtM~vmI7B#s@nHDZ^3;UNSOoi
zmE#E%955D_HypBa-yw)XMX+UJ%E=~EW$~h8O{QK!4+(iHYSlaqo)>ZfkksYxl8yX?
zzrY!*aUq!$f-5RWO2lTXV)OxQOsU<AIESOZ^8EV{@z_(#=x`@$QTm%0jwt$zddz$|
z;5V!F-a+^n_XWM+#H;dIdv@OlqJ;!|Q%pZaIAe`cWZdwb`J7In61T*Cb|0f(LXRcA
z0?r(nNS!kV4)m>DN%rUd7nokn#5!#MW;V=<!*EG2pQzke;l!uU+X{y5&*E4{clD*`
z6L6rKll6*Y``LZUp&ct0yoc=(w$tW6;PE?R&tn6OV7~Fd#@5Bv{!v&{i+hz15l5%M
z>dM~$zy5Yb&|}E1SK=$w26Zm3S|g>}TQS6dRTkj&6&UsKCXz}kDKLZ|=1vFX496%N
z^m_AAJh;=S0NUpVi755~HV2!%&kC|clG!qyK^C;=?81aqqbRK;F5Hc`4+i?_T97pM
z>z0nZi8O7j7_6)-f0!$r*1-z!2q3kw2IIeUn~<9%M%&`8M9>IEJi+x$<6wmhoCPot
z<HoL-GEZzrR1|SpHe?ztJ+ve%KOLc%VmsZO(=fca^7$(8V}#%|LcJQAr)ylN<8p*U
z5sBVv2L7RgS{d&F@SFn0#5sYEh=M63@y#I50y4qP5EB!>M%&2)c6b#wln6JH2kWH(
z-)ZS_WuAN^D6;mRYcq_z^2VwID4JaXq^-YKzI$!ZM&i0MY_2;_l7xDv3^A^K4<*q#
zvdXf~<P=SvMDOnAEQ$Zk<@7U9l-n{8a1;z8_o>9s%>{b@8@l-?Y;pLnZu87i=EnQW
zN|kDVe60!&KMubcvU`v$e8r?fSnAcn&o_wvjkMd%Di@NstV(v}K#b)cd<Z?-OT2)Q
z5Fn;sJ@x0x&{78}GY22Jqx!J<)*Z1{+SR^?r<ZB9t}Px{gn6~^{Sk=WS?r<(GNl}k
zr2sOep=x7mxi>vE-&6WRS>v>oO-wA1u_Y9l&Lt{%TWhonvbB-Bb_c)d@G8x+SZKY>
zl<Qu^GX&V3Gf;C3lHgc;rqU#!9484+@hh-EOgLVuN?US^mw%cgNmFwyQSmwE>B=)3
z+~c`BR;cF_c7BD^Fp`cBcj)n8O@RKT7IZh{F%7_2Wf2lBnm=6Al7tpICl@wBrIYbC
z3}Ow-aiJwkWI%ocNtuZG-KV<;>fqJT)Xjr;wF!J(x$YvNAPv4SKQ&pDH?KytrfHcA
zK(yv@v!C`Q!8)|1UVQ>$B_&O(FD>gSlF~o5li}Aty@LJe-IBEIwXOKmbYeLm5<^Qt
zFSalb#dhqg!c;|mH~#1d6W3)E!iDq)PaM3V-Q|(k@O$lKZ!M^IYE^G-!7-f|Y6Rp&
zCb0oKJm}g+3c`x47rhGgud%J)@?K%C{aagkJDzqF<k~kzkO|J#L$P=!8(r+$H6_^H
ziprAn$M_5=Es9}?NJfuKf;UVoE&X!{ibia^a|lRA&BywngK3ldyP%zERr|XI;f!9?
zf3AU$P3@{+2>PvWdLY6Xw2W(jGkolH$FP06C4X;u5gw^Z-Vjr|=v2v;o>`)^O`B$}
zDO9Fb@i&12LXIZT!c^L&W&V$hcVqOg*WuQ)-J-vxAD1*iYQ{`+*MNt|Rdd&@dbt~z
z@1B96O(U_`s9@zKIZkzcyRo&OX<JcGKKr*=T*b`2bS;G-EGP#z1V}}9gd1T97h%Bv
z22L2CLfb8XqSLxDgM^~<va(<t<XDg3<3<WHjbvln=G!oghPTo%tbs?>lY+O6wiU_2
z^Qd#CmS3YhIv%9L`DwFCEibP2po)J3oO)u4e`AmWehNyUjMM<UG^RU!3$!-&CBWLh
zxn6<*M?`bgN}|T|7n{&zceiD0dP{yfo<xnNx?&uqHFMIr|9~fT(s`|eNxTxAGMbLH
ze`-B?$!92Vhds){NeYit+N=$ld7Ro|tEJIPZr96l-6q@SifHJJry!GVWe=Muia!#+
zU-_e5XN4zxmbJ239|x`4@Aqv+g%9VS_dP#v3n;dE{y)rOV2%Ajd>@bFSJih^ziQb0
zp8wRG`n|tDQ1yJgZhp)$Ev#0Q4X|7qb@2vY{jq;vyz1`g>Cnsa`O|Tx*ZuObet4F_
z_i@tl>*MUn&+UEkY5B!`=mkm7&NtE{XUV7g1Mu>uy<fgBHELb+p6^#Ze|9W$)f-b{
zD*3!E8ooe5Svu>L*-!6H$D(~4e*L)U>3RR)lbVfgwtl!dy$M-)TC<(>Q=XraS6@I|
zwc{-SIQ?GKXZ=22^`sQ|P*2T>Xk`UwQ`;PS4x8UgvqO!G=jM^{c9<jZxeVSWsISlL
zhMy1Rdj7np7SwMAZfngP{#ac8I-o~?@aB+p1`?@E_Vb}a*_U;t`)&H+D4OV*AE#-d
z+cdvgU-24aa&YyoYT1dKzSn^F?OEw{>S4xLaWzL34KnH|e$ghkn0UD0L{6;|enE?;
zeVngabw~AAIV0+9*y1HqZnh;mZFy|PqJ@7p$XJdK)RWbE<5Dai*ef_<05a&W&=SnR
zud#@Anp;#<7Z1be0<i8C6#2cw=zSkP6)R6_4^SO99$&^_9!J9*5I}r)4es@B8ITxX
zZGze9H@sQ;{VfVS3AK&}Ecx$B(zo9SEE}w=OV;*%vJoph0{C)3#&f)(!i-q`3{@<1
z{2+`$zXdV>N$=Z{J}WC0sz$8nvwBrd#Ca;Pytgl1+q-?PUF%-eqQ}|uJv+Bz$E)G8
zY0`0>e&5sUOMShQ(<h!?WNzi`F|{AqDu;UoaCb^aWk9=AVJf<hr%HL#Ij<g~bxYbU
z9~gF5**|#2Z23N_{a(PYeg{q~2WdLy`?A!AaO=pi>fHXW#V%!%W8DmTuEowb<5?W~
zNZ;yZJbY_-8zr|-m>!n<7NA$VOJ8W=3t`5x#)pfW86d}s$L*&M4-KAe+2SW+hk7(#
zF4{M(JitTA8&Kw@l;a8VWB!m_HAAl!IDOuiq18f<nZw>U$C3!xPyHfHYwJaYd+R%t
zfE;TG9H4Yrse3TApSw<S+nE$^gY4Il=l;X`@r6E(gu<=`EfKMWe-3augy7fN0HZFC
z#?#*Xf*V86m+Z>Bzw_c6YyB~^lz$t%o=USmM16Dj?)g0-xD@~6S!R)aHjH>eIOoq3
zxI3zkVIldXjrXEB-$VOu>+QRbkMP%+h2CAin&08PjB}`CE{!!<CvSt|cw$3#r=J;9
zUT$<QC+(x|eS7L!Q;T-;GtK0v@mhXF_TiWU?tah$WKS;YxzRb`>x=$-!qsm3^tGct
z_IQu|X*zBnGV<}N=S|~malx+o5BP=Rk_?QAt+A7{qltmd=aHSEB@8P81HtDv0RaIk
zCo4PqKRENh@NeHfljud<oyC-#4V+B~{sulV0|r2ZfL=&|fRTXS$N&)X@_q{c9ny>1
z**gD+v?(nEEdv1?AX~+M2?6B(RSBkl7e+v@>|t+0Kre4#W<o$p!1!0;@&=A3fV>$0
zIhS6>#Mr_>(9WGe3ji?yD$Ys3$i%=vp!1iw5TIayyb}S-zfTZzv~#ilkIMXA$Y1E^
zDS(Y$2~f17fvuDMXJJMj|G*Li&W<i7|HOm<Qo<&#7DgtDVuGLGzuKy3;$-LIXk_9<
z@ToUNnEz@TJ0Sk4-%m|Ro7kE;n-g&SyIP_a*3Kr51oWcT0L==U7y(|K^O@<t1Q`j~
zSvc7~^ZJ*`+%qrKz1-16nrlv#7I`*#c;<P2K$H9+K}{fpt_cnX0!~5}&W<DiM%}0t
zFceOLg}O!3(3K+a4>g;)#wH~QtY@r8!aqB`MG;bUgWeiP$3T~NCa%{-V<$`Y@&uvl
zcyjvF_3OQRomEArrkbnfcb1Y61)(r;Bvf2)VHs+P-}BoNAF5#$p)fX|#bYIq2Mup(
zT&bvFDaDVE;{_}pQ#r!HFq`_PS@OeV?@Qf`*atOeMtV74W5c=~JnzuB<D<HoBja<1
zX6m99->>VGi6v9%uf|1;nCtAdI&XuG5~$Fev$1imkJyPNvYFgj$z#m5?_Zih=X1P`
zJ@pQ1)NP&^3B8%(#lM&8lXk+Csfb&TjQSGXA};h{NJbgs+L@orPJ|AH4oy%{kHU~?
zNRURcOb53fQs)ag`23knbmYn_Ow&#JA}Qqne+INl#3-5Ou_L`dKT%4er&x!!>?oqC
z8A6jN2W7DL!kHvbv5x~}Ko;_17!s@^mVXYJAnwv&;NHYd{|8AH;epQl+g6mYF^lPD
z?I<QMSx+wL<`o2cB8(TQ#y9dbn;nEe1XTJNv8|$k^oqyYA3~O4ELrP9=kL6OhF_7{
zY#>J!zYoPdPFQO(HK;YyzYH{(h4gx?Ytq*l7E)(RLy<P9|D<BwGa86sw@$%QOrv2_
zrB;EycvA-Do0aD5vo0Q}D7Xt%^SZ+q)SO&u@x<83UvE4SUHvg!lLtqq*F9_Q>pF=x
zJZY6e&Q64MW}BWR;;oyokY{8m3&Q4kcz>L>A)v||n3iIn`bH<iBEk}0LynvA?W1Z~
z&+BP(S+pl@c=`hQY{S;!V!S894m6<s@&{zIHD}x$@=MZ)V_{FG9yynVSb~s(<BCxK
zR8#iig-Q=M@LPB5<H!TNRt_7_GLr@5C=<`B2L5=GVnet|!ajm4Wz|}}3-w2{?R!A^
z?ja&yc!u&pfp8Z`P+PXC(WyYgfMGEO`uI=j-!xfbImOd!_1#iYMz9*l4)ZE`0TDuq
zw7W|*I>dt)^&5jW>asyA^r?9#>GN|gHvV}PWV0`h&s9=<mhEsQ#bf-qwuehH>nJQ}
zb;Lx5n_ntu?K*5DU!NT+bgCzj)<To54)X11dC?O6iqc}VUR1OE7U^K&$(?n`HV7;9
zg{>~&=Ed0@qw?0?*TjuFxpXt~Y1zMEox#V7#zAFqyQE&)iuojrN^i;Do$8uZQZHpm
zDw;>2=>un9iYo<aMr7|wvvRd@wSlVACkQzeN~er^S@Aq%Pi=`-Q!i&(Yzhgokc1En
z3VtIAONuk{=Mu-UhI4^;39J0Zlpd2Z)K9?{5t}$nwTFvXj%aE0P&Wml7T}enA}Ccj
zx@J^8ydkpWJ*>T~?S`dMMmL|zIUdEN_Tv@YrJ#FO<D}eK?L=j&tGesb@{H#!f6<ah
zQ5>c%(zTe=-0+=pQq`il(RV-8Y>AJNh@M;Go=22io~7O`yBb$9eOQ#u&YxU-f8+kA
z6BnXO*?d6WYbz-=Q-eR{V<a<`LM_Sn(=SsCG%5v;Qp;#z`I-n}O#DiiCJ49OberW8
z2&*1iS(lw*p=uef1|n$Gzw*>M^H)OICQa|HCM=&&CEtgetJaTLhZ@xn=eaE1>MqyR
zA9E9GlFb`V=B=BVq`XpSXLa@0SIJDWnnl+|^bC4Txs&lU)$go&In-ErzIbnx44t0L
z#6vF1diEX*Iptwo0migDJxCi-Yz#w|4cx~m@DI&`lmX!j`=IA`50!!crZ7rpOr>LC
zn};9M)htrRxx&JTRwV`n%xM{=`uTM%2R(B5B>Qf+mcu){n=t#E+`I)BwPoANEn5}3
zP@#chW17IY0%Vm;X%IaUV8|HFenL^SF=GMYU=EU78hmO7eL=7-i>ZmCR^>|%DFTY1
z3r9GpiTT5+4pIb>B@ts8B`H-gwqi-ex=It0^_xU<g7KrvcvE|dRXCN*k-M4JQ5bZ9
zfi-WPxakP>8BCqC`enIFELD2c_|_3)Ml8GOPBj$aFwWG9d9$DL!Xw4^FLSnNJL6%n
zX0O)vk+zTnC}FOvx3_shJ_z)Yr-xzh_!XCvDcGuwHO44M$P;T}Y00s#BFOY7IJZHP
zy&?w(bXHBGv7T00p{LiU#H5gI(`G?xw(DE&8?o$~_$*QH^WJtZ_IDK2>$jro1QE&m
zxEKj@@s|}ohd-ig7MBpb-^*Hl<z3AV%vGm+UvKHrAf5a}_+~j;cvib!YydG=i)3+~
zz`?|mB<QV7>r%PhtwzDOUnsWr^>%?v?RC#PVc>{hfHc-Cjt``8IR2H5q03r#z?m52
zGVlK5W`1wr=4x0k_UK*0Z%yy?>g?-q2L)CPTvH@lv~<CIp+&cagXIofQaU{)$VZpA
zxKnSao-?eZa1xBxiuPV5AIHJMK;o94_6Aakx#wMpa#^x#b?LYL1hOc<JLOpXS1y;l
zt}@YrWBwb!i&bBrY#Kb$S3SSy^bBBF-^WGUbQ26^!87vCKY~xX{SMU9GWvl{NKC0H
zcnUr%xYG|VDRKtB7B+=WJt*NINK<n645dI_9X>5gizjGgfs3a|ijT5B=z4=xm5*q&
zhBbR*kYty9E~5EX=tcp7z`1#v_t?F7xz;MfIJk$ku|>&kcoiuYQD1K>{B~=yP~&l{
zc^Hr%ECRg)#?L8|SwNp}gng5B+$29*#@oo=dVAaMLciX2(8gOc%_pR(H9g_iHJvA<
zD7tx+vuu!pPmxU#6LH0em!;l`Q<i6}c}B_+;weX(6ZRWRcC;u~LfXDGAwOC|S{gI=
z1p51gn4|^PUCQsVwXgLndHPjNT(ko7sC#I){Fwtq9G!T8*Fl=)=iM+_e$CM$LjR@9
z+|zZ~7OhiVgEW;St}&ArTBxXrnSQ$b*8Xc1J~}^g>*uQ4Ma9G7E7t=MbgrAk{M@~)
z0@fCsUdeG|aO2=Tzo(+4WtnPuDwh;|Z1hY5iB&y<EJH82EdwEhAtAyWjjqh3_*KqF
z<bB9V<lJ&$*nCY%ix^b8fRByY0#24VYUwmJ`7bPQ<8A1vlUY<bx=QReFK><20i54o
ze|g;T4Sn^>-`^i3t@yf%v-bKn>_@RW{rgHvYJ40PUdGYIGtYWFV1J+8$q_~r@hiG>
ziM4k9#bPkqAB7;cw3rnWgG`KzIGU{M=;}o(jdO?RrmY3JO97U;O`t&DI)Oha0;1lW
zyg%;w4V5_qVbMf49opBW8;Wgz)&07vK*gB-s1A>O)4o$$p3d$<s7UvtqYFngCr>w=
zx5qZxpo~|)JCjcz*kw|q(Kys+oFa*IV(aZA1-i9TIZPTwD2zC1Cd~iyLjE*xY0nL}
zDH9E9O<R2@nIut8tSPx?5u>Xpw>7}1-X4qS9F>fpY%1mStY`sF?`9px#?71R%~YzL
zyhk9qgKaM9CBBz+AS)@il=zh7lq7w`gGmTy8HtpMD1@9b@m1yU`eaI_HiC~lmHJ>x
za)ruH1)<k23DsWk#qF8D4MwlF;!Wy>%zOF|nHyzhK)Y!CEJ-q%0`<#%#~j<3<}QJ%
z_j1BJ9pADd*`x*5oVSE$O_5hdwY)41)<I#yeVo|V2vPPSD`W`_7fx}L#31hv<i=8m
zvk^~{sOZ*&d4_J2c9!y@-#Xm<c=aVksa=Qb>JtNr5QPH*^%D6|yL>~NgaiA8yb%~T
zCvRM-WmP--Eml@0SHG}rCMZNb%j59BV;Vb9WMk_i0T}@S>p(lfM5>%FgzLF7l#F*W
zbZQRg_J;?f$gU?~|ISN|ptyDfEx&eEACWEiExR5sNS@_PBqR>(5j8<b{T)SyJ29q_
z`M!|&<bCQj+MzL+S0pFYWTDoFT_(`l*=n?Tc>-8NTzNm-=}5Lkdb{sXO8!@7msYUF
zY+X1_3&GZ;@VShT-CXo@exo959SairBbI?n*Eu5O5_wIs+N*1!*lPilyU`mSXz|z1
z@8y}cIbl7&C>ENLT7W}hS`CO{LG}(tREQF+-GqcJ9r_0czX$A+h{6z;q`wa&=hI$y
zxU`Ja#V79cg?(7Lg+KjVgf1!G?_z$KR0?yw<gRsCk2xCdeA%Cv2hUMBazc{+)_quD
z7uaXC*+4bs*W|FAdBS{D;=J({>aFhZM;BWTdTD{dNJ)-0Y|+r*kboB-L@0@4`2<E4
zyy!|tN_?%bv`l__PZqRe=VUJZwCQc$y0)NJ=koKC7P239+tH@^8{__--mGO0R-X*^
z820$kjl<adxdkt`tw&TpRHQ*2P0XuV{OYYz9rK>)OKRL)8fl%>ZpyP;;-<rwa{6%5
z^!dd5_Kc4POtc>}OeYtI$nM`qv!5GMrTiRRFX!Q3)XLmugcx^+vU$7?XPSJ9ZLzsZ
z410T-Hyf%yK90Cch9i4~-!wT-+lY3Jl*D~0NF~Wc%MybN4r=*4OR!v1T-49>@SI)c
z-x;A5e8nZBVDn#y?NW((K?+)WDj4^xh+P_W%fmcXhtG^VEtW{cLyn(pxp_#s;JZm%
zeO#;~F%s(Yi^|d0TWWfx7m+i>I-Qm_TMlpJC@_}!&}nzE@kI7StwX!R^gM4y;xY8N
zXeKLUPAIyO_4w2&x<AIvcE?A+5xQK!S^_EsyH!P=CCRXi^(j{H+a!|*pmheao1iO{
z+>D#uik)v?72j;p?ULP_oXLNhtjW$iuCWQV*s#vk2fQJW1p*dm7a%u^<TI=u#Z#QQ
z5Z=u8he=SaT5WThOxNN5IYnwEah5|L(G<CSfy8dNg~nbHTB*}+{QjF%YFUz;DwV!w
zL%Y4xQ9IXk76;%?8_G}T4@*2as?p`q^G%S=Y%(6DnJ9$c@n88f#sQruy2}k*bIh-8
zOlVPLbS%u3`jJqbC@YBpf(QB|fHy!bk*l$J?N4ePgOC50o##NUJq3>J*S%*sKD4J+
ze(IAi?eI#^s$Abs@O~r2jQ`n{>P;vJ5kdVbS_EgrA-MJ@vg;e)Ql*yN-Y`Bo=X=>O
zI%U?M84MRO9b#LW2l34Sx41ukAHzaU;<SAYkz2NitAcI@6<{4^`f}>!gySPhD^5{M
zgcHs`yLI-tI3t-;6S-CfpzuWN>r&(Hw29cw@mFK5_7&+Te`>KA5U=_^0#%sgG<eQM
zP8vT{hEEo*UZZ>+b~Bg?K}~@4aU&`#!Wfly#O(IB<`}y)p>sq&H9%|&1kAzdiAhSN
zV)|-vGiPC($D-#6<RyFKsrcOjJ7&2cIa}luVZLY|*8@L|CD^*)D6WR<7Ec4lV@?n(
z%(@KhgfGNuaqlVFn2h)hcQHJU%jm0OtQQY1<z5~&ABM#8P0}Q}N1>$XQ#HvRUGt#p
ztWl$au3Y~<%^P4<$uMUuDbtQsBt^ieL<*vVR@b8UXl=nG!YkKwyBfMl0}*G$mq2t%
z#Jx3g>lpj#_c_oJ1!&F)j~HtrIiC|I3L(jhS$D-6I3uiQp6Xm0{%YtS5S+#^ONWU*
zg`v(NFp4qMBG1WQH&@r=wCAY%ZJE5(K4Pakx(Tw9E38SZ_|og3_{zpp{P~4ay_G3}
zLXj0h1$UrVXe2Hdw{nyIWnkr_rItpzxy?;3%DkRcftHswp}7U=;E8-MWqoq(u2{TO
zeDa%2$6Hzz2vqGDuS5Gri?#;rkBIH;Os004lR?ion#y=-ES$A-+CMhTieAKXs!0O<
z=YrQ{pfP^ZZ@hPtevb)<&*9;_J-m3DL`)ZJg;{_d<h`-c6P7e74;Sl2V&^l*zMyJd
z{PRQ(LE9+YE*#;(efzyJ!aMxRCN0${tF~aDZo+4^Xo(C{6u}8`br^dT&I9bnXxBc&
znRM|Dq6EBds$7GlqvjZ?-CoP1rWS*mKHYHV>5}e~VRp=m5eb|{<E%3FYzkIBiP*(h
zxWz3q35bRyXuV?aix*g<_rypB>U1#b*%UlfazR|pR&Xn0M)7-&S8xaB2yxb^v9K7N
z{s?R{OPXB75PL=Pmk>=qq?!GY9`K!4npO?qUv1l3!0cdeYDnD<eR|Z}o=Dxg9*BQ5
zdz)aM%R#U+w&`WAi~Q+-_bvioxA{-kZ;u@?zDa^>4}DJ^?k$pIel8+=W&!0zzOM6+
z)VMaI_f`hR0P{W$_@fPU6x-_u^$b+vR|_=73U_$)g?~Vw<F$mtSG6~1cRLnj3*$Q5
zpAV|E#-G^*`Yp=89n75_Ru-0{ZDN=F-JS?L29|?t`w3+0%XNzXFKBnAUORAHbbH}m
z16YJ)h!;ZOCdk-pO<+hwwA&!D?QJ60ZFT|QT!sZ0NWpV<fff4gXqZyu>vn%j;GQqF
zHJG|ieHC6oZ;OU29m4}p5C*Z3x&rxn7J-`}x?gIgdSwxnp;vAaBCkdQQ?;)R8G{`p
zTS1y(SDF_`TcB4?gK0C2o>L50v@LEY8379=!eW1;*H;SZV}~wf&?ok7tOH@Ibi0AK
zsNDiTOV__hC-$!LXFUk<o<vq}2v6q2*gpu7$2Xh?-_ZcBP;=R<08DL%ppKtRe&Sz+
z$x8Jw2tgRHGxA_e$}f}*s+|bbgH~@J+?4{Ssnf6X7XkSK1J(55*az|<1q}P8m-#0H
z-}LYi<c<aK9oU3RA1?XC(l#Y<L%O~x>bF%e=5+mbe+!TgnO;<h>sEijimJROaNo%E
zZ$aGAa7aP$k>zRh6a2%#rO!b{WElFOLqPCR7<Bmsx`$xX3G{*>3yhwFG#F%i)i*rO
zfky87FfDHxFLr?Gqwv4{6obVq8h8g0{g~J%27j9fMg|Gp8?gr-2u=4^M}v!If0joL
z#bi+L^+9JS1-V3LkUt%RWb5-Mwx70#f<C6-zU=t+W=p@ZI6ZlF%iq%tafM;&BBTfU
z8)^i7rXw}=$u>}zM`mjrmdD9?Yd#nk&y$3|8CYY}C7U$21K|f2*E9=(P?)Wb%GP9X
zHI?&d;8a#%rxT;I<kPjRfcO)?re$2oCTN+!G3J7Y7(1AYIC30KZV*mF+%yRySOj4m
zG)i1ZuwgiRZ!F3^Y`9h63NTVoG$!yxWFDSmd6vKV8wD4HH%KQ)KA5|GpqPJ1rzU8x
zHqfP^Jv2k+>;}^I;Odn547fR2DF`mdBq9Gzpf(&FB$lQ>Vl4((e$Qx8HNOl2h&e5-
z?jy~`o8J!MpLMXeaq^EI;H21ej{oh~{&ceb<JV?kVEV_?%=y3Fv5cQC<iC8<^#7MX
z_CMXPItk;pK@3PDPahE)#gXA*pc16P%0)O|d`cU?0zJkNp&Mb<Z(nimeOD}lO&fUL
zs)!HU-}uIEt4-*E*kIuhV&KfS&7>D3aD2nWm3*Kt*09yRyDpuj2K{5*M#I5!gQ224
za6bqkmDRe|tKKOV5e6usMV~S15~QQXiMs0X^c_+5SXEp_C+KIut}fS~H5n)gmMa{o
zqrLWv(Z`bKjc<bZJ<M366JIcXVZmi}<d)AhhFW4;hD?2Mk0TnMK;CVFs~n^hT1bkh
za79Xo{HE~P_a%G}<V2U%AkJj|`juFTkQX{9JW|M*YGJx4hgs?{o>^)q;e|oCSkPxS
zRiQ?thEwTYWZ^0Q>IVSt6738%OTl89&LtIdib?UFe9`Po@6tRh>Bn&IpzN01dhroE
z#0IG%|G;#h?~I?_dH;3OV5a8n3!F((jQGE8_Ln98Wi)1H)_-iq`04on$A|v6=l+vh
z5H@i#a<l-vv%~Q(pZO;wYhVN54rHV?RWwAXg-t9CR9%z+F8zO}iyGKiSbGpq{GCMb
znMV0{qP2k;z<1B|Z%M(w*#%lg1||jqS{61Y0!DUDW&q2;%=9moLBiR<+QLY{*325P
zgxX){2{;*j(iEIb9DhYW>-QO_Wdbzi)2lCJU@vZBVP+0sG63291t~e3*r*b4{C)ms
zMEsw~XLA7E(S(WMlR@}TM&Xk}`QO_3J3ALc=fCI^WdLXKsj0tEK?5g~zsQ*XpJpr^
zot%Zt4IKYbfV9EC;*3mx6EOc>-2{Ib<nJp+#1=qWSlF5o(5qS43fMYX`~&<|vYLgl
zv$+$1rD10LY{mb*GqW-LE1iv*jo|<H0Z>PP)c-q&Pn4DYlgavfXJh^6n4ROl%4Gv|
zFLvh7zVv_ZY|Nj05uhB#f6o3}j*0!h@?aof0W_W!&?i3Y^U3vmvQGd6@cD~;0+2{{
zDz+A%Ob)^4z2-j+_rJUGC(HGB@07AI{?yYa5vKTW8q4LA^!g7jiSa*qGI>WkV;3U;
zdqiPmVBu&-z(~i)N(X2ng}Jk{Jr_NIkOQD*jt2JT7Di5Vc8+G0e|L2u0Q=``VP`A+
zN#;=qb1^Y6F)?s3aWF74aj>vZGcb`eFi`$yq5s7M{zJ|Q836jeo!MU|{;LW9qUQdK
z^>TMKF@<3uU}S+|`1eKtFbgv)fhob?7#kZK2jC|Cxe?g@3uEQvU;wo7e_(8Y3-7;U
zfY_&z{-+!pK;!=nV`F1t0T}PUV+;&T089LLjFt7XgZ@v91z_I)fpN0_&$_U&a<T(D
z=6{!CWB=cBY#i+Wk)N}p0pRL({EHV<vhXzd)Ya!rLeb6+VDwL&|9yc;*qQ=t`&YmC
an+Y^<bpA`bY;2rN%rK;+B69z4Zd?FK!TBNp

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error.pdf
deleted file mode 100644
index 662647f3cdbc8cee6e7eec0dbe4998665c6f9e87..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 76444
zcmV)pK%2iMP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lz6ypkO@*RME3XK;_jPf1e)
zK?4CYaQn`J3<3u>V4OYZWMJptXR~UpRn+cRJniRpqx(IqXHz7LRH;}WtJ2s0{@=f)
z_y0?I-@pFzYx|dN|ITf{&acn^{_{V5{rmrG|N5{0@0Py)`}_a?xA*`3x9$J<Ki@yt
zzy9wn?O*@<*S~xvd!+yW_v1?a?tA`fZT~KN`g(np{CzaFf4=_H*MEE*@&Ea+U;p9n
z+v$@$ztZ*Hk5bF|?q0r2ZpWFv{{Gtj{eSt}{<ksa-~Y?@@BUW*m%snF?SK9IY8j8S
zEdBfRS(fj9T_X52AG_tk#i1JrzjWKL!HVeR?RBSm_4hiW6WYIYIx|MH|DySaysu~b
zK90ZUefe|V*M8j>=Ivh=)|&k|dV%mux0=7xts4lxbj#<*XdwL3Ej5nj>__`g`Jc}3
z{BZX3KfwPzeJl=y_2SBTey4gyHxhp7cD(<4>juIv-Fo^M4TN91)q|ti4zT@)J5b)j
zt3SK}>Cbndy#Jft|Bc0g@XO-zZvTyLApFv8KR!kSVcjiX<vtn-zjQm_ABh(7pY8vt
z9eA&6Pe(f6f1Txf|LYz2+W&k9a_`@*O@f?+Ul#ZN8tu1kApFv;Tpy!>@JqMcKSl%L
zmu@M4$0xvBf6D#00Be6OfxiBM^M8}bzf0rv{tivw3vd3?<(LlcX#Dc?c7E47PYQ%z
zy4Cu9)sXjW{~@>2TUcEWXZ;_L_o<|h#ewk4;?lvzp&JOlbldC4XdtY+UHkWWP2wKy
zb*JO_E>{S9H2;wMZ#h*Tj`}~K?DTS97uvt+i(D7=#c5&BU(D~b%~Iamze%R=GIv7z
zm%ZXZ#`S9&=70Xk=kN33#Q!7OecVAv$dmH$Z=7X$e_Y>ZKE3(h-$(dC4fvC3*3-Bg
z(-a}Cl+&K=vmM<;Sav&_-E5+p2+MA#f1;wB2+MA1_Zw043(6mC!gYO@-#6h;UeF=V
z_S*u3vR>i)U`!X=cRv!=-QFLETQ9WNo!;M}eCtKRy4x`y6L0+i^HV?HFY2${|C4Xi
z_=w+`NWywy@AEJ|CR0CAmK}2{_RrBVDC>@Io$I=d7?gF#y1Vd>j-vd*UgWntKYrhf
zKher^tM+}FW-7{hiQR92Q%6zO9nWN+!KtGt>yB5m``pw~lx4@VUmt4>${&3j-a6=6
z+ErJ(@n<)b_c!=1=7X|cBEI-jM^V-t+y4346lLA<z4ZHsEGX-a$N3?9gYqZ4an$cz
ze%*~fy0Kj8<Leoe<r3>SA-5$4W!*7dA0N=5tUH!6ce2*HL+y7NEW#h`!7!{{zwg1H
zd@E|-Z(mNf*NYox;?|3Vb+>bt5#CyMXfU2dr=YAmzVFuePgzj@fd4JMNBy1uf1)Y1
ze0_X7gR)-YI1~3Jin8w5`iGbg%DUsRe~9^@tUI3d<5L!tKiQ4<ZL<8n8~?x^N0+es
zmFMT{b0z<ldE1=-HfH}mMad_d&-`7x-O@hi{r`<=Pv63~K6Ji6;BSHRmf~@V{&)XF
z%S(GZ&-^uRR9D}}@U_4H=lJUt;#-i9ixvn`XwH38tmRfTZ*^F)%VCC!%}D%#+b;6B
z``C4LP=>-WDAA3Sgh7t+>+zr#&3CKfK5mpfIb}~bN|^>4cDTcC*xQ}rhLJ(A+xJnX
z$2cWVj~PoJlrfv_Mwy;7ZuM`<^c+xjaiSS3UE#umNOA+OQLG&g_IA-^s<D$V6)1yM
zwA>WfV+KY1BcY4I#W=cuw~uxTW))-TKCQqg{enGeP~M__5Kb){1RKcLn9R<5X(YC@
z2!oq%LJ||4a!%vC|7|l;jFilvd`@e!v-+mQ;Uh)o##*^;Q;Wm;^&<B}!v=+iq5Dzo
zhYqh%HY0IZ*Zu~D!@85xD0}*#@XVVI@Yd~*XbtOlj7)oZj4X;)U<dO}u`_We#mKb8
z$H;aJd)H2r(tL3s839L%%^2DaW^dp8cRO<LcF_WgGpgzAc0YA*N(}5rtm-gN6fGbd
zqpEhk<4jcz&UOs$N2>DFbsV4SCu=5^Y5)EFlo;Du+5u~E+Z&|co5X!@I4*_5HXMy2
z=8M9Xtv0&=bdsHfOwOxK);FAk5JwH0PI0su$rhKz{GjYwfbV(|^PBB*ilJTByeVDN
z_kB*^?W0ZBH*9hW9{7%?V10A3v5WH!JGhJULFrn6@9A#S-axW7?b8nU7VbL#J`mYo
z@rv)!dM~hDdhh%s4hoo1eZ$@aZh#-nLE#2e+oLz3a2G55R+sqi$9GW3e>%HD?p5EB
zW@2yqAayOFS-a^m_A0iJdj8$aZo{(U;BUsD1S7^4v}0PhF}#JSa|OpJTDi;Rc1%k*
zhPM!P)mmJ(zg>gEWfyR`JM%%Z>2+;?0gt<uU7W|EYS1<4qGtoC`lE673RoP%uNe12
zJt^RxBwc~rY9Z_jxYx95S0DzZ=sDRR919<RZG#jmcZODNxLX_sB^K`dtlEZRt@o;(
zR~hUJ<tT%Dp&Vs!uWH%uq-?%hn^WjnJ@p*tULh;8ys=%6@zYqo`HQw$Gv?w)PZBVL
zcSYab4Bi#AjBk?w%s7ZSrr~T05tzZG5P{iR+>FHcI>cWB+p^}7z_z5_NY13B&F~xM
zHb`C1aV905!vrpc7MH-Kqz&<Zvj@e5oKs21BY{=>G$CizKFtWHDs;O9_UzM){8WWl
zOkh}uMIXc-#51ykMWF%i&Z2thjQC89q6ayT>ZKX^+y<rTLB^wcX+}d6wYDB(@8O&B
zp3Vl6aj0I?e2gFUoaQr*Pd%sU*y*V*FE@~E@N=4uv7?5_+`Z)w>Av1U0dM++8%jMn
z8EC<|9-PcjgKg}Cvw>oq6&^Dv_9hQf(}S9|iyq^wIHvj7$*9LPpMt@62!?)P<$aou
zos8P2`8X?j%*R@s%83`JcFpF*8IVQ^rF>90n-dF{M(Jw$cu?bE9wZyPX*Q=VTo=QB
zV&QF?k1xDQ!|f+l-lqBZ!X<lQ9XE=<>>U@|TJ_QCr#0~%=(v<t$z9w6jI#4LLq1ff
zoqj3Uj8OCxUnBKS+!6*M=^?(zik6@8BF!6@hCw>`3}2tbFm4fp!e996D2KN<$(vvi
z?lDz*C~g{q!Y%VF2rNfVz#eAp7%mevi%WJfs98IPi$RrW?$G*cmUh&;zqOLi9U6R<
zbnej3D_g$6r2V4yU8${hXx3HAYKL}Rp{(NiGTP(|RN$H<b$Y`BB$sig8Ez$V1}bgc
zr|I|tc3B@fl+(KF{6IOaxP^BpqwhA)50uTiQ**;TXi&IwP%Z1u7DAu+)|-A<B%phR
z7GExH8q`6BM-{&)4FY!!>R`F1xsCN~gM`Cf?ccd$(Cf;@mJK0M-Ccnz6xG|Hm~<@C
zZE?FA6i&?awQ_1+e#8fb^RiRE8HvZKVDjfQIopiFVQeExh;BdiMuFztp;ncU-L6EH
zklfIiiqv6T(*|WsZ*!7&0@I)&l|yrbLR1d4e5N6^v&;BF;sz#6SGIr-ZKiZh#kHBz
z#VCI<wn4&Nps19P<gTa;3Qs@uloEm*T1jcr*?I!QLzdh3y)^voj|geI;{aB^yt^4`
z27%1>13xI_Hon@0flj4eV1op3<9E7H0{ca7w6Vm7Z*r+zV!OZwSpsmi8x$_F;Tv2i
zmfPj845Kv%!DkGqjGNwQ<6GMJc`cI64WHLiczEBG!=H=ufvew}f|gG<>x+RPIwR?+
zK3U0WzY7{cPxaY)+~PI}J08sG!kAlR=EQYzP&ixvCKd_qcHpZ~*!1bj$bh?}QS?-w
zt+edscEw_<^#+Ph7qYw^_BUsW?^}^%$5nDrIMa^LbxE2lK4*np#+Z`wxL6Jfj%|Z+
z$^ub*THRVakN5-?33OZ#bC!Xjx$PrMKDXxIo<ZXB{RiABm?Sbxs<<qUHkXf2LcUxS
zg0%a<T)%x6vgCEEni}5&{|IE-BesGI<REeSxbNqauK_OjSwg(w?w%#Y8*K7MBEe=S
z1>A0w*5290n4cxo{Yq&Bo{7TQq2)7^J-0!qXBjyfWO_b0`^=e1%Hx_jD4f1Y@X<!g
zXC{Tc`5iVN!F^m=v+N)(Yj%`FNwXvW6Brkk5nMb6iAzWdTIK;tHa&eD8t#!9ABW9I
z*?-gU3!k1o7R`s{sl`n&^F!em(9I}Z(5{*BK=}pqO+m|E^W5~}L+I!DZZzE1GOaHS
zceUKK9lN)DjCx@MVRx>Vy@{iZ&A>I(D2;uZwKKc;{>lA>Tc}ZRv?^q|y7=bFa8plg
zo<3=~f)0u=rJg)mx>8hJfwHa?6{0)iPJsx;(XJZFSyZJy*Aq;V!N;arxiuA1I_uI=
zT}o$t@+zft);F)3?<vb1gbS%rc6Q4C6RZ%|j$CA&!sXLQZ14UP?hiZ^3V|)Sehvzh
z-ik{^)<+Sy&z$vDthh2{U0`tg%sESb;r2O5TovvFS>H<BKL-WN!lfW*o<UwejfCMT
z*z-3#B|L>22mL?GEQPRjqd-vL0y;=sY1MRiJSoa$xvwz!W<J(VM$WQiRcP;7_a$6F
zje>PkaO<mEq3sw6V>2T{=B`T7jSq2!0X56~Rbej8DNbzBe2PZre7Nwe`EcQs*5Nt8
z#q&*K%O0X{Hm;q6!iB>CnPo%sYv*Pp>^OApETdYbaMtAwSI<EqCukkaQUGewgm~PO
zCd5;aG$BYAD9<^ZvABF12@~2iA-(`G#pN9>V@#5>w(hVrC0z|GWO9=7QDIR_bazxp
z<RoRJy4t-N$tQ!$=AeKVxNaH+ZF|d;E|j=y4oZRES|Ev&tbl&C9E8lrBs>PEr1;#x
z6~A5j8u4xv$k-&WN-;B2(nS<kN2B<b6jzSZNwp3a$3X!X3UuKlHK#zzrjtjcAebPX
zl85EcY{&<wze%c3fx#!~N?Ty@Nv8xwfvim@Sp!L%q#)tOXcSBlvNoME`<L#_z&|_x
zr7`)<a1h8VI8u{TDBk)8$&XBN4`q_$sKCyWq*E0bRgzpu1@bc;!7GT+q}z0X!6Zr5
zDiERR5U-#Or_jD|i5w*G3Qn{nb*xk^oxG}CdV<n~D`QSl&<czisf%Hdk4Z*X+y{-)
z@F0lDB$W;Kzd->HAs~~qxB_)H(Nw#Y0@qK{tsghOLE(!ClSG25S0Mh947w%zRXa)D
z!{yB=m><O7jl!jar<8t4Dq(>+A<3M88=6rt<D`|7sV?uwgS=_!aO5vE(IhR>lK_l>
z*~7O$%4Q^IxJ=EskqrtMPB|xwMS*!CH8DJ28XXMJlyfpsXG*%6!m%p!kPNvdEfv==
zqxdp#>oSVZIiDIUD6Uc_Dzms_Wo1AYT&axWn~+Zqjy=e@`lrx$Glf}0%TKlRU0jCl
z6z8!*H+cUs5*CG9dy;=MAGa2T7?tMiM(9*!M#U`#Bv3dq#7l;Dn50+Zo-!yDFG%VH
z$tX>uH?%Q0<WFuITRUkX5=qY2OgSbKRBjqNC>)s^S^3?fnJQC^O@t2Cac3)rjy8v;
z@fvpkBY_dn`z8wXzNE_lH2gOOEx#J5*(`~J`;LqGjgtK*JP6S3QaClBlN$+4q3F`}
zB2#qD6hC!#<Jg?S(Q#lh2j}U?8l04*vGrmn4bCHki*}MZFDDHi6b|ku$R32@d8U$v
z_xbG_oNa&66qJ~EzSJ{`L-UyJ8agN#nWt=L%Q&7c4TM7nmF`aAIDY8TrD3uMKc<Vr
z;MAq-);cu`qzzQ2I|YiUE^q17Q$<MFdmPGi=*dCB7pI_!xuTUl3md009k&+TT}c-~
z|730-B!8lULEoRGxz*w!U|@?LP(EBV4~id92*Vq}86?|m;yX&p_9l4~94vfh5Yz(<
z%=(E49;=h&n@hW98<ZTm>t%OMIa&oXrwrYxQ0fVL|Go{oH~k_gx4G}tO*S`*`Zz~+
zSQ#e@yh~!^UcSlZ4efH@oIR^cP>`yR9o=(ug1cr%_(>d#J;ifGIc|q-Pv4(yzmogm
z+;N>li#m-?_D&UMrcCe0W`xAo3Vfx$!WS)HmmVCHV}5(LL754oUGSQj2p9woBm&2A
zv5_y`x@OWbOQS*fY;znJV1vSea3LHd4&{<CUx$`7Q6Rb-+Wcy;-L^?04+2LHO1jDV
zLD_GzK3}lG#wTKs?jMao;n*GQ?BDI9&B6Vg4hjc98VUSbf|)HomZIom>F1RBc=6dC
zl=ji)*cW)$D0YJYAyKW#+Z9_>Np>)9(n-LkD!mY@<RBGjRXl~bT2&poNhtv(loJ2&
z49W@Z2IsIyDdnLn8l0!BXl$o!gOq2DZ4juF@<^3iD{J6}HonhQ2PkXcphzbLXL9JI
zU_*wZN2=_bbZaGzjH8jLkn$WPDWv$`43hM4Fd=DVo`fW|kQ<+*lET%HFI~0J;;o8X
z?ILMz^P0nbh5;*XBZI_CmG9zteOz+}<$lc>6n9kXb~H%y{b{s$%fYstaihYXoN=SV
z_iK=F&EYnkR9ATG8x&rturFs^say>;3g(QRIpa=+Z8+~OU9h+*=Yj7aFS~;R(*atv
z8sPOi58dUl2j?NP0j>apM7sg@;OsIRU=O;i2IP2`)nHIIC$+CI5{x#l^4x<ivw=Uh
z$!NeGkgceT-%SP+^1I1uKz=u^{NR&qT46yMq=Xrh!%Yh(hpQG&4*To5g-vIWCbN&V
zX_&&XKCA3f<S6CWfz*-#pCr2!CRoBQg$YuC9pWGb*un6&L84)bOr)*o5D$wCQ{-X!
z3j5p0D8u*pAOo{3a^zP2o(+AY&1I8U&?s@NvMi!x9IsWU7)AMYic!2(nZCa{rNNF#
zMx`)_Vs0r6q8Fc>V92yMS|`yUN=8wDonq83izpej%OYxb2`AC^i(eExg{<0X9VV}K
z%?7+W7<M8%^dKE>$_96i3wuCY_MlA0?$PuukQaZDXpILa4vIM%*7HFz=cf13KJgf1
z%w{Ay2f&AeLXKwsL7{Kp;B)92K)}`@aXMfH69(mW$jksVw?t-|p4=AsVAQ018_X|+
z0|XTJJ?`WUY~*sIWMqwP;cLmv|B^o@Gk;4?o6JNkId(Eqrnd0@FrQHlqRjLrIgv8+
zl;mj2%sKKK{|1sz$h*MYl#_TtXJis9pw-DOmJfWr!grRLbd!^qfq+Cg;h0=WH(h38
zj9WE)c2)D?x~t~HQ&BY^E*u)4yB7H%&WDGfVm=uypG(%u!6=ffg~L`9p3ux3kesz}
z1PschIw<tja^cM1fM=G;p5eRA2fdM53on`vHk{5#UF<WHD&$MfOrem&IWs>(PH85M
z!g0+9$(Mbx8-3ZC!@EOL_ossn$--=x%mfDb+VjC!5nXhS^ga3OnO7Pf{XsEbfV}>h
zxdVy|cvGgp0j8ZsYyr|v5q_|N(h-rsjbmttG<62|E6^b`xZgt|Ji|5NF<nD34g=>C
zxv7e}U~XyzW^9>Z`HJ2!ibt8C#Yhz_iShOd5%Kg@k26sx2C861-5&v2)KBoq164-*
z@F)~Sv@w%4LS2~2s%RJ{vLa%J6ojgrI0g)Vx3HVcKzD`ZFuyfIcbMO*@SfbEiYfvq
zGmu>oLYD9P#Rwwix+=!VC|O}h8z_u2!f|7qx}upz4k{<dy`g|sW&?9zBX){8un}LC
zJq|rf{bJNPqqH_7<%r{ALTto&F(Ec$!H^L9rFgOIA>|$~#w9e(j!S5aZbM69YiRq-
zPQ5U_F|>`dr}UNv#Mp5}&}GJsE68qR%4|g9Wrm6~ST8eLT=9IKLmMG~mP30X8WFEN
zV#5_VXi2oy0}{!7%JWMrD9A5TlwxK`IN}&H0>TyOXqmQ%S>)?oz7;FEflv?&$pyg5
zr<lvkFl}i8$dvW4O+O0Ib`{z=D0z<lw9Hu#I7Mqm7%Q2;95Y3jX2oFZOU)SUBpxJ2
zoPq}?p(D;UE8JS2V1--j6Rc=!#?&IW7BRQ));2}tT2k$GPC>g&vyH%BrrAdDuTji2
zgaF};h;DsF71f<JQ%G>dAzR`t9t%&9k!-5PTT`U7rQu%Z6bx+?d!#Il?P3_OEQv_X
zW#IK_&w<&Nmy5?9{6WD}sly;qH)6nzvgavI{7sqS$Sp}1QSB~8nYA0?=$5s6T~o-q
zQSekqoo1F&1->(n*JI;1Qd*wk=QE?ZeO!iE%V41pYkfC7#Cn^;_?fXAq5jO;jdTE`
zAQ=H`JeX17Gh^JfJ`;+&)`y`%dMkT@NxevM;Dda|2U@;h-O4?qS6LKH=w+S-D1Kg#
zn9G!`VL89oIpuR0#pcR<y$rB(B!+Ax*+}fd1QpH<#tLPhFex}vRI<f<dxi?9)|8<V
z(?f<zOz$hQWiq3{8S(^@4RoP(cnS|^2Hl<cI>;jaiku#!cxDji1yx>|LCh+S?4jJ0
zD-=`ntC*6Im}u-tN|`a@N@8Nxu@ap!gT_4<Y6A(0PT%~ACsXR`)}Z~@U2{XI4KuSM
zIXTj|jACOYoqXH~YMLhKDRz+Mo=ohkfb4Gg@+jfVD0uL}pL9HzFJe|w9h$xZNox-_
zS87~lxOvr`r{VtKv5p%^c}~O23_w?+9uuD<nJ>3IW&2syvwirL5ojd)k^D)`zh^b1
zG432SgmHq2tx_7p;-mCMW=bo=F*9Pl>KcO7>0IlErtgn#9SmWwlD<h9p5#+fu4eX#
z_HD}MG?ERf%S79m-^tCwS5bJ=8GwCTq?R)8I?_)wL*JF6%1mtJv65mYO(nYyQl9f+
znVKCLvzg)XwM`T9Wp}B|6?Y=#=Q4jga(J1)9eKXFy1fd)*qc-QeUquS;zO&1Vy1XU
z((#}$dwGus`Rb2pLQG$d3FSEp+7iJpe-6!9mD$V3G$CKTBsc@}m6gq8ab<3M61Q)?
zOqbQKXG#Ijl_|~Az>!fNY2+LK<Uje3=5+MT_<m)qXGZuds~v-4eR@ou)8jeQNTAP5
z0#K4Y7dU0&4=y-2B&#d)oF%H6Eugf2a&y84FqRK?2ta_F5Fi6a+4BTMz`dK$3I@sX
zHuh;o4ul~2T;b;sGy>1bgr8uC$!3(M895Mwj9?Y&i@+LmDg)8sO`0Gdc#s1X!YDQy
ziD)J@w5%JPBRU2Ig}pR3JsGAd?yQ2b;JZeo3s1ZEr<{6<bE}|5aE+J=(KTEO*6x~y
z5IHjQBmmh#sSuzZM%n!#2Y=#d5sKe>lk`phk@yLG5ff21HJN;B3sjPezcDLAlj_UV
z3xS;&rTTMDJ;&K58C+=*6|#zvz5;xOayIZ;OcvV&C4rg2(ZVDHfh{nYK>(`DsmD0?
z`m}QA9#mwL=+3^7t?es-Yxp$@Y#aOHT<2Hd-{2dxeE}thB%7RER~4{BGJ-I7q=i_m
zFm4O6hhM;e^|6m+^Cx#b$REsQ2ci)Dj5Q#IaP*)kwvd>>7&@nw`&m4R7dMk)>CWPF
zTDi0MnpW;Ch6TbN^aTJW`vGBxq}f)&4$0h5i8@4&M=iL(2@VP*;6*`U2{@_D^q3xE
z5lX7xjyICV^n1uf=&b^`nklCq)B+;Q^)iQClL-P!m!P&XGjD{(HB<BpTcRMn2Fbv<
zQgFeMw`5&_{uj_;Ger^*A!!03qaqnVWpBy^WX2Xo%|ufR;g^Y~c5jLKS>S4!&+yHP
zh@$GYAfdKR1aclKx<KEIQcsz%ezu7u{gbIjM3|%Q9UycwMZeg-0>_RR8G&_oqg?zA
zf%SH+z_0Q>#9bD!UX1OaYfWR@CM)hC2rx3>#zB+kOzG3mzU_V51K;&7pXEg2w!?TP
z<iZ<;OZW=(!*|ON7VXa@P)3d!6rQvsm_~}8BuqxSyCxFHL=<ojITsYl9>4JbHgdaB
zu<^J8^>Z4W6rMVuMhU%gn@Oiu;YaG626u|?^c9yW!fArAeGzceZ>K`!oZ2ypAF*p1
z#X&~*xI!c$h$iuh6b@rY?%1b+NI4ppXopZxr9ny4bH_P6LSl(fH9e0i5^QQ_#@vyn
z2iwU!LPP~6PKjHHjyykmF!+!d!Y%U1(~)pWiRTbgcAJ_!Q;7E#E^SakHG)C*2-S$!
zQ_KQaQz7Kelo-g4>d~fwoYLdW`;GSKQ!gXPD#pCQBkok7oUr>=2RmR4Nj&6KOeRM@
z%k&ec+!j4T7YAwTHWqcZnJedQ(V&Pg#>!I}<U#85_M9PmycKV}ZRXkU+q-#i)qGBz
z5~mB4c#xg0a~2&Q-FKeT%WB8;oJ0i)AsEJKKhNpGAkZ|*cjlbMf>S0TV6WbJO*1AX
z-bLf(EEq`n5Cqpgtw0n65W76N_UV0X2o9X&(>03)QsP~8&%%|am(>K_HOmDPkJl_1
zNV&<~E1V}2Nw4!bsn;wgj4+D{JE&KlS4h(IeHq-mX2C&9$Rs<g*Ca|@qq$~TVu$rA
z{N!DeHsj%|QUvUvUgiD~-4yjYeQB>*nIR>VC_AWEoj>VUgzHYEJgW*<2qzI@TswbP
zjjtIrkZV?DNV&8EJ8)N<lqf%5Eyngl`>TCwQCFMPCQ>Gi&6YjuE^cPMX641tPoLB#
zKQ4V5%#O#bx`5DwU%vBw8q0V7xVI)9$#*>@Oxe6i{o2FU+f8l0j_GpXyLwF565rKB
zu|^`D)AhjiE%XxDy|458c3rq8tt3cs5Aj_)r|W?4+BIDVnlcB__Om))$b8f03z=`)
zd?E84nl5CX@pFA%$Sfa1_ZL#);xT@06iwN}B`mK(a~`{5xfi_jdTxfUp<{J}a=(U-
zY!1CVepfY;ZqDN`WPp57cu#(B%V_$tH(sTgXyU&aGcUTISDUJ$rR;ug*(;i?F?^8j
z*Ze_=+jqCg=INT>FMn`c^hb#Epxn(4BflnTI?moQE&8<SmTA%E{`WMUL1^~R-022Z
z%HR*fO4%!0HZdBQHke`tB@9f(CN>+GoR71C$@w@Nm`uV9QdpS$!8iMoB`zgR*LgV`
zn4FhQ?kX6w1}Q8|NAr{@J;ymW*_WJg%3Y>yt?U-gQ@f>Dg}Kk!)@SQpJ&}fmwoL-q
zjZQMg^|0<amqLJba49TH9VZS#jHby!Ap1MGbWC$`E`=!TU`dFwZp!4KOa|B8pK~|3
zj{LKjj<ZQV)_O2M&DVI~WtD>!rr$v!^AE5pbgcu-Izyd2aHvArI>4^DgB@U3$h!mV
zy5<=<dw4B7z?^HEj~^jPy93;!u-j;fFKNdQj4^4Srecgqbfd!HZ>fHG6HnJ02C0Ey
zoJn${!nrUg2Y)h-Oj2|V{30bmC3PQ0Nnwg|#t%y7Bbqg18pe;5Gz&YRgAmiO^`{im
zIQ$_o4QGH_w)h<K_{8!vr{UkILEuC#ET7jK-^HSY#SOlwlBCI9Sbc~|SF}qiX!+tp
zL;~fvD2ooRvl1C`@X{0}uDJuQL<$<5HYIY$;It{JOcU`1o7jX4r$l}h9EK$_t=y-x
z8HtY4-PapIDmxZDJ4=1Rv$NDf@k^TBr47U1-K8TbmOkYjn>>3<ZQV^4BzR^^n!TmI
z@NkwUYlTO72Zf%}#AQk+gzu<CLJfRJB}KqX!pT;^OX4ymbKy-Y%zJ^yyF^M0oJ&Os
zEbcc)7BW5BzQ%(sTVDjcWN+P^_a%}^TITv9+$H-q%C3(<ffAV^2qv)PY6by(d!H*p
z34C>uz8<om9Boi+eR7u~@}YRj1|Q^WIu$PAM>PUm3U-a*i3qwV%DvbanK9DNf8^FG
zkwbxik0J~q28EQ!kZ6UnCZbwUyf-o;5P(urgtZhbAfj4|v#EG;0~}%{G8y0yE6Q8&
zSeX)O3viGX&rx6)k1Z-v5)7&lzyNGxpa{9?80bWJtH=Kg00QnC^t8w>KnxL33kJbE
zM3|BZ(!!(xIMfUrLD5dR2`%AA9<~w*0`RZ_c43a8DiQ9FKr6sEIKkK-q5X*0Dv0CX
zMmSfAApQnjC`W_~bfFv(F0T4S#C}8QT8RLC_~nXX@8Om!5qpmawn4c^xmgj(rsw!{
zbs2Ampf!HJ7)n<n)E<7jlB?O3;j}9eSr1&)l0$ey(TK=;1pgJp(c?kBfCw=>{Afgs
zAv6hv%>(MSOkwlDgDnv@56D>Jnf%cCS0YXxp^65Jvhyb<5lY0yBOcRWTSRHr=7jOJ
z%pp=Q>_O+pu<wR1!ysjR=%yI)9qeVyparm&Dcl<ou4Rh%#@8w0y_3P^aFB#SBnc6U
z>lix>;BCU?`BB7gnWD1&V-P{v8EjSfM|X&(G6h&eDl2vxGI<J~&i>Shore6qMNfYb
z)9A-NX=7$(XKSpaNV#-iZ9ygdgk#O%ln~)Nw3jjkU%UEJrs!*PnhpXvg6nzNbw`1#
z4d6~cbgK<)s0c#0GcyHXn~<EMuaOg76kA>KP)RR1(Tt)1f8%|j&gr4}fV*OFz8&eJ
zh!AtC4b&{o4cEgW@rIm$!jS7tezh`1Sa-~Z0oIUTQ;4<8ucADqPWe@+n_Aw3;ea)E
z;ano2!sk-ZGC5l!9|<`aC8Dm8r%@v68s0afV4%b2RwQ@eeH$e1^zrRK;q-9{Dw2_2
zQo(@LG|=fQl$?Y!u0&`yl3YrJW+MrvM0j>bR8>)YHXL+@{kF4L!*e2S$KI<_=d>LF
z$T4l_#8bE`A6NND{!+=j;I29&V2q2KIHw;G?9M69raAq{_fT3h9D0VM$G01Ifg(YR
zd?~{3{V1nuP?#eIUB5KFjmXU^5m1i&Ed&4C*{$P2%ztz}9s%atkNkcmBFvBEkb-`^
zk!xlYjFX&K)V_~IR>?$bIc<b4{E=7Cfen9@1y>>f9eHv<L)<`eR#8Dm!W}Ubf0UC)
zoW&n`5(h;q%-B19hmZkSB6J;Df&_K^Q6^zQH2bD>!xG`_$VfB_hNpl&Zh4I*BHRy&
zXMNC+A4zD+ALUS%2zp1JB>^peA{mpYmp{tbEFK1rjLs5a@bGRLrSdm^iXzVmxub@_
ziLs%_Myxz?P)o$hBTv<FJdIlv<Ff4>P4nTxo94rXH_hinL^mqn8L9C>oDUZc#k8np
z4~aZ)1l|&>)JZ;@$n@@*jczH(C@v9;Pq!^$QJvKBAf_Q>E^|6F9z#}8c3(=wI}Xj~
zn6s%%gzz7Sro+<?#j;#++F_uob80v7VVz>9IKupq9!^wQr`TyIiu^~Od8v`w4P#P`
z%x(zk8kyZl;4jP$K-znW>;NRj8wJyWaE^QdB-ocqM1N-Cml}!Prkqy!FOkSkNM5H5
z(N_~1{spU2RnFa8J`2DH5cl_o2m__^S_TY);*Q=8B>x2w5g>o7;v@ieP?(+oID}Fa
z{CdLIO_<^z0V@#8_($LiML7(>XDC%SJYYC%#6<oP&_k(mVE_z*NXkC~j3}P@06+;~
zFB4<J*dR3upcEytAuK4NRNfj9lTfNWA*Ta^5%&3qXc$hx)QW(je}twnC=G3AfMCxE
z%0ay8A0c-TkNQXG9;H$<0{}=tRND3<ln?@2{|HH>R9#VlHbOY;A0d*ITF|of=>iK(
z6C!Fm#g3zV%K$<l4EK+~Qnpfg?M2u{iQEpLt`N`rN5Cv4vONIa0u=BKBxghsEQ}un
zsf7TFA(Z%!pkxYjL^k2g6eWomAWf;#6oFX-)N)WxOn9Q$hb%HnfR97?bEi1RD_YKN
z>6QTE0fah1cAV!@H&0h&tFG#Z3@J)bIZuab$LtYFdnY-+Wtau<P^r>SPYOcWYENLo
z7N)wKrv|<QArVOa=Zj!TcS`p8Q%6ED2?6PU5KK}kRb7OVlqyvhP)<a(A65iJmjsEB
zP^AVu)y@qNJk^d(XlU7ymx2s%syoHlKciFmkq>mL#3LW*RJgt0D82`bNVq8dWY7Qx
z7b*Y{gA1b*hm68cs`%xtz!>wFZKn8jr8dEiao{`ZSgG<SUQjJ>6b{UNyvi4A9Q-KY
z<W9*xd4P^l*h$yF;Lg93I5M}jXk>0HrCm_)2C*)~55rFG1RuVm<!jaz0zoHbN_axh
zNvXP7An2q-3KW7)?i3r@FCT!^^HZn$h(YR=%IgSXP;LZ{%+rCobfxOXa&-+oQ7)ez
zk4M+gLGhs}SFf(Yd1kssZ)kJX-lnLNUCogXw+|9W4lu;_(dNKJvO6@eP8mFrRk3#0
zsnLVNW#g!w8XE~P7MjAUA^wZwlfZF!@GgxL6s?jc@6t#?@dxwVT^uP0KGNa%q7+*P
zTD}xv!|$%3&21MGs`Iw*{1^o(@u39EMcl}p;t%#SS#}7UgV!p?ji5eDV3^(re5#*Q
zK%oX<BV1~!g4Rbk$DM*s*ZCEwtTUxj#}tbH&Np_ZU~r#Z`@XmM^A@nPjfAg&p)FPA
z1ol%?4T|>x$ZYZob9YL)Zcj<nNoPvF4Gkafb|>X&{;AG?>w#E09H^pfLI|Fim>QoL
zgmT}T)S{DrY6n>Hw85!I7f~7x8_=G+o&myfJ6DdWJRLnC*G-2r9a>IM_)tX5({VVR
zd&h&D-j;M~Zb8A5zl1Zrsd-IrDln?=ghC+!244D(05^wl*daFvnLSbRKFJ<<_3i{W
zxKN@Ix%)=oC@uww0Dh-XZg&E?Cw((;THR+CVwq^<cS@V&{q`eAUC4Vn>iCf$I(oFT
zMkX3Lyb(7FhsFWTSwjbfUkw~tVrkt;92|!f*zx+r!Y_Agb8Mc|T)yK&{zC-&>03`X
z+?^r~VYkRDI^IIppyTaM!FL3$S$BbhZTlddP$+Q}bCqUF3hY@@rcgs**0@+`;7*zJ
zHWn)g%?|YpK-fUx*gRHUWAhYsDaApdQrx1Lg0xe#IXKTq=iou$*nUK|Q4AuKX1ea~
z6b{VeacEo|ha+@TZvP?OG$_<fx&62rV1cJb-nqb&dMS6Fcd>>R?_u0%%B!e{aq_%J
zJ&g0?HpD_8afw2$5M8raP6YR`4J6&w(B@5yTNXF5iGu4K^66Regf~Yz`r>j)zg}EG
z>DP-(D(bJyH(9vx?gS3*+g5y7>`$Q;Dk@o&q{}cisU+P;u_cA_uA)V|1Ga=tytw_-
zi5DgU7QeYu@@#2f4V_K42zumXulQmmp0H`KT2I(LSklKR8wd$gCc{hETrlGjHW$pV
z$lz00@u+C+;BS%9g*>ibVG*LAER06(CYudQ^oqINi8YkME=3Pm*skdGf_;m%m}K$-
zH!1Ci<PWD-*wR=WiuShcM=q=qmBvex?T?Q++%`yFQbkfh+tO#tAd6dt^$?CH*%#?%
z3In9OnP8&aKp+>$NnXp;f*F>4<F!mBaf_~Hs@GQznPJJdLv~p3jYcRH@Pn6U3j;5m
zI$;H-PltA5`f$RMjB;o&HnSdD!Bfbo^Lw&b(-jjo?Ll#yxQ^V(>yPU17Mq6ug{@E}
zzXCD1i%C@KkVy6;KZslJ@tcmvkR=p^D(zP&2;nGjUj*G0_LxdR7=``za8memDg|K_
z_S^X>Qe{6Xe{_GaXkWNUxZ-f5u=wBReipKnju@wSL_!qygOw_(zE`?MFE}=MOiGl2
zuXK#6)NrL=RE7O29ix{!-}owomx?b`xU%>ThP#VzvRq=DUia{u(JUU$H3}PdzEN0(
za}MHdn>=`wlXCM(x`r!|LOR@qsB^hZK1F^I;C9q^B^;CdHih$&pENi)S>coO;Tfo!
z4;NlFAG{gN%qaYK1VyM)UuAHM3iC0iLXKT3K;itA%`!a1RM5hWOp7BO%~UAE6-^x!
z?&=LB&If0o(Ji_?GB-i4ajN~4h?|otJo8*BuB~#!^HLPfdS1!s&kxfN#q;<L9izH0
zF(Uw>1GooAYymFdbNGSZ>=mFuYeIxDpww<eIj|Zpq9B}E9yq}TLI5k2f;E35+=6w1
zBP0WrgSRgPZh*wN5pLzFxRI*C6gP6Q*To0%ZM_sX!c|?08{wI~6gR?`^&+<#nse9-
z3o}P#OhLqZQN?83zl)p@qxy3ZR3fWGGdhRmqa%KYHKrrR2X&~YI3U)kj#weqvW|En
z6ukb5m?PH2-XbumAVdnQ0U}uhH=*iw#6PhzHzK4qkRpoeN9DaE(26C%BN&Ty!WFQ!
zshD^XmS#c0aS!_{z=Mmhu!3lDMUEAZ4WDAmipPd4`m8hxan*KWAUHzUN}~kNQXLrN
zE%Z^AZI5s{ly;AZI#z$Dy1xCOKs?J({-}h!BKHbIx)t2VLi7;;SQNmG7(tZ0k0`=H
zV6-0@$v8vKjR7hQ87K^^F48gD9Pn5gqf?|#AdFgJlch;8@7iSwW+@Mif>||y8CY#0
zoW)^_aMRmB@i<@U1r|gt4M0KE(f}HSGy+XW`xc2h2pwIxdq)JbmIj%saMwY}iiq7n
z@nBZgvQ@<L8P8;lEV<5TWJKm}MbXImlrb7vUos#MDFnCxcqpQT2gTwA6iHlwG6VyL
z6MP_jN}B7YidQZG9zsO3Ewb+s3GLznfVmMHT@aBhncCqqV1V`Jr0bfZunQo9B2>Eo
z;8)SyrKhh5_AWg!tY3muVavMd17$cO%L|Z*Bl>($T$Dy(`JNbljuu1bAtD*;EGY?$
zWQ56YAbIS$F3JEJih%n;Ve~xSm<~PE?Sq?B3L@}#J!cO8FTfs(41uCJ>L|U(Kxzp&
zAQCYVVYGd|x=41&IA$}HUdVFEI7U-Pk#=BNN9siJVCpEy4%i~(Uu+=xgdxBXU9BXJ
z!su$|co+f0a4OYvJjf-eu~}EG4mCDvrg!DBaB3Ack*JW~q1Q$^^v*mM&JB95N}mIu
z92qnlNPfI`w#I6rhB>3UqlP)7x}!dMXCg}!C<j<lWCab1XGiIh!btC^Hr^Za_}KJJ
zFWoj6=*<+S(wh>YVluvj6IP$zln6!1(3J?qsX#DCE$<G&oKC5c2oI0)-2lCh^sWLB
zrbq!R9x$#Xv8^y-Jj!l&=+{wXySp(r>SqJ0DH7I<a(P0UH4pihtc3+qrZS#fIdev_
z^|>;>6~H@1;$2~YxoS{%m_(xBbU&1v$J2elJQ*dVfdCcRf(2pdN+>LyskTz3`vLt=
zS&5~eOk4DpauCTR=G96?W|(@ET`QfbwIR-#U8{=6o!Par=5|l7t#TrE=>Ac4n4#=Z
zFt{_pHpDk>177O4)5#W9dOH(pY5DBl;53*_i|V!=pUSBYZD)QhO_QD3v{F@3Zo{)_
z3*+IVO6P#K+P;*JYi;9np620e&6<a=G(<F$X)_XajAEnaX&y)@9<Aej^-$_@VJJP5
zlLrAZM%pFNvY6vM+S&7$iyneBYVd-Q_DPTugM>_KwAxoBVvn|O^B&XimG9Fm+?0WY
z??FHk`7{qEl4~B!BTsq?63Km52vksRdSUQB)7OnKW}*!D0+cW2z;A=#+4Zs%0rx9%
z>5X!oQ@(ux6j<cs+k-s2{+y=c`SmjL98gAt08p43Ad~=mkU=z@(}V~<5ECN!0N!F|
z4+yfL9C^kxC_o_#+=D@J=14bXeu3~41|=KzhCKGnIM}7G9<a3us=+8WJ())i(|UF$
z$`z(0?2@$y^dO){Si7DRu0(M_w1A%23X>KLm!be4O~4gSv3bxRd6WtIqA;IfZwzP}
zBtJp&_Z_$y3TLA*=|NZ=g9027-VB)tAw&<O*z6=hk0Kxt@*h?~z=z;LZ9*6+Or8)5
z$)GsnDqA*Psk=u3yhWMTP56|?woR=}izawVEZWak38_%O0+XdM8AG@&gW|lD4}~cj
z!hbP}2?l}043aTZ4iKhs2x`VCHertAd`!Ay9*#v5QV@=!ol-E`MU!<d>ehYGalY%?
zeGr>wpH^*WQc5XPMFinv6w^wD^HZ2TA~2vqA@WbGniQ@Y@zH@iG)RuZB!LGk;41_k
zsyYbdXr}OkcsQo;6%r4q!@^TCO3M@GQenwA;4*D@QrDy%m<bl^!%&fh|1{c;xFj?4
z(FnyBq6`Sk0-Gwp91K9JK`~UU5N0Cq`peRGR|qozLSM(kWKh_;&Iwqn9DO77mNzG4
zuEN@S0`D3W-yqpyCkl0DR_PN|m{G24f)kr5<SeTFT`jgTNce^Vi~9;u1-x!Spv@F*
zBOty7rZy-u+*-7YChSmJHAV*9R-K0St*&g@qNUeOlrCQRE{AP$A_dcJpJj>+Lek`Y
z-%GS+3_K$>N6tGqdjjWaqeY2vP1*-0A4vh+SB~Q=fc?BB4=YPU0vT|-Q8+Bn;x7uW
zX!C>tVg3ribpZ8IScXQruCD+*oGIL5FP3)g8Yv4@aRbFq*FKFTisowvP5_QGg$8t1
z(gYCX+%B4(9YCT<24T{-toYk0mzvsLld~f!V9S}Jr@E*)&uIa6NY4;8C@OFs)00Vw
z`I>$kh@Bu!u%3fr5T$*34hU7ea)eSL7YC_LkFmpgN~sA#(pCbbG+NtNpqv&KL_O;?
zU8jVWa87Wl-pVrhu*NC?S)<Lf@t?l_<2E$<{XLKO5jt{vKj(d4*^jf1tKC2U)7QUz
zrLX<{zyAOK^J^2&4%_xu?AQ_C6R$#X^ywh`Pug@U?aIhR&goS<%ETf&|Hu4}G^Ho2
z-Dx4AjOd}|nhfl-h;9zYtuK<nS?B44>2R4nO`jW}x9?I7j0NqQR0BJ0jV*iKo8V>(
z>w>mAY4$eP=8_h;pe^JSU{+hqgO%0lHQ#Vs`ie3kMiEBXk8Z^|q8w3CvQDN1@HxVX
zSa31Id{~<>f-pL8`#r>gHaMHJYDv+0=~b}I&U?)zy^8AE@kQyo7aOD3fQ8V)t%X7@
z!b70zAQy$IG<>)7%~4_lWvN*0vl?MxQKj%N_;+AKbxM$IiCLap)SJoSg}tUSq6`YQ
z0<3iHdu2!I?JU0#Mqd;R2+JyQUGo$oa<X!C1gMx4PmH56`4UFS!cy|m*_`WEGo0aI
z#@jII!BrU5+Zj$5W$qac2nqrXt;q;Zy#5L9*NkB!m=Pr^!a$S@m!~tCSvOqD3W^=)
zu=pet&sL|zN-{|b3rf?^y*RusN(n_Dk_`R{9>ttwhflkH<Ov9uro$8r*1gtiv_or4
zst@d041*B45qu0OtbH!4)Xrk#cr7;MrPxR|wrArQv(WBj4KrfArQ|KsS;D|b1t+J-
zU_({Lq_nY<HN=(Rb+SNs6QCD9rsE7T_YfD3M2MZadcCy)@S9|DvAkg0q{z8Pd8j1J
z*{R5RWVQRNMd7^>)cjsNyWPrJ7rl?n8fP`;sQe6s2^Ll!q}|_pp9`$9tQG8P#8lFj
zVj;?1O{G~0fm6NeY4a{DBuy+I91Bz$^~>yrTAou$Ou$n`SxRq58OlJKa_Jp~ZQ!(>
z%Ox7G0zrWV`v^4vKR65cA)s?EnHN>)gp}vsuo-I5rWRR{KtbH@HN|W_b5SoLJ^l!P
zbFOp6qDV;@fGP$R=!&fF6J<SEWQQd&K8x~raU!1r&T$jMI;)QaBxY1M;gD9jua`hx
zjT#|@bVT)$8DHACcq>6+rw7<Hs5oJRA42(LZG$xRa>|S~?z&oKg2P-ypnP<j(f^IP
zN0de*l>E-X@c`~mF(Lm=fDPk0XCUtqwVq1B7I6GC_P$?F0)HBn1g=1CCSrMt2jwq;
zs`KJY@Xo*n$FU@ydEnm$E;f;}SOn*ax)}i~9Y+Qr#%MJY`a<?~_rQcR99X?%Khb&v
zF*h(^$q~fZnOz+_67Z`6C~cEFWQG<cbeo4FC0So*q)Q^T5yvuWo0bn3sUQziAl**z
zg@KOe4&{IiJmeq`@H=;hD-OWm<;)qZ&k~A4-C^F2ro<2@_)kuVQg=d5(w1RCfon$0
z8J^xwWSAL6OTk`&WrbihA}|RWic(%6P57`d?2jy`!MkYov?otsJpUS!=J<-3-Rzfh
zM~Rufme)1KRr6Jy5k{CI8UP|5H!)#pFf(z6d${Ld%%BW`EkLvZ?&HaXmB^}Rtn^2^
z``4VZ9r@!*t0yEyWcEfXHM=p*le!JOhs-f^n=+COp*ikMt&e0~rc}s)urrl`4(^T4
zkfN%Q=J9Fw9N+7n1)O$ex`II5)+wtpl0=z985yCW>@v}o4?3}b^6KC%o$?@a5(AkM
zmbFmkSOLIoPHQBBM`Yy@B7^B(OaPC}A!d;&B_&dR;>N*D7T$E2J{<WkOw-Q@H!lr&
z2E3#&t6W(S%*&EnU<&YO7;IvSlCE9(12<_3_x|#$or{DioEc%gw5$>In;2q+;L}Cs
z-Z`N4ViYMOK$+R1sLG-k%8u~Jh=wFOBBS)0DEI`9yE20R;yUdCX!4P^^CQm9!*yg5
z>$r;sz~{KvGZO0~qD!_}FTXa$8wCcgf|d}WlV!V9e9IiW!Z4JGcsUUOQX^Qxe-t5e
zLgJR^-~HBM`lZV}F>;Vj=M<KpG<|ZzyR7Ro;o)|@5$1;U&wF_K=(P*~)TbxR{e|JH
zM=i$LJp?uN3YRq9I`r1kZE|xf>?p|Mx}HqRIn1yAlQh|IT_3w98>uNhH@j~4qDIGL
zs-qeg4{{T2xIs_+Cf`ko8z88@XtS*CJahee|52{@z4HCXv8Su22a~0%1N`8<?6HlQ
zVi?Bwd4wU@#RKu+oZ=??qkh_OkML5!G<_)HiH7t3VQt^0I&bE5==vDY$<kZ6I{X=7
z3Wl4kXIb&+{Od_pNjMt+!g8rhn1kgw4;gRZdRAppI@}2Z?dQ5pcO)}k?p~30ijeTD
zRroyi?<VB=9|hk;)ni5t<@kQNX_r?wBYZ{0>;j%e0dR)0MS=1HEe&;`ZgxuMZ2^2X
z>e*X-r`a9#HtDtv$-Xh5HWx*a0c<!&Mg$^>^OQ3HXMrN_DT4DPxM8fk1(VxP_DQzW
zo=FQQ>pNxzuCN+<7A^$~iYrK&m9TT<ouFi4&Wf*K;o=DLWm(*;Z!!zAW-)%0C(1%;
z<F`0R$SLo7dCsw;0f*UpZo*_%r5*OL0WoDIM+9W4W=3N7Obh2^zBDsZmjNzcu!{x;
z0gYH<3KW?fk$zBiCPSCSK$}4-lDlcki<Ij`+b1oZyNsg_>IqniFx@c-Ge<<8M>1v)
zze`~~4fADl+bJ!aFdy@4mr$#3GL-u9PT`M1d|N6Z8Gw9}vbcbdsFWr8clWO+-EaIe
zcJN}gF=ilTA;w*Pnv%*X0<$PZDYXk5&ALDr>@K@s3yLhHaZvyhY3}s><Q3(T<@@XB
zOJ(!MIpWQSMr&`;Xsp}QNo$?%^=Hum2c|c^V}lathGSZRRu5-fyf!joBCOp2G~u}m
z`1bL^2!M5XsB+-$S{>#rI9yim4f`X)$g&X25z3dd%6=ixF-tXM&CzYhAtDSPAEL^U
zrE^i$^A0tn=ngM8QIXvQG3{oJ#8uipF#!{d9D%F^zk#tnq%rW55eYt<CgBeed}%x3
z3yX3HhrSJg^l#p=9OeZSEw2I4kHDKixNFeI9DED~ATsfBP_SZCxtpKK3>u{+=mL!L
z4e1LNKz_bZYz5UZRMn+rnOuLuCMr`U<XDTcmF}8tr_A9f1vJ;dhUK(Jp&yvcr_#>Q
z9Q#y29)8m>T0%nhscMz$HBsUYXQQ*S9KxRZ6~<7!XUAMm&2_9>88cxPM_Z=6isOHD
zG&5?MeuX)X$grT8Vk*0-_c&c2SK&2-2-OT+1+LSatWVP@Zr2R!A+W&>tr47u8~MDZ
z=X$hCl)P+I&}kd@Xsr_G0zp-Cm3udZ-VBI)79blowE2w!@JqC{k820mz}i>>eN_Rg
zDEkIHw|z1Ius~10A0rBV4|6`i*!C#wd?B6|N8N)7&&dplplJaDGnp}^`ITxOm<@v`
z%=%N^qgKZykoL!pRDz`U+T+8cG!7FZv_&k(;U8%$o8fm>8ai>ApQ@v<0)>t%3c62q
zK{_B4rrI0IN|IHR7iK~IF}Ws;ny@}hRV7%Z<eCLGk_u@XWomDlq<&;fW{(5+1W!y(
zMoPIGN7QbSy^q140bVZ@ZD9e?5jSJByXAzBydn+VDGp{FnBOPuGY+zS1`Yr}$pm7O
z5m!*OtQc_;fhfM(pU@WpY3im!T1oW^UWAa5{!$zfg}ztEdy=Q{Y6RM)azbbigOa@h
z5(qg5dm!$FPndW*RK>C^s;=7a#A>MmzSxNer<<H0@uaiv0yO$^m5(@7q-0@CeYvjb
z5AariRPpCTsML@`daF{w6HU>fCldxySB{)N0C<_y2OOVViJ+;=U=Fi$gd)&bO^hd6
zKOL=x@YtDA@Fji1!xUK(X*eXfR{)g6DH9M4w^*^lfJ+Hn4Z@NXM$}c5Mv$GL0)v53
zA#x0S`3<bVbHJ+{(|jXCpMVF!`+Cml>MV1oq8^bvuYhpGz?g`@HCH*{abr~#m@mJ-
zD*IQaNEeGT!k{>kpt*h`oma8E^6cma(k`X7B7g|yN!~6t%SdgWh)KIaW?CZ61}rJY
zAni_vRYX=*C8{ZXh*^ALp6HXm?CWRBU}MlNtCFO!+;rAFR4&x+Rz^MpAIEF5q~vzX
zHKB;!Wy4omjpB5aq7qglI5bqF)srt0!|9j~5#jBuy&L&6MbX(b*;Tqpai5j3Qt>_q
zwVH?`rma$TM@Ds1@!2en`;3@*1Z1DO`7@CEoC3k&6;?Lh0h{pnGDL`=2Z7FU#IA-h
zLSz^n|H7=;KFx}ZQ8~C%4;^Wb?2|q6gyD19u}x-6A8$5eK91HDdMVrInSL8-Hi-II
zcN6L3X#TUpj-p)aj_qb}^%3tT*vAnIjIih^%DL_c^C;}OKH^MSjL0wwbQI-ScdR#i
z@fdOcupmEl#3c>N*=sUAw{^#Qvq$@gcMJ97h#rG-imNnj*LBBwvv>Q5cMJIAi2k$A
zj-(uU-4VAjnA0)hL|Kh!KWpqr%8}L`tIYK_+GM<c8p(r>ckG=h)yocLb^(k&*WD-Z
z(2bsh%x)x{%Wmc7U-04X9*4*A{AW5|q8#gvdG=q-BC!9m*$}!-$4jn|w(gj3?h%NI
zo5SQ;FqxU<R7ZMR>bhgTxnCwRA&1ObFd_QoHF<K%x?{SzcV3a<AcxPhn6RHUb*wV^
zEIX#zeKfy9jXs?9ON)T`S9qfOzV5is-YGwEH+R+J5%*seb}Kqat8V+v_2t9eonepT
z`OlI%l5#9NdH_FMYrgfftL^cqHIJJ_CvW#<C*1q#wDT>vyYU`3{e<n39qIpT%Z`9C
zpij_8yn6{BNAwH@sXlTq)@4VlBuJm5Z^G<@eBAVA<}Y@#c3TT3fM3v?>6>u(Z$56g
z|E#eiDJ`u#(l8zGUi$E#K5m2mOz$2kZT;?90ZTe#eY|KdMr&WpEqQ&heXTn+8G~({
z$?5wviUK@e@Di`pVtkJ2I`(b8JCh%el>cmJM^XB^W4XDeUjncQXZ7RJq9cPH>E&L3
z^I$`S>l@6UDT|GEcg(4d^rF{w$257?UxHqtr~Pp&e6$0d=$<dDPW#Pg|57ASc<~>%
z!GES>OiEpgJ$d(CZ+PkcA5j92+n}%jbOfcQWk*F19QbJUdJjT)+yn+4pc_N%_f<DV
zCUjnFdijWOc-#twG@v6X*RmrDWHVl3VoX`z`Lq?f^Ua&H>ez1a7!z;G`p&1V(4BAE
zoMp#)i}#qBQ<hf%ZO6`z^9HRtmN}fnd2@>|dE5+hB46r;u#~p$mTwMVXUyFt{J0e!
z!E&l2!(QsTW13@OUbGTMaLnUI*!rYYGp1&(Q@8yVX!8=1VT9g1ZiD}<t0N^(UUsbb
zDj<&MMU=-WvgdItkaDDspa{wGVZ`$mC*-`jM-Dx1ML}Q?JA$H^(}xj{IS%P1<W2=9
zJ#GfWj?j&SYt;>y!VGeH3FS1xo*uWtf2NmLlxy7)pdVQx-(8qr5moiL75=l#j-sqT
zGH@m_M#QIjkJ@@<j{i(|cv04Oc=*2<1Ljk`M}<8y$A7k~W7F<0JEmK(%uCVm5kB+K
z5!Z|)4NBo^YYnRIjA3)esP()Jo^p#0#YR|l0J=EC;$Bla@LD-wJYAAHq6oXX?1+K@
zGyBU&Al?%*l(xx^jNn^uI6hbm>wA3>9zFv79y&4}u(Km6$_RSs*bp{oY*7f|(-znW
z_T%w406QOk%pB>HrdX)u5taDJ1m()2BPcnoJLX%A<4X>~h<bctLgeD2BPe-o{4Gf_
zlrQrxMnvU9hw7nr=uoHB^}p_r6@LetTBM?{Oll10tm>ATD8K5K&pGJRr+A}0GXg)8
zIYyLg*)jK9OzBHWVi9Hf$Qb`wVMkG}bw_TtzHuepC=2E^#D=1yDC=)rrciAZ2W7ue
z9y>CaHnXEB=elE_V{S3knX+I`zapppHHGh<>yAV_sQhr`<0HuTkvaaeq>iK<>yG4M
z6?6JW5b;At#v1FgFUqm(=oqvNNq!LzI%1R`S!2IS>X!HluezlGgYe5~E;C`l7XMXZ
zHxiatVFgO_)|T^3c<hD{Y+d$9Sl{)4yvjiBmw=BWbo-Gh9ean4q8#gvg@NGHB<rv2
zFj2<F@%(dQE)*VOAOuIO`6DCzXS+I*($^h#pjhA&X`kf?WPfBrv$5F8+iOSleoZ0q
zFM;hcME+qU#?iyPrFLI*+PRf7fdY&q!tWoM;Xm8ek(9N`bw6*x{LcP+c>m*u`_Cjp
zL|MxapspfW0Q{UO3y%8FWQ!)Hu5Ho4KV>e0bM>B`@W@sFnZ7=vtiL`EL8@Gbmts#N
z`{8jr{AZ0FNhxXFvD|VgUSB-5kzMi7kx3Xy9Z5M>9X%}?xf(BrJ&n|jhp{ZZqpQnk
z3eVwTlzPhmc?qpEazY+DGIeA}$Ds6e$2@14yo7G4l#_>UNKEkvtk;yOvU0;)T+@`k
z@^Y-tTSCi2N94VnmpU>NW@!**jdxFv@#W3wGLNhCAMM{<oVOR!3`mG0@5Z^0#$v1O
z7u|ji#o|#aGq#qAJkEf7YR@CfeeRb!7TtbU9ZzLjo#1%8XAV6w92x?<WoihkZs(~i
zB;&`Flk~*yFQPoXki@h!JC5i#Wj4JCm&rt@M;1Wevo2`nh0BInyv&z+DM2_gsGb;r
zpV7G|N?y8vN5CHQv0h(sP8J=gXxh<ZD=#=#ZaH2rAyWKu*^A_`u8yFnV8}zqbju<0
zY2LHS9+^R)Hg;q>T3L78ryMoRbRsNR!`l+N6`7hA-59i#83ZxT%{?RTVLZ6b5q<lb
zQt6gq7a7o#vYrmU+!F2{HzGH^TCd2{TN-QgaeUY#2VedT_DE&@$sQSbfJ=L1X7mZR
z*%>oa7F*#z(@_(puRFF|?xFMMo{jjp75ijsdQEAJOS^I&(RH~7W2Q{Ur){uN(7{^E
zJ9a+uoG<A!yCqOQvf}Ww#BLxg)xYdf5*hJIo_D6)%qJEAArf7@xr$WEs1d;w&zD8&
z&XmWFK(We29Z6Y>y-wuI1IiIW%b8R9$ovG+fo>p_ebo(hRG6RY)4XS_J~GCC*3=P{
zvJCtSh`vi5^G8PPBV+t$H2#Sq(9(yFEnL3UM@%=$W5-h-8+0T^8Cnk=>xcI?AN#+>
zd#k)(d2b^Vc<H^(R;!BX!OogFUHEY;ntX0A<rptLD<hJ0PCRy|+*6Ssx52#{mpU?s
zxve{<Ik6c`nJJ5H@SpAKNXq)<MQu3dO*?DunbeQlQ1A}0BPqwSW4orjY-i1!r~SAU
zzRB#Afg-sa>AYopzl6XRIpB}m;6E$sNXjzsZ=`Y}qx|LIn`J4<x`&P6=N@0P__=V3
z>DM1DpDBw?_MbI%1f?$h`b=L%2K-B)lS+wy++zO~obw{o<z*ScpG>cJw%-%(A2-_H
zu7e$wslR@08Uw|oU-EsZYyDDCr_wKl1hCdG5nEHG0wA_VHRvBV!a_|hbpy=6TH!#*
zDWL~misKG2g2%16z<72frT;eK3~k^e-oXwYNA#biX+)<i4S+<C9MB2A4FRO^xat0r
zVjb98j6gV9MA2DXbPyI>ed0u*8whO`MK}J{q0>(qB3i#u7UTKPnmU5g(y}8eDica#
zX8qD~7n|MH5tO#J-vMQp;ljQRckqhG&9<K@WI0eT)(0Bl&=5y8a50|7F?QqU$>z8C
zxgP{zYk>0;VX@WOLz&qP7#(XZfr#+H?Qpi=kvtwZ+JDASk)Rywj?7tTZsBS9h7<BQ
zn*S(!C$-O2r*=ae@eRIXkUSnK{~29BL0RSv5)T82CO+T|;^c8WY!$kJ(9^mb!JuU+
zpmb?#vz%a7Wc(wguT2wmN{iV!;vJvmaYQBJ>>SZMmUYK+LwoV9zvI6=9y2Bzu_J+F
z)?ZZuDR*9YDbffp^EjUWYG*eRmX~WGa91(rx=|M6`OlI%lCt!9Q#(*L-#BbHXq?BR
z?Z2YaLWET|pN%%b>|nSX@Xqsi)sz0%5tL(n{Y2or!}z@Pr6a7*<7oaP2qm_UwCa>+
zfFO)DQx>E7&$>E-a^!W#bi*I=*XWK&^!VaBAp4<?gfdz>&#BZ$LbH7?C(2?(&)Jpt
zNKi>@?@>(?ev*$j<0(Ck){F`4<n6UJ5hL-^gn`x{XMZj~{%9^QW`vACI>jDZD<Nw?
zDHy_A%RLf?)Qg%VA*CM2$PKo<SKvdfyet3|AvD!X5KIA9^*C0-zOy4J=hEXWVE<Dh
z^|)hUJ&%X{_srFKx3vIIfvXi<JeL9hTs-ewtZOdLXkF8X@LaoR_~||55EAfLTX#%1
zG%&DnqOAC6KTFda?3A_5oSbZTPA>I3urA*@xfI#y24eOS09asdJdWi*E9ywfG5}cB
zD9&?In`X*NYS_=3I)ZX7!>XAXM+`Pd-y161v-Gu}_35;DvBY1FS-N4oO<$PnS7p@e
z!AbWOTwGmu%rk~uD8JX*JPlR*ls%kSbj#pN)Hk_e>(8mZx=5%Nq7T)k+8d7}O~`jI
z-T?y&?{Tc7sRpDEW`tj^5cvkH_fn>B0PQ`F=RcEQUzA@i5#<KkH(koEb=ZOM{uJc^
zN>s&t*34VL0zx&PC@bCEe%93yKw$gY)L&T~d5^om4TkXf?qToR5qAL=S^nk2wFji3
z->&W;hmW@_=ji9BIf_RwMIj**eZ)J6;^T-8k#tRpD1jA!QAB4*#<;Tzq;Y*`ExVjU
zqAcM~sLB&=?j;jeU_d_J%E^k5Oio!l`D(i%O1=cV5EzrsrmX8!B@evB*IbYO@xTGG
z(hVwtuY9zo*e`gb4@3M~Uf%bBz;u(;9TfA?CgneC)A2G&S|WL5q?r+6(`|Y)Wnt6v
zbAPBKD5)$vLRvD45>~{0#`Ju)B7zm{NHEZ4SR`dvQQ|>HW@TW8K3hsncInzFu+e3(
zDQz`H5zPT9x{PTK=+a#sNm(1x3~bJ=e24w@Y)2o<hCQ{U#TwELC>2)vIzy*ETk7kn
zbMTrlSC;^3G(QuF)x8jRXx2wBL~C&lUV-VVDpS9(TY6@@Zj@hKY~vi1`v$Mm_u}nB
z9bNP31!3X2@?SBWgoK=z-I_pZ%`Z1W);{^<jM;_$xCu~k>2fN{V<dFYuZ#d<?!<ax
z=&sG-Ko20W?#m2icc|TmjzHv1vXcm-cWozW#|^mmWd_PSl<!}66yoo$j-)Ij`3X8j
zT;P`i0|F`dVMJhb=A@3K9BZf0b;BKgO{l_c?WHDQaaKoCesyn8xW+G<Zv*J~p&Q_k
zi@JgEOK?t_L6cu*pSz(bKXe1uvTpPsl=W*gu>f!RITIec1<TQm@X5<CO`XO|VL;ah
z{_{h}uG7elpp^V;{7?-v>6gb3O_axu_=E_KA%Llucnpk@8ab*j#YZ`I^+N|j#?En3
zBS&??j2Qv@rMR!a#D3@q=<Iwd&Ls+YEjywt8Zv!f9@{oio;n_^Vkp-yDW$E&!+8Vn
zewkhJ4(a_cB9XsuA!-e<!>f+F0K#8pi!HwdiW#DKgryaS248hZH_-8ynIrEo<PRMQ
zoGgczD9f~Gv&UZoHMfrEjq=zrDo3&-DND#omL?`<`pb-ycNF!9js#nm%|Vp4&A|Yu
z<w-izgwX!b;q<M=={P6I>&L0hIPWjP;0E&hLq`I{GtDhZS}uVM+)iJF<21~YGp_t!
zcLMml^gM5`5u7r>ZwEmA%S&aV^*9QOsTR*#K&viBpoozOINJvd{=-OF?`?#VJ23lN
z=m0vHp!zQ}PTyhnA39cTD?1XOe+h-ea^S#2f0@PehT{Lw4Q2?1^a=dGEW5F&r*b5&
znef;Rg#?OnBv@HsnImzsW~UUjYyYS}@X+yK;mIj^guwdCjzq=xl%hP<HhAa&l@N!R
z#Sj*2I&KvbUP{J_nhAg1k);)iOw1~_ur?f>ESaGEzB&^g$4iod=*CJ8>-@f5)g4Bk
zKGk}7=ujjDjTwfqv+R(jiV-g}Yt9uU9y)oMiCvw%y;h?=L5%Q0FSBUgic>svLkSDT
zdXlh?SB7I^lx%p-Wi6gNuxtXeJ-zjqvp(h##WTKMGUWd98mi_7UwRRiL4r}ZgTNAd
zxltZE#?l2xEXooBWz1_X{NYKu_fjAaBeG(Ma=S%Ye`c?1E-dmg+v2U#$isM9Vhr6#
zSo!YF*j%G($;%Ck6XmfZ%bg^3BxM=VPGd7Gl)PkYj+!M89a&997{8*d;c|A?OcAOG
z42w~Q<)I_1wFp&2lr^fz-c*yt^46ycEe{>M2nsq_Yv~Oe6Jf1xj*@Sb$BwML9ix%*
z%ZMx{9V3>HVl{u=Q8jHeqA0(NNcED45o|q<1Vy%HFvMF+Z~|7-arBF*t@F@<M~TQ6
z-daLD%oTco=`m3rJF>J-aE+8T*OJQg@HI)-jq=!$rGxZ-iL!pbR0o~zPOJ1XQ64)+
z=_hm)W$9q0C47>~Io~Lc9eJbzaf6g!P<xJBfg}ggxtC1(>yE0dB)mUS)_8yEx)or0
zsor;#WO^8pm79bHBgz^LChscn<TyxC?&+Zej~W?*)AHN_HtIluM(Sw!1qB)@sU=XL
zMOmXj!(Lee5IbKt%40{W?LvbQWsL@tsS48#V^yvu%40_s%c4s#C`-pr0T@TI6paFq
zUazqA(1As`b~40Tj{$o&k;*z<Hb|KXPu*DFi~4@l`&yRO$md)G%;Dp1MZq3M^U`5~
zP|aFmYn1#Fsv$w=`bWvJhmKG^iy-JrD5Jl@+_flRW|)5;CCwf>(oQA}U)4feWB8W1
z(E~lKoHxp2$GFq8V_fQ&9jk;;5_sjkBHKepsQ5C1MJc!CrEg4Zs_*vV-69IUJ#<4^
zxXx}MtW(Tr#zFBohuFMTlY8jKnsY3tK|)>m6Jb&b+XGB0znCvo&`t$+Kv<hPhT(yx
z*q3QTzZhnRHWX%HYt=O#Wo41O!#eb-uHHijmfovay|wE8+=13<;WO6bMtSVWcPuc7
zN%;kXINz%Oy-ZQN*8_a$$g+V#R~KasI9lnoklqChVp1MEvMixQo+xX*%g%!I5j)6h
zT?DQvq5z*lVO>mZE{OOt?C5)m#D|Woq^Pf_DC@5$1IgqZ7~t6V5{!S{k)dny21V`0
zr8|PS%@g~PSsNuDA4a54SzjF0hWus2FFilN-)G9>h~ZETC~uCq?6|8Q<;yVKqdMh7
z2LxQ@16$x7o|PD6vKGM<6r^62U%<ju95dj_=_pu(O*h6ns4Px9KdNdzbZm-uU`J5O
zx)2ZQ5HX10HPzo-h809{&#I1m!<SG;K<Q@*(3h1@xYY!G=!VLn4C@nN8Pzw~;L{YU
zU{5#7V@G<Kg(@h@8dY#+jE$G4_G2e9-7_a{o3LWZTp9Ic^*!#jQvbT6N~-SaNXim*
zZ?M2ap`tKPy-^-V#K$tJw5DpfuFC*<H7^!+eOZZ?Tcy{B@w^^vU|zF8>@TH&_PJ{8
z%SzDP%E&%+W3gElKOiA5FE2<<Eds@g;<D#@nyh8p)De_53|B$ECv6Qr;!IhL=sy#t
zFe!Ph-ZO$LMRA_<qsHz-N0#D^I#W$iUcZzBnkx3btSHm1gzrN)6#CVbkc4HDe{2Q4
z6UROi9=ma)iGD1?x)4yEYYk(#nX(wqezr%&DV8n%rQ%dmDdQLFgR!vjLkFvUyq^$$
zUI}?6`g*^WM}AqIwR^$jhmM!xlw+qEr~J!SPvw_=z*{}$$MNh}D)I|L`bG2|b8Y9B
zm8`oJd;aTgED0So)0~jj-*ZMD?NRKm+$f9j{AXo4T25IP*X!r4F7?Z608W(05n0eW
zt0O6E_+7?2?NQydepJGK9MOLk)lErRTT1(NtE>G|ee0;S{V*a6a;xT(DC<k&h_2fC
z)^+^-_~YULvA*3v`CV+ZhrY{ha`YSJc@$&-$!?;0;%mDJ5y&o8*f{z}+408_{b#DM
z0m@*<vg3X$V(uf}%bGuq=s%O$AC$qIWydrXNq<?@)M!6;LS=Q8FhzS^!8F~fufL*@
z^R@P;s%*RbsiLg?sjNbI6}_m(jj|Zgf3{De!6{4BBEBTR;C)%4-CH^Nhi*+dsOZKj
z^ljNK-%8W_aQ9;MkK@_Tl&=|8?w9$R_QE0vX>_{OdhE~@e&hmSaAMg3NMvV}`@U|J
z=aKL;8JS4Aekm{x@t|B{t2sSU79;x4qHrfE>taHza(za*@9Rccjc7lUK}M8c3XG$!
z(pk0P*Nw6m(SH_4jFjV-li~;=XO7cyqbx?WpB-_`KslFT|Eg4es#XS3e?eJ|XqW-#
z^kMOib8(Kh!n(Kf%wO-XP2Z2RzW-=7rT3x!=YRV8i^n1d_Xu^36xxi7p$FK&CREs_
ztcUp61n3}na!@HM2<*%Uv$1AMiD8-nPrSv+cBAmX6$A_iLdQ(m<2QywV0WnPgH$xU
zgI3gORiwm&9Hzk-yxm9?%|@|x(4R6>VvdG;<6>jGk+K*9fTO>pa4`Rr49c4!+XpFO
zJ5Y4w$hTIS9(y=MNIdmun?uQ9<wQ_PS^{tcjx-HJ%C26GaIxEsK+Yg1_u$oIrWDQ2
z_Y-N9TaY>t1ynV?U(*^$i8VO75fWUs8!0#Z#!#$ia0~((3HU+5x;JGr(&xbEzZ&?|
z$qveWTstY-jdC0KxDV`E9~w6Sq$tL<(?t|jkj6gtBlgj8jkw&=vcFJVt;Y*$l+7`K
zFeZ=yd)Jsj;gC=Td)JU=vhxS=?4V>~?`Vw!+1oU<BP+qpERD9CaNRyg{D~dM-gJ@-
z^|m*?;B4=jyNj(}C8qG%=v5~TpRQgd?eO{RRRi-EWl!4&DaK}}7@e41r#MH-d)1p$
z>`;_xY(EA?W3wHL_G3||q3w_v3EK|*gr2o<hj8dw>lT4S2f7x7GvTkYwjKp(d*(3@
zLX7OY<Vx=bl4GSc{>1kn<P++-_B4$oip|%wMdw}!C}LRc)1#d^JI_@Rx+Vy2g^U8E
zdk-1aJpWYF<3qT&C}-L(e}$%pv}@upDPpm;_-a9!Z<kh$4_a=LU&N8Tv}msx(n4fa
zq0DiwfwSTk_l>08!3w*c<8XrKG#`I(%*OVqL8#e<#EyMCr`b5Do?2sz+A&SeU<D8E
zhy8x@l<DjG=)^4wO4W++7>XQ!@jU-m&#_%<hjs}VPp#_>tk{ySO{&)F{A#0`W$SqV
zP(`+NZioZkwvcqtFk5HKM6@t3bqjBjbtuHrnigyr;H_y)=X-NrImsCxvJTgU*7W89
z45ig+WM6HSyeY~#A1%P?HVQgi<XY7c2q4a^pO~m`RpUCyOsi-(H;PUG>S4D~s0{zc
zJ!cyTzTh&=%-35qGhc0)W|kX)NxkhK?pCxj83&@UwP#_AI>p(OxiS9FW4gvHV9mFz
zW9YShT9%wZh1r(1FMvyeQ{0piB7P>lpoaR^LLvf3s)a-Za(WAmE%D7s({!>whi?UN
zwpyB|<2(o*&i^tf22IByQ1Fl)r()M+2<f?NGAP;ZP%Rrs#+zM}L1~p1a&!l8LXKK_
zyGjeGS)Lr|`kJQWSlib$ojaN@Y`cR%&g{^X0GtWZ?$3$oIKc45>2y@CtrDgEf<y*5
zhm&j-H;Qd=m2h<s|0>Z618DZZf(;~J7wrk96Sr8>)z#Rncw)2A*HgGN+mDR)Spm6&
z;_K4=trI0%LKhk@(Ze>7_9PS?rx+-=q;3apW|h$Gxa3s`-3>mAtVq_vA_K~V85Cc7
zpQbY-FFR%2SQN@RKL#(~^qBOo9s}XjPl$!urujGzrH%GeNYk2+x9|{L(+1|&MuLsp
zVlD#Eymv_P2<stDwBt^uERF)zKaj->OGwl@O~sEIM0UsZs#bj~dLXxF{)UL<F&jTK
zQcd4?gaDTx9v;6L2v)tY_(v_;Awael?GOwkRk~_-72bim^c-J+bkz=(yh>MP$%ZOX
z-F?%y`;T(__>Boa#Ra}8Uk<kRW8TjTqli%rOQJT*awAnYZTL)c&1@OllGxV#eI`mC
zNX>slMmZ{6mE7)4)e87x`9Tp<qLIF`qD|>8&Q(IYLo=*WepwB|lYKXk3c5A6cQ4F<
z?<j6CM!{U5M==a^Gk?4>Pvs&CE;WO~(V;0RnsZQ$c?Gsve~{NixiFt-S3TGZ18_D_
zhKj_tIjFZmL5n3LVj_093qXP21g|K8{ehB$$jt3WAtt$;ng!Gtr9c<llXBq=zoWun
zIfG3su)=}7YJ|*eer?JnBsDAjgj~+JofK)q-JijkB~1U&%%EPBgEKSjq8u_ssSL}(
zmaSG=afjMaLP7&*wS<HoN?+-k6iWs{PsSB2myph`4-_iS9V&yvB5WXajLYvEi|vH8
zMq#@W(t20z8ECb*x3M0`kH!C7_zg}C5N)zTJ&l5~>?+};xr|Q1&1@7k!E_pGJQbw+
z8DaM-KR94*2+qQkV}?EDBFiLhT)EJ!TU78v#siNO+PqNC#UI(}k(6%mA{8jfxOI&-
zUT(j383C#`kgBp`HLcf<!bn&(zC#w;$C$mS5rnv@%}JVy?|@`)b8}b8+7ecK$(pTw
zbiD+WPYx!klC?)&b)q<3R1V4F6h0rGOE6wTRe6y%-SBBBNwWa}WJ#D!pUPhqzr1Zu
z!c16-N&*_!w<ru%a68LInzO^{Z%)FGaO*D+$*dGnB$EBQmW8BK8q56buFTwiLpJC)
zXnA$VOPhu-fohl;#jbK$61(AJprF8lYu=z>wo|pQ!U`aspt6B<OtslYyW;^o{^k4Q
z2b>rg3jwbv(SkeOn}U{?%{#R?Tx7FUa#oP=Qgj<gUZPQ-0^Icmg)b{)wh)?1V|6ye
z0p1kt997oXft!_7g$)Z#EQ-gsJ;6qhrPs44gzEGa-0}tmau3%$qi87XpgtD3`DFw?
zmd4tIvKZsq7exmL#d&qmEz?|f=R;G5T+Xtsv>jFZIA0VR%KWNWgmG?DxxM)}5S~$^
zk0%g?oD|Jk{Ia-tUB*GcZ7~ZDtJJB!ob!qW8dz1(2)qA;U!Qtm1vq2`a?KqrXI%XI
z$#KzgLx>7g78Wtc`czfijxtR@ECis!iWX{anyt{p3c!c6d}4s29F)qTrdpiyzf-rx
z53qQA7;@u&ddj&GFebhW>d;taas$D4PL~xRYG-~2iHn|fdBK&?C{X`!1&m6Wg)p_O
zn_6%K90bl40zUKlVmSzYZYqA@XTE4BP=+GQ3We(*i#j^xv@dMd9f##4vg}Ym+4!LB
zX(}%|C~j-W_zu^m(Ro0jy=UEwkbs7gmQLW<l<@@U&a!9`Bs>!mjJd6E3R?GStAm2K
zNB1Nor$#Marm3)yr&Br}#B~>UNDdMg4%Iy4i_WSgS@yCT)nAJSciv=uF>0|U4<gj_
ztPeautTX@lUN6_uy2k4xV;Ue;1_ejc)$S~H0QWniV0GDAbh%c_aA*f8;+2Km$OJ7G
zb9IVyBhgyUstZ{T3*z8ssSK6!S@yX~`OKT%Mo^Kgpl#wg<*dtJg`S-0`9NCiAaId8
zKNnI)D#b075u^ZSp@WW`Drbe%lX7V`+`@8cI)0jwG&czNr~|>qD3#B#ZP{fxLjIPO
zm&RC-xk=Yd-1DLY^`O}1Fvi?620NaErQ>F2l%3D9%}FvMmQyu|8`}QrC}4UdUvWBx
z)0sNJ>T~<O6%xOs;^JC2Kfz>e(uEfnyDUi9;ukw3RR6L9Fv>_+PS?zEj!Gw^ZvU=p
za-q{UNom4uZ&3UU71o-UGrYhwlcYoym&KcrG#NWpNqQA-cv;cl1(ibwh3Cp0lIhe(
z3|U%6!VKX$OjNFLor@~#gTlebe>W#_bh4{*bhJ<t9#RvRxtw%$ANRS<35`$iZIU)t
z>a7D*<EaNU;pB!tr}(gBZqYNzTnJF57clFQmCo(8$x-~=egbobuz?2!3nZ_z=E7r`
zaj8qv3rp5?G9S#@klApdBx#BTeqSSD%1QI#*-YdwTFr{ZllzdHsmnuD;KoSOC5!(6
z=M>h6Bt6n=CuabLIKcu7jD&eXLM9oV3k(Sfs%BwXa#^8q;Tjaa(iz%kl0KR*4i4tx
zK6R&XY<qj0#KE22xDjQcN)HN02fJ|xG76L|T!ID(?8c4fPHB9QGXvKd{l*`JeZUW}
z1=fN}ndIiokabdiaVgo1<eQdZt-euw3~I<3aWKLWCnBm*5E_yx&7?Eqk})XQ%M8sj
z!K-T5hpa3Xpl56!r0l=pM#4&vq-sOkzf-z-qNi@K4BUQH|5Z0G9IqR+b9)dDfKLVu
ziY%G5awW%k7^=qQB_~%6%#DU2AjziXy7!&n%dYY=<*Me7r-3#60Ly{Gm=sq71^G^K
zV|n7G0eN;ef*&&7A~GeQ>}ybdv*%LzDxowcS=}-u-c0Ctazne_S~v_<haqd=pm1Pr
zG$Ol`Y<sSBZkQY>9n1_$MK4Yc6`5`nk8jWnlLq(pt|fDNJC_^;jx1TVW7S;1u1(5(
zEKi3BI2=56bgj-LZ~6YDONS#UJRCTL>C!NakAns@NDxvE{C<B9PlqVCr^48CCvky%
z>ZzfF;^TNje;w1)e4+U0&J#F3=Xk^%F$Gt|wmXRo;T-zEnpK}?MUASOWPZ!woOIhw
zxVGLXK2I5s@&4Z^n>YR7;x(NgLJeo8Bn-rdFx=%vYPSa$JqB_hW&T2K{sM|o${NV!
zLgK53D|X^56zzi9<M8hng^ftb?`-LiC`takzf;~^Plx1B@|)?F!bbyev^!<&UQ$l<
zn=-d{e<hNCD>jhEb5mG?P`xANbE1q@rA&Q%w{NW42Km<QDbnEq4meZ%i=K)E18SiJ
z#i09qO%N~p_-f8A<5PGw_Nqq&#k93Sf}pdct3wy8-EPLW_F%!GI~i&(Ibj23u<+1D
zZucF#5&WUfvyqEq6H^K|N<nQOq;5>2J;w1w?`_{v+Hfpw%UE3~O-B|E$8tVeJucg^
znZlu(wOva{2ZD|^B-e;A+BVQZ`wXj8-6{4|g_0Y#>Gnb3KqppEIZzNd(si5dmaZ&b
z4ZZ2!wzF_$@yaCConX(sa<B?VP8HQGDQzt3%3_tjFL#PRcw*glBbb=mgSRFXrnX6i
zowhpT?U18;p{?glvZfzF=78NPCS7-$0FAQe4~k!&_M&rGH8!@@wYB}aJ%ZPDJc5+%
z_6XkcZNqH(6UAGY2QHn;#2pliGPzMWbZ#JUWNtB4x7Y}O4Yr)fdM^l`vN+3oX;64A
z&0-~-GG1J01IfQ#S-i{|oUDXFFX;`*9GtIE=2w{SN7h$Zlu2D>4qvFW06N|#HP|qR
z@wE>Mv}v@c!gCXOO>I<b-lR$S_Ey(>vVYthndui7PT)QJy|sa$TPxbUEtB!PF3V*6
z{)MZs%?Wv7aa|r1UYG9#Hz_c^PF4q_$X<X^PHJ#8Ukr-O7kVxY2Be(uwI;*}4+_S{
z-koQdW1MqVl{2g@_K+|GZMRM^6|q2ORso|y$*?%-F@A_)rrIpOjD|CR%At|Si9=R1
zGUAZkii|k8ix-*&mcm^Rp*b??A-;=xyU*hbRzY82m$?xO>>swpL6P|pZQ2&`;h#z5
zcBi@V)Kl(e*^vTAYa`x_Q{I#vO*feDT3`!{FcwJP%B}^{x3b3~n+()gWR-cG{D;Vv
zRolu6Tw(g&oW$XI?&wR|dF-l2Cnu@~H&$%QQw&o)(=NkaKPcv~NNCV?fCb2rLf63{
z(RIL$qbnt8>*xY!6xpEce2_nxu9GCzz;%+unQ)(w4W^9SwRQXW1s9m*>fi$DVc|2)
zj-R#FnGUh6z0Tgkm~^jX@&tEe`H8&dv9+N<oQb2vFB1D;qO<R5l%w!tfiKp%`<F25
zb9C++m9Hs%Ci?cAum}=~W)S>hE{B?t@Eo#i|M0`bZ-$?4<YLkr$?wELA2ywREMx+Y
zASwP3@QvBC&|5br6+8!QLE>i)o%En@TYAxPae54j8^ykJmKJoJnjScFxRlP+Z<y{W
z53ALrcDE?l!X!;OY6r!=$Y}T^cuyY1Qs@ZY{0H<X<IQ0ry(*(+W<%zx)j~c4K+3C~
z;4xhOAr~`F0u%b=&dyBG%Ty`sL7Wec0+Z~r^oo&ym!&{3cP>k1u+%sYBjBRDf(CdJ
zOpMc=&xG2n;%pgdWVz{eVV0Oe21bRU2r0-+v{%$YMn0JCqxpcnRnZIC6S)-Lz#2V9
z!D<^qKG0w+2UXew5f@k&-Qry*+?8a(Xl14{DYV1t#d|aexWT}txeww__y$x>gv_8A
z@45#ZMUx>%=oXh&#N2KMuw<t4WY~C|R1uy+rcju7y&3e2&%a5CPeIyTW_FHZZkRZ1
zaXFYGW10?ekTFdM9Shm>ZSo-wGRWx=J0QZL?H!DHqDJPKG9GBeB_z#`OGug>PdnY_
zr&f@7rcNCKm-MF=kQ9PdG*tGV6piHjc{2MXGeu?k5uN5x+?af#(5^vgh$HJB!OOhm
zObZLsmUBLJ=qcMzEu6C5=f97SgVeZAxvmS?M8Q-Y2#GOvmh+5|IoLt6=aVQ<k15YN
z!{?ouJCdcfF;yfhxh69)#9{=Q^o*!NQY^+%8X2;n2gTnu&-d7-=)~;#9tvM%Rx|?~
zkrN#ekeLY>MRDqx85o7iSZ8eOuJs(69F7;WBM^YOIjK!CnoN|AI8IbI%tfkJXI!cj
zE5{P^=ue2t&d5|oj4+LwVW&!>&Z>!*mHkkpOLddvLa}64b;P$at2$y}GxHiEP&Ri)
zuR^zBa)Y96nQ9#Yxk$Cng^EmX&_j!qln(oeLVcNQ?V-RKi42Mq&P-$|f<0jN^&sKI
zRK_5amyA@E`NR^fNBdw8H{B}K8O0?d7&<da!O9jg={gJYG%I7F>MGIUv?|gbJP+Fl
zcq-&O?4GP2nPt+nl9CM7CS!|&#JTYqVdPj3oAJ+BUlZrEV)7v=l^US0C3374QJ=fw
z?R|aB4A55&P@TERG=P-ri0d~Bo(gBXk*YuF(u0^{u<Jq2hC|a!N_WW3U&h3A2fk{M
z+sbChfN&fX&Jf{GEOoajy*roxpSHK@wJpc7#OC`~++o$A!ds#wN>c;w2JC^+-RY6x
zNjJI-7%vB1M#J{M_Yt|)(mppL?t6K&sshM*;yse6k1bNvB1v&X*8-UXMtT2hjz}VA
z`w;BUP!eU}mCGb82COIsX^}Ztt4UalTYe^k8|p#Qk8(Iu(|bn=+qf_Jo?vFvTRgm3
zIJNRr(8XV#3cTsVPeJ#5`6(<3M5Jq$^UWK@*-DOCGDF@COIis18`^#NJHA2bW4`9Y
ze~6yx$H%D3nL$Cv;Zt5)QLFUIE0315XWpE9{+au|)5#9kUpg{0-FD&r&~(|Q_k;2V
zg#Wmq6|x2ZR%07*Gb?H|8P$>9DKDBXr`@B3T@G*a+H}!`7ekXlzXPq1@W<=@H{|~D
z8+3!Kg1q9=Z@o6+Lo*+Dj8C^nx<@oUhjh5o>B<Q2_T%hVJ7Y{VJ7b6v_7dIebU%ax
z{P8NRbfHME!wV$3JaQi(=tOJU2VE|Ym3{T}cub&qMW}2#MMn8954XupsaeN=_Y1KL
zM^PQ)oo;%%zV$9gQL+njlzczoexDwvoL{`HDrX-&^24E2?c}h#rnk{|vTFkIY7luq
zDt$bZId4<wB8!=7@{rY6Lk~chkLmK!bnWT%|Kla6L%KFbj@ilDA0EDyZXiwfk_QEx
znEZ|TiQr|T;nIQl0O6yoM(AzKMS?t50<#PdP&3)r1w!tH`QU|))<w<0t@`kiBTTz*
zoO||h{I?@$09qw0xQn%OxTmqLowL2-Nuiyy9o98Dp>IkKNv|)x{`T}`uZZUkclV2=
zyL=oE_)UQa{NXRxbv^i_1H2A*MnE`+dwn?USNgK_bGYM@*Ke^`7!g7i+0Lj4GPXXd
z9SXt)a3u?HREkSbJ7Xynt>p=&a9Hda0zu6%ltLOb@u%94SirkYr|RAnM?t(i|9Zn2
z`tf%LL{KT(J2HZy4`iF{41G|^7A~Lt$b`V=Fc<}Am|HI?wSOWo<^_v;ffWIR>stFc
z>hF&eM1xxa-_-?D4o&Agb`Sz~fD&sbZJh2lI4LgFifNZ+PVL~7W-B_RAFVilfnX{+
zlj+CP`2$8$DPoqfQ!0PL$SJ%%(a{I-Rw~j^Jj*v)C1-%4E2v9+_8F;XuozA1EXKK@
zz%e{JD3C#kJ#masbQtPGvkw4MADV)=Z+D%(^eO622q?l#d_Z~mp`(tv4Jg4Mj$b$(
zDF_duP-LW@Gw7VC`K%%14i4B*+}1j6d`JO&Yl8;}qFY30B6b}mYywyU6z~YaFCt13
zi!nCo%Ls*`C`t^MK^6F&LXG*+4*59kh!=!#I;>=fEcwb)e&Gg@zsZPL(udQ%YUsRd
zj4*dUdQMjj2C{-AJ)y2D9j+7(i{cmeu6Kg=K1|l5oX#JSxG2<lbxcZz1(SlDlq+te
zTzbZHlTzFmy-hkXJ-deV;+FB+s?1y>V9X5GCWW^#?wYX_^QHqY9m6sdT4fuEux8?3
z5!S>!DMQUL#u_ih2q{9tLQ--nWpsE_I16dc0Qa2%_jm-J3S4;T(L)ai4SMwG?<HAW
z5XU5JHCQr6f0Ob5LE)e~L-K{xO-e4b3>6QGvv-E=JKW_m3pV~Faa9--Zag?7<#5<#
zGRtyfa6)ySyJ0-|%iZ8_%=x3=<b;l`r(f50IFvIp{o}-8Jmu3XIFq4UtV!t<YeXMB
z2&d;zHq(Im-pbGbSZQkFL{T&O5gg#qgH$vIg~~j02MRk!piEl24n^~ypUHZ#m!HXc
zuqTSx%ZsB+$3#>d1pxived+`WeNxal!;D^!BKyE4%%wTf;ZmVXpA>f509kM;kGT6)
zmzkG-noey{g!*VXqODe08gcK8hnBm1qBL=s!Bu6leNZNaWf(@?p8tL{nSoW$$#y7R
ztVP(@H$pyaX~0>fy_X(M#&*kKf!8O}X{7V%?iBlDezMj6nECvIyq`MRXn(9}QpTg5
z4BtE6OY}m7f#Ad&7U6uAxa|6TutG{~;WPl`_S9XElzFqX_xO~6KZLXWQZb+9bJw#x
z)?#xvVZLIqsu<&&2P^j=P3?jB(Eos9&uQBeIqkVWNt*9lM`5@RzwNQ%g2ARcGAZv2
zA6@)VJ`K4)hI~cYKezGN20<B*Z!||Z9-mUW(9dz&$>EIO4bUGe--Ww+mUYJ9dz}8*
z*g;^6@k!757%%?*;5A>%=G2H;No{6`@A=>~DeJ*$h~c@OTb-mc3Hub9>v5d0owGMc
zS!V^KopnF<DJkbG+AXhJLqPHEh`bWcsGj1GTyF>RUbXf7ATpJ~^N3FMXq_{<C(M#U
zK@iM`h*;&JGmw&zfh1~Hd6!3l5PgWFJuRy~^afJ+h7MtP;LC?_)P~rpt3DKm*r}_^
zZuTG@)givcWuH}tWk+?0y}RsPb-0Aom6o#XA)C7Z!4ExWwa2(g(ZK+PX+2d|QqHu;
zE?Q5WHMdNAOgky3``9&7Vq>cMW5)B(59Y!;xcWm!V5P%b?x{C57nH+W-WAtFhs}NW
z)M1m7f@LItT{nT;QscQ5l9BOb1eE^9#&~BVC{He~^ceWWhM!y22eZXISvf}*?j+04
zCH9cc{Vg}MKQ1nDw6FQNxWs0jjD+=|oZDOO-1)d9<vyLCu4{{D*>y<kaZ}88)}!-m
zXPqk>E1k}<-<K{<JxYg{+{^3mlKXZ&Z>?>H!-(|cyxK<M9^G2Kr<cjO{i2qbV;ut~
zl&M+o`@zoM0GlFqHXGsLB6jw2Y$q5#)x2)v;S;0V{QiU8f-W!*>V1yDL*bc&sBfDz
zPqmdjEmf;M5=U_fa!Un8?SxF-q+>F%mHDP<U1%|a`mkE`p3QKS=Qrz^S$d>A;)Y-)
zd-Of-OpA27&Q&nsvhgTj$5A7VGbV?N##CPRG#tgUG?ap;?YVU3A(!b%$z^J?q-B~c
zS<!L<+R@UO&rAC7#Qe919j#_=vST^R`R~V!gcP**xz!^f_}w1{#B8RknVic0upWj2
zLjNw1RyK3k@h(5HB;?GEhaqp~b{G$Ka;}aZHZfP@!4Q8V8*h{VHio5jQ;sD$C)8Pr
zx%7v9Hz!k;O(;c?f=q2#&!lAJ1KD+Ne;BoMGX34C{TiW+-qFT6BNxUpPtQ5r^Ne&O
zbKegd<F8D{rdNR+4G&B_v~0q8ScsjmP{?sC*?O3?_dbtIH-@J36b}a{9bdjIghwP!
zEQIsgq^4%_3tJCvbDx|irIXNZo`xn^Jp9Bo6={@sy$OomY+@qHIYaXa=A<m-Bh98f
zo^5)zbKa0*q~(@^)icB5^9d<FiSm3xijkJ*6H<({JRgxlrKO+g4?X_Si8Lv({^h_6
z^6&5OZJVOU$%=tX`RquvdcXt~<Cg6JG3kP`Cg1IH;L<)HKjL%J`3-hk{VjXqUW47$
zim@2HNfBi><w8ZYBNcDa!HieXaQfv4b5e9HcgvEVUJVt_3vTk+Q0iBD8lOktm_@z*
z8~D^AoFNBIj_-V_vJ)YIZ&g;>gOlX+y!W46q})Ai`$^+(`8gk7F1(Xlc|QHu%#><s
zF&9%BD#9>crqC69wWk|*QgYM2z5Jsuv6hBgQ&5ldqw!!UW=4lLkO+1>&N?&Go=2#j
zRk)8jW<_v-j&bYIM%+t_a4x`BT<Hog_(dF2MR0(Q5ef+g+=m?xGhjn5JN{(MMtxkv
z@FHi&6%0reD@3v+_w$^g1N`$KM|4m-j$zD(u5d*J&G0u@l5*XiKkDd=YYX+U9NYl(
zM?_shL-T%SEoQ<BJN{vK?z7_!)|v4()#iMt%YhwS81zHAh#_0X`%hxe9!cQ&R%hji
z0;p)mM~sQwk4qSW#@g}t>hQa^<KTs-M3XmHpUR^B<AaDVt54)u3~76NT_Ds<U(GGS
zl-g9a@vvz1APb-t(L?LfTcgz{{w(=_;?H7Pj-M7XtT0^1k4)4Ot8m=10GPAmbcF{+
zJMK_`_!%9bE@q9f<KOi74ZDB*W)T>e^GO`=ePyJRgIPq!f+OboALk_iAMLm*Wi;hW
zfmVL#snX<l^dL0Vik*IZikO$)4$2$af_#Pm_GCPn9|DBhaS_7%<_=0jY(YM7nnFYp
zduog#NqDLqzaYfGHaY!V@dlbfbJR+%6E$}{i`wz;!Lz8TmoP5aao!ovl<b7{ZVHjW
z$%GF7zy{li3&8|UmM%2N-(-qHT9q1Ihdf?CPwx4O2<dh_V30n_5JMHuqhJ4^p=0?V
z7}oq?hYj;1#})*Ex8vA?K=D>XHjH*<h$jrDVS~yli>FglbXq{a-w7!~71OpNe162J
z5;8q%$<RL_f*6)J(~3omE8?difvV2)eD`FqtRH$Bwc|sAM^47!x_;=D)2i_N(eLpH
zft08^$_JzbV<P99=M{wG1du%+rxA}5y(Q447Q)pnACvIHX>tgOH_qL!qDa?~cj$)$
z2(HX<0ExtSij($3FP@C02FhN+hx<qH_U8W))*MruZ06RBKyEj^O32$(SFyK@e~*2Y
z&L41+$)a3jk~5+qkjMVv`GI@l!}DX2v*Y=J!&{-l>AzzSM-SWtkDrIb$YfSg%sG(+
zKn|OrG**cfGdjh_(<g%P(Z?yLMCU*9G~4m}VA65Z%>d7&@f)1Ocontd9Ky`uis%lf
zt03eck&%ee2CpA*-P#ce-@LmNqwoixP0fxAE3Q$dcg&<*`6EmPZdQ+KxJx~%RZQve
zb45tmO*(#U4GnQNDmL2jY{f0dj%O=!T$wyl5Hcl#I$|~~LO^nu2KFS8kfh!kkq6B6
ztuz4fDx2lSDg%wsw=fwyZmPzqI)19S#T<7OBt44|mzb)iuDLxMy5_|c>EReD6O`!v
z_@yFAymBg3B(U2QxO^ZlUWDbuC~-G1S*?)TFQR**+|UXoGaO3~i3wsig(JstZBK{Q
z-21#XU3^cr<9vhnWIMh$aFsP1DCLK#Yn3C^qa9Zqq@oPUVk0?S$4?a}_HoByzD+~Y
zjEdx)cKmbTWE_!L(UoJijuR?ust=DHWOHTAS5VN99Ff6K2x8v@mQ~GhJ2K`Ffn#<A
zqs1nIJ@R<-M3P`TzC6wo+o7wchqxWz9_N{@3mrVsO`)_Z(rhDiZun%v<o8x9*GT@U
zu;$ruPhD6cmuU$8^bF#gKgua#tGSy6XoS;#L<Y`pU;=T=V8K5WA;3&=M)KS~QAT)d
zpD-h-8QXDRojjx&Wu$!AaVwfUoliUwSjUc|(Jb7hv@QZ^V8{Jv7IDHr1w66YMsl$v
zQ)kU0I)VL4jz|*<uJZLTHiRALq={6<3<3Q^K_*OTe~4gU;Al{KeWO^EsE<w_x-w8s
zQ{NnMp0OvCiK*k5fh$1}==sF&h-qjU$^=%S;{Y|GqqY;u1lhOj_(cIG5fpHTGqycK
zne1(FJf{%JBq)&i6F<Pb!SvFkZOznkk>80iRTvFCDXG#l#X0HXgR_)Js40~c!nq^`
zT@QvPXYiSr{8muPZe?YiI3bTa*MyR*3|EL(a|KBeY+^=EWE32t?L<cLEP*SSJTmzD
z1yXEDx`iRuj<pjN#l_nR*pm}b<aCHQKX#nQri&LgG~XJToDzMd$o98M3T?!$-(wpE
zrL!IOe4-nL%C$+{qf4C~N{+LllpUR@EI9sJJs&p=3d(mzXowx>HXuWcNzyhUb{xzS
ziTj8Xu*p&pSP?t!Z~%)iH2)8VwfaPfJFp$UImE}Z#-L+afnlzSIAfTrLe_?&Z*fu-
zUaY8Nh8HWE7=#xqnihzlKl}+eJMqQrIOYLM@=i(Zw4LyKRm?HI7_`%7C}poKWtVmW
z#KAhCTzYj`mM~UW29EFFGJG5~<SgSBeNe!|BODy~(0ZD9A*E%B;r^h6wi5?2ukmk$
z&N?U$Fw59fh<g~hC-4)FH_I?hx3~CyV3m8K^JspOvS)6IuAUEt9dnbUDWDxdIPfEO
z{2SL0J6!ak1vnHgz&ueT8%Fhr!id>Bl<2;pkUeK<ABgSj37CcXN6ZIH*|{)43%cYR
z1&6Y3H_Orag8&A!(<Xa;P$Fy(bCM*9-5*NsEZXfB&%Os?fk9&57LPt56B9XNO;@YM
zv+zmjV33b!YpE}8!KKb}3j!?i_zkfl{LPi5_Pc5WEOwMJgDi6Xa^D8*BM-kPiL;ga
zmbedVidK6UwtEO+hGIIIABpK`+1a76WrUTjVpjyTi`^cO0L4H$zmER)6XV~rB-Rdv
zZRXauyIt=^@rB62Pl|p+PS0=h3j81?r-)H}cP;(zDXO8(fR8XB6IfPO8~V|q<Zn7l
zZGQTD+70jnKu1v8KjrP3ugLF|N8<%<;4GT9Aww~TV*6H3ZutA$U|GWH@ceoE%zSD3
z8Zb+Ujrlvu^~N?X^KX=PhFx%OvM?WObN$d;<&zP-v^}~#GkqvxHeciT*!b8y`Plf_
zk`c`Ez07tIW!fK`3%{9XPl|$OQE6(Qh`_A`qrM^Q%Hta>Z{IO;y}VOCef@>D$v2XY
z8BG4tK_h~Wnq98v`09)Z&yH|-)!!Xw^&Dq;;^MW9$MmIe^g6itvUU!8hO~dDNFc<p
zFTSH465r8|_(6>QcLF=dCajfPUct+2J+e4=QLRr|3<^atHc=%=;*CVXp9@~?t)OnO
z)b;3G+z*J?mtr}d%pU)yE<(Ody2yh<osEpQPpU^ej;-~HVo=(!l`B;+gk7&qdItt`
z6fSnurP#6APQ?xm6jpiQo{qXYLUDYWqt6N#5^X?l!%i6L8y`R&pVU3RXdNxm7~<`y
zntZ`J>Z{f9Nugzmk)sCV+3KMxTXhbd8`{<Tq2L!7gKOx8$tzskoJ!<|)l?-*+GE`B
zGhh7PC}0I8-g>x+rmi$x+No;~o{Tn$*Fml}&n08&?FJJsQs{`yu5+(Djp+6yiaN^K
zwsY^yO@jbq*SX8(6Vti>nVoB<>TpQdR)`*kMwnaZ=8X{T@}xQ~7hQ32uo@4lxSL*j
zAUfAqGn`Yr;_`jyT#O$-Id$-DpIY_3q?;w%;4!AGxppp=Na$%*%Yr>-^_T-1Tjr`@
zpIOyp;d;Txo@2n^vyE&Ve4{y*6F$h$GIIUUi_9^f@creOSNPgOOU_QP#VmV2`1+E@
z70wOrn99;;Jo1!p&ze}lhl1E%SDLbr3yfL#lJIT{Gt0kY>)Nr&@c=X#<uD`1D#sb2
z2CC$I)@3i`gmj9YTQhPDb!?ctaaMqSItkv5r>2aGmJ!5`;gPQvGEL?S#j$4cJ>r-=
z&72bU{Kz#E=SR5}Zj{nWuPpL-8h|-g3G&u@*lcOkKUQ5@@Q>w}7J4KiyhuVroKU=J
zJZsTj%vG3Ts3+KjMt8H57Le?4&iSmNyvW994VuL-8qsAs=iiQXoh_OIf02#1N_m*R
z{f2gO&ic~yV2?LGWGt4}BHtHCe8j-4V@sXa1MbZ8=D_`oDPlu-+UV-~`LeOUvhxx`
z^YD2sNn3C}V_<VOK0GVMUn_WF!4$Ofu7N3Ncz2%9be`wsXB$bGuJMP?!1GuHYo{KV
zaQ<E&=b<VOe&%!hA@OmZyC8-#!Q&5!#P}#U?e=jV)F|%t2uF#ZPj*l{Oi}rutmJ#*
zR1^6Vt{LByl^8FTu=Bu3O)e<VNM5Qa-zceNpJz;{_~)gQRu-N#NojoP<Q6<H%uDU?
zg_-McUYN;$<CCc}D4!Q*4&b~nb16DLEu?;H=Y_d3q49Y=<~GZls$RE|AXo?dri_pC
zLT(Kq(Y8FuB3}GCnsJ`pF;N50?#>!~@aM&V-bE*e4xNkioNx3cvPbIWJZ+l9D}sX@
z>;UpL6I{TA&If*wIiC+a0U4n$O4X!z{)F?vCuQBlT7o3F!aS8t8YNs`h^%1x>w~^v
zitK~XU>0qmIIa(-+CESZqtA++6w6a65-u^1WoX)0kjNsJod@;Fy1c|Am!2neC8E?C
zk7_BtjqlAT&+-yDXQ;CWI4ASV-vZ}g>F76N(h@t*^XG2>*Mafe=sjXm6zLd3gpnZz
z74v!~g*;<L)9HgqCZl_Y@!iRy0VQ9iYX`&PMvi(^0N&ZsN8|YmA*^!3J5FzDf^@zR
zQp<Yb!65Aq!OWOGG%2~1MdRapwG_gxlf9hcrymR;+@?ALNN%bhg5+?MrW=Gwze9+*
zxU*nTJnp5uAxszGbr(r1e}pyDZ=Qdy%9z}V(v<$x0l+l|i#9k+)b(JF=)%KX0#Bvo
z&^sd2lwKeuSd;1r{T&2tG(`70@JEB=Lc$}h)1Iqv+SYMeD*(9BTY%V2gKNNncN#nc
zt^)xzx(3v26^}EDS8f@Zi`VZYBnDP70E`%aL`FB_`GrO`g7>S$KEeA8ufD%&&nj3D
z7wQ$mae-brZ3J{GWp0PoK*L0mx=a^Y&bek<Tw(Gh>@y<j1J%1J^8x(bWg?FGT}>g5
zIcB2r2i+BoxO~Zbf$k}|JM`$26;A;BLs@A);+7+nURhHSpw^fR!7{{`DOZ9a#FydX
z+n0dgTy`AP%Hyyp$(gLPLfSW6?gg}$xEyzuvI*hpB?*PAmoyyV!yxdxJuvhb{_imK
zo6-P~KRqQDph~O=GcN<iC<6Yop(5ZvCU@j9c^#Jn6O3N+K&W}b2n?Wk9sdH&7s+_R
z=6S*kHD4YK=6vF6Kg#i}SZN7HaIxclu_?LjbexY$ZxAdlqK%ny_}D;RYg6W*O`<;t
zG>m~WzT#dzs+?IkHH78gG^va#UlwdVf%R`qmdQtl3?53xN-)CrPqKP|^G{~_fiwRk
zmPa@<J`?OMIzsh7S>p-UKRMzDJ?Ewt51w<n^$j9Sl>&ayDNg6}px@i$C-k4<2<Z1V
z=~QMw?VFNqZ3_LTxWG*el4S^sq5!X(Bp<NOAJGSl>)9W!Wk&CSlkA+))8vq5@E15q
z%Mnd2ecFuP14V~zx(}pN+=X(?lg?WD6EK-LLao_JCO+uS#;eq2^e{L%zX$!<bh{d3
zm-1g2nUZcJS-@pVs67Uq5;-|^Wy9@=9ttOa^{K+^5`7v@w(3VMGD?3q-H_<%P}*6&
zA$QKhaZZa)-;DTXCt)(3AIf=iAM}vZePz%ej@OkzcR1Zw2EE@JO7K(E>&9?-r#jon
zF`Y9ygl;(}G(F)2elfaLlyhjO*e&+pBo|eN^X*n4-&{+#iYrK*l_}q0PRpe4F!$3u
zzQbxK!#EV`{A0>3xTu+E1^>>`lm{n0->c8x(=nQxWy+sgJ<y$+qlKU^g{7F}Tjr;M
zt6HJObYy{Zj(c0-@w|@z_~I`xUs9$K{7z2hL4l7sckGgnIp<>GkwFgaHW(>D3U!3c
zJAUy|-t5VD-Vh=W{`D70YaK8Apm=|{=^Mi69anxEC*}Yj%*Tm30Cqg14uBaXqd8#*
zg3_`POpO!8tk4CU6oCh%Q2U8AQ0_nfNw56LMN%*<OPezqfggTj`uxFhP9Ki%D@Zwi
z{$M$$Pl~svrSbL$J2`#SnXf|{4|XzO!FaHv7!_)WaV!uE(Y!nYT^Rjm6b!@YKck2l
zhB$*Ks)ji%o3|`rUKI9YeriWqq1BGg@2r&#9foox`hy{c4>=4me8^#_e;||dMM8|L
zJ^0B$5dtP4G~%XoHG`-sglGk6<&RG9jHANdYk-6}70~u>y%~FD01chJ4h2y8e2rc}
zx88O$mDMKXX@nSz5ncv1YI+6TdQcUmKKSX0dJ;DbZ8KmxLgdDXha+xsZt8=Z+_rj~
z%QVkKWyRitYAIH7Hi`bV?P_%6{B=7)f%sR20D@xbP$+MiFb;*K;7Lzda8|mdA!n4y
zOF%Y|f-fDg2t0X$B|U$Glivw1y`>W~Kbj&lSvW!|bkivgwZTwMG(0d58$(7Je5FoQ
zsZH@N{NS^h$>=4gnR&V<;S4()o{wSsGcuOBG5*~-8IkQ^&Bv&d;*U{hNHEtPGsXn-
z$JklzK|!^CDt$0v`8$O>qJ1!Zd6XDO45bVhb`Hct;dW>U1-^#1I>JM)b0}tP$2GVl
zDxZG$K6z0t7JJ5OI~|j9I?m8w{n2mko}-&SNZf}J%2Cnf4Bl-_?hQ&q5IcU(41Cxg
zeUZYcMeM`&=qV$=9R$-M@dq&`dvr~TbE0xZW$<<dLX=h9``Zr~=uqbG2ZgLL(Bb3Y
z6N#mkQ4YB!4+X3t<nOAFo-?wklC+yMJRw!gOcS}JV4^IOfiv)65xn$4;y!2KK^cLa
zfd|jocPLUo7<ur1^p?}B7k^Ri$H4QGxt|=7M2^M>gJAOCJOLP)PnxA8<>d*ixk)kk
zQ<~+2!V_RTB6zZ-Ll3<uFzA!Qp|MHb)*lqU(K0tEf|5SVk7iazOMNs0ij=er5jc;I
zCc@z_zWC{nhT{`gU{<4drGmE_)0@sA_F{i21ni;oM=KduR?A0%77vY{ljJmFY9uM`
zNQi7kS5uYwk)0~{r)Evu_w+J5%=eEIvDe@^8a{E_DM=|0?j50mulMq4G`@tXJC`W?
zo!~!x{D-T2?En7d|NJQFA=nWFnGRV9TJtae_2Zwft?A#dN%{Q$U$y_ozg(~K>%V`R
zA0^b0kG{W(`f9Iy{N=CL|M1WMbpO-+>gq55eEskL@Rxrq&Hv$F{`-IZ$N%Fm|MT@f
z{pH%<L!Yz0+8kw#dpF+3>;L@YKmPlV|Msf48_)m!FMquXo~QeE+WPqGN5RcG%Q>=N
z<TgXae8KHM{ICD{|Nh6n{9noCL{l$?tiSqusV}$BwoM0r#Ad~d2iZi5p>J>*PxfDO
z`M>=y|4v-CJ(X=wp{-iR>mPo<X0`kwleC|ZNuo5KT>idNpi@;PB2N6I!ib+VREQGJ
z&A(wD+QuG!y|@0|Klc6)|NY00k3A#WUW?nSjJ;y7fAm($>n#1lDM_u9!)x`q+rH-a
z51UIxqa#e;9)2{h{7HYq1Z;b-zjniGQ|(v2Ki&)f)U*};b}j)E*&87aoG#qRA1^Gb
z;Vt4+)8oXK)$W+-Q|pGl|5c@y+N3HqYL{PD%B=UCd=$Sq_ie`}_dlL{`~KXwv_+kP
zjr9uy!?Wk9)u}0eSq-4iQ%xw)FRK9|e5%#?E4{%Wtm&75_<Qre-7WrP@7KR${t+?v
z3{D|*zZ#q&*t@EkqQ8Gx4cCoR&1p~hvKm5PoodSU^JO(e%jF8N{LK{zOvs;n0p<HE
zK+w<`oKQqx4i1lYr<z{zzN~ipr`~S=h2D7OQnhmj`?A_hYX?_=<-bi`dDSUiX69+Q
z|9AyH?(eSv15us94PNiR92}4=r&_ni=>D`Cu&k$=0y}(J4TyqMO%Q`GtL@0BXZ}n5
zo0Y{g`}>{jk58bFzhnQuoyb2wjZ5UrI2DjW<I5`k*tom!lb<7S;;Et(ZC_S{=N{*p
z<!{b**#WozWUv1n=Y0Wk><ms&vM&dh@6L~E#UG>l(`tA7)Z5*Dp*PqgR7>`WuPS-k
z{W$$jGvK#o|8-8aKiTSkhq8kZfEw4ZUl<qST0iu~$H4wvVut$u5SXyKeSI>;E&6dV
z;a2_STCt;;_4VlHZ{PCuxA`YK{_oN5&mDw>`cNKz^)|Y1=`S{4^S|L5f1(C_hfM%~
z51S&Cuawh~R>f0IgfFWhG}x&o!k5($Mdefz;mc~}&KuFGcPQUjg#GaG^F{d12fB~5
z`)z=S^7RM<>iVol!q?Tp4f#<E<*zFxw(wDlgs-dlbDL!88<Stge0``to&E2~rjmKD
z9!!$(^}tpl5+3zL`Lbdy`SN!v9?I7hfjNCt6y@uR@DO@b6y+OhQD5h||9maJqm?l*
z`-4+az8)fQIgg5>d|eUI)*cl_`MM(F)jTSS@@2)qp1k#VDBqF|FCBDRU+t^a_}&er
z+NWdwP`(}_B>tnKC|_4ZN{mNEQNFH-^sbMJqI_M^=clvxP`<Mo`@PkEx*FfQu^=GU
zgHuty9AZPDm4}cQ<?D*TwLU6}@^wYCXQe28T_H0*J?fC~jWyVYwe|Bg_>Qb-8!i51
z6XmZ5mv8WoS|og3Z9dP4EPYv_!+3To9m>}g5iI6WQIv1Yf8RlLem?)-(Uf{!pJeBu
zd_6?OMtD>d<?D*@HF;DN<?D(7;XNvf@^!`8K8dnJ`Oa$W$f!SGjlbiLqf6NPmFLID
z=aKyEmjCI!MucygOkef?O<rtD`TS%f%FjlanHwJUn9AYnYM&l$Ncfrg<I}SZ2|ug$
z{&2(ccNgLQw|TlLH;~1T;VIGf*W>&Aek00H%}MohkH7SU^HP}R=N^CQ5vSax^XUO=
zQTjLTPLIXdJ{|vxcPBA=m-nX?QGQ~-`TUZze(5D=eSXPVzx0x`;E;8yjq(f64-1(P
zWoByhaQW6EtgX@h$*J^rShCmWmmCs)GPut#IqR2Rau(p-4=btv!h^s>SW{J-N}c;<
zwNEcO^Y44fng2E~IrH;N&itj9oZ0PBrQ6Sb9uZJZ1q4L-vPvC~3X#(0%b&l!+RVS_
z)n@+NyxKVM#2S<fVEm<#KBI6ys?Gij4+0L<{Hf;US9<&WlH<ShlH-W4sHX(QTm04v
z_<qUxlNI<oPJD;M{~4Sj0DL((B#1lJlriqhYIpn8+ueSlw}Hsj=gDK;zwi<<knDjg
z!16a&U~C2aU-1q^F4IZ$F}PvBGB^aJIMw?73lA;hv&uVuN#h-#QA*>NP)g%o>@8Q|
zUXRZH_7&J~JAd*G{9X5e&yPDV%GVDWc>#P>Jd|%-?KXxrEq|r_E1UibVmdxpeUN@?
z@qbp!;<s%6uaA7><J_0y`|UdiSw;5B2dfX#PmIm>c>_F1-?6CgY?;3_(r;~7I6FS~
z>mmKb9-H@#XVpXcj(v2;H!8m}((xVh+@1ag4|X4<U$H<wYl`w68|01y_e<lP-x((|
z6g;^-q_3?@i1GHQ`XGJBzO-Xm+0Rd*@2Gn;AU&Bqq_21G?<C2mL;J_a?^^$ramSed
zX^(z8R_9pftiQEf?9apg|MsXKZ#Cn$HR~+4UwG#O<?#>yucqfKVE(o?|37~!S3G^-
zQmmw+n(hxX)gE_ZDqfwsGu9To72K850(p(x>4=FZu}we&`QGnN1IP@wBX_zRO$2m0
zx^gBU3PQ^AS*1<q-5t4x+|$i+TKqHgyz65cxP*iIH1NnP{7f$_clsPngZj=WBr`)S
zyVIEnDTdq`4GKAhJe{ngY(1MmC;O$`)BF3%@@~op6_lBNXFlkcKJ)izKhI7dj8Qp}
zrP+x*Mp_^rywK!hv=2I(!`sFOEl4wwcs>;6W2T_q6!ellJ3bJ(DSUc-(5D<ZfnJ0x
z<N%zJWM)1xZwh)$(54RtTbdES!v|4MNcOV{*`FtCJ{VeQdX8#4Kh6p680#oJqI}S;
z8@YLWF!9@k+&nMJ{`1Pt=~9FYJe!cWEuckw&@&M^c%1P^f)YD#Y;M>6`Uia!*NqiJ
zn7@@r#V)6nWThvrk49HW_^SD!e-galUW8pJm^{L-ki^CZ!&0m);9Eov8z1x!%oH|3
zNRINFIOy99N5W0WPjjIy9}FL~3>$>r&6$5D2-&7#$`}_IE|5Ny;R&vkKIr}Q5&%AU
zCa;EBK`4oZi`<}bX~leAKGG#6lEHX~SsM@O-sydeOfZ`ee@|~Z?=<*kK9?&f7-Bkr
z?K?MyICLw|FEx|7cxSjA<a61CaPLA27w>d2Mi!S%K(Bc(^iGex@CNoyaN<I^9PjDJ
zvL@K(eR9S3=pCO4e4@QGc+Fa1VPpWTwZH+tlyt@pLbkAi0XqA_d)qr>9b~eVD=3(S
z^n>(HAH8zl;F2HIrUaXG(c6UBE`5jVxj=~x)0wBTz>VEIfv5$Z?wgW*msnDI^_3fY
zYm;I$o04nR)N08^Gc{VkKQF(pA11fP<FFtQfOpdXAd9-OC&;31>IuRq407eR%~w?)
z5JtU<d5EK4HEWPZy{gv`NZAm&wHyxhu1&~InB6q2e^JK}P(2=YFOYH%6!jcJsu%U!
zFgV8WDu__w2sHWHS_NS&yz>j)lwj_D)Jo=Vu?yMLZ<N9-+1nDokUR}v_9pZwvJ=Rj
z#-Li|h5%}dfh-CFhino%h6qBHls}E%`X<DRx5;i1Owij@&nbf1RLA)lZwh<KFMU&P
zOf5pdY_l3?Wq}ns+-^#+<EjOb)P@*@OlkwMDhmSJYzp`(ca-v|C<TJ3F}6uTNS#eV
zKP6(@d80#aLGT`L2t&0AIk}8uvMD*Y31u$@@~L&YJeQ0q<gKgcgcUfGtrP?*a%D~_
zh>zsVS#bp^CY-TFN`a(OZi#{nJC4+1yIivhX91BcTxl8#f<U<vGi*w-NA-16lE13H
zTa@68T@anhk>hTc;{#EA{{pW~X9m7fXs@Npdu>vTu&CdT4OGx<$CByWERbx9bpN_U
zT~Q>X1DxHOqygTjwHCxObA_AV6zun#?54O=RQOGZ*;gERf=*o_-Zv%qXTb9$#Sr8-
zQX-*`E9`nfLLX<i^a8VrD>nK?0KeN*=MavHeO@xfk1No5K}sKIj@MEUI^7j=ycCE`
zn<(uTT&zMMnv2;5-WaB1Q<636s-;3AMgZ_qQyL1?z6tSlE4uflq`s?^!Ub^;Hw8Uc
zh(n{ETWX0Cd&RZPB2Y&`07h31<$@$VuGGr~ksVzzxJ!lTvqo*cAR47JaCNB`1u_BA
zrufnYCfgSUrIgY}1$LA2O~BM*>@~%XE)`-;fuaji<+zzndF0A*g?ui^mE#KeyeY|i
zRp$_HX(_&vk`r6ieUB2m#wE<E#td<&2+XA-a)ir4h2~FJ=K2y&)ow-1L6#{-@uuYN
zVo2fw#O|h$Ifyb#O}HSat=p}B91DFjV0OvixItp)Db5svxFE!?Gv08ikZ%e&TrzO)
z6(s&7CcG~79e1(1G%>i0)uoPc8Otm+IY>x11qLn^S1!c`F7}dcl|gq3hUS${l7-Qi
z9YKFf%#SO6Z$VIJXZ+rRNYGyW^pTTYhgd^IX|F?Fr*u<v-h!7bM=aig0NAcryw@h>
za0dH^0IWlO?-KRyg1zPnvRe!hQ8x)^1RnetRkt9nxmPLGmhw<Rb2lM*Rq*<P`0QSr
z+J!t+*xZ7gE}Md`S`^p~A`Q91<`x_fUZrOvhs&nm_~C1v0_PUPEw4)RMqqv?@Tnk@
zzgLNG#QuL#P|7W-d`Kk{3Ty)V#dT3}b_)(kuhPA3L<xNkj!%j=PT>~?rC156)JWj&
zRmXurSk|Hg%pfgmQL7M^wV<>cy)}anl!}R4GRex7q?<p=O>nDcNXjb3JO!dF25v!W
zkJrTCDCX;{^zsZo;)Q2Jpa?diKmQ$UDb{Q;UK<%~wxn9&3L0CWdU%oY4E1DFa8khO
z0B^n*NU>1G*>H&h29Lxft|+nvNvSu5Jx4eeFH*muet8*e6UNFi)NbAp6$7>)vy*2G
z*klcYP$63jl8`w<ww6rd;fl0cpzM0#lYO|_#5O7VWHWJx7pcm~YPu;M<&G*i>X^fD
zlQ>8Sxzg16ZdBhZl5Kc_CJlvumo>n=-xX=nxHkj^BZfp%DAR&O7>-D$S5R`gt7<uB
zPI@qIOPj)3fJ`gO^<4m~azr^Tndrh5<8%{}KbU|E?qyzzx~4=c(x>6k=0z%X3z??C
zrn{V@ltPW96`KOB5E&|5K}t7eucJbgZbGc19;*woQ8<E>UP(#-gVbjvpYU4>G;&Y)
zO$8cH^p4x-o~$0yP~k^+ImVz6q@_a~-b@0tDKV;hswaf(+9Y(9(ope63(N>F3Q9R5
zSH}>A8A<d4DfZ?qy&EO=3X`Uyh;B;khTBof%ZtK;Zc+|LIyQ1U_$?J1wi{Q3(30kz
z%M~HCzy!1@IHr)P;YC3yS(i@TTbAxfa9TPpii-MKkZr*g^>b5lG+mt#$I?-XcZj=b
zc#w)Wb@C3Wc+<?hDFw(EcAS#&@>|L~Y<7N2c?Y!hML{WtC*8fnEP4WSZqoklZYkYJ
zrQo-e?hfI1SMnR8P4P8%Ij+{5gwv(t7I;^+3(=+^o7<%@m$0zilx%4Tyg+HF#Cd>p
zyQP@-lx}xX-!PnJ2I%;HU^!K2%@VfdU5<`Ne&<8+F*oJK%2@ik$DOu_p&*$B$pprN
zK0Wf^7%!~jLtwQ6<N3&h+ZRYZ2y8MB$W1|$(f?57%Yvx=LxC^LK+x8)^ciQ2{;^zL
zS3shmUXL_xjwJ<qSd?%8W{~=^pcLczVwdq%kA@kePCQz6DU~>b&u_M*7mtPs>zdUD
zzN9JREoLbEWEnk5i1c0Z9VbZWIX}fsVAuJ%jwNgK=)j0IX2jW~7@{oF2;;sfXn0_~
zq$+QS=c_EaJ4SB&p-__ranpywNS5JI;%FS~OG(a{=t1G^JNTDqM#S?GQ6x)-HXlnC
z>fu-)X~|>em3Azt$zx)CQj-y>d@Oy*5qW$pDar^m{-Rtc=5~~c8ZVcd!k!m)hSceN
z?c4-Jk}r57-6VFja!66ZQzUKx9~#Z**-6P6@vwf5CAApuykki(##8W%f>Llgr558c
zc~fv-&*$c$aF7Kr(wl<w2l1LWg&pV6H)VHxB`G$+%qsg|Qm+wEc~kP#L$u^gV6WRQ
zxyyKcD+pISgqJUPtRIRWSr9dMOvzaUvK<*5G8<}9WR(V1WT{5H*ulV%1z}t_ffJDO
zY$!BjK`_-ZWvoVI)G=kOMpV<G@R6I6=fkAA8Uaa%B1jfQ79EJZvdcN5uD(Z<G`<1;
zo4QHH$COI$4pyX01M)eh$#UQxOJI*mvAd?M*X~#o=-lpD5t*-jrj*?zPRs;<`m%k3
zKbfz6V#;N{_Sh=drm*vgDTf8y7baY)yDyBA*I-{5WM$yiP1=K$;_eGWfKEOk7N?YQ
zU`sa26`ah1gJw#fo{)S~25JP&+>~S{dKgpcHNtKV7uI5vVt!pB7>sTTjs*ZyHidns
z<a6W{NJ@OdPW>9tlucmokd7`<4RFe)AS`K_7De`)w#`jJs|Gl+K2dC*7bQw5AKmp(
zIU5+0syrbdU7s+bpl%9Vg?#i-p6C7&U5YahC&Q&UPY6es;tUl0aDCAeNpFWsbIxya
zxD;o6w=YVR^1B``^EAHwkzecuQY^abN*zd);ZmmO!04n*Pe?~^XWk(mo!WAuNrtya
zrQ}U|Fiyo61*JG2hD#9!3S~Hr*nvVBE*myrD8psL1`K8Rv0+aLKbH-ALioAV=>)6{
zmo^PiGBPNAjBsJ=$b>yp8oI35b76>*)C)3Fn5?S+iZYxyj<O&Dfw3wp<(tchjkwOk
zWyDUgeFe!`DOX9~JjDNSsLw0^jgtr3!(hgXBpE8O;}CH}`u57BZ3tSmDKWVN+Vw*A
z_Dx_<apN2E1T0Xh#*h{c#cK#*RS-!08bca1@GC<Ysj>*W_eZtx$ve8zN*Qwn4eJjb
zbdyl5QAu~6RAiHc=}oB@6kdA}jXh}C0SMV1Br-6v$iDMq4HDo)1;CgWO{+QRFDg|k
zu`xkmXQ>bbiJKh=nV@mrQYe=DC``-2=FylIenCsrn&5MubxW}rBre<p=SOowhJYYJ
zVaqH6K_LSZtRvEP!Hp~k+&9^AkhDdCk-m>c75BOq!NtJhc=eP4L`{%_r3yq%P_n<8
zkeZ<6fGaRHLCW4LKs7It-Y;t2V1tzXZ3>3R7mRur4lr+P6<6aRV0bl>StRAIAYd%K
zo^8_1Rp{!jaCn`s=k=}}U`Kxy!|NJw<?wJxtH9s{1?ooy4Ch5_Vxe;TG_hb=<Y<k%
z2YCW3z&JrkL0W;v2@?7@4!3Cr8pmO0Yz;%<eXYXxC`fF*aV*Bx;W>?D^cA+Cpbe~e
zCzn-CcXC<PbU$v{75k~nF`JBc?t!9t8{7lDnN_643DV#$7#vIy6N8ITIGDjT;L%c%
zCg?@Fc@M9Ns7Vr5%E{NQij#cZDDEm!*RD;;b#a~-o0Qwoms+0KhQ8GD!W8?;h8E_R
zDqH*{=T~Z5MY^aY-TYOI!*$)N$X2y!DCYO%w1d{jiWP)7RcjilHvy%XrB|6Zt4+&I
z<KxuHd6p)&V`kp`5r$rBe#1e-*kPa#5>Ais+k6qa`m3DS&i-neoq~kHBNtkb$b;dt
zkXBX`m=hG7UkSR2wi=r^4yUR0mPNMQxMY0msDRbHWT<qripP^6q3K30dHdP{LcwKT
zzcyi8e}llrDQg9OkGP^8ZFA-*Yo(&qOzn4phB+8nWd9VlUeW*H{;TSr!q=<L;X?82
zRSZD<3Oir%x)r1j0v5bbjMf0+1chUB4ulURwFHN^#z4tSRqhHJ_`cB>1+O%^S}1sl
zl&=MHmr(g^D8K%(G!BYhX?3+w^p2&eq~zV2-UUj}GLFSU!AszL1(GMjKwz*G#Y5PH
zS}BYNfxxvw7!Mj<D;`^egi{gePG2Oat#;GEC!z7Rrc@O)zE(<Aq2o6RoYJ~lE2Zin
zc%fDb)d0!Y3XwW^wX2mP6}cO)q~&gw>v^q|slwOSN|`!ftF6_tRImpsWokg|D}r&p
zie0^14zz3J#!+?k1M5lBFxidlG;!F-jt+(#YEva3^@D~ZuTp#ltbP{}7sSL7<mBKT
zZd0J34^vlz^K9yFV6IJ_QA`d)5z{PG!lq$hcoeCXVslh6;8|qf&V7czroR6w^LkJL
z$q5pfNtro#XRDPWbKH+=INAxpuXSaKtWaEzTkKF`4oPri9>0QyW2I7Lj$0f+WcDQn
z7CwH0`fFm9t|Wm8qg(~DzZxZL=bf%vN>+jWYr=Y>p~<!j7Ey5i3XD#Wz@-)PL<PQD
z6;ssUD_~$jVq=uAfbwrb&my@5m^5f)wBnQK(&>%jwKExFHHz0Ro!-*$A0%>M*nu57
zJ#aojAP)*?GsJ>XaLFs6+7`m{38(<_1gV3N+o?-^H%eeZ{;T08D>(nAfJN!%M(Nrc
z+NNynO?sp8B1_<ZwUH$<OwlUbe>Do%ZhXJlGz>&afl;`2sqY5iDsO;lyxVru;CQu_
zLqIi(;9kXqbHGvxfHe&gb!?-M?NZo{GPbjrJV^;R%1*q$$M`5bI~8-I?Cd%mjItB$
zq~PoX9o0nlTuH-0X%wCPR{s>8iuha`C8s<BHp%jokx#&;VHIu^5j}~oESnUgZM52M
z3eM%mi$HC>#L6{blakLS^}SJW3fNy;#mCd8_@t;5wttgyp;SajCu#Jp^3!Ql>YI@#
zS8s+TXf8G>E#)MzNgXY*e_lVEqllsDe$b3V<NcuJ7jXrN{o{Trzk%9#8Ev{AGzwk$
z3e<+weJ`41bE6Cu)W0^!(AFOn!B!KeBX96Q1FI0BO{#yR2yHkD8ii<+^4|t85v_>>
zO3~KD!j_^<*8@yykkETh{1qe|1&y*6&IPsc3M==5+HixFcR_8F@}cQ6kRT(FFmoxA
z;XY8YKZC%gQG^|?Hi}<)3)DvO+lt!dg|!upgVMJl4_R#xzO9_jaC$V|1pq2aQm#m+
z@NKu$<4*Z24}{uN{>lNN0&5hc4gxmst;-0&MnTKNs#8YG2cdRclI4R?aoh!oYIZLe
zvFV1;OAZ;)k9K*o8jh>Zn{)UfTp&dyY5tv8Vw2j?DYH$gf2Yh&SY<Xvp-pE5<QfYC
zM@NxuuHjK=o7`(REjNql7SVZgmg_?8EsGo-Z_eSk5aOXXES>2N5mI*(q5y$yRQfyR
zwVV!W0*J1lMR^Ni>tcd}*relk3S!eS(kX{c4z{&Z5L-tv*N+gW+9`ysX%;AiEl;#7
zX%!W5+;v`Z!#`mcF?FV<XBOG)<Yht*3bj+*T2(DdTcbYTQ<lnapmxbptC~T|Qj1o`
zz5gj~e%zcu82c+!?V!NeUk62~ybtQ27&RLE>wp+F$^Jo8u*u$E2k))Md%)nWRXzxH
z<gL|o6BxX;+WDdfg=m%fJ}5-tKu`z8s5}TN9G8Pco5!FWl^ek(C7*R_vM5I@)%=l{
z&Z;b$5qBjRt@AhjB<H_QaX>*Te}p<{>8<n36eMZY<zUd#D@TPoC`sX#PzNus>6wr%
zp&52Y+i%r1VDR!<bqyG_{ibUI8sg}54;Y=}!#!Z|{#vE<4+!5nWLY1SzVb<6o}nOd
zbiBjLPoWNq-|eT6O?j3$yOh54Td0691qBDupzy6}xVw^;TUzc6bwK`BT_6T6$Q4?{
zp#8X>3&fy6rawa+yfw?Ip~95&D(Mn2D5k5ODW4p#4vc}H;1C>?-12JJB#hX28V`!;
zs_VjloUS@!2IaJz8LCrGrzz(G4dc_ZfKyJ>siAs`>8d-1Q%r|X!&RM9y6Q#1DWq#r
z|CG{leyEx1K1rN%<gpJL`lpnZ`$Ki!nyW4mo+7yF6|p*Hu-q4_QwE3oLUl;iqPu}p
zvX(^z*{0?C7CjO;C2P?mfm5=U9PO5>MehTdPy0$5Cxl|P=!W4bRtsH+tJ54^vJ;x3
z%aQU9=}S+C>LW_|Pwc27<=-h*>BUezU4?_f@eOvXPv4zgOVf9V%%Yco#Ft!2L+iY^
z%H3g;Fnf9la0=I=&)?(Pru2f<X)G?h3OH@WMRx(meHShd)l;$-!z=D4<fbUn-+i%f
z=<oB+0vMSTt#oL(f`(a?aeq>_7U}bovb9K`pOCFZF2b9X-zoxP*2xR1yd&zQur0)3
zFgtLNC~0PjTlq)S$y+RZAL^v>w@9a-FaVeA<4O`f1L^e0U;HB7YMilyrO{7{<n)0^
zo+y$Fl=?}5Tx9j16v%}-{Y-%juZSxtxpH!hsFNaDo)L9YB;Qi$Cq?p2qyL0JmS;qr
z6v%XqsFRo7TUP%`5q%%4|D=?@rTfpGMSSLy5?S66k)=8b(bt8{)|(`Se)2XfkBFTi
zJK2`*J}G=}*8w^yeQ)PbD14O^F%onq+i_0JEqUb>Q4<<<C5^+N?3G^xQ-cSIBctfO
zc^3!>6`I0PIVpO>HG+A`Uq!tE%!!fe5n!f}y@JNhC}rg#Q75mpw;ll|<)s`PDp0sV
zIu*f_-T@W`X1F*oAN;E*`MpvyGW^C5rIQaDI$M;Ex1IqOrQ@x40AOo2=|UOPEt$S3
z8R;BR7bWAZcYuZa>s|H4ym()|b(dH)M9XKQF5X3N-2)b{qUrB&ftD+yH-bfxdFzc}
zQDWY_8Z1TczRz44r(Cy#)yS%jhSkWbo(UEO=Y8wsTl>IYa;n(ny%1~hkpOV~P2g0e
zY+dlFs0(nBwRFWuP}N#`AplxxEnXaem0I$vs6aifC1=D<%D$!TuYtbx5U}#wTyUGH
z;UE#k<mK9wJ<)4P|6h3!tR?k-Irx+I50uned;@qjG^5Cl({j1sfKdUE+GWl{O5ROj
z$1_)P$p@q6j4XLzR7~1hF#cm!cbV-juus#!-S?|RrQPluoKb1tl;n+Hw_)#WN}dYF
z9k%FPVYv&Jd@Bq)b;-NJu$?!BofoigG`AbTPD>sZ7Eq@p{|W=rX)R;d1uIW$|7E~A
ztyR@|#nSUrw}d$@`B+$f&Ou?<HMiF$aae{yu(X>fs$k%)h+6}5Me}dqjheOrxwKY6
zDfqg@Xv3bo#c9ji#U`=mhD~{^=Y~y5gTLL`EPL&k{QE*NCSLv&k((;Y>@}~IYc6$~
zB6SfQctw!J*l%;HT8g(NOrO2v;VzM@yn>$O0hX?X*CwGD>muNu0l%~+)NxDj(wcs{
z$laIXGY6Qay(NbVOWj~iSI4P6ETQ-eD#n5X#TAs8);ZKy{=H$NEevO<o4nF2`BPZI
znYt9h+<;M90^M1ta=Q#x;PSfU3$ZE5N`vNYr9=sgl>$~$QQzfcq^XaBscm8nhO8xb
zicN~iHT7FCxv<z9a866!6b2P~Q@~lp_A>Qdf6G?cbH!$=>L<V6b&z<5ctM-QYL?tp
zv1{Ot3cA6~dQDp9FM}`knnfHpFjz2IA?#)myAXD>sOOe;halbjQF45%?~YwZ{oNAT
zwB&MOz%^Z))IrEW>RSe=Y0=@r3Phq@F071?b=)ls_sr!>-E7&jgw@;S7?3aZ0uf5r
ziq|xyfb=QmAs+?7+mv9|ry7QQ^r?n%lU{VMu##<%cZf%KO&bKHAbN)T`f|A{8}9VW
zU0tVulnaId#kAbnaoQ{wuG+DuAVdS~w@W!fYU)<+C}n-vIhN3ShDZ+A3SWv{3>Ij1
z--Kj=I<-{@LLu@D_@qsN&D{V`TKR<qGHKC`BFedVw6_~@Nt?osOYVjx$etl&#*(we
zrsT9XlyXK*9c9)OKN7lDjEDAj3pCNIjDII%`icQ9T5ynf5n71CCFci2Y?I|xliIMW
z^jQOXw7jU{#$8p|a>v9Lu?8XMMN<Gd=S97ToO9{l1}p2L%Y*@Cv<Yl?<cD#q*?}QI
zsebLN3c)s(YNhB|@PRM{0$TETFxaY>JRUYBS8+@Y9FlBI@|S{45V%bUZpQqLKZxl}
z%jyME%%|KYHYLuKG1d3}yQD5KM{7{Sw!{}*LFypnfT&ShVv9C`z2x;_Q_u^-Agv*w
zyaj4#jntNRDOshqyeY{lKTFH{I8X9XW%ET%+3@nR2F>M$=b1HVEw_Bc2?`ob-sP-p
zcnjJj^b5&1y84FX8%<q9^bI*HTL6$Yfjy@gbqQ8yfEukq1sg!4HKbt!XS9YiY((f<
zLmD<7$(C?+mT|r|fjy<Xyfz63ltEw)s@MkMIHXToh{qvq8nB}^gq$(Jj@FPqZ4i&6
zswarYQQ1>UN2H|QpAlXw*Qoe=?&PALAsa{05Fs3g^zt2sZ5P?=z)mjgbzpqb$?*)k
zhGcNQ)vh7qx8Xr|jr&n6xx1sZ^F>MC0!XweI5QGQbOi}#kwMD!r6wWdI;-r}>r<nL
zfa~<3F$C&cUHW#$@>|MaV;K=}Q&5WO60Xh~uXkOlal(F<uy6*{&+0?9Al5pJ-WGuq
zS09=%;2@R|ZU(T#rm)@3NmrW?SiQ5&$~mK{dy{g`q)a!6F+t!qCD`xkIQ7nJ^~RP{
zGhJQ!b6`ytz;BjVoz<!IBJ$7bayK!6cQ%PX@vK5N8YWFzFQ7S_k`r(l@H?wZgf_@5
zA=NAbey&dZ`Yz|pR`lGVoA#={A=SE6=LWGRWSb@MXLYI04d~=e>LBE1kz(9DO8FrH
zr?a}$-R9uzKGOst*P-t=2WR@$8YEn&zS~m5b*Z}zXpUD!@d_c=mimT_Yf^$6WSo#{
z*7EN>;eqT~ZLw$E-r7>v`2nvs)icCin>yhW*0Y3lGvIYrqY8}Ct|m1Y0KV0z24_m;
zs3koZKLGcD4sHsj4sn7v1^pm0^QN#P2)aP8S;BEv8>frhrEQ3Lh`B_4T_ELnhI)pa
zYZS_{8JB=;hVA;Ipp;v*b#)A(*Sb1})N4|wyJ37%r@L{0(x*EFSd)6(ap4oB&EmV>
z<x?lQYtq4ij(w3(O75f_BVhI-bj=c_v&-zHbDPpuZ3y$TnyF_<ux6SmNU#<<H4ews
zDy^M{6Ld8y)xZ(2R@HUf_gYoIxZO1>*_Q#vyqdIZ;Bi)yb___)5*W?;j1p@Akh2<1
z)0>n_MEx0}Xf>(JiTz%UCg@E_R^(-D9fGXg>MI4AE%k)Unl1JObEiS)zJe4(0@`es
zV?ag=w7sPDGO6Ie?<}KsJtz%@Gc%xYmPup=2xpm8V`wAG{84A3P73Og1u_9iXVR3B
z6krJvX7D{&M$5B}O5TQgPElt=9pl1gP^W?4StfNF@SPRlvI~?Ppmgd$?<|u-4Xtw-
zlx66pOW-nN#GqwTj>k!N$!1bSnheqdBGRNBj}(#DGHJ&HBGP1$9uSd6eL0l)lSb2^
z<}XuF5W`(ylh`?Ar0`~jOT{wj%X#Nmfb?HU$z4cw8Q`2{rru!$H7U@5<}6~?UORPo
z6xlPbk0$jQx2jFys3BZU5}XcB%d(hq)1(O_t;kZwKLfO88D%(tHH){XBqg)i#{Q$s
z(?HZLlX)6|noVJ^yeOJPJZ{B7x%s2m3eu(luz68-3D}xd7hxHe{%fnsM2#ffOCUFM
z2*@gp85jQrT-p_s-Eoyk8a9Sa0V}XWyeKHe_7m955-f8CDNl{S%B(7jG>|f@5@~J#
z%B(7bv|E%o>xe_Kggi5ZuUM5THjFTvz<%<6SBFgUaK+pt_5<-K(AlOWFVdlbidn>p
z?S@jiRhgt=(pps}X_&n>1q?#ARmt7-X}yA!KY@6wGD|z8Ta{VbA>OL2(jMY1V^d!s
z<OEX~I|N>pRT_|+RiU552)HU0^vlvvxGC%zm%M7~8J9d^!wg}7Hifm|eY}L|+N9*K
zJgOywv`ZTz)~qVCbVjwgg496>2Bm+)e!Ga}GMIQbfn7rcRzbxLfSgT2-}BD&!PzeW
zIh)c^&LQdpPAtw9q{`pqW|WqmNSsxqqXTxciZpWA(^uldE|6lei!9UdZ{HMjwf`)u
z^n~mb?rT%>npk9(o)DfzW@*4}R+(xw*_B3)w}@3-69=fxD$>aDgt3aNcSz47Jw2c{
z3)b`fE#awT6{_jL*=zzkhlCB7nE_$5iq!PkI7aE|Go@*v29CF)RiuOCJ?TY3Y5%;R
zsfUylYRmwe*%X`}K+P<rGdF~xcu`OayHt_28W5UIA)}CxLX{Z+G^@y1o%oq-h+R9l
zZ|d4H`3<F<c&X?+jz^SX9ZA&7i-1D%rJFV&Fso3no+}FMe?i$TvQ#5*+$z$c@fx~{
zEY*O=tWwl!u9HyXo3c;|!(TThRjT+(aaW{?<3)HCM#eO}8gB~bb(JWwQHVpq!VIx&
z)-92_fOXrX4nmI-28iH3>y||tuj)$xEn5~PUilY9*$spA!Y%He;sc`XmOXkwwjt<5
z3@?S75L^c2%BFObV*}jMs}r<xORG+x!<8fq7-H;}LcBV<=7+R;c03++a@x91h6Oox
z%ft*Y$GT-=2H<1e(3%4fvIMuXHOL(;%*3_aQlg1#xurxC*K$jX2D0UDX9Xa~1lls<
zSZ=D!gt6RGnxlfu%ZpdNTM9FQEW&G9ggV`2_5!hY%euTE_HH_C+QLommPB1C<pj*y
zgycs0F_A3@MRO%7M<fM#LCoE-FSm_;xhazy(Jw0HfqK)p+z5TSX<TlIIlC!2!UpKe
zO^vz%`f@G7yc)4DHx1025+mfFlkr=P;<k9-1TeHai);}x@4nR{?u+-0(&lrnCC+Oc
zf>Y?MhM2&clIKGMyk%3^PfE8<VLymMJ{PO>*T1KxEG63{e5+x%%r(_-ZmGHE8C;&|
zb4_)ef?#4!k=}k$<!%71Yzi3*Cx<DdR>OBU*LYM)UIv+qFMO_{Zc|pxrC>`9n3lPQ
z8cty~S69OWQ`y<DV<r`Ty5SJoBu=+u3^Y`?ILLOnEdC;=s<GXf3gKK$(>ZetsZTc`
zROT`<x3Yv0E=;uy*9{PrP3kD;Y@7I4m^jlMEO3U8_WEc*5^oavO04l*G*oXwPH!5j
z8^X5FMLYGT#0%0~)TSGNE>ke9R(2IC(hWj$Q##7YzQU`t6uomnNp8TS%yo;i3Qq3d
z_={X)YP_2=bK~D^#iBr_QpnA@#8`^CP2q&3nA;Rien~kug{x|bX_<4W=UmD;7dy^-
z&_sa3nEVulb58Z1!f?*1-uD)n!e%w#Rpy**7x>Ig;ix*s;A*#H3{-(zdLqo}8UbQ;
z%;_4#0L#w41{l@{oCzE@1*P5Q;B~(Nu`=fn|0x{j9O`&rL___iaGX=`P%V}2O<~8$
z<%@z+?1b4hz7&<4!kz(X*(7#7ql8bpOpK0tbHjaQ&Zb5tm~GSpTi$TyY^t@uS`)Ji
z>@}2<H50Rotl=iy>Kz3f7l5$LNt1K~gk?^eq#I)B%&Exo4OvZIB$Q&ssW~^mT;{Co
zv|!$=I!+AaoK+nc429}+gD=w*o~r?&GN*)Th0${gi`5dQGG}?zN_K8B2+=lgGHBRs
zN5qC<U=wf_!E~@G>?o&sQ`l4cn7-5tUJo`2-Q-eEA+a_kM&zkqH`qp|FZCOz{d759
zHW*!|PxX{CVhWtqfLqxV@|ODQblqQDB3GunYC+(+i@yPW9Q=*s#>L)9tIKrPyg=L$
zR~3}xkH+eT^iR`=`VML5LuVmUNKGH;I@z2))Heho5m^mrm`wouw<R8CdRNbR;%y4+
z#3~At)et>rdQ+Y7WSQQ?>;i9169u6t%+;nOcQi~lyK$mA)a*?O?x<xq7)7U3({8Yw
zPM6Szb#)#fR)Yz4I(6-4S%p2Pt~uS<alsf(J>zX~Dp_~~2xe1oo+J!r6L4$+^s*`J
zs^*Xw<*>m-J%#9MFk`<cQF;kZmj;cbanq$jGqc<jOsfIhGF>V(z%4HdO2OtWz9BUI
zK2rv<shr`PlDm{w<OZzErm*Lbntn6DR>RxGi-bSNE*MKaL#!%~cuQycq+se{2AxU{
z-V73wxULp2HoHhhAOOeI6hHuu{Cw~*GzHpfcs!cJ*=EYV;bH``4_>}8J_x|!>KOu1
zIlvp9zNT<o%^>jxbn9zVVk*Z_XER1LG}#j)lKzeO4s*~p-3+hub96NW5eTGKYj^w`
zj5G+iL9=vg5O9M?>4vAsDGXLateZ_in_z@y>4r3)n*txjhIkyC#Li33uas}33!MUG
zZAwliwCz?Pu!pIu8YRpCo^0ok@|`f47e(JKqT9@&;DikrmpP<11LHDBc~r}pEaJ|<
zUD2tG7w<WsU$++jCa<`<5lz+broIX67x~raxYaR)-ni9q3cVqX9B7$|G~*3enaSKO
zNy;HoBL`Gw4r%29m6=^SdBYV@`N^*aXv`E?t0jhEcIw**&@=l|vndpnk-Rku#V++4
zNrX3r?LsJa8lg8O817WTTgb#d>HXh;pqZV&PxhsJ11>VVt6zx3E`2;uCs$C|Z*nl1
zzq|oHGlltT0I$3#D8(k|M<I`1rHr?Qu}K+k3uBWqzHv8MzWIyTWV1^b2Yly6*`-7P
zP31FhfXz&yy&7OMn?eO2u$fIltB9fXqC{!`oaX5U5Y1FJ^VX3Ua0(38I_{Xgsb5IS
zE?qs5G_y-p2a@J`k)l|!F4EOAnfN5AtaaOk{1=##hTSO>d)2SAzbXbG@|2Uj0SPm^
z^l2brX7YA{l<QR3a7esfG<XQSUNrcI`J{ZlTF)vtv#>t1Q{4t&Zz@N5OHkhg46FrU
zWj1DSX$YS;h2Cm_u*?R<Irr`^a%_-gN+y0ad;_!TL+v37XPaskqO46coBH!?G)`|y
z9ICTTjSsR->BTo?H>+zhAT6^&jmFtAn_`W$JYS}=k2e5Xrm$KK;L@pN;tfG(CU90)
zP<oV4ot!x-z&K@Rqiwq3B%Y17={As0ZX%m_%L9E1Y1M$B-IU5-<m7gB4cXS3ZX5u<
zY!ds<68nX8Yto{DbD51QGhr^XNoh`)%WTq_0dtvxXEg}W*`y!?;(Toq#{>b`s3ij`
zJ(ZGtQ*r?DVUCyZYXWUF#5A2v>M<gp&Q{eeE__W2Gk`FY3CXXPK$t0XR)hBPqC^R@
zugNqG49sjYO%G&!-z4@N!cQ5?8&EJ)_^t-X%Zn1FfzjML<e{uhWh`${=ceFXEmgkR
zq%sefL!pXo>n9Y&7wIEQ@%flk<nSSwCIuPTmQ7(Vz_x4>`+@8;S*MZo;YC4dZ(-#n
zZ@|AyBVM`z|1wSHX#ilRP4x`fXHv!CpfPRAKmsq0X%nR!pj2@LSDwmE-V(nuO)9iQ
zvzay?wURwrtZ~7aCMDYQ&o~}%KiU*3g1AIYlK~t4Fw<nfhR@8Vpr6zTryT<}LRwE?
zzM4axnatOo^2}tv#;tKOVR>^JQ3dd70I^IZC2t90nF3}tU|2SVl~S->o76$bDjZ@%
z&r*@$J~d6|>F6YF(=k5W(hSCFIA~3iaT;;er;?2~1Ye(mU|lUkv`>?g4Lr-Hbd+;%
zNQVx4$0P)+dB&EWNGra}*{y8R?&$VDRiabry$-2X<rLUp7@Ae)XvdvR5UNcH-l}wA
z54lzsu?r1ImQ6z6xU*Gh#{ja-Dq}R#Gfe@pu9i@iS*0%nr!p&bVW3o|GLN@;?^6CN
z7pp2vPlMrZlh9(gRPHjy0<X(W!9>C_b21b8)!@82tG)nXK%T!-IC#D&C<WUDVl?E_
znpLXsMAn^Ir3+68MkOL|$n7wN%W5-A>=kmcjtj-uj8#@?*ikoy{o>J2X~|ofV<&K3
zS5k6c$S{rUWwT0KM!t+$r4dg^Mc68%p%z6p0y$Wv{KAI)qM($_N<7o*J&D+A318V|
zoW#JdYzodg;8!+<9YYS*W2%M|^^7FsEkG`_N{<G{Wmc-ufVj*mOZ6PDgQdz$jfa9w
zVW$IQ(>VZW%2bl^258DPh1F_-MwwMs>IoTFWu-<cnpvqf<Jo0a1@&lno0-67wS2wV
zMRo%rS7o*au4Pl;X3{cY;Vd#;BQwurUh#(PJyT$<h7>=uKmlhOpjl+Po^it~OFiQ{
zr-bAU&tp^gtp*&+EQ;sX0A!g(>hvm6ViicaBC9o`xy%A}d(pO8WVc=ktD8zUz9|!x
zaKPYIaTb}a7c%V4BD?iUF;|8<hrP4FZjBfcvq&r>&crOlST}%XHidn^Zhu8OI}kAw
z8Os~+FtbP>Ux;`%m7u&KM#mJ?sv(ZYrr=CKj?_&#4W&>n)VNoV0vUr~REqLV$=TND
zj92Yhj)fX;-?K;o&*$+?V9y<!j_Nla*(dXuUqQ-UXZS&U+(icJ0MX1M1snjGSqS<_
ze9RRT98Sx@e?=+SlHLrM!Bqb8wjeu8k(B{CduNeF8hL$R6qI(OGDrgoGs`Vb5$Jy^
zdwD~C;VH~k13G3?aQY-VW)s*i@*}=TD8`cCvPc63GH=OwAY-O*Up*uJ1O@M5n-m-?
zRr#jG2Xn(l-4n;M%gI~^4rWteFYmz0%t%At0d|=;HRBGj%e<Y9W`T_5s$KIYcDe)W
zGL?nABYMje(yJ2zb5p(U8PsXsgO-mD#L*_9XUM{PsCUZ&4)tvq;2<)(6TNbG)q?N?
z(5q*1@LeP?5N&tUEc876CKHKwglL&JRpn05%iVtCFM5;=%hNHpjmm#V#IH?a*W*<(
zbqnDpP*=xL=WXa@Kv3VNe)7V1n<g6<J|!OS1i%Q?wJG5qH<ees6W$_7RtK2nF5(8l
z>@J#wiG@WB?Vg))Du;LnGI8Ees5`)mo4|e`%I=%+l}*aYz14RJv-?)hcmfnos}lut
zLl5tT?|nBl@tz<UUo=5?fM8td$UDA&7h0?1P`P|9wUgs>r6BJSanOam+U3pPrkrMW
z7n=f%Z%5?9P0F*amz@1g!60gKJk@mt$NYUX=F8P{p1!_ZJ?HuCi^_L@o!`D(ou+})
zm8HA`E#pFTb)aQl6qH7=In--tj+?+vTYf{X)aE@!nhW98A@+O?b<;5WBTD<%ouI-F
zn6nGD)q#ld)zxGNpIuFM@Y+$@)&^fqoTuD#<ty*N$GC7^9RL|$O+Am)w|q5qJz@(q
zbv&>I8cMnRrj9*I`9jx=gH2O?&neY+TpXNIf$piM1trg^4YI$YOr|E7(1#9X&sSBu
z6Wg$;UHCdUlWF!u!}uzil7+P^nv#XJ)5i})%%<=Rgp%uvns<k4>`bKDp*_3uX!cOA
z9dNJ?@QTmH3MuD&QakQIv-n)7Qsdw3F{PNNntg#38%Y4Ijys3XsYcU0;mCiv%M*1d
zec*`Vlg8;@Q;NBgU-pb`>;iFhL`e4OXcxI=TzM}0>*D6haoKUP3koJE<dh>%Wrr7#
zC-f=@nBvYSz#1LiM6N8A9amLXlFE+jtmB?`C267>&XPK!gl`;|W@moNjytu_E@nq+
zHLmQG9XJ<Pa>|}a7Z*aS1H|G?JlTO^@pQ+yK-zUo%{o?0-yF;ruAGw{zGlvplh>x?
z%9}WzV9!tr*6O3tobD=S7Y;w=r0f~CJt*vXVE~mQTEAtxH~;{1c~LGDbH5dJys+J9
zc<wMdxzbSfG)wtZ{+kZdl?%qz0cm+rP|78yy4<ZqiGAQ}b|oh7FrWFPs@%iC=1O6?
z%Q+Tm%A1nIiKurSRy$V?@}5wZAmlOt%Hqms*#Tv7B(%Je6k}0B%MQOz_pI^~eS&Uv
z;9cCQL=*1f%4699cX6NU7UIvPYA58ym7~0;bL&fK5Cp6vBZDgmc}Lm?7kH~%j}mJ@
z;Q3LLksiXC?6Sis?8<f7({AhnYIT^F9mdanP{ID}%5&KbB2I}eI}F**JeNH{Fs>Yz
z-GCNzfVnndq6WM6C~<U-nWS265PB}}hz{(EJC)@B^zk3Ay%X;jSFi2lwZEEpU6AhA
zmv5zg{KtR)@!vkm$Nl;*|M$QA^+LQhN8<9oe$0X?;MX^~s8mDe9@@UM#Ubh^Jt0nR
zSKuU|gMIL@TG@sx8Q#kKjt_#Z7qEz~%yKJ_R9AjB#5r{#6rede5|x$IYrS_GS<4;5
z**j;dAm*-jr8kEkit|0W;Hu<|s<HEW=AtR5Q$e6;Z^~MaDA=yJ4y8amDr&=3UTfic
zdn;ipab?LVC3m$OIxg@BbiMYJ3WeR3uBFt}HyrOA1ql^h?-2z#4%|4`1-`Uyg3T0|
zp}j8sDD@fIw@aq=a60S02+#;BzmTh-Q&&oZg69@j-hqPWBA3f&$!s?-3Qd5ohH!2d
zWyEf&MLEOTm-afQ3S?-BR8L-bQ7lM5bvbP{1#w86er*LoQv8OJRPfmEH_ycaXoBAg
z-CL0H&2Jt81#x;@fuajwCVuDBOi8$m>ppiC<Zf}rFfJoS%~)J~gsU2hriB7<*H~JC
z0bJf#Stai)L!J-?sprR{_$$B;4tWX`e>M3?kse8H$H_A8sTK`sLB;c(U`(D`1<?@)
z{7qlSXMs!_62%26orm*kS!Qm?p|r^bu{{Uzy|0F5oUKDyiA!Sg2T#ZXg>)!EZb1~;
zp`)xUpw@;{sV*z+0|W8x%4&!{t(!qvjHbS{RTsd?nRg!DF~+zit=`Cqp4~?V@{dd`
z9^<Sx<62Kec-X16dq<Y;T;F;#$HFXXO8Ic(7lpY9o++f6k5clj7KYe&rcTME36YE#
zofSlr_me&VChVQoH;T&Isrc75HK0sZn;cf=;uwk!P%A@w4^2U3PAH)dYh{*+p(x~)
zNgl?@2x2=OgD`W|GRJ{Jh*e{Pfk)=chFL@Snw_%2n9imvemer7M3zJFWX!?RmAItc
znBR6XhcyOJ7Y?Uppq)&Phl<F|Ap}aKoQoN4XCE|XY!s-YHfE$~%z@IG?4c>)NoTGF
zn>1?I&NK#k$FH4v1Rlw@7`NY)H={?<cq;6KPq{fwLEQ(#$m@l+BLD4+l)qqhl6tZc
zjDacE+hHBdTB#Sj3NUhc<g{^Syr>HGQJo1Vl;6>j$>EVzg{c(uNK&1t3o=w~HpOf_
zd{wBE@%@Xw$I0YxkAxaZ5OV{hQ73b>oZJ!PH{@x+^v;=C3a|jsmm>Z@qW;#!q#uv;
z0!+DaE9J&gE(@jDg5I=))bl%rk!po$szPmAG6@;P&<Z<@rPB0_YL4KIOR*nr2G2hc
zx)H<o895tae-&rwhLl;l8b?^@HG`6Vy_oE!>!;xzC&C|R%O!)L5`1UH-(m&BEnb%h
z!$ab7K5!e9re{c6L+px2I9UYQdc<QzEJoxjHz-XJ%rsfU9d@0w&r)yNQ8&|{J}+%+
zC>#)!rX@tRL1{WcAuq$lVG%rRP@3LDCuYDthG~Gxw3N4ZhZc-u<{4bDA#k9=>P3h=
z%mK8fM{qmDBo_41pf)XKDm6eyBPLt!4ronF$vq8d*VRt2UZ_n=$TLeQV?@<rL^Z_S
zVQdYkO*`&XS_vb9)cqbY3V!yF&`t<hW(sr$)oBSma~WdTE&*Q*y3>-5YycUpsyH2?
zJ}m+?Y|qiEUBP1*aOT8W$#61?d<MN~DJhl#(6MN7{E@*x8e)iKLqIevJ^LEm|CSOc
zSt?EuZz3%Lme1;skP^_Go{=38^zso=!4$S&CdkHMDqgqZYeIEed>%49Qm$L!=AbsM
zo4sER=i1X>y@reN@d9t*b`AgdE??&?(~Vi#=o+72=qwC<>FM>0cXpX}TcH>EO>MT}
zg?dh*Y*Sl$x{T(t?8B)NURsKA-!gtpIy=H2tjevAo?O6h%7W9NC{2YRhfCYXH5K=}
zK~I_r_5J4El_L#BX)?4m-I}1mGz2UQub*rI3er@J<pyKK96|~~J(`Ktq_;}C$>^OQ
z%F$GI`ZvD~P<pzeq;9n#J9Ju*TSMwaQ<=~Y`d$b=s6|uhyRVH}Pw=<gx}g+J1s83I
z;X0L-x<MtHjp)tmK%_P4fHDiw1dZq&)ti7_jeO8)xe0sofT)5WXhhS5Hp8k+MciwQ
z0saI^{tmy`65%LB(n0$Ph?k&2DlZRs+%5^ECMfv>2nOH{UYM1qu}#3Kr-E5Eq?~x7
zi{=})h(H_y7zzLkQXHQsm3a^)z?cwPa4;N%m^i>7<p4bnvVrfSH=b9QDCgN9)=Ivt
zA3Hx^$@#hsl$8!RJ|XY-Vm|erM_WEV-FbtL$JE9L%X~JX-qfK1?MFbqPVx;;kL`FW
z1KcBCx$?QH^L;3v!ERap&jS!m@_dMKy)pwqx8FqO?_Mv?vjd+HWTdAZKTVkMX?&W~
zWw@T7t;5H#n^s({fJ~<?U((a+`T8t3Xz%q8d&$i4`iH-+1EYLx^vtv1Vf5sCy^NmF
zcec%Q@CjRXPk`HG_Z)v<_e_)Jv3u^;9#+q2{Y#@KY@EmFnN^O>6E>4$^~9t3!|Iu)
zq=(Uyb&k>V&F0x<kGg?W^(NztjGjcc9HZxu4f7a1VLu9+r_ne;qbD!;GI};Xo*b(u
z?Y^*jZae6Q44&Ht%9r$G^OW&bHctwIWAi*#P-N$D9)~h{5@slyCoRs$=E-yTm^?d0
z>9Kj{(QquD_B)FwZ&WgPBACIpe97XuWCOLZe}aG5JY^Vz&C?4X4Po=V!Z3;f(CVqY
zkurNKYvVC{!ZaqEr~C(w(Q~L0jh<A1WcH-Cd#s)nA;4($bj2e&W=~lOW%iU6Jk6eA
z8ij>kmQPt_W%<M!$nGiI=(c<6fK0RJwaud7UUpAHT8`b57HFA0dDS>pPk9u{>^Zdr
zG<)h9Q)W+wdyvsnICfb*We=CxbNtTiNuxMMH(X}%1&hu$je;B4J%>-VGjK|BoC`6}
zmEeXZ&npayFj9r}n){h1PXVfq$#XCVpbVa_XeY<wDYxrm@uXY$F?vc5JvPt5<k2#D
z>Y^>1r<|2#^OTSAF?o)Yu~c?X<vuue&;D-n>`J32ljm{uJT_11r^n{mxgy8rDF?+g
zc{T-;rOmVPTsk&Sx#u05r~K%S$+Ml5*0Onq$JnuVHj2cDy_3mUW$m>5%C3jG(`4kL
zxzmmTl;%#88CcfNaE-a1#?D8o`$r;q)RVPSz8}ZfStn3h$JlwYpUc>JGLLs;^u{)k
ztur9`uybB%c|?t4=u}=x89U3#G*4TnQZWylpka-~{+6v%dhD@vN|8OLP8lOTQxhpq
z@6*;PFzvB*-Y17NO`U?D!q$0xyyaY_u@f5ZF?HTXyQVCiSp#NH#jx0R&ZY2dG;^+{
zq_&G`7RM(W=UU3@x`19;!i^mh=gEai3#W34%gRZW23F2U)kpIdOr4Khd@;186J3_h
zliN;~&XY?+rcPO|py{vqX60m@9a%XAn1Ge@ibED1!OTg!VOTj8a8y=Kh3%G=Q&*j1
z<~*sNn3+d8TWICv=_(^9PT=cl=adCacFvQl2WC#?@SvTOm%K}c&aN2PG<0@_)});?
z{P>TN^W;5Rh{!BY_G9KeIY^M3p(`{otelD@x~-h4X350a6#ZT{P9=w+iBnN5W#Z&*
z?>aV4rU#OVQwjEH;WQZ#Y2lQ!W?DF}x48MVaVm?9Y@7-pPZOtNP{PD{E%@;r3#YyZ
z8aS&$qsqXE2&FP_$~}|zO@+(#{s>V``{pyWblNu+fju>(E2ApIc1Z)LBACm*$<X04
zZ$3l)hM{N`McJl(Q;BA1-jo4X=FJGwF4Lyq#!uTOSdnRypW(x@$yRCFtQ3aFw#f~6
zOq<W3m>G)_mcKA<D$>o3>)ce5-DBQVsF;U!lSap5-(&<fU_7=t^OJ!S*w3eR^8~l6
zif8xnX5FMc=3(BXSrYCRg8d!y<_U*(%$pwK{%PLiZvfACS$bsMq`&Xy&{dbLn{ugz
zc@wry7&l!ewuf<3v4+xdU@*wY!?t-s^U$=(I3hG{(xUsYY|az+g{IA%-DBCLA@i6v
z8TdtkMKnO!HnsdRZEE?yG;J~pz{9plYbQ;cGBGPk!-;#4rcIez)3kYowKHcB(jg)T
z!2C(eX7nPf=5d>+RdYVwztjC#{%f*o%Cb(grgk39nw6-LW7s@i%g65*bNn!F(v_0N
z&EsEttef-*M7*pj7d06-6@&rCO?f76_h<#9KgP}ALUv7k`m$>>YMjiPO?ygqO)b65
zngXrUtXT*fmsRs%L21^MZv?HH$AgG=&EpM3yC%)M*D-7os0)o}DhK>AYXWdCqox3%
zdAO%P1R(XEjtjubr%hANK(c8b1aT3*o@ja*H3fyINmE$W|G%}f>Di=5vhqHEMJ=Zn
z)1<%cEfRwS3j{PP#0E5jgk}~D8u9nJ?YPd#e5&5Ad8e9gsk<D{?ew?94xcz-lcrIn
zHfg?4-7;zlTx~?KT@5g55|mda%@>@vJ-}I+J!R9>Gg25eKicNAi+=m$>>I=R`A7Tg
z<D>shqbB}2BkZq$l*iDXFyn84IuiieB#Q-`^%%O#&txDdMp7V$BU(Dc+&Hw<CR^Vt
zgOJN)!1^nr&lGAIJKPjzIq4m53bL%D)D&V_Mypv)!dBd9luY~+1LR}Z6+T&`L!9Z+
z^#*YQQID?6%fz7Amuz4l@jsGp-`k0?T|34pkAkD?zD{`UH-;7qY?n{c+t?h*C|}0c
ziMNb-?<OHhhk5Vte)tF?u{*s>rSoz*#DE7M?hyao<}*CwYD)|;&4>B#ezbpsOm=kB
z8O}BiWQwcEa2!*tSOaoA_<%>(?GNkQI6+LW5S(V{CIav9a0t^MZ16mA3@h!49c6UA
z%&z++fF|DzR*ghdSWkNErow2wb*tBP6ZqcdpQ6ITvn*V3bYkGfy3<T{z?#E+dD!tr
z*Q53Nf}F-$>(HeuGui#j@cpwxj)B!4fVb4J6%2=}(fvG(*>rR*=~ZZkF5C+r9Wm?S
z#WhT<w`x3ePy`-2&&x+;(V(qxEgM~T*I*UjX+UY5gSRB6-@=2Zi#Pyk^8K3P=aqQp
zKpU)ME!;`Q?uX}>Fdz-RLI<?qq-hn-J8^`%LUQJh<DP~(d%@Ou4lu7CB=FB0&%k};
zC5US4e724okB^Hy6>b5eGpP2^)n@UkVoc-@4@r1t4wK{sfGh-2>QcS5B`h3tOp<rB
z`!GQsubSiV<KaO%6ft$1bf{(%_MVp>2Tc9?x`p6OJag)$aB#hjh^LSn<!ny9Es54e
zIq5u)>0t{U7@T@~LM!}86+sJ{Q*TSo47DZVyN9=9o1=k#1BnyTXh!D~|6v$~ng|lH
zC7{0&ktDW=cM_saY>6KEPC~_?0h{&^9s#c}uYf#uHe>U7ygm|t=rrl=FL9VchF=n6
z2KXiAm<wO-6!`R*pzl0Bl7(K1->YS~^e9g278D*U)jITPyWP6Rqo9Mirns?>rb9sj
zvOkRS*w3D^Kin$n%RA_WD86z#&zaKIkA%E|jVeciyYnn+*3QJc#()iQr}s3de&f7R
z$5qhk1X^^MF)$s<0iI+j8kPKdq(ue$X&@1{W=k}L=OA6D-X+qFT7EgWpqELZh3oJ{
z2{mlYACJS=`*j#N#g=G&po;5oISbbsoxM}K&wH}`Eih<|$}uGo4QLA}IvwBFYOjcd
z&bD*Tm3Z46#$x~0(=~eAM1)&%8Yz=_N=c0r`XNEXF&y+Y@f0;oMYtu=NIlG@NTBZ%
zOdlT+sWaWH_ov@@R7XMA>h=UicT3cfXlSzzCSHNJ<oQn2Rad!`<XT(f`0{$cj}%oY
zq+*JCONl48p-`_WLGw4v75F0p0G(R}z}u1-Ex(SZeo}H)B1G7zz!!J}-)WW;&nv@`
zV7Dadn(U(z=EY(AYyw*}syC6}fG2P_ta3oO5^sj%umz@w&^F5Qgy6BiEKi6ZAP#8?
zi{SMS3DK6Qr?`VE+G~QzXgJtwB6{7mMdbPpJrVk}_$e2=#1MjZ3!-wyxopvyCdF$T
zgYK3HaS>S<<cvx!gH-4qQw1idr-rBk6OU_eR0r;_MX$VxaD>+u(Urt39Hk4x5enA9
zV7DL|=yjb@u;p<S#64|`R5}XQZW1Y%K$uYQkC+o(GK(DX!ZFY5IJm<`sV<{1#MNa~
zd;qHvGlZJlB6Thl5T%lesy|Q{6zt0daBmF`6q{gJ8wvuu1yNTYAaZC=6A~sYV58)x
z(*T?}4(xA%Y|yCC6z+6<R@feS$eN{ai(=fpMeuq%%u=|qJ2C9uA|f*BC8tJ2m28c4
zCzDE#EA9gTLZ22}9#ZC#TN0`Ld!HaOn$u*5TN1U`nIdyD7!DSj;2s<&SnQ9eBj^ja
zWC)jZ20X84NiO?q>L+K+v$vGb$4B;V!n4oF-c5ERu7hogLJDd#dow9$%@_O$t!cb_
zik|u`Nk^nj(VN2oX%q2#M^-8t<1MJ5F$Ks9Q8dSXt|d~B@99~6jz{}j$SjC>NA|8$
zvV2&lb47!UqG1V)j8k!}k&(MSB#EXx9FaB=aQX3sO{}$%z3CM0!*85eJxTe+qFS>~
z2>>{@K(MjUuGs*uf<<`vK`udOI&7c*5sr2gup`*+bPT+Cm{Nhm!k!AL^n+hhxu{oO
z{&qU5TKv%-XVt7N<~Kla=+*<X*r|5hgjH+wY;4~bqL`0a-{hK`eYhyFS7gEL&e-{G
z67R{^7vLSt6$W=CRPZo7IiaUV_DSIcXdeRfhajqZzdjSSz3HRx5PshhM~Fd4ql5Vi
z^_;y`;NSO=kP0Ve;X4uslVKOQBs%2b7uHlGi;CrLo9yR&&QWiiA-Xu(sF65}4HF@5
ziCnY=NJJN>pnpm6626o8)FfPcMiQPpK|DPi$2Q?0Kg_0>I9?7jDqi0sA<@N-VVgLy
z4uz~uJk$@9C#D*4R)_rpx8zJwJJBRg)5B3~Q_y^Gfl7)ex9b2gmw}n&D*jHisk_V3
z(I>WTs_po)AFqy+q&>2Wz$!43?IINw?icYbi59kJHiZ&5uxJaSh0R0#BWM&IZl1;~
z!RJ0q)VL+>q?<nzGp4!|(Bkr^+=9@9rfN*w1Ba;^6L-a7s>Z~9awMN#DhJaysx|bu
zU&9jI_v6qoCY*AIX&BR?&mTbqb|Huc*z!@aMLVMIZ(wJGBVzF8c7-HnxNkE&vwk5S
zh{@m`2V25O98|*Ea2)~rDah<$uvY@ivL%e=2~IGQHz{l(BN@t=u$T-xKP3E`$1N;=
z!jv=2znDlVM+UWSd@!o__Spk-(U1ph!k{#6qiGx5Q1`RPge_|jcQ;||8n+J{Sj5IH
zP6~`><Mvsj>Hd00vWmSSQs#4j@&Ti>J#!Q0y#amW6{4uS&l)ZCu<>&n4t-XU9pHWd
zNMA>E2JH4(1FPn^IcwmZJ{;UPH59Re`=-{flTt5o6TW@Uz!W<i**9UW9gggq8YGDW
z#>Xu<4SKNKxE<V$RMgz3jCQm&w!JF^ff2XC6l3+97vl#&I6P7c+j|{Rbhhs<Ey$$&
z+Pnp4wLtl}Vdc^JK72G8s)bZcU@gY&(?>fR-1y`~h@CA_!Ed<wnV{i(J8tg?9qoMk
z00MY)fK*32-`)+nwDYa)pa=e4*!D!n%RMX+yy%UQPi7C%(&6c5+yYvqc<dQwf82to
ztFJ1&7!CL!Hy*zn<UJkGL#=ibJ#L9uO7ztNuHMFtcnG`RR3_)%+f5FcpnT9rV?K0K
zLvG0iyDt+NBtYC>odBY8zDD#$<+QrP<+?+kd)oJ%=RoSA{`&H<fXB?fd@ShQyem?O
z8+d*MOi7Tw-5y$rch+uh$HYTzUtX&5mV141TZoOQD>QEkSY}^V{19z)Q#>a8Gy5{o
ze2bzHrfBJtMp*Oj$LQl9@pw!`8}J^yw&b`NnC0;YuZq4HI$tLGilLL%?<*c>w&R7G
zy`o88;eF90FY$5HBx`t(TUTFx0vR_=(jq@@`EL)8o7&1636)h}+4tzc9Q5V)4NwW)
zL4LO+hSH1pJJ%8P;hSYAGuFxV&!=u)!=N>~g8Xj5B#TTB1UmePPO4COFYySL*q3dS
z#8cc76<gH(k7G;SsrVPJDYiV|EZl{bNx`yn_<>kL1Amd}+rw{o$~630gosE4uk2!v
zypE{zqsC88H`~X0175nK{U+Gk-poX3v6n+mkJ?(B10mcJwSG`pD|4vj`ZQ%jB6?^)
zv3=7CE!yn@nII?H5{iu~ZGp;#Ca6!pN<e(~b{3jA3wiYi$6hzRWP*n8>eIS=Eb}on
z(vgK_P3YEc>d1tbWe>p0h3L$zDgV(lZ+w|p+4Jaxon*oSGwK3BrOC5vHv%-lfY{A1
znE)Sc2~8sGZJ%E36SUUbMJk;}X<^Sqo5cLOCDEpHz7IfApV=;uK#IB%`3X=_pH|+0
zir#)$IG@dEO}W1CSD_6}C7B38+|5jqa3Af{+IvbH8Uvf?i$0UfEeuEe9erqa$rODa
z?qL^#sQT@XR;q3f&KWu6F4oMx#blePi!QH(Ejbg?+ymeHp&dbZi%GXn6zDKJMFQN^
zhgUyy{!R3C6zG`l%D7-}N#k|qv-ozBVg}XsL7xTu_K1r`-iOcolbd3<D_d+8eRzie
z)YOM}2vAMkA%qjKrap!ZWNcF1-Wus_W8IkL1k|aEhVn;;y(_Ulb|MHTcF;q1##cg}
zDuD1#S8{00g}*=_-Za?Gx8(5*j3)Ul1Fx9wpu)#{FkA!eK6upWu<-yaR3G|lG{<)W
ze9QZIU=(1Xx`Pg<(0AQ2hZ8EXo2Me7Mn4i#P`5o^jQBM2^UT!nhJxzugA2ksx_6k(
zY7079SS;{?bmPajBwFJe!a@OuroIrJ);!d6XyBKBWuY}PS^|vff?!_T2XiOSA4A^?
z3He*znT=Z5D8HIqLuDw%dFoj{P=t4Lh-^t`POEw7U$oi2)U6&%g+A)6xZ$zmX8CxE
zVh4WK*TN3`tS`Zzp7pi3I}Ynl4)sF|V@-LVM*Ai_Oi$h7^<hiYD-##1r?wMssB`$g
zLb4r190z<0!cpreegII*G%IQ0_B3n{T;jAcxl}qBsF!DK0tK~2Bw^L7ukVH<-LrNw
zSg0ezr!6jOM<P1F8=pKy?9R8m7e_Tu+I>UzS4o9qpQ*0$jZ%L3?<Q^#GE!ZckOk*Z
z%TGAc`XgVCw3)aF-Smn124&pMLy?K5(AVvvvyZiPBKUf&%|N8CFAl~9&sFnnWQY%r
zh$<DlKOMv&-}v!;Wa;%S94Vg;De`r+7w9eWwa2AdKAGKgY`45p4P@M+7@}_PQ7kFJ
zYq<2Q89tfDGv>R67cvxlK&6hzKGk+rRt1`TwcGlmeguc44AeQmQb(fV`$HMYw?iw1
z)3-j}HQSn7*F`_s+`17-wIY=H^~K9ueyaVclRS01sRFUnZ4t?E==MW?#@KgcxRl;g
zp65@sr<}u|YERKtKK|Or5_u#lf3lM8iw;ogNS=?!Ows**%j8yVxOTop8+zc`nb<a`
zwG3~%Rq^f*rCT+BeBbY=C1->T{^{Ls;GgKXD+jVEyyf{w(loW>Ezl<Q$hYs^><^13
z*rxbVjCRUTf6LE4KmE<JOF<COeJRN}?j0E`EM?UjALNwPx7EcJt->m|?;!pC;`%S&
z<*t2_$AcqLm5N&TuyOJb5j3TALX9NT3rN%v@o9P92d4XYwey<tg?s@2_@2dUU`o{N
z4iHDew$;Ul`nNYhDlbZh!a&oeYbiaf23@NncI)$@p<&W~eWH<_?M5vf&#t5j4fV&1
zA3+Qa&(4%)tjuO^P~c3lGx4n@qShtShQ&OwZ(IiB^d?_Op<vtc^p=8c59ei)N^Jlf
za+X4UsA4k;wb?nI*V!X7ZNshh>De-8G-}iBBWGz<7$HR8N$m40WVBA_mYl_G(7b(Q
z_-u!(l+==O7B7&eLpFi_2IKUFe<Cw;U`NjYnvNia)jsD!nxdsbn{1Ss7yTn*B+sLN
zQ0a0qfavSU8b68I-n^S+=})7ybB3(7HB#sN`bo<snX@!ys~W@>DSg5k(BuHbioA|Y
zgVQvs5AlYSpaY!ej1qhZfinc#M<#lX7jLlI291co*g1<ix)oQehjC)dPI~La7wN}P
zL$bdrmDqH8$x?sK-dZ`M0}a5=St{_MEY4Da&HM;iDzH7w%2_&4*z24_13pY7S^BP-
z2skg2VI0rdl*!&TvKdrvCdi`JKH30(Iy5Id2IV3JSj}fqr2ncpe~XBE?a-P_sKmM+
zniDBSGx}w~Oj~r4N#rQgg`p<v)H_!$(vvUl73s+@A}CYzcDY4U8BtS3iqd|!xtK@V
z92rI2GS&3rC3I&sUMd&q#mdV@E>epxMi|th!PdD*Ek20rT%;HUxz0s8&=~7nY9!gD
z!6usQ`U)95*4@QPRaTiiGm(|Qu+)fEq>9U@h+D;&>I_ixP}wM7Q#H*aU3w%j3myWT
zD9tB>B5kPv?l~Z-hkyIw&0*}y)8kT~j@X_dXFMW(eW-)AH4wQ$^xo#+AtOl|Vt$h{
zBdK<YB1mKtIbcjzh}d$9^sB?J=OP9B(EAiASkTm4aPBZhQ|BW6YX0$}JFLT3<RXP@
zJaw*wt2i?HlDO+f^bibH<!lI`E;74$#Ymj);v+>hEs*zu8p_k)>r6Y3==sz+avs@3
zXmkoJ({<0WSiVSNl*;_0a&bc|Z`Swd^D_1AP?yE4w@O=<;T|Zi(nFslg=y4vuDWm<
zcAYCa^dWe!)}se}ovU<c@o}N*wkh;=299(jrf-U*ZXQ*tw)lotb=!PVJfTAsnmyMS
z-@FctRVtLACAp$N9h`kjV&OPE`xeoV=2KqPWwZFq06*&&lBp3%O%mza^6U&%%C=PZ
zwv?uU)457%mf~)b&fNQ^2>jbOvF9V`%9Z?~sa&j|=%j4rS9L!GI=uz4DvX}aRZ8>4
zl_i~7GRd=;ixq#9CM<fS$W7P7qDP9{q#R4~my=d=Nu*=Y9#SqT$1fr(tyjt%u3<-_
z-fvQl#!+vAFWMp2v1ZmW$9`zijpaT%r-fq7J}xxfDIGLEH{B^;%wf`=c|BFqWiSiz
zn49#Vqrm4@Bl%E}#mve!#vWQS<)R@qYUwl=L1=e!(>>6U->=+s5fnE?Zc=wIZnOSf
zQnm5QZ()u-B0eMC_5@^TQf;}DjOv*htVyfoCxAkeUVHJXNv-84)PxjQw%TsGJ?6*u
z*|<I$#GIS1j}K2<lY09iiYbz93usbr#xmy?_eaB-bCWhRV{z_xBzcY6q;T}5b$gd4
z6UI4rDKdkcbC)VRDCaA8E{+cIp1UrNit(Pi?v4)fp1Y%8WZ}|sm-=(4_buY%3}u)4
z%eEMFT_+DiNd)DP`g<|lN!b|%y+u^i3cgF*JxJ)>MZ9Pzbnd!Df`!gKbmEIWPdYK%
zy*qbZA{`ehcj?6JEubsn#}kD_7S}KfT*zW}5)D3gsX#}A&s{n&=~&SDa1?drE*1FV
z_|wfY$;<$^LBt@Tj*dYxF`IQ1p5t3>3AJ`4oi2s<@CQoWh2#nmwf4!Ok4Q!q?uX*i
z%3aq(M}*IPisF!%@VQITy?6?x=o}|L!)I|s8lh!|Lt9(BZhu6FKa_`OzNPlc7uB?_
zwJ+Vh)5$cX*pgNK&}A^mJTM%z#i49Q+y#?8s`8M!OEww|sXNn&<)Qnaql#@24Jn@P
zL<c!Cx^qb9rFekM1C5t_Bp8k)Q}m{shcsUD?lGkD(h~<qDlZABm`7;6u%GHv%t6i$
zLrU+(AIWVnWl~H(*%7ZibQ2VGIgc7CwwqB^y@!HQ+U|=;JeBHNUHX!Z2t)Q!u@!9z
zL*jj8G@U>a8_7U*ChsIe$}@S_7}A}|)`o%N3aZSdufvP^uxIv2qV2&Ty(0VYWO*Ht
z<`VbETX}dlvRPrEP;Z|bh7{`kgz*|usJAZ{Lkjh_A#&)hczY)q=R*!zmxtmj3HF?a
zNLQbTL_>=CX5Sc6%lGh(JW$IIap;g*eu<=(9m{@;VxBzF?6)i?io)6F5o+1+=sa}o
z1RuQxQ+Z^@o_C~QOs3H^n;53F@{8LPEvyhs*AdYY+Zd)pFez%<lp4PMjxnW$4^;Zf
zGgPpl(s@b+-@br=UJ7c}=%OjD4BP7GLsH6S8qAYB>FpR*villSy+w>$5gp-{MRRS@
zn9}8jRp%*P4z79&Xl(Iec1n{!9I&Cv-)Wj_)93VS>M?IjJ(AwGeom?E+t$x1jcv4b
zp3>QdTj%LVQd-|$|J1bi%gEGyRp9G<P;~L88(54yrM`{8&eOEI-ub3(wYRTFQ<vI!
zOuvw2C~;K<srg&`+?1BTeM6eMpx(D_MAJmRH^~iMFc3QfWLgGdXMjv^0^Tq^Ziy-l
z!7AlKD!ZnuD;8ayZs5*cYYIY}XZ&5A6{Rinx@9m+Tf%-Y33Buh0fS;%4tkM6F>MLG
z0*Yx%X!BCsGToE1P)th*?|e{9%lPgLtY8`6ok1RK2}>4q0<^@Zkt;zk{4f<m%WBMb
zCeZsb<~tJ%eoF#!k{7|%{N@6x_#-)~OdGvb5te=}zh?)$={h2noKGVk&SVHwzeu8y
z+R8vPZB}JHB?OvjEpJ_*nYKh_7iNezF7QoTa?k-Gnq;G_N~^p}txBsNPG=}=PYk-9
zI@7^#GekOB>xqV^7<9J3MpKT2$+()hql?x+bifuoWYW>dLMj^gP)id?YuWKVf5vK=
zbucdolb81{kW$N`L^DXKWnR|2KreqpB%?Kc#$kdkqslXr_)T&hl(!+ckVI=7F_h)9
z49j6ft>vu?xYb(m(M_*xlzA4|$}saRu+@Xd5!lL6WwZ8&wQl!8psh^EorShqzRWGr
zX8Vnp4enZy)n=Sg*7Ut?#i?LT1%><Ukjr57L;Jn!KkaB%AmM!zfx~<}W!WhNRD1_C
z42ElnBd?$jKeKqwZ;^`14}W!^1(x9H1?141ZX8qeSJ4@EL)HsWrDe!^2{_Z5W+}e0
z3M_M2ZYJ}nTX!zVjbG&Ehs=5E@KkPvT5MPb3g?P7%{?7wj|Kd^aHx6nqr;eN$yM&1
zLASPYH)^KXa5pUAj+9o8U)oNq3$Pt;ky;Z<dCltD_o!LXXJKkK(!79H+7g-vA@_9X
z#T)){Vb9AwPC}Cjp82W!Sh?Yy*rG|*29wE5)SR;yA(2X)#NT}JXzyun_i|6VUVP%=
z^|)qsWl-KTxiTnl4w#$X{6>RMbD?t)*^<VP#otwzMH`a}UTR`;(dhI^ewt^R?+B{B
z=I!N#I-fTB7H(r}nw_4T-Ws}q9p?O9*I~-|l-@l0!~)t9mO|WB*KoW-F0^Zy<{W_1
z8dIN%JN0^kD3^0_e)IFAKMg=HT*;RK=mkj864v!PA`qrbTZ{>7=)P32IJ}Aft5K$0
z#kVMG==hH5FxneTzSGfnaaSq;j+TQ!mxQKY2Kns}180tn?y^HY4go+4prmDdc>$Aj
zy+RWZPtzd4lKM%hWW`N&)KM@>YxpUr9MjVp-X<_lEd}~6xaFUqt+&1#Lr`h+K;6IM
zB!q@Ey1XP5<ftA<6y!n27BEjM;N};iXr6YKG*3dc5E|LhM3d0S#icT{PP_(+6&%@{
zO9GDUy(I~5%(g**yfw0}<XaS#*DjIo69R&<f=Gg(5J;kK4yPNCr|V0gTa@3>g{K7I
zX$z=+R!ocdGl4wD?Op@zv_;WtV4b!=B_I9xicW!owB#xfb!?Gpf`T-4Z^7LCk&rqK
z?A}B&gs7`)-@vfGx`Pme@qG(am$(kUBW0jb9}3_CI%;)gX(t%4$|WL1_n{&y)UPZ*
zB`fYncL-S?DvpFEhtBQZdwB8qNJyPI(2bBUkV3tpdZ3jJQ!TmCKp!+toZ5BZs3l9|
z8je~r8dr?L1tiominqk8(pN!Ltv`K+&h6fFp!HeCnHGRf%LvjfiNZ~rw?$_nnEJP5
zRHnIqOT4iybN?2e?p7B^=axjzI4W;Ge~*7rGsnWtsJiaO9#E!hbuV_HOsjjX17!M0
zNX4uXo}(PR(&~0gExeX)5ykMN`VO#?PKplVopzbkw-k7|S9bsm5JyXp&jQ|PnWeYz
zxctOzDd+up^=D<n?zIdQEj(MVPGIb!Ff$Ig64;|<c>9S4Q^})(VoTleVHnWhP+vxo
zo)9v-YhNK`YG{yU&fYCLjcPK5Y{_YqXneOIzN=QFJs%q1EjlyKJiY~B(h0du;pk6u
z`)<i@C)~bQNX}Y)$GAB`x?>RmNm}OaEkv$fjVLUe|L!_T=clqhLl7-tHJ>2}AEP)r
z+#CZjdLcR$)nYFDgFXI5jbuSBM5kHJG0eFGy#w>0&VYcHASqnUhk(Lu?+HC#7PWc~
z0fETb!F@CXxb8JneBrX!9Db$VUxESMvC%98LJNqakA&2jc7}Zx&_-Jlt*fEyTJdtM
zC_6{mD9}i5iAqM_8S+`cC#?hc+^I8+Pn06GUCSyLUFT56rRI~0zoN66Ba4)v**p^J
zkg4Yr_y{%jMH2Ol<Np<+m@Hn<AdR+!sUAS1W%Aqtgzf}Y+6}rQ%2G>T;w;sup@R+)
zKxBz5cMDD@nJl*iV(2;|W;1{x=0u={mT{T|u+XYrm|%rgePa7mg_pOY1u3*DK#Wqy
zNoe@E>p2ydpz7;A)I`g)xP=%}?^sgkt;%AKvQ|JaFC<ZUD_U@*tNO4{!<GZG6dJz{
z5!31W__O+*JDfvU0ejs7H4oiZJE`-Kwaj)~Vu+TxZVS+&WfW#%TvxT`W;U!qi(QDK
zIgL~_<%y+*W;2qroL|ccq_o76uIvE~%WL%>(6GD;!&!hGt!kwnsH0Ww+EG9lEtB6C
z5Jpc_uL8hmnE|()<+#(Q=<5h#%mwZ$AdFU(Gid=}w5k_BRNYHVxhH;Dv?{xBG-PE5
zXy``=*eS7Py+V$K*%Tz_PDa&yw{Ivl0Xa{Qvh&R+NLgsGdOsb71r&H@0eQ5H&fI~`
zqAPEG_FU!+)hrE~&v)oEbk-Ni=_R8#3kaee9!($OjJq5gy|j5!%7XSPUgiz$^@_2E
zxw6b>lA^wfvh02>!^1VHn$$K&hh@BGIcJOONHkTrn;Dx~IJT@}J>Ae}uW)boNr5jY
z0FPGj(g%06C5?1c-Pig687*_*UImcRG6`<se77ZZEf}L!tkXF-K9T3Hau7z#v6yzc
zld1SKlT4~kq-b%6E@c_Axkb?;UG+P<&S1<EPExCQ$%96U7<kcBs5-}mDnOBzsc{QP
zq-AQ{a-c{%ecF5-!C5qgsCK}RRuS;4fI?cL&n;XXmcg6_U$kZZ+yW};9ip$&Na_C`
z%CdL^=#@5R+od|Uwvyf7XjDT$3$A#pWK#R1$(^m6T}djJi(Rovpf_5m;DP90Gv}57
zFl_<wmC_a5Q1^Y1NvqtRPiWNQ^Fbd}^_Jhj7PT*73c2Qq4R^;aJeA4bIJk1ZA{q95
zet0LNV3FMxAW6%yzX~`1m2L9tQi-OvEnz@drnW6m7p-g~ATXtsy>~>+p_PY>>H{5_
zy>}3(=n1@tk~9ExOQMMiO;$$yo(YFxW*Pliu-z<^-4^US%Vf7@$bOpjh*<)wv~qXJ
z*iVHRE#Q=v`ELv8qLrKH=_n`3Fk|)F5@kW#W$z1^&rWPfN-nD16K*mTUiN(+R*02t
z6a-wfvJd!Ri>{S*!UtQlvK2kv`cEv&(1IqkE#Qh)HejoOD_TZ-7C4P|1Wb)WqkeuJ
z!1}r+adN{#yRy~#vEeS!+!l<y@3@-iPNO=@fL(KCFLY=PmLk!Wz#XmZWe)6UWtKUR
zqZO9A3sJNvxooVV28Na~Bf=-eqJUp9KXIj8*|!M{>nqz92*brPJ#HaP+R8Tljj2Z3
z_BYVOhaa~DEzL4LZh^UGOXvf1ax#^6;cej^k@P+(N+p8ZGGA_)iX*y6g?TagLNZaw
z0)>_U94$ja3vi>Ayxo8{TFH*51-Q{WGAbH5DHV<Jl>~C4m3$?c@TV-3<Cd9EO63xZ
zI1N%!^X^ZgXj2!wumBZWphe5U0PPeLf)}@yY(W45w31I7Q-;sv;|9b>3z%r(vF~ft
z*C^QQf1>>Y?|C6=N1*W|TC~xg1whX`b}R}{SkKS01kbaQHjM!D?6k&^Yo}>v3s|0I
zpl6vtNLKRofT*e~`Fg;s?G9b5{u(q(XM-7v^7<OyHY(^9A7p7qK-0NfnrgNP;*%0j
zphEaOQE~<Gc}e2$sy~`iNX;@G)7Psx2;>$p&7E9i;gc(rq7j(|=)gyEkv#P@7PEjq
zScYR3Fbd1mv}HvOG}qF_QE<&7%#OjDMVOs?kvg;ASj_@n=Qb5(5g<n-v<14MWfIyV
z_>IGA7T_dXf+uNN<s?;eG~{iK4`gMTcD8_Pc}FLfhP(&KQ(3QFA#v{RKI66VmY-J<
z6z8_9R}mKHHg@0;KJK&%M#<it)LBmkSQep*UU8FAux6nx0^Zy{CctvJZXXkZ2Xozz
zg%GaH9e<fwzqowfwjU5Pc}r9lIyTUi*AcWYL7dUCx8Vdr<lNpQgvhyzi`IkVtxW<%
z&h1S?fE-YjMQ|Lm)fVA#?&oA7K+f$gVm$$-Pl~zW&0xoOJ88|Q$tmB6$}O5?V&aCj
zG{;Q=JGgGY76QK^koAQqs>`84@SEGAb~pa!#=uZP&D^mQ)SG97Wg6NF`OrHwc8ZEQ
zTC*b8F4XuI>_WGIZNJ`;jGedw5uM9Hmchu(C9C3=^pop}!5vh;bIIPYC3~#rlDVNW
zCUeQ;P=VTPiJAo0*cQ<Zd-!)UPKp)W?KA|k0?wT#w5`B#=CYr6g-rP!C_MDsT!Rjd
z0KRLum6aA4O;CyDI~8cRvf!o}Z7Yj%uKq{;qMej_lUw9FK6#@7-9<MV;ONOPS04!-
z9MH(Qnu`v#x+RTtJGE^tyfYmfjT++Zxx7)l!=<Z-2d#Vps1I6M)e++~Q<sTr3u2t=
zAN7N1WOZc*jjXQBq><Gf5y0E&;Kdc}&RmL~4RmLk1h<0Rc|~_eEnU-a#(KvORPthu
zXMJ@s#k1!Nk;Rv73R|?uMVr!13miv09ew?dD}U1fWoQwuUiif=it1}KsepN=@ryO3
zlVa7R#N<vo0dG+>h@aD%+l8c<?N4m`#6;k5QUmOB9SL0k8__f;ZUq1|4OZNe7>?Tw
zCRo5+I<wRiN_$R6G*2-w6SQLGXgKF`BSSOHxv*Q+IABgA7AuF)Y5LsCL3K{=OJIa1
zG?Q0|P9vr_rh^fh)7uglp(#?`3P@-R)JhchoRK7^yD^QG@Df|1VQsW=xLg93PZMC(
z2xT#iVXWK@ra_FA`@=k}yA_wRIlD_H1kYDdJ84xVH1wPboldxqIlDXeDCmzMs<ms-
z^y5j9%|D)WsrQiM!8d1h4bZc5R#$>Z^V1RHBaX_EXe1W(sw#U$wW{C^6|m1Vy>2DO
z%QTs8<)XVK6#lsfPxI*3%xmbJGG110(^CM)$`yPX(pUrQGp8(-mCHSnQ@fmKKz7L~
zT993Mq5;`u$HJdL8m}XXCV5{WSkIhM^8S~%6o5X{6udRSKGzYcSoFLJcPqZO)9}O!
zxMxo7636T_<6eIuh^6B7k3H!lIjQ<>3WiuST6xGKxg}Ar!A6inEgP0tF>_7B5-X;#
z>G1FsbJ-kIr>}}lZHpS|c2dPzPQ8s&tiX0Y5>m0g&5~Pz@l3IJ*0A(VlXzB)fzu?O
zThhtn9_!IUff6c_xTY9zw;<}?{o$i-fh^XHmK3hA5@u|g$+qHZ|K%rV0)6?(8K(hz
zOwI9UR2%F>(^$j`IngvhVLd_BrlE*6<48P5_0XU*fgV;k38twzD}bG8UfNpHN%0_E
zLF~-owF&*g99o-DG)!XzD>nKGQSB9?)A2GMRBZiQ5}gF>XA9`~l4FPkFWQ0wJf6dc
zfKooGq)(vg-h!xW@;A|SVP?J%MQyzn1JSbu^gdvnDVSj8iDwEXcpXtY0#z10HtyF~
zVv<`o1J;>cV4_-hlHMXlk$0>uX{1kmyKfD_V>0{Fh@hmpfkKscw=Ej_&1pfO?wX^g
z`g8-(Q$5CuTjcCslduF$gYzmJL0dvi;>TN{xe@y7n!US$D6no7dB|&~*&{2lLuc=v
zh3K#I#1kz<TlMC?40Y9gu!mk}b|36P?#!Ty{2Zl$?o2a9)_R{5V;In#BVi0d?o1>6
zYG8G)BVtuSEi{estMRx!MfF&D{@w!i#EK&7^|Y_<T3KmAptL3QNX^tk>ykJ6*{w4x
zH^*+J$y@(4%CCY4nB6K8%)snckySUxo>f+%t^)SeV4>O)Qqiq41J+uZ)z3M)Rx0du
z7s#AxnBNveeSMa$C?x1@uOo^2`Ya86XPO~$OWH}RjcBCq3x6d9;_SED7#hbozY5dX
zG|sOQ?|B;LSA(ByHj}(nAT-nLkrk@5Dd1l{IGow6VnOO`32cTH$j%li%UP_==V<ua
zX45%3P(8ExdSBsxna%fmP(53sve8|J{#8&t6X;)bf&H&5!NF(K9zgu?El|Nnb+ztN
zx$c=5@~RN*Z4vEhD6ghta|A@6W`?Z5dZvjXYtxOd$>>*s_RJ>4PzBmEn>-ck>4D~g
zQGo|@av?cOt@#WNwr83ZvI6dzB89Ah?U}$`_C$qHXaXCoEz?3@+k;eb3s?|vG0x^Y
zdee=s`M}*W4YE>i<)ql90r5<O04smn5?LlFb2h!<SE@Ce@7t&1U(+#9dGWiBDC&|t
zCheqD*GA_i*Oj|lOY}-(H#NUw4T$G#$=%OAt=%pK71(^77Nh7EF(RnI=8fVYf_A$4
zD=`btaheG{>k_!JLNYX~FV|2EP4hg~K+(?X+jT=JMqs|vOYt&4>+*<j&7&S@NTUhs
zS@+Xe!Wx^!bwnzL3tjcO8$8f7m1B)9XPU^dvX@;GEMNuuv(tPRXwR%(zXwr0jRdUh
zv$Og&t^&iJ)jGZ3RL?6MeD@R{um%Er0<7E})zOmGOT42cP0d(A`%Gg3D`=lBfk~nE
zNUCJCX|<jQ?K7+OJSg{By~G8DpH*u-06??KG*<xtO;CXq_|G&dumb<t5)A7Voj$8g
za}YVtDnndHpBe;Mdp#*8ZiiQY3IljVQ5B!BIm1k#dzDkpG<2_W3YrJIcOhvfo&1d$
zYOik&SF?JJb0V9fbKKqE>2MY~gzD2Ez>0gu6bNt&&W36-$J&D@>?1iTZgSO19o){W
zUe5=%Gph|~9mOg@c8H?-XUPNOnI>=Cl07Gj7d$>OTcT3H^KOv}LW`E=35FIezHImS
z*DStlcR~ctqEkC({#kr#KevKed}{A;y`N@#tOLba%(hYk?K4gHSV8+tvprVOKC`e7
zjQBTo9lTmjLjo(;r&+uW0OgrR1y=516I5Wu2W%DxuHK?WrWkiZkW2#wYq*h3!vrgV
zOr}7A*AYdBTd5DUqG5q`l#^nJfd5QG0&Bp3t|L;rQIv)SR$T0+V1YHzKeKob0R1zI
z$(`!JRBEJPg{5c~t9nR^rjdg6T;peP9LgGjIF3kN9zTeRb$ta`Tg%oqP-xK>mqH;F
zFBS-H!6~i<iU$wwR=l_rD-<mb1zOx)N^vRf1Sqb>oj<gv=bn4d_wW5=C$nbFteLge
z?BsdhOp>7$i3WdHe6EWld9E}RoBl*;dWTIcuKhqWiqe>G&kN-o6u$Y9u{(XU^^Cwj
zbF=o005*i&r19VkgtgG{A}Cc#t>e4`<prs{mglq9@6PD38u%Z&T3+~ZF$<hM1C4Vm
zl=vSe1)aV6tXnZBM1jL&VX8kba$yy!^=xLGxD|cGtbNNZa3caTu|(0b%xo~XzWy-T
z+O%tmyJ83lPbdc3+r?}VGeMUnowVI9{>*G27tc90{{;Kv*l2Cr(}juA(zY<M(|-0o
z$nqQ#vjk=)-kd?F8sCxKbWGSO-j&r;YE8Nl;Zgh;&Tjua96thtVGioj<tJbiw9gQ^
zj}Ym`Xz^YCf=~6kD4L(m5-4r6T;wTU(?x%TiW^|{`a%!8(TiFW=!udi$6^RVhB*iD
z>LkpPP5lD45U~cVFc32`qXN_-pk;`jr*UIB!kebrI56EQ+*5HwM4M3bU5m`!H#ll`
zPlYwx9$JTLg>VgWQT6i}d24OxBH9h(pO<_~8R9rEIb^D&DFkqjT~A@HMQl-@_2qOl
zDa*0szMe(uCj)^WHXf02VeJ+jys-+E40vOaAPqne9j$!Fi69Dx`nP=pOb-JQqKD<0
zaSqgZB(^j)jEBVoQB3kAwjz=<Jqdh=6F!Yinb(NtmV<3^0yADm&J`VW%26FvQ*T-D
z^V4TqiY{ns@cNiCzr~rs<x*VmGdtY$>sn6guT&?pP{WMoTu9BopkN#t!4uG5UGhlY
zEMs{$to{BZMU=d%bfmrF$0SP|T|i*_k1q%4%473g$f7d}j>75)A|Otc{Dp<bgi9oO
z=M;=nZ=si6=t2<MVl-i5)58mxFqx?b3mVKbFWQG-ISm@t#T-grQTN292+eSxFV<zm
zg1nyf;tNJ%kKDw$uyP(7{Nv%Pd}S|AJO0s(W^@}fTyV4hOp@fmD`9?6Zhkzy*eHAT
zRUTUX7B@BzsE5r?HtTB8qD6E>fsfBKKRZclR~vU=Y&B!v{A<o+RT2EjDV-vKi-XsQ
z>hh$~-Er1`^xK;{SU}yH9t(+=8|w$M0!{dqu#7ibMZ_+)qbXJV$4i1Y-=|XY-AS~g
z7v)uf)ug+02ry@H<;BdbE$L5s0+df@Cy{q}hnv&*FwFSAdQy#D;`<psxHK}?$2(r%
zE9ReJi}oVQ0)1OkvTDDbo8RS~`TjnP-zzU}*h}NVCHMYX`;~No0e()Kx4e03L;aId
zCxy2MS}=ReHcS5%V*g3xZXBc%w5aS_8|?sg<hPSZ^}JYZmZB?johXWY8p#(HY|?qk
zZjtWyn8&g9scX~%9<2Bo_JEE4=TTbBNU?^R07*R0Vl<HB8+n`lervO9+Tn<EWYTc&
z1-%$E?Zlc%D$*_v*q((I%V=~%0xD5UW3%tqh^kLsJ6=Zaytxh%v6z`9K|h_b-1>pd
z#fZ@)vZrSWt?*oASdZ9I7%74o1-1UFT!$t6=<dihl+6<4gMam@Qi_qiD$al_E3jI8
zfQo$%SX-Pq6x8O7wbO@PU5s*Q!c-y?&8j_;Ws$b!S_7O|zE=nfZgbwH-=;L5cSgQZ
zt1b9Z%lKGqTk9zufzLCw%KELPOb+#v4a`EVn?Pw@M*XCGLcI*X;ER{NAThe}VRV$o
zAWUb=R!DVDj8MlqO0wGzl5h2#kG<fZ2*i3K<L9#^Zk*9<lPuRX`4qV~I)h1Wp7yUA
z^$<?_FM7%<ypTANYnW`U$9y~eRPzJnOw+?L6AW`ir4P(Y%q^>FW04Jht|UkmoVC_L
zWmZ^~eVX=5HYB(kWlrlhB8p)A(WW*7uw40MZ55`H<*wuA^xeeBk~+tlQ>Wn&`L}HA
zo`SApzHd~Pay&!Y!Uo?epQ9|WuTeXj)@GVUmLiHFd+a(Uk&TALNq+T*piU=<H#G`_
zC@r2fHzDeh*pI^ZCcIc9NJdlU=fA;8Cp8_kG|&#JJJOPLkK82iuvzU`nkOYXTRPvv
zLQg?V(R<r!`t{~m6kpzg1v-+mHqD!js8{1A^mw@;U6N&{wS6F*P^|{ahVTmHa>LeK
zXz1I9+2v|WZ2XOhyiy|0iQ7ilC<p>&7WL5S_*5x57e%S26%GSP32!PbN8lYc`4y8u
zQhDHvyYx3Tw5~BK1EnZVE1v5&9eUL?PF8-A_Tj|srHx+Hd{H&AP<a(;-UJN?5%a;&
z@Bu<`Z6~tDSo82Rq&fd!hEpwu^!HWXzLv#Q7N~|#-=saNG{q?Q#&MpcY=G=vzhsGR
zSTmiS^;dPQ*sbz^N7iRV6!cvr`kYZbf3G8d2RHpynfXZB%QUoIgM%+HF1`p)O9P9b
zo|C5;$xFWDyPEY~#3ce|!d(Y#QPEP`_`2-R_c+9OKTRq{VHI)-po+cPW+7~XzGx=Q
zLFf?4Bo$80EZx1knDuEKskvG7xlUhHY2?YlUsJ{Ff{~s_`CRSp7YhcQ<;O1G-O*jO
z+>V||``lhl9%=K@mk#Bh?xoL~9eQ4kf_3h;_HQq5x35&E(r@=JOMFi9!8v@lTNHPj
zws!}Mx5xX%K1cbMCEu!-;?qywtGAp@THalod0r{rozC9f{+QK|y1Svcv!gknVX*ex
zukkrgu<Mq@{&JN@Ft}cIVn%RV1n=f<h~oCRB`Yh=Ha=!H|7+A%Gk8{6`h?qZtMzRm
z^qpHoi^_NT&`}@wKe8O|-+d$a(jd0I*In)sFcH<<4E9R#uJ|Z{WAthW=}l*enp4NK
zNiYcIcJ0ZRn{n_BeD<@iPMI{5Q403;ZmzS(hjMmWbk`3W?c)Q3ZggMWdIG(!S|+0?
zXcTNL>~SuR#j(d_4_LQCy)H@9?Pu`}I)L79#%}99hHtG*?mQ*jeP_i8)sA}<9UAg{
zgp5+#^e*s08|%~UGe3K2kGd2q=0&(~jl~XzOfXhAm1}e5e5|qe2A&IezrpU+2co(P
z%r~b@IzPB^ziOpvVt-n2d=$ayqi;CSQY5YysYi124ld9UN-rywKPGx)M4ENiZ}6kV
z7znHMt~y9~eQ3t4<Ce;^SdP)FSRt}^U`%>)_Wt4ZYL97iN4jZI<`yTq%-u48jJ*n6
z!I-O0@!;pYK;%)ysUm6DQGeWk4kmaYNP9kR0HWueVBJ2lZ#7zZ10LYAjVDx}a&JMu
zY6^a*_>p5IwQF<rcK6l6?(GQ<cJd`Ob!i-It;1Nt6ij`P4_>U)EWtFn`I$aDa<;u4
zw<OScd%PZeJmV$5^GSbu^XB+y*70UmA2?|u<CIN4yFB!?x}^6+wwj^iSg`^z(Y-wK
z_>Ih4y`7%5gG2DZ!%O)aa755mE)FrN+qsz}jCJbgBgE45Zv;t=-ZMN*p^99=byv{p
z25*fST^}iEnv}lT_9^iVv>He8%TvT$AA97>=H$Di`88G^1ZRXW#TAbW!N|Aok9tfK
z2GdQiZo6lF;2XvsIJlLQoE(f=xzW8r-aC1*qc4PX6}mk1*{@}T{6I&ONgB+LJqWaI
zVi$_NW(7}Kr%o|hk1O8Z*2&%as6o-xOEg~TXQgwoN3!aQ9TFwi%&J|Iw58YVN41p4
ztl|@9|EjJ&2w=G3L)6RCH{XQcqr5d_eW3M+fQyeMQ5*Tp%sfvTD}?UrXxptf&nheL
zL}eL=vP-s_#lhALHsbrK3D=_hQ6+Qx7VFpXE{BpQ#k*9OP=3-+s~Qs@Hi)!5tU6ZH
z7X!UlYbQ-_yf2%?!Rd8i^Vof^-Ilx4j>#3(yPuanW-mowpqtnjJ32X-K&<ay*&14)
za{_>X`)2?Ez{SJE&HYCX`b#b#a9_nL;pQZz>I88z0sI!+%OF5_0l+FI0$>BM8bRP!
zA)$Na-&a;iTN|f;Xqz$vnSlWK&&2{%{!)VL{WS>ozl{M{)!gk&0IW(7GZO#}fbExY
zC5VFwyf3ytZCT|_jG+)wTQ`6<Tm%Gg^6~=M*nvQR?k{yQxM8@yBY@-Y22u{T&UXJ8
z%x@#Vr1wqW2dgUFv;)M((eB=uk^3L9G{DKh+2l`246Y?^;sP}?QIQh87ydO@6%$8W
zX9pt_N5H+`RM7u3HEwwM-oN*rk~6U}b210;{5>p5sFjn61AtZ13hr5P6C+#WUzYw-
zWCL)s^K#wy^;gK;Qg=1qc;b&Yfz7<v`*-?xj7%#?52vU}V`-j{qoJW8tEpqJzKXz&
zHZXeoHH7|yL3BQTKrFWK10>}R%XnX6rbrx0M2jjw2<3PJj9Ejg(ASVO#zWakPT?{I
zOLOL`>~3M`#&fU#BWT^rduV?@mF7KmR*VU9h|lF`s0qcF`AdG$h$pBqc?#*=lZxb_
zeN@z06qIW369fe;2Q%D3Xg>|pcHGa)0&^vLTd@=LJ9&FR<jLyG2XoH2S3XhJb)eF=
zGTqnGFLV4(evnkGu_RWt-=a@Ef;63%O^@c|ILrl~L~61oaaxOzXfq78UDjxxeGt4=
zng*_xXzmb5pr(sZtGuw#WGE4{Ai%||tk@5^epdA}7nh1eYIf!kZuXa^FM^<UIgSUR
zriKhuX{*???#g5IgSIUmIto<p-w!*Es6bJQA$xS%)RJhR!H<}V0}(HeX%k+S=@R7<
zIMXAkh@uv)<d^*bD59)<dO(KU%I5D|9KaKpuVyhBqFBw=Fv`PUEW%1W38Sy|kpY#t
zws7W@?j~gKzBXMDj<wI+O*mz8)my6#RmFdsriAI8RmzQ(w@sZEK^yo3hduo>tqk?9
z?B#HCv@G3l!>%ho?WoEnvMw@XL3Rj!0S8X`fR$}*k}>U?FBA0(hp(HXboJygzrmy7
znWQG|0P~+X_#`yi^+Od7-hnx><uHWh$l(`b0q8#B-P@=Iq{jN)EtJrv#)$?h<`E*1
zR=nNq6>d+Mw9+a^wxf<1b@?({MV8iQGKrsh*4%GaDY+%D0*i=dA{ALlmnOxV&6Su#
z(-VLL`mx<FaU%2ep2+UZ)6vj<G&NgY!`vGEuy%|e>(M7OXg$^2NKO(|vPda}{ehfE
zr~)?s+LqjQq0aR#&zk>Z`uW<*DjhmF_tXp!ZRa#k(TtA#4zs_o;C4Ds_o%Ozi0*89
z{p_y#XOAFZI_IbCvhMsSD~vqxuCJo+hkisPrdHs53ty9z>aO@06D^J@pOswl0ns6~
zGoz-}@bH#YM>Mgo`m|<2)LY4D_q9gM5_#ZHR{UEO>jRSRmfY&k(pGRcGZ}`TH%|4M
z2jUP87-}+|4bU9@pfl_>TE9$)3)@&_>ofXr<q|hvMq9}0`z=0B_Ti%B-7Cy6IrI2q
zm-TapOQ+LHiYA?(ajF=ERq}P>g4ugfgc{r1+v}qzVrGKerrrY~F?5eibuUk%ToXD&
zTLMn5*$%-3)@oF38Lr3yiTKNk4AeO@xW*LG$c3cVD^GP$x~XW|C<Aw;_-9LwCJEP`
z@Xo9w5ygc)q)Qf{i?)8A>Hm&^bvSq-+lYUA>-EJ(-uGwu+o7v?@#Y%i^tNfo&!yW?
zd4JGSUU{6&(2uW&Jxb^1>fI3U$xPCzow3mw%xR(-wKFrTlNXced7dW{>!Dp&Y1%jO
z<$SjOgugJ%a?y*fSUG+@T-_d5m2u#kEB3(SPzPno7bsytEIHvDql7~>VLet1jI=EE
zv^*+h(uLAG$pw}HwW)dGwPbnoBA=s1GdGjx$DFML#5Az7j%3brRl!y~&s^l={ibyK
zb4e2dI4U1$PvJYs$|dM(u9B}vb!uZ~_V){b;CmCYb&0FDH$9SkzBBf*$1t)lalJ;7
z%9-ec@WhhwzGIu2pF!?Yb1vjkEplRVw6d$^^cUZlE9Q6BVBLzxG(FHumO7g<N@Xj?
zkCls~0UsT4Xcs;mjy*Ac6Gk<kw0D^DR{HTk4Et+ZimcVGx>L$`0%ji>M;p_Sp-SkY
z(J1apk6(z)qB_5K`Ct^`7{O>x82x5LaD=+s?838LKsw2)L9t0OB}cKGhz~>e!jyqI
z-qbvbhr*s9CEOY#6+`EhaaFyFKD5L^jkidL^;62R{Hd1Nmm-CdihcV%d(OoDl=Xg_
zBT5dty&ORsq0|wpcvD$YS}RY74x<%}a=gw`s$;~<))<m~mcnPc%B{3cHUV8Pr@VtR
zZ&<{2x15X*6l}6UK)gglFP>~%6xG;IHp?#u)Hp4?oaD<G3ZWGYR2+fIrc^D<BPX%O
zal71Oo8@z}rR<>3nisU4y@Iz3+0&Tf>w4gfF`r`XdM`aAxp0WymnauT(ogb+XAG*9
zD%Rw>U)LBMtMaEEc2TO+1oH)ozKptj*O+3RQZNZ79PxY#9DF4og~)nV$ma3%cnOhH
z_l!SiM1Z*e5ksBD$B&!D4_ptGw=@Me=&9qNnQEwKna$|R`f=l;f{SdkWxg!VR(YiH
zf|UwTyT*N<^$izeO*T;(6^2`-+t1<xGTTETZ<k>tm-TMfnDW`s&$Zh+le3l55eeU9
zVhkUDk$mRln(<gj3RAgzDnm7aD<+>9%RdUaZos@@*d39^sY;MBPRlUuP}Y!2L@hXS
zN+}5bZS}x5)GS);w@+344L^xg$;}rRO85c|C0-<XO*_}+ZnJ}R7wwbJs+_!|v5ET#
z@#2gh3YHgRs|L%M#d&CcH`X~-sQDfmGa8nnF&kB#R{6ZY`8s452bVeP0li^95z*kO
z);Y;E#y8rC&6?HKwYAJg8j_d?Z9+BEho%}-j0@U)X-7cQU5Wl=|0@aXCnSW&elo4n
zt1|g@>e<19@-D#^M;mz5q;;c~ej0j13mbb<v+~?ezco)U)HK$*2P9d0JpUpb6qrLs
z7dsNXXYFy=BM-K<czQ8|XWJsXnExnOS9i49)~7;2>sohXd}LF@phlvDEC<3c0;4P=
zj)@EXP)JbyYVHbsb-=}gzHoZpSbsbGM24#*G9qrSSh*P(O^($?g(1fpu(CUD*NT;g
z6~!2i(dmWlO7rdsUB{*!wAR&)X+Ph1ihay`#)>^<Fv0YVSy!QiqmsqKS37F*9f{-{
z!fR7A92zE>K;~Vm${O-S_v^Mz3V|2JVJjS8j_?XOr1>?*x%hJ*<u$u|4rerN-fUnO
zen;g~xnA0EygIe1aC@;YG&D4akHJ;fllM^*d$%{pyadweKbT_FcJhTy5iKr;c#v}S
z^G254DN}CN71J{rqL5e1iEdJABY~cc=D0+i`B|aw^4K^M-WB7Wg<Bgo)TU2-fAn*n
zWa6jDd)u@f5iL*Sm%yjVyDU|_y$uuN_*Xg{_6_@C<$cwO{A{N+W+u8=!L1md^jD@<
z`)@jb_AQJ3^mRa&GPTw08e?b8Q4pochh;L7vNT`sRIq9nY$s)wFbhf7Hz=}rTbnyp
zy#IbUZN{9K^F}r=v}0M@^NAwkbmW*4d&89gnN(AL^pJlI&rYmrdLp*1Dvd-+Vl*~b
zbaVwT@q^m%i?xCSbqUUt&%DFN#qyDp#{rswbEKAzFSr!<l?xISE35Q{ch^^SYf!~J
zy{6AE%dZ}~@U{r^sJ6R9_9bIQp~`j%ibtD5R|p(o-X7p9pmQRZ9EIuR&DW^!G_PdG
zN2%BaNEVK}$IizBIDE7W9b^L4Gc~3d$!st(X{0BNpY6a9=xSSi%|rY&56XBrX{fB-
zW)w#f@|b0{KM=|^#1aN#a|C<5@f^cT!WKg7mF7-I1`WS;e7Ksm-kyxskgxtqu-5+k
zd)lNo_@vt?w=0iX|7!Rn?Bn{~amt97)%n8Mn7=<PQQYhj<CXR)9ZgeGoT}SU?X@qX
z`{<!{$+xqwQIeHy9A8=RhQKjgJ!5E#KXi&>^XItIxdJY`cWt(7%``I<nTA_zqL(z^
zDbmiTV=G6(kR))p-Cd)gT-7^*hucle%VaZ)687)X_dJ(-3sf}><kzD*U;m_(&+j3`
zqC4<r2YEicVo$UH)%6poCh#UkfEYY+tL)KyuSMf|P0Fzf4C_roh<$Epu1izeA9vV|
znm>>YAM&8?r5-0_$URh>HDLJgq<o%czDH_?R{DwTQO<>DU}c!bESF4*b-J`3iCS@Q
z8TJ=DEDjoU6?c7J-5!%V0gXXr_T8ElG>F;|TH7rEzk=i%Vj{#^QR2sWO;V>-P(9hM
z?p{<*v7ofz=lcFG;7Ppf0dK?CJ0|_Nwik;(yy1&%lAb*|gb2@qHqA|OM)I`=)7KE&
z`trq<{D#7u3*Bt~A=!Obtex)!y`eOjscNx=PJJnwJR{e0-wOQOf}n!9WdfiG!bp~9
zuWR;<O?lp@`WEP#sCa8UDAr|_oOH#ip712C2;6`Qdr$y|r13>kNd%?l`ZGFUA|Hps
z-AP*7O)Q{1o4a|m(?>NfmU~i(yEN_f7~}v(>ZkHq&FTEatXdRld^E_0vYdvp^2F=0
zJ?{-10_4aDTyVqQi#2zrNp|avziG0yZe7qmk?4{-2e46c`St;bh}ylwaE>W7ax?M+
zD~Ht!2((^f*v7=ypMP^JKrLH;c#siyTpNuHK|S<%`NWjYR6@qNsM=OPFtl)mJId$m
zy`|<#HiarnvFG#puO`WgMqRc+kVpC+KZi4k^!ezStz`D7nsN0PG^m@e`|_8Emc%%o
zn@+j<eimt-2)K}WPGW2f#17QS?an;Er98VluVUb5&)(_T6tXQJ%3bauk2)*<Iwgk@
z!t|q(xZa)ubCSudJ~Y&Kb)#ovV}gLrlSXbUEuxsh-Uz`zpwe`HFl~EccZR`*MPIT0
z&Q0O7&(`#_<(VqWWv%&*6UGGFsZ!5QkIl51-rku3g7~Vqo5()BJJ{RF51f~8D2jv}
zH%F4TjGSiXR{Pcsp9`u#{CcU;p^(Ud*zyy31;aizHz!3QXLJMUQuXq)lN{gn{>sqt
zlarR@sfLEx%ND<YjiyTCs}DN+QLVR)`&T~anYCT7wPb6Ct<QssTe=RsJ~W5l9JVBF
zcIr^30&|qx9db@wyIQ6hm#<>4E+;R%!h?v<#iAHf`ELsb993V_P55w}+P&_~p1%X%
ztz`1%gl6nNUmlBNb|RXPDRX~Z9grhg9xLF-EM<<Nw|ZqX%i<82+8z_1gR(`EX(Y{6
zjq4C3`{M;O;L0viU@OzzZIsdqX|`+6M1BV}A@i`pVWKzeHSa*shjZg*3{~<*syZAn
z-b*||sooxubF%U!V8dJ99$xc64+k7qNUb+U0j;w!+sJZeMUM)!%!##{Z2e0P;o|hv
zVwk!IdIA4Sjp)%I?gk^~<&hsHo3*;RjZyGl%Hoif=c?q~@f44T9a&2AQeAV5heTf*
zlBz_#5hNa5$pC|&d6#5-V5UXMQIHII6>CQ%YuK=XGs9vFpmad@#&m>H)yLA5&0BF4
z?8PA9$64q!Oe9l%P-(;pTI`(I8u3(@+wNKatm%$D>D{%AdNxNlA5In@+mX1|_wbM-
zqB!71&e&EY)t6q)1ivGD6caQD`EILjN>Ev4;tow@4tOluLWiNhL?F@UEvTk6DrVi{
zvho-U8p!|hDTB!e<%xvsF>D9n7~Th=vEJU<BIpqeP}Bub=ba72@Xq^A<%Be>#qS3<
z58-7>eZx_Hsixjks}~k_DQBthNEdkQ!v4;C<uL!8v|e)F-fLXB)74=1D}!dG#Z<&@
z_8#il>lCg7gxhcU+~@g22PItUbXdC90vwfKG^&ha;Zf3~ZBelO{2{0GhW)0h8Ldvk
z&!$tzx|><12Vs#q-7cHM`$;C8;L_*CUQ_l_6$c(y;E(i`!z!Bs3`<SzP>j5%aul+b
z2l!**YULe2)a5#+F7_T1%RYACp6;9JA#)dCSSNRgKB1|&kjlX+VW!h$=A~SXsj=Ua
z;;DH$n!J5A=U0G<wiO(afz&Dk-j;S7plifpNb^U-nczYmg&-F@qxuWUU19gyHQu-f
zG}c5DG4UU<F$)9wYi^4kI})Iv<gh0BeWIhhY%-AcbI*NwT}}&qU3$fj_>BBq8=-l?
z-;(nn60e!i?p3SLBN!vyb=AXSWLV#L%@He#PO%@WMMl$u+Yv+`!h;K?S`H*3yaOnq
zP9rcz|Fa(k&q2F5&z<x`@FHTmacdXSEj3Js@cR1$pHF@jNJ0)BKFofgVAvUw(AOmj
z7Qazz*Po-Z8M`bzCk>k3GOhcDOEpMB*aywNi>T&b{Nk8@Ug!8GxVf=nD4_CGkNoKJ
zJW!w}Bd`;1EkS8yhA|_y;2z}p>Z9{8!J>WN(sF1ZyH)t+JqUJ-^L=m?e(on`XFxK0
zC+WM-itf^J3wT3?aE08c_aG8U4{sO%BSJb&XdOyB*!qazQ-ypw)^PC=VXR?^fci52
z@f0)61hD~m$4M;B_Zchi#XBaq9yHbjVbtIN3xft<Ywcan6yGl{Q{}wLwhVp)RSy@*
zu&N$5X0#n4eJrv+SVtb?F~C!pQF}nj&2#ZhZ3-4(#&2*_FXq|g>pU*uIZvrs6Y&a+
z2OF1AdS*NX-`9X>If)6gMEOjDP!uyTUL!XCB2B~HApUXul+tS?0{Vh5gwGsHW=QHx
z+!yGGee!NHt?Y=hD98;y^~Pv-1->-0upV4Z9oTC4gVL9+qKFu&z{ST$9B!hmbC2ow
zeY^M#6dt`tOJs(Dkp&V^qtFwf?_eOhb}A%OCcoe^l@~BdL>i<#3^%3L%1os>#3xgk
zFI#Vr^3ds1vwp&Vg*>axE9U!kGgBgy0q&jv6dB(Q@|^ShD}C+cgR_W8*coc~<dO{{
zp11J<8j`nhs~h4<sadLTnGvQC7t*({yywIZB>7=1h^`Z@pPtr=wZ1F>Q%oaLJ#O1w
z0ni)N`p()oAI%EbZ8NiY7m?bKtifuK8+3vFh+-%|(1_WmI)a^AVLET0oC@2#8+63#
z{ti(RFy;qXW(-y!V~$aR#MYA@cMn5^ed3=0Gg{DZ$}?;|e9xHujybp$p9m+Ds;D9f
zoVdJ16HfOXys8Cch?V<NBR1(qhj`M~x9KCHJ;RP-`uagQ^?@h7NV@OT;}8<W@0y{6
z*sqY9lvJ9K#g}us%@5EIP(!d`-w<sOX%8*lAsC_6%Cs`HLZW^=Msy*wjzZS;HT8Yb
z8q{Hhg#V<QrnNLK6U7ZtTLiF0s<ZWE4B@#i*Z0_X#nI+FBJ#r)`PLS%<=e+Io=Ud=
z29xiR&A-58PIfNPA9$Dd-xw&{J#PC82xk4iK+u0;p1QGpHUU6PiL(oI*8Fgs62v@Q
z(ZW1ZLa$Gi6bPZ2FKNX6ULTxQt$bJ8Lh_8Av()VjWf^cZ%E!ubZP_5?CZ@F%DDE4#
z3?T37DWpaLZSGd1`v|%!NEq9kId{~Rbz~KyXFcK5;cn?z>R}QTqDKf>XcU2OseG*e
zLA`pW$PvtwJr7WK#(Mb3;%uaD(nd1G|6+=mFTMKaWi_~SeGhx2RDn8H53{&<bc3Hi
zt8lqC$b#4+aN?R@7F2fp_I9taP(^HnCoijT2R{+ro;H;&zn#JHc`9~(nVZo9(O_a<
zSF2jcP`lZ(&gJ@C%lnTsXH1SuskPWFiHc$dFDh9tpKs7;_e?u{Ul&;nZ#H8Iz&N$|
zX)zcPOTt@W&OTur8;7nxv+Htx={9&)w^4M)5qm(~&g6z3*Ln5EKHNy-+#3<4E4%gI
z;rbPXzv2Y~0sn-H?H*|VgIWJZ%I~p!aT7-)2dJHst;0R={R`e#fLOz^dMPbAS#bqM
zaT5!Oy0a=ALjSv75@HRtatF}=t^(ZGG5oHyf|$Xva`wM9MSr9D%xpk*Ab^>Jiygqm
z%?pB~`XKhdP<?49h!xaG#Kz3Z1OWWiPQ=mZo)+L`=lNB<AK!hMnH|LWOCScZduakS
zGlw$=@NRyIRGmz$)d4)e+us*n{wdtg5T1!9?0|d3{+|f`J!SE4Z~X4g+0f}1U7-f&
z2<|=gODYO+H2Fn-{Qo=yb#QbNGlw|*aey4;uQD6^Z^Glh-3|B^kl%|%!Uj$fKyAzb
ztQt@o5gSM7AHgrn8c<^=b4NHU0%E(L#s7VRxPX7vbAh-3|NDSbG;ryk>;K&YoN?j4
z=Z$`!T%3PibMySiDi=JtxIy=s^nagRpnG-(Zinqp>)(3p-2dqV2;hKEofDoB_v5)|
zR_?hTxCH+AMfJcb8{1bl(0kqlaDS8eXW0Io#P^)i@7$Dy8sB^Ao_13Cn>2F1r<nf1
z+_3$Vl~QuBHFh?Fb2aov5U7JKfQ^NXlLbCSdUGcyJ3dx8{RNkrIY8{pp+=4@whm?t
zzY|>y&b2u~ZEeKwsWW<UK6W5GJCKK+2gnBE0dg?{+3A2lhJPCU5AXJe3KN6CGvC(i
zSAc&_;V&ZWKOB>rgNZ3R5WvQP4*dH7z{3LK1egMT%eXmtIN<ZSKL9p=$+&potL=Yf
zJiPE__uqQ((tVKbkN>pg;pKvR{J&(}oE*UaZOg?AVuwfKzx6n{xZ&><|0ClD{!5RO
z4ft;xZ16k6|Fq@g1;Uf&zx(3?vcnVXkIcyd0$<w>zgRd`sE5hDukLSRDz>)ppx^ua
l_wtgqF@?wWKJdR%$<Ybo;PlJ8++097H%dbzp(u&|{{RYy^H%@>

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_10-low_error_dirty-hack.pdf
deleted file mode 100644
index 4588d6b1975fd9b8cff13350d14858343a4ce472..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 79465
zcmV)SK(fCjP((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Pz00oVOp+wF=Tn^JXi+(g2oGMi
z0|*TW&|-ReCukvzFar$Ew`gf0>FvdEH!}}rC3&j<Mxm-Q?9e~PjdAgddHGte|NO07
z|5NI^e*M?a@~_MKtM>IgzJCAzfBvVh|M-8bU;q98Udq@1bN%;!x&He<mjCU4zaCh>
z{?DbXU;pdZzkU_}$@t&v=gfW`Yx(MZ{nf7j|9n~dbzDD2;QQ;peEsL;QLMFJ?RxqW
ztG`Y=1%%jBP5-a|{`H^!WjUg8$5*Yts;yh?m-zO}YTu9Y^)H|0KmNDBt$!OY{g?l?
z{D;4lU;Tgjm;bT+&;Rn)0gn|e+pj*g&WrDDv-AA5*^xp7eh@qAuYGzI%0CEg{nyd!
zBn99HF+051)%^tiZQXzVI`(GmdTTGg&i$eL|9a<JtG~)Rw+_G$tt<UkInPN9z`NKr
z{q9qlzz<?a;Z%kgfFHy*i-{Ej5XHYZ``fnv>JPJj{rAlNX8V0A6ZoNRZM{uplz$K^
z?LL(Wyo=Ry<5UhY0zZfy*W%Vo4gi6F(-2(ks%0<7_12^PTL1h7e64?d0P5E6Q<=aI
zt+VYul?nVHc74&esZ8Jpu~O$XGK%ja<?NhT(ftJetzSSttX)&9T%YRp)cyaSFQDwl
zZ7QSuL+iG3pUMP&5WD{WHkAqdAXX1fWrzXzL97%`EervGzxV}|V!!I27oo3z#~yIn
zeI}#)-nM<e&tsI|g|>B`#a{YhpJ~7C^X(s48|#Mogk@*T>GW@&_1D+AKTP_6*P-XU
z&))MNn7h+CkU)7`sICuU^i_%pxOVt|>pIY{dRo8si?4odqxN(V`Ac1LeeZp$CW^0Z
zyOy$cbyx}scoi$xx;g%wa*4bPUh`ml?~|aAcR}lM_)b9~e_<GkU8lh9S`E(karg_P
zP`3KpG)v^YiTnB6L`&pd@Z4?#&+@BKy^bvRp-<#p@LEUjW1q-h7>RnV5$*i(i}-6h
zW4+FR_vx0%dn32|74h?x$h+X-=f_Eoz`NLa9ah)dXb5=~Y{hP4&+=awiB{HM+tK=I
zZzJ)Sj)<+5-zHlk@6Ed|d-utf$h+Wmxx9~jBJYCNmFPb5iM$J*$9?1l{FSjduXn{^
z<#jCn+SYm9G4GQtk=G`UJFVRo;Y8jA?R0^8>m~9oxNY8flc11y!K2MWUiu5;VAl#<
ze*Px@(xLG@f17BDyf$qpc5V|*z`Iy$zm0k#?}C@Webf_q7rgHJ_fb#euN<BFwHt0f
zeiMJ~>~tMdf17BD{4lle=g|8Z^ZV=fAO1(0?9Kh#X!yA2L_6zoeQDA9-<$mZjrLB<
zc>T2=^%xuKbp%XR<A3;n)h}i3$5F4hZr5319k0JWtE+GSJW;QYr;d|I+`zoFp-YD5
z&+i61b$N*xE;0kTruE`bT=oE6NE|tUT>rX|TdCky>BzW~T*x(Nm*1e;0gS80zWR^f
zfUNFlM%_*q{r*~J$n>gl>KaIB@Djm|+JWm&1IR{ty#|zxye7|u?EZ#3lFja;JpFqc
z?_vYZFJ9D$B+{pTX|8OE6&%Ruy9>FxWtkD1I;Qyz&%8o`)b2obl>^jlc~2GZsrHMV
zPz-t=y*iMZ{Zzc4>eNqH_bd*npRQ8LKJpU#r$Cpq;=<~PH^#rGh0titwLq{}5@D~z
z3u-^q2XT!XNbmX~AJ%@T7fOs+-!;EW48esI)yRjSZ{wx>A@A`EGS$d?{6dOq<lWi3
z`ldwp^&Wi$$ZKTkpW^*C5cbg;UtDkMqxb>_qCQ%q+j><Wt>~kwK3dU7l^@iKE{aiD
z0C|OqX3mN(D(bYMkhm5!b=iszT7U6puc|K&6xG<f$M|6mWXwOy&oUk!NKt*qzpi8c
zF-dvvTnNPWm=ptn*nUFMxMP;?v3d`no$={i&{#QeTL{4W#x@QFE@!T<?EGQx3ENn@
z+Gx}k4#2zNLhv~c#9vJ1*+9J2#xWTOkn4TRfGTV2QvxcFK%&u2QU@B{D0HCBSc?I9
zmsgHtC=3UHfxLidB6WfTi6#~w%EbXMVj%Yeja)e-`+=dw=wD@T;yQ_xvEtQsPBPx2
zrqSOIFL4O>XinpTJb>|%cH|KH@D7AS7zTmb_7w8QH0s<2;vaXzxGxU*7_}VuIK&Ku
z1HZ?o+%}fR0JWYHix>I$hT3<Q{O3#)C0;cUPLwUax@HTCQSmm3M8(@A67|*xe<7pe
zTYT?JApS|UI!Q&xYvbKxs~HF<SM2oz8Ix;q#JgG>@7_`0brNb&)8{h{n*5l5%YeKe
z>&a=`qbuu?QeNVWH7NhJU|+~SKD)Y0BKmb8DdpW)_esjTuWpl6tWkBF#G-cFBo@`v
z>1Q`DQG&J!Z`T6In_!Y?sGdzyQ9bR&dqd~NX1oCM-fNRsRIg29KA5%YWjLJG_~w^@
z!l060Jx)ZmOkz<ZE&4kSA~hC${E$z$x=vzIqjeIC4%3MYC%jrtZ81A`_;N}Nn|C=U
zF|Sd{iGh8&9N9GNx#i$=!j@b1Ny@vZ<mABKc_9@`95%|5lLPx=*)+Ye36_no!k$-j
zQrpLdwm6bP-Ww%1g!L+EGuW^%6|D>#cA;Y0*ta<1To6jp3vCjKPS8<%oNK-IElO?%
z+b}=3LzXc<9=k%(dF=w?jXJY!2i_Vdp(UVrZJEU4wXm>WfETdzZaW&ga*>a7^VMVP
zNr}*j4FKE1h6Q^)xtrjMSy!D2wm7LR1H#YvpDD1#i&q`-Hmtv^CdGyYcir_NZ&+Vf
z&5AA7g@L4)&#slTVz@kv-d$r>ECG$~T{SCkk{<|W#f3y8`5V!|oE04#=&Cc}7L#Zo
z?0y(^)}~Rz!nih#!B8HKa={gAGc=M1`Ymp=1K<dlm)MyNovF2BYaGRb-f#XAoffx-
zcWC#3;dmhIljbGdXSP_+u4nY6#FACyzA}*RWp+r+XTGyWkGV0HkeApK1+UPl5muja
z?wVJ{U*R)w0nprHtgFEm=c1vJXLqbHBIhJoVQ1ddzG(L_G_!r7a7okiKx%h@lO(>I
z3mK(;#yPK?x;S+IiUxo-_E=vBf;RROoz&RIj^pQm@WcLR^y9cqxj^OE^#k3cTSY%m
z_o_9kALuAP5H;6&(qnxd2<y6IfQ#z7$F;4TI%)PD)yGK_SF}-PeZ%3R96E)>rOgrQ
z6?&}d147?k$f(DKMCtmMW=fB}e;}+`j~jeBG*#k8cOhCVx<O1^NRQ8PAbhRG)Vd%P
z$B-W#-(olXXy>=sVO2jmCt#1Sy&V3!1(0|C!3#x?`}+lWsp2=ZPIP=+ht`Q+SutJx
z<IY&1lL;Vdr|U(>H+ArO+3`soeg;?o`DDT6JP`lkoC*a$oKs=N564Vc0*W!@R9G>B
zE8o4!y!P$d=y0K+6Ujh)K9pUT4#U^6YiF_8b;_;-srhDEt}6h(TpN4ND071~%zYX9
z4L8$*d&59tD=NE|4LCEEIQcJtysLK27mM@kg+%H4m#!d&dA@717=CI%m@T-<mR*V>
z+fX-MNUg)WM0<_(Xk1DCo^{ks3yHZlY5+Zo{_hwIIj~gC1B=se!C5qrsGC$tW~iHX
zA9=nM-E!gSP<CBkE+pzEC6hJuo6aiMu9DUjtA3{#NJqJQsj?U&x}xOM6GydyVBX_w
zwglwUbJKy=qBdpIffje_fpC_taM3w*%(6I%4v2FHTg9g1Op9%@q}H*;R<PwQw~fDR
zBDDj~K|Yb%j#5V{s;-R%_u#TM?SySZ-L+FROq)$RMT;-GbS<R~Ee`ct{1BSl^+DlE
zS-P~U^#rm_h}WpQ3+&=R!6Pwd6)o%=N<M<uGR?pG7<TQhbr0QM!Ac&`)rZ|UOR8TO
z2GIF{m(b_oJ~IFwu4>%bOQ(v}aI+i;CToo&z(CMRHI4uSDbN$wj-FKC){dUk=YtDp
z={mSoL$_6)J1RagR0iA2wcf^lQycnBw?JGz2f}`8e#sdK=3~7+rBnr0>?K`CyIRo;
zx(VPWT0%P*EiCXd(}}NQ?=XF46<^SWbd-I}?c_zS;-qD##xSmJB^8J@&Q*4(eyf*I
zw{l{wGu<CbeAdM@MGLkC(-g%ubs!yO?|a*ICc2=gzEq9{v(U5)6nu%caY-mX2`$bi
zW2P7E0VX9y!I>wtl4V1`@f1;TwlQff$`(^}K$yJO4K-feIjp6l=d@Me-a3$uvJbW8
zU9}kArH!Is4L5xQaHTDBQ5%R4Nu#={zzfj)0$VVpOh=DW@fw{$OT}xnd6a?=I<=jp
zph+QugSu(sC|GMvM-kj!2f_sl*VhXgrS<gT(PUpwjE*Mz%9)`v>U!Y#Xe)|7FH$+W
zVqP>EH&)kZ4uHRklW&XdW{nwCnx;AKr~~0|_|iB4tPktvrC2Z59(vW%w5_Z$7Y2fX
zTCtBe%<?r9Sfh+tvtom8n>Oe**1D4V)fETSrYq9gyoAZPV!*M<1cKUaC`Qe?np;pa
z-Lm~QI?8M<Hky{U7hFF}(-e;@=m4Us4L8t%bd-IHG%ou~!xeNuQQLvU_?egD#MpRJ
z8i21SQtl2UZmX@Ky6waXQTpD2#Lq-mk8*TA^}p@h(8M^-1QIRehcb}pdwwVv;-wnx
z!{*bd3~J#pIO<l=O9P7bVdH40MH9Ji3?Q0V^cJiGu2YV>VYg{TuWH`HRqw&EjV}A`
zgkGRg-?$7Y=J~2O6%5&`p2A^Fs_6^y68mJunqN<K{~CizMfCu@&6T%>cElO0GFoK-
zzF5T3V*%u?t~}zk<B+3tN7;L-9+*%A@lU&A16nQ!lcB~>_(Z7uPDk0hsd6`JxP=yJ
z#0L_0fy!ISfNK0swD9N>VhcO^ZBrBDyfhFs5xYX&)I{8K>xL$pgxEy$QbBDS*2B7S
zCL9gj-}UB({^uv(VAn6T>&09pYR8+ag!twXgVyzO98zo7yK$_j#>+|z7r%k<-8h3+
z)4Nwm`KxzaI4iX=%YZ0U`Am#7^)qef>}YJao8L<1?%8Nd8xTf&=j@=RU?3rc*}QXx
zXfeUXvxF^S0Te>$2l#-L%0p*^UC0sq3=Ro3{3pg-g^8!ss@fPPmX;jYXB=7i45c{f
zcSaCIyKxe&T7}|v=>UEMij7LuLJPCT;t(rSDaE=JNwF?Pufl>J4k!b_*3n=@D0S69
z;iOqt)h9NSx^kelQ$jG%4Tw@0tL>x|rYtUurQ$j|0LsL)Sq2nB{&y(Xik7=A)&WPN
zZd=@C3Kb-6!-idClxfh3m!ee>3h;rja$WC2<zhxGrBGo%AV_%$vq6TP1|JniP&>?q
za!{+%pm#2X=b3>}tfNdJ3@z2j1+jCBL)`&<{#%t0K0zvm%Yo8(epg)!KEJZ7vbb~<
zEx#VG;br_}Si(z*V^iy=Bw))PkgpA8=Pc~lItp!=tsfFYU8#93yCx=etwn2gkF#Up
zC1U`-<Q2qw48WI3TpdO~^^HPk12v=wIvr)optpOdq8vdJcyyrA>_WVNi2<LNfnd$S
zZTdo@bp5Nd>pQoJqAh@$&eGWuh7V~^fb&Z!y!{Mh2rUjdP$a~r6bWITLrGaW8-nk@
z$nZO$n2%k<vtn|&h@F^NH2*cf$c{1wCbW%9K+!@wBor+Sb)yW14cAmh;;n`|<Zu*U
z0K_aYe#f?Bl5lfshViCDLNkuH;Zin`7;##yn{mXof8jzo5R9n#ulm1?<43=iW;hur
zy0TfrSm?A&{a$J8fyVLE`B_n8O`X7D*Pdut=ZkhlD_p9Yx}jjiv{4#V&jq^7X8f2N
zr*Y%wEVEi`{G7F$Hh#{{O9y&adn>$H9Eq-IP$@eUm1(el6j<w8!)3ozc16SazUai?
zV2T_N`U1D4g6POm_SsF<QEObJXQZQkT(cTiX<Cw7<07qny*2a}FX63K^j6iE10QpT
z&<b4e3S+Drm5H)aH{2U8#7jKG7do~KD0*u`yo4^VxXTrqG6xc!S7=OWINq0{V@8E)
zXF_lQlfAr!>X7Bdfr58opz5a3$3zUT!q8PH=ZTCT>hYoKKttW&4T+8kdu*fDuM`eu
z)lxb`Y&yP$TGh@(YP=icUG)Vew5l&K1#nE6kaDsO@kvoLR&+Nk#}oqEsHwRjb^Zma
zT@pBA1gEz`hjIhhbEy2fVL_Xb@vmj-g|%ziB*MN!Z?2}kO9VBJ7E)2dL0X$yfMHx~
z&Z?LWYvrs`xo{XUho}d+A(~aud27j81!VeoVqsbH+lfhD&)>h6flObEBL|lneq;k;
zPsB$!5cC8Ao>wbMTxf8nsnm4n+pjRU=lW1RBraEwQNAra%LVm$<?)BQ79O8A1K_&T
z(CkocXpO63USGHp0^-_jXcDZlH-t-fys75O9h*iyYcAbr1WzW^@>i-dxC7L4)k+P|
zu>r9MIS8vd5Pg2|Fw#)co)+DCK!=grT&1R>(BxAOo;9&I)&rjych3PdY`WMr1{9se
zeYhU{>cVt5%B|0P_k~P*dp&v{B+yaROYo3z0n-_xQX`>rMm?sJ2P?*-hoQ8s^GRkP
zwNHngiWrAH5Y>bCO`Mt>DL5jrONvf(m_G0d_XC@kR~_IuHK=dUxvx^+z=L6>!a--p
zN__(km`gyE!bAv{;5eezoyQU$Ve8Ig2^A)F*Rcd=;kxrw!qf7FeC26+1d~MX$9cQ%
zo1TZM`+~mm%sygGD1f$go%7i?)0rJ}d`EA^-C-1KTsAO#JBOFokAZBsDxo2bGO%Y<
zsuXm~sqmEKJ*e&+VBVA}6$*Kqs?;d(##Q$sDNM+n`{t&R;VqI4So7+M(b@PF^Nu)>
z5W;NRPF+3GfGuy4z7y3gFOg`$c1Q@z&bCVk1F-Fq;s><xRuS*Pjp9&cdAvDPSsrf=
zRkw#BUU&F`G^h(Y%9LSkjW1$lO(IZI4rrx{0l(Wq>O`SIi-EbZLET8bMnt@XdIXak
zAup*OVZ=+SP#E=+dKQm-p`L|ZStQ2Ftx#>QC^aa6*p*a9uQ)Jy985^Cdi|6Xs@G3R
zq3ik~Dd<@$jP<F;8VJQOGwG{UskyIIDbzxXZlzK|dbJAked^vSl?qbNRjL(2hZjH8
zCB_<ciJ`;jepRDcF(axD1D$)e6pod?RZ>chSQ<#NE|?Wn`!O7;mehcbP#Q?FD!9x@
zkvfo24Qu1<&_XMEr_wD-I@{Wdq*$L-%3;j(zDf%B6-L~o2AL5zsb#LAcc2=&TB@O;
zs;*Q!K$~4d>mY4+MT~Z8#4A0Ts&*Em|DIIqmHtaozmM3O1L}9oTZ7gSI{Z<tomzfx
zA{~@u3h)q|bv73;1Sd@j48eijVF5%#1z(<~ig>wAhK)*91g>s@goaBdk^#lU(kg8<
zRP5|<tQ@k%RQMDvX|Wj*H+!FqIs=Hors2nfa#os!7?1<I(E_MXrX_~t(D>x>IDIxx
z4J3M>x>%3N3F8<IT_fTq27tD(3M;eBWwk*et+lc3=zh6jR@jvX6uTnT8?w_~$YjU!
zcpSHH($+VS@MMrha75wkJ#B^+7T`214kT>nTD}^5XJnkLZtqR=Wu>k|Ce9Iv6UNrU
z7tzkmRcT?cPFhnLtRsV~2kXG#%2&aWSvK3+a1{!}t|KuyWcnQdZOZH{Ob!{4J$lD$
zBR8%A^~n%TqK`CIGn^-E*_EDHvUS%`nJkk<{DNdJA8|Wj%BMxWR=PXT=w9iJm6rJt
zxD(Bx`My$tA_KpN^7PpWfRQ}mBrr<usU$CgN?$8^8dUmP$rGVsAxdwBT047xQ;lKo
z)+b&KwcF8bD8l4A!7v`US41N@7vO_Y={qGCjf&kVy*NCIXH8F!ai~X#PI`xUgpP}y
z5~HhwP8~G@GQ$aFl%kPxQ>oC>$djeY4@&0;`9bNhP-5d)!aatuI`E$X60g;#RgTFA
zr{bU*K02cmXI?q+R2-Sp(`O)X>(P(Io*{>!3vg$m(OU(_2}Vv<TvUo_>&5jaJ(Mc0
zQ1W709HM^|zU{d5!5u09IZIXOnA4rAmd3W}wuMW4`ejw<Y}0wGLNy`(t_yJ2FK=5c
z3vvys&_Bt4%#j!}?P>*+g<fcjL-bx_+g3TRv2i$q!sBfO=!6HEHmud-W7BPJ0C2s-
z2f0GID)+mA#OP?kukeLU7e0peq?;c@d*li@fNf1*!BKAT4CG07#Q{|=ha-x|Jvdj@
z&y`AYTtt{p`ZglWXPF!zJ<i9S8|fffS9)*iB)rmlQ@hD(Fu&3nv##>qL<ydoY#{t;
z<nB45dcu3NW)tbYsnaQ4ue#Ja!}Uter-%be|I`7vyQefKE1frWoLr%$k}K>$Hax@j
z6$BK>oz??{yc2Xhq>Glkay>u@&vcYSW*hAr(LYC@yna1AXq8{E!h_Ot*du`Y>|MMJ
zDEweKQ5gbML=#Y`m6R{@h>;05aQ5xuK{D<~-6RGb`o^`zBVPLKUF{Js?n)gs<}Ke{
zvqy+ZxOUU1IuP%F`gVKJO1gfJFqNLp;Y&oac&&I7A4pVPjXCH6&V%4UqUN|UN3=_W
zn>(6!;Kna%4aUEubG*mDxPShNQp^K7*AFCo^TYRkgtmB#<(-dsm~`GBK&N~E0w5gp
zxs43Oo4E5Zh5(r<m|!5@#9bz>0r{t@sDuJ`7lbZ20!0#|8yHB#(1&FJeF}{z&>Sjy
zqR^R1Ar=LEC>e%P$TyO)8U<7!8P8F`$B{uF2(_64LrS<jEfF*_N_`3`DWI)D+zF6~
zx}a{VfLa3aD+{0))m>8vchP;<i*cA#tW2Sfau*|qhv@j*xVo2}Q8>I^6#7Xic&C8=
z00BM=Apb%c05kyq9YhF?azsICVu55J1C18eKBJLJ_);lci9tLHaw-V+&p4<O;r+`L
zELFm}O3_p$LiID^s?fK}W3&o2pdP}t0C5323k-n4VVDf`vr@R2&n9n8oE2g+b%dK0
z1h;2|TA|C8qSyu!&uH;r3{OVL6$FN7JRLtW1l<KP1?BNW^+3J_fKTl+2PZr(6c5Pn
zKVt?9b*6|bTmnLLA|B|BOGFuAiK-TZD!Gb}l`Gn(AjkoEU}b#Y1p(O^L^+VCJ@-Ve
zk%iWxfTI3d`8Nhvc9bFllDpqP`V<oC>$Phe6gOI^sy(>_ZpRdQTBx^Gc<MkH<q9o9
zp(-~5U4bypl`X`qSGerhks{9Z$QHt+t(e<^L|3sCFQN{0Ahl0Xy=CKtUZKAQR7eO9
z4!{Gdc?v5Es9rUQ45*ghehIcD1}PWlku#3DD56>$gd(bW##(&aUZ;5J0mPg1X>W$`
zZGGE{scz~QTc*(MaXg3@X+PLN8lf2Qf~e|_e@8@hrvkAkq`IqDKn}6yWC1DHs>u@c
zS&V029EtX61%R3xk?}yhCwI*<kUl8Dei<aw(V2%j6O2uW(Ju(M&M^MszIGYtUp8#;
z$p$c>+LJF}l!IVlRqul<NxTDPBfG;2ulTZ&-9aY`_t>kl=#R2@uuS9w31*4Pkh%gb
zd@?B%@KaUUYYSZcf{J03;>B%}aLNeYGz%iMgY99IMtfyFEbt0U#)xqujd#jjxgcme
zX(tL4{YgzxI(U9WU%{g-F3$^)wM;A+ejv7EV#+A64v0;oAhcVA8;e6uFtJMrL_Or~
z7(kb{Aj(mfV-g8+4IMr^Sa@V@xe(EeeEXT-dqGqrC7c?;R<Z!`=`Ko>xH(Xz5@oN6
zOcc0mBzej*5bqT+tc<9`Dnr7!y#z~4)mvf-lSQB~q&(?f{La&hbV-3kU2GByk{Fw$
ze8o!w8eXufwC>{)7A!GcVusG@l5!o_l4LjoiO$+4sXlS)l(4f*ygQDph1@&~pdgLe
zC$XrYu3NpKf;l6=I}t=d3n1^rlaq)<JLe=6U6_-ifkp|N$>Mk4J~J8l-S|8wwxa^O
z4+)V5F!3efdc91fN)C;7i+G8VnpJAu0@u_ea2iM_#nS@7JGABc01}>NC^_SkO>YUp
zCz}L<kFQ0|u`r9Qsvv4V*{q<02(qh!7=DsrEr8aUG0PPhNvaj9j`Ns^x2XIOH&^M{
znv=iFAv?(N1ti$24oYEp7gJb)C+?C|Vg-h>q#JXM&FFk_k~w0BNXrVmcVR_Y0Qp=I
z_Zc-oBu6Wqq;@()z~xsIYm3xLNy9dfpmWoqv#&|zHWX66T!`(hgzNA!QNj&q4<0!Q
zMGI{b@=+4^oGZipy?JZ^`(BdR4J6vQv9y+n0}m>;q{$mV45YM$#mHc%;kTKf&sBN;
z4l23}42~fBTL`UXq62iLpttdy#9|aR(oh`Mj4d9JHyiAP1#eCMLh2ur;n0yju^>i3
za1cC7rC>pHN1YrMn@PA>(Bvd#97ueQopzZJ(FbnWKc!78Fs&v<WPywK#3NaP>oB<{
z3kW5WkJ6EK=Bz9RemrobEPy8N%Yq?HeoROD%%Mr8Fo-sNRkc03M*Fwz=o{S#C*)Lh
zytlShU9*!+bXEUsNLEqQKZ&q^z`rL7QYg2ViKw)IFhg9X3Fs&vUh(8ZEtvD5OkHk}
zwqz*QlX=yVb!KNxgbc0)R_|nab!6g!Wm$?F+r%B4J>$ByV4J1RKe=dUBs(gIV~?q$
zi11p6d_5w^P2ik5%DH6o!xRwT<wB!Ga`nzg_KQym68_FWc8gySlQ|d=n1u_%6q0#3
z5z9uBzIahl2Op%JNDgEnN6S~rg^;Dr+XY{DY*X(LIW%})<s-i{BBI7n<BwySNkpa|
z8+~}3Q;z`v0U5{QT&E5JFinFopl6w<0TB3vXl9&cng$Nksi8i>&N|HlBF8*$7x#!Q
z^Tc(8Kis`^^yyPL=TFQ(meX{o<QH}R-8Xjj>>2+s&-oMckN50zUj;OOXP(|>{>*%t
zIQMyR0n(r=hcRtHxwv>o98+ictU8aWvxw-c+1<}N7h|6!=Q%CL<8Q-XI~QXjoHgLI
zYpEZ>ialJxb2T1=+14_x#-laE%RE<OAG!hMZZ+OA+}Crr8b8@m*@2y?rM|=9Lpq?`
zt`4tJpSG*RYt*Oh>hKzMO{P6Ay~9tReH2SsTeoR<FJ7a4+TEj%q{4`;d>Ke??$IH~
zw3$bT9Mfh#sy4z8w3kOj#DF$c$UCI0(}|^({2Jp_<Jmb>J@1QBa(j>SQ7dH<^Ug>W
z#i&WC(;3YBq2z{l#?sk}cD%Suw~{-auOm&)**pL?IaBk1I1-WQgca+4g9kGYnoXf?
zJd8H^5%a*>7?`(w;Y{1)(~EQOg>3huaVvQRUA?4pbo5wDbwr%Lo4i|jL>~yRT`Ssn
z=o%FV{bfL#&i>IxibM;g%EX1D$<>pWj#k&WHN~x@$wiY_m!=3|UT>N_D|rKIRm_{b
zCJku5N_l(^FGX?NYVvO6jcg!0F23UuGva<y#)n8Qh`jo>s<DroVXLMa5hA4qlv2?K
zlT<|;WU9b5wZX{`_t+NN2i<(f(ARB}i56^<=@CZN=j(Kvln=0kH+j|ZUf$$HN85Ot
zl@DG@9fGeOcf~{W_oR7<%FdbxpDj1dgU=Xf9v0~<+D-E?y7#7d@DE^8JVfVC$_K-g
zpOg==Q#Lx8Q47;1-9s$AZPGoAZ+FD&!QcdKPit+G+2fHEiQ1+5!B9P8ggdoQ1EN?*
z^-?|AQNL7AcGNGoX6VBh;rLCZSwulf%&WLf@AA=YJ43*SZmzXl4Pt(^maBm;HXfq6
zQsEbMIVPdLIFK^YS?46=H904l=qz1#`tH%B?C;pyo8@fqHEaM9h>DnI!?>(9E0ct4
z5gF_n(5Q#i6!8wRoC?@5Cv60_N6X0&oiPwjaBPODk-+V51oiSm!p>%SPJ?QCK>Yrq
z6G!MU#ZL4D7l+uBj3@MkO7dp8IGo-Sn<RW<m=4^~!#CR}i8wk~n!Q%^M4G*@SET9!
zmVuV43%4CK=Y^cD3oZ2)us}4E{Tfz^X1^IS8dO8eH*FoQry(Qu{?@f!xW%M(T2K77
zT_=PM3|Otpcnz}*AE<b#PIzJ3X{o@#bs2&63m~8Co%*V{KsWge(azMm<_2t04J(sd
zPq2u}M~GIf)-^Z$;yq{tXc5AS33nja%@zkZV&>cgX^ZojoGK4k=Rk1qEdw4%5Eeku
zLaDD{32gEjqP4Jf+8d)MwP^U&esP3--|-@?8o2DY&V3{-o2_db!S%n9?f07&(jb+P
zS#=B=vV_vgN?wX@Sz$q5;a?C;wF6?u#F{w}bPN`xRHDEv+%_4!Hr@y}S-fCiZd*es
z-Xm?-=6};v!BVreY#<KasZwz}II~jIPVPh^oj>A>%9a!5#HP6E@&Jo`+dA8abL_UM
zeK@3UQg(*rzh%lExCb~yr<N7{#3QGB9W>E%(kG#9hq@o03vJUX5-N|j(WQ|d5d%SG
zpadBReNo2AOP*A4x*!wHw;VItE=?!G*9M~vy++~$unZ_V20kByDu;E6(QCT~-hG`$
znKeP4>|I+1yh}*j6G;4uF81z?;@m&-VDX`4YN_;oYP*!5aC~W~EWWB;M+f-MI9t)|
zTeAeE5#AKv%+6K7{c{FS5?j2XCQ_ck&1WD8V4y2d+jVJlXQAM1`j#tHW1eO@9JM`1
z`M{lQ&tb;=-*cF;v+n6XgH2PuO`#$PqAL1T`L7(hNx;*p9oit^j@6EIn_HC)@tY1@
zi}PsF;}5r>LmD1<g0+K}N_dNrvFls@Rg2Sl-Q3RFp_RZL(?*$2XK~dyG&$heHV}j_
z(EZIB$521)S4T%FnoJ!K-0TKGZ?}e(;?Ncn?s_ftcka*E4y_7s_-luBLeLC?c#W=v
zQ8!&j;9NKm_8m5wgIXfEceNvawX<%tlf%)mrAp9!A;~KDO;;}x&wb0E(%I?gE*Uz)
z0kQtrGtxr~ZEL42W^f7{i25HNKxz`<BRUYeOF|!X^3V!j(*eL;5(iKz7U8ivxcxYT
zd<RHJuHy_cz}Y2s3Bo|M8q0Jl5z!DQB8&#X@pjM|CgOe6PHh`-6>}y<`SeEpwFAHv
zcrY@;4LR<c%OIiLi3}l2^%}g6ZPm90*JP8s5gnxlVJ5pA9?s6HiAsl(gw&hqCGGT_
zMq~rRC^{$uozqiZ+aacS1aL<<Iq1!^+rrIg`AYY1lU9x{;)8LNp55cFKFUo`>|G?K
zBUEZ_UWD&^tP{5GU+Kj@I8Q789G%GziQe!7k?*^q?{;;Iq3bgKz|aR7f6&nfN477n
zq85}QU+LmM$X?mLjy^cmLf>GVA2!bO5lmooT|%&dxmJ*|2u?1G;E6bE4TNpP#zUIg
z412Jm*fz9nP~CD2qirV5Az~~R@!@75h80C0_>t6tlEX=EEon0l>S3iSkPOivmfRIk
zaGD5>7*%4)GJ$$q$v{}drx?i~5W!+%c8DsDGNLw04VGcN7D*^9`4tdDW1`4noQ)+{
z0%$G<>oFr<Kv`kpIVcu+bnzmK9_nhI;We9@XLwB#3Lvz|NFRXUBWG<!$POl#l$s-W
z$;z$<Mp)ZG7$dadH9Na#M`ILugQ%*(IL)7lv&lkQ>I}^q2!7{4ixl~Z@Gi?hdHl<Y
zwim>bIRr7pnhox4h#?-$GF}}qYnI+w6%pSiB1T5PkqZ1<5ptFx<cOkk0&%Pbh_tf|
z7<U@;U?PvPf|u1mA{H-ZlqvXosZep6+_)GlXc@JQfWm=fn4-VQQ1HfC%>YV_Ud{MP
z44<637!K)-?lDWMkM-iL?`RSBld9Dlk(L9gb1>!rSlyF+^U+Ty#wkN8vE9@Sr5GcH
zR3c#1GK9LhOSdtC8bPO{jH)9r)ug#)@aiDgXP9h!<W<?25CiMbJx<m#WE!!wR{0?`
zj(h9@V--d??8pGXK-q>SG7J-uy`D4xuQId}8o&hs!UMpY@Tn`09ixnG3X<;8D1~V<
zdf7xp%n)bGnCJ~-HpfJd90}~HSO%<#3IZ{wHbqItI$%?fw71pTszHgCF&)G5ttfAs
z!ldI0?P(k!7TcROeUAt!ABdms=yEjxhS85p%P2F59#f?G4<M+0Bp$~cGsKRWoaqo8
z&*bFa3ZS<Pnnrx6DP|gB_yZtg31aoFiK`(3`W+!dK|^=a!Z}C*MhOG~*lse08mt1A
zG1TzDvX-0-agMi^oD4WnSreNOcn&NhtHW?_46cS9+*<N7Y!V^$2{;$5{YK2-89VrL
zoFiKDG8~ZVTGpKdVgMZ_itydo2^s@aJ@%4$LB8pvwRrLnQe$v(C}I_6Hj|d0v=;-p
zQDejpk;$Y;jNBNQB3flY!(lQGkg8*`4CD?vj{(G50PBx6?Y4-OG=_SI%?4Rhf`Y>^
ztGEoo*kYpA2SbT9?-y7|Mp72c_zp6DQ)oCyPzJzyY?A6I$4eABi=anqR85nU#nZpw
zS8y<BCrTlqH4DZ8Yo`Y2VBN%o13kaV1CvxU*2IJZI+}rSfDnpn8IukLydyDZz<o24
z-eAgr8^`3z3I3eLA&~VHNs+9lNGhJddXcg0&~!V3Jtq{~meK7{V>3_Bx0r*>_;(l3
zd1W(Jt*~lF0aeW?L>eKS5lu%LkRW+hA#Bx91Djk=$*(jJ%<rIJV#1<tF*FTiRB-tg
zkCV|rM5-rGdW0Xwox-%*LTzbuX<bAsH6St_of3=Bz`3bLkrl>PVPdf$#g&;BWLKto
z0;d=zs4|(->04Y{W+J)(-IgO*=@ADyAg>E(yG#Zx5_?$&{e%2#AYn2GL6|9*2`R)(
zRxr|xnfZAySjd>j>N{D=9Kvgi5~Lx+=3rX)q0)2&uYotV$={bWYi8OF_T5XM9K%7u
zk{=FVyO}mb(7l<>{BSY#bTJBT<^b4$6SFFI5Ae*z1W_b6bd8qO24JvrBpL<fqQUUD
zkO|L{{Qz8fCVyq}>6!Qt4i2quW~Aj~YO`-~_nC<?=)l-&Z#p=(y3aw&x0vjXbOJOZ
zha9K|&9r|VU3u5O#Z+kF7`FhTNc_Zxk<#u4hD1x!2Cyg^-LMyNEt*k_5?V!5b|LaL
zn(1nJ@I%&~NaDwlUG7`Vkd{mkM|{QFF%N#lx}kz?(kxH!prkb8z6#n(OFoIv51MJC
z1=XdQyz0n@X)@W8Gt<aI0a{HnT?)<?$@QYPCkUIEZ|_@NotDHE;PbpA4b=thW~|W*
zGx>dsOw>#YClHQWGGKs}^o|_yA=3qybf+exGdWT3Nc5l13_+`Ec4VjHOm8CG13#-7
zj}@SBWzNEH(Yz8_oC`LJ-b^yX-jNOUjSra&vnC^XBmcu4I`HoPB{thzIofmQ!v#VT
zUG`LrZ=<g8hOno|h->VrEjB^Y^_nqom6X1BgdGEl+)W)3+XLx?O-v=E7``KWy!=4#
z9cmU4sI$$KB7v&28^WQCnKU?)Zza_Zi#uqSr{Acnh6%5(MID+5I}{-Tpn;y+1g7Zh
z8jwlf0CpZ3vW*|&46*yjh>er+4Pl33e1i~snUPJ+A|p1BMl*7oeAKy&^72In?`gKe
zVQfb9!C}_d{NCcrSjZkeeJu6&FOD?i6Vmb%iw}1Jz4-)@{ybLzQl#f9(V#||fQp-w
zRvVJ98-Anywq%jP{f=}lbIVuKzUNv<YIu_;4f*4>f|6pMi|isA`doJD50;BH{lRiY
zr#qNd{6(zz+!RQgubqV4`qOSh{{7sLz|p_trbQ0_-0H~lpW7jm0py0sgaJ$Js7xr3
zn=q3O<VMZR1lr2!&xP$ivN}|rSI{+9bzVW&;9!kJu#PmHK4QtDc0&YF%)pRG7G`P4
zBTchB<V4TdQ2FUp#553jbYiNAJYF%KM4rGJk3@M)Lt2VF$}w|=PJ8s;LXKJ>JT&66
z#3UJcj*K)KJZLh@Mjk~Ql^Hs&da{nF8$02Y5I)Ji>g0)z=sfo*yHxo6#svWF?uC~G
zw7T=;qckAB=#CK0?p1dLHnLYqVf=fQR0y@aSl~@9FBZK<<`>gFfsHWT6EK?Hs~i8q
z)5_`5kt{fGNz4_aixiW|<XsEySa}^|P8vrR0F+_ncgkQyI?uOFBf|47h+DsvMJKPA
z%(RpDP-f%FyDC%m@G`q7sZU;b!vRZoVmV;ty_pVJdACNkq2-HL@^7Ui%4>ThEy{a6
z^BU#dpSh3B^`gv|6f;kW0JbJ6R?sBH3Yw&#_G7*#X)u`1DYYET`4mbJri4l*3DQP|
zf(8>Bxuu|O0YWiM-*Bj+%7#g-pww9aQ3iE8D8i~85@Kgkt$mW%3Mscz55=rpsjOn^
zu2g8j?J9L%aJ!lnW6Tnk+B0MlO9dN~jfDb^$;hCfi%es&&NBkKQBNT~AM>736NtoU
zsVamE)}&5kZnac7G67qtB$=QsHI_``7D~;i80LX|shJIqs!`^POXVqZ%1OVvMAo@f
zz%nsiYH69gE;YH4-Y!+WNPsu%gOMh0QW}R-R;rbmYA;pKOveZH^a3c<%G!~r$Do#*
ziT_d&&g6hpl`lviXbQP!iow*kGYw(t<dLZ`)%HkcxKOzds6pM&chks$CI6s>!}M-i
zIE)uXBw(DZ5hFokS}T~qF)bQQ@t9T*q=8&y8DXl(w3{%UWZG7kax(2NNJ=@`Xpp%w
z?Kn(snWi4PSfx2AQe>vRXkiA;v??*pW>}q=hBK{Fbg4?a6@01|*|wPQGp%3937Q5n
zrVULa8Z(Q+(zXDKLDOP*manwd4acbH$~ng=&2{lXhh}8?O3UEzkE(q#95Q>VO^Hvj
zZOA0aq^wJtEt$DBO`FW_D(ffmzsfwS46!hwE`VB}%&bf`o0iy-iPppl!c4WY<|3Kx
zGFg0?@iwi(%!+G@0*bu3X<KGyUD%(aZkP))Qa1!;(v00AiEo;@nd3K2;YtJ?wsK|)
zPFp&22{XaF(ha9Q9vO+3wAnLlahmmQ#dSfZ|44P5&H+q@3<rYcD>EjimjO~LPo4-&
zyBw|xOwyd53`pd>OzsZ!Ig70DUy%{IPaYD?7@cku^e%Hpi{(q1ryYo|)#zU(?~IYE
zI-NI=$r=tGUrKhpOkN<&h@GAyOqreDB+R^>PAE#vot`Sp-<{qpCif@q^UMjJZZSw4
zzD&L|blZ}9jYYDmbikoMR(k0mi8(!ayt|O{NZvk7hHfNWQo{6f5n@7hx)Ci(x}I)E
z%*#&KBxY_m<#VJ<ReCrf1^hC(K`~2wdP*^qyd0^RY(AZ>_=`(=WHD`hdTlYYeR_5o
zlBJ~kmmw3%lKx@dFX=yKNMS+;v(ee%t<=;^OpDCtXUH~^&TLjVEi|#^3B_H=K$vZr
z>TW<WH2x!XO_w{1{I2Pg2T!QUbI&TsY0|yVXY)F{0CL8so1h^fZu%19TUsWELj!qL
zI3$je!J!egtMYkd^_u)0mv1fs=@V&{ZkyC4TBYBna?)35+UbC~XoX5IO<&m7*^|@2
zZ3TBvN9eZ+%Rnrl;kSviCfD8YDz!?N&5bSG<h9Bcf~p`LR|f>gRkm`UJYOwRJeWxM
zEYygryeNEs^FGjePRA`d;`*++7JBOfIe;MMnj3Vw{rWE6XV+lv^za`Z2x3j)W4r(g
zCs_J-`tij(iZ@Q9YLWiTJP_06InLhUO}$BIgD*IDRbCa+z1lAr?o17pNnBC_(nsB9
zNA7WV8XoTQ^|nS|Z#smJ+g^kv$z$BFm0msGs(C+^+c__^bWEp-K0MbKAlo{7xAO{~
z9`L-j!%ZGYxU-9r$dv?>w>{Jf>5y;M=&>IqIqaj&29NOc{HHP{V*{v^QTPBgI1yez
zrB6g3EI>TaL=g&9L1h$!S=SNVON^CZ#XBpusrFsr60ALDk76#UDa^nO=pUC1-k=&Y
zVml16of-Qv^s5LCi4ywEwB<opm_a5~EN2)Bb=VoILhU)PQcFO6ih+ThBg159hsjtP
zGe+nXz3F5FwZ2=1=x~xUL<i|iZ15c*>c<coinyQ!kpF^$hYT!N8DM0gZ&Xy0!FP&b
zOV;6K;+N=X4>;m7(#aUpzw`EQh~Zbnl+nE^!>SA<c#69+M&IweryJw#6{}^P(PurI
z8R2JIW;?^r;ztd2)70n|b<@eABZw%2&ju86W11a|Z&wJLbw-<M*C%mf#>NdO#I)3m
zkaLFD8N<mHf@h2#58svrkdM1!`3B-sis60+j;^-pVA>IUg8;!LApd5z9DM|(Dbmmw
z6256dV8$~#ad9X@Kea1EwVH8`hEP{3>H>){N2+_Q&!Lmn8I!5ygOS||!5oN(V0Kmx
zlRZN_ZDRx`_3i_yeF_mBK-4z$BBLC!l+uD2qqH||sEpE9xT-;co8hbjiH>O~^*I{W
z7?rJ%SwnvL46C&bQEZCEwRn1&B6iJnz!}qPcm<<=4Lacr3%099Q{1pA-dYDZ#ako%
z*br{58_R|`H^ne71|@O^I-5eQbr##OuPA)lyw|DHk8*r8jKVerSZf_nfVFlF3~vT|
z55$k33<x*HSm#V&jCD>01X-K<0lQJ3=E8<}^_&Zcnd><haJ*q0yg{c;v&#}t^kAK&
zq62j@+4e6^4Sdmx*SCncUZ$vigTr1!-EpE4CxC(6EqMbBUuYva&VY{O9x%pWi=JR0
zLHD5Z29|<Gi~ayy8IVK>7VAfHB^Xrg$){l3Iq@wRJOn|?umFlTZz+N|<66ofZCM))
zxh6yqu{abo6POqKIuT45Beq3CVX>%!r~-iB-;>S4uoNfbg)y*ORx8`d^uRd*3&4`>
z8U`NwWZ*D(Fp8vO0MQF&5{h0ZbTc+s4#WmBfanLEPIs&|vZ)wY^O})`#&(cEh?m6R
z8=2fC#yE1(n+(M3Lkg7mq2OmZCNZy&s8j~x{Uf#&L-@HES;h|`oRXX^jzo>Lb1))Z
z8h=O5Bk5t{hoVM(5(~zdK8ZO`OP}5qj4@QaFSeT)ZN>vQM2q#tcJl2==YYf>NuD#1
zIB+yg4IH*b!84GkU7e)7b~R<9az*+e|GN&AJBTQnCI!iMq#xKxwzEz`G1;k39!Q_a
ziwq~NBsdz#-jf2!VC$J^k_Hq+P`Z%pSXRZgWH{v|ACn<6A3EM85bsQ>bPcD)B!4ob
zFCjV9C`W~*o;8N_i{g49K?c<&<h?7ND%<yo$I6)hB+0G}#;Ih)8c0xYwMi`M-zKS;
z3}W9JP&5E$jsXPu7Ad?2;$2=RnW#UlzD9xprC7E7nApS&{=LaKW-yc`E7?Gtxx|yt
zj#6-==|TaI;G{k?zc>Ujnvtu3#A%B|!Hky6K<pGHR{=8K={B*G-j3RvpgdS6wl~{J
zaVL!pT#-c>=fHVRoN@!HowRcc5FekC8$?pvajH1K5cuu9)C(!_fW(QW<gk<AE{7fb
zb~)(ex6`1L-%crs2IOCnnEmVkO_7-Y3^vGQ2Xw@anL^MaF;3D94j_hhour~CR+dI(
zL}fUTF*6k9?7*msC=mzZA71MCND#473vomZCbC6?qjwTA8d)Sn+UST^M<4xBNc<QL
z#KxNHIM`W}Lek(ro-~sK8QlUV$|aB>$29dgG(qCDG}vpC_tJvDLd=+p1701S^l<l2
zj!i>aq2%E-&|ZkDa{$3{BtlO>6X~bH2|kHI4Vs66bd-Zz^vwRM6V)h7?5CJ*Nmn|M
z;2x#jA;>qDq&+1xQKK4EB1xZWkvAy`Rt0ozX-5V5taj-GtoI~yO+ZF4*up^y8v|Lv
zE2}e{5Z&>Q3a;6HD-~7NSBd1W1vGKo8dye>2RD(DedRau<kKaToVy0wee&|oNK<tO
z8|`t<odrZa<7Bkr2%eFyH~Dlq4$^TYv`=mK86?)?8OetFtU`jRG3$xwbab?dIXOyH
zjsBOf|GbRve7%14YT{n|1z)S%x*v8eu3!KBPhbD~Rle5iKk>i+^>e)ed2PUF^U2A&
z>t=Bv$HZQzarX9YQ<IT(XEQZt#Y5|~Uie7rjvQ-v?S1+_eJE;QryVkQ>W^vR^dF|%
zqCq8A<(|b2Z>jQyF=T10t>#feA=&<SkKm4@mVbEF`1?pR&(QmCzl!+CXm3P9z?%Ef
zwj%=%?}5m)bmqkvNl9`=MIys0(*W4t3fWMo(<x`3%!AsH$q>I?XEy$p3BxYLDQBc6
z>_P4$MX5KhOzKo5bK7@l?~x^Z*B*{ct(lmQ@quMKrFd(RY*AK@y?<q{M#D{lEP&tc
zP~tz@b#jS()yr2Voiuo)lYR7CvHfHh{SK4dsEgd{VU}LRd;CqKZ)S|OGH1dy=6_A|
zJF;%us%ztlev#i(xDR9+Wja-O=4d!oc*4adPsbCt(2|ZW2Q$XYmE=HzFr2Q3{@k0a
z({;lE1nJ<z;R^jCX8=0L6<Oqm2GmEb&}DIS{P=sgiIDcNloO7FNGn?8+6|i0qVrwD
zIFur{GjJG}BA)ohWc9M}Hs)k6@>^|@<2D~@kt>?Hr55g>r7!_8_KiZylW-y$5{%pO
z6ojg5Rcc7jDpkWaP;}0$Oaz!rByr0v$!@|NcIC)u*Nz4&8T^Kfdr9O0SJ|TbMeQ80
zOezkGgO6cU7@DObCW>&WFO{Kc%3aU+FoP=GbHT@tL^yS6VzyDvb0v>PaK)4by&@aD
zB|8Z^N93&)2J@0p#|6JL<-SH1d6SMXQ!}fV*F*f?-^!}yEXomnwPI!LVjWq7wV`ye
zC&NjIjI!U%)ED%hK7Bodpd+G+JrUPYl4tQmX2UHLfg%s_z9!pPjYOp}PJ_D5U%s2T
zFqI9I6lKWfSq>3{K{?>$WoIDh8iXV+0r{jj)e7W>D5u!xl!#C?ec{hLn6aSQ%fxue
zX^NCiYvxUi{6*^y!pInan%w9eL2`qk2mKD)i8I{9uk^Ti)QKS*c?T-;6!b_bShYQ7
zlBbDPTe+HIt-R$j@`@)}ufhGOYEFT?-#;p}4*Juobka&T&@+h-f^+Ida!6*P*_4Bf
zNo1yMAaMb%nFSaD6N@h?dYKQvo^1L|T_G+}<V-l`%mFRWlFR(ETNaA*b~yLM8fRv!
z0kPwn9QWiqmhVL7F*xSZjTS!?0?Itld7T!6FZtjn7Iu<^Cy6x~%xB7PvTpClpGPgA
zcmhRhoq6qCcjCbm$v>RgI^k2^Ocb%S$;{a$!%&jxBx$Rd^K7~iylt7>@|4jm*+N&?
z3i)N@%AM4pX<5a3n!K1vWeOG0L{3R#cq}`3&tbU^h5qrNtB_Lw(yt=wa;5`EM>*U#
zwCbD<-WiHJ9&2Z~{M2bR4R4oBfL>?jIr<R^@PI(~lZwZoKd~ad2D$AimK?rs6LlD(
zC+QOQ?FaMl1{JG9o!lN{!w`cLsR7_=?7mIlcY%MkyTD?j?DAaZPI=1nmy|S&B1l3&
z25mJZi%0GUI`Vuw*-4$f=$T#0u$zw9e}?6V@uG;Ag7gs^qcliVageBj%moeZ%oDvq
z2N48F5*TdBz_pCm=Z1Hko4(BC<vRtTe<5<b&jFqFWXLCuv@3(|GI-YzIgSSy-KhwO
z!eB~;fD{shNUFf5M_-Na2%tR?pXy~(%w-0fM$nDIO%!yw@!-`OqsucUa8>9Y!|oK@
z?j=U<bO!RB3{TT_pf?3fWo%abYDOgG7{ix)1Et>_q||?-fN8jr&har#&!ECPjDvGT
z$oXsH=t1bgEp`G?f>Xf4As2cEP@W8xP@K|<px~+)-^t560MI}$zix!`qwb7aO&4cr
zjaK(&{`wB@Q1{N1>brn#pfDKZy3^5VmaeAZzRB&K4$HP4x=$tnX8IY%Gx<X>ySRfO
z?y4TRyGpqMin7^d4@>vi85~8fpr+i`__Am3H5<1*{}-0+0~QshfVyse;fs>)O1$-h
zHdo2&%?<f&=Pot-!62sEIvKbb!aTW%NGIV_lHLX+pO>@2M)w10{I?GO19{)lB%CHD
zRA2lmG@W`BEzNV@p$LGI`7R9$u#z=7h``czNGmJ5Pns8DKdGrJ$}~9q8RpmVVL0gj
zSk~0JAJFAfvjq!5`j1L=PhT^sIy+BoGsNFPj@8uVNKLrkRDe99h0@RZaa8-d{&9VX
zSFNviuGhi8Jm~z8tsC)JAJ_1O&QDzcN58r^DO6)esC0E2IzRJ^Za&~Yl5RHCxOPo0
zs@8jInoBHgnJ&@}rv23LjFYt@dO3tudmt@wRq=E*S=Pyl+;N+bE62{ny}PD@N%KdC
zUfjMisj<P;tQHwlaK@`e77bj!YD}3WzKPK6QRA=7<~#+vu5XPD>HOHDPm}|G@z1kH
z9((!@LXUFlD?sNC^&ga9RLDply})mAaBXwlfzC-64~Ebe9Y%S8C_6Q;M&-$lj~0#(
zWtVRi7!=DU;|ItJ@-oekwGur*M{2+IZY!2w*CBKb6|yatbVaIE2+${>QXin9LwLfZ
z76d_T(Jt@t1*5(uvvhdr57l9lmT!ZYIt!%9MZu^HHY)PG&{=w@2dNB<88>t)8Pevx
zo(e*6e3uM+i!ay}I$sKAbcGKiHc!_F;U(~6D7tVpc)(1GCI<JG8pn%JwABo6j`>n~
z%xs;{uV3Hv2wPm?g|PHcpE4_XkOU01A+>$31}#aI5Q>FTl(q__5e|{31NuKvx1Om*
z#5o(rB}XEfq9U}g6j5HnpL(eI$i!6ddPEqUOX1aU@vN3>C^31AuG9qLjscIWA|rYY
zt$!(EKiUv2Qk0IJlz%1pd%<E@l4G}X#KibU>Yg#Iq2@#Vs;*8}eNv#&jfz7tZNuTG
zv{e@uIM9sg$9ofcB1t(hvr2Ma)=-Hysi=4(8{Y#jZ7!2^eu!i$$r^|7pCb0Lm6nO5
zR9fRhWxBWTATS?eDeXVG*GuN_J(0pBl01F8R?LMqrT2)iOD5zAHK6zSCT-0L75kRi
zZ9vFhb|n@H5Bsu9r2r#d*_D0vz_PxJG^vCmMJ~PtHm#z2J$5S+{C_KvNNNEWW;H3P
z^+EJ~NrHX&BRbVRlpe@Ey7D7h3Y>lGn)zI!K{XRLZm|DmQp63Gxk6j>!dy{KZ5^5^
z&{<w{=1bZ`>XyGTLSxcVmx$1Xsz_(9`Bl`Xo}|sU`xDAUs4-={ab=<(8n$21ONCxD
zRe?;8-t#@sDRySU^4+{<vY?Kf9(Bu9UPy(WiGurz;}*4tBR_ejX|dQbYxpcJGjx>u
zi{_-ctlKf=W<(m=*x?7Thy6W8LM6DPxp8DwW+UbrT$u*F!(cz9_GHSxlG;3Y0T!Ev
zCyvjV7p}*Nd``}|@nnuc-{85{F)QL|uUtF*lqX?hZliE(G|k2?`k(K}U8UQFpEcke
zi<WHQm~EN4d<#`zd~P`7r|Dp4_AX6L=HS^7eal2Ro3fw4h~743yQ6>9UbH^Augi{v
zOb26;cCOoFMR5(}j>&y67$<YfK>es|!B`U_C}@{%@ig5uv79latVoJCR&gt@aLvI!
zyL>ByL_1~kA$i*>Ll$}1*548jtXu<^VJ&F5cGFPAkW|m&P!N(=#J~!wv=Zd+Aj~N8
zbg8_f=U&?o>tB)*+!*Z)9U!$7l}3>oA#o<R#A;+hPx5836IQ*+$ObR({)#XkH(|$)
zCvM^bmSIx;R-G0|PQU~Wn~@-x)T7%j1r6T4Lywu9&O2WuYR4TM<siu{NnMNs5m*S4
zV_5u_s{RQAw7A)hsc?$n#{YiI>^CcUm!#KPNkB)7T~qQ5lZCpFi%B+LW_g&9Lq9|Y
zx{^OcrQd$z530vpYUDYkIkB~51@6J025nXF@JPi=>uoa<aGcT)CK(RNo)CKC)G+a$
zNUAw;v~<$rkp7E=L`{5OSiGDAg=h76lQ>48<gs)!*i!>d<sWJ3<@U~~yD>-6x2|lm
zDjg!HfqaS^*+%O|+8L2r@RLC#t5tbp!{5%BX4l9qIdKD!*eLaTD`UQO+l3w91I%%!
z1D8&QdKcz)S>^x2Nbyz5IVQhY<&aFq#8r+lb%Wx3m4`}Yc&wr@pndY7Tluv_ekIgd
zfx4^IiH(tnqAM`O2^>;o8q-&0Brf*MV^u6YlV(qWf-vpu^3!81p|0cz;Ny*aaV0|R
zQ_@8B9g0CUgLy!;{~42W_O7@E=rG1MnhL`W0Ws8bKyN2fyl|DuIFAi(@6FN+3<|a>
zXrU-hfNDF&OsJvcYHC%^Y=~NHRf=3Dy{qZMAKQ4LigQP_U}+gBfCGzkg0aB1HDAQk
z>FLAFB<L&o;pnRE4xIF;4ia7YG>7wMI+Vwpu19vn8PmNUeA7@0{z2_m|4!|9+>l2>
z>I*js0#VTJgJ8L-6^G#do1*bSkow3bK_ch7V7aL+<BfMk=HnaVu~mXZws*nxrWPH7
z+g(xmBuIVgCP5$yb$x21w65O1NeBDXHc|9{ptL=HYSXOAjW*qNyN_*(E7T!DDuwM;
z5W`AMaZIth?)Y(1$79(cKxDFbc;j)?M8|;Nb<>YiEFLQoB(lE>BKU)f?s(&jyu8sL
zgE93Zr~1kaz)x@7rAUvVNVWRoz{exq1yFkH#qFk?|D=Dkz4xND`szg?KlEb1DgQrm
z`%iPgWB2=G?VzCS2=*@6C*uNMH~}y3i>C}?1Z;g3Yd6EiCs%x#G9HH_9$O_yWP2B+
zn^mZ=KIw8TQ_1sCoMAtqAZ;w|U9j8?FCX7d@1~dsL0W7~f<W5(E?8#64&FE;FK>*;
zG~I;kuY%CK(QXu-bGIZt4u?Nhb_vo1)m{Y=c}%<1R8?83-a7{xoKKp#>iQ}OM=098
zqN;aG*kk9!V=D!PydMmZUmSL|kDm)C;86_bxL_~(O!m3<DpqHk-6!I-XCvN&7)^cr
z@(GmJFCTY*8U#NKSf5OUkDU^a6$ujAUj?a~U3EBs<|<8)j~#PBg-k)(F5izL(Du@x
z8CAWRIG;Nw9_tc>2k2T}1^YJJOQWVY1L|Yf_*0c)1deyHb~DC)$gnY)XCJFcn=J)t
z*X{3u<!0>th=C-{zYl`65^oYTRrOVHy&03Es(179W9JmOHd7FY@*@9PFfwe=R{h}x
zHjUShUE@!!5(BWkih=onwwR9yd(t}dSk2j9{+Vp*@0$$By=TGmH`DurAT9J=g4;h<
z)iN9MKk~YhW&c5p_Ww#T0>_&exDUcf;1f=TDnGuf%CZ(hEN?GDIO@>-AjIwt36E8b
zSfrhT@??0wRX2tY#9jI$a<p`Kco3vtM5iE;y}S#SoBKov-W@6)s~V4KaT4;r_<{x(
z?int)-H=B?_;qwGPV)5VuYw>f7~UTtl)fO3RSb8K-3918(w^VYZyqI|pyj*ym^=v5
z6-8%IBHQ~JwAP!)%12Ix>BI6^RmQ$hkjVZjSkBoa<|7M+Tx1?A8c*?%C186K3vvN^
z+k8l3neI0aZ}Ybl({UF-e?RRa`iibRA6G5koqHYx=>ya$NTio{!FqEQ3c<Vc&|_8O
zu_i$x=d0j)-dvGF@a~-SSk-t;TbPjdTMNUi;OP{CGxAc^cx<JhknLTt-8`v6@a|jn
zSk-V#(WWV<toP1AJ}r7`eS*yR=DYPENEfe7f<R=^`lDb&m;^n+KH?co->`=_(uK?<
z2*lPm!G<7xI+}&xjJ#Ae9;*;c<aie>H%B%I-dx+BtLl#x2@=^~1;Ij3N4bw^P1AMm
z;f)NbJS9k<yZ$P8*v%0Sf;ZQ^=c>AA7S)^S)A!yv(Af_^zmIHj;q~_*Kv%!b1yE|w
za}%^L^c@VLyEoxu)#5ReAP{jOJ-l&~Z=wrLo{CRZbVo%9c<Fo>V6X8e?c|#`56A~W
z_Fj=7k=L6v$sOTO>4J7c9^Xi}zEy%mwpT$07}pA+bl!ZdVnihSTjcHexSzKO{G<!$
z$B8FzKA{g{M!!#r!Ijir#riS(mxkEQ;q<YRHQXyH20ztTWvNpf!g)1h(v|hGdeM91
ze3`zlkLSzAJ7f66emu@+0v^Q-Pj!j`pyB+_V!<Q`XWNjPoo^qj2=7%0X~18E;I_MS
zy7qE&>wT<Vc<n+c%5{Ags*{7Tgv$F`f$C|sK>2;WXvge&>|%C99^Xcv<tjlU$EzTA
zVR{aS;N92xv8r@shM<t+U9ila(;xSoySY+7h>384Vs`gu{-c;j9ZzoApCD7ZIch%$
zLhH4j5~PRstHQ2A+eNqUj}pcbd3+;und>P*dXT@~QQe1p@+uF(yPx@ERU6s}K{=@R
zcfoe^T8H4xkNvr-{@5x(BCpo%x}TF*{D;&;<yCDiSNfGgD8Jnv=@F2hZiOK?J@6l^
z7?06>mB{N-QFjhA4=@$p80p~uAjpYTBuM1-$TU0xrf`9fyTuPYR&?*vCokajiyw{!
zb1Xv0-J=s8s~L|q3JN*j1?#*vd>D%S(_+C836od=au)uxSU<2Z99$|kyCIM7E4LNp
z^Cd*#77uUiw>XUuyhm<4RyAhiPC<oyw0A)svS}u#Kg2&!)nJ=Z=P0D))i7U;Cs}T3
zwc8DOd?VR=P6_fP`?`r%<5|pH(OY|&$}iRI=mr;3d4ChCw*Z+CyNAp?Rxuu{670Is
zy$KEitjb&eaI460oTn;!!zmE4Id1}Oy9M>Q&~ITrPgTQX^gj~PUX6bhG`t8Jg5Zq2
zRCU8$ih_(kYOjKDx@1h!$5|QfQA!VQgz_Kmte+{o>3zwqR4z4Dwf+_b^;p$-Or0a-
zRY_QJ!DUQU2;QTt9;?bxqacx214IpuFUD+z+yuN-lq66P3&38TMJjG+5f2tpb9~ri
z72}}|LMX$_`{7Of7HRegPO1rc6g;xuLQp|#uik5Q(vf1r#O*g@+a9Y*ttkb&w5D%@
zV39?n+(#rS3Y~kbXgpOZM&RvI>hT@tp(wnMLcTIC@3ETkSf?Nn@hv?Fwp)~62;SrV
z9;>=R&rLxF489tR2YJ{WMHqtjxWdP(#$&4liEM9z1$hz~rTB3_k9*wW!y6giSS3j0
zRYyAlen_wAqrcXv{3rwkVUO)uW#r0u5NfyZ$`HE;Ts~GY`fisXBQ;+?r4qp@4Bz}X
zH_<Jg^Fb`Gv;CA9!a)10*m2%sLqG1OagP>#cprmGiv)@6uY%xzK<udtwj1*JMh2~#
z1cB`9tKeZWz{fOm)~H*s>tj{@v5h-RM#;Wj<w}qj^Qn)=y53@GAH)!Gt9lZ6z5kI(
zi*dOjcaPM4tY$n`B}nA;G+2-VigCZ6aD|zW$2T%yxJwYoQC<Zjk|AAL*v0SeA&f?r
zKZ?SWUoC4SG(*ht$6ar3LCg<g40SFL6Y%C{SKvj;fauS}rugbJo{`jDf<Vq!Gmg)&
zDd74OQ|uOk{UC@>^*AKR*ll|iMBFIX)2Qk_!uzpvHh5N1kjVBbh`c+D7yl&x<oW7G
zoPp+aTu$VC7worq^r-4RLjAFG;<1f_Kr)d1L9pH8-J`1a2>8d&3G!uCRiX2*+R1`E
zRSc*9#BzTNuzwI_9Db7^k=N^;lPaGXu8*poa{&Ky=lEk<7Ktbl_s@ce3**`F<D2N6
zAmHJR;1R&t@G~(BydH$;{zAHesOp`7;IVV!F`X8K9It|4&?1|`M;=hgZ}8YT@z_Q|
zBK7qOJKjjPgm_zWCp^9>9$E30C~eOIeP&?z_}Sz}$?zaX;s)F$5_r2y#4(ce4j&vN
zlkVYhpu68sAr$5I8htj-?fz-DHg)-oymWaywn~u5t1k;3w8%^Gk%Lw;RXldefr?R(
z$op5`%fx#T@0)or9^Y0F7t--AFTdTYlV6v5!Gf64<k)x|27j!b5+pgtt6q@KQO?-m
zVtpz<zKt{=4MHrxbx7QPNd*!;a^nVh?ELYR?Ggi}NP88t<Hj=*ue&pkJiad;%XvxU
zeO`*>m_6BUye97h-r18ZzxL!lGo*azX_%BLkM9~!^<83MT6ymf(m8L`yO1`x{%~0&
zol0I$g}mxrz>zF=myhUAlJDj5jq#XC5Xk;&I`B3od(21b2+_$rx6q?YcZ!jP=FN0>
zy-n0K{;G+n=IK4oKS6;tsH|TE$V<KJf{zT3L|&GIc+4m$nw)o)0^fKP&8~VwetaY2
zF7u7AahIBxhmOLWm&dDHO49tS5+w3|_~sXW>^Vzr^g!?5cyQNGANlz@xon@PhT>&2
z_0Z$Hy4Qz7E3yN<3E4h#7{#k@q(+bL+M`C<jeF!t`k@y|kQA><x}?YV#3P261b@<_
z8<7*oPozuOd~Y;N&l|l(GN?nFjVMRocbkdSDPDMEd3t<bJXI)0;B`VF&j$&kV%MIL
zmwh`PvuRmyr2O!8pEp9Pc;lU->hX<{_e<&naa+CmWOCtd3YQd@Re4_)#FSO0-7%2Y
z08LMNF%fFTIqy!f^?1^Y$4r7i>Z^}t67n-Zv-IPJyj>>HA_@YjuOXr8ifTBiCp*~V
zDIG+<^AOaRkJToQv5&$v+MCHZiOEa{Y%jMr?Kg9lHz{A3r@FnyLWuUP?m8=z2<=_n
zgJ8iXt6TwZ3z4^b=@~gtAt>b440u&c<ZGWGTWhaAfWg*g5-85@@_K(eCqlQ-Cd>qH
zkGh2JK5=<H?^E94=c*aQdCEv3E#kN*txS0OLBO0>?p2`P=;uOJbtj~IRF1`CS{I4*
z_jM7OoLWx>;Ce$I1+la!AV<i1L{8Z@u;;nXP)vGH+QMi-DBqlB@8#kB#>E%v(>pug
zqrx^GYZ4@KzAK2%8`s~*RquE9zlS%HBv85vBHO#Rf?2A4!iFw8%P*R2f2ia7FG9lp
zCe&t<LMiv#dq|$R4Xea9vPiv(*^L1)i~@H~#7C<DDXBPiK=$%3xZM~QKT36%oQscE
z4}WYsC@8YV_eC^P_U_ms4x9KKAMH6koc3YM>CWKwBCsaSSM>g|-H=DYhQ~~TK#q6i
z26BxC>13GVW)jLrOI$nzMFY#n+a$(iigcEr2nRoBg3AX%@L=xraZ6^*S0A^6l$)f>
z{4nL$M4<T~NS;kbVkYt$iCK_86m*>aM!O+Tg5vR%-hjyYt~WR{uLSJO`<?#tK@23J
zo5TWm=LB$DbWbYLkDEyD<f0FP_*jvw=rggBz7NIOZ&an>1aT)XeGnwasV;{?-fxHJ
zaic;Fe~lS=5KIo$CP5;v2CfRyL^7>@lm;)kS04mP(JDtr(k-s9Hk^tK%w%$f!%m;M
zT^|HFYKH_#3j4Zty5X#oDfZ(=rkOeRL5TFSD;!x^emO;qhh`4ij}q1;EA5{JMP4iK
zPa*HafUGm5xcxX2&z<!4L6F?ICP5(O-TkRFQRsf$CY6M`4+7xaU3V8C1Mj1GsUi&~
zX?Z_kz*=Xb-UmVO`N|-f48N~IdE+tA{(jshB@W;}KTek5g1UL(@m5Il8}p5Q+<rA9
zkAfs1)~pcnJ}VHsZ|NrA$_;rGB)_p7<%#^@DG!1I(jb4Fl<ZE7{AWS&CvOr2QeWMw
z#$!pd{Bf$ZnRfX>D7cv!#3ruhH$_!NRw_$>b#SZN5B}<8eolXNaY4WPtG8|DhYpA9
z8)5W=7-*&GiX-6l+FU^|OzMVkJ-^dY|5;G1)e6B9@*W-mo@J6-hnM`F?)pKHtk{~L
zMB4lOH0J7~UsOe!*QC>a5G3n1{i1}lSHGwVVjgmHN0h^zt^3b{B=xSl1WEJV-UaK#
z{he_f<N|*X0%P|0&c8B-WAL`T3eBwI8Ksgu;}3%D&69#6DDOWBPORk-h;ySc|Ff9L
z&R2>N*nSc_4>F>E!t|EFqnP2TGF8%nH!rigWj;JiYUSB`W!p)f_NuTZBCl*aBWP--
zbN{%>>rU|gXF>76HwhAXRa%g6)}+s?`*A}a1#>=9kR0!?y1nsO(9sW>qp<M!IN0ku
z>gEYAU!oRSdve26&<7{s{htNJi{B+!$O8Y9;7p(YaYNUPJPML`UqO0A?EPas$cnEO
z>@2?#_CE-M(7kB|6Vw0u3U(Yb{r|_=|0m!{3|Rx(E-|DLXg`TDwZJE`iT3h3=*&eB
zb4r;Bo)3y=SGt1F7gKP)O<G?p=n@;*4&Jx?lWA2&C$ZXZNfG`isN4zdkRY=uyc1Z!
zqn{}jJ~D6F4-_@b%^*^o%+~N4el#A7Y^#idZip4noDL6y+*=q0EyP}<pc}%bnGfRQ
z86xgEBmOMN)DrEKAd^k>p9JR&6d%t(anDKdAc&82dLuvEAKsX$GQgry%ME!HJT#6F
zRI-fMJ-n4eqvm7~%!csh6o#}L@itVFBls#brRMm!wd<Cv<3TJ|n`{_Ue7v`--d@#y
z?!kK8UUK~WhU1n?Bsdc8*+u>=$Rs4~kRa2N{6NZ3r(7jT0TJa#AtnqyAjE_xFK5XH
zzr|RE2P4P&z6vXAim$?%L*;Q5ZjI?rPA+v!qugHI#xo<!CP5%pe-fM%w*<4uJ(bIY
zATz#f5(HxJgj3dUiD7~@<(?|$L6CV~HVP84`Ys5qoeZIa@n%Mz1UnLWHxZK%c{jX{
z$ELhC!I5)Ibn_sFbT}rl&O^nk*fuB4`GlD)fk!b;wnoaEoPF<Nb4H#|*vcm4Nl>YL
zngofwQq48kizAgx&^2ZGQHW`Ru!O68ybH~#gn~=zo?PfbkaM%BZA9LO98}*-RRof)
z33(D!j-yqAM1CL;<D@3fb=!{{@+gRpM#1%&Rq2)I+H-KPO0_fuk8(pE1+f%WnoBcl
z(<>=SLk<^aata=|8F>;sQr$yACWU&ZE_0)vDYSl=aOTWW4?>Y%YLk$c-^2JxV`p-U
zX}s&ySF>9tucDz($h#wsoAXZPxcbO;qoh}V7E@|0t}g;!*B7-$1X<_)TSl!1K_=eP
zHAcugA=hbhey*U0yd~^<5DPVK(O%6wU$3h2#@kzk>LrtZy^)$JXBa8eGKtumq9>o?
z&6upFnQQDput^P1LDuv2W;`CF;-55~=M8xj++=E?AdvbRP&gj*PgE2(!wfMakAlpo
zCSrRb@67fzu_5u=Claqs$djNlwyhE*vi&G{W@5LG56nH)+k+r7!mWn{nIrC%gV5k6
z$-HsFMLZ*qf;%3gokU1^wUZdqT`(_Qa4p|6)jbF@p`Fsi2zfm=o6K;GTpu6rJrmxa
z1(h(bNRY^D<ht=vh`f3q*%30+-h-eav)(B|rs(VMg3&2V+xJo0zD(rzAc#b7=Ptnw
zg71@j5+u=iy&;c+%qN(`kyZUca85h;kv=*T5&l_F`3kE9iM(D7;#k=-BZeO<GtJ?H
zkUMQ2r-ULm;`<_nqfWYLP{&B*Q4pSr2kAgF_u_l<B$)n~k1_HF+%q&j2r`jlry!BD
z{3JN%dyK3I_Y9DK7F43hI#o50_o`aC<&%u05BCg{4}wTUxr@bLsVU!C{6Tn*e3f63
z*J4H<1>w!T?-FF{%U3cMs@0edGjey#$fF?hXqtNUNI$tZ!TpwQGm@Iz6L9`nP<c9)
z4o=8>x+Xj4be==5-}8Guyf3nVW`YZ*1%1zN5jj&@rnl((EqUmZn9-+{VgdY++X7)r
z%tIRab7tgGkO@qy1c|(-P+>UCrgd#wZ^)w{5~OymZAzK?Lu#SzmPa*G65TVaJ_s@a
z>o#?cBk#V&#-N2x9~UKM?XL&-Oz^6Ef{<4q7iN}X8raM%m5E^=-pKs1%EKw-Jr5@<
zW~ZvU{g!z4L6G@rx4-M0*UOMWmBTc)ksj=x*!Dq?`EPZU7IMA|TBga3+-FnP+y{}!
ztjkOuD8A<L!1QJE-AD&FBaecIB1a%d#9pKPMy=-Lz8_EAdr$ZKXF+8J&SZ&1ei-!Q
zmOS_qx$-9D@r}$ntju*ne#l&h$hf9u8~Fe;UGc*k5eHYba4XO8`^vqq62x+`Z#U#o
z5Z<Fxvc#sUz6zFGZsm_>S-fXkeh_3*=1i7I<dv;vbcHYSl}2d;XVDJ<Zc6&Bkh)9*
z{c4vsL{CI+=#OXToO4A#2qB?#qY%pH51BxHJ1KJ}&>4AoTRb*r0uAJc&&lSb)*sIR
zd&_eDAcpNl*%g%>`*mpw9}s5D{&-&1TMF$5F(lf~$r(WTVQz-Pmf^A=rE&csfHw1Z
z=Z8yVdl&4tbl>sDTLSRsH#*x$-a?f*{QVXR8fs<}k2l`)i$A_G9-~S=kyqyYYho!|
z`FLBMa+f~{L~uF3xznrmDzM!$p!-{X%ZdK<rg-egUSu-$A9``SWmu0l-gB-$zA+yA
zyVSkM`);H+=G?3|<i|JW+|2awDR`{|Yd@~hxi-gb-4DC|(XEtg^#1vuzW)AamGC_?
z#b*lmXo!J4t?nGY8S$@vO5@J0F%i0Wcslak^sD9!6|v+SI&!H<6qq^Ld5CmmjhyNE
z3Lv)^y4hv9L3E{$w=$fPrGlRW3&3_xwep|J1n&bH!c}?nW~51MFq$0GzkQip066c$
zwyR%2y0vYpWg=a#^@U<{rSWoux~gkag7|EXO*K8vWF`?Z8fYx~Px26Fn3V&m{RY&j
zvV(9T%(ARm<Yli@*D_OkcI`dQ{DnA6%Yjbu6ZzthVa9;VW1~jFGmwu4b?mMVj0SYB
zWlU1O)Sg3FgS#h3keTIk1i>ZLkKg{jvWa|PpMPYH)bRNu-I;gTmsMOmKJrT}aNdBf
z&mwd^?%JzHI%AHh!<mGhi06&p;~CDEf-0Ma0J+n9escvi<|kKT1f877_^R=<RijeS
zgsMR)XhGGWFk}6w)AAdVm5F@w>r@&4-upT=!N2a{Md1%cUiJJ!LCXQsCqo9<QDzfB
z_r_d-OF*MOcBmC`#vce<0X7!>h}TZB-xg}EMVwF$Ib#(D5+}HUU?BGsHNmQB(6ZHV
z8d(52(G>lVe3kb%Q`M_=-xxKQzY`N;!9!ks`@0{q>4$vbGSVeG5`<bV6Fch}99t>m
z^HWq{I2MyqY!sv8=(gfWbQL{o4J4>lZkPj!%1~?M$W=xnZ9f=!ReU{I2zk5LNoLfg
zohjtw*0dhrL?^bjWk6R^i@_e2r-9%*mdMUu1$m5IrXjRA#Hz$4uF}KZkIJKC<iX&`
zI#b5k9&C56-d_L&rCOhaf}pNXLf&Yt^E_nWuDk@)zsTnwW$(?#b$uuAUDX8M;%Dn5
zQ_LG#Qz&|-Xa;q3P0_sTptma&a<`vBxu;2wr0H!{BRg8Ks*xS!fox-Rh*Rf}VOqX$
z%cx3*U~o1WK~X6c9Emx&aUi)6l&;ENO;r5LfJSxe{&x~u3wAL0DdB@(ug-Ctagq`P
zldI<%kVw!Rra&}D8^LbTny!-r__=EBlT<WErz+ee2a<0JDa-H1yvWZJr-It_bz+ZK
zLc4+Z_bTf+^aP8?-KAKxp-y7{fz~>SMQzF?wZ;z>EFhuts8xFdcohc1Nrj6+)!_~P
zK{aB$7C_!RN@YXsRx)@xGJZ%&yawV;4PO5Rkk?3Ac&PrUW!J>V{w02&3-KsR{_KjG
zrHniS8Z)bGl8D<<m0^D%{`r?a35|K^2?bKjSKMNgShQTL|8}C~h_ExbW_cJX)|&0~
zB0fQAIIHqa8IHVzN;OtA&^jdPtAz%BaR}=miF!*(sd%&2{w+!rAl0ky(hH#IhLyG7
z!T!srYAP11%=Z`KB?xTje#P;+(s(pyJtPrBGZ1`WNu-O?_$1dn%x~coI3TPJNX$JD
zG`HhNcXbk$F65$J0`gzxRnA~dsq3ar!m_h&{FcB!?{U>Q*=+II52)jj?j=kWL~D(3
zcFfBOIrXAg=2xvD*X_U~;30xr!fGf*gQ-m&NcXb0cX1$?lbgmEBzdc*60QTQ)(+_0
z2NLa-#em5SzGY4sQTF&95)7B=ccOv1Xl#`Y)NNxc=-d_khGk*Z`m)8ckVMr38Lt=!
z7m6*}tSf)Vx!X_eKpRq5pNFOc(ovj8PKP*-7I_qybLWmSTeX6odRMFBh?=C|!%*Ty
zECDdo3?wQClTtag=k(xym(6|vesmiUJ`(2QI<*Ti!PVJO3Mz0NM{uoj0(9*7AP_Dm
z9Z!ehDr$$z2n<=Hj1d6w)gbWjA6^_985~ZnKb@53T7EitytU!<4IPF3rf-WE_!^{p
zI;AtfRg5_i0`b%)=c+#N4|t?t@Dj3<iGgDvq=o0NBBAu5<p*g?KpnpT8VwZ7y@Bbt
z9GVHZtT`b{%mmPe5*ZV!Bdz<P{iq{B+>wKiRJupkz#&)K5zSo!^07X;Iv8{QFmz{R
zWj%DM0CR0QbolJp3kSsh3-$AbpyZ#{AyrSX#Fj(LLubALe9YhOao``)Ati$$Th*b{
zs39rML8m)Id@%APEP$diS~3jTfeuXy!wfz&DJ=fZpWS2kVq%1VA~gnYCl<R#*=Y<O
zh!5tj0}3vb&OF3dBTdS#>nmI)m~|o$@4<baq&(5XF723Y!99h(!o1&i)fe-A*REt8
z6%O(Z_hT8IKLEZMQ(uWSJi^6)rnA{`)-5|WDWqH)WnT0RDWg(dXz?ZN+LN62xrnZ5
zlq1y%mlStO@i~%eM%-G<-ZUX<<||o$M>@*BYz=^otf;XrONjCt2<wOKVb|H$N~{rk
z&d;J`4d3qh6eCbHCUM{$2*#u_lSv+q8nTY1TGL~+n8M<lArF}Z#zwBXjk7QUWtT|e
z0Knh6aTjaIzOd=+gnVNqwV(|-k9h(N$Y-VeM;K$A32+Ri)XZ$-;jx~<fM=SB^YCmH
z{&!FFyKyo#%(qRe7HAL$QiQ}b-E>06)wpb$Pt5wZ=>!alcJlszhbwt>RrWQ8X!C_1
z@${viD2<wTu;gE5FF>*mUBwc_@hcJU=dPP2EWu9pE+pO{MN`~5mmtPG0g1Ey+Z`J{
z@sYmK>RsHo_;(Pu`oDXeWJpOL5K}^7PFAE*()}?=JILzk07;2`8h{Oy#K?j8G?3SY
zdtIM_psTQ91*!O$2B0AsOx5vsUx`vR2^Uq8$$q<Ib#xx1Q>_*@Q0If-DIuS~172cV
za1!g}L^7nZE}_g^0Qqm|!dllL{f<|_U3Vb(je?v~onGqhtLsx#E-duY9!T^F5>^!I
zIt$KKcCvj4038Sw)de%ibivg_43M9nVU>p-s$ka}y<c3%L{j5#_vrQy2t>+(cr%SR
zpTb;n`!AN`FqtY-B;6+Uc_2Q&O(&ItRIDcDN$D}U2E-l>RnI^$$>6hoAt*)Pbu}6%
zGV40N7mNILcrTJ2b~PC%Ei*Q-3c#lp{_cxIv34SJ@BpyDfhuYw3}g$V#MWWTS$;w=
zco#YV4ItjE%lV4KPwHh?tVM`eTxLk0;(91eAclTrB19dkS1k5$KJ_08EyqZ+NHLtw
zO&`k2`Jk&9F0&;z!ZEFInH>n*!5N{CY0b=uSl)0kE!6uiK|MCanyzOnGE}v567zN_
zAkW|rFw#ICnCJ-bD2SvpqzNji4qmYkHGK<S;;dgwC{#+@)i+2=DV|;T_$Ct5aYe$l
zR3NV_)^&MCU67ajMZ;HK*+yN0-t$Eo=Ee+uO=iR4`t3<QsdFBHk4mE*u`yktXiq#y
z>5OM^6Ce}bfNIo-8D6`787Z?Gx7`cz5`VR`tEi_MP;?ddn}I|VXt!v{+t*C*iSKVI
zqE7bUC_8QsAx~jzs!SXLi~PU_GFG|PxFigpcVFgOQ++u6P4&T5sx`f<dXiSwMKhx6
zMFk^O)o^G58V`^IiR$sr(}Jph8A!~Uc1-DVL+W6H-ilIGjoaIWcnK@Qa3uFn3EV_<
zEFWdG7kAHrpuGpSi^h-EgXp?v!bR5}oG-B6G+aDAS#C_$16Or9nhm5xKdowC$0S?T
zK3q!LiqaUcda8Ly?-quF1<&|rUr#*X3CE8~!l%EC1P!hSrShoO!sxv?gfGkO`o+(1
zC{m`NeYk2=Zjcd0S?bP{djs)mktJau-r03mH!<z_u5Q9=!gF6h6k|6<#$Pu-xL^Aj
z`JXvHEBb_siQh>V2k>HCN=xNAvV|Sb5e&~Be@B<>Omx1fV(?}f5GuAasrlxm9U{~?
zHMkKLW~6FyA6*<_)#5-~<Jj8vO(K}HuuGN7D}cuxuaR*3j7_!em<f!9YCC6w7AV{$
zJwJKO1eit&94425D8_DS665Qu#IQubov~Ee=osQ$WQZ9q^n8e8Q1H`DFT+S<Ia(Z{
z6ko>S=7D=eW=DmzN^Kl(sn<Mw8)E4B?T}bUnL_CLjoH~*@;i=F*f$V-7a4#C5)!1)
zXpzaLRBCM+JY$wpd6sBQURbqIg=>r>@lC?Jc>wq(H|C#@*|}i`<a=;+oL+-d#Ppg*
zp>Ta_xG?%_Vva+ZeIZ`L#j<L3+?cj~RUcGN@>QKsB*xB<t4duph&V;aQr2)UT}tJ`
zi*!u>Gf_K4F%((TNR3dcmg0U&s)aSJAw5B<u)z!<YJ)jWoo=NyzEKri*Zlj{#=<jN
z>zE9MdeVkuz@_li){rTxh`(}#2gD&;hP~jFFXdGIajq=%vTsP#P|C^bcZl#{giCKJ
zxUM(PUpI>EIAm}w+85wU;|R)QwioRZRL&|mxZ%QD3U>~;(hLC82ba^O6smolL?on8
z+WY(y<?nt1%S4bDMe|k&q2M#HXmg@IwJ^+nL@4+KEI8RBWMOdxgJbb`3=H+Ag^3OZ
z(!Gpv!ToU{Fa<QjX`)aQ*^uF=6y%?2xE&VRR!3L^g<vyj)OZ$Zk_G}XFZF1@_CUi?
zQ#M+sqgfnidL*i=9nTCe-dHzm8nWVg28tLyGKP5gN4yH9=xVA+ou|gTTHByOzfrnQ
z3!oS(Mdx%Y^Fxk6jb3zeHzcwx@*`ltL{a9<f%u_HX66Q!VPPm%!xgENya7;8ShVkg
zov6q*JrK4PQ?u=A28XWgY6pg{?G*D8ZjxdT9!N;&X3>Tfr%-P-D378ew7WOto}G|b
z{)@JIXbu;LP+P43#ne|#m0@2sRVJ$2{NK2|H=O7J0bx}z(HhjpMb{pXhm=rL#1CP)
zrwzYR_o!q<4S6gl1V>{>aOSVB9xl|Ak8(i;iC~*odZdBGG&ht&lY=78YzkHwxp_tj
zV*|GrN1}B&LIUyD!SltT7#|$??#Tbo+Pn1Xwj*0Y{rM|S^WMfy{0Q6OE)s<V4Fn`D
zM5j;{656*xp%U=#`5ZCE@Lc=mS?A==Qc8KYV|{*3KZe5*BVty9YqSHGN$}A7q*mSO
zS^)J*^-6EtlCOkYG9RdV>JpzXBJ8<*I3P>gTY@*)nhyuPZnieeAUhR$RcJ2NY_IfG
zOE58N`6_wj{qV|$_`q)opg5aSmWGn)z-71bV54|T#vRHWgEBajO239O`dCbj!{}1$
za=%FF9Lg);{8^zFI^>3Ie}3uGG`5%vUuQ<CKTokzp+0$uiar2lW+|FLn7O5B98z-p
zA^<lGNv@V$8;ARmt0mV@+gdFzNiAB2Ply(`pIoZp1cLQ_CER^t#fJw4);COu+rC?2
zo>7gOnMxDw1|xu4n>wY>9jU=Cc6Ey1`lk7<*(KA|%&ooc`|$y)+P+^OJ<!KzYq|QU
z$v=`T26vMuL|M%3QstaMiYtKaEt)}WZy|h9gMDk(Wa}Ky!<8DABPkfV+?fwKYS{Kw
znLRaXO)6D2A4#OLP@Z^H_RvwKCS}NzqD<z8ckY;Y4>^MVb(DN+MWD+*pLc(KsB@T3
zKD6tiyQV#t-OZElsiJy0BIaV}y0Q(VwY#7xom(F^hL%S6ud18YJgaW{hOD{j8%E7f
zh?s5QC(Ja_?fc;;zVh9dIlSe0Z60mypEi%SwhF-~hTXF&UfL_8d&^Y>YK3v~t5%o|
zzbn4mGLFHP#=NiXXHA{@_|7ozeeEvr1|v#&Qp7EY)emh!tX=?!-8St&8w0*f0FKr7
zF90qjUtu4;b}HD8qM(a$Ii#2pH&;_Rm=mkraw1buU$dP25LKBl`BqgXev6_!xtx~v
zf}y^b-!39Q4nGsfAKji%rOJNuBZ(Ae_;h8-N~S9Z>X@7XQ}u8L<WB$mkYiA-ROTJ0
zpZ&fN9RYJ;sibM*y=gsd;=aSXTAM?6K79W<bg#m$N(D%z8ndMWBrmo2OwfSnPTQyf
zsWeDw)PU%!e0+hHZqqqlur3lCRgl+5dp1%HH*_?mNLzqmD0t4*HUEg(TNBWz?U1gZ
zQQILELxb5{Y9XR+G;))wg5E;Vh(OYz5Mf>ZQrEyW=&jSCZ_riP97%!d1v3J#__a~H
z-qM6EwP^SRg9=WXF)<XtRb4THz}3ASXCSnwscgKP$wIpgYP@s=4lMYl^KNvQ#55gg
zqbnO0-Dt{&`8KHc5)2vAd+8LTGDDilMrFn;8&Gl6VK?9vB0XsO4N+B^1=&`%fixAR
z_-1e$I+FBVqT5g?WwZ0C(~u@N(j#@d1L@R*nM#FsNF|$Hv!y&N6*^CCvxa?NI&69p
z)wKVAAVMyDbi*x5%JN1lE-KU;4ZY}U@F;jksOgm}2LgJIM#YEJ{oz^^Y0Q9hEW#TC
zT8!J6T>I%;ln)bhE4uF%;a2qZapNOmGEzUkhcs$I^kxE|p?GOQQw!&-Yj`<3w5@f{
z4!-oZ&iRq*z1FuLdGNSI$D%5ylh&y;=PuRr!L`u^sdXyNu_Zkr%96Dwb*RPkv~?u;
z#>R^78ykBtG0(a-seWJC2GV#w<1+1hq@^<YBZ(B=N#Ko?4}i!r?js?x@R3%#50oqS
zsj(q)M7%{J7awU!k<So6_dS#TNVUuOpi!aH1<CQR`<&Xq_IjUOkN;72qtQvOb-v4M
z^8v$crCU_Ps8sRQwiwAOPpZ}nUoCN0rIS+pCOd&|Uq$0VC#BlsPT8C<+PoZ6-=cT$
zh*gCbZS)b0sP{p=(Ksw0+#iVINn2nI{B?S_Z&=Y^e^T+1PxRKXX>{#0@%mP~Fc$Wy
zYevwpxz#?Ain|VM5g^K`r#<DEj>(>((Q=F?53MEg=+Yk3Md=z_&_$_s!5o|<wL4Nd
zMq2n0IqZ3vcpO)xoMFz2`Cd;8$VT;#XuTVb@Tc~)&uVybxfUpm8X{S#97%z33kILI
zVaN9Kfgo*d1S4b_#uud~)3B;y06wj1BdxUT(L%<9K{dW^HK_luVNavw7ZQ)`fPQ2U
zxoDb@fo#5-@=sY0;d@kS8>}Nqqa;l1nrc4lH^(ucihlv1nyE$_cbd*y+~cY|WE*a#
z$CwK%9rw;7$z@P`B%rlD4oqod#A6c*fV3y0f77)$i)e<WzHHK3rM00f*N!N9rt>gN
zzm^(B(=Q!&wOkvz2ZH=$c$JB$jqwY?@q%N@1ir!OdL*e}qtjE($y_*DXm;MpwIoDu
z(xIsuiSv(Oq`@NklB6(oXexu)Gz=fnH0U*kW-ek!K6Pm7Qt>!62WbK}baWJ`GKP?B
z8Ifu^Oa)e|P{EYIDno}sG1;49Jr~TGAxK$3{!oViWWl5vnyLlbt06d8!pdV%V;3f=
zMl_jzN_Cj31=<}#dGJ%JL-%B=EyvJVTClYYZMGnq2`k@df8EghD{%IaqzP@RnV%nu
z-C76dV5P~};2f;fZw@}|y?+yG_X?x3fk_#0RwJ3+JU&P9ckYDrQo4rJ;V%@!EpzJ%
zL$BG?f!zORe+kn1n&|v^{-i`lV5L5BnhI`dQa;q_{4R5-H5FFoIlLKT_X#U>4lfRX
zNd~y^7%C}Y^JpAC)jS&YO+sEe5nU7bBgvw9y$?sC7%m=jHSN5zAlHvNOz=^(V<(t=
zkf#3;W74N&rg1#awj;^`<95K1&~@@&eVmKZOQNXgg+~*yt%SSLsclsiL{F8fg6OFN
z7rvTiV8>4)do{y{qUGOGsj-OjjvzfGG-+TGwz}FiaK~I-ea2;Gb#<9eDyEj=W{l|G
zl~!Ski@8z_x-^YIb5g~5Q`1ar4Slv$j4n>Bh`!BI*p^h4$fxEAvXc`{!TX^cbHWQM
z$6k{N5w)*}PXz-AT!0|?>Lpa2J}R!t>&w%qg1DouJAd-;Y<ph47A`*#&OF<`(e@&r
zC$=3YnuucKZ`<|Tl%(dud2gwpctVSRuuk?V1d+;F1(vJoji&Jx;TAZYDM>dk?Kq2W
zUVM0{;C09^`{U7YR`09|?>NpgfnTM%@h8~+TvKO3kyynEd_?I5H`M3(lha;IlBish
zWr0lOhz10Ms}t!ggx1LPvbt`D6`J9E*LWbwUh2bBS?v1wSUj=qpfO#pldwanG?&}j
zIFe_tZsJ?|Vx29P9|jh6yHdeT-zx@5Pf5CZYA;wYu-sjpZ;@in6?UDwt8V)F8dD{+
zV3Vb~d26Fs^zpTXX!O>qTj$N9i|<f7=;1rmmh|u)w7#p0F1{0grh6~OWWtO?tZEg+
zlU32pk0cczd%dz{bJr_dwpY6VeE+Lx!r|!k;ABt15H!eiwwCvyI_cx9Gh=$BJ~Qh<
zj`+&^Rc-q4ms_oTvgtH-y|yb^wXSb>4c61^{ar;Az<oeG0R)aUcmf)4l=M7ng<z2<
zd@I@m=0qV~4V@WyJ^nq&HK17|Rsd5&Nef_V>OeJ`HWLn!;lN*5Q2NPh-oU5rNYF#D
zk(8+(l8vMYt4u@nQ@u1)zmQ4?{X1{KHFDVxh`Nr5^DVi+M4&*Zc1aeFBt7(<dKkLg
zU2cY&bYrdTS2@XtuvHG&z!(JKB1h3gRMG>~^2#-mS^}d7x~(dNlB8u1uWuBUrhxS+
zNkWRI&j6Z%dZ!I(2J}K(CmBh)z5^Lav;obe@(N>viWiZVc0mtBSv75xjwJgqkV-ZX
zVGs}uG}(I{$-yv}Xyiz;qRF8n^T^aF6jU=`nF6U@(vu^~9_p?zz=I{j!U`gSOQ%x7
zMDR2iQr@5J_fMi*`&DqVvg}vE(dH(`up=T-3=59Y(F;rkFI>~(N(JFH329C`PKh9`
zK_*b4wDxLW7Sow!Ctpri4sz;n`3#U?HA5<CZ|s#NyQ43S=*z9KT{%-__+Ale8mvJf
z0asPn+apW-eW{F+%tVAm!=)3<{K;)JnPZU;36mP$s;#Y89&iJ#n<*K5_^!z7Ws^rm
zg`qE$p(rLarO?UTQuh5tODd^bYVv*YO^z2^Dsq23a-F5J_eWlcM{-m#+f0%wDjX_k
z{F*e=PX*aTlY>qjB+=5jFhHW!HEVHn$PK9u41JS_QypZ{GG!x+mMPmngS4s#JQ<JZ
z{wV3gxU6C1d@09LIq_m8JAy2D@|B~4SFrW<$~7W=GbNvxzBqVgI=}c+VL#3HkNi>0
zKE-OL9;L}g@BRiCh+!PAyY4}HWx@?G%s!IAbV;VTn<rMV)w@^VtTJu<(DMXw9r}sW
z%XlM&a;QP!`F#D&tt>{z`m2FSUDscAwQ<S#Qty<cgLdnRp^&EYI75^5?}xNmjXKTn
zjt(SZcaq?YG+iME4oSm(VSva|N=mv^pEpX46%IhV`#eaxY`vP3eZ2d8QdvSV`J^P~
zg!wC1c5>fN#FQ`{{R3>5R4az^Fuvx{^>C2xvLY2d7*#uEGF#H;qz=%3G-(v+^UY^#
zNKTLFre2fmq)BNAukes)*8*wfxF0`L95_%|j=Lj(#B%7vlRRwPFAok&sS;}%_@8Hg
zocjZ$mg61<1?TLTOrD`0f`uSnX@hg2U<mG9016ndxlk}F>(!+gmi6jUvU~cg{mJg>
z^nbdd{pvvu-G24plsxZB2l*KliO;QUmUs21<XP{4M!~bb+Cxc>=VwxtFk3-e;F#Yg
z4ID!AeFkUtuc_ByCOn$&Z=J2}Kab3Oed}zi{XA4tzH7I&ua6xm4bw3R`qFHDV>R@(
zzvsMYSK-L1F_#tyB~lWAs<owdkp%_wF_%Xs?_Q4Sb=8QJEIN2%$~{Tb{O<lLKYhGa
zUb7-4cX^lJU@7(}sb$PDSzN{v^xLj5eXI7$kk)WtGiYDss9rUmB<nTunQPH*@QVE3
z6y!e_<mIR4LK*kGMfTI|qp{{&!cjac>8hJT@T6g>=4LExpZ9yFVEz0>ecg{U(&QET
z9tixkreoGzMUo`@=h^35+7OC%c}>5Vv{#XoRqgk*IO$ilPZ|!ZmZ*2vpXc~)?@A!K
zm88;Pw>v7?kp3E#*m?JBK1t#lhqGO0v@(uVZ0Y;`4Jo-T3}CaztA#N;Qj_%jBvK1w
zcI<i2sYtPPnPST-5SGa0ZUIX_U$2w2KyuI0Sh3shrQ(Y2SsEMP_IsAb^t>7*9=CYO
zdLSB2X8O0Be$_%Ks9&uR3ObU1Q&4*qM9KI90Qyz@1ZwDo?@tebMK5=i<pFa19*AEe
zaq(A)4EDlbp&RYxZsrYrx*K{%@VW{dfUABLIDje7aqi&UK+KeKaXJFZls9f;NRNxa
z)<_=`u3-dbx(XT)%Jr+E0r)%;wmJ14y~>G{koJgf$D-(3UyVK==}7t)T-%dEG$HmU
z)ijw|(Y=VV9;t$XzPgP60l}XTy`g-U88~r!ulB<28SmtaBnmcd>bPxm8CLT?(q-$+
zJ4=_@^5<d`DSiaQtf;T6TlPu%UIbc`H8EM5j$cvNed_!e!Ebn(%Py=}w)4TOzj9@B
z?;f3(j9zg+eZswob1~JET^6-`&hG8*))@ju=Cc)1>Ypz2*vMrW8|de9>Z_cX_wCLO
zcqDd)7*0MbIB_8zgV65$$c5G0ogcAR_OvK{Ac;X}{go@eS?fP(1v*qXxfZ*a0PxcO
zgoq=V>a&iIy27iCW0L1;c)o3_FLD4TQaNSYd}WC#+U6_E2%o&K`k5nnDR6pPk5R9Z
zJ-rt-j}&L7qgnTohM-#Q>gSwI+plcdwEfC9<fNGC_%OY^@<da5xvk4hr}wL%OF-HC
zy{IF^X1^Ep+?aZAUvz<|J-xlM#ctT!D_acKOM?^2rVb6xlaly?FBJ|YCUtO$6m_}<
z4c4hW6KwT<_4v6mx=44zHX>YIZ=M{j`N|U$?xm`MvbSGV4TBtBWzDRS;=2P5P#MhC
zS<yIY>n2XZtGbzS64F4ff*!YDy-n(|d%x;C=(;=E`Kb=?GJb>3JiV5sS0CZ&oS);N
zPXCBl$jV<_-F#FdGqw7;pml^Nh=&BrzjA`j)WsaXY(CCl-?y$zF;8TXR>6AQ!Ce`z
z4;D!(<x_2SBz)7z-P*2R9)ZuUa%SQT=~p|0w;KiWqZLcH`N|a^*sfw8zSZ3b%adTb
zUv&-cieDvJuoU$Z`<=Pg5bR&lu|LyM?tKTG=+u1&L?}ArrSGYr-tM+v*<#v`I~7)>
z?mJ%0eR1p^$$7)*<G$P^g6V@Z1Hrq-of_D-MpNSuZYz<}1JMvq!w;Ft^sD3n3rZh)
zNQUi9A9O^nGgH}+9E(2g^x3G^ROXIa?`t5QMEao3z+|A!yNMu3+;~4CXHD8fzyjJ2
z%W)<H5e_{g!&;|bGcj<?^r88*GF)4#+v9B-`@vQD;HA6|&7L&q3EB_SYx{N(hy2Lb
z`G7b>vnLIG`p_=IsDBFRQ*n*I5mbY7HD)`*0M)$M_gP-W#7NDz(Lr=_{%m#7XMNi#
z^!YYIh>38OMqmT#QX17|LFNLB6!`A<iOna}2mKnjF$&+j_6a~<^V%qkNO6Bh+>1Vi
zF&JF(DvXk8w~OtRwnaU6fgefO+cIb`n}T(F4cy>n*r$#g*c<gptnpNa8=P@5T!`+e
z*jBVY>ep~Bl^-GkN=fvtPvH+3Bn6ug()ls`RZI?@zlzDB6QxUK_&zY((g1=$eZQKA
z>_<Oj@k55BAF>MSG;Di*BOCJ}Ut+hgewR=vg6Z@nWkS+C9|0ALuypD#^EDj$OHT!`
zm+DK0QL26V)lE5kGy2k_F_^0RGNeY3R}G|Mvt8UsU>Vk7w{{?n<J?_>qKHFvBsBEG
z)$wOTwN68|B=pX5u4Ni7RZA)(1V9U>Fa0LIC8h=na%AJc<jYWB*SZmLrmt~hEU)Dn
z75KXyp0Z44zxlENX1KltS)mQ<OK(e#8_4<1!=Ip(YjGGe<{GdeSo#epevGlA^<MP+
z>$wE|Z7mrC<6o>LcS>j)89k6yTT;9~B94Oyc~~y42rfY6SUjRrKazk$-Ko`bfc{`)
z2Pb{--0`F3^`N_y+a6%ByPTP;?_|@H$!fMtDA@tzT^D5#7IyK=A4y^&AFpgtk*4M@
zq6++x#%58EY~nUfy&T~OqKO~DWEtn6$4<7fprqG?nOS$~y>{c+Yj4|FG_JjELz&^4
zq#Mc#*EHRoJ=AR~4V{l5E4TPJ8k*Byu?1iz-5HGF2}$hAideuH4}I(G+W8ROul*b%
zhxXlsX+bU#KN`#ypIs3aDo83wjQK;xW=F!e%#GQyrBjzgnll)a^=n!OJM$wMNauBW
z(`%y?{6c<7&;#}@&kWG7lCkuMVv0P6*OcB2fEAk?4h_KimM=6yoE%owD~Vg-`4KJp
zu}{hDjgeD=uoac%He;o{Bmwt=85Z^Dgg)%C*PkM@@ze?Pt&)<d--KC}m8ydBR6fMD
zEGTz`BcWqP4unbhNu#dEiX3-J9-me^Qm2E5F&Ez=*1y3Fj!q{`KjD{BQb0G1jSh+J
z0NO(<;y^)&pJ4cnPCwxT6Ybz_tAP{8%Julk^=&epJFYe+6>ECpJYpCAp?E|`g2tr2
z(aQDlX_2CTPmZ3I%K-q2k6=SaI~qn|sU01|aGiWQKF3Ov;szE8V-TSRItY`cT?5^V
zNo~tuPo!&(fihGs-yraC9m#dJ%F5~M2JSGEvbQBI!V~<_*Ym555M0Nvtevm)4P-`S
zriQy%O!8Wgj84&9k7i`1_|9QQmW<f=&Z(m~5)x*BB+u#>*SFK_D)&_AF^^;*oi$g!
zFVWI07`)LVOxG&!)SA5|?{`YFV7Q`YL0Ps|QZgpmrEUT9q9u0?SRn24v?O8W6CyfB
zR#Yv&Q_yAFWfKWM#$Yl3AvZ^>CN3T*J597>4gT|FM^8!CBa#p(Gp*`<39g*U%#LiB
zXkwzHJE&bsjc^zZ68Jn^=u;Xz@i{@@cxsnp1BPfOQjNBPjGjK1P>7l|-VJWxNnxMq
z*gq~21{9lLCE5IS{buvdZkGuo4beg(-{72i)RH&&T^pjwJt@i=5*1|-M61^qykc~<
zY(V^G;>1LB#V17clTIjiA`e_Y=@IGc5*>rv==hz;903g;h@wN6jUru`?NU#G{?0D*
zL=W^~qCcgLnzgs<cZ_D!q13VKwCnmkP`7SJM--J`*YAnSbxJ|=X;S3FNG+p7AlJ%Z
z5prh7IEYT7<2byO6VQd)<&H=*w#P1a1c(fegf8aTW}1#O1QE3+9-+P?J_cSvgDoH$
zqtgw{izcg2#4fc)P0+Df%bG8_k71r&J_($53Iy4#M(_^OIbfPK;wGzkW*rIn9P(2j
z3P?zDL%GZm*i*#T+z?v;63{iE7%}H$)Pf^Gr>&#YTKKSf%g7{WG9XH=DPkrg*&Yc#
zt#O`-O~*LTmX1J+U8j*b$2jk__6^fcxDT|U)*PvLU9!e|XYg=D+jOeJgV&k}a1h$*
zNG=IT7~vc3TU)f$RV}B}Mv8T?|66sykhR%XB^-c_Y(l7`WGXv5IB`UnLvw}*T@!*D
z|0anGCysU_7}l9ybsF@mmL%=TpOcIDh;rP+5!V#pl_8}~FFy=AeI!sW!HAAwckm--
zBNa?uFHOe04LVfQd(qQUhiW3VCpV6P_P#-bYQ3uCKtUZ>?M5?Q>z7Xl+fi>wWsXaw
zgK5Edx#a&j0-mJ^AZ{I=%CO+JetC5K{sKd_?{5HKpdYn<$#%A~kzNTK$)&r%o0H*i
z_>tk(Gn;tX5V6oM1qK`rj$|OsJZSR->wt+A0}n)|5DjfMg<<+3L%WF8RPcA?xCmzU
z4DW=7b!B10y0VaV$|A*P!HvQ?H%`34d=bP{(M4i%s%UGSoGe2ddy;J(2^JdEsMdAi
zm{Ymf+NIxcV@IG<(<2}$!`>1{w}rK!6*bs>KPk#=!Bzn7vJ*;+gA3q#$vE(sV4W`m
zZ54h*U3p+~mqEHtIt#@Xw>U3oSVXcmOB$LaxN8_s?d<T|Gtqp2D((nK&eoL))}kbx
zGd*-3Nqhv|w7^|wo$e_lxHHCGdBR|iKVqYYendvO!IIfie%__c3f`J_c}JiGWoWb?
zVfe>vWcT9-r&Z<C;9zQceQi*A+NCVXIOmp(CX1i{ogpu5uN<5LM6Zi8K&&TTGL@ei
zp$sD$+yenKkmWJ|OqxZ0eJZv{&S*042Yq8U47*agE=NqdOyzj!0CS!cB3kjz9Ata&
zu3RLO?8<d%EOQX0mvK`rPEI(6M@&6bHk6IM3Piz2?32vXkJsF%LGfsp<^{n{7``th
zfp{#g!l`C76S)%&D36HU&d>W*5*?7=!;wV$jpr^H03I`OaD-CPOg9B^3mgds1`1Sz
z_e2AY0m2bJ5TW^861%bs7`fzBc>kiQ0~4nWs2S{X+rW9(492cuRcWs1h$$IAr9&BD
z^6qF*A=+ig*`_{_0@u)m`sMHS`T9qG5yZQ-OR=+4XJ?mBXV0%GoHnvvAb&4HLH-cK
zubFfeU;(zv$&*CE5M=9I@g;wxO=WyQfEffEHu<qM=uy8)av@%#pY+T%BLoT?%hG<5
z<mXbT4rp7SBLY)%#rJv%CW^_CKax0Vf>WqN37M%UsGlQ0Uo?8@UsLEUwV56I#J2=j
zE(YpMQ4Z@{68+_?$g#G}QM%>8wCt;hxlj!D{V$T7!nfp5W0_2m!q^g>NGf-#R^I}4
zDklb6z9o6m`VyVWxk7UAuM)N<clHhymn2WvN#YxbihQ8SH=UE=N~Zci34B7{b-4<@
z5_Ti!Vh1mk!9=G+^AYK!hA)^>s;ObKc?&pPQ3e<;?=PMX`pS2v_VduRj$Yq1`-tIe
zFwyxc(s<^lYMNT;V!NX^kmhF^WWV>X9{?efzDm9}?tTD%$F?+$*tms#?JfDax&EcC
z&TWg0y;G4b**{MPD#u=}yI&F8R`2&aqAh9W_nP*&w0#jcHaFaLI+b5{7sA!(wNv5N
zbGNq+#y;+nz1#CnXbVM$V7zCFXGr6{yD`&vFG|S{PVJb?G__+g6L$yh_?-$V#0O3Z
zJI$yWu0CTU0t~w+)Um5W1ChcGuXsUFE$L9C;oUtryA>VCdAfGf4$qK6R&^p{{9_pJ
zNl#-u#xMRMV>~0PU8gQdh^T}5^P;8>#gULzr{W0U>j}vQhGScxuNH*saF?{M2tqK*
zGx(IkChvKH!!XJN?!%{qnclnLp%$~?coum8DIsAlmONECOI~U+ri3lLlyrtGLR)a4
zP+26H+^I0?BqHr_sRVG&LEjuu=Gtr>QX7{Me1UN<0r&*z5R(W#rvrRLF7EGC8g(ka
zI+aHKhEB?x0-ocKxgAC5;@~Cl1~uxsPN0k9-T^lY0vPB^eYm$kOzClNfo!qqf@c{d
z1vc&X64>EOeJ_fAjIS5YK6EWa3YQ(l97?xx>r+kPjc}?dyb<z#+z}x9!7VyOyb&rm
zAIJi%Q>RL+I-~D5!+fRSfy8n1#u&q~(r$QAI949z0v0O#Dy<Jb!gY{NSZCC}S(OXD
zfc0<0??%a~UM8hz+R0IoflkbJTbN@!sVAIB4Jke{op%9gM>?oXt_I~uhSV;Z&Pota
z5Rt>tj0d93azo1@2M3P(#Vvz+8?5p<xyeu`6oz!j#A2qhar~FGTpWKeuv{fopQ*xP
z|6EzvL%)hKq#bH6xI6TTy}^(e(D`v-@eEIeUQc(-tMls%w?nE0`zp$UAxJyYt6Mw*
z)`J09Rhgh%V_d{{IjK#)#c-C~V!HB_G$}ixlZon3hH^X-^oSY)g<xHVEd0CY2NcLz
zLs@cSz<|!W?kkHEL)V`*Bjt>dIq|gwUe;6=ES1G+Az-nVasf1ehs?y&+!u9+Sq5}Q
zI_sr35=L5%mqrm`z*x>i^-N>AcQu?E@ptDAQurj)om+^a!4|z3pk}Yig^I)G%@hju
z=~4~dpS0XfZ@5^V5DH4@JRzuA=?+`k`+(7%ubi9hGd+{AeWr&MRzC6>g&|mn9!fAQ
zsVCCgONUXQi7Gq{)bgc?c2clV`%RBTuur@1NFBbn_6kJ{jlm5@yV%7Wjh4@sHySP9
zn{+Hv!KA0K?l_?B6`^*kAZ*dTRS<j1S15(z+a(|Fu$#hE&E&My;k0X_lRpx^Bch+w
zIVC53#GtNvB}6}W)e|N93DY&bV$!_LNRj`9$nf-uuS+#lQ*>)69rdQ#K_hqHT%Qga
zIlaqvgg?5kxktiWjXz-?7L0cVQ_O(~i;cHt6pUR(&(R$ge%7>0?zGWqipJDoymz0z
zJ9t>{^Y}4<YxxY%0bKeCJfJ!PgqtElbVR%|5hC^U>otX%U@USYi_)Wj<<_+I!A8!&
zy>!wWb^^J^4I#UX-hQx{dos_+-&ENf<RmpP!d*iKLqsuCzz$2z(-WfnTCi<1xiK0H
z{;uJLf#mHPXBbG{o@>HkV0pV{9tQ1`EJ2LgCsAI}SnVTukW9l6SE;yvR9C6cJSzg}
z7fEhaM>JlBEk=En!obj2?OMo$vD&y+HAWV=Yj{K3G^;m)eV#ZX3^SSp)`?PRQX}($
zBZ_e$SUa|2hFCwx?2EQYjRIOC;RDq|V;O=Y1Gk%rG0kY|r;v=tIIF;1iUn0nE0ML)
z?#tvuZ16ZX#U(TFznOU8tajQcQQ=~sBR9D)TjeaOYBkVEt!lO5K2fWh4b_vl>Wl_{
zRZ|}^JYyJ8&`9f+O3lFMgXCDE#XuyrVA!#3)S?bx+o**oji3FR`&p%xsU|%_#eS8f
zh2rLmxPg@3%2s<_CW>sY%SMrH#)D_^w4t<&5`;PUBhs1V_l16{@ciQ{x3bha(9T+!
zsu>$n!DFSty02hLhrLx8iK<YCktjzB=2fwL@grQA3$G-!owCB45VuXspo>`$=3}9w
zkHP2J#35;j%zY%7AuyE+gIeqet;xm~^AS-LOca&|H)s?20S%w5bbY%<J5{ZaJm*Xl
z3Kn5<u-77;rBEsO7;Oh-!pwu&iWWm2=hqY(sK825Me{FV;Hzn!6n0j$y91w?$Rub=
zWTj}>6V-%aHoLT7ORv2<kyjUUg=O#;o|7raJd3#BpvF80H@-}##W~FgtkdG$UXt)b
zxV#~TFe+UnwzP=oV!Ac(#>pff7uA=Ee!l5ncL1s+uFC*59|6P$CE-Z2i~4|vOX9Z_
zg%5;?S@=@jMcoqb&SAB$QBGA+dPT4{I0(45kG_RJBSp^$tntwAb@w~w8(tr-_QI>u
z`3%lS*e*6?yrza%M+pFwFQZ2=^ouMPc4kz%rZ)*60J{_KLPLB3{|_mz<5rME05$4$
zZQ+wr7i$j`?$66(#$c4!U7LW>3q_lN(F?`c;Ji$Ku33iU;9Uu6`1Y{1;IDA4bhtvF
zTN!Y^!9uTlQ%eTw%{#RvRozK8rbpcUFn4Ugh0C?_p>^%9rEhR$@v0$!-->Id+T?W7
zR7DW+BSGb0bC4sKfdlXQgBfCxKi6r@puUw~*%1slof*vju2<TT#K<ktW*NewU*9%^
zg7^Br8A$WwBo`7n(s96Do^(Y&${tL8f{ko<R)O?jDMq*<s>gK*G;nNnvE3V#!*VP%
z5FvH&fIlh9a(I<7&;@m|@mrGU9RaJtN+3ViV=yu7iw{ml9-YN!R|Az`Xpm42e0mml
zu*blov-rGWq`z4@1IRx!1?b5yGq;-DlObVh?-_I#*5(5`$xb#jI|MI^&0rvJnNAIy
z!EmupAri8;OrY*DLPN-rglnSWP1u0K61ql+Ryz7(`VB0fNyVfM_#Mun!G)tnXhMxY
zO5b0>YEqMsxy}ZCeY*yZzP_F8GX{IdKD$~-U*8@n91T<W84R|4>gXC6v#!V>24>tY
zzCMFO{3Ah1zT3t^=)29;Gt%9g-w$5<v+(=D>30f1j5uGW&a7k)d0x)xHt4m#Uq4E(
zeZHyKq}RSqr3ur!KKLGDlb-v!rA;iiA-p=_`=;0}Ht8!o;vkyWwI9QvLZ~pgg$(^B
zQ$&j-3>gEdBp9Ij*}zcEXO@&CIe>0g6Z%gvCK!C^`_K^s+U-lcVDOyhOHfL}Ah45?
z)8I=FMh8e*GCHsr(0eGHkdfeH;3e0{?=f^~0%hZ6pfE6^_kn8?9vV7$_70|kK`LL?
zP)w<Mc}q#MY;1ira))fBVy`jR_aJeIFbnA1yZ)Z^8oIt?)pol_#Y{R7jw8s9Y^un4
zQu!}Xrf3hr_7d-=EDoE9B5WD9rFec-Hj<`rV&Hr=`AFE|{V+`m5DJ)pY;1*i8O~%5
zaMJ(-VRwZfGuY5}8Wk9sL1dC-WCoGFfPoq0>3XO?qU>XNWy?Ma+Ge1HWUx`Lu*!Y^
z2tU9`Z<5|1mBdB+{u<;vx&J&VO5&o8A0+vXFb26oy1yz(@|`Ghl`t}ZCy<dgr0beX
z+7KD{8u$>p?1OD3Kas+S8mxo69{rAF<!^2tG9|I5n#LB$0N1xJGj9X=h)l%|0XKRV
zIt4Mqk)XREW_Y@c-3@O|T_GWDk+i72vPFB_D^t=b)jL?3WR4~-DrNx=kt2hF@1e_&
z;YjkJ&|`*yvqW6xN03Bec$Ki#WoHv9kaBGShy{*2J{}k;P4re^u$u0A8L)U3>tt$=
zWZ+~4ST*vV$g9TE(z=rq{-l#YY`*d&Roc9*!*)qUyy3mA%LVC3f+S9R$b#!M73$BC
z#2Re&%9LG_ssgcUdehxxVMml-SQNC9C60~BF0@yk?1D}SK;JG`H(OA~^roxFy3}{*
z=0J<3XeMJz<HZASggwJeKNOu}6z{+g<h@@7F%W#OLJ}l;snmik@J>|W&V}7v@fZyJ
z9i6&eaKlu6-ASUvsWAstfWo6&#HQ+3ZM(n|P<4U8tL8`YFu9XA@n#`y;?0sggoadh
zPB({?B!we42e1*yQPyB|e<T=f94c37yH@tN(Z1R6yc#5vn+0c=b-h?|6kW9{9$;y4
z8N-j`sg_%J^t$X<-NCkbzw-jw=6+Qj)1sIAp*?LzQ8Ui7tINbq@<=#Ual(~#S7fTK
zzWgRBQ140yKaSL$2nE*Z2LFU8sYy8%a8oUJGT@lJ+Dya``$(9ITYk9*L6V7-dknCT
z{oThXwZHoq_m<LM9f&?QO<mj+N_(|8dtG1c&0gQT0XkV;?aNH%)uqf-Ua2P12aMd4
zw%6*x2z%|V_9r8;9&|8rN7BY?;M!hytGJ?}9-W?C0$)S;v$p4J9L`)i5<;)#;tjq7
zA#!2#awi=zip><ev$LqS?{Z92vm;@Tt^_^WKmEDH5a`wNikfCW%i!jH)9i0zs^f&9
zwRlB#8yCZLH*ZR`d52Eta!lL8lYfZRnjT|Ym>S@&R$EfyuThD~;iA~RB3<tmqS;(6
z<4eMwVS^}pN*gTEc#T%f4<8z>O!wQ#%+l}actv-xnClK!N=}yl`M3Y^slT27{ipvU
zL-&3vAM3*E^Itqv{-^)&+kbq{j#xfD{rSJ2?Em#&pHKSpzkl)M>>9s~qhW5J^6GDY
z{nzKe`j7uo{-u2C`s;su{?~u{>pxdp|MZ{!^MCl~|Lw2;-Sgl4^*In~xVKN4v+h|=
z;h(F<{9G;mr~mf1|Lc?Q6rTV8zyIs=nHBM2#u@3~{xxXb&V<W!cI{8L_IM!Lcdh-W
z|KZ>N-~asA|1(?ZD5|eEKJ}Nsl(O8;Y4^993D<kJ^7w_GY4r=O>=_66n^yiW|NXyH
zEA0%WogwVI)%p3yDxXoUf3uOqD{N($?0zQ6yOsYo6Rca535ILmXM)+%2-dHE{Y~jz
z{@(GhpgH(<j{UoT9^;?>^N%0DosrQr+ni=~o-g<L$FN%0{F_5VavJuMZrgw61OCnO
zQoTQ*hW!+n8VU-2XWW<#)^w*G*$kQ2{XO&jbECF0&$K+IsDFDh{mbX#rP=iN_b-eE
zZtq|_@Lk^whpsZ2PT_B}r9IirMJ}{&GeL85b17)>x7o1gX!t4k`-cC6B3D0dphrW#
z*Y6DfuMd7aQkHk`I<;uu_6|JfH=Bshzsq*sOTSEI3jQD)UV?5mJq>-EZ5q}g^vm{l
z@AjJgp`rhs*<b#V*-uY^+c#T(Vk-AEwY<4#diiZ87@^!;V#5C}TSK@}WowE*`fWDP
z2PJ&~3jV&M>?5zMdIFR3w^zV#<<~#JInlpNWeWbFcQ(IHWeWZvTiai!G6jE-?c7{n
znQHsPJ+i`rP{U8b-@5`n=Wkyb3U>b9@c$z#pyo|bokRK$dN=FWsZ7BiWP@YS%_jQp
zZ?iS$R7SSuuc`dI*<hG<KY^l<{?ZDl^#c(9_9pb(KX3-%ey7gqzV}_<pe<3Rwf@93
z4#In7ndOfU`u@{7-~Ytkm|Dxb?aVu!{_a_SbhE!R>Hi_nv%k*X{U_$`3kOnAzuTzr
z5_+>qz)SSsF(QYT$HwQp_-%ZSQTsh0@=HS!N|M`5B){z&)D<_A1m9+>(DvPYSMq&E
z*z~_LO7eY15dFV0O7aVzp`Hh=`PmKj_ut_cz5;_QzgjBE_g#dV;FVF5?=v22^>;R;
zzs<zZ$~W7Ue4i0MBd?5-{KA)LVH*F3E8^EqM)Hll+A7KSot$5<i2wTAm3*HuNyuOM
zDEK}bg3Q12N%C#Rh^F+)#`G_IiHJ4jeQf*gOZ*Z<<TK!_osxXtJ%mJkWt8Omj9{aB
zWt8OmjGzO5Wt8OmjOoYm%16Pke2b%LO|bIqxA?WA6Lh4ngHV!hyJ!gD{MMvU@_j~_
zY`l+NO1{qslZsbHNxskM{hcXNzwjMG&;7@1;+H_<-ak#WEBUr-Bi|cuJ_)|h2406(
zK1sgMh~P4>jFNnx5gxg(jFS8cbUH?3^AFd=uVJSF)~i=rCHaG?{S}9P#h5>S`?=uX
z-RR;|)Oxp%(5XrA_raUbNTs@~Mrgj@QMlNzY~^eyT=UOX9*<y>{80~Eyl1`gH9T;A
zpDq2JUfIh2=6cI)C4KvDHVFPG8#SEx3gxZg{QEyb@$q}tpMUB9z(*(<!sXq)xxYV8
zkrAw&uZ)U>^nFGc*1s}}z3KamAjf%SZ2qTegrnB|7Ipjr;D3FLW8(2UAEW&v9|Jx&
zuO7+^=er(mcXlxIQSb-Z5EJQUTlQyagJtW@HtTnaYG$*9qx=d?|Kdm3#{&NM9zlNn
z8*GrG-p+|7_1n(D;^=0R3DURO5I^>2Q$X48vU!Fvx!EZAgKSa*=NIr_(E=aOy@Zwi
zUswywRw9Vq?cAJyrgNjevW)&mKM#MUn*sDh-)3p^l_8>pe*1GMiZRwNJ@MZ^(#I+H
zzo51eEnJ%qW9Zb{{+$Yz**vZ6ZZ@Yk!?)QGo$F>(xUO%r!MWgO8~$f%v-HB__%r>B
zUtk?iqTl%f|G<vFI-k?nx&G~Q8neND{AQCs`M23X%y_dY(93t(CVUW;ZOSR}+iZwO
z$1lM2FMfe}NOFH?xA_ME(476J&dqNh;+PHW?l;>guipJ`wx1#I{8NZ`wl1YdW^4UV
zTm@#?tS!Gl*{{m}{x5KhIDcmi{6qJEmu7~NZ!b)q7GkfASMm$D!ec(07xY^H3u~<^
z0x`Ur`V#$tF89mOAo(kb>f^#P@oM$0Cg@i-GKL9yHT5O>Lk;Oq6W}HK6-DrItol<u
z{iW%O2wLy?dPUzW_7H9To%M=-MY(s}UhALf>HHPFQYm;Ny^5tP`U73Y{GxOC*Wa$>
zSCnUmKJicW(|<{Smd+yY)?U#csKWf`$?y{W(yN~RW%NJZg?<I@QGxVs>=pfi_Wb9Q
z<fl#h$8Z0p^gq+@=<~mv-k*2)?5iKvvHaLScl-Z4y?#Bz&%bPMUi&BaG4<A=^iTh<
zhUYu8)brZ?|NQQ`vcOgs$4Ua#WZ8p<`;zyx*GS~}AujA%V$<_<m0F7qa~Vr?t-K1r
z^L{P5M1h`vEviGpRsTsr!7s9fM9v5ldjxs1dlR<Kn|x9Pgdm(jyvM&2_JL7gEpVhG
z<mg(w(8DHqExO@3+>4joy3@3IEt=~)tq|z^56ZX2D8IiY5yA>q!za_xW`znyjM5`W
z^^T87puF5U*QB|Q!(VnyumT`T?3%pJc=$n`bV56@JgiCm5n{$30o+m$Sl~!dOS)?w
zK~{2}NY|uu7x*SVf=pxw7Wo-`MGCd07swH0Q48&*4*?i5mf}Gl5{*ozW3Z<m!kY8u
z2wRYOuBCp;rfDR?5-ho;Bkt=Fu&*2K;XMwlA4iZYIwPVk`KbHG0G{S=FcU2~tRt$y
zn(!rq0sm6m>@XZY$*d0qCLh5k@xVu5O%fSoyn~a@(khxuPlgPCu;k|sVwGo2dZq1#
z?@JfO-OxfhCLx~e5o9GTTG;3{up364zRsYnTXKWn4V~cf1&`ekpwgr=Sd+vrAdNYK
ztTfd)OJUD5IPIGBqu5wn*OML&B5P9Lv|$wlo1P5cx+YaUJ3Ro`pjXt!G*}Gj4wsZQ
zXvn*BDy@+^l0D;}xo08t>k(w9AH=a;gX|1pOK@)Os4sofmLk!^gmEEO{Z5CdHC$bc
zWwPX-kFX7E(DDo3IBSq`5oADX@XEPC$#x{M<aR8mLFcQD^)%)!Ax3fVeg@UZ8j3)Q
z(6mP~G8wJpk_Bba5j6Zg8%YAi4aTb_K7hS3&<Yh_N~H2TRPZ7lNp6J|1WQMfd+Cv+
z+C)*EOPCL=LG!u_EO#WV1}hH40#Axs=3-S9{ZUBiQqd!@QdE#gtwEopCrjmxx*{0x
z8j7Zlh!jV{dK$XaRSy>78l4rTPDgA76`WTq^nSJEDqlmP-b=?cZS*a!1#538LVTfu
zsj-@l{t(dBLZuXZo>LTUQNVgoge~zIRPYThR5P$ZiUwhvvw01LkS<(;bXh(UM<!M?
zBgHBvMz%ai#;}@#t0Q*Ck*onhD$2HMovA6?B#Eviy`L7^kgI7KmvRLU;gPUaSb3(<
z@r6szxLhm386Tw@3vx7Ov2~tpQM~Vxl^zL*%qyaFEK_uQ_;DUd#n5iFd8zWVi!GZZ
z<En^*yo}+=0d|*7Rld<rI$hVAzT-<I4o^+T(<4FM2oQ24s5==GKN6D99W&JILpqF|
z^qC5xcBtSay!y){$>!m3t%#a?1lTA*cK968fS{!kG+TQFG5bvcz!5}unW<`E$+V1o
zAj%HVeXSyt?y`=WItIL}svZO0RZ-6!G(;E$Lu;Bc8Ct`&SWg*MwGPx;xf@q_KQF|Y
zs6k}86dvNFb0Diq#5h(p1HqS<SSM<o_|8RD&m794!JcS50q>E-Ho6!as)EFESy5dd
zK&XHW6=8N)SEPB6eXhQ>V^zRLMLal?iEQj;>RuLu8B}nOuI>!yRx_&ZQlNnf(#IuI
zizA8QR}g^;8py?{WlxBrQ;c&~YyO=*1n}&RRQ6}7*4$^FrPu%!oUKcd0FLDB1AVE3
zSc)A7d2LvU8QSB4C>zGJxVD<99NUJgnz;BYSRq$1-PdG<{LBOK*w>`MT_UnSf>;Tp
z)c;6;F~z`9!O;6Gk<M4p_<kfv<uDUCA4v`~7dO~~S6;lcdp(k@7FV=jlRv2(L1O2M
zaJNf@?MHI<7}0ecK~AIg%9OP>He*DBoyQd{ZMPnXas-=tKhQAZ;R+h)CC-nU1QiQ$
zKA)82xK`GTtC^_NsX<+0POpe=yT}#tgeVJU-9VZ2&Z&({PN#0;l1t=VgQ(+)G@F|T
z))JpNy$=?dLyjOCr?{@Qf!$^y?CTMX_yP7h1fE^uFRutZyTo5!;lQ|>)BCt0GSFg_
z+K`;@q(HV69xbamYR39%u2U-;zM89UT<t_#QV~~siHE#`U1c%WZw+ev&rm61aK%H`
zQdHpziv5Ma!!>zcB8^pwX|NijW>n0SCD!qZ*|fwuUO_3dnox5@5jbhYzN-i`uoQ3k
zNOC*}dw|QDNXL&PMpL-CgM9UfSQ9R6jm#Pq453RL;}rpqR_iLrqJ5ppfeKQdrTErI
zk|Qi!3>u#$((&2{nj8&%Qqr<y){Wa<>qup5g^RJlt=3dAB8{vjT>RM-m*~eUHq9f!
z$N_7L&ZQz$%14r|!i|q?<RQtvRMml7pZH#CZt#n2<WESlGXmB)Cq5FSV$*5@*4;CO
z!SFmGmPp4dxKNJ-yH*D_73+9KXq}G)sk2_{z8??Bv~mkT%%3F&@|vgds$2DLyxTIB
zV_t=<5#VWwOr~Z`s8xlc5nJlM{Z_=MdX6ZY0y2PAg`)w8RwWZjMWn(ddhv>AUyDKJ
zQWRrbg`@4HrmDuxj!ZTcA<vG0HRG^2B39kdOQPr_iCzjs12?WZSTF!)8XP|mjS%n$
zG2KLmLyCkY&)8}fDR#v$F{(f|LR*ET@JBH*L~UM;ukirc3CLG9DlRHO`w_8XTm?mb
zek9pJZ4U+{TRX{gYg`YO*mx>JW~~a;ZNRc3P^WLps>0m{ey9-PlVIuArn)CuEF_Mb
z)2dwWLAknWy^RA36@B`VWOIPU!NYpe*hLJmv;vI>GepaB**Kt5QKuhC4!FR$VKoYj
z8^Wp_5w;e?rI5rx6|vk`6&Sa;6Bfa7u(Ync2|f@-mkM>#=eZ-+ji}NqZuCpsK@|*!
ztGG}+NLh~v4a5`7kzjO2;+RE7^&=RO%mzOdysaM*{+x{yxE{C@7GY~}G9C%*#q&ZD
zxCV=BND6<GU0O(Gcc$v;ky7XIpirhN!E!BH^dnZQXxmSEB2UG6jo9-aQT)Kra-s3m
zI4yCwS16^9gtZ`e<SK&W&~B|FG(G@xOAhh~ix~C{7&rAhPfB976jQZ;xJ77ujB9Fx
zTCp@4sv<@CaRRbKA-IYl`@n5c)b4exNMXwuxaurXy;snXu0p^*;s{tpa2#Z&M}iFj
z{I4tNnI4E@V5`c-A}oaCAWmIHaD3oqh`1l|{ctlZ<nF5@f54jY;7|z02Y_kOVIA7&
zCnWKUnNJ9F3wk43T1c{sv%o${*n8&sJCX#HGc%x7pjSN-v<wuha|?Mx_daDCS0}EA
za|?N=0)K8HZ>ad^2J*%mz}&97^E(^~582t!M?vp-knG$`RVR?0d#UDz9xkC>ym}lF
z>+0wg@p?X`%q_T%x0bmD*C%*F=LTK}=js%%Rallp-IK-IU$Rs--_YElTg!z1@fKR2
z32djF;_FOcJ4M%D@enoh_2PlZkPVd&n5zlF&yl?pf}aDuG*VU7Iq_kH;O9gObs!^B
z+}u)R=gZxc+3j;AJ&G1Qp9}4w)_SgNj*j2C(40W$$&`8qT<{!JsYk-bIfh*5{5)Ak
zn$<eSyz#NH;vMuOiqyvF3XbQy=@GD&jm`+4PXunCqVzhVoOy!dt6(fEQrT3&@nA8H
zG=Li(jgJV0;#qla0dhP&PlYR}c%7a>0#;XEJ*Q$9R6K7_Cm;tM=~OU-BZ-~Dg~-7^
z`b^)dxy27yYa-l_1gV&iF2o+M`X`M#d!nr=Q~V=p`4em{U<jQeBCAOW8WI#^k>HmE
zkLMIE*^y*J1k6F(IbGl!B%Lz@oINRtVRoT&P;gEKNvI2}&;`!d$PP@BE>}=zPA58F
z`A%^JSj=mpa$)Ng&6tXra0CI`j)=LkJJW%!lQwd?6xd)nI1-M;!q|!6xPk(5x|T9X
z{-^lY>hegjUdI3fSTDR@906-~jIWS2m;<Ny+CZE!UAP)-ch5vLh6<*-lV-Ua?I+Oo
z@<~YL?FB8nDsM0N_JG-5&@#bnFKAg+nb|O*Y%d&p!ECP>d%<jk3_KEylUFofFgqGC
z(}w1OAQm@cK2-E&D&|A=V<s%r?O0(;2fAYqJ0k2Mh&wo!j$?d>xrDmo<IN?2jn6x8
z7>J7RKNk@;rpQ!Wi0TPDKN6&3tQ95VNa8*_moT<p(`Qy~vVGnxC-(d$i0uPYV=W|O
zWS1~@kO|H;Rm(tk1hNtD@JOhS_59;p0?oPlLx9nrXo^5HHjyJajeAm*qbtzt3k@7d
zok9hheW7sz$?my9FGDKUt)f&^1c;dn<{d{6YjkzBYe$Os**DrGMC==1PjGh^d_BS4
z9rN%A5T>+(YH}`uTg29xiegc5cpV9Uk!=&Q-7!A}Z8reqVsNA*8IeXESQavvsvyps
zd0;*eWq*pwZRn4b(L45uIR%J;0VeFIo)o1~J5<kr7E{4A>IZvFdHmH4=qSsnBgrK=
z1$K9SmpO%Y!6`Z?&~BQo%;~q5?9aSl7x5aWEU1noIwZ7<0FJfn`&si{@Q8jpunVy5
zlh&1G=UfaChJ0j--xQ{|<zkr)6S9!8s$3Q!!qne`KA}}#VWdmpzTX=W_Cm%g6J>^o
zRR(Ad2`ilJ?)~Zrr4usNIMHRlUw)#?f;@X=iuLDX#}hI(Aa|e;vAP5zACW7kqvg(T
zd;a@GnhkO`NVk%`F?JW0>`lkmsqdS2yb#@tXaO%GtrWI^K%^mxSctOetzhw_tng<e
zU1zhxBk=6<Q0YjHOkifXqAeU*=Z_kHl^(qWFb((R5V73GR$E>@8!p}<$-|%_5L<{)
zcKZv8W*_p#_Yo-y*^!|eT`d5uRS}eFAZ89xo)ax&Y=#5}VFROc$k2q&57pI(E+1x&
zWM_{XRb;IgyUgoKLvXy0s4AzirM!Q%GSI9_i^L<!wID2WM7i_{W{zYbUp4*)&59kq
z6|Or)r)r4O86viF@-q~T)XeWt?m$g`2rk%$P=!Yn$%O$|2&*HCo&mo+DaxKHs#SwZ
zE<}b=%3tI^(O?0bBf?}?tg9B$7*kOAqipc<TPi-sa`gcZiXr1DZgzyp?8H+2n|;7N
zrGZmDB)Hu*s7gb|25f9pf<LX6Orq{uuml4QwOY6_FJ5OF>}o=kwL||K67(K=<Pfpw
zyeWn#H>C!J^hY#QdSy=rOK+KCgB$nK#rK4Uc%va=(T%M%72UA17{=>Jat9P#YLzQ_
zQK{G}SMuWZr&X-vWoiO~ZGU8)rFV|DHib%8^VQTU%T=@(u%YEM$dfW=99T)PUT=6z
z2>~0$MJv#CL^!~RyF!L}p-rI<wzR4dGn1@;rp_~D0}_mRRRbo+ys80{9p;s%#T!+W
zR8;?BX9@~m*b-Jz;VTyyt}_i0d!G=o=+k@Iu{XTlg^2xdv>K4?2(rynaakM4yF=Fa
ztN2Jz-lQbAI$^a|H@?wS7{-PW79nF3;I&jHZ%8d7wuS(kZQWQ=)A1JH5XCh_Y{SM}
z6=rLV>sO)G8Xi|egolD7L+fdR+Yqbuh>(mX@siUJxjIBJL23vX60#hqR@o%2dqiqI
zA|zw!$U^=|EcZYe$sZX$!B7Lh9-(k<4Z&PfgwBFY|HzQWV4JGz*)vmJojo(v)!8xQ
zm98~n-`SOu@K?6*M}#)<`qUcN?(EbgwZ`Qu8~GzbQ#+E;%%*k^Hj}{u8*DB@#QFz6
zKvVsbAE0TNfPQDA)mCeSzq28U-V)ijM&wI-`PK-0VKILW*tRmw%DJ>>RpngVQ^29+
z;#Nqy=Sa}oqWTwmTUfuN8^Q#L{}ZB$BfmMjLJ;2?F|+LOk0|>>L;Tk8gBaN-2x@a}
z!4f|hYokH3$8U|uTNe4PaV?Kc%~)$(xdRHzhG<A3!A8*wTSNtA>lMkoV75-gJeG11
zFpnf#Zyk7f@Gfv9s9nJnTIVX2$^8+<=qiNXk>u#Y=>7<DXvY*{N7Sj1VF-F-Pjorx
z{kNd3!M@drgU85tKCKf64;m62QTBvafo_;wvZZgGm)2oa)EyaGX@6n9$$Z#LI<KuX
zr*C~^3U9ux^WG}^`UYFW5V3w<TZaz)&TH%F0@xkcS!VV}k{buj>{};#mZAL-p~LNd
zIl|{51kn>d4_yR0(X-6$kI0#g2VWX-ri?Z6nmU-wc2||dOY1etZ=JW+!Mj2yik4Y^
zqr)aAWddjg9Xx`WkVB^WtrI~HT@_$i8zK&+7OM7zzIn!sf;8xmbXn*-yJlOp@iuI_
zD<EX@6EbXZ#%rzVHUJCe6y-ps;d4mPCPqdM83qMW`Hl$5Y?H9R@vci-{bs!C+Qt6H
z%dQFg8!x-E*FPc@&f0m~wH0g7c+)kZe-bzs+UqwXJeI+JGr(h$LiC7o4Vr*~iGWHM
z0<uaM(}lozt+f%jF-0Q<?1-`5x)P9iy2zHl8Lz%(w5V@3*m&Lv47Xv^mB5IrVa|U9
z=!<NPnh{mYr2mL=g~_JB*+JFT)whX>nqeTH6yY;z|1e%`O_v74#n!asjrUq>+V_kX
zTf?Qn@B_An_*l^)n-L$I!U;7aL^fRqjF(%O`yYWbA9icw!b~f;Y!R=vvid)w?22v!
z#*3@rHekHAnpCuHluYOLGD@x!@CcoB&Lf%Tx4|1JZS&jUg|rLR4_-*SQ2pSAv{M6n
zMA^WuvpT~zKPkgr5l!yG^l)Pe5gNd2tE~1LV!3|ymo7{{h=pam-v+R-Z1>yfSn;&X
zZ)y7Tq=?0H74`u6!_Gei@rSX6Q;jw@kw(D{!J9*bl{|Q@4Fmp@%+?9w529jNyq=jp
z2#dQQ{vayu!uW%zSa$twBr@(p*mV#Z_km>27a8`qF*C{0;==2K{9{tpA>;lA$n+5j
z@(<$KF33L;y!NgJE}mSn`fr2awRa?QadhE(*aL+qw<3gkenP~`xEQ<e{or*~#{X^L
zzS^7WcPbTnmcz?x7rr07tJ3(t4PI4c{oh7jRnz$YfdoC%(LM-o6)UvO!j(m>e1p$y
zh*;R<Le{;1YAI7K-zKlBat%15Y<p8+$(CNaDa-!MywtX>Ch$@V=YTeOqiqU7+a}?%
zJOtV#T9%8z5yd{%Xp(Rw+2x2*`aqQHPfh}D5-!6_piP2hxd}A*O^1kE>Ez9}>2@&l
zX4`c2pS;;NT@NO2w&%)~1sNKy`@tlJZhR|flMq@i25k~VH~HkYNfZq)gEmJd*b!pr
zrn|x90;iL~6SBys>%ru$w&AH@@=n`yJD9lB(x;%!b*6j6p*@Lh6;HKIV%uiQf+;C)
zfyOAyA!FCMdgU?DCReXq2HM2!R4xN;IuRc!Q`_X_R9*vZ@^adw@1MM!%6Fj6I3?sc
z@JVB1pl865pff`A6BxHKl}oEtn$x$%duXFMQcIOvNYJyz#oY8f0KSP3;h<QB{m{m+
zc%^MwPGk_`U%buAg`j1;<0oaTy|Sl5{EM(zo&;?HI?I#bNU#NlFF{)b&Q*7SMciC<
z30TC<ici~CqgGWe1q}g+gPfE(d8e(q1T5TOt1bbnvr+OjXp4}yGKog%{D&qwM7g!C
z#KiU90Tw~Ad=1*-@|3edTgb(#xj^ee62mWFgSL3XrL#d>yx_{)pe@{Q<!sQF-ev1l
z<-Fm_;h-TjZji(>C*OJGQqUGcyC#<`a&k4xv!LPS<0H}|z~Tz81pI43A6<p`7w@$2
zEoh4uT1D(_i#J+%7qq2!A^8`ymDk!T%)bboE8htgv9lZu+S0QSTnySGa+Z%lTR_h8
zF=&g=KnnPKMChHa3X99W>UqKW$P1p#BN&-PKhpLn3esi4dGW1!HgH~i<&Dssz#Hxe
z&566K?g~!at++tViM!>Ja74MG$S0w>aJRe?nrmGbwL$9|R|?mv7SK4RVJIl~Psc5`
z02}19Z3?jOIPrAhrNR%SF82X|^h~8_UvOe-`5-jU)hic-=3Kl*4*<>^t^5#<C`Y^K
zvf#YX${C?KZnWj<|DCth!rOuqGb<u;^BKwfCss|-%^-~io|K^sF4Ur%f%EPfz62+k
zP0`K3d2dbkf(J5;s%{3p*kIiZe6hv488`~!y})_FEdxmmyzT`~I9+r%aKh<gQr9`~
zv^)(?(A%73a4bkscFvGOCx8*2jFg+b(B)y5Ori&y?>BNjXq)dhr6UPVRuLB1MAGy>
zKv>@ps3NTTqKiYC(V!?cfIzzF>adBU6-c^mE>5{Bv@~CSQieuUej!~SHj-=s@5Du~
z128svLWaFy6aSW?oV@QUEcFqM6tI<`I@t1BIHF+t-@FoRiv*jOAM;4?*J#X6pM?ja
z(}XRjg$NS;$-d>Za3qIfd+RE&^ZeNvQRGa8orlzx&%%+M0ylgX7>RnzXW>Y)R8~B4
z3GS^cK$`le1ml@Vd2d|-_C%-fK(J@FcIkOyPc&EfKmQmKmb=hgy$-<PVW-E!lVQ3e
z$@XUx_SR{SW^VZ`G&o!AE$pA}7*B{;cOdI6mxUwf(O_H;cJ8cO(Y#xZ{N7~hX>dc?
z3h~|Iqwg(^0Q^|?)`bDSE_>s?@SLFN(Gp$_B1(F+gg1jD$+qxf5V6%`=y)+Wk~qdT
zy%q8U@k-FK6!zwgpu@Lk%Uj_{Mx?Qg9zhOeW0?(8p{d-K&Cf*t{HyY}u=m_Dzw6kg
z_O3{soJG}lj8;*{xz-Bz(Id(x74_WECIa^(X<0JsH4JG%DoWe(IOy2Bw{KOQ8~paI
zF&~jKj9!AvkK{ozR<OH@4E%ZoED;M!rg=S&y^TZVGv7N7$4md;;fVK<AeHUpa_#Ws
z+jKbSpX2t~zEnp7^X*G5Pn5fTX}lKtvQ%s4kAlkJkD@<QHD?>PPu83ecgrWCr~Bh}
zDe*h-$q}(~EHqgH1}SSaaHz=}4U|=1&(I%7!uD-6hd})Vv&!}WryoJA0a$sT0S9>7
za8u}k?zX%XA|MvBpmnuizzNWMjk(lSZN-RpR$I{@g7YKE{`9}_7dd;n`d4fAudCjM
z-ZWLz&>iCP4urk|R-Ys4kz`Xl+C~I^B-yyCLOL2()m(5!Zulwmym)M{8YaYE^s43>
znoI26am(2W@E?eB^ouID82_TGb8p>VP%~ofxR!slEN;_Hq1ObkTW$(Ra^|5t6*{hl
zTb>FX;jeba+j}5dnF~8W%_pTJVdZ)K+-tM$b8_wFDi)fpEjzy>iY~~#;Yea<Sgvvt
z^lo}L96`&1YrzCb*t^$KrxNsTnfdj++i&?d^qMFCPH&u80ErFuS{f{mF0A<X&T1!{
zu~8}EIbztK4jy>kTlxHpn7cPDxJAf)Bv~C1_mPZ9!*}=y;*;m%X$7N2z<ne+TEyGE
zRg9LY;=CYknc#IOqjoqkbTC=$)m3VySYo2ekYK#i#wbK=c|$`9w2vek+mXtKYQ;AA
zlpPVe*K>dgvO83LN5YnOeAcFl8SO>3H$AyXLWHH>KCpCE)eKllPl+RlbuUkeBZ*yl
zud1pUXQry^#HBLN>tI(o5>}j_|JkdkoPh=tY4<iG#Vk3Uwp<~OB$_uj6yHY@<3G0=
zoafAjAzshuv|FwbM-b~(?h#Liiu#CHH&Ezw)s2-konwWCB@4VG35>MiFmVJi{_>dU
zElc1qIr^i6yE*!^c+>BA9XKL34iIw^M)!DT*pndoq+@93r2Fs@IWk4tdWnCdUA<te
zxu$zT(}<uuUsLuZgzk8AITBQyJWNM`G3f=PJy31MP|M}FgU#uP8h?}h8>%}n=rmQF
z=hB`8*%3)HrksrJIv%O^B+l-5$lB9bQ^qWsg4xNH^@Iqk9)wy)!h$;*ES%jtT1=ST
z1I5m+jkyEHP9g0M7%NM>Bgrl_)eRIoo1kt_7(1Kl#>H_Gjw_&(;CRxG?U{+7r99D{
z@biI|36S@JmSt}fkItg*1CGveKOyj_4Cam`XQ1GA=ei5H-Ld3`&~^tc%@MKtxcLno
zwmq(XLx3Bv*&j)yQiHXVsNjL<w4U~Gy`LXvd$6u#1$QJ_-O`VvHtD{PAjWD4H-p-5
z58-Ce|Lq~%40^ylbQA7rVX%jAv*CU>h?~JXcm&wl45)KVGBO-dEb1ZPY?%cci~&-P
z!BQ(aFjOiSU-l5NhS|oJg<Ma*#yy0qt)aQX)z+}V4+3jzXs@ZRhUNlSTaSOU62Q=5
ze2hGzSg=E|+JHlckhP`G>qt;<;!qmOJt2vyH-M}S%W8DhovUgHSes$^bxfOKcb7d}
zho#VwFdHDG4BfgVUL5t6DOmCL5R`_Y(jGw4ARFC7P};EOX!v#n16jDm7?#|i7W+tY
zyoID~Wr#J@i)-KjjyAZYZ`r(c7<wH^<8N}fg`?AA>{F$x#g)%4YDRG0EsM7fQ=e^H
z<>W1So2#H5DYktlu-USQ>j)NmBrFz}LKA8R6Ye&m=H$xVc2Tq8mS{rF1GhvO$Q?=c
zK(HCHfp(fhJrHFGJk*V$-UfAe$Cub9V2!V}EueLpF`hn7Rh)M|<H<ZK8Y{Fta0#@D
z)cN_ijRGPy;cd*|ElamPfJ$ws&{PtABuE8xHUVx}m~Io`9$1L7aO=4ww+V0O(*DeS
zGbD2a1-N5p*v6%t7P+4^5?P~`<Ul94wVNT<fC)MeT+d9<d0@4fpffhiXIoSECz>Yc
z9Ja~Z1fF5Oyp7-)7S7wM&I=HaZxeV1H~EpU^1Q^E!1Gw>LxEEFNOENq^~xi~LQ^rc
zO-Op+0%t{~dK~*EcnyQ_-370~-M;%~k8&mME_6L|wLTjbaYt}k-vzG+E`xom=3Mhf
z!m0sJyVIzq0|)HRgZcv#w(Q_KV8re~)&Ls23t3OX(=K>DvHCiFT8|`qs55_J`E@F`
z`-HpV?n?#Xnka*}K2K8xw<nNhpK33V<^e_z1hFr5L2md~?9PRq{ud{$N^<IU0PfFB
zm{^rvh&v(Y?n2x^rAIQ5&f(YcpYSQ$oroLJ(RLT&o)$4Ou^mp_3%jWnpw6zxtP@8)
zcE~O?4VRiNGq(=6o81Mb;hVF&oL4(scy=e6o--0`8t#Q%P<rBCD5JL{!E6wgp12tH
zrmFL5*af90AZjO+#+_@Y7sCTl_Oc-r>#SGR90;{nRg1@oUR5o^hipX!>@$CWO0k+{
z_jV-Nzlu~e8-V-?Nw!<ZHg2-J3y|ZwySo56uEZY+QfGf?!sBpm+f8sB9&lTBZbuTU
zrwNd!olh2onitk;Bk4|u4&Wm}Dn3k;mONP%w(Q$_I0t^x_;<ETYZ%^zyAijqgsV-M
ze8CrCH-T~}SGLU4da7S`6DEg>W;bGTFjMT*F+32(u(qiYz+JEjlSiPTEz`7<&QSv@
zfBFI-ZGz=10cjH`UwEyMVOodsYd2x=bW?pogcf5>Hl4`}&wsFAJLwTAmWu0OyC{6&
zKG=l97hWxzQ24@gVB^u9+QHo}3SYpm4JaH$C%XxSgA8Ri!En%}90{vlr+-@da53IZ
zpd0}yccT@`k!1S?(^EZ~1z}f7rRr|N>Cn6GCYTQ0>~4VR(B7Uj74&fC-i?cS<=<J!
zMr#Gp7Z7X{L|<?z*-bco0m3%m^u>j!^}e_e3DcqG-mPfoN>%u-!s+mf-<58x9nSMx
zHfh~)gRD;Hup^4r$Re$01gu^Cl`B?G6$(cbtX-W?oJokZE3HmC!eH$x6plDpTLx+!
z90a=xg=ZwJCq%5hM~XG$T3Ly~5e{oto#u##^^s%;0c5K%c)r@~I#ny4Eh-OhJPz$j
zRQ?=Mwmx9FpZwB+BihxLHClJvC95zwUb>#G0F*#$zqsZdA+SCYq@q>A<OqOuBy1<J
zZWYgb$CKI-v1(x5YN|T0ZZ*{ltXmDKR2fv^c3+XorJt{kpEMHLCZTpvjO<E((;g%w
zy9$pZ4%V)M;|PScWjJ;uG2^QMxo;djm53aqZ@WsJji=gO1<1jsva0}jvaReY_mU3g
zmR;c>+7bEc2vBf@zS>ogd;@#R4(#bWkNaJ8e8Svi!xF3~waqR9)1bfEMPPb^)pHl2
zX#~C6MY?K4z1l^0=ZJf?i|{n!UL8rEu!wuLivTrj0(KFehTXs}!qaJ1uwf?lq$Cz-
zS?CgwWmzg0Z-7PcdSfxkMC>`DQ?3v;tSNR8!UoynF3@L#4ssU(>|~65LX?X%NhMDj
z3m;*#c9BXO<djFkssT{TkTwIMvyLdso$+sMI2-u15M9$SrU+f{xEAapfDQYXBVqq=
zbu7|nZ`=!u@bxB=ECSfk8-Z&?%-Tho>J2Dah^==T9_%8|&kh3AEkm#lmeeC*JsWdD
zXgVWh9Rb`mJ7Q(+LO6|JS-a@e-M9%VmE%e@ZKXVs%vw*p(ri7Ev%zv}%h1aTUKmPI
zt~iXJU8usg!llUdYK2R&yvoU@5ilE?bqb1P`_1=OOLMRCy;W`QXD%}^gNdAjN9jq?
zL_w@KBg^ltYIEmwl$uD$x2tAw6F98ELUPuCZ&%GZC60t0w%;5>XlQxv)K7}C>5C;=
zHfpJrhDI$lbD&`a)Xx!}h3%V=+7Knn_hi9m37sSxn(*^T*icxb`JSqLMyg^&CPsCz
z%!x4_Ds^V_2Te|nB->9oZDpZmQ?A5~z7r}N3}hYq)d$mBhQSI^!PIiJrmN46=5XCw
zhQabp(~rlncl++BYGW|Fnzu2QUH#q|%dWcP4(GDwGH{>!PV;L6H@a_<yI5K!`zAC#
zf*vi=mDfPJ?wj@@mItA4f@MPpEZ+pnh7ef36D&Ul6KvmAbysu%VA;Zw+c)8|!Pwh(
zQN@*$p{VMLJ{DEo(942ex9lU)vLQ^CZ^kM$gvs(<RCjK5?pt-|c6cPLx<`uDavjP#
z%)tKd?#hxkJ(mU8k(}1KD^uR|9(PxR^AK=%j+CJ-ORXD`!kz%g=q}rA1F&>oswmc;
zFV%vz=Zm%EA?Pvzdn|)#9Z~#XqBm0&&+N@q_a>S?RSk&cUFKc}R}%N3w&gQ}%iPP-
zY{h-NG6m{zCq6b@CO#6RqAjMz<$$`ITIXn;@Uh`q<8G?iG1#W6^Y5&6W3UaWctmmU
zs&}J%K*)v|BJQ-;whS}kPIeb-si^h5zB~{`e>xJ`7vgGzC)1H+EiDshbHmeuJ5jYE
z3X97W%n+!>y{goTrdE}jEtQtr5H!oZs__kt*Qt!Vx62mnNMiMS<*Vososx^{<{B)l
zn@f<m+ggtl>+S3#VYj71!q;XIxi9<Dx`kTfNCwiGLCs1~=F8Qv1fMRGE;}D)xr)T{
zTaF^(@8rwXuAJDuTmzEFl`q%V7}<6$a_EqrBN`CIAg-ly=U*}lOPy#u!L?<0Ctpxa
zpLDilsthbXT6kG%)_l!Z899nlO&eln`5GFN?3%Bkad9+vp!pt+C3Ln1ZVq3AH9JOn
zsOrR`zD%Q%Sk#xP=AB&>SBoKLmdhIKNMgAxQ|-A17py}Jp23dD;ir@EA9fjqS%eky
zMaXRktL2N3+YnaES7*6+vvq|Kw^aTf0k#b2hL405RkXLMszj)duco>ZqWWsAD-&4o
z2($H(AeEf~+<rndLcmHJ+AhEit-H(m%b?wNg$6&8xR<z$y{ucLm<5n?30rp{&Q*|#
zDLEC7$?){xiXLtVrscBzGCWxL+^ROG&5?j2%kt6VNLY1FzmEi|7-mHkH*gC$Ex(Mx
zw2p)|&q%RWAkyhb#cGn3*O8owmXQNu*e4pkRA4UBDZq^|S*~c}hA>$^FW?4mgHHi&
za69-U;O-s?R+AS*pMu*R)aX8SIwN@2kzi9n@GPHXSh0M!^Ep&;ZkCTv!g9R-`4lY2
z8==EE%)qMQQ=r_+C&f@LW(BR~E%``d+Dt(7d^7baIF4{yuBhW?IB#55Uxv3=pIzkw
znoi*H;3M%VG>%wWM*=00A(oaa7`fR=X^G<j+9$9$o~V5ai(Ar0x<ZW`p1NJ8Tn73U
zpF+_H+UhjuI)cPSQ$X6V-ll*wB4POyjyA42;b=VMKaQZ|mSi?Q1*8!P>qt;HE`d`x
z8q_(S+zk&zF}OoOIs#$2LX#T;VYv*y41uqFz^3{!1NIzSRVDTuu1;bdDk!;uOUQ@d
zw<T?)58-c+68RAPMzAa&gx`on?88-e9>9+e<~S`89!D@OA4~P(aybOYVSREWcnLMc
z({jc)w=`mL*_IjXTs{({VoMmp<AxAbN5q<O*BnzdV`VDJxgoli%dpH0-_I4M++YIa
zvK+It67nI84nrazg6Lq_`V7=SGFHtHB#(yZ4h~)~A420WigHlMJSiF>U>&$O4nrzO
zT6i2`w45emHgMVXAwZtt!jFLU0*pp5azo54mwlMwmp&As#bAQwiZpH@bn_v^4c0dw
zLfqhn^ECW<QW9;cYMfzMg}4#X-4(FhFrtn)WapScU@RY1wVz^zxAB#H5O3o{x?-5y
zfC|N7GiI<P^dZEZ#)dv<dSWoa@ljMQ)~<<F<%mun8OYo)7u~ceV7|Hmr+=or+g6c?
zp5=;TZm`L8nUERmHr<5O2cWJw3ysE`^GVNOAL=HcK7e!;`us>@xyXRbuz9%2klV25
zxB<H(oR*ug`^dkt8eA)7D`o@3<%&;k;GT4vhgs~^ZUW)h&fNsU5k2cj@&YhxB(U^h
z2kb@&4u(xPL2%G;x(R|ac$S+mc(QrA!j~HuKiveuanQLDapNrXG|+q?I;C{g)X*QT
zW*o6@!r&l3JrYpL8e(O+5rl(B)fKMXK(^{(ZDtuu%T0)Ub`HKEIbepHAUUFGxe1XY
znwB%<xdl{llb418&3r^i#SUT8fy3<GO{g4(@orW1rvIrcFuK9^#${+`z+Fdz-3Wlr
z7316{_%>a}Wfl$tZo=;HDR3*VVzSAB-9i29H^jMRTrHOwnIWu}cLDVYFx#aEpTM$U
zU3^mHnJs>RWvGbf2G0to5t+g9!n=U_j0Z38!s_5z_MTnARZ<3GhIm-sb>x1oDBfkt
zZMegD7v_dTi+5t~pr7_G)Qun^-if*&Lxe1seVBp9+PhFUxURhmb+5cOcA@SC?nm!L
z-H4Lqig9kZ-8l@z4A;MtX4RP@vW3@?GkUp!Kip*wW?&ij4ji6$-IHWXI~yh-jyto<
zUd(W-_AVR_S1j+q;mhLR+?x?N%e$1~2%O~#gKqHla+!-6SlPWR$bltwyZ5Gwfowa_
zI`j|Th1OF=;fjN9Yp{z#>+p#4F0{TT+DEjWZ1>)U!@-E}y-0b1uvv}}<_7JK%ihbN
z|2dMzpA2Ndo2tR#&zm&b@CiH;R_>9)K7$Yg-Zo2hZ1YW^J7Z#b6X=GP%w^7HP_?;Y
zj~hZMJRT-p=ARYSgq0Bz%bTz=Vl#LXR))&Y;g$8ID84GAms@HLT_#@!#o|X2DLha#
zVP(gQzc*oJIJ0^aRt|4hS9EiOL#)f(%iu=)k;KP?<%_qWdhjsVhN{5|QzY{vnaIT_
ztJLdy6S#)z*PFmK!e}`L0MCF5V}2xO_mef4!TZ>o;5CAec$2alF|@o1UptQHj|j=L
z5}HnAghFu|gBg6QkAM~Df@}SD4;RG<YHo;^<xTh+@m`LE4FiglUDuJsG1vsJ@$BGD
z@EResyiuWz#|u}Ga)W>S<4x-p0ke*Tbz#Xhf$0dE<xOxJL9>n|?HCQAbX?KP4G%aD
z(=Kz|_?qB!zWI0~oPG>%N6ygX27UpTA(tV*q1UZq@LE{6I*_l0RS+6aS+02HhNmvC
zLeO{)I}%j2VPWPK5IQ4rd6lXg4{u(Dpb?SF753af@8ESwO#lvvBSPi7Mv4^!s8--<
z#CY;5JiWmt=~bW_@uFPDUxr6auk@xgMBH-4FSiZ<JEy&u?fyv!WFx?qSApyeyovDT
zhUi*e<@aa^ujO^9%vcjuI2&)sUWKy}UdtK4{0UJEw-z~qXL%*6M(8ZBrh-ofLFx@=
zBbPmwZCu$DRNN5j%EPM5K)&KtSa@SuRk<n}LRxth7)C@ZXVh`qD-zgOU`+6lAeEZP
zDk!{hf2)GR8~3*=D4aG6uAt;by9Squmx1f%BS9)VQ&dm9OH^5qfKA71xt-&h6Htx<
z1(P>dpkOjgJU$Yn@+ej4aZB<bmwlLlU&sq#@&E~u7sBL$pjpomWkmzjMIQ-Lr%;~8
zCmnq$0LcU4v%EN8^o}T2d2v+?>{(nDW4RSqy|@+@rqDrR>48{Tu0Z4ip|V`YU?W0h
zopf#t1Cg@4OsWb70%dub>_JE4rkb1hQ^sHe7EoRk<#f;{rcBk93$P3|7z?lr)`T0M
zVw4|Af(96a9YJ<!sP4G&m7y-;LRXBX0$dioR}C<kxx$AJG}C4NHP9C?gv$f{^&ruS
zKE~y(bTtK+x6;)ZT;3Fid?5an7Xs!{K#S<5sqVbem8Pn3r7I1?003H=>IVMIS@1xV
zy(D5D<rGm>G0ba9RW-3POGPDoFH}hK0h>oJ0N5ib^t==`9j^?fs8Bow7A^0ARq2Hg
zdmzY_7eMUsS;r@VhGU(tO>{jN<Z3CD`M_qeWF$6VLAo|I-2;S!Ym-l8RB)rLy;*gx
z#<jPqkM1soGauOhmh8j^_Sv=N_&8v4yHHO6%(a)AlHlt|*p!?liy_BHO~=3`JFp|k
ziWgENGE6liFL`TEjX@qei(wIu$Rf#F4J{|e9xz`1NRY}w9IC_ua;-g7iJ>n;y&LEY
z)z<?=plc6x1|EhV5t7+bQ?WBs_zDvZH5EBA!bYv|0C(xyrdlT2Z%D;w=<3Ww(*dVP
zh4x|Xu9|ZLUAwF1h0b&h+5t*ycU7BEYNY|$15r*s!tPN$QmEL`^rkW$O(zB))iLzM
z-~)K_|8MPUdUn~3<M#6_&Qe-P;deK;0b&EmBCxHjf^1^g0fMWA9T@rhdDvZ5oO7l7
z>iQ@WAidM)nHiEZ<a9Tyt4v~^6F#R=%X7j{HEDOw(5|wr(uxV^)^^pMHX2)Xr<{By
z+0L2u4`In<`b-p!NyYOR22PqdUN{A7N;vRgz?~Z+MWZt3M5JJXgH4o{n6$)aGANtC
zV8;+s#a-)u%T%I4mvg2%)j4EaFelyB7|cmYcRmvZG$wf1M3Ie2%yUK=j=8D5`4urY
z+_`6V#N2f6bQw)L<+BZRlJ4|O&TEq#=tT7Sm@iy7-BA-FY~qAmQ6OPu68xM&&TUXb
zK3_FRR+;oZClsqp0I~^^?_=Rz7TOAb`<W?MWj=MMg$FX!`i18)G;X<WnLuPSGYC(Z
zcz25<-Z>XXqaNr)WtvG4bcRxuT{X}NYIPHeY(j&|B;YxrKxKglo9#5JsRgK(H*adj
z#$6kmk$$BK5jIiU_p#t8UOv%yPvnlw>3~lpn9S*b&&)xYBt9q7R0cHIlcpR*o{?_^
z9q`#}9Pu6%<5zSK@OPWAU$f_WV-gjgS;lEbe|n<Q(<I0_Q4IQ+$)QHYsG0m}l$Dz0
zDgE=8<}{QT%*enwq1RxN?3@sxGAVXWh&-4CJ7;Q8nbbO;iA1Rh4mKf6Wt8VUhM3f5
zy47(tP0F0JgS5h=%sC-mVS<Rwo~Q6G6Fpk$<3x`Z@)#4zWHUM3nQt~>$R={q$HLnz
zJfQslCr#NSdECf<8)Z6YXik~r%_nNC4G^-~QH*3Jf4f^8@wSH1r?=e=jc4|HqGa5X
zApP|4AHMzFb6&>sY1QZLwKhMO_{3i2GiCe7Ir;m){q`^4>bLUwZ~pH;{_z3(oFy6i
zAHVsz2S0*fbT%QP09rNSkN}yrrH=t9AWb|^pr$mTZ1A}>Q5*paZc^9V0JfUweE^&{
ziOXfcY=T69!PG=fQxOhY%Aq}BI&Qv6W~_p5(<TFg3M9YHs^5guXd)Lma?`nNYlpT1
zes0?Ito3u%A$5EDlafQK71;~ZzFb9}o@rmJf*9Y#Q&4Nh)+YI#+K??W$<$PSTD8Ga
zkvg?bS$jY-P4($D!IIX6Ypo#cvaa@YjA#R*q{cpjDZyRA{A8*Kekw}*O}W~dATd)$
zw4yV{^3w`hA(QSv9p`0G&aYzA)Kp?wK>=c7z^@>dF)`BD0g#x1M!teU#YEy>0ZlNa
zH|oS-Dq&Co^RQxASSpw}OeI<s0yn10sEQZYibfo;CM)t5Yit`^k>vV<F1_k(DmcoP
z2#jlPQ!YgaPX!2YDIlnjs8}kxsCNFH;b+CB)>5%SHN2loEU-2Ae3rOYE4~9un&uT`
z`YSNy70Bx4T@w(g{w0WYMUs7q;j*ICbH#_N!u4BXf~*eu>80hhZW8Uwm#G`#<;+A>
zBq2i)9G%=Kj!XS*T<Uw3?39#G;%*aZbfM&jkuknNml=y-E9AmAk((E)NeBzuG8gm~
z|1D%?&kfqV79|Q6KdP-#^<znPnyla=y1V+yq|W#$rHl9Xil|jeqM{v_D(~cr*BXa-
zx-QmojOUfb<rq&or>&7(|B5>{4DoE-MtSLtY9u<x_$5II#lBqnt|;bsDR**^heR$q
z26=FAsCDVOU6Dws8y0nMaF9E*BS(@iNBQcXNp7z*S<nUtxhrqph9s{<sXZhpr59py
zl%Y$N15C-Lr%ev9_9@%s0ADepi2=U4LQ|4C_f?Pxm52-4x@t6wgIlHVAiW}%!?#8C
z>Z^6KIJQ@xM9Ml!<zLkrN^BUS`M09R)oc-~y>Vn!6x@shTj)<7O^=>B7!X?Es1}AL
z&8a=5^|(35R+Rk^hIo=!KL;VpjJ6U~4GZMn^h_a2kc{lGv}8rcyMP2p(39uAu~cuR
zD8xg53H?z6>v=_hs<uMbo|NZ`E<19g+f|)g$Uv-uSR`XXqMU5hMq1)H0^N$KaJ!PT
zR&0VOL)-GJdmSW)6$wBkZ>q|3$pf4R7)4WUIuaZ^HKD*;8;2wm#VAUZyJJgvOB7o?
zs?0Bey!1&b%93YoQarM>JBd5xT8d0_GVtlZkZkJY{S-`*Nq={VJ28^d!|i~I@7X|I
zhp{BI@ew28n@<ijD}$e(KFAk#Sr$QrPPE(eBBoOn^~8w2*uj!)i%eP=P_1o!!VB14
zJ)cW_PuUofc8Qh=D$=`)XCaj4cGq&>fi~Y##Or{Q?IvEYwMd5pYAy1i1Th5#>Nf?>
zI=-PVE|(_a6Ff%|)`;h1iaCU@KSIu38TN`DMY2pC;rrGOXZIFN669ha$#_+rxu`Ql
zNSa*phn9fXaPc3I*kprrQFH+@kVVuv@aNv;_M{xR#p*eZrHWvAvqD&m;mF$i){Z&%
z(q5I)EH<4&zp4gXbwveLC%04=yJo%x1IDJFZwVa^>@Yax15Vj$)@SBsXzi-2#LheX
zd{>5RR6ydDOd8nBch^oV!Y7ZlZ3H8Zlb3uzbIwi7h_{ALFqurgxd~?ieL**Yxm2`O
zRhf>!>0MdWRItNZ6jnO~&PU}tLaBFdEU$pC06*xW)Exjn`qDOYlyc~npd5{wf!Kpr
zkpt-|vaBF*@2ot)5YAhOf*}+O=|dnpcgMlO=;GQOlUUIUU<PiQSi=dxu`6aCpyYEA
zGY$kyJ_Nmkf@I)Q3t^`KR41$x!zcyYf!ZXOw>A(ixdP~c$MiEaVS?HC$sTa*T@+~p
z*&7#G8DVnJw>)nGN-1A3F_0krDOl@`kE*~S5qODjx>MdTF+>UU5kw~eBEX$HhVu<7
zIp_l6G&jcbd)P(-8-y5{7aLKCTZrtaONC4r1JS=s5LURTQYOTcylAHjB2bTul4O#I
zp=etNj0hBVn&5qL@o3D#y_Ah2`5EQ;wv}uIIK;L#&>_rVTX#;tj8WMJ8%()9#I4JX
z4a2G|bd8Oa#vKsuh`cr(A|0$?Wg<3u=l_{v*G@MSR8O{>c|Yv@T=9u_7Mb}_=4!Do
z(y>2b+R+3Nq{T>P=5S0u;JD8p{qv1npFiy5{;&FV;xHSA%pqLoSK=^NiC5wfsYNCZ
znMHZ!4f83y@`ibe@`n7}C~wHG&CMI~ZG7bo^ZDPrVLYf;+7LMmr41F#Gi}H<|D85u
zuJNV~kw>^`!^~+>1<&Nzy|aeM<wVwy-<o&U5VrwAf@S_I+NP`_cSDpl9Nd?<Swrq1
zAZr+TM0f=^Yq*qJWY%yhv&gjJ_<7neBZ}vpHdJ<rX~UpwWX_QL3^!+}yi&)=n<Q_Q
zGgNv<Im52(9!9fO<pj@FOO}h=l;PG1Oc^qva8rg#r9uJT>Qq`(NyDzx9tN}WHB{2D
z(zm`z!<`@Bn=`z5Mdl3k0F*P#U4xr3)bOv6X*4c~Oc<J|hL|uk3Bf60=*l26Uuak}
zZ@%zm_Rha6nW=ms>Qay{jFjR#TlhpuF@M2ip^~^t7Q(~7`9f~T+;rjKQg`!(tea83
z(7BnfoT0RMkTX0vMf#ktoT0{>IYWdLuasd|GLYixu^pKgLbgRaf3J+8Wbxh^LnH+<
zWtbbt&pTsCm-dx0lq8}uhRjjC6NU&yze^b6Qa549jO9CFh*ZW+7!KvF-U&lq>zy#n
ztjIfIi0sWx4kG#cU3M_r@J<fm;;-Z&5+Co}Aa-=WOAg{^N)F=il^kT+@0}Y&o0J@+
z1oh1ga)jThL0su(2Bq2XN)1Y3_@)Mxlf9`yiD%x-U{i+ZrUo^{N)0MRR(cQ`i8nbI
zGNlt5qP2*R^=1a8=zTMTN(kS?;1#TICks}o3$NUu#8+=_P|4thp%pS1xj_i|GGF-8
z->t~#DLE*~T9f9bW)x{MBJr0`>ShO}vUszDSM-=;D}K2~S1NLU7?_(Oq)INu`J`-#
z{NR>ziR|F>l5kXdP?D-j5Av0Z?4U%0l^iVG7E*T5={hhwC|0DK9lY9+S40lM2Q!4?
zsa1whJkZJziV~6;Lb;ZYGKAW|zga?wYh7V0q!^SWR66P=2{QwDg_V%YK!Q+`M@kYd
z(Vi<wxVT_tk}w*f1YuWBkqJU^>M}tnB3mU0r<Bo{Ae^FjMS_r`L`)AV*{SrPvh6oL
z$aU?e2SuyP^q{JTl_1Ot`tuBx9~8@^@`G0jh514H2{%6|KkeoRFQ-5AgOT~2?M-E`
z+@Lfelp5scL#e?loWRteRK=7V6k#!PgIAS@xj_|c-Q1w)bD0|yS+$abgE<#u2w%j_
z%nyp5RS7~8q%uFKEe|9JpGXIa${7hl(dsHe$W)~AgCd%a{9prXshE02mCo#7p@zXt
z4&r4|a?q41Ms^SspWoi;!ApIb=|K@sD?KP)_npN@n*iaP9Tc&-vV$sQQ+AMrB}xv;
zQF|u`^Cveoh!llVgQ_BAYLHxX&v&Uo5|?Fa5S(N;Gsw*0%?vVEcr%0KExVaP(z|UD
zY>}Ud*}<PD2g#FglY`&BOAL~!=_Ur5D!hq75-8!j<0kqNB?kAOCI-b+#N?outzOAN
zU5E)nB_>}9Lh@{6f)Jyk1mRYdw^D@m^AzEw*kFoKgmteJVWf0^`gT)<<P5kuLQ)Sf
zM@XIoWC$}|sPy3alk}hp{%>~h7Tq&D$P8i*<@2s4XNFMKq{<Mg6igYyNX@>ogDQ1p
zc2LEJ$_|p&PRYS{QEem#;m$p;<e&<_l^j%gD073Xbz^Q2CCm=5$Xi$XP^m#y!`*s5
zmJTvG$i$$7$?$n6231AIyr6RL$_t8j1bIORt7VjY-P$8oFfcF3teMh+bmN&8bnJj2
zCzypRxAMcXT;yj-K|x4KC|dZoF)6rJJEW|j>VlLN<cC&S!J8%|?tBOvsI;KcbuF>p
zUEt}=3(|?dc|lha5Fed4KACwz<x7<pWLE0t1yuplLAz}byH!?DV4Is4<Ywp13o;**
zxxvq8=Cgo)`<%EAobdC<9Q70B|H|B8K|U}yKE1v{hQP^cSp+!9tTIePX26UUHDL2M
ztGHg`I61da%zV?4V9GH`ggQ{RMDD}eKL!9B38-ZZ<V477+scWMRg#lQSA0ty@K}yE
zz(}_Ek#RsbZE^KUu(d6EfPiBggh7FCvPBOCc<y7!bOd-qZP9)5`OdmB4NE96zMDpx
zxa8`8!XU`!>4elkLDz2*1O;2aX)6l}8B5}eCoPf40(acE0M);bm<nD5l{$VN|8DUo
zq9M?_+TunA0BI&hIp~AG5U9Y;N@~<I>1<RQ{RX~&gU%?55?;AzU~Q>13U|y>)d%V8
zm^O<u)OQ@@oJM7{37G(r|1cE%B5|CHQ3N>tZ~i;WHV$mol^~Bsa~(#h$1%ja0Pu({
z>ZC+6&K4a+kPn-P=irH*3_H^2EaDRF9C(gjN%*YclF;ZYOWz6iT{t6O(X5}bMdS@C
zY)q_kD8ey`jG|7*q%oTN%THKv+ej;GHx%pdYil4cehla<R{SOCO9teDLN544&ONR=
z8#&~at4>xnnMm!3@Cnp%HggErjIII<fA=Q<hF?t92W|H`MBoU803%sl>I1|vE;+N+
zCI5~FN{kdA=I6ElfnqSJk?!?IRp0Fr^Z+w=Zhqo+%-zWaWCPhwtx|k01DIWK$=pv#
zPkQG!?Xk%P1$BBh`RPTRVL?h4|3c3fUuT;v?c0R(O35^epiNYB$Z}gS%>mwUH+xWc
zXk?yyzGbnZ3DStz$3!xRl1H0M8%VKuP5R;+?4KXYx7bdKtt4c{LCbHGt3(BLKen4-
z8Q6fzt%8EmE-9NHOKf5Z?EKoaLUtXc&nB(YlfTQpak;42C9tW)KH@@y)@g;DfJyJP
zmdftk?XbKJwlN?nU_oP7Atzu05LCzsSkl-%Y03UEPg8S0!$f0Ok*PWs-Uh{D*lLM!
z!hC&g%VEMw{Io)I;*I!69VakZwTveY*k8D3QcJCn88ETo9ZPmeIP$`cNGYh+teZCJ
zr&eSn-+P8pGKOnnZ#a4G9+<MF$XC>|;(%wPjB^%^8p=3l(W8RG+-qMFRh+YEWKn`S
z=wsB7MX@0eIz$I-C{V1(2^wyknX=bjC$_n42u=?102|C9*8=itLp!khCGFB0n`f`>
z(t_ejaMPXRY=oSJN<4rF>MGO(-nAN8`Zcr#%z|g+*q$_HYqd88set!>Z7%yZmhOf6
z%Aw++nvus)X$I5+Y@l?grdYst)g$m`mEfzD{_N0_kmM9Lv?PG!!p7i*QG+RNyUM!g
z0e>NOoZ}ELHugA8G4-)z>*x<uFml+CW?BW#*TijClhwn7MXZnuFz&llhy|FK?P_He
z*l4;toLlkR)jGc`p+PhwYP%XtCN{KL2d<O%b~%bL2d;<SR6QURU~)gG*36jM(7eTd
zu}LtsVi&}eT)q4BRX1h<=BOHP%WZqy8J_NIBOjjat3-%XQ3=$_sC00OSI$P2SYY4A
zBGX$F&VA4Uyp89@tg8qDk^{$bi<6>57gT`syon93*8F#Xs45f%j7)bGiUKC4yPE7k
zCZ@Z};%H`LKCc(6qotWzQ61g2mkyl)>paTFtA?b(zp}2yrJ<a&tD33hDa1Y?Ozpxc
z2t;8I4zn{$cS%S0g{Xk1E6LRg&L`^`csv!fP$o*f%6e;2>QyEYM5$MyIbhmoj0<Id
zrtaS3h<8Q}C<yh=aTc3hv`1%Y88^hSqheBAt%<fZiLO>C6<8k{1te0s=rJpcsb4sf
z8O3P4$i&E^Pz&{B*1HB}W&}sI)eBA0ryeQ;#HOSru_}DP@LhY;<UtXIQB3t1^8M3-
z!Mf;9089>>kPoR$@PvssMgS_T;H%t@gN+FE!e$^%@EBS5YHakHNcSpmh1QE6Dm+|p
z?o|-n+1+2M*jF)<?$zYUGjZ-!<f(zzVR5xIR%?`_JYiw~5Q$1-wMGN1ZTy`jfQ%U`
zx?s{ueU}#U3UFYtyIpe>tTAk;7&~iR2A+!XwZ>FL#WOJJt{zLam9P_n=bHSA4z8D|
zY=j|RrDnQ0D<6qjLcA&7zKR#|W62I?a4D2$?eJEm!CE0NY}(eU5Ggnou!&Zn>MdaK
zwU6&mQt(xqraWt{o2Gpq7hJ`@478NfJm<SL1qxUbtjTqN-~bR=4@}wETj>dhRjhoq
zuQ=im!D9_VzH^kZoGAG!s79>`f5Sp*aq?BD5LoNF35b7Q;4tFHRR4%|-K5D{vF@8R
zSu4H`k4coZ;tOI8!9veVa3JC2irTLNO=3;DR284LgHz+3!A5eCYx#jRlKoZ45*R))
z=OfrLjm7_WEG<vsIBX%}IN%6g8~;5&f+GK`@BxflqV?k;n0Wsx*mDiMe-(%rYr-m2
zY%-ac|0?v~t!aTty#te`YlW170bue}Fan#H04rF7j|D}-nAtBtUyk3qPB_Yjwd}y@
zGZ6z;$Qu|~04uhNOf-OXWGI>}fDbGQ0MsHg2=_B}2#&K@{VJHBE%DcRp%I6?2qv!>
z{VEC;kA=-epjqWV3<jEYp$8dez95VUGpkk=#0VA=uN5JL)k!E*4PgVT%29xY+oS|r
z!PIS1f~^oXFv`9@VS0fl@uO_N5UtqIv&twX_ZO`Wy>p;YGfBTzC>xlhUn|19cd<93
z*s5SAqC~4I!>b4+jS{dGNURsM6V&LpVjPZhWgzoZXc?GD2ahHDq_t(_d=`+tg6{oT
zcqazGsu`+~GcYj`R=~nuNYmIZJ;&@e+~rV{&Ej-;%aW6=8T(t!EM|q6!5gev1z*j9
znJ7^=@dnn|(KS_OR^&B~1x-Qf<5=(nkRP!k0{uF{H$>z^%`y@bo!~LV_(E>>9LGXX
zl%7b9gC|UlzlkmtZi3X=18U1MfB3$Vnyn~jITj>dk7<Shj{~|0$HE&U7%t>PfGolV
z^*(hHk*n1rbrDPigB2BnMjTs(EP|<`wNA#u#q<E+LyMNM&b%szA3Hlmgcwk~0KoWx
zDPhS3vsBdn91Hu6kho|`L9WwMqV`Ek^yv~HAS8|g+=_In6(vF;>|rVZsgvPw(JC|T
zVxN)GH4zk6q<oEvwKY``4mw)hgH!#YVZa0~NN{Eyz&T{!FrCZbRZ)NXLS3UW^kczM
zJ_xxjbH@=ohNw5$9iO!1s4JTZT$D+?wn8G|1?|S>4zi_ZfnC_&0ej&&o;auLDhnr(
zQUbHRD0{i0bINysa>ZB$T|o<AqBE?EEE!lq79!tL6=h(X#kA#Kfw?;tc9Cosc-#<4
zFcw=sVanDrSXn*!F#vz(Jig%eOc}4u^<<$Ib4k#)rbxotN?br@X>EBMA$PDSO<RGg
z0cQSzDKO?6o&(ek)>cviTYGCO!HHtN1GJApc@myq5_^x8D3zz)1RoQvLofpQs&mZN
zuJkDu2@Y#2B7^~N7z7TM_z6`9Ain_m25W0mvqIWy1!G~&4ck{$0JePBR(OG3;Y&wS
zQ>x&J@&R^nqb<b5*4Vy&R~TS}dqKta9B0MBxMV3Aey*)=K2#5ubZt)|LpD&`4_45?
zOG*Op)sk#&g|5M?zM*FO^Z|#o+#=572~##vA8=?EtgR0?R11y;7tRB`AO?MnCDGbr
z%D3oNR<w9GIXzRf;B$<FY}Va1cyYVvglv`EdgvA0T8)uZFu31fqx5M<`RkJKY=vII
zlJIOb7HVvb85ZUxy1@!L#A8t%2~OhOV|8CFtgDb+L><WkQ}j^q=!$yXrRuv1Zi3~S
zjF--aIeu`5-GUU*i!Il8IQd?d>nn_MjupzX)gW!YRJwfYUKHkoQ0-Obk~D0~mCgfG
z+p}Ez1i)V}=RN^yOO|V&0KoQR;V&jm;hX`h&2nuMK-6HVw7Pm>!A%~awU~&>l=Fmv
zRXQb`&o3tA2bRl?4*b!(WG6o*$HEVWSJdoq%6VRaq(B+Etso7o&>}b`KO_YLxxf;)
zMFre*sUW<j7Qwm%K+qys<QBXIM`HUurWu4q#$RO9^)-a{zyipsqE28*G`2cuRF^B$
z@0>4kx?e;{ELs}bT-6ofsXfPp_D&4-WluT}e+kA~!3VNT={wLht$aPQkLkB9Q4H1u
z4K5K3R`6af5e!yH5-bxmpe8JLiD<B59xUUR6e0ynJcAXqoJ%}|PX%}96477{de0@*
z*$M*CV1>e+E>D#1l;0hdDO61Ug`(J+A_Yq_v=!RbODuyGsJvy8&Z!VGSfU!NsPR~~
zc<=mY{EhzIs<x0YSf=TY^>B$$uwv0%lBKO!SeImJD<upTNCj(37%Wi=R?vAJ3+@C7
zgC!Z-3TWc7@Qn```7*h?kVjwEUngbrG{f=1I+kopW8?Hu&2QeKplsd!a{$j3^uCJ<
zuoe8j$50c8T0s)LgcGbNm06}u_Jrgt;RKIi<0K%;PgP%zN>v93Mn$eEJd<N#P2a#X
zF84w+4lkKlc7bzq!~YZfuY$9Ag<Ncu5}vNDrK!2o_gj~H48EW6eidcwYw?4a82q*F
zUOZg9wKk5TbCQOw;IKXx-X^!K)>5#$?TJI)HT}r7G$R4<U5o!7JzLsgLrqjI`!1zf
zd!44jUuE^zb$GU;)N9|T>Zt3=H}QcjtGG6n-EhR?knfwLxNzSG9fw+AH^wY%d|@`~
z|L6=MOb7!<W3z91)*D1v*CX02Y?DjW5T=CbGRbADSn?1i&nmfF?-eZ)1#?R>mo%}O
zw4&X@5w`+r$XAJLL!1{Tl*l0x3=_%hSO?3qnuzkITHa7u2X~{P%H-D1HgIc&1yyM!
zL4d*3$G&w8u;0R078r`VswKSp#qie(GI?P`As>_u!h|*qyeF=b$B6x3MZK*ImjBWF
zXb?9D3!6Ss=i79li9$*FA+3OVJ#4)EMAI+t-{ezhYWZTz8=DYP=O2Sg1EGTuCJxKu
zQ>eQ5;&V{#D5Vg>hO4t`xvGE0-dr|9Lk*;SkXG=E#8aH|W4yn_54FOX87w=k<h+#s
z(ZFwXDHflwWjE|j14lPZ1awH}eOFh#vm00Vz9BLAvC$1_kV*&>%BD9<wCQ%VTJrET
z{)uB&U(@Yq5K0LXnHUS+Ub!L-1rDtBeqcifRkB%G&?_dj28Dz$k&3aRgC;&mh$I{v
z4$(Og5JG7tOn7dPqe)Y4MYW1!-o3HITnNDP5*EBAwXwhHMm}lF=_+@nr78m{F=5#}
zks~m8c{v{qS^l))mIK#PkvR4bl3f#*pO`<^6U@{A26|V|S58=C=B;5*<Ct)Wk!z~#
zhJHfWK(@K^2vxrjPzV#pa<OYUgiqSgHI+JpH}RNo_<eOhL=?i39eo<MjKY>bvftw*
zzLUmI6upziKJe@Jxsc~EN6^^|6g=1OsRdv{7mDTt1bD*626*;ksZ<@CaA88%Hu(p(
z#t~4VuyG(+t-Vy~AG?HMU=ubboa!7}sw~8%E(gNK8z{%;u$pF{<@vP63BAa2*$R8O
zRPUY}q(P@ZzJtOZih}^MYhmKmE2$|(#1Mssag3LuRd&a42)c#!x-fdO-ejz~cC1Us
z+H&ns8AEHFy-TbJQ6C#D5LnV7sSqZ%sIv*#;(_bxTigaF7C611wB^iN{1!u0AuJq6
z&SaGw98w6p7+q7aaW1RupaH)SCbnW`S1!{m**a8v(148y6WcI3nxeRX>Oz=!zlBaq
zDy%_xA#A+kVyF2Thf-s(Ww3{qhmJ2zGxo0PZpPl}yWVn|U(yW#R>H*Iy{I|ZJ7e$i
zD$br2y-kju6&8md6P{FIH^>vQ^r3IT+;Is%=qOLnM6^w>QS}84qMc#F>}{Nule={-
zu}Q%-j0ZvhQ}Pez{Xt9~CX#>@5{hv0LZu-rym~!gcvbU%j@j_c3mikP%BnLsrkL;4
zv_FRU{Dp}Z<`kUrw>zewgzOvOXko&o@TmzCFV(*VPYRpZu}-O!pmn;<lC}ru$@A^S
zu+rf+UqWUmG#pbL(qmTrZi8Y&n7F!hPVlKY-#MEn=Ql8aVZl4n<K`p(WVChJULevC
zCXNps;VD16lh<R)&+c%Jr+n&8=lC+mbWS~i_gl9-#Al+L+Qbd827qUnzyM<$YWdxr
z;qAmnxEmtCS#^5`w-mDvb{TX|AL~vJdTK&;=SPB2|6`hYjBjP97cIDd>vW=p_ix=9
z*$Cg?AWeNtI0WI1KGvNxnY#83BG^x|aiawr)H#=eM@%_LPPD;@cW7>p!jHVF1CA|M
zJ4q@W(@X<Ke9)_g=>0L^6F-=zXoEiW;QSwSsa0oiOfe@fS<t9lT~ut)1{Z;$kN3bL
zFfPMS!^0bf!-yV&b%@u_V0vf)7>ykfY4%_&eaVUv^!}s`Pi`=t9t(%r53LEn*M}(|
z+#svem~#6^$HY}Z!7({cWCOSgjEO@$qD!7MGLTk5!6iHz<M%uZ9pi4nG2szir++Zo
zR_Q?-h_+RF&<0)e(Q$G5<wIZhvGR}uM#p?~9HI|eN5;x7=rcc--YR|62P5hsdhUVn
zc{Chh+__{7M$V(&ai?28ux1Q8<wI-6z*Vqb4Eoyx3&GO{C;pJ<J~;6QJomxa`9)d9
z*m*#DGi})kIqrk8bJt=p7&~_^27|G47n@p}C6CdKNx!=5Gd~$ScRA^kuJ(&Y3oBgM
zmd=c6rz(Lq>1(S_piR#6?&3k4nCPktXp^CH=OOy0rC>62?zxfhgbDo>&l3-MbGp^t
zaELx=6_^d5hpu%1Wol`{WyiN53!8bsF(e|tO$N+e-ugsv+?70=bg3nD-zHt^%Q`mc
zQFraAx0(KP*Cd?upF8)@+vKF9mQ0%~kFpO>o1An&@3+ZVSn&O0!hlJ8U@{a=8nk#p
zC*om&`rBkcEYbVJX@<^0OJJs>3|x0SL3+wvKKK;tn$l~No^sb`e$rd+g0{5Du$Z{~
zV;MXV-x!p?9up3;BZY;gZ89S6%B@X?#FE@;aFfHtmq6Tb%EHZzh($bn4B6oqSsXp@
zw$)*J-t^Re3i7w?aU<CqeDS8qefi-uxff?`yLq^UY1{OfUyO&zSclT-F!17)oOWEL
z7K2?P_S>SLEy#XbWNT}ZVOVsu4;|hU$6&hCtX!m(Ym`x084U}9A6$1ilEUD(#c()4
z_zj_JEuv*<OH_RP5HG~c;^KSSqEFqfR7U({@Enrr33q=?7%_Zd55>Tf$GQevJTw#x
zdN1$aV$j><j3=GYlQz7P3sG-Vki8i6Hig-XL2qOFd@Y7F0@$}@dC0Lhc23{kMbG=i
zMQGf^5X`<U`rg9Xx5e4q<k~OJ<|fa6xjM-2^g`@QWPOqpZm=KnC+MBN(#u7ys8970
zk>X`djN2;*x9E5iU4JZ*91PPXM9jrR^gL~Gzo|(LWWo6s%pOFFPukD`<7BQ{1`N}=
z@@sCK&1849!YvG;@0&5MCj7n`<LWBU-a__8vmM+jPuM0b;*G?sV-4?f)l@c4<%)3J
zKw1|THi(nCG9b5}M{EouX5r}@^1xxD3u}y`FK?xZ-BM{YLli9x{jq?yQee4e45b5D
ze-1%^$qP%*Mt-+3Vy^JJKkL-bNHa~$n%XflM$KYiIwtgE5RlfOj}^9wALYfhRv0&;
zDr0zK_)W2%=f$g8wR{*|>8j<!(v`l{p2mp0LfHFQa++3o0!H7u$`df-Tif*_b7iQP
zBh?s{SEl8S3xi<w%@~6VGT)3bcy0I5F$k|(Ka4(fl`NLghpw9S1{b<YH?J9eXaVY*
z(T9F9nqmS=5Tu!yP*tpVh)D}i%;)0_m5UN@o}qHl4x2MnE?Ws4=LS^K4%?MQ(hi%`
zi@rRo4kx<YFT2x=7NWj6J!wJeo70oNT1`$*`fLj3rMUSls>9}tsf+gAoU24p5bqgQ
z7bAO1bH>%;gLQ`0R~pK>3nd_Zb4Jxg+<wgwS{EhdouM@u7{i1P(tCjHZCDuf`N(75
zjb8obsC9bvMS5MHYX|Z4Pgu}9B?X<qb<wt)Gq@HhWOK&WWpd0BT1#o6IrqhgrEkt{
zv7&{@8Gk2n1uumT(`WIOM;vbk0|49~13Jq^=xNSqK-87TlvBAV7;!EhMZt)3@d$K4
zwup;I(bk|NR)6vRGF~rqSe)^CVitHQbXY!&Gh!D|zq#ijd>CgeP#WO=$ArE#jV0oN
z7u_&@f5GgVV{HkT{gVbXTYCV`m8CEk*(VY&+~qrL!*~EiABN3PoYck}uDWpa4O--f
z>=+G%Uip@4(9<AleoSaG&^O02aXfJnUiMwVnXCn7gHh&1tQ?HU+P&YoUAm=CbSz1s
z495aOYJ0n4*;Ieug5x)c!|$!Fd(xwB?F8(O4ha<801AI`JO`oa-daBrNuC057=;l>
zybbWvhZLGU${D{m7mhu$wem0aKx;3b^F%|g$m9Xphk+!}IqA0;3Xdh*#(9nF?M-Lm
zX}IYYKL1#9crR!5!T>A#PklNi6gCPQKPDVzb0xVK^$S~CQ4JLid&^<Ku<zZKSHiP-
zk!3qNpd{aRyknY!S+}tX#DBt)!>ODeUbeU5-p0e%?mXVwj|E4EDEGzGz0m>9Sj>$L
zOj^V2*#f0?)UNE!ExVqjEn6V9j`Eki#S4uRnJwhnvE(euN&TcLiN<qI=OZn;FQ+PL
zehX)6(S2+5PjI!4#c2ba-?4mc7d>+6K}w$g+C@?h@8y`1l-zmKm^#AXcdXId#jIU0
znVj`7&oN~)q<@D>tV@61vs!BlmmfstJ5It;E-}u~zn2+Dpl~i^SeK$+Nr!s7IHpUw
z)1X*?V6xO)Wb-H5I`yP5;l$k8vubWr^ydjnJaLz9A*$~-p>)R(Pgk(HUM!B-9c*O1
z)gD1q4di}@$Fqf&>u`%U!E!x4r|skR(7+<!bzcW*yi^Ud{BaBJ-%%mC0r-E?G;tPh
z?s!6%jvhSPPPf089b%Or(Jq^PY`XPEpCG7+veE5gS<k}KEpd=u$cx|T&vsO(LIo3+
zm@bzYAC<0~g#gDe;}ChzV^}z6=qiqL@DA0y3uwPV0RFMyD3SqNH31!}9oxxJjw0SI
zz2Y8)zHh>QL@?VWAly+Nyq%x-j!NV$z<;kjj@V92W&!PbsvADvDS>9}yoIyti2XKU
zc0Eh0x6u9_l;}HQciFo1@V1HU997&~z`Kr!bqjabBc|O1-92H5wS)x#9l`NSrT`K2
zTe>v8+pQ9Srzea1RtZ2yw7$)B?}<)mwWteyfFwXgMcx+b|Cq81(nwg*1AgE;iu$){
zH9_J3PFURoQ+7ei2~r+gusR8=YBj0p?(VFmiowd2bKBJ2bLy)wpeN%&SSF6M{X;#9
zAa0xZ=BuLz(jCZj(MDB32Rrgx1Y)Bh+`{Xvq)2SOh{$hklVmM&U|TBMJ=iGDF|OH4
zdPtkq1jmvCDOJoyfr>n;7(-3>lnC9%GWw8}u)H1IQGx3^r0kC+Up?e6Us@Keu}wwI
z<Q(K4T}Q5T8}s-bwDUVE270Df_uAYo>&U@wRSa|_YPV2z9m(7+OkD@T%Fgs-UTD09
zHbCLB$qL*d1$GQr<1<Me>by9NIDCsIxF?;=Td;Scv8I8WXzUgA0AcAC8SpV>YYn$r
z@i*_XAnBp`iroEPD%t7a*x6zPK9=l|WHhJ*vUJ~c*EcwUpWbo-*n-n_Y&LAt0v|)i
zIegI!qc4x3p-6CxD!8{4E#|x8=+c!jhPun5JJ1{*n)*_MIf>dQ=>jh~2q0fN7Ty#d
z@EUqkfWJH@zAA8m*U(FPyurPOUeS#X4jkpf5_Yfm5{LOB^^)!CILJ2X6AwY)W5Mr3
z(jvv09~fedxe_kez}sT>?bzkptLnO#vrClXy<?7o%(p|?bBoTmCwKoAn{UU?<QBN@
zIodCI^D7<=cU1(vM-ApogekdQ?85FTotF+8mksRPG1z>I&~yZZQ{QM%w|^`+iU&3Q
z4t#`%FBxluhoa^UQJRt`;c51CP6dv8IyS5~z;Wj|8=@)LF)xUXJBF0UVSf#apOj{=
z_zg95(ubT&&k#Q3oO*_EA?N)X0wb_Rp4*{%v6DRaNb1DjY$-xK5$E;}sra{e55hVD
z;ySb;_C%7aC$-`h1#XA<;GRQH7dRSsfZxthwp5ZZV0GL=zV(q>;dnL!g3VhjxE*Yg
z$HM!<K@>0Uv1IEzj<V%KvmaBupOaGz;<<Y^-MVG>nr__Cy+#s7=@1E8*MXtgQy<yU
zL)si~0bn^>Ai85opAsOtW617k4nmV;PfB)=^eAV&H^KWTIaDbk2~l?}(W9cVMtn#f
z++)bcQJ8Y=BhH9_%ng@4^qB>8YQLnK5FSFnq$dPxkIj@+2kGk``p$wEb`SZ~;EsLE
zzauytuGbz|vJE6$2iR;6eS3#dGb#>p;DvyL9Mp46IE<z$oF0h!2Jx>)Eh<~eIX>VX
z4!dtWJjB4l^=RB%rV7rXfN)oVYU#e`<1_SmO@869;HDeTL7&%w0C31@20-!Ig2nZO
zG47%7EufCaf;&%yfLBCo!t)%eo<F9%Owmc%B?+=mIGQBg?UMptLvi9n)CY{*Iqo<I
zPY;5kd&si}NAye4Yo=$qg^%k%u<pT(TL;PY7N>3p5%vx|+!6IUvtkI*ek}R2$(g3`
z*Pt(*yxm&_x*bc}9(e~yTI?ZTdLo<~M7MX)iSHp9svsQSqw2PZ=5on<V9K^Dex8Wu
zM4;OzmCxi;Pfof*v|*o|bqa?kXI;Tjv`&P$J-$*~Y`C4Gmb>fw3{Lqi^4kv9`Yj;a
zu|(@$vTF1NJErpV_?s^RJi*SXEJZa<<)GC+vTP{EI)-crzSlt2Z!y{S^>N6+H`{^c
z-x5DRmRuV;XB{Nuch{_2c=1Iy+aaL$QiFrU!Lz%j9sH)<HSJc0SzWUZ6%Zc_j$(!A
zL!YmehrA;Ex-K7f!Hts?Q%_%V3)R*a_K>$wZ5_oRo1nJ7a%u?H)=^ZlyS~P#J2@7<
zqNq;ULbdgUQ0q$I!IR#irS0&xcY2@?Ownd0r#nPHwrFTOWI=XsIEpt|G_*aVhvz%3
zJ%n4rw{?UdTg0?SS}z-;T=T+S<`z(`FDU($*IC&-MYm96*`%565x(uV^%X;ew?!k{
zQ8{%iyl(zGuZii<Hm^ys#+O(iBBSptr?Jh|A%sFr(-3uI&jv89BNX1krFE2_?Z&AX
ziafh%B0{ofH|<DwsQT=t@D|EHFDXMnbdCjmMm}JZNBEc!7PYH6h<tui3M#4rUy_KZ
z7~CL6J`N3d5{?N|0bB}O$hD3X$tG~EXA)(%sT+YUc?-(cQ3|;QWb0Wfxtknq!`2$X
zZ5_lAyA8edktW*WkL@V<++vLFprAMw_8_y_n}o1WnBp~;@*{k`*3~*Vd&H}CFl6ke
zFQq|fYzx5FL9DUG5Zi-!V~ZZPquO<Y9=4+%b~h1BcVzc=<M$K^z_%_X)GZay8eBjk
z*`6?EADNCeivvD<xO{@Ab!0fV&}qkV90=jljv-qwJxr=<D%)(>jspSgk-p5vivaeR
zqV)=hAuYCvIJ<h8@|`XJIscVe{+9|T+&+TOjv?MRfz6I3np&k=2@0HNSABoMlCvv|
zJ$n-AY~j&5l*@MIG>3B8uC7cAis4_HppICsDzoJ^kMeOK<-Y}T>khwW1LW3oUtx<6
z_84N75`L{arl$B{dvXOpiu8dc+s2PKs0nt}$J_fk%D?iS(k;#J;j^oPVW?<+EI5jn
zsOkd@I)+_`h7_|c3%MVd9H-&^^chFI33lJ=z)?Q!tDZXZQkzVz9i&%VV6&dQSX&B&
z9c)^=>dOmVvYoK92c~%Ct72cEOhT<SjxGMi!gYNGTpP{yHtt%icqrOJf#B{|ywDcc
zV4-+$DZ#D9rBGZ8v^cbQaEIdVTHK1u7uxr|_r3pnzujMwooD3CoHM(dJ<se6;!*kY
z*71Fuyg;g*sUVT7l3fJ8nIf@{9$-yzQ@c9Ai_c0&n5WzIH5(3J<@3|zS0+Y^6`>VH
zRU^Vy(tOkUQ4Tgu@-y5{s+_e0k>9ZxFw{~ih)~4^s9E%Ua;csdT*@ghKAUV>4miku
z#pC+fjZPxB>+Ton-4_t$jn(o>-QkmnowgVXv-+hSm9a1cGtuee8U<}(o~{~g?d#5W
zOHAHhq+M*t24>=^v9W!DtD&~?u-7ujbCTpN%L`>@Atk7Gpy4jc&tV1=jRY2^@Wb|y
z`mI%5-g1MBBfP8jVuBleMB}wCgsZ9S*LxDdyV+{|3|%!0{MUoWaRya-C|TvWAGJdI
zr$~E?4}PWb07uT&?RbeoG>C_T$EMh4tb!+|NUMsaZEeWBw>52cF_8}<Zh=ybp0Q^8
z*=nLF-3wej81ss89P)lHz(N`&Wx}kwNJfiLbpz_?JW$pw_CWdb)X8D35&_(|Rz=aa
zEe$L!4K2qfxliR&E!W(+*LfAga`X$(1G{Rb-pHGzYB3;3G`lWyaRNk{T()9*L3+er
zx*QC})IRqS<vRoQ70P3lc*s<3GA;2^rz9qQPCnh^C`4T@G`IxwHGSKkm&*6d`Snwx
zHn3Q}rN+;GQou}g^c#a~oblwh;vrno*cG0!uJlxM<PnfO{wMz4Zv*^^k%-GcGHV+s
z{^KVz_{x!$7YK4x<#exp@bNN;XFgo!5KkM&8e`I8l(}R&y*cJVD?b%l$hmJldOXxl
z<&j3q4ZnXhLI)JEZ%n>?L)CG23?)s*4&y7U5sa}yZUwP3%s`_L`k>}xEl9#;BUc+m
zT&9e!FJX9J#!V#qMrB2X)?fqFnl(WqYmrIW#nq9WE;SRCwzn?R3QsQVtoJ*+`5MnD
z?G;B^Y)>=6H2YhAa6;}iH?#aM^vkrKAhmy|sS2e!eCCAFbe@h}(1b05^*gpLi#n91
z7=79VZmo*BpKnE;j-*TDg{(2o(y&KFNZZ1S9VLd*=4cj?YVfU61dptcrH0u>W)x((
z$!Kh$<cmG&XMs;G5~fBY8JWiWMpi=&I@cJpcDpqKnb{gnJUH}s-y(Y=?Ca`O=(l3p
zP)5TCZr&nm)=W6Y<K{I3GtD>5K2f`LA~M;b>iJ`j@~P9Wl#o0b8<?vWlbG*ME9roy
zC!=#)*063?VQ=$sy>T#d*FC%Rs(9&POLj0@zLt%(@D1@L*Lk6ZY?2rnl^J#}enxph
zeJ%)Xh2uP{Nl4CqD?5@fzEjAwF^VyAP;XnBdeO>#5^9fQWVy&ku`tfROZ^>W-u>|x
zm1(0ST>^GBpStb3)YlKM=pkB#y-=!T?C*Sl7aQ!hSMdzk*qsRBX8Rvnepz{7*&7Ta
zG9aQAP3eEGin&BY=ilqbX(d8C#Q>v`>CH*#q{Xq?Wu6XpknlfgSuT10ZCHS?nuSMI
z<`VF=i!h(@v}-P6fA-SC@uh+bkYDhTIvGTx%ZKf<-JsnO**q%UMF4)6LtM>`+J3=5
z;7+Vv2OgBZ>HYw@Bj3zYWcI1T(Ty@+`M!!0X|vHa_g#_4f%AK<ok(R!{xy5mg2QxB
z{-<E@t=NzPYz!Kn9KmfTQQ03rYggqAH8^$XdgP<yZ5s`CMx2qGn5pY|0fkPK8(&G9
z?ZCO|8n2En^f1kDg`YfmysU4i2GTtpBI&fk;3I6NY`3aXWB8m&EpowoTOVWct8?fN
zokv%Ou_*)`oY{NRDiM3Q`0WPq*V^WVat09xxW1JLYvH&|rj4H54iYFKZWCqjm@^B%
zBjE1A2q*9UDg1L&ZU|ZASy4jm)F#?#?_7!<CDEI92=e+#m;Y;Q-ZQ(AHnIF&z$j^s
zo3pyA>~@OarAu2h^%pZFN&-H}sy`ATH~%HMPdi}<ZF=dJTNL9Y+R->}rWKX5OAZ8&
z=u`}#xs{zoS!lDNR8N4shSfy;$=I!z%#>)?s1{=jjjuM<8A2<c>)WunUWYqpw6ZA|
za?W})2dzp*mf#n1)zL?&0|}L0nUaDew);^FDXAfP(RDG3mg%8&=!v^oKMBb_StgN$
z%$tZ`Ky}(C>khoGVA+wB(TtF+d9?4MVx&|ZDP>g{&R=@icW0qY$=LUNWkcJo&A7Ym
zLPz$Xc!A7PR0H@(WqD^g8g!W+Z$c_@fZ_&rjO<~th~s-NsgUs=L;kY9-6y4#OJGOG
zNnC<jk*1GTk0sAml*G_nTMVjPkcHRT7wUk=7=;;#30%z2>?HF0lSuvIp9-Uiy!;Hm
z7XXAo07ViuJCwM{(jrIyocb+wiH*r5s_=G75tEg#oO)#6Xwl;Pyn!5onfk75?k?y>
z7(OHhlvzLB5~)nqSpZraN`m3)tS7JcXAwBuN#?N)59fBtQkQC73Y`7vCWzXC$e*>(
zE7)>nP@)52nw2yaW@3Un^1EdhudETnLF^6l(6y=Zvag3p1^K72i2$`xrFiz!v3NAp
z#E9~JZBs+S1UH<c6%|mgtweDD<_PwCOt!-X1l^tvV}6N?^}_8_7*8AQ6Mb-+E-RY<
zR1d`@a2ZKDaT`bQP=~#J0fx`X2Oa#L>4B^O%y1&G7?5OsVvJx9Z%GLB1!VagExt#;
z-37#lcLg)S`7VOe9eZiUgUBRA=5Mcj(SA~gQ`tp#fJLUg)#&GYB5{BVxYzeT13d{_
zmN~$6_*whI3;Br|`^5qjZMyt$ki2=2Qb!`NKWLNE_zF_Kj*C+f!D_!GdGYEUq@O&*
z{Uu_tGvEg8RgXSKvtQT2lOD=Ay9$Nl$fp+RH>faA?`I1iQ%9T#4u!<J+CM!%4I}Kl
zL8+HsMwRK*|J;NaQx1AzFD%=sAKK{Wu`RuWuu&1w57!VLBJz1|;c8V_hH`3qjcF5}
z&wUophSkiA>996CWt4`1OO!8qT`+!R#L|l$v<Y$AXFjyGa#!jah%;t1Wlesv<LD7O
z=$S)ek5$=h(CRVvBf*`(eQbo7hyy!l<XFf=NP=6-n|au`_O7uHtU}#ps7)H|1dHAH
z$*VbziI2T+yniGh*vz3TnV@B^i^Yew%a5TenPm{Jn2S~IvR(8B>?2k6=tnn#dd_+c
zv{{^Q7vg=Qkz=MjXt88Tk>*;~)}-8pU)77XmL6rzF^JHToy<d_$q`rk+7;LuAK|y8
zldNh615VnxN7RQS-d4-d{OR&FDi68vl*=Ejh%dRBO%|X<$@m@=*fE?_$8y#wq9#j?
z^u(k9hfMc2R1B)m7Y@gpxLcW*EV}V=VbdYrI2c*A>Ve2jl~LKM6c(0)A<Qbn%#NG5
z0^1AKt+3?t5)!n#rZ)U{BRp+CT#~omSY9EePAnwA6cVbVWHH|p>v*-cf9kqqmso**
z33Wqyg62G-|G3?6B)hAAf(|3mJ!#aG*0-V0MDjM)4gQW_PihbXxEGD}HKr&jK3-!?
zc{bdY4@h?=-1_idFoRRYfIeMuQZXQw{XiGY7IoMQV7Sw!q3Wa}iF5=MxwbrxVx$dm
z%Kof%GI$$BTr1eMOO?G+!i!pG!@knwXBH6g?SQ;nfl3o^EwuT_Dtf@dgc@Cg2L6Ae
z;^#;MwYoV3i8^YzUm1})if+-=oL8M;t1&Le%8W4!dt5->#+_{!*t(&rhFS<XIDTa#
z>ezh^P$2Del=uXz*C!x0@zgpsnPb@2C55^Okv5d88yp%Mk@aqnG*-h_>N2C+L?Yo+
zQnq~vL|!Xw=xc<240QARfUaoN$ojZvMVpL!QR4OszZ^45`7c*~A@$H5<8{g(o{;im
zY9+%2gJA51wZg~SXa?`S+mxuX>VF(MAks%M)=gCzgiC?!pDj_d$era2Fz+NZKJAx$
zankijJ~a2!8=Or(BEdVfM`K+uVR^v(TD=6yy0*LC#V?iGmlF96Phoz}sSzmfk$w9}
zT6hfWjq?c1d8-XiTP1bs`1g~a+#jg)5bP4Vm!aToip7;B(z}wUD)jmJVA$(wse=x1
z^`7f|KIn<Qhdnwe!8IV}ZU7s+pcW(xTLKEGrj++f+ziP+5diRRt`JZ~r(i2B+Yg$r
z*D>I>66M>l>pLNGpubvc053zs=eqoJwCQ!}vu%wzc0QJMO9Kb>M%!S4_E-*5oP%M7
z-mTFAvxh^1Wr{vf|JF}VX#^ThCM+QVXG5R(q;68Pf3+?L@P8#A^a$r|gCr&jdk~O)
z%O-5uD6zWfl+)Hv2!q*u(FCr3+!pL_t{`cZ!V7KiFt;#m(=1sVqNXHF)fzC}W%nBA
z>BKvQ*W`o`>r?<%vNHaCI@ER_)WU|Q6rnY+`r$)%kw=3U)lojRa8|1vo<fU<c{d^+
zd1<(S2IgQf6`}&n)9J!|hk%TT%>(DTTI*`in^Y}CS{M|<78yln<<wxkAjLM=am#=9
zp1z^<M>ymOhrD%%sLAqILb8Z6dkN0Ljw^l*jzQEeDlf!dNwH>77+IP1j1<A3>;^xS
z7XBE|Nh+^@3zcxpVntVfW|+{A5Z)2=jS8XJ8~&Vz^Y%3t@`}CcT@#`;6Bz{r+SF5=
zin7%tYREeofZAK!5RB_qi^YMc5UsV$xRT8eE(baWby5BBgTR33W=r}G{fHz2rBmbX
za^b38<J$<h0;T<W%A7VH>nXr2gw1R;k;EH~F?}A3AI=_mpMa9<>kO!=nb*gPhwXv;
zHDoOn7Jj}4HFh7&vux%mgnP|b2ep~I2`;>qLzCc5MhrV?{bdmhO(l~fsf2;p+jWLs
zMR~ObiUFXc9g8SZ2cVYW<WC*WMBm3`pXtSw6`R&U*pWM&L2Sq!?nX8MGSKoSit-Vt
z72gysAx~J|!C;F+xx3Fxr*6;qoD_|V+QN^Yx%*syX#jKHi`o6;v8gU8@Ex^gLpRi3
zReuO|F?ET+xrLuO6fNy=fLXZ!DE&=tPMNeBQ%8_2W-+j6t{g|ibuFfm^MepX-GFmQ
zXURNi5Svm65YUBadZe=iN-CL!^|2ecg<TqcA5=b65;FE2mJDpmJL01}(9jIwdd#lE
zFU6^!vOvPJ=7~uBb|R`-e~V5Tnq#0oh>1{*-7AP#arOl12-N%Hwae@Gd}NV2f<Dy_
zuLc*Spp*SUT@j>s7;Uu@=|oZvsy7>fIH}mM%l?_BWUD)-#Fs?w5Ywz`mHv))YnxB?
z%#}=yjkcaFM12jm+o)<~wG<_UqtorjZaAW<4g&bx;u0pywp>y*D&Ndk;>`W+2ZdHb
z`DG=W!p`iaOa?I~M1mncMB0%2l~l}+f^-6wdLAQ~ErPQQG=hmVwmRFRGWdyTkZg1%
z2*t5eP5G-a5?_#*wBF#^h%IS)*T`(eNE**FH!~I8tfrgcbV1=a^DH%Or6t4Z^mCPg
zrs;HwdFND>F=(YH)lm?HN2^ap_CvbubD~2bTYOO_c}PfltR<wr^HIuHO|7$p<e&^d
zV3ZmU+c!on_pQKC$Ux268)lhh8%Um&Ah+_zfn;}fA~T48@@zNLMId<jOJ|>UdSFPP
z5G#=dB%8Reokf7M)fhejn!od0&71foMt(m5=Cu_Y$hC_U%|0lMU5b2=Pm`Lce5`!w
zX?5bj^E$N6(lsfIRTK+jCpO?hlgm04_+(&NB&t=PRkjT;@p7V(yO(!z#qZ-t>h$}t
z&!gTu3(L!58@iGJDa-u^x2D7mU5QKy%SSzFn>}dnxkIe8rJbanobnA5s-kRe<TLXO
zd(&qv24<($&f%G%_WyJ>TY$|u=LAh~G}0=Fe_Zoob|PllXblqyuJw+xaBQb6*s-JA
zzlJ^933+>qVJ=7%u^jltUob9{yV&r9bKs`H1P0_yIJG98>)jHMMzPeaRl9m69|f=~
zQ%Zag<xnK?<0~nbLFJfai8P`WM>O?K%U$7((zo#O*lQpdcF41JPz!d5q6N{HljP5?
ze9J=2?ZV1Pu*yk+R=}@tLnrxlZKu7s(*v26k=z^MEIv!(yR<@H%aXjD&6=LBN60}o
zpTkle@_SQj-+Wm3(e~bO@TmRiQthYD;{4enmc2iM{Lc3>=sf@m7@z2$WzD3*ds0ja
zpQZ$1*jpk2NVfAL!?rLTg{9v>|J^#djZBjXlhsC`)m*u;E>s*AI4F{6lM2p1KP*=9
zZzig6dbkzuVR8D?x0Hk)1h%J!y*$)5-H&+b;2J^Sr1jCK)24Ix5WogYCZdpHa@Yv$
zjwVbKgphRv4x~<50rmQysO+|XJWL^~=VfZx5cj^WFL)<>e>-^(UobYY_>DT7t3>i4
z^~2iYXG25Dyz7vRjQjh|)BB5%O~}pV!NHAQHMgW#l91IspLpreH}RXJOZ@wr`s4cJ
z+G*Om%gcl2%QpL+vc;R7=G#&G`!3qMlaq|Q!&E_``Pt3v;{Dfy<6T!bT}`*Qi|?+J
zhCDX6FPrZ#x(fV9b0@lYZjbcx>f|XZ+?p#|=$1~*1AI@6?l<o*_h|3j_{JQ++S$I_
zzqmY081f$zx7)~g3vSaWNUUMdxr_-$yBwaxy|uqzw;%iAh~}K?w|mV(>`N7WOg?*M
zIXhig+3y-_xFb*D8C`$P(SYQ8GArnNVlRGsy2qnq-?E{nK1n`4L<{jY?ESSln|evY
z>rr*E5MKJ}rq=lO%r`^4(MssPS}J3g`_WSagS_mEgU4Z-62=*uu7=Qn^~)2rJvV9m
zJu=GcKHQEJ2#wAc*9tQw-^+G0VfQrotAJ9qKL3SD@R!5e<Eq#Wv-7If?Fu;dfm9Tg
z>V8X_r69WF?nZjcw?jJf;<VVybm*qe*O<jKO`x{?=2sX@t3j1`Wo3sbYyDcN{Iax;
zUK?S*lHfTEU+g^*)m>|wmG3~C#NGP1w7FT+_VS?hS1%e|-({Yyi@8yoo0NLL+pTma
ziXIL%WbX(y6YRlX()e^Nhwn^Y7m45D_}l%gAN+OnRw$(GGM%X?hC@yI=Z&aJ^{G)B
z>96#IQL78=0zbY_YB1TH+XF`-vCUV->3N{_p&@_!^{x!4bl{$=s?ed4tKHe;Q$*q0
z<4yFuQ=zPb#rr(QTN~d+B2$i=z6|uE;7$r2DsjFM=G(K)#b5Tm9rboBf?5U2yjw;t
z{jnWuE-6I$7wh0mtGWW6TVA&Srgc%<tI}G^&p3j2OxA6*o=C2+-R47-yKs_4br~1o
z$z<H?3dmGpQvrDAs&BOSVtT&!g2YX4DrXX`#5iV@j&}Gc1NMmb7GKoQ#s9=e+x89%
z-O6ur-_`Dy(WoGx`~d84;p;IoWU%n7SY#mqHLrA3*SGex*`0z<;TKAk$rVU#X*cku
zmFl8+1xi`gt<mg+5tHwc=Kg$d@nDJ?jq3msHFO!$a(KVW{52cnY<w)~XP@euYdb54
z3*>oWpKaFkrODgt+bA|O+-sK7{3d0ivob`wJF#CW?=lPIM?CI}((iukV0A{EUwf(;
zomJ(yula2A-b$$9mmYm-&M(+O_Y^AAxwhW#J2h8(sdFZ#nMk{3No;sm^zJI^l!(#<
zz6A4V(rqd<p;^@@8D3_L(Y~(-$rYiSy++Z|_|)60tAX1%j-DaXy^N;Yp79e6-}4*s
zN!`9FEOR?Eh_jQqiS5IYy{R=8FMt#9@CyI{_<{VqTz})-f8in`4^bSl?#}X>&L+<0
zfIq+kX2J;%063&20YCr;$OQf^Cial{&o_shy`A$vQd>Ode9j5rgBPpuS0Z@2zbe7?
zFJS<VR~`=L01kB%OLG7t0Qg(Dx`~rHye#0~c{x<f&A=v7_U-^ZIK&Cy6%+&jxi~oi
z2EUU_!v(|BLjXMg${_D#@8a-}%KQ=X8-2(E-#9ekqMc0aAPx`0Kpua?F96O?F6MuS
zq~WP#%w54Ca}9Z^2k@`9YM4XpU7SGX5Ws`pG_d~NG=6yaLB9{0QZ~1<bhZKr{Ht1W
zU>j$1Cjf_>4P3J_<{*2s-;(}H2n6u+2=YCY^_R)qQ}?vJ+=*ptO1Cw~Mdw9DM@5q{
z8Il=@V(BnT0|OBd;|XQbBLIj*b7hjIGV$0L#{@ctN&slE<&Q%OMu2|>u!4YQXZ!e(
z^cy$Kg+3B85_M<#3PWOkrUWlfB=-7q$bIADZPP68YlG4fxJN2YQ<{ZNhCTu#8kSo~
zRN#AYGa*i7`jt+GLL7Yd1;K+&EGhc4oYZHQ<h!jga#0I4y7my;it}OSjRfy~!%tDa
zv@n4jYVXWU;V(LR2S;yhmX~gt?Q+(z=1sk$oqZZtFqm>}mIr)1%U@=2(_Zz02vcx4
zD%$moBCbF+RX8o7m%Hqiv<7)J!`sZ$XuVY1_8ds(%@v~%_Su-R0juz}f=zeNJHRpi
zSPPlrdowC~t6kOp;LhOAeiqgqEGC^7jPH4d0>5vtW=lEx+z-S#31#JeG>j)zRC2`K
zL7095RQ%|%th_eb|Czx^qnvosNmf@kh%HVH!({bRFkYQyjS|6xDd^HPDDbs>_AYv?
zf=i`|d$lmfJ%K9TFLo=Dh4(UMJQnk1J&(nhnlq8-577AIu)G*`M3_I?F5~&*5pn#G
zU&w1qDLyMpmbMPzNt>14y%lRWr6uIEMeorF>x@3@x6$LO)T-gQY^$^kf_cp9a+I6q
zvZgCzFji`JJmXyjwT1KBB$8`<WaE1SfAHVCd4()KtSs1KliyaHa}uoObwVShJ23Ih
zlWZ<~w(6(cbaGcIeBl?PreUjht^>qf18)<V`JWK%*rlY&dK<=$Wr3_!k@!3}PPabJ
zNxl*D|Cs2Ibi=N~Bg+$7%1rf1<nC*ik=ObBq+IjIuAx1`ojE(ly}ssfdt|@5{bckS
z8^P!i!prz>r`+aLBW5A6e5~|Krzz>y!Rqw!z1Pjch&N5&&$@r%>SgeWPI7_Kd$>fW
zb!htHH7Y~RW7qIppMIUGaACcxvAgvvTG_xC5B>CNJx8WdAfPtg0<<kz*=Cy0Lekfv
ze8rX~pOHT_Q_-aK9)zt!=s5a1%P(A7<N3-2n*n|MUd3Fyt+r~w6h~6l&y>*-7h7mn
zG1Ks+)5TXMaqBvqg8W_yD!YvdmDxu;#O3r)Oy^09pWD~lMO<Gv78{fd5X=N8yj{<B
z7#1Ur^UeDhsdxD%&3Bv~8<*MHfN74d*jVQ69?qx&pVRxSncEo!P=k=+r|jqaq~tre
zQF753X~Hf^`*!j^u|3KQswdlqmS0#W(iAnU!ikL$)AtoL19ZdFSCn~$YK3Z%-*CiA
zLvoc9d%WI?{z@NQkSk%GOasqLOYtxS0otWR7((KsK~NzDN*f#(T$hk9B3vnviJh%1
zeBn`XUC&mj@Qd)RLBGlek+l50;$KTC<@U^gO1kD`C%n7#C-vRPbqd)>lLY(Tb7>`C
zqq^iY4eR_Ya@P9!da$viao>7JbSHb<T2w;;t2V+lU(m|*_UXVIa81>_wP4E$ao`gU
z;TNZ(a?I*H6>jMzR2nH=a(wnsW`(u6(+-FbzDwb#U)J?^Mpmv$=+m<Z?q@H{7{azm
z2glf6=bR}`5{G2#;)QTYXg)T_I~Hc2FM5GD?V*>p-w+b4^~u#lmY8)hOIt8|DwuD;
z;`D95^*NE^ZCB0L*-hTgD(#I?A#1nt{Tc1E%-GTdtID6FHZ@#IUWw0#4UK1~natB_
z<Yr}!Oqwl(6R35yPu{`=w0K2Hz2^!#w}1YKK_6H3gl$Pfvd9jyPG3QODT7$%y3h;T
zPNQE+bPgjGBGAbAkYqM>7NTCUfKq@->^yv<xV?tDd9NrB$jLsup+|PfRP1@yLED=_
z64CWD{bZ#~z&pK(E?q=z6fDGQT|0Hm_mxCC*F>Z0qh#Mp^sg$P12_och`HF-V)H(j
z0dwfuGYH&1;wF9K$O*LLu`t)r`*PXLi1$d!MIaQ}-0Ii10YUf^>nFg%r;N|?DKrX-
zXJ1zn*xbCRi8VWO>8q|wd>i^qWz*eKZ!-kb&%{QoT*0E7bqA~5S$n_eb=0$z_k9bS
zz)w;97Rx0VbX}B#Q&u&;ug1<;!bnH#h?o09ur04`93t${+a86uP9Gm<N&Db&z-O!u
zxuq%IA4sHlQ&npAXp^viCgfv6)U_-j2Yj?_fFewGeVzSnwOo|v+qB^A!)<y-^x7fI
z04=-O1^2lqeq9=#_qU_o_LmMPEUdG~a<hQ&gf%L%*pZn1VxNuV52fQ1c;2^#-xjkD
zhTBF;62oS{HR~`A+|%7y_vG%B&E}h+jg%394`T(mMB}BrUp;sEvecx-BEFU@KSO&w
zCZu(}>K)s*320-C@`@Hm%I%7|=HqO%F>G_DN7~Oiy*nCRZ96*XGK$)~ec?M}w0*Ec
z+f~m(9*I*O!S_KqXEYbw1a`Du#)(hic#3q_=&b;O1sgeIE6T)U=}qacei0W~A8U(S
z@YSCqD6sN8DR@<w;9BxoWG$BIz3<7ZD4J^_m#oG@xtuMDqv0c!>vP*mkCbW8u#Dz5
zGMm%r54KH!&NN)0*ytJRfZLV7o*pQff{y;FhSWCdu+(xZs-o-;>P*NW32XZcM=7>~
zlM9TOtR<mCGS8`{Kwv6r4Mv(rv+b@&1Yfi9K{MpTM<((13A?hoH@R*sXn2D2+gWE#
z<NGt;Re<fQ<Z}y8g-s74<ijf}>|}0^&BsbTj&(QuvIAu?mr*1HWm9uFvOyF_X<OCm
zJ%wUb{NIm{>s&ZyYu9VVN{7Uyb@hh&eH(|eq&4K`H!~(p5@}e{St7#^fYfQ)4U~mh
zX1Y6!0zsZ?j2R(U<f=V+Q7@DoKF4N%c%iKPIP)iFSiig?nEWL1s&|IAVk*n{YqijG
z$x)(J;$w-_wmg9bYWQq9mf2ZHT-LN1dQV6e4Y`{eH)=l^l#~(-#w+Oj$O_KY(0!b;
zJ$X~NIF0)uJ7S?@T5GTP*Z8&2F9gg?w-=)$r>ZZ>7jTRUwyFZF+D|1sH59E2-xMVY
zDd9$a_z}zSwgOL;6NYNXNrz@ihj+tfs4}2%kZ~7r8uT+_WHL8ow6x%xJVuJ7kFDhx
zWtsxf=OI?+MRISmCCtH}!$fNAUnpw5ymhAAD6eQ2Jx;_sX}z-7*4i11X{RY?u5Y@0
zS*C}s4wRJo`mk|ToLoG!Z2J7x*7zY#SaSHZB+dmk`W1WQfqeHb1Nc5hPMMpelI=ya
zr5%1K8Goj;>v&PUFs8OI$x}X$;4fA#d7mgL=Pf9fd@5o3O3)vhSZ?02ZdSQ6-)^yd
z@t~N9Z1}DuG~!18M00W|y%DcC#h0Bu6yJ(D#dOqx0yOtDM*Cz(J*91hON&is!x%Wo
z5CP$XwJ;(azkR(C--DMM{<DTI`~H&oylvk>7-wGP1G3HYk`u-F7e(~CimTvALk+cs
zHlTK06u$HO1eyd3CCG&a7?s1#CYn!JEXkYevwp%VKyI1BO3_PUHEms0QEejbJRSmH
zCsOn=9gcMbK`Op9;irDu*BggF2Va+ki!&#&t`90sJ+ps}2eXeSa*(=oyO5~GGAb*+
zQMzRE9=d08dz$K3Cl@o!kihhk_42fSgs)e31@OjuGWM2Td{TpH08BpO{lc>}&+Ai(
zx+)v_dT#7#wERN%lk^Q<^a3m)%KYjV?PAG<Ri7Pqx;+`*fA}6d%GqRI$5WJdWgsj;
zT~Uyi)VMLL-QO06mfI#-@gf^zMZ9yKu5FD@4E~P)&l{nn!mrC~-`>78KUk!&?Prnm
zEQ+QHdu-;&l1^bvfB-^3G{A&lMZDe~3pH}(Ea+?CY|!n>Yz+;3q&gc*ag~)6&T{C4
zTy*HF-L0B)r8*lU#hm8+L|OsS<9$CJYuF<d;kd{u?$ccQpSOe89~`R!#bh&r&Bw}o
z_*MLEoZt4;O!gz{D7;z=g>0&RQ(kJ>P*Pt^ZPW_{50{6seFH2E$n2^}+mC#>$ga}h
zE$1O1IU_f5Y23v}pI|Oc(7JZbmA}rxa0lH`Bj?jLgcYUQWrQ>@vW(ThX9Ww2{BA;z
zjkLPn{rX9)jhnQzwPS00dzjw}gB%upLCS4gLiY2+dY5nA<uP%~Eg^Sr-9pbh#xV=>
z*BZHh4QPhA?hBVW&PHx_HC(RskD_M0+=LJ)i!^QI*!#DD<}07|`c^wmrvBvKEO4Hq
z#keWoNN(iIAo-kQ(p`{YgPqse-YMxNjuy<|RMb!Q6<2PmJ~5_DMp-30r8y1LsbL_K
zW60t-YgS)MuVM0HLXXgwqIPrM>IS&BYBX%!Ox~hG(M!?SdF0qTx(gN)w)1%3iV<N_
z&K7xX88dwhpTKt2;xZ|E<RfFb(n{imTim=OX%R=LT*_$NY2By0%E!dXKe&GGZNO)h
z>q)<;Oj7c7blo4tz0@jn`ymZn=}Z^(+W1lJlW#{MRA35&anDzl+}&*o7r^JhmbuXt
z+^&7H0@74?$HJ({Bv%+0n6q9c?pZ+Yn&_gvV?^!js(uT^eECj6@jZ6-CB1zTy%<u?
zx8`Et+E;p)D#M}>&o^B=W)0v828E!lb30*ChDO{b#_v8ZHW6g871?=3B(vX2Vanr#
zpX3`L6Z79Tj?`GlCdEmfuTW6SuFBa2H-#8^9(Bi%840ls6s!DXX(BWd*Jf$D>$6<x
z>qf<EbV2#%_eHAdjqHUY6S<i&%M?wmVnQ3HL0ft?X0fK5S&du1^YOLDjU9=7f_t?y
zbBFni>W{M-KIw0^ydxEUH+W3`HE}N_nL!carX@Yp8b9`A=F_2Av2VUk*FpwT41_xd
z8Q;Fx$>0dDj+opd;J05O<}VKZVo+yxd&Q_UsmS~+iKBE*zplYaKht8E@}T*?Gdo2h
zByN4P)KJvuU94(qwOJ2ae=hDabn3oW05eW*MHsPkOG4j_4x9(tk`YR}i!F&$g|CH6
zjhyT!=BE`WR8=!`pA^mM10`L)@Yh>?DUg1>dZ8vxeEwa6^(Sc^uI9xXp|GFSS9p<q
z_bW=U*qk6)B3ijT9FTz2%zZ?oi1@@8J^R%z8WO?V!Y-1hY4<<KT;vVt?bv=P%=@`T
z-}~NmNkbH#w^T+f*x^r0xtSEB)LR;>X&2G;b!$#R-cQi=J9ji0tO*H5a3{qHO|@ZA
z%T<&oMW5(D;kTlhj(WSM!7<RG$7e!6{q78**gT`sb0lKG?AMpjf!yiCN3>mTCWApl
zvFJW-PYUzMdX$|WH$iO#diTxQod~y0@N50+IrW<(<Kv!j(Snagz-C!IMxF>>sz;t0
zVPJ~L$()3A*=@YhJUB~C^N}aeCTBCcROpym2g_qb3MIs*5ap+M(A)9V^8_;{`Wve8
z&}bnLtwxlWDAm)|ELL%{7n4Wv1I!+|igM>A46E!l?XJV1s+Wdpt!r#IR2HxhXL2Qr
z`e_1<1tvt6C+pu`^KL)rOKs8}xTe^bvJaTZI^$pZlRU*=onf|#bQroFLGFHuDH!e%
zY4b$Q=O-77wBp{dyGAJvi2OpdB$G{|1Tz^;&<ty0BhDu`*f|JGBa&72BEjqE;IQxc
zF40<Tsu-(}{Pwb8tg7M^Z#*xJ@+>mVE3-j~>|7<-mqdT*h+^rS6XXM82A92KwE<`$
zN>LAdO&Y_@nrfF<VxC|9t@lfVGjmc<<HRouTh!`Y$;F<DtIu<7E$9{FJ*y+T?py<n
z+nMm6;n(qVS=j3i1YA(+zM}rfBUm<~pFC%ocd3w3!r%`b37k>EB<tXqyKQ0&iwwoh
z5EVb(*gGG<Pm%wQHHO_Tc4TWLqi9|fDi0&z7q_C=d-i?&{+t=@d6i6^Ot^>eaadKj
zcj$rb$0Sf%S<V`Jzt42u1k+<VJP7`D7ex<_2TF2J;~M9Va{dwi3tYn_wMs=N-Cjof
z)o*9IdYoFu>|G7p6Ncxe>5-Qp1{`qJ@GFYpMDlC~`Musy@G&<7l8z#Bg+}0|7fO|P
zfA=S%p+KUYL0pW4oaoYp!0*6M`L`Kff%T8O>C<}5WaM#-yRmC{KB|Rx@)swN2I=||
z{8$TWMqR#U`>unySi7W$$d7WPMbPBfV#K=SNzi2Ifq$<HtH!!0LZbMz#G!JS2j#ee
zjUyh`LWe4rde?zBim3XXVM$%EJT>l%Jf;gCWHG|Sa%hCkp(Tg+D?~CB?=8Q3eT2;@
zm@mc!LV<4?!XPis#wMvmo3X%kfxx>ru#A<ZD5M3l!*r-P#^+Kfw+rUYduSbsJ3qE6
zwm@zF3iGYQ6N*S|0j8yMqy^H$MCc->yC%#Ym5Rhc24;edmw<Ljhggjsb*PJoj!%3X
zAiuQq#C3^Z@?9q97#6zJF2Cdy$I=I^&xD6{P;10y(z4RWhLDzGuYj9z)2aHdwsSO-
zD0D-~Y$LG$Jdz=4nG#GD{}txcQEbFPw||oUp(!xXQSm!c4fa&cc+WS?sqMh$pFkIh
zrc?Uh;{l*LxD}g1gu_@fsD&T%Gp8~AyQ*>|zAtV^xZtt{)SVRLy%c)yuTb9gAnyS}
z?aI&uak91bAaxqkA=G6Z#9}R%)ne2y+i0vY0}1C6(^zRq9wtF}edQnzV0?D2VnA8H
zzY(T(UHgg>DqFd6IaC&j6bqyJ&Z!0IP6-j46vo}bDL&M-iM|X*JVEJqX`y27pICZ|
zSeasMK_oJb!kuDV2L&VDslbR{9DavBoj?#X#}Q#NK1OmUres8-Ayj8Gj)jJxD(@o8
zs&KYo1|iWr;xv?yZ0f{L0T>0K=YTE(bU0OE+H)Se2;C<wkFAe^d&`I%?`cRo<gp*;
zwcR4g-Sw~0qu%rf5+Vh!b~_-p1*dpx6XSf~zfdO%e$1&2^C98<jI>X}slMHd&esB^
zcNlWOz}(_k+OHS6vE!H<9~w9~mS}E5J0P=mkv2lU!ssUXQJ<7_Zs%_(s<P0BEedg7
z7!9PN_GFN#LDZRdNoUNg$4e#`8sY&+hu9gsUKj{0dFI^XKbYp<00BBHo*$}8Dx6E`
zT1OYmBNs|;Js$Ir=SOi-AdF_q44{mS9%8^p38yQ^d=woNXd227i+Xg59s1UP3Xve-
z!(+s~h%9QwqBN-04T}((H&O#qHj2B0zdSUkK^GaOkFam*fXSIUJV&t9K0Rpl1J#P@
zGZK}+0G-5<zdjBQI=L<szl;neySXQ?L_!6CWcB>H;ThZBjqftu{Vd8&AM;%^VtiDJ
zz<>L-ADpaz`L%g@IRE9=7W{8_EbzgF{M#qZ@xT1B|8&0^#P-<*a1zL#--YYsM}&qT
zzhDe}l}AbH^SO!^;Vk+I35dL6=|FfjOrsF{W81|-aZJeCoCv?2KAi`CCD<{@#F=l2
z%P2r{>xfGzVcl51a-nHuRyj=zGkMll$I*I@v$)8AEdVcx*QU&?0uqIfg%JDA82El4
zslF7#`t@x47GHJijlye#fDXSEL!tW_6^s`=2b4;it95%lX9X8?B2qNX+~hs|q-2Za
zIBE5nMI%+g){m`&2H{f(;+y_NKbc2;y`Gp0R+N1$6rmh+#p1K}j_%f9kVI97K9!r6
zmR^%i3^OA%LfY)v*ic>ux6(!ox6*R#C8tcjl+SR|%Tn1=LCsUyvGeSMWH{a^*AQ%(
zNX|2q$tVwrO!OYO)NM#<)ZHj(C3CNT+N8K}=_9{Ef%KL6?y)0BL(K5<?c!0TrIz<Q
z#8ifS{QtJuZ%h1TG;VI*zu5ucgX8~iANn89{R6ikV-5j1fgPOfogN(Vzv%{56I(cU
zprWk%T1S>u#@yQEjf*DSrT?#ZITKs3jR%0`PZZ!G?&+UM8xu>o@1E;lDW(3f3(tX^
z@S)$&dHA>h@bR<UaF&6a>o1n!g|mqb7$j+DX=4uH{GCq{0(zh+1i1u$2OsM95Pr@D
zZ^}arrA-_Z%)ypca3%v@%x_53+1&OGK;TdQhk(N0frl2tyQ4W5;DJH-C!_E{q5QWt
z{uJk8>inBNc?IVz9yIkEl`?^t|0ZMpf0_Y1L7b(nOq~8!fU?P7VIbEZ0_H!}4ft)4
zKWB`r9h|fP+gSoQw7_<fb`bF2z;DS~U^8bc2%M$i20panfA8FUoPWjhaq|KGe;+t?
z1dsjSB|M<K{0~glpPi5Q?_+*}f6L{AcQ1bKhraZ`cRub1z6dS{_;>C<>A3j+T?QwB
z2i|yIc%OKv&jZ)<z&^nd_~$qI1SgT~U)zBnm>j^vwdS9O`|oc2z;gZRol0P{2R%Iy
zVH*FUv0NTVuYYh!z<=^&>Q44%E+9C2!~!w_JJ|z(>_A?2coSKyoShwnIN*dF9JO>Z
zaj*h|Anf)|mQVk5b!j;J=M1*DlX)QXSY(8_IJvku1-Jw_f!u;zf~=fe%$%H0|0(p}
zOyJ+-oU{qN@7r7cHu3K!{6)?EoAq*cGPl6u1OR!kIRCW);AY|G1y}(7VEh6CeDI<l
zHh|sV7*Oy*+5ZO<;DcYx{{w>u9*p!K7(Y;e2X4Us!~}S_;5z$Hj0-3T?@0fN@$(7(
zS2}+F|CS*D<odsL;THh%!Y%us<q5zq0{<5i<mCBBot>Rb;AgkfZ(dLn>}md>tA~q(
shP^%9=np#obAr9Fvw++7cfa_<1e!QG|JE+QAg7=J79*pqnjF^u0|2wDe*gdg

diff --git a/source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf b/source/armarx/navigation/human/test/findings/start_pi_2-mod_100-low_error.pdf
deleted file mode 100644
index c1a797f1ca66b3105a20946a6d6ea0f259472f1b..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 67483
zcmV)_K!3j_P((&8F)lR<CAICY`wBE5Fd%PYY6?6&ATLa1ZfA68AT=N`AW{k-ARsSB
zX>4?5av(28Y+-a|L}g=dWMv9IJ_>Vma%Ev{3V58Py-lxWJ8UI3-@oDxI|Em5N|g5A
z(*}YD0%XwLo&^~M9drYYQv)Z1B>z4~<XVe5<yW`tXBf7hSXXCD6eUsoShTP6{XhR;
z@Bd@%Jiq?y&*Ptt^G6%!bASE%|NrxU{QCF*$NBZ&|L?=T{-5{%{x9$U{U68w_P@XX
z;QabO4?Dm9*ROy2viQmTzwe)O|8bx8HOBd)zyJTwFYiC@_m7eA`uZ<l|LOQ`x88sB
z_g}xewI7c^B4oGUjr9Ne?_dAnACEgHcYn3^qxm`8cz2&ayp8L&uYde`{QLj*59dFu
zkN)F-JO152*pKl){p0^Q{^x)Ejsd?NsLdZ^n_V=&pPN6=kLh=HBH<6+?)Kx_K85xl
zI?eIp9&PId!XLW%9b6atN%+^X|M_uW-TV8i!+t#1Z`l9$neV;*uydas2!EKJjUV<r
zTQ?BC@AekIPf;e}58ZB~D5Dz)f9N(n1uGXIn}1XK`@DXP-$?)YZ;}4)*QY3x@Q1ne
z^Fx%;{zE70pQ22{_ubkvDazT6gg<n<--p|<S^yIMRZH-mSF_9R_gC-!<NWI#@OA$E
z1!%K>iZTg*n4Qm0Q6}LJ-QGL;LzGGQLpN*t8JW%RyVx@*Sjm18{<S+`+}_`!W$&#z
zf5-lR%MP&X{t#uf|1i60pQ22{AG*E&|A#1(@P}^grYNHu2!H5iM$y6&fbchWfSLbj
ze|-pj{TuFp$3G<*?eFJyU7vD{_V=CUxl3`h{&3IqU+($-FE|_9ggoKcnI%sDYN>zk
z&g(Zq|8G)yo=@q0{spqT>47BJcL&vbLo8lZHxb@9{J-`b81HfVc;6Ra<9&_#?-Y^0
z#gg}aAKNg|{B~~dqpZIfR-Hunwwt}r&GpaKuPEPle9OVw?^{PvzVGNGmG9~(%HLQ9
z^S2f_->1Rz{W|=ORj}E95woIvKgH|$MbL`!eaB~hEIixac4}{x<#Xwa@_onmIr_Qw
zMfn>m(cWi7fBv{5{@%^l-a6o?xE1C5NzTtF;?J+5eBbd7{c-C@!uQ>tx3YSEtcEDx
zcI@UKYtQ!IScz`uk9qg;_;)Muw^YR5?H6Gy%J<WIKlVO_ttj7jd_OKfSH39UcYHsI
zK3Bdd-*<fO&y^S9@2ti1{#Gh0->${qyE@-*%uit}%C}QoZ(9F2gp2ZhM}MNje)W>_
zeaAV2d0R(OzVCSVy;HRQ#ya@>1hzl#iNB>ZKF=?LR+Mk2whTKTf+oWE-Fp9J)r<0d
z$9IR%RWHi-9p7*L&s8tV-%*{$`!<|^+!KFKcY3R-zX)1U{vg_)dg!N)`TF|xhyNv0
zj_Llxn)rI><UHH`-f21eU#I;4t@&=pc>8hQ?Oqq^TLmmr<G=fV#TPrreYf{l=UZ1e
z*XQ5c>do7~7S#9VX-gBy7g)3=Sh6gC@iw?<%PWfGA+soNu|9&7k3EpylvFuDdH>g&
z^3gK9Duc4#ByY-FW{+P;ZGf<z8rK;={z0hWu4%OSMAz5Xv6Eb%T3Xklqy?`icu@!8
z{ZETflZ<gKQcdzLJa5VsU-+cdw8v_1|2@~YI6;qx7cC-185>`E7+dlL2W9c@O?k8B
z*eSj-rpF7<V?ar1BM8N+AkeZEoU-6l|3N00!_K2mC#4miEcnzmKE2s<1W9~)x2$*+
zE%L`;OFHpj4N6QV_R~Sqn$7!wAXkb)uH*;WxW$8f#x2Si`k`3Xaf=I<D>g34x8)MN
zDW(y{5{$V%${z}jze%nU1;^hM(};qdV~97F>>DF_1X7I1#UBg4Eed&b=8hX(Jjxxg
zDB{tXY#U8HI>DnR9-ZJ(<AyrHqFjXoq!^G%a!#<w#I$9QcpqqD*$D=nKlronp&vmo
zjX2oj+?b29<j-qc<{vMLX}s&d-fI56^$PC1Dd={kP%H|%T@MV67o_yc(|Zy6lUwgi
zS|<ly3rPsx_~b(1aTfN<!5<Dz_+;xnN2j%L5rPeG3bym2#D{4-Ta=i!b4`{4^8Vhj
zNR6Wnk$}k~DLLt`UN<J)+3CidaTbFVEN@)NG#D-d7V=HVDbgmmC^<!or96TVO)TVf
zW0EJA<hrr6Sp9c9rg&~$Y@K+mKU<%eQP=8UceJ>KS5Bw%KwgCPk$%?_#_}!-moOay
ztzXqCCevwiTa?(`9qWDsDb}dh!lx3mC|vj}w{o9stp)0%dK}T@pHGZ_uoXY&5|sSZ
zqEJv~?z-*=nmO>kb;*JEtxJwu8~#mMjPJSMkEFzw>TT<ljMv3`<yEsN6t2AM7i9_8
z5tLxHF5YWkyyw=b!%Sa)(_zU^`8yUV_}Ctb?MPO(yLv^766-Mj>%e|fuC?vjr5?%G
zMX6rFzIJWBf_-gnz4DA|bL*C)n_IUWp0uCKqs1QdO~kwokYWn19v#E;tyd0Dck$K1
zyu6GLkb--C>z2doTen!u*7PwbXD#>qk)(8})UJm{)NJdPBhsONK@n+r=;Mb%;M%!$
z%MqPhw`7<!GH7_s9$hgPZg_jt4VSk)TeldIm0;jrw!5Z=JJ)WC6RuplwqC&^E8)Q1
z`KB}+akwb0gah}YO^G)yL7V&(?mUyGcC8ET2ugJdZdhFi=ewoLVB%gfoeUGVkhw1Q
znJUhkgjRB)Z(WiJQni;}8>8>p3OCq<e9l{*G5&ep3MPH+O~@}wXPY;^nwrp&r2MRH
z-SV^Wu)Yb=z|lJ|O!nj<pL+9~W9P#jX%kxnTniHi_WAHO!4tEc(g|j2YR4ksXX2mP
zVdjTVsdy9T?<t{}IB?HP8+qb<JtY-0&xJ*)ZXsPKrDBCVEbg8u6-Sa5drwIPH2Fn=
zRJ<uUN&ZGou%u$(0zIV@&J?0WA^YLfIlER32jkhb2FrN3+J-0AbWD;8{mj?wB5(yf
zT4ZJiGj(>%&Q&yUzsE<UEzXW_==Ol)cu~lc9xc3QW}av7ztK*~Bg+)NvM3|kWJt<0
zzuA&w;fy6ITI7V`6Ve*t^|9xYTv>b~B=7*ChsRh?gPD5KvdEJiC!EM7Bq#jLQ}fGt
zFGn-ymj;(|JugZdL7<T2zIjttYdopv*`tTUh+VV@nB&Ovbx|<K@qkI4a~x1V7YRQc
z{|r8^*Hm<9T)T0DO?p*~8)I)ev&IcZ@egw3I!{KP&x^vbURYq$Sg(Ax*&|JJTo^ty
zO+3+7o8!%Z3%jL-<fAPpv@47})fWl8eN)yr-jr;;|4WiG^6p<0j%?%$-foFXzUbZ*
z9TvmUO;^as?YJoXtfy$bNocMmzX$f>aQx`tUL5eM--7};a<|(ZpF2Pb=HGl!jC{Yp
z3DIi!4V@DMo9os&F&YP^r+>Z~4K|r1<mmLg7}!%cpO*t$>JA;?04an8kMpF&50@wy
zez-*8#1E$=97)PGq$r$N!IR%U<z9P*H9A8m7(}utArE%x(c#z~mu?o%TgNUbq#l>0
zy`KQsxxVh4)#e53kbOD&9WPVEyJ1oCDzZz*27;L^HU9&oVAUmg@ziJElx)5KOHUAo
zoL>?a$4@O1qy<k|yJRTxiLvQH>I2awx@&yo<gDy_J}@>NBp%kNMHtzP|IW2g085h`
zcxuB2T{I~<Hkp##F*e;kihMD>auMlZm!2<gN{&rNChy>zbQSOKmd+J#@upamf%b@2
zV>4IuL@UG-s@kGJ?xC9<Nec0tQfNI#V^az(-qediDLoOQb4$(g)I=AFvV*H)N}cI>
zO<GwUdtL>zUb%h!y9BA<2o4HC>K9rAtsJ^87QBOPcHM-1V(hvpI>ct`rs%n&ZRjZN
zm~ool@`o_xp$&y6r43nC+XKqnC^4cDA+Sdf41bbq)-b~{(TWv(AJhETSi_;)wOwi3
zGo0i}dh>8NrKH7!VG#!ZAX?yghR-Ylm8+I-b{jOYI$oBG0%2{b0xSxc)KUdl6oZ|(
z4RBJtZ3CRt_Q8YGh7`BvU|XZ!(XhoZ7+f#!^EU6B*1<Eq0`d4<6!NLZBWF<{kL|sc
z$`sgemkg<Pt$_=A3E(AaX&uZN8ludk@ip8Xu5H$^gWi;ZcC5KSe8@FuTK;Ga^Vw!)
zKy0a3`K|Gt(Zbm5!CB{eKUi*SbBU<oT5yRdo~es6&<@`FC7tL^%Hhl8XplnJEnwJ*
zK6xZq2%)EbvLxMb2e^zB2AwCZk~YCNY7qwA#$~mznIgJK5Z?C-H9tJKtTw<oT@`q@
zF3LbVmfGvBYL0K|qA;A{u04QIT2qMHqQsJPnwtz!fF2K6gGjkl4{P|0bWm&fj4lr|
zZ0NFfnqf-W1&X@s;xL@GE>#4t*G1uhh3D&=v|8sA%OhbwAFPgq{iI|_M?G(-kA9*V
za#6<76LQhz+&IIcxd{AKXudtKn=>WIy2KoB)J5TM#L>72I3La#tvoN!k#<$<x>nAV
zg+;+aow&z4r2I?+)@nm)PF&D^>ViJ=th2JOo={M`o=9hp7KHJ{g5#1&3Pv~4%#jUE
z*Dx}@vg0+n+MF#enqIyaJU^{V#PbQd2szY_7wDo4v_nKXkNu<L3A#u*+C|Cr^Jt~U
z*r_QkLYyZu?k-BcR(r>A`vVP8_TELwpGj7)b~2y#-~LQYG1Zx*<P5n{7A1Mljq;{M
ztL6M~`E(kCdIk)xu^G6uNI5@T9R2Z}BJYhw$SIn>f^#5j$~iXNHr@289y2`k9jI*#
z+3yeR0-g58W06wMPkqU-WT!X<WlW~&Hziu+$%!++J!1cvi%LWFBE*~<Ukm+C9jh^0
zWf9`ANY&#2DQ4ZM;`RGhp!7gHIMr?l)S|@JZn%JsHwnVf@+U$N8u#gH2b&siqmEao
z$s)ce`4(t=l`K-r-^m%?L!CIo0lrO5G4-WI(G+njw5ciLo!cg+=<38NdbA9q?KltH
zq$J!O>>v7a2miU{JN)|AhCa+wq78hxsT03!xoATlhmzWcz74gaIUg%ML;Mzn--Zs}
zT;D#`D?WYU!P#hyITneX8viC&n)aD~Q93&39qu=4ygfU8X^Vu_z9=2^6f8=1f;3;0
z5FI9Xcv|`r4v?}F_<$G?Yg9Tr{6ay&&p=6N89%XP6)qlYO`~xLmW~|wXM%F_Z`g}M
ze=&m~=M7D?=@iP>Wf1TiFl;oM7J9lhjv#R`jlDP)Q!kFi^eG(Z8Gy0~xH>wV2-Z$5
z6g16tYCL(Fw37=pA9aF*ZjsmvYc(JCg2>{*XbsQNMPQ#4n`4o(Q~W!OYo_CF<~b0Q
z9NWydjL|^SCoXK0Q>McvZl+Ta2Jl7U;D)}1!KFkTW;EC@5_&}o(jdo9M~q5PFgi$s
z-L$H7*qzO&&nybN4Yb(_OG`7dA$RTw(g*^!|7_}nEl9(#-Ds`9zcg0E_OnZa#iPS?
z{6@Y;wDFVa2{%i%sgFlJ;LBd5I2-Ju6b@V+MjvJ$x4L1hw7l9S!KAI#bY_p#9gUBS
zMTjHMkngbwaZKXru=q44J7EsAkRs`Hwb=*U9%+gS3Z_8SfljkGB^nS6#JnsD&K$g^
z-;`{<|7(!-gV%)V3ZSLa24}+bA>9cGelg?gXHizCBS=9ob>dV^ogn8hQrh4|u>Vbt
z-$hD!99o_e!WCWofnd@7*W)3(+E|#hHXcdJ8TzeGIm0wJ%3;{?ObtqY)$xX0f#L@U
zDJ9N*>=%TDms5AFHv<y7bG;ppvPH=ir`NhWS6ufO9+ZoM74`Vl_%G-BF|MUMGy`Q<
zcJEjVY0I?lStkcN*H8Mhvc|fYz-8B+=s4$1x1t-5sxCGdR!kSA!}M&hWp?Lg?iAzB
z?JT!i@7&J1O*^-9kJb(D>TX38OHh&(9VX=<<zPDe9|mt-?|AH6BP%-edy~fB;fh=&
z@B*(SLw4k9hji0))H@I9oiZ>!o>`rzG(E|^^N`lP-aEL(M|kfI+-ll6h%pZmW`PHu
zF~_>+Tf^j}?zAp~awG{nj6XObos4u@lw{vVi5AwNJ(N&7Hy0_{S(IBDiddBfTh9k&
zS=<&S*9pqH$)n!WxcJddMoD>TQ@N3d7wt4C8ci09V)!;GBN-))hsHxtjwB_c(qr43
zi&bosQCR-QUAR-i>SHEVsx>j9C@lvA34tQ^Nl6E!Ndbdmvr+8fq;eC|mbMX?Ga8Jd
zZAWROk^6G)J!q*Z!mTx;wg9tBjpMw;OAP;<VqH-<HfsLo5cj|s`2IJ3o~{8F1<cFw
zb!uouATP1hXV;uaX(f0mA7`WB;jDshf0H~KQ$8pXyyWL;C3s-^SsN~;{;d6mjd7k^
ztI?RE&9x{JDw4MS7Q9;&aw@m+qJUE*q{4ROQLvgkyz=yDG@fjfsk1AOoEBMjIFt?$
zJ`c0@jQubJg=bla)gtgH>*>2}Fqi1uY;f7*a0P|efn!Q=^pbJ}iPu4Xs?}|PDYUu`
zJb#$V4jl*Wfhg!!Y0s(CpNnvcfn0=B3<S^b)NhWw;#O1lWDbU=58a%N#t)+xsohjx
zJIqAw#vbI2ya*i^Ihb`*f92KQZtlwTMjngM$F2{&DVx5~?jbD$jH0Q7ddHhUwIs*o
z>H#L*n>K@iQJZnJ=D90JixSQhDNqf06QyJ|xYwzO1;L<okt0UVyI5jU3$xQHrI0f|
zr4@3<r?kQ}A2u2>q>nb*Fr>7$>rpQVLPi;<*4r+`>y}#FE~+{-!n6y)A5^c~MMZ}S
z_?z+t1wBVb#V2+6c1?A_`d;&^o&hU;g@2!`nZc?1Yhq=u@Ew5lyLcu~v|7GjuzVMn
zcj}0^xW<z+>Fk8XqLo4qr*?6LC*}gps9s-<Mhd>rg2GOi5LMTyl{qOEQ%l2_DQ8eG
zQ!LKpD}~R_Mae#J^0fJ=6J{{$WjfI2yA%_cxBA4fb3~2|J7EFlrEXY&$%jg|@JP8e
z*oiO|J?Iw+J;?Am*o&j3LUd!aLtStut}Ge!!67+aeK=U2(6<KLv(tk{r#%Iy-Gm8~
zwi0B~lr@D}G-YvN5)G^}IX1&)q3tHJX=w1l;7r{(I9$$QB8uFaw3MFWB@Ns#Gev4m
z_Tcaa4cs(VElMcgG-<sewT9imJNW<0GPWrE76cQ{{sT5PkU9)=U?A-jGSxLi1e7_i
z!A^0M$*<8=A-iCssY13x=IE4p5ji^RhjLme5wuTcdJe6c_zg&e?3^n-2c5WhaP!Mx
z8k95~H;tvS7l(rP5p1(ZlCqa>&H>A|?ny>k$qd|vsnf`?kjUYI!I`UdsvFJ`B=M9{
znn^q|TpvLiW!i3Drfu+omJArkTN*NCKyQwikg~EjMoBeYEe=Ia*80YfC|UGZy3S26
z00h^kx(&43*gOY~F;DU?L{`r!55xfy{TTds`9ApZ@_q2z<^34RDc_tWjphx!_L7pm
z51rah--k|VZ}eDQWH^ov`F9%Ql;i|jNj%rs{6ve8Yke_zFcN)Ex|*2eBVQDfe9BwJ
zEFb!_BE=_cesXy&QgUBsXUE%1zO$9YlM6uiTI)EC<$`M+Ms6LB{Q~>x$!l;`FG}8u
zw3xJq{^&Pp^9@FhPxwsfKU|dbRMN?~5__&uZpfBS<zsVIE>imAb$oTi;~<G92xIez
zHkwb;Ynnr&_uTj;`p$JMb^6ZraDo4qKHMV{fZ)XCw-6jHKX60;^c4pog+t!tMZhej
z!FLFUoYIjI6vNRW(@(gmx%zl0^irMShfV)@V|17N=Z!`eIoaP7x!_kSP|Ci%^sO<3
zf{y&g0I#ltqCvS(L_kZE%drIwM0(KJ0}GfPlz|7U74ZR6Lq+&j1}_{SCHEQK&~Ok{
z1Vp0&rcVtRF7({uM^aLxpj6>Nu5b*d235$$%JIqJAgrS`9ux}uXt<s#G9)sC&OLgB
zSw9tU5=lQ9fuYUT7(OAjqh*q32DYqLhBq<trNNBjr}TKmR!M(QY?ZVH!_DDrWe|_)
zS8u5DirZ;+Z*e^hifYFFtX6(NZ+5862p&2>La2~_B$r-6NN)lHlp^6Lf_`8lZhWYi
zYg^#?Q&CS1PpFEFS`>y{L1^>QcOb+nDGI=9cmY?4R>RY}!nhjV@CfxfK+4bPtpwYI
zV#eMCgp;*2=2Wy<Gad`B2aMsdsi?J;<C8&8dW_Kirs%iG42qk=FHMdT1Cc+WXDH6D
zA>N9Sc&m+QKEA+C*ozd>w<x(h68IAusiFdzEriIy{2^!`3@==Sc~<=4YIj5%a&%Bo
z6~%b0%%F%0Wio6e4{gDaNFAzpNu~}}Ol71F#U@tJWjh%WDpmMoM5y%M6GnW-cQ%+9
z55vzY8k7@6jE+J`SEf)#gvwe(qvKGXabq~wkX>hmb19$|xkVN8+R_B6sMyFZ%K6C-
za>7id@Y+Smz*5)zpuH$UH*${RL{|_mla4CVH<FJ0RxI#pC*zj9uY{s|Fp&5Fh0(_Y
zZN?raPa>;m>=Db0lA*N_)I(`SCg=g9RZ{WMEAJ*l%c=TD-c5vNL(e~yc!Ox{_#=jv
zyS~rR@*FW{7}4G<>m@YW3I|`LIPMuQ9*Hm&PQFrK#ujiM$uTjin;x%4%AspAH>1j_
z2rf#FoKNOO>4=<%>3)$y2nE-{oSF)_kDQu_`9IOhcz?WH7a`>d@%$@Y=D}awm~pCf
zN(fklv84<c&3^?)vPdz-%QSo(;Yv_gl$fHD7#1aV>ZKG+17Zx)A%X%+5;G>4oWpdA
z)gD{6h0$`Tj0|Idl+rc~7%P?9VL&yh^bb?WlyXE27$22Lg7lp&*~Ab=bxkw|vs4Zc
zl6TaAn95W6E(W-Y%84;xQ6O*T04Y~i8|#KPsr(zGjZ!H(k@XWFQyiXM%<SRw!Wes{
zgdhW?LM09HCy`ThBqe?aSx2j#nN<=j02fs95(i%iPKRZDmQtX|1SL)x00b(x$^aQq
z`B%Z+JwwYf{lBufjPY8L_hmGJGA(Qo;_sC?wkS+EgD^05ODSj}O)(JY3X3q1!Dbhd
zA1dq37{;Z{xJAj?-Woa7Rwdn8=9(W{jvhA|68Vy{CHgS|h{=Jmm)D0geeeJ&aw=<W
zU?)=^qQPidxr&Bd@XTe5BjsSOBM3-!)UcSSsZ)F+idcD-i*k+1x-=wtS7PR(<nVbX
zGMA_lJQpR0?>bv16E+80nN`W#Z&AjUW*X;p{yjI;WQ5@Z8}^&BrL!9Cwn}+j6lTss
zY-q`?+*w1~cBR)Ejk`+0T{lwlNpdjZ1b^<DA!3@rNF4r31YVRjwoGB8Nm$v$Heu93
z%5hR6Nt;@jDM|a(A~H$aw1}~RBJcS?JJS7?8*R$c)&-#~ZR%KYYoAKNK9Z7O($=1i
zlyL2B<!RG!XOX9^>tN!!T`A*>l<D9u&Sa+cz<+0!c8LnJw1=)hn6Rm%zND%s1K!f8
zT{-fLkn_U<a0Dr^6V6MlOfV`X<S#<<QcA}Jkc1NZkASj16AED9PjZI0WXxiQkJt~~
zCIJjAN}x6ngJ2O7wBZ!@fxjdy1DiyQIN6DS5egBthyrYK`LA|-T0ZneNwkWlRRg*a
zUBgS21-y|QwubP*gm+l2{4(Jm7G-Pz5td2c2M{DybFo_PLqnutp-?Q1G`~s1t04~@
zNEQc32~|Psi49-}2@-><txz*;5H(^l1U3|6zc=&^gL^;-9foxA0`ag6YAl?OBb4v>
znY%g-nG3R=W0CebuH*!BG#4SRuR<nylLTGz3Y|aLAb1nYK*>TtF(j7*CFKBV$flC*
z7>QgINLwsGmPH7r2(;x`?~|sW>h*d_<e8=}d4$O$V40@AA;`p&C$QOM+_yp49^bkp
z@QiQW66VFXUJ3Fhv-^65CGyNrHwUwZx_J(9Zk<953WO)#cN<QR!Ov1yK0!Hc!~2PM
zV+`=(qtxJxDd3>>-pm1(L;%a8l|%r%=Yc8J2Elutty4nfJX@!PX5wWsaFhxh>4>-S
z^K1x82EPwMmKI^dU}CCg;WPy$PIQ4e@mbzv)-{B?7AVxBj14wwwS%9%GpsB~F<wV2
zP^5h8kswlaJ~V(x<-n2MUjSGJB!EK5f)OGCv<$ca1+Zm^xCIE;0n#X-t~7N#_Xg%g
z<A?CR3<z}v33dd@Z{mjGk8<!gd*OH&`j{cQx6sLKoMb+Yonf(A9}~`5Q2Z7Unjs>%
zpwbM^HNdGIAjPx*xMqVud36@xnvlVg)+8aj9YIQnI4PauEO@wOk%}1!LC&0*c#KwA
zlt9)Z5FHI$1y*McEF$6Ag)uC?E42ZDen$c0EmF>LvUS>qs|OQXLGLX>PFaEN=0wHQ
z^7{_@7q-0k1`XW?k7I!c!rpgm5QAY9j4wS~w_L?%>z0s+T4@KQBoPk{UoA{T+8+xw
zF(_k4Ry06G0DkcRX|aMfIi?{Oh@)Z31@yQmi5S@#xtLv~0XXhYS<?)z)q<TggpD_u
z&Me>)j}5=l08&vHmq9sq9880Y7GRmA5Ki*|Az35c&Vj*K#xWR$0p1BpaONhC*rMb_
z^&;FTkA@T6ny2J5PZT1K#t%&tz>xW8qmVzq^b@QpjoXaczz+oziH}+Ysqz_VPmEQA
z%ohwRD8~lXO2c}gxd!Fj5nqckC^>nh9)%nmqzzk^ZP@{R3XhhOL(0YZ#mbdwaHABX
z5{&lV7)8p)sKlqei&05<Hbw<LZEZ{uZVfl=e1-o@KSe<V2W9b&Ai_JL*b+{+LL(+A
z(TWYJ4~1r26t77N68T_LiVsRz6t1!;cdt(>gpjR)Ks<f!o*Q>a*|@QWeCri1ir_Xh
z`TO1^iIk0Fi--5KaSQ~2nsF_jb7Keyn;5JGeQXy4P-qCFWIVQsK@i$D(GakwZE`@$
zy~}Mz#M-CeKDEzAv}%`)2(vB0iDT<=dgHaDo`1H-o^6lC#(efI7W?@bJFk+o@3SbG
zvv0FFCZ20QTtMk~HS@fAuI+FMM%){-LaLs7V-_jNtT)rI2(&ic4Iw1YvmM6k-&Xi`
z9mb^8VH_gW%RYh=dqsxVX}lJ*pSGRGYc?z9yiVg-x<#tnYJFuzv)664ezKRb12<7G
zgNGwsW|8W;x?@CRyRPmS(b%r5J4Q6N>*~o7&F#8BV?=Yi-7Q9RZMS>!=-O`gWj0<E
zvgigw?(H&9hTPj_zJ|8)6S~xoILH@iYCypdJ2#D`TkXcwY9i}F!wX()1`6m$-E8X?
z%qSDZ8cCTafUD9Krw*;`2+~ER(c;r}<Hb4B6`f55uq(-n3gRkmA|)Zu{f-D`Dw<u9
z$5ckU;)toRc18goU#ZjvrL^3f_54(gyVVo)jF$B1<XA6rMCyTE;jL8B7lqHR6LY-v
zj7mlSSR}rqPRx;Aa)vTx;z7|B>d8k(Z)e(0@@3H#qsgaBSNJ8LH(imHd;#?)G*3R0
z7U|<D)te4tytcZ+8~Gwzl<0Kin{A~ARi9WQ#US$O*PGTpUxvN8o>7*TlSQgtIR{s-
zhB?SpfoEz*kRRT$J*^M>J2#T1)F)>!)n{bp)!3iYeKS75jn_BpL&G9mTen<<&G-<l
zvLVFjk%otZq~Q1SX+-EBmWPm*56eSH3@i_2ujn#8z@*VX3=gpZHp4?QcQZaXM1HeA
z<W1R$6hbRZ-)s+g@b=C2u=eiC0fZ|Z=APdB*5}GUsV+IXGCw$m=Vda?H_9Th+raSj
z422o1_cBiojIXZdG>9o{@+G5LWLBzM3~_GXiq-9xo?ByPzUH|b?|QG(AP$>I`#fpz
z%dy;Br*Q<K`XsZSty7HT+4>~2^xPR&WT=wgdAD~jX^1my5!4|E;*y5-TI+6GkFXOl
zfi_8N9Nwx+FvLp~aA9uN2waa|!jQ~Z6bd*l!!k+W^|um*xsh<QdFg4eO)nDnUovr}
zBeUBBPVjKZJISe`AFz@~nllfFCpa<HBLu^xaKjGY{n~n@>VTB%mn{0s%6`e}-^+9X
z&p<EJMfeVSU`^7OkRN}xKKXI^ui>TW{);1{!!&ff;OqzrJLTQqhpvn8nDjyKNqlxl
zLzqC->O;<J_+|J94Ih<;m#&>&1`NEHk*t4!6tX^OugV8>SIiLoOnpc;;EU=wnZmDx
zLsT(B^lJ4X*@%btf+nCx2qz}Of#f(_1g@9|-a+}|LXykm0q-0@6JB!Q0a)PxDQ772
z6+D5xqK4ot?1TQs<fIObc-kL9A@2u1q*DWr{XTe)q-V1aT_bq@_o0wzdPw_}#-C2q
zj>@C-vJ&g!B`+)hF=7Y7SG!1LOrDvG0><D#DkBQq!hJT07+(Za9xphU`|N1tcVyF^
z@oy3p95u7o1fh7BNhSQ?taMF3d4Q7){zx1uvjhd9fqm-n0FQj1jD>*HzR#)oK}nr5
zcBbpUR~aCN2lS~c1|bB1X?Y=%saFIRf)e^HXDA{U`qU|sCXYUehRBeJMZsWT1X&cu
zqAblzp;QREAiB+qkr|1AGZ?)QhxA2JU_8gMNC*;v#&c=mQQx3nTKI@{T5XO5wYM)_
z87Rj<FrcL5ujpYP;V6M8qzIN+T9&Ii6x7l$89x#D(k}+agtT8$9S}Pc2uOQu&5<xk
z_)_kfi>E*UDlP0K&Uj)ZGM*vKXHn>3M<`Ig^k|G=p~QiDDVnIW_A>*H`c<opsJwpF
zGDH6VS!`3kDt-o+red4YM3CTDdlXf_^^!oSRljvXARMdTQXuYA6&7C%;5q`E%M{ZU
z?7n5;K`2<i`KUy+7*W7pimy5XD(oaFWZ~9H5RqxC&7iY<YTObIM7Avo<5Up-7AR&I
zAMUGrpp{dm4G3X&i@<2Nj+5fn6%z4!fw{(Lw-EMQrvd{0`YoFfEQ0`Z+XDxQ`1VqC
z;i8atxM*%#i4dgN@BG!lvC&VCNXK3#!H9(<Qr(N8UIepyDV{PA@9?(Dn9Cq>{J1kJ
zLJM>2kNhYI3R@KM9~+=7i3k#16oyN}9`sOYMXc!}<U<tUs9lCdgsd*SKuS>D02Rn}
zKM63nhr}KULWo)8m@XqCCKBL=IUxkzE{MdU1dsZoYXhNTfzJ4llH=D6fKcFt@|aUZ
zwD7TjEiY15Col6F!jApa-a=@ySGW-Zr4|S$S&j(jK<dPx(?~)%&x(=`$WJF_f-)I<
zpO4JI302f~c2hzEqP7EY^dqv{E6#}F-!7{hV#EW*l#$)*t-jh_e{l@~pGNF`k0yfO
z^PKSW`l>MYg`?W|&&f<~Bu2w83S82RrE*#H7*g*FN@CQ#pOt?wz=O&!M)<x1b3`%z
z0U*oy4e;R64C8_c%-PiEGnv2{x`bo{533-P5dyGQ=?TFCQ~vIWi-*v+mG<DK+&0W@
z!RK-fb8arnA#yAZVeD2ShMUq4LM8Qt<cLHLFWd~Idbl-;C9^@iz$;+j^a7?pT8S6R
z1jg;A(s;~IaiBpUg(cb-3BfldxLQl(Vtf{bExhm*kVE5zr+_heVI?3LXCWyw<poLM
zE}#SRtj&uLd2(oIdXCRbP0#U}S<}nC<-`vFj#(f<BWDM~C8Op_UUIuM!Ay2o6s#vw
zq80@#x-c1~-XN=Lp;+^0ki<=>YvpFeAK`ay%t)!9NbmAWl*fO$>3U%<*&?AEa?KW=
zH@YDo%`0KOK^8JPD}N|M2EDS%Vc{ga_)8gbUMb{2H4jj7oCQd=^U4?xX!Jxk&$U97
z)uLoFUP_cJ`TJ-vak|2|m@Md(wvB|sMX5B!_>!X$lk-*ylvur136xkq1$8kW(pzOw
z##$eNB##;4K506=k!iUoZOg_C0*Ct$!=A~WxlWZ*iR-3Kv~rD<Q;CdGuN>+gLDvo|
zEt5`H8$(B8s>^bV?9~A6XP#_s@}>$;%z^dFnMR(hSI#tYX}xhHbguiwI0Ob)t*Qb{
zl<k-z^DvRw8-)n)DaR~f0X&c)ya*Q)hI18#Fo7&%-?F4fPD**29oX)^B}Gq&vy!4G
z)=cOS{ffE^<WwF5-f2i=UbSyo(s>T}mL(l?^)B28*fv?>;dm*{+qX37d_qTQ2z1Nq
z&Aawvhc?oo-7(~95tv559xbcQBzlNQj~_r%`zmG*8FOSYx`OGD9nXU2FD1}>B~2sA
z-jy`%I2U?l!y#GUJD(~{=wB3~1az>I9?k^{uv+<}z|;3iq6Vyh3q+g|Sl$biA@z9g
zN}_WpRNjRq1fT=2)arEHJF~0d2lrmU3{zd0zzxs^@4o^wtSTV<IP{2KzzjEfRVr$L
zKrF&Qi(U9_+ytG8sgZlhS|cw8X&q6Jgt#FT4yCNZ&E~T56ZT?JKCm(Jhlpfi>PBn~
zh=@)Zz;L*n1H|e$T$uR4^H>A`t8{eIZHrt<XR3GlY*2|MaYGzZ#bXH07O&jzbftI?
zzQ9AW3cWz$2Xc~Kx#2)TSp<$_s@Fg}KcdW8Bt3ekX_}xcQBnrK0>z*|Xk`zbS#S<`
zf3!e1$0jHo*!f){n8cd#PD>{7XcmPFgz6n$Iq5LK2PI`D!Ed6F4nzjvIId7m0O%Y+
z0$7i!7twl5z49+`UQ{kSEZsrDos))buk3c1v03})Md+Ya9|*1JAbn*zhel)xfD^IA
z(2Mv*?zF@b<H%hq4N#DxQW36dn1NlPrvO+A3gkO6m{<hqC5Wa)u?(jpj+4_tM5w1I
zq=X;Fo5FS4!ffdk(@I#WMIzGCqi(qk0-S0!Ibd8BE*OgoMP}S}AcrwEibCZw!Ia4|
zQ7?gMxeMq5cw0ds23cx;ixgu)HB^^Fi^yJHN&i6qT9kB|10c)`1pp9YE-x5y#@s{S
zOBga1$9fT^>_`$m<Lp5gGF%R>a~~$npx`s9Zym09U&5@p>o&NqXaRE!ih>tD9Cmv`
z5+s|j-F*j$OVQKAD6N@`zzIB%s=Pgpm!Ridk;a6lbCt0ngk4Z_QZOz$9DfIq@Vw9u
zfR*QpS0<pI3lHJu(&}Y)1JjA+(q6*ub7y>I;`>F7HO%wo+Uh+AE8pSrJ2D8+ofvX}
z8g$qFbr02YdkL!0GcfJ|iCyw1CRR$f8z2(BKpOy~=nTU?gth2SD@s}wy>K0n#Obc5
z<;{((JMl)?^{QC+5;CM06vUmoSU2X)U91->;3nNmdj}?^JMUG%R(jz{q<zp`7cDA*
zxGSoTfS4|qEkQG#C=`Izbl0Qc=~=KZN1HI5hidq}1lH*VTmeAOPfEvd0lS%J^ug+Y
zFQJLL%isjWQ7;G#ppt%4?%c=>!6n|Q%jrx^)K5zCPdY>5s=D9Bbm;Uhz&+rzx>K!q
z@ZfVH@F5kGlp}#)-Bt1gK(U{ciSgz}Cg7~gNe)oj;}_D6Z;!9Sw%yw~pHFyPXFPvl
z=(^BCh_m}iA*TqC>*N$-%8BReP7Fa}{(e%(7$D|OF(R)A;tRWy7>GgqNxAalH@J6e
zTBN|7?XI#5G@X4=xRfbL3s(7~rP1MV2Qc&Y8|~CG;nU5;(4vr`H{>CKqPIB#OS)JC
zV7m_jnMVw5=SJK~WFJ-v&`X~bG8F5Z7~029nVJ@1wW%8Iln>#f&1JQZFJgXg(u#nw
zouUl~sc*I4a%UU_Am27i`*p_w$$Y2u+G0p3BtUwR2%ugk08!TKlmHO>PH1>J>9irB
zyW=<7FGm(p;Xf&Z$K3H%Q1W#a5^mlVNkdF}ouGuR=OKFt+P;om#)H*i&3Ldn(HRb=
z6aNs>J}(7A@#`ibUjKI65YxXdB;fuZb!o9KKwWjL9Z=UH3k=kS$sz<t-l!~6P?s<Z
z8PrA1Y6rT?8PDa+H+eClt5gC;bd}n`QVS?98<Z~XBabXvHv|yHst%>Hu<}ExG~G+d
zNzV8(`AI8cX^B#uSbn0^E0(Az4XjfoDm4wIE=rYSH4JHcjNU@sTTrMp;<3cS8>L5P
zX$~rytlUwmXs0nl>S`1K$+3|Mk2+yXj#HW^7%`~#sAAOsHe0FKs8`}b24hK+Qq@`Z
zMA|$<w%p~=W6)N;2oSUtl<d^&VSz98dRUB>)nr`n1Wv;BPQYr87;gR-{#tcH1^}??
zmBjipdPuQAO}(`cj#bYw*0~AF0RsDQ@E7}FMF#cTt`(tv+X>aj$~^VNWc8kUhqA&?
zy;WHTh>zJrg@WqAn*msQ6Dt6#-pvfas<$;N7#&}HlD|~usGjXv2&vxntd&%6f7Vm-
zu#2(=Q%aud0?e*n9H6Tg2k7brvma|f$%4TWQDx;|9jP>eu*_5$Nl=O^4KxsF)T@HE
z1r&CJ_+~&AO*Sly1*6UZ68m6mH@k3Xw>puTG;2SExIh`NvO}@bR~f5V4y+7X2)inq
z7s9S~!x$@%mGunO$;!aS0%mD|V}Uam=(2iQp7YFr?zB_L&c|A6v;?BqTA2zFg0-0w
zS+A{3jx6eyCP@~3D~lxy!=+I(2L?G%EHx|4(KN~$bY(ncojTc9kE~=@23QumD=RGv
z;*}*gOXiiS7e)1UdoW7xZARk^$||!m%lDP(nI-;Uo<2ZIv$Ad^+A(P5W--AsgtOov
zP2~ql61r0ES+=n3?JR9rHhEM(EVDfdBpx*GgVbT}=eOzPz>$B`!{PciJsi%5B8ob0
z-iTH7vAh*53RxZvmW?d02TDsG@{F+jWcf{4qOyD|EMr;z7ZkeOd^D(rS$-TA%q&+A
zL#)ajlw~)|Uv#i4XL*%ax--2_EbUodDTY*)-wH8RhkRQsB3j-r)EO-Y8B39t6OGkM
z;b}WS%0<&*_}Eu@>sDY?vU0DRN_Smu=*P%@9du6~99tn(TpL?4Ra_f#NwU!EQEp3C
zgDux4E5^$EiJG!<kE-e{T&M>~eQa)4mai>O?5b`{SM5vHZ{^KJf!t&B__B&_d4*YN
z*Odj7wRp?7%xb;xKj+vW3vyC-BxTZ#-Lo)oxw%<4xLn~XE}Xt{Rv#{3I_nd=pv+Oi
zxcu>`a(tA}o~4k>t?$6JD%XFOPp;qq7Fb3A!SPj9m@CQvWtz801eS8nPz4r#u1E$H
zhd#D&2gaObrTMR{GCj5k309%5FbYPOMWDs;rE1ne$ldCUuTpfzDt}$U8>o(r0FN&f
z&_1>(5LVf)ND-Fdu4ocg^R6HimHVzp71ji=Xckxa6YqJ}8LzMy6eB;j*cpaxDZIwB
znpFkhFdnO-bWj+bkvzdJ)I3tO4-2fj0GC*Vy+VXoq@7_zhYGn@m=SBeGc<|S;9ccV
z7*bUcPADsXY++EWJYSJgtWK{$Di*M>U@QLOQ4v{=nkyBx<tV69kzI~rDHZ<ZD1~xV
zd|2?M;>R2%Oc-Fcn4Qr|UDJeERE<DKCDRIKbE8;DuoVf#TgU;J?NvT+k#cF`N7`8-
zcb>&ODku+;P+R1lHz3<ocwb2KxrYE!;wwzhQB0#^39*-sE#T0BUX=lftK|r2#ORu0
z9yz?Oc*o<#BcNg;y)kT)wnT4?+f<$V21`2wFb|zj6{Q&m+qp+_I>4<E?im!uZNf8<
zM`*@vLf7QEn^C3S7_vDz!>OoM&Ja)q6}Y-c2wdeXuPyS`v%~|UV?h{<pFKcG9_T!0
z;Fbb$<JLTl(Ym1Apdja(7j%XF#w|Yf&|u#5h#y`Q<eDPJ_y8$`U>V;T>Ps++FHWav
zk@3t_h#B&nx_3rXPj#Az1?R2Gr$U8S#{(mRsbMn7M@o{ksrw$tz1~hM!d<c6-Wlu7
zfbjL&%d{j#jK{MwhR0Vm-=_*Y=Yy7k>2%R&<oW^1Joo5!KEW#jp3ioK$%B&N?57sb
zBX?QR_Ao0{K)!ot#D2CEu#Y)ABEl>3pT?BR4WLm*=>xRjWO@OOKAC-RfD(x&%21#Q
zs<If|hg9%rF;{{E9~{`!=!eoJIC@BraxQ2oti%l1ACF4jpcylBI~=*4mHV;mt4I#X
z7I@~m@?a~hBoi8zD-DG<>`GOk^_)+sBS~Y+fq|c+(q!m|sazU&X6Tr{^l*YY-@Q_F
zD5Ol$0eGb^yaQzYI8sBA7j%FWzo6tH2g+3?7<t+om6ha(onqRO4@8;7BRb~;jJV2l
za_013eEmCe_?0o`46mxRDhCLj@~)iO_ZQ#k&U}02YWZOH*{Eq|`k9W|!Su8IQODRM
z8pCsJ(i{eoh${JPkuq;g(!u<8rLg&6wwZ4IG03c@c@K2cQL|FcnO^5iCszudGkg3J
z45b5+t8)1kB}9tpem(&7GNqUfB;O!G@JLeZnOUokq%>t3I#a@@1OgJz?8GBTnfj?)
z8K%|Bb9AJ-(omO_Omn2U$H$&J>4Q0$IzE`$trW~fi4@Gi!9mz7wbLgvFll#Rls2{$
z(M8D7rd?#UGnZ0U5NDS5)P>3{ZKbO^47iofx+uw*j@H<-VVzmoN||-ktgp0MpU7fU
zF0M}?YFEathYh%LdL5r&)~~}RTxr4n9?_OJ?8>*60;hayq#rxdt@UD=$a7N;^WiWe
zSE92k#ag=9#J!^QX%DW`q@V5FG|a+wC0OemP=d8?4J>aZdoN0;pG*jM<ye;_Fvq$?
z0ZG;_KHxSQn=DM^tCuVwXKs`%K)qoeyu+qVx66^F<Y3!+B?G0I%<GGyfgP=UeV?f0
zSXup!fW3~fL!%NVfCJpEa047Wv=ba>k?z7CaOPkOo?uZD?m_wnj)G2){vw1ipnwoO
z&yT`NaG2T)Pr>K2;Vn2K1Odu$fRtaJ)dgS1vy@5N@-{kZO$Z?32vWjKKrXIx1DJ4T
zYzu_K^H2p)1qkteFEk6sQCx@@&ctqct^6X=17!jpfTPeg960ucz~P8s6iCM+Bo}P!
zlw44W3y0@GXdsJ_e2{i};jEEQ#etgFohUSZ0R%$0B#zj~!Y*;<kqh2rQDQuVK*=9U
ze3pCb76THL%Ay2+gtp>HKNlj)`XQuK60;>JIU?O0%t)8TKPb;#@G$v9Iij(3OT?J5
zbqk!9v3)BMV`z9k{Bj}MtUrJfEz}#oh_@q~0}6W-c+R4v!qFufP__lZvnV;bw)Kk9
zwd#|DGueaU-=$Pu0HWv;3WDv(K5!9i=iEA_u+yBpC}RUJa%frwaI`4bC<r8nuV;fv
zTBHPm(u3r}u_~-3hn81(OpeTa*m#em1T$sQb!dwP{^TfMLU5?n&H>9j>rCkv#Py;i
z7}QXw;I440{JJ(AE586aUSL-a=TsqLElNUf^{rcuzi+)#7=*sHNI3zxITj(ow+P|2
zD8cf!^~v$m>+1v<P>of;?hQ@M5#L*gV-81Ip^`01AeTh-+0{yHG(9K~5nRw`9uJ2E
zMss2n5IF4!QX-?(F_1Tf)hR&4JG~|@!rRe$laL3;hW6$cA?{?cK`62S<AU%!8>ZZ%
zv_aUp1C&@Fs|%ta?kFmOF9dwMXbmF-9w@2NSS>pN?rPbAZ&!;>d^;^V@$FRIZjoXa
z3E9tYz!VAj&*6hCbiknay+a6kR>moq!9~cWJ-1%TiIc507(p2>%90FaIR{}4MUaS#
z5*x2<d<2L%X@$6R1RL0*Bhb458J#E+0&NUR3`d*(HUdB91aYyJISzi-f{=8?j~C43
zqAa$Yf`fHpQwXop@j@?5ONYO<a4$XaD};=B1R;haO%HGX!q{|_6)GG~2keEQIu{`^
zjs)ll(gynJ2!bzQP>1DVQ3l$HE&3F{+6Fbs7Wo9!c)^t}N@9=F?~vddN5P(wv_Ydf
zOd<uJ>RC6b09Hj%@!myA@LAo`H&E{h=2`?f!QcxAC~Pid1Fo!eI8pS*zZ<Y-$4ARF
z*f=E$zZRqo<JN&PQaHFpvEo&{$O})Gq{7^F`0fjrcc*j>ccIa;F5Cx2oCz>mVFd4#
zp)ZBF+&AI4igayr4+#=#@lL6UhE%b@)KL^^M|a<lle0zB=zsb8PsiHl=lfURQ@q-E
zli#P?dENd#T)+PFfBgEVFZ(**|C9gszy5rGA+0(qqhx*IXCCs4l`eS!w$n=VZ#0#y
zPnxV?hofu-ff--nYh6oG1#ubtWTrqM#1vQ}BRl{NGgEf!L_y!C3dDI1s3z_iMR!Lp
z<e|lQAmRul@65_F#MDHQ0|n(ROzK?Js&0alcf(~RVw_iDu1B^$B3{tgkKrLgg8q@$
zvE{5Wzi!J%V8Ab9-4qQy=VzpopG@wej@A&CdoF*u6EpUbg-LJDr&OZ63LW}R%8!rx
zZvK{=_s14k!kh7@J=1<8K9@3<e(Hv33cg$~wmA9ZmqQ5vyW|Q(swZ(k%h_MWmLm#o
zEvsC@#OE{<=0Lhi4hmD4cueJLs)92GCo7^2)r1SxsH)cmF5(TbCro1s#a;vgVB5D!
zCP9-S)E#Y4g>XnkK})j`Si;Z6BD%dP4uH9b2>0j;6K~JG=bM2g*GJ^*RK(a<23>T-
zF_il)z%S}*b|`O`9uNewE5ii!e7TaB-2BzSvP;Hus`c9rSE9s2l&;J@`=$d*5K`J!
zC;vtMe)A=Ysi`9=*S8%}B^1*9Q;%zj_iqM@O>o}q#$Dmxbwhpyw#v`2pnvS0zwV|T
zHrWjXVv7BBH~59Q4S&kJSsU{=9Z}m9@!CJXiZZ|J*rCO6oBzz1nU9VCn~ppmPIN5F
z{I(;^x;#dHX8h{M!Sb7qJb$J-g3{Wz9g(uaW9p|YA$4&5bw{3W=cA51@y2%@m%4@D
ze|Kt#lFBpjHytLw6dfkN^4ku94$G7EXB<xZN&DBG@;F97$xj{6--=d4Fk7D4KNC4*
zJH!9FlMZ@AC$_KOce2d)!)@?0u&nmm;jh2ME5z6d?dzLPmPyRKXMVEAYF#|P>6X_M
z&b*&>U-`G)#{9U$epcB+-D<z-h|3QVDnGyKIvn42WL+HGkw3p!{<?0>-+YmmtEnR?
z*S8%}YMyuSPa){nt^AvgxV(Wp`E$F@`}ZAh-SKOfzTNo0nOhnd*dc8*-*zA-b6&eY
z1H5*p{H`NhV?84Wu;A%gv2Q!l(gwBUXO`3bP*nc9qx6}fj-cH3T}PB4h1&D8K;HVd
zdk(tN$xdj`?>Y%-sYA3HB5q2>`psEFP3%-hQs%cE!E`8Wap2t_l;3uwrswL&q@eTL
zj?ehe2Y;p+<U>RJO-Cw{)P{=k?NEEWcYQOjwhsmLw>KLQI@k?_@4v=0owqVu_janb
z-`?48PHy-0n~T3!E5?U{{4)ZyK2_%5bfji&(nm<SzU!zcztq2fMu^!)_-!|A6jL`4
zu5Y^`2a(GC&xjZKRQG?=k*@-0M^f(d+m5q;JRW|ADdF=u@tcl(bqsX`<@;02Q74{{
zlQd`iOP(uw)tEZYU##f)K7P*iKz=`qZ7##g`#*-;st5lsc^_W_1zE-$6ev=S_oB#l
zP6*s~$#{-%v3AKeexp3nCEK_ta(ATN=?GGNKa3t%*}1bi(`9>uUaXt-+A0cSBMtp#
z*x}~0%^)d=hq_s<?N*GUNY^%_FbmFWn-M9rmQ~3%M!RmLnq!!*=Gb^lO3gZ~pL0|z
z?KCv9vO=2|D_T~vyTx4)iVtC_%{UP<E9`2sZ7WF%e>PsBv&m|RT4yNtoO6t(*b*(W
z1f_AOq808u_J{=qN(jPu#1dG)hI~+Wva2ap#R03*DpchL#@fQUqB$~E!$7{$h+;*C
z+)Ovh?hd(`Zp8C8y%!znPHo7$c%u?;#iHE#Ukm-~)`%=eB#&Z(J_m(7Lbcw}#iP8h
z7KJ?W3>|Ajp+`5Wmk)&=(Q;bxB><pqs27x!!D^Z0QB?UIau)-~y1CrLF!naDT@`}Y
z{3&5V-Cx-Z9g&&MxzA7rScnE;k*VO3G$J2CBC}8x*lUjfgFt-0<r&kMI`07MZa%k8
zX^i)|^-8^cRIiaReV8FMb|rE<^5_EYk5lYmgKtiuU(AbeQnd;-xlz*AEBxrDxwqUD
zC}Qq(RIs3Jxhh!DwkZncW=-3sP9saxs!J}UiN&aU?zLSLSCX)dNy%knNGjeei$HFj
zS!%buoKIHhrJEY{Y`Y?k(m=Eb^i-o%dcWnVM)g|cwH_cX0{%HB)32>VEQiuh=?!k7
zgV9-hv@YiqJjzX08MvK8{oZ`l1ND;S5s$&E-a1|0O+h5|i?=O~1Z8MD&u9Su6Myu0
z!51%x(wE%zt)fU!PqtTl(S;H7xqLXZrB-nyS(3fm)+q<9>=OheH03fXY9TOP2O|)2
z$miBAMtp9)V#Mv)Iz=FL6zcv;`)rK3JzIcB47lmAK=ejb1ZVrqzo0+!%F^w7BuPj_
zyVND*p~=N{v2yz!M{;JdbOw^3_NM|#80pfK*cZ_;56Y>tedb?iY$L|zTbE#5b9HG$
zsKZIfp;bJ=$YSt&AW&40M+Y4DO`b}G6E#2@GvKJTR>NY!cH257lT4j*9JYNZB(9x0
zXb>~CNZAR8aAnaU@M^(DlhdfpZjbsz$U`7XKYNfDQKyp<qp@3^(kxv8MKl&&ilx5N
zLt6Q9h~92?ZM{YUX=6LUy{yQR!!r+mQL0ZIds}D;eC)C}F#xYA_3Z*Ebzp<5*MMog
zg7ngR>D4P4Q2}PT9LFN5SAv$GibRYrS9BS!jLKNMV67r%dXnN$GKNLwcWvwP=^exK
zh&b&@Np-D~)DVy!c<+kp9MP^$$#6*w^l^aAGdMK85)c{0m$p+9lOd?BQqCsIfuFY)
z5^lwS%2%(LX2qjG)d%K&Qlf=OUkKMS05MiNuboAy*xeCr#rftG)7?2QOiw5^^3|x?
zf&&v{Q5ZR$Pn^@qejI}=q<Umra&(dcnXXutO-MqBZsmoc(A1(ZUM}OL+bQKAq10K-
z;iX{fR*7SX$6jV-GLi~zMYtfa8@A_{V!xMljm(5vdMbqxRl33iN9N$9I`vSPFt$H>
zC*V0Bg)}gr@VhSpb2|~;ZxsqNlP!zFxcFtbe#$f5@gd$dhr>wC(jTvg$d4~cX!1U`
zN{|EOtW|K#M5gE>ahm!1eN&>92Z}v<9U{YEQ8>kQblWp(hIxG0qw5EG1&hLTh#2dh
z`jAZF@p3qxXp2ONPCvjCsSo49$n=0m6+WxDm=PFCtIP_<F&>Nzw+*0pSeoS(DI~dq
z(mBSRV?7lKJyLOclhBH}-I9WlEe<Om6jsS}gAV;lrbF&R7M_WA7Or`iu#-Pg$xrYM
z-j|NjtRrc+vL6A1#9})yWeV9{xlRMWlmBugDZ5FRL@tBfdwx@P`z66i-j?H~w5Tj+
z^va~E_!;VwK!dVdcLtuEc2~X=%ma2;zEjUiOyESuK4m?p*I$HB;H`;Jlmnz#_DlKm
z2zaqeQB25iSQPR+0%;JS8c9kgJx*Kp+?wH4`HYastMVCBFj(JfNjl0R+oj-g&lc14
zQUWj8Y~=T@e8xL11a?6uL{@~Ap$yhzyR@zVzOzeq9K3Wb^|S+|n50g3AkA6jts!~B
zDsK&#a4h6@yqI6PNce-;G#4XLk)ml=B{>d^uCg4F>uFb|IgT8i6b8>0Ip-LeR0C&(
zz^Q8<&u6RLH{`7v^pTfRTi+D4VpS()jOnp99}Pc+dKC+NL|Mx?WiiV93#%MA<nr1q
zWfJIFHub1Pny{6f4{v1_S$w4@WF&=A$4E$Cq)Jf^Nt|)g1E0z!1PEAESy&PT%#qCy
z+NnbUPiIph#YBj*DJ?Sbpe*yeG8z2NI-I$h3Daa#yT3!$rVe=|PO$1}QZgoP>Z%5C
z5G%VTCD=H$zZoW1cDKx72#+v-+Ek7A7117R{mKT{&nWmyi~}$X<%VBbXCt=L$T%+W
zhc0s#{8;YMY{ixsQkxJZa#VZ?-6gAL^eZ7{q6G~p9+6h5UTtQ@Y_x!s$I9DDibWiS
z?|=xzQTPrx>qp@`;B;V(@+8?7;_^!Hg(ZTnJRcytnBwaI+j>O(b`WB@6+h^ip1|Vr
zNf;_m{}POZxe914CsXV^#Rd|&#mdr$gawo1oG>lsD(U5TaT;(v9Yuspn4OM7Lnic1
zM=>HJxaJWU95Dx-?!f6VfnYk`po;?b0q?^ER~eO)Vj*NS1aOEk>&$TG3p0}7Ba1==
zl`B-DN=3_r2NQ}rK~5HhxFQqmqu>H7<xM!y%<oEa0nf51oO8ZWO>l~UXE9h510rTM
zr3)ZnzyxqegcuW?Au(jEY>Wo%IjdZ@M4nj$98}h$l~aLET=qtU9hnO-D`0U(lK2xR
zm?Wzs;7?4oBpi7T)*nd}fO{4xz8)`2+hSHB2VKV$;DD^`k}MTxz~3XRkX72-c_Xk`
z(ew!eZE~#>ohV{{5*7(@!DYP!Fv+42n`kJAj3LYe-=0Do!Q;^cbjP}YR#|W-)~y#3
zRW4E<<{=FyF3?`MQw)A9<f(?w<6Uv$0u}rmOCl}`Cy|x|tL!<1B%AQ&0tG96x4@`?
zwiuCj7*48xG>sB(%L-jiL3cEk60>Vj2(0_hV|n#Qd>j+~%apqZfG`7o@`32pCqG71
zGzNzWrw(NyjfU9-E3-~*8gOPu#D?)ph+FSgxM(RCrVr)QqchonSZmgek3!<HnGyrv
zlxPXkEzTHa33g!M+lE5t`D<1%bosjOr^b(`^oBy0Of*)wA}pOHSj_>_2m;xJOQk(p
zk~~dpgQ<i5(3FvilB3oHR1VyhML~f7gDV7P<v`~<^H=z#^N1#410fxatze>z&WjR~
z(F9_BL(RyH#sj2aWx>{=G=nu_O=t0j)yDjQ$zlxSITDm5#zH-_!$H0%1T72|gfMn^
zXj<Xe-KdRhO*okMKo?>%LMdqi!G!<Onm{n2#W$4&?dbtDVcP}j3Oa$c@VZ$m7|hO2
z@$D=<oJ*z{aU|C)3O<gMj3(e?Bs*Cn3MLRuOz?LdNnVR02+nA6(zrfap<v?rXq_*W
zHz}H6H4^>|HhLnitTtBpqHyqtx=@PKlnBbqj5h_X>>(uL3xYv7%nO!^1mQnGVkhuE
zBdZqy(}!=w8Xt2Vf$WC#(shDmj;}QxJ((yR6pm(~7ccXkDa%1f!%@FrifDov#^col
z&et;y+nRtgudYsH4B*(Tof=PrxStwNLpPpdu+m%8Id-K2ei*zJ9l7<Z&2=($!aAM$
z5Y7P@%B=}hp#xT6MP@UdAtQN$g0v8*nw3yAANAt#kXCFnoqsS{n^JBAhXuWIg!5t_
z!cqS743rFeHtO!gOEF;-5-`Q&ap@D;L}ofOCth==Y6<}yvf9l3>H1-&!!-3F>g>c)
zneaamMe?RZ%g{xLpa>!{Q&oY9`^-$oEg(`%K~NpoFJ^!xo?IuLzKJnoiI;eQ5|YmJ
zV}gX63bA(BAx*%d13TC1ghu%^Ghr74CS_58g?_0QvCuDd;ub<FHv=|f0H`CnpHrCG
zO1{vH$UJD^v>(a`2vW2-c)Ti2aQwrO>84|UFi?N!1Vp5?nc(*m4#fojNH`ReSBz*V
zixNitB%v4QgA3ktThNe5U)mzXy<|f&53sAsIOwP_X!5rax8Ic99nk*KMoEE(B2T@x
zqt;1Ka#qeQ$v6(;o*0tEyJJVnbl06rty_q;J9_%MbD?!D(N1T=F=Oe3MPf09!ER_}
z7u{XU3TMLOXVCytvN~%#7-2G524WG&11>dnaAKMq1}x2vr=cn3eNl3agaQr3Jd>-k
z19xvxcs4jUu{3VyCe}si+{RMxJGOC0BaI>^WgpQcCKS(36PeLz-Vt45Ov&#kr+S$D
zrUWJlN{*#72Swoj0450v+9BXTz3m9+HsyFO%E0Kb2LKNq6pWYWvplvP4=Gc5?oMl)
z3G2G!GX0<!hQ|j%$IIIqTFEP2{vAe}56Wj^5P(RM>0A_8^0#g$Cc0A$KaHizXpu~;
z#agx8rF%OkF39f2UAj|p;;M_l1Ra4V^oD)96FNqW1#g#_0bsS>rnmtaXxyk9C0dY(
z#xr@Rtk|lcMBBv}w#gRA2#t6jlpH({nbyPvh*4`|0>r2pr(6V18U6tRf{+xHXyrkL
z%m0JG!9otRl>6~PIyJcLbw2vA2xK)rdum)+^Xn2DG5C|4Z>LNwGI($fF^-Hn2RH{#
z0;>9xLdFfWDLdKjAywOoo?X)^ibN-+0x;X3luluX#8E`iGR>LQ$nbpGD5tmpQ9n;{
zAv4jRM_V!XP@qF#bVb>>;*oi~<Q<ZG!!iEZ#u@a5+H^R7@(ch%#PJJ>XYofiw0@+{
zPxjCWiW4j9>){OLZ`2uzOy#G}P^48qb%rkYLQ;5yc5tDN(4z1NMdJKZM<}$I_UH)3
z^0%jHniE4bT{%DucuZFgDq#f#1V)r6S)*Y>cNZ`qw)<^S$TI-Y5e1?yNuog1MM@Ni
zx@;S&C0JT&QCyODG#EltgYk9S;McC(pFk1R4-zKg*i?vy*y^C*+b~y3@n~>!OE(E@
ziRBzGm8KzfI4BrRS1(8@B6dq{dQ+lBd4iYQ1nbjiTA+T`Xjw4k*EE2-P^mkT)Kc>!
zA9x2MlmF%osN$_RZ@?<vsvA%hTp#s<P+X6CVb<3z<rcHPa<2|PQ`^POs`B3#H>}Ek
z!(lF6n+b=Zj$@XvDM)2+*Hov0Hv3?fFevD4(1<*?NSGv-U)5VLF29Pm0$uI>dO?fN
zB`)OE^<2V2UR@6+OsGc#!hAKom#}0PG%P;3-h{7uk+sXz0aAMLM4nn5p2$-W2p5m!
z3$3=lAlu}YRxQ=ZEzQEIQL88)ycqlB7FSW!$t|uTs96^&-o*Ibi>f;-ngX@eOa)C5
zqGp2WYKTWOQ>{{9UYaQkw*e`0kuc;TqXLIK)QdwN>IC$jw%H;$Xor~rBX;%Sh^Zbu
zXa%QK%v@#(6*J$`>#?1G1>vAgB0Y;aL6b2ElAjS*jkU#1T{!SEA7SVLq*ZpShH7Hg
zVi2e{R>m)8uv3v*ZTvk=77eH|WoBEH>;x%bWR#3`jj>Qo**c4qov_&kjm)};8T}+6
zfyj(W>*C43NX<{+b<B%d6pm(~6PScN8B+jrW1Le{HK0YxBz%qqGN3r<#;B&Ia^L|L
zT~^qp5T>T$-=nD$IfJLH;;$ElpTc$+sG?A2<3=Ne%*t)R387-%3~dsKU_+I_qb%4B
zp-i-KGuNif;0;*e*7)x*oO2rjg1pS_4HZ($B;QbSbWy+v_}`7O2}w#zxK3pF+bs&+
zyj$r!NcPi!(Rk1j$31)w5C10Z(^H=v>IMEgP0gxa?TjmFad^7RL4q&S%&d~q3>#`X
z8Q~E(Lii+!-N0%(s8q+<DIGfYJWmPLXKl1|G@Ws@bHKCIy!=xTc>l#c)#%}t4=YHy
zW;(>29;%1fJGeCDE?bl|S*X%e>-0rDM5WrDa?G+ZRgY?&-pi9lnbzsP)VbF$y8Ez>
z9eRT*S+!2T_Q`<8m0XifPt(WZ{7|MzgR9z9Sc}>3ru>wn(O%MZnq~diMS#c<xuomt
zLZ!6uu%Z(R5ib%y=F#GupiK0p?{s-~$v?aW($$>Y!aH2m&LSaa^H&pT%esysjC@fN
zPOZShq}OItl&MzRO0}V19s<G02OThU`wB`5a9!oOj|`sl?I#Z)8`h}-LY5W*FX#q$
zY{e10DbY$1V>ngU;m{ZdK|^(G$SE>a^J99Bsoo#cbF52IYH)CCV*{=1FjXUL4QEQH
zx1gaSjP)C>Tr-tNM|zI2^6v}zIT6``4|j!sV23h_sy~`#2V3B+IU?mI$HMK0i?O0p
zTB|S@ENrVNm*m#bT7|i=8x~vfGL42CH!&HOQpDIq%FP~;(-iKchqS_-bf+uYso_T$
z?4-zv2DPwahFWTurYyxs!pWecTw0{u7)!%8Ly<RgU9(WrP2hJ8ZVOW(+m`PKQ|;Tx
z!O5^HXl-~SnP9*h-dg6m5AlXG*8>G_Mf1T3&<3Nqsg!Yx=dGzca!W&YP;yT2fVgBl
zAOA;?I7<dT=|WTBlT>{eHi=l16ogkv%F~p_->`_X%PkD(R}+*06L5@0*bimkn99UQ
z22PAjchLDLau6dsalbGF_y`h%2Qjh}8tORF8WEtFgFAs|#1O`IBE}KIg<4M)2-#5U
zDS{=PlnmL_y>SxcQMl>M(5XPo$kADYAG#(^JY5yK*#Ihw(9R>XbQJmdZf&SzNY7aW
z&c%WG2(db$wq|{S92OidLsAa3SsPLvk*~8TSbyZ}*l@|`iA<EC_x&%xfh%L?%J#)}
zHX({9?tF#LM!pOpXNe<7L*d}*zVc&o22}JGCB<AJyel0hxqoexjJoB+b0v&q=reER
zMadshC~{<#ct$Jp`>@R@emT-e7y*sHIRUvic{v*3Rx5CNQAV^m)ic7biH4Y7ra53|
zU4#q?pJ-)>bZ&m;lvFVIqQvf*yv{76e~uslxDm-Frt&J0S`rkhn1-TE6~T^VlZ<;e
zk;WDWZwdThlK}_@#0FCx83Ve4U77ox6h`R}v>Bq$N#QoVOq0Ta%jo|j6IMJ)DZhq#
zO?H{4iLG%p&A_9DHN9bUznUh1Sn{iB0=R)M#Mv0ou_7ZP+K{kIu{=z1vCB1qR>>C_
z8?^k(HU1W@8)E}jvt2`jXZlOY56rz6^dtl5)IwxQu+1FW6dvr&)R!sg$kdl9rXlm?
z(q|F&d@;u1u&a_`z_^RaFgIG62y+u(^vV32`~)D{?Na6(Q*qccDLFSu7p;w#qzn1!
z81wNLK&Ed(vI#%RY%BUhn3!X?=|?9FiFf1Z@rJmCh5F{N-83#RSH}dLW=Pu(>B&Rc
z81Qs=%?F06+p`q{i!TC?@^<lzf%&)O;qqt!`xmOjJ<-bkR3z+T`c=;NNK$^EX%faD
zs5`@3jJC}C(o`YHHzREh%WP)5Z!sCl=KY`*5_cDHaG1DmJ}B*iM{bcgTSQGgrzQ(o
zRxP|mLGm6r0A=-&9cz(dh7aF$MkDA$Ckl@<-V{m6T*T;nBqfJ~Jx@F7LyJzFoAD*S
zrHq!-$F*%HlM8h{O!!M4{A}i4;wNEHd#FJ!N<PLPU7f%PvIjO2n=q(6+TchgS`=^>
za8m2KG{QS$V?2BY8Pb96(b~_cTvpC;GMlxhgU^r-Y|pJJ;<>FBa%OQ3A`{r2N3*0M
z|It3rL?vM6Wjm9OPpu+A3<P#>O8m79lQ2L}M@I2rr<Q5S5He)_wo_=?NN`$|E0i_M
ztl!X<@M!?PoYEDL^xK5-Zz%HBgl%?E*@$#&45vqnYyi~yInau<_p`(!a0X6A$x_8x
zB(e>N`KN>fQ2b{J2eAF2+#X5F`QQ*hs9dD9W1zqgP+e7nojMiqSLACUtNjt1fEjQ~
zeVD+MVPRN9T5z*->(ny2pT{U7?iMLKjY18;Webyclgs{BFzX{pf#g6R=prP70ab4s
z2`qp;KL{((w;o0S2Jm4#!ZyxMfEAFRtpM3|j00w>*<cc@g|)re*g6qI0*o0qAtb;|
z6xwSH2DE`X&jC$=PQY$aw4xz|u+ep6DDu}7Nx3MQF0Yu(MIxAndWE1V9@GZGqII7O
zj8!Q!2J3%or@8?zP5uxAQdU!$8NLZxQ$3O(oryGpy)+2NVq3Sw8fp3%0K;0-g@Jl-
zG_oWm0a^OiEl1S#F`yT;UQ+{nfz0`Q05w_f`KoHFw$67`Yon&-f{0<acx%xn_0kir
zDa_u&wb2xrf5f}*Npza(L<F1alq|cpFD1*U=0&<<j__8uE_@v>Sr@(zKZYZ+Jv#ov
zlM-e>b;=PwTc^ZaI=4?H=F++KN=%5Z<Dd)l_!Up=L@TPJ00*h^Vhrw?)?4jA)b{9&
zzuJVSRJ{PF#0}U4rv(2OjR39J`2biK*;5VWP#1-pJ&g&=1RcGQ)%hfH)WDwvKl{*G
zWC33_w+|(R)l`qrv6@VwhM3ndt3Mn|PC-w{0f;drm)XFpx5?INh?H$IZ7xb+Lfu=h
zoB%uxLO1Tp)Un9HZ>k+f^G%b@a#0deOxJ#ze45JC9n4Z~GFb-YOdv8`tz%(|MSo<l
zHl-aJLVCju13}EB*5%BB9Qq@~G)NUZXp2&v5-`oRl?lu&Q=<Ve01l{^vSXW)IxW3%
zjfTY|ZD*b(N^Z^Y6Jr{@RI+ICaug4MJLr?m)97N`Sz9Lt!P>45u3n7dNVZ-Z1Cq7(
z#<ql_ySMo#=H6ZN4{R#g2aDHI8-TmeWDFFqhh7Vgg!VS*78kDvT|+cE($QMX9<*kY
z*GE&;O`0y-kcj{p%x%z3Y@QH{U^UF2ZMg0kBsnh<*#*5|46!Q#h{h1NpeUe>>G5J}
zbdbm$fWr;hhyoLlzW0}Mr<;sqhdK0%p*;<EZutE*oZyZ2G%~K+&_m7<xzUC;F(TOm
zlvBe=RL@iV0m|Ie?d{ZErmk;5Tr}0XHI&zG0uZ3#x=kM2ARKM#+|E$?Hg#@8V%yYP
zPL!&U14z3SHFA&;)6)A~6xlf)s?;1}VNo93G?9Pa1l&;V;!SMad40AvPK9RN=CyGu
z)_2|;r(${My>W^ZajGY$o{dup{Q7LH3ZU0#<5WwO++tLmzSmidN`h@{39-3sV@p!n
z#)XiYs}a$vNPU}U2vS+uL>V>WXlb|$0yzJHV8c&wGFtrce^%ONL&v8vEu1p#u8p4U
z+QHCW@7lto)P9ANs%m2qO`y>V<4}qP8dQ{9TMw9q_g$hz(zA_k$$nrPRYMGbHm;gs
zpd4FaF=8K7@v)t9ak#Nlh1EpLQH9RLe-%S3N-tqjH8uXX4lJznLxUN`<B>Uaqdfj0
zd1Yd8q(rx}u~1+GBZ~qq2rX@jXYSiAC|6zd*j=h-r#;DvciPEiOW7!h0mfk<FfpAU
z&$Ay)XH#iD9aJjb2g<Qk_~ZFjRRD1)R;56mtzA%SJb#a_ii142t196dRFy5{*<XbX
zd1avZA#Xy9!T5IXwW^|syJ)nn&?2ue7GuOs=rNe_aqpq1Bd^aGjx=Cgs8ty9z@=No
zBY7`Zfl1!oDniNoz3Nn&v%si|SyD-;f|pbzswO72jjWkz&U&L~sSPM;ZRe(C1#imw
z;Vd|6o0c`Aoq-@!m%6oG$vU%m=%!>nSt_)YtP2%KHQG2GswycpysBJEEwFDU5|$jL
ziG&45<#zm~iWuG?ox#g|rgTLe^C{D9Y|pBmgB#T=IW@OlAu^j01$8zRc*~d8(G^F_
z$5=-W=xSeCfwmr2As}{d53A(D&BR>8AFvB5XDgi45F*&^(W5F}oLwowc$7wYUB0SN
zO1sqq36->!=xoqrd#eW$k_EaFt>fK%W;x*M7E7zhOoIa46?SRB5P$zrM>E!GGn9lA
ztt-zx-uR0X&C$x?yWD)JsMt3f3F>aQv6%(d0&EtNyePU%BnQ0Xky#~kN9I|9m#D<u
zWIjV7?hpG&id4I{Ua{BORlRb!Wj;e8?#(=sI^)q5h)26mSKOW98PFMIX9#KS!oygU
z#ms(|*#cE^x?HId7~3~{2#Rla+ddT1+^x(Od4%>ZyErUmy;l`Ul;7?;A7F9oL^erR
zeT=Ygy>ftk>ot^knC%>(Z++sf=$nNkPw?Ky)-4#=>j22>KawL)nj|fMsH`L?`_t#v
zEkv--ty?T<zqVc&(Y19;mR(!7WSMN_NZ?+S&1M^SbJrD*3In~DY~Zfz&(<wR^lZIy
zM1F4FVnlv!-GWEHS<YiXUgD9*&(Xc)gSD8fdIg8PZM|a6Tn{l+SLgwYcYqR0Rz{S0
zMvE>J6qzmqN}B$=dv(aCPA~fjJP6%=>y=*~TeoC{j)w^o7E_&H>A#36Otj+D()uP!
zG`rqq5vJdLO4|l@Y8QZ*A-2CO!m7$sNdm%&(`o)V=;rBV|9~5)yDX&>=dR0bl05B0
zhEf*Z=tJ85#7R4(It0=}SBLnnqMZ!S;XX`HFc!2Kx)k6q>xykMAnEq9mmoR@x%>3Q
zg}@BPRLr>AyUOR%o!3W~I}ZmU&gJmL<x{&4Xc8<EHuNYDl!~sZ8HPeAUC4em5scS|
z&WSk#6ro(4A($13gvUC86kdqW0oDS&smV^g)8Sw36|1D0K6LHoXKry4@UM$RR^o6f
z8w@<c3sOSv-~5i$hM8LW(TCmyK&9+c?{>geFA5#pL--djg#`&DBT4b4DLr#O(JD`S
zeuQ53SeuH&nh`nLD+&u?M19JzHgRZ7$_XIDyGqT_!+-QCx7>wV^JTsP`e&aIl#Cqc
zQx^(?3pydDUy4BJQ*U=<Wp!24F`&KljMhRPS1)5u20|P`Vyr`pR>fQ7P%GXd2fD{w
z#8B@V7`A^Ia}v!aC>&S^D=WqVDpA!hA~bBjDpn>L(yxk_$=UZZ%^<R6QE0e_fu&!H
zptxpY>^uypiG8XHO$f0eRL_f1I7h(woD8wSugYI`UD0CT&V}C?6pjlc8?ZfHx1fk#
z89fxE&_)J4Qopp35rxz*hSJ&vA8%C&V~A3}q~l$<0IymS)ZMzYBsY@2s-PfavHC?L
z9OAY5#o(@3)=Mu&gnRX?oF<3~>z6k7ozIb5dmE8WU8T|)d)6_4BS|r-o8f9Pq1zbr
zhFj>C(eB2jb62!oj}X5u{ANR?n||*RcQIvwKpUXE`dtxs$fE7HLhe!o`pu9#XxX>a
zNE9gQcSYQdXz}F?;IV#JxZS|uD&#JWK)oWYP*SSj<(fwxa=&#7pn_J<$SaiU>NjI9
zVAtz+MciG7;MJlT+QwZWoH*uh-5xhAHUbG}Oy|+dD2M>8UV&IJ4-z&mDRB(kvP&Sw
z^jK(f7%<EOH}#ABkA-K40Y0gkJ+dDmC~Hv|0|_hQ0?vapAcA&LrYJGuNB$N>;`XNu
zzYmnAiqAsqR)2KDAb);QrYLb(KV4eKgQw)<TenymK-aIZs*vf2HiIXhSZND<|KEj%
z2!%ESuKJ@@%Objjb9@2vf3=gXPjE57Ccj=RHE;w$q0?(L3$ilXY4`9`Nl9n!K3A0l
z#xnUS-*p3SCNVaXviRjH$iPAju8<`Le=iCc&v>Q)^wb~C_#-6@{aU>JTszcH<mdy`
z!W9SAPLCD`mdc`^%5Xd#GgLMPpfvpS8d%zW7KsBxmC&=|)CcBFtv{mfV>*hMYOoEu
zY=#lOAAh8Tj599>)mUYnj(|}8T8T7S%44;$j@OTDa+X&v{H00WSlCOGyz_GKQ(4t8
zCc2`oSczmIz*g==j-N_nJAqW>DpJy5Ui6c>&gX*(#9%BHC|BW=MH$g%;*wD?X{cnZ
z)uP-=Cy5nM=vD(JNkHW?ZzlJ-+o@!h7(ZjV8tjjR;6--J8lEvRW0k3iCbM;Nqq`tb
zTEYY;vTt$)AzNMmAVg|#YfNZKiF27i8z8&9&^3UB;02SBpayPTcmaSWb74|3jLV5!
z0RyBLDg~g|ocIz)<}Ss@_e7=qxKcQflkY-x0GOQ%vEg7Gmn+<iVO(z78HS3t1+D-T
zKUW0W!D>q`m^fBs@<K9bCzemR1&G@61Sx1R%DMv3TBDRyt{sJ>a_#cCbGy;Xj}%Nm
z0$6&10>I+v%I}B8(QVJQ%PBrISFJd#SWIOi0Yu4VgN?Ml_+dH<QJ5<zDHBISQna^9
zzsuvqnbwcUEU&bFpsaeO@dteC5#Z&>n#6K9$v&WBU3OcPFbfKq2X~Uol-p3cxN`0h
zmgU0qjJT}$Wn}0z93rhU^cs#4!HKeRn-h|h#ofH}<-1{gol)owrpQG?Ix&k(>z+W~
ztE;5hqKvIFF@mm+Amxwb6-9*mmqM<*DK8Zjn=#e_9*jy-#;qd5GVAntCAp)PpUc$D
zdVk(3%?|)>F5`1VVLe$$n;E?q=BWMEx!x-D5Mfv&e~4e>f-A!n=0%s`y1}}*D4N;>
z_9!0^^%K1b=mS+ET+x3k%qn@L8Ws_p6(hRQO8)ST!^kZENM=v|R5E+q$NrJcp4_Q)
z_Bf_}OJ;9iP9?La93C!Y=SaVg87Q6IQ*M;YjwF6pE;|xKz3H7yFaWQFc9b4*RVHM-
z)}nBl`EvG1hF+&jLi>BymPgX3%Ua)1G{C#AKlt!n7W`v{U!k1EOVL-Z_(no3xU$<D
zT3kaE=kBI-R=7c3xZnhQa0N*=cpjbT;>3(_K>Zyr0ZVx0yJrm9A`qAZM?^1Rj#Hg@
z_raUz3btf~mJ^S?!Ns-+gu-a*G|*nBXIGx&XzG$njc8J@eE5h-UB%~#zyZCXyRI4p
z$u1HhK^&ckz(L_~abc(rGh<<Zbon$I?2oQ8pFlo|A}D0TL@$*gVVIY9ol$UnxLhF(
zJ`Jzjdblfs!XLWT4F}1%)r}*{i=$5s2*-%(0UQnP0k6FLjI?+8SQ<k3U8M#ZV0FDR
z_oIr~5fm^8CVKC*p0N<LS1$jw{8V8c0f8FjXOhBBMBHiYlz-6i9cd(p74xq0AuW?Y
zycfWcs}})|cx)8F5hWu}#{ee66{GlC*6QB7@tn}1I(bgq#8jJ8y@-o+sTbLPsTbLP
zsn>)KgrKoS0=&?zUYshVKxgr!6g(O-pCN^0aGm-i0%dX0bvmbAb`dZ@m?jVJdU{-@
zUO@RWa8+*+q<gwTi5s%k+=Z~+km|Nb93h^-&NTAK@N|VAH`q{J#fguGlBSE4T^wDA
z?d9qM!A8=b(+jr<alNy!Q<CCLR9N%EKU)W>3+4p*n_gHAC^~io3E#Tdi!(@>W}T^|
z#7QrQUqcZzRHq`$TU-z>JrkvjU4>T~tdveaVM9i!1H2}{?9ONsLl3G$L}EACBE4`U
zP~O^A0H)nQ+(dP)q%4UkXbBh}UB1W$<Kv=WhIeBpP7sNki$oAT?0MJK1!E&heZ2xF
zFxOsnI@+DfUnq)Pe%WGfE`LWWSFr#TN9rA3I2Sk8UXTDt;an8X8tP<$VcZux@fCkx
z>P0?q?FAZhbL|UMkxO58Arz``;cTEfqN_$wgQ<|E)soUNLgGonGU)Q~E=n?8_9c{e
z^up_ah0wFaIiWI>%es?c8D#mlq$H<hSVDnHhk6I_&WRBba}zKA0s}$tpsT17V+S2h
z==dSL?_AeA;sssBnTT5YN$D8ThL@T=3PvL|(B<4_Y~W6TO-LC85gT|U0Rz5kEa1hX
zu@Hv!(O8la@q?kK>st{(_)9w%LXhbvR5^XT(}wAS7wahT>Vi{QF@$aWLdcaNU^}dv
z&J>3u!wkU-!u{gaFV}xx_Q$=2WfD~U>3PNPBs>fS?XoD>_#jNK62N??)(P;rQ_Dmw
z-wUj(Hd#j`-&>3dN<|a8vN#w!xKZp>dBvB406!@g#34b+0T2H{;D=LqyIuN~qJRa&
z!ajfbm3G$f^UJM$w#0iPV*~K&lceD%S5S=ZlOkp(FNs|DNgB02fS;@O)ZnqAZAv6z
zSMTkjOhPc)C7C4UL)P%*{iKw1B_nBikzlt+Qx@U+*b9gN1LXjTJis=?qjIO%F9*Y-
zY}@z97%+?&I~v$#dH!@f?6yOJwwjHSUcfqBItp#oLDxHO?fR3ZtAKw3B;-0m<6AgX
z0jFQ5JcO#(DPI&05cgM4aI-qn7vb~R@4b%w{8AnIDIiDhb?RgF`}}O_3c%|3x&pBH
z{i4LPW<#$lfUA9xS6s(iyy80Ex;CNRGN9~DiWct#6>)&h9Tzl4_n=4BaX7h+RLFtn
zyXq7<&-W_iU{YzoOjvV{AO)dqx(NtUXmT{(q?)j@LziljKr-FCR1>hq{i{@|?k+tA
z(hRXk<*O3}vh=l1qm8So1FSZ#q7FVwRm>GaV#ratV)rRsk!-otZJ<s45=RblmE4t$
z+z~Ec>TQphc6ZfhKrDLc$Q@DR(xZ>8Ns@{*{vdaRN+!Tc<0^-Me8QmQcgIP!R3PyQ
zMp|!zj!<cqwS6g2tR5E(6pKd+79R<@^-AfZf7K(VBShGp9-uzDdQjfST6xuS8eDnR
zqZ?fLQ#0bVeriI4uM5?8LU3$6?=YpQZk!Sx<4)7xqP%71&_lA*B;%(hb?HG0X&u<-
zXEbg-mSKhLvc{<X6CylW&G(gsh4Ap@1RnJoWYwc?|37PQ)3ZyCEQjsuSDfYC#k4EQ
zB$M14ums2pL(+I<cq2hqfY7thH3ZB5-o?y_sHc0T-#&fjqJf#0c^(!&ip5AKBQr4q
z(7@iKd7t>ub$ss#@PIS^1<|J&pikQ5-h@xI$-$V=lkO;UL#1*$YyGuJ^x0L1-NU9X
z+XlH_E*Iop@tf;Gn9%90hEkas-waSViHWk?;i&gv=jjMu@*0Df3hR+%37Uh9QXNsO
zj|5|$9HX)_AsY5;0P6_W^%}`KqH4c(v_2QdsPuY>G4opFIwI3Nk}P2}kWueQs)jVT
zNvo|iDsbu?-sU}S)xkF#x9a2yzj~PJV8sM&wgV-aQZZ4%#UX$X9LT*ZHBvNH!%Rh2
zHFkzpTg+4Zjny`j#8oAf#)sLr(?~<ha1R=6-+X+7)@1%b=4U)(s!DzH$3XL8!tOys
zZLfTIf!}{7<8#>D@i_;rv_g^KzMwo2N5pCzKkRdYgxIPDAOwXiF9CKM{*EYXF%u}F
ze)*dTbls}NU+``M-{r!F><YizL0NMJ=*<L*yRK6(|En%e&@Rpel`QmvsO~3_WDiua
z_p+rUNZWfM!+emsv?)4ST}3IUUWMDz<qyeW@BI+TVebtRGFVmua7;L@I8D3d!un`c
z1#6>eW6VH$&f~z(VuR(S7^W#y2}=yLFjuH(B=&T~;y9}TVYyrZr^yC$x~Py0#th^~
zQY8*>m;T`je$7Os{*ghHm%n7WFxx5fmjBFrs8`)q*1YUn*Phvz%Bq@oo~UEG^Tbqc
z<CSMl6wN<PN6}31>P=@xc$DTHZI)r%dvk?u7{$D4vjTCf?t%{=tnN9rHEn1Vx=zld
zw%HN5gm;>XbSd47J@(#OXX@O$ecWt!q@8huhR<BTfRrYcde>@EBDBrLqU^-bFW$_b
z%#!2nO-~%W^{;iXVe9+oFDOS%CyTw_?m-VJKAUdqJJSBR0^oP}p1!yKhvLRtf81Lg
z5pMnQ1N5yv5GVIdzGX*3MnX-4-|$RuxuiLKQ@zoM?64#$2f-1LMUew=a^afn-6YDn
z!U;K|r81LzNwUk;E|&*2N72<>k&KRLlNPdT1Xv)vSUv(0PB;;@&aY&gpk?xhwq}C-
zA#e@-j><BRX9Orxi)Y~EncYQ@;WMCbD9>i{%=T95`H~d%Cb%3N!FrR?gKF3;6n4rH
z^w*6_l9P01lRIE>!d$MHN%*>pZ-mJa#f-{~Bde7&35@t$&SW#5IrH3x9@0dS;zO`M
zD1nYwVxmiF>Pu8D@mx->mS>to%3Y4Hp6;zmSziLuz_6&$E0;?xIazMJFW}JJ+B;L&
zGmsAO%#eYnhF5@DbUFBXMFn%^=DHl2VqBTQ_zGP~%Sg&{C0%nkxjvFCfr2FhpNm|^
z1Cxtfc5B!qm)+`J?J2iTJIT2EARIcf-nxRv@uPWpi;iIB#cRZ;SWHN~k_Pk<H<F)o
z5-6*4$awOSEWIL#T^~$LZ|#Grc{ZCiKG>W^ntJ)3jw~dggy#4VO-!UwCu0q)Qttlw
zX`}a0Yeh}Hh%7IEH8=B@<O<2eZ#YEkLn6ywAU%CBYRPAMiMS5{e-L#G!CzvpXB7P_
ze}OMezu=?+weGI2VZkYsBFRU7D@#jiGIxnM-_UXHrmm40tF;VT(2+Q&9I$lrz@OS;
zP7TlUI5H%{zLH{}Pa0c!Q0fXS!Q&Nmf}eFD>k9tKb6np#m5{dpeFPG+)-fZ=N?>05
zpYt@^H)(oB0Ju_uS;w)tZ<=m+KtB?!q`pbSN2y5oH%^4SY)^ha$_u~1+lSeLYT(bZ
zestUg{(Q-3k_u%F57*ay(SOY=Z%J1i6I>s6g_nhysxs7LL{9e=Qq_3d+ZR|KG{rpv
zl*;Sjg&UX&y8^M$)R@}(rlbZi)ZOwlhoi{#a~fFt(x(NpZC^v(hllub^&W0l%hh{C
zKIjbpOB;R9$iTcU=!zW7i;cdzdOxaXU8~Cn+<vrn9DZ1<X|~~qwFDiAJ#!?m^Ed*$
z^hJ#c!B>uet;2;yIN@|*xp}~JMjcrsz&S#S^d)Fu#E>P82z0d$hpK$glFQS;PtMRo
zKmhhykEPWKU&L5y8>gHe+WP(V;$q`)T9ogXGjvA0OD_+P*O6cf5ryn^D|2|^zOH8u
z9vsaECCO2UHR=^<uWS$17Q<Z7<;@Z0?^rM}QW#--=rY<7Pq2sfqESD<5@n=`knVzL
zhaDl#Px)*OuY;d6_Csh_X0V6Q=ET?zq0MQ)87HkpsD>RkNPckyrli%WB;}ncbzs0x
zv(K&8%2j7>H3o04DHRua!}?rmeU_n(Gd|^xiTTCXFsJ5smOtiHSK!7wCu3GPLap^F
z)s=AuCT>SPGoy7S0&utmr%@8m4f>8sQ)K{wshtDy+WO?i!C(QitHa2G*JoFk>w}qH
zD;5E4W*){s>PydDtlwR8+ejvH1_7ATFc}133V2{>?o-<Y!otCroDZVk|J3_Oq_{ry
z{=p9H6ZUjR=(vvOT_vL5GxoMwB@7Yv>qml8xp31l&eNEE^`YH>{`^C`0sZ+0EGa&l
z4Eb3?3qfCyBci7`<^=4+KA`5&-+u^n=<kokde##i{)aXKa1{ICMo=EoeMo-;XR#~2
zhgX>Dt8PbbJ_c_0SS+*4?H+4oI^6DcYC)>Rt7o>7Q!J-@t(Nq%&YPaiN7NX#4`506
z!TiELN5vjM4a7PbB)1(&&E&0_g!`tFy!ad(ASr!b-&<FtNQXT?uf(!Ebz_z#1ff{k
z66oyjIx`>&diV8Ft>RyVX1{g`#Ou0BvQdlOMSv35ZdBV2F9J(YVJ8B;jXF(sCH8R!
z0Pv~r2N3{#s#3N5E-|3&n~2B}hrau}#1M2#yaTV80RAp9#022A`IVxm-(Xo{V-XL`
zCu5H26u>wE-dSnGQ(E`3KB1%PKGkuL(a8jKMi0=nrXx&Y1~YkU)m(r-?+hrQyF<t2
zN7p6bk<=29Bb$S|+Ql$+h8WP*+mTdY9qmELaMHVC^f~gnc3p`%lAat1s{!>zEp|pC
z=plm+T=sj9k80JU`B5!jm@c9m+}YmeJ2XSwnxSeHMTb?e&Gn&%DlV0X>mH0trF$F)
z0k`Xx#sf~gy?<1z3DeRjj_#GBw;Cf6v07IoB36ScqAL-v<Skd1hl3-DZ`bvPBRWCv
zS{qRR`~6X=CQx@14yEacRI36_@s`2Ev&3c?Xo|MFz}4kp2dPHAU)=_HFwm4XoxH^A
zvhzDKhV&M)I6(*OEj}t$STF4sNI27#KhrammiCIErlpjf4hD0Ff!#|R?J}kx0fKsQ
zBSS#WPGh-4r|q(hA4$c@>K~P&f`wtn#I0M0nfrohS5&gX<P&+~H4!8FLx1hTj71^y
zZ<OJp%d754s{6dMa%7|Kib3yryVsizF32L&n+WC(^}owi&@0Pzmw%xn=}tHPGlRtO
zt2u!JUV|(WXLoxy0%)4@p7f%8cjkCLWk$Wzo&!{o-{z5wEUQjM!PB`nfHFpSxE!f}
zx)Oam19rTIRE>{#pdt46$rV8G?MV%>zkR6@wvWD4V7#Uki`cap&~Wcx4BND7Icoc9
ze2iHK5e-@)44eT)Oe%&3Ez>3LX!|WAM=*5eewP9RWlG(Q3Kz+Bz(AR@DFy>&zS}u&
z|NH&!=QtbR?~7!lOufoCP$s7j{-FI9)JFx%d|xCE*tbp|jEi#nPkd|z&U}qoh;(u|
zw@W?FP@3=e%TSuKZUsYWGP_Djc102G>M)~>@^jo3m=wKbU`<`tFs&44j&U|+cnGK*
z_x;nyZ}v{wGbgt~f$#lp^#~Wf-+lU(a4HdGe82lNg1+zfn3;x)BN)FZnL2kK*0v4}
z2rtuKt0V)!91*7yQPCN@!V$|j3G3=EC7Q{K0qnAi!OqgQf6OK%Eai~<$7E9SPG(wf
z+io8-wY|dqzB5G$W@_EV_pfGAs#O7dP`V6MtCHy3M5N{;!IV(KKqi+XC{BA#l9K4t
zTu30W^m)D#ln!8|KZU=Nbi%;c7J})&rbJ1`#{kabul8C7A!>_+MF-{Lc&xm=D+z6}
z|MA<uzwF!j?_d7wHv^w@FxU}jbXMQ*zx<bP|9qX!-p?a`{r^w(|Mf4|Q-1#YbLDQc
z@ogL<aC@F--~RH~>wo#@Ki_}8pSJ$;&)5I;r@#D@dHm^L{>Oj$r~mse|L*$V{&Jo9
z9&5GdnbY>X&%>XS&z$k?Km6No|NW_V9$x?ZpZ}V{cF!6Z8R+`28KmkAd?4`k8QORD
zHhuKI>g}KYkN@=l{L^3lTlI3`Q9ast+JBbP9m^k>`n%n1MHpr;8*BtW&`SjR`=Xcs
z=l}k1)Js28>1PW2ZZ@Ak;(lh;{%$83Czib=JNC1ee_N^5x=<xBp}(#Km3gGI(_f`R
z4_p`gf%zy`+b`GHzxk&z{`5b7{`uRP87;HTWoGldx#y4JcA}2`y{U2F7)MDj^6z<p
zfA@Ly!49O%cpg~V3<bY2Z>$E+*y%@gLnN|4vfiIFm*4X&%R?Fb`-|z%&-SU+^vB0%
zv!)B9v-#U=f)4RW;-*TjtZrXcD~G(d)`B+wWhD?X-&&I=lrO7c&(ZW#@W-bALAdDW
zGVWN{cl^fm|M=w7^Zp&3T=Bmg9klVcn$+{Js*ww%Y83oVHRRQNt0~dum(`}@JA^gZ
z|L|_F)t|)K-&p<kKeGBe;wZdh^Z1UX+>6Kf)*`R*%Swn(^wv_2xv#1n<qu1_s!{Me
z)u1}*1vK5Z{Shd8<QBG8sVjf~3;1^b_zP$tg1@7i{X3R&L+bRmnsTXsSq*MiZ#88m
z`?6YcaNbIw<a||y={z<4Z+_1|_60on+oO_i&fl8;f8-0WI=^Xf#xRv%jt))$Z>?$H
zv6Kz|V{bJ%lzmwZ%-6S?($ald4Sc5e6^P*ULtlU$`^MkjgueX)7_j}9D|!2OEM%BD
zR7pvjzp9i`e^q7PzYp~NS2*9lV{fd``tP<g-{tg&SN)-E|Hh*Khm@ZE%hkKTW9@$E
zffU$R8x<}V-)a(&u>S{U<V2|P@!-X`apH~qmLl>)Q<7$(x0@(_IksJv-?x$kUsf|1
z?%sN@<m-xXpZ%yP$=4OZj`^r4$q&2+JGV~r*$wvB@8JjD0t3K*^i-0shX{+%M@31#
zu9$rDk7_7?S*d~6`c``-Usr_B#z#d-e&9`HGS~gPU&N0gV*~T)qpy;DJ;?dXBjR7b
zy^^mhuGAkt>QV4@wOyv`k9v}PS+TP6ywzC#fj5y!idG-nzj_ltq#|~>9DVdtlCOt{
zOZ$(Cl6+ke=?6Y4O7eBZWxsm!ujK2Bd;RjwOYkG_;uua#S^4r^{1|j1Zs-RPO7i6p
z>BjbHNulKHiik${3B8njT@ehAkBX9fU2*l#N?H1W_mKAtzyD4AkkYvKuNK-X`EqEZ
zd;{Kk5`0|^*YqFtB>B1`7&{*oCHcByWyJWbD9MkgPKPQsfA^dCG2Lk(IMhd9CHbAD
z{YyRcmpbOp-+ukz-`wc(RhYfoN7~dR_+#qLGgD>mvdq}^8wMBuk*%B^MWDa4mFHcD
zB)>Pp@`C%QN4L1ItKGX!BdT`qFOIjYc30T<w;BY$SB(}<yoLMI!uiKv!o9|C9e@7Z
z|ACiq!(aSkcyoV^r>KZP2_F>)BmI0`5nTR{iVAM=bwwnX|EQ>R^Ium)B<%NHC^YsD
zzKr7q^&2mv{Ua{}-Yg#@lz+=tBiw6ofK`uz->HVoDsMHVTKTdX!g9XVrhR3oW;G<m
z;#=5ClJ!F`VV{U4zjX=n<L_W2iu60U?%y*wxPiXa<QMv7wL4(VVzoQIvSy*$LTEcx
zqu_U{$qZa?VEu>{_|Tn7tz7@gR$%rL;WXaC&G|ip8~vk75|zLF`3aBmQK9cIu0K(w
z&5sIg{@%}FD8^iW*opu6Odk@~zoNAfJ&etZF${`=uLl-Lqw`i<bZYprTG+2z3;Ukd
z5C!M0HrDsF2GTO;pXDEX191``|Hd2m2X_4EyiVib`j^*ftXAIGAJr^AM)#Z5;Mw_B
zldI=f)#kpTnxYy7zf%o_JiY;zfA9^=LxcH^-R2)qfadJK8r=NyB97JI-}P2g+Ql!c
z{aWRn-=*=+)@AglYOR0AQDEMit<@X2_eW!Y{0$sJ=5Krh|Ij($!!kq3mj@;gqCP6V
zk{>t~9%64D(9QmptyTtB^+#7fM89Lp{l(Ov_#=ku<E}GtYxSii=tnj(CZPG~>WAoe
zEu_C%03V_sF$6ycko{dF{h{TGxEG)6^%Z?>*h4yi&#JHJM~r*NJ;=Uir1MAYO81RB
z($}!`ihjqIF@Irm`0KY<@*~Ex<G21@<6J*vKPzhLXK!E8@0h~YuNT9I=!b6g{HM`>
ze;4`@b&m$5&(6N0-?5(m8cBY&Y5)A~Z=U`=<IXYv`HcSD!`E2XYCn0s>|YQ2|2w1p
zxQ3rU?bVj`r}iPY3zYu!KQ%pH(NfQC_y7BwxDs&iNmwaGwVa|?sXY;Nj9iw5n!i;<
z<%muvfK@(Q5p-O_H9*K=8lmeWXaHI1Se4})KS=-ES65!OKqKgM3!-oYEd}uYKZ5La
z&p%VoyS`PlfRwcQSM-rbc*GZopbHejszuNbb5)AJBS3@X9ngJumA~i_R3pVKk04Jw
zd8ARUc~_OsqheA)0Yf?_J!w|`9?!46GbRZ;Ym_tFkyMLy8xfNSnw1>+Q!eEW0UkmL
zbXR$9N5xmXN|K{c)?H-%Jc4Ru{#1{|pe6=^-_`)+1F(vz6_dG@Ryn@JWMF{`Wf7D7
zja7dHebX2GykgRGprXM&<@5JK?-+4lt?VATPzdWElko?xwa~|Nl&xH#G3g=#zI@1G
z9XUc{(hCrAKVmAZ`zjmuBY6t@e*U04$-eQ%5Xc#!<6_cr2&Dd~6e?FqCaP3>`^E$w
zuLNWgh)K61xDgyd4R2Qg-y(v@#iW12Zs-Bbvb&CnlMaM%WQfU6bK_Y@QdSeB9EizC
zV~FY!6P{+U%A7JriF4OfjGEoiZMw2N0B{Ou(=jWc6e3%}DdT}TpI3muvyXpX44AdS
zGCSq^P<I6lI)eQ7@+3J$GzXv1Bf${M|0I-td{3Rq>r2h_s98oE74ho`((eyB4?=GC
zyPUaV&|hZPxiI8*pKdY_Cg9WEQQJg}B5xx>LMYRErC~kghJVi~9rSrcs)HyG{Ogpf
z2mDg@Mh{@vKLPHtR3A1N%`xa7yLUN^g)+#)i6{n%eO9>>Qc@q(kz_ZOUHk^#q)Yz=
zNiLYdU^0f#MKMT@Gh|$dp;YGiN*Vs#82{*qDh=&zcxSGsTD`QchZ_2?l<E~l?+CCR
z8vL`4hywr?4Q6e=fkmUMC4f;H<m~RJUrlWQj1)+~kkH{sIBUQo1sAXzQ4Nj=&Gs4&
z^)5sH+CVdo_piLw2x@gC@PabL^NXQ$*Xj8d3Q=H{D54~o_<`QujDU1R)m?s}R;eRG
z%8|h_FBG%D5Z~*Opp<TZ;Y#p*19_bJnKNcsxN^PUz#eC?G(-N0@J&B&gBxM^R>OcG
zR4M#%e(Q$#X5q|MUNHo(l(6N3AO$%vq`D0SIWR;OJQCzdMpldKnAJEd8(pF2@{weB
zlx`Ugm*G<#1SYw1G$TE2I34Ez)Icl0%<e4JR$&GpQfLH2l)7++ZaI>p-#8s8kDz9k
zNurS+H<XgXkiIsMU&0W}Fe($o1yPP?sO55K3}!blxUPm0%^Xf#Su;C>DjiWyxDuhm
zPd3EJH0yW;NS<D<wV_!1M^I{|G7K3~=!Syn8<N$AG8q{->Y>p1W}YR4Brv3|4TQWu
z<@`XrsbwG<gE*McUQ3ntvPy0n3hQ9-XgHFAa=kKro5)%l3hMA2qOL5mqZ2*5HAxeF
zQ%ZBhPz)vevhtU%2cf$KcM9Teh;SK-3t<Se7z*2dB-#H8+kQcmLr~(gBN<s{+vR+4
zBxt(KD$(~lQ-zVCi0p>QouP>AM{-_%S3-D%XAGp0OF=qsh9aq(0W$kS={zCSRRE$A
z>KTGHMh`-n0TGp$&yX88GK~5uWw#iXzz{Vxln~G=pUjmav<!FrBSFi^o*N39Zq2g9
zR&gxr8BEw3&SVOYZV3MvOpKV48lJxH2I%WfZT^Vzd+GdmTh9VJ0ch*4jsV&+Ah}hD
zgEKZNu!i`L!I<P$0e3^eF{}aBI{mAy0op2B#syI=wyu@|ZJkc0hAhX?n;HkWm8JM9
zNlk21^CL@a8iz22+%SY&j!u=?D*Nq~*BY#bQ<Xx9TSkoxMGH5?jt)f&H^h;Q&Ul4}
zAk@(Xvj|ijh!}2&G#QE*Zisgsj2M2UXrdAuFE~>u4@0<(V8n3x8$_d4Z4G|<N5r4x
zgtx7>^DNf3CI*MGw$(5WV@;7_4zD@ik|KZ{Nxr3~54At&))+m=Ftj5<-)i_*iUtHD
zOXwMr(?)~#Y)B&%iu`Seh7wHyB@D@FL!rN|VyJ`ye;aPH0)f8`*=a-BjxR%s+Gvw)
z0|47p+owdm+pyL`p}(!x<CP-p5xDScgAZ-!zLe^U*dGd3V(`a|Ca-uyUZH5N=K>EK
zFU^jmx=T&_`L;u$w2j#aLczZc8$>ke*~lV$B-nm<Tc_~a)^W;Hcx^*Yg&^_Ckjpw0
z58RM3HZt6{Az5s+rX4JEJw%i4jetMVq<dqNj3(W?&n%(M$?-|?#xDFwP|7zUl^QuS
zqG>xoK-6HK_!3peO-}__Hbdz=^wtalC>5&3D!<27qMJXeMR2QSAZ3$cUVs=)dU-F)
z&ol8iigo)cy}YuV96{|3$s!2b_&d90Ql~qQjm%MRrB;OEy%<!FFe%SaPmTmT1=82V
z8<N|Qr70}<V9Npqk32d@g25y6PAG==ksPJhq<%yF3Y&Z;jFk!^W2MA}B6u5uvK|Sw
zUZiRY6PP0E>X8hTa}tLJ2$(Zo*<Xf)kzx8|E8y4>U?)J>)iB3nfpNyL7UuZ6Lm|Bl
z*~gBAjh~0=dqsM<BN-^y66o&$>wIU@q;YNt)2HY_G?N;PY*A6M%MTPe5KRHR4H4hM
zqzB`)bR?VwU>ZYuUn#0CLRt1gG?T83m~~+=0UOR`VWy^uXeNEyfoUd{IulccNufqg
z@lYUe275RXXoZebo}%d-$$5{r)Mv*jPnXq(2&_kf0H;S(1O}<k$Z-{l%5$zGZd9vr
z;)*_S`aF|05)E%D%L8brusw$GgP{oGh9Ip+!j`O}&m0k&Dl}9`af2D*k)Tu~3N;KU
zyp@Q^V6HeKwp=B)3X`S+1|3PRhC5KI!^<rldo&D2IyR!Z9tj(%WgEA?>N4+Kp}^z@
z6VQ=hn;L-2d!kfbmrgyrN_PhFGQ@z5d#Dj0<2}>}kntXBgglmkQr<%-W|1Kl=8@Ev
zg^XWEfX!zB6>nF=g^X8{VbJoxV5Gc*+WJUPs^Lj@N7UH36^z*`Z0wO>XBhy$TT1r;
z_#qZj3Pu*$5k&htBJ3{6;~t8QWH6M*ZF(-C?KVEQkgW`X7bK2KoClzrf+|@Bjg8yX
zHVmhgyCc6JSWa&NZQ7ROh8B*z?{iC^u86L4>+7C(*&?O_M;PM3&JBHf*54Q}tm9K;
zHG}bdR%+Y}qLBhVvNp&g!6VBJcGE0<B<FEcah$9o-CiZC(al!94>jFDiGq4v>CLjt
z=k_dN1FZO~b3-Y{^~EXUt43D&Ns_r$px>#mPs!(~36oxo@W68q&8nkc(v)!*b0qlE
z=g1NQ{2D^A&P~M`H$6wdrt5Q^ii2+zfi)!=d9y@0L|LSfG3`k3;EDGoRrydnpR#bb
zf-PSu!pB`n)l$OeMwU35K=-92!&T%+IQxPA3z}!3{~e|5x-8U4$#x`cbk&h|Dz23w
zlIoGL<%I$2OU_8Db4yW1B-KZ9p;*gNCTiSV9tm6CSQ%2M>$Y<uhxS#HS_sme=dK}T
z1;jo*1U@_zu}|mL2OMeroLg!!?s?~yUW}{YM}kuJbV)77W%A4@To)v#r%MKF+(;h@
z_8$Z<JrXutLqC$!@KvH*1gol?zocFxOzDx-t`{}?Q>g}yWMmn)Z&u+(Q^c_~j7Iu)
zfOEHmvq(30BnGe!&myZhx*|(8;(HzmItONjvJo7~nXS2GtVX2Hsi0yO1!!~0SdGw}
zQyB}6r1pnJb2UP5&ZW&D2F3&(9C0?M@*14TN|TAtvWWh>nyHRY1v4{*X*?2ku6Dt>
zx-177gz*U8O1Zk0tk;OIcq9YmdLuGl2a?bn5hrG$fBLc!^>8kkuMyJlNZ5ETm20l1
z#uug>7HotXoJ*=Z;s(yeV=zJj&ea$N+%mx5TvFT-`R+)v3c}P)1<x^XOQupK7&Ge~
z5x#dMTbN4*YUJ9Ri}vYkVJ@lH3%D2JS{zZ%ZwP|X(HUf07>Fq|q+i!?C!!r*CCN`X
zs9%GcGGnWCprg_<7|1CTVIYqVv3eHSa@jVI1W)at6YCSj;&~)lDtrtD!99}dm{esX
z-k8eRa3s|;nWq=<F;aP6=SvJJ&S0EOC3vs}a11HVV8PGO7rhXke1<gV`X;B6Kp4K;
zN0O!bu4l+Rjc<R}7kfdJFFkamPA19>DbtnpBqeMY=!nFZIq!hSptf9Wk{SL{srn{8
z7`x&lK`Hl#8B&D7LOBvVG=VQ<!v+myhHTiNp&SWKKnvg(vSBZPUr3!U!pc;F3ImiJ
z3A9td%?z2aD=y>=S+Uo~5QWqm7%5KHWuT(WAdllns?YeKE34rQ8L>C;Eo8*rNH%vw
z!AkX(^vwhQkEDK4e`Du?_Am>xFNiuSu;GNbDSdm_);2}0I+C2+3GKR+p(_P!DNlS;
zo`43WYAV-;LGhYmSQ&!VTysi;27hIWBW0Vk`}nAqK6$UMv<qXdl;QnD2R$MbTUOGU
z2Qg1mgy}8RO9_uXd(ekd=bl}kT8h|#Sw*&8A8U$0Co&LY9+}?eq`#<Csp7_@gpHL#
zkRmR2Fl183c`Hz~`&F1Km~4soF#Lj+sJ+n7^}e@)#T4<yE%f}=oR9@FMNrr(@<2-1
zfrYLw9HDR`O99tSHJl<XQE;U1SEI^v-6IHfU~{~>$^fG#McJhWMomhpy;hW(l+=J5
zI5jD%)*47Pk4X0ytxm8hs`icq!{ZG`Lq^IJ4G1t4r3O1PJg8Q9gU4oi?A8)LqE&BU
zs5#^C25-;X-8jI3_8NvaG~mYJ;gHtA!AS|!j|LjfBXf13arwBq(5uMNcCH>Tnp6WB
zCnW`>4Q!kgq5aO`x@N#Rj{c6#F%+KH8hnpZ#HTyQ()o0FPG^@-mj*k@16hN?C`Ekq
zU@w~<Jzlr$hV?Y$n9Yt4t^w1$O|Ai+%-TJ<$i*INNXMBnc4G1+7zZ=?4!E^6B;|ZW
zH_zd%7&Rrrn+o>pR>j4B-6)<aQrE5{srM4xFB;M!rif2oScb9n<c%qgT@TurU#e{R
zlbT<tZAVlC32qpzyz5hf<5oiw&?7^!z9(hdYMB!>1-YxXGEyG_N;ykUnJ23wt3?y@
ztyA+XP3%PJyZIvwy~0i5Sr|JE^eMvbk$#(xV5q&ui5+YYIV)0x!6Th#ir9ya&q7*R
zD`HMcuzwZlCZFYeeCKdnPxmVF$<9~CyN(80&4Z!R%^EIGQiMl4d&$#RGXgD0@2&Ex
z)`R$PVy(#U%?P$q(2l4+0I6urkbb6Qn1fkGwokB)hW01dUsL-8-)P#0jqt17W6c1+
z;?6hRZl!2IfER9r(UwG<lyGdpf$)N)S@!VO7>K-7<*t;W-#6MK@Jgd=M&Kn=z8P?r
zRQY;Pef@K59E4tJbw^Y~Q_8evMBbz6U670_V_P%=FNyOFOr8n@fx!}rr??5N5sW8^
zz^ws{CylNRm#rznuGoy-4BBd2Bdm%Ve?+4MZ#{IBhq@y|Pib8}BJ`Bxh1LkFNs@03
zkUDv^YmJaPC$E=UBdE&tyftE~`1P$3QzvY-t@SDy)<7esCdIxX<Lgr#YQ5J$heqBx
zs-bpZJt-L`+u0pg51rl7#!y3bRRU8#W!Ul>;WKIVr--;9T|EL$PM+b81Pc1>YHD(x
zyPBJr>#oKKlbLp|Ap^}*6f5D#Ffd$-v_{yRO&y3TvhCnH!@rik|CD(=XrSbzh@C0S
zoIJC&M#!A^M>TBiq~N!<tHiDlF6XW85HY6^ycJ?zDZ{qX2$}O%4*;2Cs{<P!KS}+q
zBi~Gl(1}i51+%|(BJ1FpuJuAzk^NiIdh$Vw&o;b7(fJ!VIw?XgyRlDH;9GC%6gBt;
z8d!?>Fybqy{6{dV$X<d>nlg5@;gcBB={w<dF#d7tgjc2BYrPErDPj*gRv^;xHSl~=
zz&<FT%~TgUflFQitsfAUPe22aCq)B-T24didnW>m^4~g6vZC`J3A!lVyc1oA<JrX4
z;nEvB53(fww?3=H4ij3%`){4#Iy&!fjtm2lQqT#mL+X16xXK%#b)IcU*Wh@xl|w-5
zgy7NCiQs^x6o6}*BI?+kAUmY6cVg^dvHBz>yc0Wd|DNL`cn&J&o!B|FIdozto>Ra%
zNIGi8?zu{ajj|Iu$F24Wor5OZ=0r|;1T?0ZOBp)g#LjdIXvj@xx10iwC`aqG+8zn^
zW#>VlIS;XN4LG9er%Qcz0;h=m%^N-*U+O2JQr!L{su!gqLOMyK_r_1hsnmOCpF*v5
zyaEq(lV~X?fg>7t65HqT(*s2eP3Hse92(CDUSGtOBDRn7sr&|-^Dyc<9ymc)z5=ZX
zLfI!_vlBx_^=}Rg_3=>=-E#GG)(Jjk=qe!8rTRM|)Ug#fLDZ%E`{W_QT|FR*x~mHZ
zMU|(qVNz3s){$i^Mc4|QSPSQZ<~+j6y`VWxu<|ZwzK9RX@YoQBvqYG=f@HW4G_21Q
z@X;v34%eLUD{q13gkLv3mj_lijf3c0#J7@EukCFNyNBy608&wj>WvJ7uisLS2k}=P
z2yGPp$^oH)Ym}k^0T%DA!wASmDXYzD5ToUT&;}04@<C|W?ovcG8+oEr#x7V58PShU
zd9fO{tHG0V`XO8pWhH6;gGXZJv}}Wz-KF{uVs_Cg>rn)4IwQ1!Be8rD+8|^r8)h2>
z?JoD)Bdf*Ib&41~Im>mS4X+|c$CGn9E+jk*$E)i)LnP`RK^6emol5^8Ud!pA6@lnV
zS(XnF_n}S@h`V(BK_FI=%_FKs+vQ-}27$N_6zlzw0@VgVxVvV7Al#j~X<PY9rU={J
z;2}5t6WXA;xpzH!RgsTfJWR+zp$)=qZ>mMK?bPQ-VX6EE+7OoZrWqub_I%2`&!5uf
zkwQ8}^-!qVDS@%SO+u)=585P*b{hNJ1dMiJ|D-9n%iiB6&#lbv(I!u=@<C{`POV)h
zfyq;Af4}HS5LJTEBdX;L2ZA;Uqw*kVa9mCiZ61?2DmMaV%*fD)oGjvKqnbbK&{^jl
zKB+p|)=&IN&3{|!0fAKh2yN2R+txc%KvLx?ZIhN>IV!YCB!yc-n>@UhXF@#*k6~l9
z{Wcu~CJ(Po$AC%OZ@DJmK^&dV0dsJCI0sCgUzG^8O@MEkvaC;{uY3~PB>pxT_b1P=
z@>6J&@O%6e>QPZ8&MwiHehUrsrIcVJngrighP$g|wWQ_F&?fM==>RclL2l3*Chf=V
zJwQwXGW{9a<f&Os4GpH8r=&x~Butm>g3rQuwP8&B1e@R_a?7isO(J)>HC!da=yY6|
z!0DzvW)i36%+P{3U8bB1GK^2x0zsUnQ$ve_X{C>CL6}aThN}fpy6HwB2-3~eK2ciE
z4-F}tQ^Y9`;|t|kB#6>-e`vu|bJHOr3WA$%5nB+0<-X8@7@Y14Er6`1vq2D9ZIeOP
zg3xNZBnTp_>5?FbtX88vsA{?&V1DD2aY6{IrV~aKtQuX1kD%t!su7x^?M3+j`qI;(
z#mrLui4|p1{)4beFNPN7Dx4CIZ?ai^`bbKfBJ4E*$W)5lR{WByWOzEyt#Ws0L0~oA
z1O&m=^!Y~~+myPi1&zhVqd?GBtYo__aNdQ>LyJOI>$t^jLG!Lje@E`l6lJA#R{<Sa
zgjPB<Tq(mW%DBIXt;*7SMChRO`2}n>xd<OoeX9tF*%l9|@{VYWV5{uDZ4qtl)%{n&
zt^6a};wcus4{g!-Ytrc#48X|$bCn36fpq%SIF?%vXY62U^ox*OJ`mL>Lb5@rUj$^6
z)qfF?jXM1*K!#VuRg!vha*Sw;kSx!Lwg}0$RQg3ozG?Jd0AzVav_(LsYeZW-?B25a
zFGBSFTKyMM`j+m$MiudyFCwzMBU;{Ory$$9+9LMeQs@^?!}5qYnN+LW(%l!q_YQ5K
zi|Bg?heGhZrN1wNZ#qV_b&yw15v{0ESIIaGVz2xnj;L1rtqXuf=w<TdmJ}*H3R~qO
z^rmY>TLj))cK~Z)q`CxH1+rJl*cee(9ujTwSbOUdU=c6n;LyOrP0?EsebPO^CSazE
z!ztDpy@lVqkdfgxN`ghIYk*C3ymbw*iH^7K0l=*}q6=kAw=jJZ8R;C+Hj(kxJ;28K
z^=`Ui-aN0~I!kOCqUAHuHqWBB&H<Z8(eih=Agec{JAzHfymd#giI_K!23yg)?{}^`
zr(CCl?d+<yhVAUCt_e1Q^H!qyBOBkgoGLP#^E1{XK@X5qVC#$l%KnB=Mcbf@?5!h4
zk*fCA4FT9vd-LD`uGE%aMFZ<;Z#g3}i*<@HwG(aYB4F3Ix#2d^(m^7N)t5|Xb0&Ik
z>HoVng1x2w??C^g{eva7l}Y<~(8?kkF3aVH14aWu>XbPPg}g_?hF87CEgy_lGqUA@
z(J*Oy!}yO`-CGF1H@Z*Lf4}diM5X;?Ca<1RX=kqTBdM>uW9=MC?FyYMY}2`-*DBod
zt>{>(Tiz8N%lSyyxS{)<=JpP<)0T%tPpZ?Fe?<q=Y46Ua4R4;-{;PxMw0BeE4X>V`
zdM}#OmXAfR&p9P*y4CVJA`Yu#5G<WXm@0Ji&D7hD&Y9-Fqi@u-JD5v*8%o))TOD<*
z$y+`3I$azQTXrnUTP-^lB@O=luE(;~fyuuw6m#O`PjMt8%WSodm3wV9T9CR)4!kl*
zVy-u(Iq!hCElyv5@bHw_t2%<d$pd=17G6h$V!js<_d57XdqExVMPAw~-X?1G6@1nJ
z%e1%UP|-^_*eld<X%Aa0z77>*!-3*TNlxpUYODU;vCuY#Gu2ETX}0_+PQt3(Q@28x
zcW{)pNOwI|xl=}0;PSfV3vndX6^G{C&9a1!nV~DCsGo9m#MOpjYF%A}A#2N>;)rr`
zyV^BOE-dyPJf|&hiVhX}NYJx}<<-@8`>CGFmKzpRQ#<wb?w5(z5ijV7Sglv@n!1aO
ziel4sxLNN-%Y0@ZtNxjK?C79jvJ&i;sk;EXWop^W?vSFJKdK(zYI|VSQGf5nY}#_U
z=-@S7M>HU)LF!uuscF;Uq8lJlE*IVAxBa?XbeuDHY&CPRXN#+M$~mCeY6TEV*NSJF
z3Ls;t^T0<@@Qx%q8%qxcKE~36agyG2ujp3KVBZ0c5t=ptq$qkF=k*<ORqi;`?+7(r
z04W!Y4i?jnV8dmz+&F6IngWO>+3%EUgw)h~yR%gFVdvOl?{!3SxOVzdoMLu?X7?kg
zE>NfL4L~SHUI#zvNMLjCpeOD6!jhS^=|+*|dU>?Bckq&qgbiD*hAqloN63sVXNx1L
zX?2upM!OoStSRv#bZZz7?e9I=L{AxiSI6`fgIcuVAn^!1p>WIjp(D1*j;2X<tSWuh
zpdRfoJ=nRbj87hzSX0*ka$%YR;9QtmPn-+s-yK%gO_zxdmeCRLxwAfuTaTR>0+i}!
zT{QsP+^SX3v*82L5eR6@<DtV=z2)(6B=r{O(!haabFqH~WTL<wLH1^@pZJ5E&a$jt
z5aoQzZQ@9BPnk<?pMMwXf^)PdHSAveqANuMf*KGt>R#NUBVa3ad^i%cf-p#XiYVWc
zHMD1G%coRbrM7$|)m46$z3O8>sY{j9FKWsiH!pkAT;6d#vnQ?Py)JQ5f`?Y$<*eLs
z7j#5u7sxk<+6MAXSJQyLDQD%L1f(Ni%VkF0qSbX!jrOF14WiMW(y+lZ+EW@fB6RI3
z4I7taTfDknalVd#Efro~M}!Tk12895><)08(x-dE<CHcH+R>h3&UDa@_LM%|0gtn(
zCBWlsY^l(3Hf_(it=zNW-)kkCS_U>w(+~lUQ+oLc!*+^nbz&tOTb&r6baGt7?kNne
zyV^Zv{O-8W-ShsaRlU2jbn-<BZ$TtF66_hpBf3(Ay{H4_#?~VNa)VXQ+Z#)x2fz*b
z&~yaq+e7+x#q!(AVACri;E|w|(<NSAcOLJCRO6!kY;oZ_SU-DA)dH*y7`=N2PTXT^
z!oY*rVz_mXC60v8Jv|wECID*;KC^MoXzD(qnlmZW4j2;!?ntuxLk*YSdF|nRa%rY}
zNPkYQ$p-nY7guKwD!qvOvxnSGI><Xm#Ggb}VK*F;Cao9LoFl0TxH|Yddk8`um?frK
z&w!tMkiUM)HM0#Z59p?&scoRzkm~G!H8I<I5r6iO>g-@AAJKrI7K;>Pk1W-P1fI?w
zQg=Pjv-_PUfZTw->w%u>TXP`XpuX#ca6{^@gU#_&R9^vdzSTA`&ZPu9FiuRh?)C57
z;lb?LzS%NPZ@$%ZeZbq7S_bU-(hgs=o-M9h2VZA9RbY&EyVPJ1__k9GzB*`rTg0}G
zAE5W34ju`n4sn8y1nnR)^O3M209~@zdeL#V&$o$Mr9Rbpz+ADuE{JM8Q!NAMoS>YG
zaf`^-v0NVsO0`6Ns9}Jf4>b(bbE(s#V|-GlN9O>gPY(c?OFbSq@QKpa^SeIfw@&rW
zrGtYV`-o7g-bpz|!0b)xS}&H)DYKEmWlCFhN0^`OT`dE_ylbX_V4gZPHplIa*3OO{
zbUT%5@QAlJHJ#@@Z)z8(JExL;b<mi%OUniyXS=jxP;$1&Xnm|Ku?7e^+i99UqIyNt
zp8-YNr7joudpk|gM^IgnmvJ8eGQZVU0a@Q_35T`5*%Hj19Xj`wq8t*~W~ZD3>a;-j
z2d#IP3J(6x?$oX)(NH|I4i?Vtg3Ki0>@L+9+Q{zlQD>n}0rji`I{~EY(v*=DV2csf
z;d`(<Ezf;6_HC-=g1SD{Fb-@T>NNN}yGxx0eP<`R?1H2QD4jalJG)DvhSs?|lx66p
zTja9Nh(WtcIi7F2OFpI`vdbVn0g+wGG4h{ZyGuKsfXFV3^aMn9>dUFbziBi()coBQ
z6r|%Ua71hz7%9G4$Dv|(>C1KI*r4=ZC8<?Nbs6NG-Md<c5wuHz1~q4sv-Ygi8Chh@
zI6ii%&p1^b2}ccZ?Lu%mIPG4=!p$yC7->beGX8Z?Yj!7wgIKe9iYifcww`hRQRZnd
zYIc`-8ibl7VXHhSc0oK&#VNV@qg)Eora`cIB&P&!&2F2tj9&h0yU9cyz*LdkdH^7s
zG-e$9H+X4RN>0N~CTZ9hjs#tS9paIol*><KvtDGGD@C<yBv)oPS){>~*^Nx|4x-F%
zGDt_y5@#K8D7Khq9pNi>qlyh9%n`7iI^VS^lRR88kBIF69z{AklIn|eXs}{7xnk!*
zg>FqIX_&NjlSvw8uOmSRfo)B=TRyE<is~nTw<fc60Nt9*(gApDvPwt7Tg9fnAgBo@
z7zY5a$tn%X&2G@oVFcWb3i{Q{P<SM48Hc>q)iMrw;)ZpE0Xh=ag7@(jqw9#OfA&$W
zI!L>8N5q=lWR|X|Hdl%U1ld99->~0qa=AK8yhp&M0f9|a@eV@H5uxpMSNh;;7lfQ6
z87S8f^#K<b=SorIZ)!10OD`tQHtFb~-E5Oa4tx48e%J+3zHF0a8vgA^f~L+t%PPHq
zo#K5RNgWeSX6Xg+G?}GAx7oJz)atG@a@<913r!rTHru3;;|gP2sCA&HNl#Cz&4%^-
zd`q}0*+w-TJewn6<3QM?nRPI1wn<H2&M`_)UxlVd4IFnx+oXfzKIxI5bbdbGsRv4m
zHP%6!ITGw1V9ji$Gw%pP@kmfgyOhaV4GPVXu%kdovC29KG}~mXF8)kCh)oB2?`k?Q
z`HoUeyj1iP$0N(Ijuh+V5ui~0(n%W>m~GUn*Ukdl-%xf<mTCl!+a?_vx1rl)sRlh}
zo9U_bp2QkIl8s6j{=PA(QpI<{ok<hNjqo-`#_YH?J`&99wk+|XfJ4#3I%3)ETadZI
zbvvQ~!N?K@h~Pf^mPH!3>RSY@zI&E<<llg@8wTl(Q{27O4?x>3d-MjjA?QR7ufR<V
zt`6qPkqne`0o>B7i?nh}t1hC$RU!-+Fm_8J-UChZL)xPno*#8;+J<(94IH~=Vg{LG
z-!d_S@Ud@b%}EH^qFePn**jX8$!oc#M3dKYONl10<(3u=X3OpG8vu@pwAIODxv4Uf
z#&Sz(&I&RwZyxn-Da<6Yh_BT%)afa+6~Nvt>+%Nd-E`RO8z;S6h`I~qM9eyZ>W%bc
zGFuRe<|<K*NDA@>%-ygr`(eM_#AGM?MWxzMZyJ}K)R&vaWk<}}BdHNOs4q7)Y6tb@
z+M;<mxi2>j%tw+V<Ud!(Z#@*J#rr0K!S5>aiNL)3))R4Fyl<3FKiA&sdCN_3iJj$$
z34A2AKRD<uN5Xar-HwFqAPV`~tTLXzm!_<cZIQm^SS@QWwOdPS?ez|>cJ#HE8ZIDM
zm{X*;-&DCBgq0&<$I{7RiK*rI?$(|km8vh3oy#wL?Wtx9tJYSqB?qTv?WqSBSgk$u
z;EAamd~jeU6@J>W2^|rqJ1_<ssy#QdQ?|`t)Kod2yGkKk+cll5#!&jSgQ2o^SLb$>
zFv5+gmf_k#Q8}W4a?N&EKQ<<=YYsMghL868=3o*Z5!x!Q@!B+0A3;rT8LAy&+t;R@
z`bhEyX>DrL4x-Bv4a@CRp(5=7%_A8oSN9cO#S41ZhLY^yqpW?aXAM2Mf8sCd9aG~y
zl2r@;=2LnW*r@`!wYEA|Fn1)Jkb=1*;pAK4+!C+Ki_@~!R?GD&*V=5j&Or+S3Ul%c
z3fEd{y})p-rPj|9S>k3n_$q5HJ{SDVBjKn9#t?e$z!<0kdwC+P6&e9zb*vQ{!$g;Z
zZB2AoA8;jbI1-f3GbfMx4#vt_Q~fV+Tx+V~i4je;Tj02s?xDPt?jvEt)yqeMQm%wG
zG`@n$BVo&+v>XweURlDYZ40BL-t0K9tmS&hLT8<Npw|g!Emy6LuDLq9(LG10y4Ka%
z&931j?Cs71whK^L)}l$;L19^oCTT|uowXEM-jUVh5uucCoSL(P=CW2}qlS5JYPdL%
zYc(}&7z)*ChcD9-pUc5eSxaErVDwz#VtLV2*0PUU)ty@%1hlQ29qd?bFT|!{;0Ul6
z!E|sWY^bLBNZ68pTd~y&ZV!$K&D5)0VqzUhjwnjMcGyN%Y_*%a{R%l<I*cwWmRc%|
zSR!XRcq>Q3zLmbZLg!a6=E{mtEdXAG`Zv*^K>ud-Ce*!IR+kl_c>&y!SCx|LAC1+H
z^iM0M+D^2Ksl5;>q*hEcUEN$U)iwZ;j4THm<_JLl_2R><7;3q8ydz<qe2d~_IilyR
zaMejqmKCnfZuHGHQ2<48u8yR7N5i!D8#`)1%|4Rs9kpzSQFH}0ZHMJ_g+LqD)%6mw
z946Qm)U~}=6}DWu=8DdS4P)$T8FzzA$-*5Zm?Ob{QZ$$&z_ta_%aO3DRzqTxLx+ia
ziP7aSV?UBCJ-`{#ppi6gg;Z!}mRq7}Imj(5q(Xz-@<>q1Zr<uQKr`-l$^e_n8Ga<S
zN_j+fa9xgsEhlQm%>Y}DyNO4Hf6i4fw^|0QDv!9AGkr-g^)Q1jB?tEoge0%a^Ty^B
z*%1KXT$%y^;H=LF7eh;=Eyv~2n!#rl_RUa7fPL`t&G7*MXQ*WWpmKmauD+IdT;73r
z6T0<vBsrCHs<D+Lnwso|5lR0>e1|n@oA!>|`89_g0|*3D%l*#3(Gds0O`4_M0dSK{
zX~$LM5(mo>>*h%COmu{1X-AsRBY}^iBOb>Qv2m;UmGX^rp-ZH!BdN)Rw(SPMo?T6~
zEMW$4WxJ-7@1nsx5`DLbZnLI>6FN99Yf5bf$7N0Xs8%y+>Rm_gOuI5}yw`+&?Vf+L
zuQ<AqP35>#KLWOk{OW7oY8aq5Z#7(?H>Ht-Ewhkj+`*Mu%-vF=8X`4vP-WJXR-ROu
zHKda}j)2NfemSTyOJprC4#OJMw-KOcjjhKPC@LelJ3(<sy+#t@BjIxaii1YzBgqaA
zs^FfOI2OJC9SoW^`1|U<lyA^Q)(Eu=NF36~lXY^XgzZ)j7W0=o=rc>4F9&($k)V`|
zV7v->wkl=ZH^wGq+&9K1W&H4Ns(kYoxyaU#E)M$6BRQpF04?P+chF{**j^6W%#l#R
z2W{qv@KnUmdL&soKc{)xL84j8X6^%d0hh>NK5)hyu6BWxL%Mn~Y1WXc4kpd@h_cx5
zUZks6GVw)HnU8)7^%puN4SNt1N7JvXy`~NT@|2U@!Gu{u`ZSm@tNM09RPV|7;6%J(
z8ax1Rm<I2dPvZ0CqpD!f!uwf+>NW^_OF7EDNPP=5Fi*nDa%OLFgwI=IZ#gI|%b_^e
z+C4>%4OpgR;+NwaSgsFsBor=RdMu#K7am*s^Ku%ek0dwM<xArOwkf^%k(|fsm<&qG
za;VYRJC-Zfh}ZtIlzrSmXj$TFImo3;$;2H&XBK!?S4u{f-#RsOQh>3`E~jnUu@f(+
zZQ3XD$t`3P_u9~xm{tx3?U6M8q9%8!X<(bXP8=Y<91+{D659p3xwL5TT$WR1Ce3BJ
zl;)zjESJs<n#&SB%K@Ovr67aid>s+T1ORku$)HLvr6fO+8bE%S^8r5>X~PlIbh*@H
zL_S^K)GQ8sE`=FHn8k$TmlqLciJj%pULHx7fPF60G&nHJWtyJI`hG-gIl)gE%N;D3
zC4QHK^72TsG%=c6n>>`YrHthcb#95y<)!j1m&!b04uvXqte;R6AJMle<>%9-BBu|*
z>Qa!wZ8;LQ0&dF@u^nJvmvtIRA07!xX9+7Wxr6_*I{DHL{>$nzPlEun`clilzAjZ9
z4jQX38A#y8vHC)(1}Ie=!IhVClY8-3R+kDL&}>$pAGNA`v{>VSv$~Y%sDH-xfb-Fj
zP!Yr-YIPZ~;SaOA4A}6QITEx}8sX}%0UIH$7dT%Yz_Tv%brha;*{^YGTufN*K_jXN
zUJeq=Qc`j+63Y@X%fVqe5>_f;yN+l;P*pfYN6S)?;Xbvx%+uLO*`{-RIHh$Mr{SQr
zx{T9^tG<+M+!1_ziGp=`g=k-0N;dc`M>0^ZwILlk?H!90ERTvUy^vP?l&e|Uq9f4k
z{Z`3FrS}F<t;s3SVHjFX=IFqgO%$pl$-Xt|!jZVvHn|H9Cd(0_ZJgPfv||uiR+BLr
z>6w;@SeF--Wi{!`;Hj)eT^KBtrOe~L?o+D2>SZ;B>2VnDjtEaom&#MdSm1SeB$!Az
zW-ewTzZ}k+tLZz1gXbebDZ5P~h9jTWYEp$4vhJ)VU3dW)m5AJt+hK{9<*Q0;6}Z^u
zg<>woCaW~;s7Jzfap|YD<X-031zy)xl3EusOe1^QYSNaGFJm=n#0#hhTV+1Tv&e@4
z2b+{%*svc7O4V7xGp*i>j4dzv$|++f27l#9u-AdVawKdRIM`lOHJqqdCL#AExvVBV
z8XT9^s78b0vYIT_Yd#xGlbIS91xLb0C&s3I0MwMFB;yWh%C*GR@?@i|CM)#<#x+@~
zk&0$Ds?E4|SxrGb9CtGd+$^u#n^R;n0J$c!HFzyY0yh({goVpwx<+Q6#k}H<>^)0l
zEk}x<Wl+GG256Z~*DFtWw$(C@b4p0=xE@>LZ#j4@%M{PgL1bAbb$VNtSOq9&vRWgW
z%QC3jo3>4p-Fg?TZYkaPkt|fg27_D0WinfDWY}9KyY()Zv#G{m?=;x05kq2`U>R{H
zmXTxaAk7>J+kQ@eCY>FOn1zhx4nE8>>Ejy_&z2IDJ7RP!QLP+tJdOl=0&=7t$@`!J
zWuwNuM;6#I0HacrA4$!&K4;u&FMBQ2xcgov1-!1ukAN)?EIO*+xMW|<V}7NmR$a#r
z^5ZrcsFOsqObR#%GRsK%D1OY95^PR8(Eo-~c1wCQXa-C9%Y6eo&17Xj&faCRNF%TB
zBSGmrR0e5KVV2$MDFXd3WiNN+7hd9QIoL5rg59UsF-O35kst99p_s4ymPHyYkaY{^
z!HikreT|CrlM>vA9Z~jJsmhNeKbRXf>QOwFQ?AYp@L-Mv_VNL)%*r(617w$VQ!^eQ
zyR19-&?>NF_13O+lRG`Yby><nJ`lZSiRm@SfVrt&j|%Fv?n%qX0ORP0&@!;_o@%|<
z0H@mS7~mu`dXT+x57h$rf#@|VIru5EFMzh&H4CG5zr{r210h=0O;vf2^m6-8{Kd#p
z$LkrGTc`3r5b^7X*z|l#UCjdAMCuwC>bg4`nE>j$tDQRV-CdK71D_I)4-#NR>N=8i
zk6X$sK1gp7C2N4pa+`VsFuP5Yu<&9LLwnR>T*@Inz)V~>6zT!;;t{YNK-qnhzH&r0
zxwqO*FuQNHj4MF#v<6u)H}vpfyzjfIiH{<|#HI;)fCLjtM?UcVhuB&Jo5~e?>p3;P
zPzv&q5eGxut5ZJxJCgS?r->s0$9Eud;Str|Hmqj<NHB<2Jzi?Mp~w7vJ}h>q<=TB?
zhgz=vIX0E=@$BERLyeY!GnA!#fGrbZbPcd&9tlb_yE)ZrYK}+1M!mkFP-^p0kQQQi
z4ZvRPsb(CrKeKdxJxD4XpgD(FTLX-k*h7yT=;zQQ2l_ftI@X5RuAUd}h4PgT@MA)}
zt^tBfY*)*(^sU&gre`hzSHlxaz)`B#-_>wrscz_o1-jW)KWa+#9b2HMRG>$xX(_3F
z>X7WOEVEM!ozRC4WiNKqa~GDO>ACQA2qx1U#fFJ(nv#uoXPT0Ycc+gZjF=<g9tb5j
zHZ|`7)i{_)b3l6z<<T6eUI*x41LT!hn-vP@Vo^IDV6(*9sM7Lpwpb_@rDk6c<w6oc
zYv9ZgYw4k7o(SZ>JmrNtL?1Y!#G-L}v_i2^^2<@NjYA}^fe6X50?$RRnNXg~@f_Sj
zIW7kdb}7LGB~AtMR1SCnMNzM6fCYE4K-L)WCJJS#95||ml2i^HX9MT7t3(Ucu$Q!%
zC4A#JGzarj4xFiD4Rv;wRujrjIlyxXC8r$4bO|xE21qQy#FGOYmMC|O3!+n}>#>11
zrf&}Bi%`zV0bjFV%E{|U>dklcc%ge8rR-Y!cxX*`Q)f3eKjowx6}CMkY<Xh<jU(DW
z)pM}{fadZ@E);9MnHt_$ZZtd(7@b0CC`Xy4Vk!U4faxkk;~Jo}JQ9@Z6;oXv-Lk|s
z@HK}LlMk5BVo_BdX<!Sbusr1&3pM2<so`YQy8)|RC<pl{DoYCLHGs+z%4j)2WeFs-
zyh@Z~Q9{cBzs`uN@<5-cTLXNT2rAK}yM*#s4$xg9mYN0pg;edLyo7R;k8*B(lm=12
z1~M{)l8_IiZ3vOKMju&X4FF!eYBJJ81e0A37==T*E=SpoLqx3s({jN0c{VE8pF?>r
zM+d|y(dB?4JDBHkBnc*z<8pMc#R6omBUq@xrXx!nU0^1uR(F72$U9<yyAnYq`9FU9
z_t#m8_tUFqIYk@KBc21&{e1b|{M&!{x8MHzH~V%!|JDEg=f7Tv*B0P${q@_f9V`^z
z#SqvzTuIa6gBe{}z8!{(V6<_=9eYTXwrJm`=)qQ$+RU<^f=ti*4e5F_Iw}k&l`1l)
zrFF)P9*RlqOl;+ffQ|Hfb~h0cS}@AK%nofU{_`7c60t~;R=6WAz)k{KFCYF2G4sYs
zs8|;A9RVq8x7U9V?xdz$%Nst8TiU;u``Z#wd2S0Y5ALOIy!VYauQ7RL0{ejM>mL>!
z9tL2lQ+(eSc7xhuEh8W6SV5mZ`aYRQAD!d2J?-mNRKWkaihi+z2xFfs$o_T()q8xG
zkTTh03E|(lgp~B*T|#{A?;28E;$N(xT6&*rs8+(q8hXR^zH3NnTsFg?Dt^ny5^BF(
zLo&i(Aypirs-<-#=b?{v^twUP+i<~}gM;8^Jmq&8{bC8d1R<=U_xia`@A|agH6(lQ
z$0FkC`&~rTK{~Wx>43F}_I*~-vvzErP3ZY!xLM5aTSP$3Kz>``YACxcU^fD4!K&Zl
z-6M5$D5ot@Jc7scW!PkSN?(Rew(h)^)d@%x&t-rI9MKn%n5%dJh{+gRL|p|ES_EBc
z1Yop>^3#I!9wK5ECH|CEBUfZ7IW6Lz22;}_G-@a@EuyDBf-0QH=}rrY&13Qa4&5@8
zi+0uT(HNk1;@}Nuftb2ghC{(4sX`5h$L>|2s|>aa0IPJhOc@`da#lL}N5GpYY?C2U
zW^Dx_N+w)5qPPK9N%B=>e%T7b8%i#VFukGVvN(i<=$mV?Q~XqLm<eT?&C^ay9;fjs
zJc26JlsZWmaCwOdgojs5Odh4nZzhzY7D0_8v(F;paZJS$*f%DfmrU>y3gwhV!1)j(
z6XE7#@|3*6rU_=0E!U$^I$6Ys4keUD80nbYIJcpfqI7OUR|z@$6nKE%IAKm4pK%^P
zWi*L^^#LO1Zdgx*&N|V@B#R6FU%@oAh{7FH-yq_22RNGB^G|dRCr0I!h1DVkzfV{;
zt`Hd$){j6+*>Zae<&)hwV=ABQ#tCz5ULC=AF0?hnxh_Q2%xLMMWV64(*ImcZD->c6
z(bhw>PQ+sm=?^e1g-D&dKBX9oFok&XAx0)*&L08Zex4!+KT`y)53w;f$S;v>%pK?y
zbvKymg2DI7lox|$Y#94uC@x4@1XF@0Yk(mtChUrlOw7G8(bUutd;SW>=0ouLP-MOg
z`X3@{0@p*NOc+Fu0PoIj;F36%M^c?&ED+0QP)|2_)W)De+ioZaL009F)S}`w@{#1a
zqCwjbF+LQT&tQ^{ip+OGl#|-j6wZcZWEz~2j{w>{9F_x-`RoS&B@~&@?w%#K3lJk2
z({6y+Aha6n{V{ItSe6$8p|E>~c<?dqk4g)b>aq2E_5qQHW8CTpz(_&&jwHLLn0tl`
zk5J6LBYC=gg;<+MlHV*?n|1@Fe5-M2unf9qxLOI{)Ig5t>9At%opR~H3r_`%IX^<X
zfm;f&XE#!Ghe(=MS5D!f{sX=|)PLZYqV5@D6kMUOdxk&;!LWOlkq$yUPP+kNKGigE
z%#||EZUC7g?-?@VgikeISf;pph73C)KIoC;DikBsaPJplgc|M!L(%u1lSP)$a9u85
zDMHH#8WAFd8e-Ci_@9P6MUUj$-yBwQh{$#nVuKz@4v3drhD+B#u35viY&h?$uOq7Q
zz%F+LH5^w@PKic2Lky2lO4%bRFw}X|kZ3Ag=j^(c4&{n9++2s~o`%cqE5!FSgKbrO
zPs25Nknd^cSzup*ly2`l0V_rLG(<)T5k3vkQ$l=CtGr#|vb!Bgt!HD)Kuo2QHRS&a
zH<aov-)cDh>W_f!4!q=B<C|GR3$VsIt!{>B^pB+aRA$z`)$KYDg%ZF%2b=0;e@!QV
zP*Odw6lGWY#t+Uzm%0rI?MwZxuRKKcGzRtwaXk&ue?nYOtN1|Cmxco{?JVW;e6zwD
z0udci?crd*L=Ux`;F!r>4FsDI>+?to?MeHzin0`)Xl;nZ6w3d4B-Ig`*N&w6F$5G1
zcuJn9HOm6Jh5Ua<LIV|!dP)&%jphZ>JPiS>j)YAEP)YnWM8Y}(wpDQ2oqPjBip1!=
z(6$Cssj|Hqm|p?jrxklFMEtz0f`UCF;WWaAg_xg)&|=XUnZOW!EI|IWh9oN?_NRdk
z7h-=}1E}_<agVgb&^80a?6|5vg8XDf{XCMWI(#PZ^0ntQAZD-a^!oYl8GRZsv)><v
zp^;^L5XeIsiqv;m!~LK_^%-)ShN!02fUGoy83NXYxTe;EE8<2m2idloE|?X~)R4_J
z$RRake2unw$~4ePqY2XM*P%##23Be)QlEjh8jYpWwnPcFr;DMmeAaOfsIYw2fpQAV
zXUW2iH!$B3<U}SP^ptWAMF=&#f?$|F!&?f4>9daOM8@e$NiME7QObqYsBT-wVNEPe
ztK7!XUiBGV=TJaCLkP-XKt8J=m7#cihCr49uk^F8BG_e!-DwDj8H&hf$j}^$$Y=e5
zv?eXQ!x28n?mUuQHllYL@<4~^orcXJ6p_zr|A-36SAzsxk-ur6pNIIHmIU=v=D*kL
z(uZ6T;;$5OJTpri3m~kS#sdgzRLjA?k0w9KBdXrpPy9*tUEex3_-Ojr!Tk?$LN7xE
z*bphy5G6JgtnWxhma%yu%xr)XYMrM=kwOi5%tNG5L$dP_Dby+-dMI9>RnqiFxiKmD
z0M8IB)DVL{L;|&r!y@DLSq9$?Therq4L)q?DL5V)6ndnU55?;<q@EAP>$|K}j!?ip
zgGLgfjT+omLex=%9uuOD8ogaY0sG9W3R?y$GFqR(e<s8mwG4I-gZl+R^`Dyn)V(9%
zO-})!X%B$H7$$0&At-bxwW}d;bbuFX6@5BP(CffI(=Ono#puSyN^=gA)(!1Ckk-}U
zjuj>>Ml|g(e+LQtGwlL?9xAmP#_&Me*Hf;=qwm{6jWHd(9r#BE=pzAeDOamGaElaA
z!?EfLlTz)0nG+g2fXhs?fV)A{+1d*lu0S@|BgpABEe4zrjT$vv0K?u37@(Ue;HJTu
zFqFvE^5hz(Zx{}VAug!lv>VLW`Yd=rq6vEI%p6MCY7R(LzE(r9`w;o_NRp!)w^VQk
zMMn8rZPd09OxJ3#7R0SXc-j)8*r68$IR>R>HJBuh1T77qqjI&{06Z4=?<z^FCj;vS
z&V)BhH6j|qkEHImg!2Pl^`TU*mYvr}4JX+UhxABtHDtn8gAFI{`3?`{8>MVDgscx`
zY&C?e4-rO>BnLA|7dVm{jdb?`$jx-E1_$9#ZdMy!rF!Xu;Cf3<hs7+Er`6!89Jdq(
zcr!l|l+MDw{T&|8iX@=gz*+H@wtx&8p+v8SBpU(7>s6wGYHS&to=o#<2yY)Ep&IOz
zp=7N#Dr5G?g(dD7<Ca>FY$U;Ctw&(EC})2QI<L5)42(q1TRX`Ba*C6BB=wS|4Gci%
zEthE<z|NcMK>6>7SgM9}D{*5VK@j}VJ+&ccOWe{125?hpUJZus5GU0T$slf__5|g0
zieYLM4`J#m)sV;LNYKAo+ss62)>A$&Wo`u>vRVI(od&l8Q}k2Ay}{f|&78qbC2BPW
zk(e8(jyMx@)3@3Xi(-;|Y6w>`#Xhyl4m7u-7+IwmN)hW+=k;~t(s?Qg>ygAr!GNZP
zARSX=Q9~5_BSB}pnwBN4qS`+aS<)sBigU}9HXYs5_lwJ_xn)h8BTH<!KGLZ?t%kd>
zxn*0!b=lklr5d2C)lma<HHzE6$uzBo6k1b!(Ic7JaMxody4v-e$Px&|h9EFgIav+2
zi*xhB%n(gxidbrhIP*wQI%|I_AFCl|%~V2GLn5-Ngsg^SWpne+%$U(^ihOFB^la{?
zh8ITIP^tweyV_h>fJVm^!)5Oj@zm-%c#3ywxI&&v<7ySZer`h{w~DDeu7&{ila$jV
z7+FNe>t;J8cx2q@Y_io1cj0sKLd|enKFLb8x=x>q^fkkU`+Re>8UioPCEHpQdd{`g
za!t<^fAv><kwAd$xt98JcG$TVds3E_DH?+z;Qa)Z)rycam%P3V!K<cHy&4!7b4h)#
z2v{lMb36K)o52~NX8{{b)LNgSvKrDKPUU$uq)41g*7<;U;t{dsgvBFZ!-ba<3|NbT
z%Ts3C1($Qt>&p;wY%c96F`p82d8Cz`qP8AM^%Wc#ivq?e)~XdzFD2|)pd<A8GLZd_
zgbzj-ib-y(WxTh!WI;znxG8F@A!^)QU2O-Jq`bZibi}!2R|ki2lI?1sIZlyXt*DT5
zDVV5%E;+?`HAK*xODcYB^e0P|9d(L@Y76f4b4hsz4`wbZ?_k2rrSBM2n7Qg1hN)CU
z1Vh-tDRQbIV*M01)iRCjR0dZ=qS;Aq>Xo9Jy0n>LP%~sRD+0_EHPt}koyy^A3yv65
z<W#GOjgLfja71;SWSbgTF;mo1!~49ZxTS`dK1D7yER08jQua<?DpuBvKx75O>YE{J
z8;I32WNll(MbT4j)l=Ch?j@)AsRl~SBpKB}i#Y<eQ%ERw>Jj8(3Izc*aAhX>sVON6
z93DH-S*hI%$QabRFI$mCeC`NkIz>J;WSf48b+&+viZo~o*OF8DU9CtpQ|Vm|-2TZZ
zf(FXWR2V_aZS^VF=nAjMc{FVQGla*0h?#j?tpH>y>YptFnBxA~27ra|c;D!iF1q%O
zZV8Ulfnru5zzc%>6p{#PVA9MG9)n6VL-$-8D5r>lhIHyvd0h=;nHl`|dQ(E*U8Q=p
zP!1*%x?UyfsKF;Do+%8VA&Bt|!876<&x`|T6$tt1)D%1;CH<U)=So^X6$a3tL(QoV
z7>t@(S#&Ola%@xZ3~g;HPps_+^OPdipx;e~610tE5l6zNfq7Hg0LV8}5eKdKH&aPs
z4FsHPDod<EL7fUZXsN`WD`r|}py#FptCb#BN0#Mz{`q~u1%xT$(wbnFGKjN*XOj}G
zt_iZ~=5r#u@-Boz%M@{a1!%1MCUMum*hv{XP%1@<FhB7Vp3WCjn0Z9GKfpuI?xlS_
z8(-ShE2@5pICyesskEI3ZS+ymn+*({5@A+%v3B1VxY3`r7>UPlDm*g$Walg@o^ylm
zVv2J8wDNCEK{a(9QN7f~-MqmsGDRT&7M(UFHAM}F+Y~|ZYd8WwvdIPwlfAgBw>(Lw
zfXx{Pr)|B#aWrM%u!E(OWM)39v7?`a=UH74S)n2SK+3>$zk3zIq6b?iMQuQWPSwtQ
zl?<JtD%B7JKSi8%#~f2}Iui7})2FH-fkVpBqO<2+bL{MR&tg8dsUd)B$~ch0HP_Vo
z;MlmmH<+MGbn{mS?^DFq2j6ftH@S38J(zsorVhYuEM@G$<XBDbJlIcpGQcgoM0lCO
zPTlHfuv54Cx!AEA#p;xFuy*5knKCTQm8(z=LJiEG6tR<wRQavuSFNg)vHgutKQ@Xr
zG<gcO^2IL^ny+@R6tM@pzA-6u&2EfL>e~@vblkZc&C`!e-z$vRDZ=+thVGQGqG4Tz
zc>jiwHz}*Gf|HXH_N%d9JR%(t`lS!nnr3~f$?`{#qtFpx+6UWfoOODK91%xYC#;5B
zg%q#{9pfA7K*zd!U1}KCqGXsW=i700)A4~Qm~+FOON!o#>{eG-2Rqi$Q=n*cb(Am~
zT|FI|cAlk<to8#%bv`1zil#oyDzf>>JpnEP&4{;h5@<%irJF!A!fiA)Kk@C!Tc8=i
z6y5;M2&M7|XjV{4e}IOV`&WwiXrk%sf?_!zw_X#`biD(3WKGjQ9PGxnxv_2AyRmKC
z$!25Qw(X5=+qSc@zsZf~eZK2`|8uUXnX0Z<b)R!)>UX+2zGWju7b7&=!4PAxBH=fC
zv__uRW4ZM>E20adq)~5yN$3@a`mZbMUULf{*%N)(?mGp>u#q_gEk2{yAK7Rvv%zUI
z16bA(3XVxTGgvu_&#D%EGZIvi76AouqVWsC1(-qb@TE>%LR$1b3v&lR>T;o1lA((?
z;)Oo-h?<9eSHa~9*aD|Y<%{q;a*_zD6~9oghD<%JFl+d};$UpMm?N7C>-dLFfa~GZ
z*VT){H*ze2c3sDZPC*RLO7xjU*m5_}Fz?j(N;QdcXVwqZyEn!aFLs@ZV{-C~XIA1N
z#1=IsiHcVO&7vDNxSIA@MMQHKXcBPnhq6QVtuAk<uyJ4=!_$-wfq(U&<;g)T7<K%a
z0HL)g3ycMLoJY02v5D{=%e?1F9%4noT#(pS?wm9mxd5V0t(hmn{VGPc<cdO-v}t8i
zY400S_F;uH0(Ft$-8)ye%lBcx;vcShsc&WEUu_!HxUQlDfvl$iMV=~eKvp1Efj1?=
zHCI9xLFcMB3t@rC_Y?->(zhKG7UW=ScaiVcA$JC`Cdt0yaZ~xwCn3Q#PI-JO@vcBF
z-`}3<(w3Y))m7b$NJml!tY|y>E}TakXAV^OBXo*{s39F0Ye%k7JcCFPo&r30Ka0rH
zEkm3q@ENka5_=AsXzX_#vY*1m$(I~=l+#=%5T|~_O0sdvIyYbXH*9q>2zWE(j9`rm
z=-(TN#~(2)<BHW%fCwrld?J^<QzgpG0}Iy}vPeHvtYIpUol)IdoN_M^#(z8YT+llK
zRa5;80`vV5YTm^S1MguHvQ&;SSAm=s#2l=>#4R3cnNhUaYcvGT0pAH&BmiNVmb)T@
zb45KEbl`6?z|6<EQ+H#znSOQl4X}*XDefJ996CeiA&9tSo)SKoxU|1?YGFKNQkGc2
zVW*A?<huh<y(dZPP4HQm))u7N1@buLPG#8AL7!dHb=NV<8DJ$%{64&$@R8S?pHHK`
zqp56tLYa_*Z-s&kV0qstR}Dw^f(hD9jnF#r#K_`y@Kzo7+~ZaUtxeE@usYdbE{D&;
zaE<9zHG3{K+7PdLd8<1;gQ6NDeGf_vsJ}khY%Z!7#mhHMm)z3Ps1@M6jd`h_;!*ys
zW=Af@_!{bfKe7;BJipuN6$MJM7t}(V3ArZAp%}e{lR3Q7BALph;=n<V5r->EU<FGQ
zG6uy`kj6&Izd3nT>Jk<}Xa=$d=gV#gV++s9`dI<!#O^y#s<Q40bgsJwE*3Ayevyw>
zHJ0{agc)|9L_nssAOEtO*a}!wQ7HC0SY(mb2-lGi#f~zQtKs=CSwzlO$GdIv1wl+<
z+58BO6;yfP{O}4lS(~gA;+Q(26ny`2+KrtUJ^QB;xE|xI6JXsssVw|2eW46q1z&cj
zg4lyyLJ8Nw&f2u_r?NAeS}jfd0ykuFTje40eY}VyolBPd$d`3cJrGD+JNgBZ&t_`C
z@%kc>$-)A>5{mCLD{o#1WGNk;u>FTCCmn!Dscxn3LJ*eRxbcPg1B$Hk5UT5Z*u=Qj
z<`1-tV1NN3(*5<Mdk8_50qg3<Ear$u;17nrSH4TOW(rGle5;q}iWd?DJwKAf<l^r;
zlW#E*Fix_wL1LIC%aO??(E^cFwovqjv_hgyL%D;jw`9DO0nsaCB1rFG5{DWTMX*#H
zHOWxiZ;jStsP)6wV<7!e^CKmbJ848HM~2^M_O~YzW!mGQ6%tii{jo%~CF81$K8Y9V
z3XW1wziL|FXke8W5=~m<Mcm*FDK=i@CIu0rw7x-}Hm@6)6=#K?_ieDDN7^s_Yv|Rz
zUv<YXS=_d)<TJ?R<RAX50F?H*3h$bJ*)T0lxQEop9SIU!+9CKL8ssD^?)#EyQdYR#
z%&pnv>o49@iDLh<o_W%k+GA>5;Wp9$cBt!A-Wh@&7Pt2X0QD{qaI}#B8G}V2k_@y~
zQW(r7g|MC4F$&bf;+4?dtDl#M!%f@x5`ia-6Q3jiy^}qBh3BNp?3LWztM`mD7Z;o$
z8mSMhTcDKT=W>f?x^1aCxN3`)8nItaqs0p0L<%6z_GqR8<y29>PH?6t4AtSYGmiVP
zxrx=YRYylou$v{7M@I_X`Gw=j1j5ur&JenZb7fF!P}AnNfON6=ME1<2A+w-tnU7l$
z+wvLA+5{Zye-Uw(U$Q}j59HaFQ;xIcD|$_nS^@Y2^NcRj$^ppm@K?23EOixdS0B$j
z*soE5Kf^@Zvl~^MP&5(LduVOnS#WdhwBmEIHd@LQvrgyH80K^}bcDbEX08YLFfww`
zBYK)ye@iO+<(bH9`2YCLQr|B`nvStTq`Tsws~wO`n&64ZAjA1YWS;6A-k+!c+fOGt
zCyy~fW#?DyTsU2Bz9;Gmk>rL(=={mii%jVsM5Rj`^0l(++r*ak;DY^f+l1m4ZwnVy
z=9dw_9Gb7RvxM%z+Nau=zQqHcy_}s8mG=6kVO#DFy=r~R2WPysp7zCV`o}avp7Ov7
zKI=w^62~pJ1(r2<SiL!a5;r<ri{qOFHMkWQ`cJ-MK35pr6Mfm7TUSvGL6!jO2!h!T
zgYdM7QsYh^iOQi#^|ZllK#zXLTj55}c`jt|Ml7~b+od}1j>-1tec_VAHj;*@(%4U$
zLZfLpPM$)8D`-M-oynFD^wPii?tbduZnl{KDzxf<-kO&zXFbEq#_+O0@=9tr`YXo@
zPyVv-K4RB2m&ekV)f}<PW_gC~Disgf3cXJsC}P0m39nuTnMNqL0oGM1zO&H{rM<v4
zjv|xsj98c6$g*i%$7ro_-0z-N<Q#$*qzCtHHv+;%7!y&}8iuBB<C5lOMKrjX=4OSq
z3t(AL3@MFFm<j-msmK1CLP%lTIaDIe7uQ2}ebt>!$vIE?O08C%%IXcXFrtic4kkML
zNqIjhamls6dcVl(#u_Z;t^m}dG6>JCN@j1GdknOe$GK@X;W<p0m!w^x_~yB`tDg|G
z!!D|%PBzo9vf)`Ey?_UNyt%Rwt`Nj64O?KK;#UtTouh}0e)9(ky#<_tR0bpq_lnK&
z>P4OqVYzF;95k5gHb237%*_^+wJaKRzepRqkB^EBnX2=an9RdxR1;J9Gx5?~RTkK2
zYXZzK8EfIb(k;_)2uptKrnj4uM5iS#Ryvz?UhbQXz%SMJx#E(!q4@BdCqiI@tV$*A
zYgSH_6a_X`IGQ7gO{^2F1(BFbW?r4NEECN-Ns>*Qi%z5SSmZzMyFs`#B(6O->8nWR
zo^(CDnCd2BF!aFWB^N}Ke+dt-I4A!)Go>?HVv_*}Ni^DI#>Jrb6gu(u+2&_-gj*Wv
z&4+`;&?e{jrc1!T?7p~KtAjACg|94j+gJjfRi)Uf=7%8JR~fN{R3ZcdMjy}lP4`NW
z0`mtI+j}i{i?!l;0nf1QmN+gFJsdA-(3kMM7=WIrV}xabCD-Ys3Sa9V4T@<?KNQIj
zW9;lH4N7ELa^ST{#tL+KkfqV@GG`Me>7p{YAoM*+ZPZ*1yedQs;RIhX+rf-c@r*PO
z?AmF~7s_-;Yjs8~eXZ1-$5-62@>bU#QyE@m5G@BVIE2D<2E;l0tCsOBi?&z{_%rnv
z%dfJHmMP-d6w*^svEp;*VBWG|oYYivP;!k?69{%`<VU2xISqBO(`VSllpds0Vu+!y
z7cJJD85Ff@;$+NK!A_C)x2f5Q0`@D2wBD7lZ?I|9U`5EYTpOod%XDP}r5h<>XBenw
z3}{`p*hv9dhY`t6e`W_lFZkYMqy}p_H4f1g&l#(W(>S?|yLrOx9cs!Hd3HD#o5~<F
z$??+TDu^psU1mRptA-~IZ0nq}n?$q)<4gXv3lr!E>$`CPe1R+p1`+=#W2yP0RJSdd
zZoK|>crZ8x(u6AV@XkhLtzwuv;&@kx{A((zT)gihOgg#Rjw&zUqlkD}vu+^0{lO9&
zTQY-#J~3auJ`I({(NZDF@%o$0eCzLiQ2{m^p*(9*0{=B=PVhwY*pe&z>fE(*VZlbD
z=*s5@vMqZ0ta#Z9)Pp!q4c+g&6wKqgp0&%&R6U2Lg!<BVFnfuR-qHH=i3KMvCnX5A
zEZ8a<i8XO;%+%q9;tfX2>zdgswR5lw&Pl)zd)!K{ZtA$Q^hAip__FjzSw>UXzp4U^
zn3%2qNF?yMl&)&Vb<Ih9u`tW_6ubo8c!-(pw6LK1wOJ0rUpRq*fyDo0dgzu?+NiMD
zUk7E*w6J^AeYttJSjj0bM3Fj9;Mur;hJTKJ9W!fUqN~=j<pmz)xp!;BP1T(C>q~(t
zn;*mo*apmcj^{??PhvrerST;)iD_%&McMhUwgdVri3J@R<MlLv=ehLfVY<iyN-=}w
zLKT@HvOMc!j0t#`%Tuko$i9|hwy0CcjstoBIlk=CJF_XEXE8vg7Aa9Xk1xPrA*S!C
z{a(+I?s{uf+y(J;G|F$fjM8gtiCbvO4EpZIGa#90fnsEQ##czd1bVcbSoc#wP8?hw
zCYLPhxqFl@l#a<TP(C=N#xHfUM1Pcy_vGVjp@W($Kmn&DEKvc))7X}eqdve2h>Id}
zY|E*ZfsqP^EFcIIMV1xU+4B01vdvmdxx3xLYUs%*PA_n06MXuoP{=nD|5nuXMVe@|
z%BQCvo49J-I44$H9Ha6bxu(Bx{-ktqaLgrb!6g<{Y3N)SxrHJy52YJny&9gOWMEK|
z^#@{pmyOgeWYnoTm`Yx?vjoziYVRb?gFi^!ZTR9qGrDB9a0Zh}8ss&kxbIv=o=Mv8
zgvmZ$>m!d<Kg@Vt`+G5BHhDP%+vUOO+Fa<ZFpqSvc~1NwN(l5ASAjQZU|N@vW2FFO
zWUu-5iAt8VWO;Ow*~>`$g&LGtI^RnhP5y<n_1+zpXVK9KnpsD|GLaBEO|TB;(M$tl
z6rHevT8p_Oq;NM;lLuOqwBIm=I5`fFvc;Pp9VkZvs%smfrq<V_Ry^zO+mCY@l`KrM
zh7;6mqmon^c_k`X-NEIC6U4LkhQKP&kDd1Mdg_<Lmpu8DvvxCT&`32>PJ<eTV<D1V
ze^1BmM}pw8b;0!L9x9Am>Cl1NikkGwiC}iQmIo(~z{5&qOsgq#B+BVgK{mQ6#`Sq$
zdor<>5?JY@HuMxARt4R}?u9cTviw2WyHY6KaYiTT<eA?kriG4``;@#aqdlJ4)v55n
z^k9`zr450?a+3861U9uI7Ex9!I{Lu61L!OwJ~UD+H>653ii1@)_JH(9%OYWm2sw`y
z<0&9EieWXXwF7eGCMM@ni$Jlsqw?+FpO!0Gd5Hs3j2m}Xd+Mn7ME}9ID$mlp+dz9>
zBjd7v;%n!zz~QVREu_!wpx(M7kRjhwe{X+5A)^l3EFm$4)%(k6yWb~HBJEl6*Kj@r
z{c61Q%4>8<X>JwJl~?1{nVwuhi@x-_v<~nNYQCAJl(--BxIWcMca4me<M;+ZOrC0K
zr0$m^Q8G&_)nK=Egzs4}Oky)eS|Du!!(ZoQ8o^*5ipvG#NlL<HAsnfi*dgmCI?J}z
z%>;#92TnM_EaQc5>`AKgzJ(Q2)xhJfQ$m~alqqpFgK<#=!C)X64ble_O<G`U!BQg*
zwj-uinj#$q2^@>mtd;1FyRr(pn}5aNabTX!%|kA`QeaO8I|t)2*)c;a*^h`W>#SP}
zcCVYglars(Le9G&tA)b1n!Qvbqx3>54+BD`(Xx>F?9dbtFz@17!t0pT<crXKl#jvS
zH$AKY8k8z{SYZcRcSfwSxsV)uxZXNFT8riOKsv{GCK^h_M6|l6fwBm(b;lU90{a@h
zzd}*UdA;1kON|U$*T$0SGc#;FVOf=x|HU>!!Pm`#x|^Y=&B=eYus!xUJew&dB7vs&
zT~ZvxMeStZM2gXa)Ww3IVe~GPifJLY7LhT{bzVa!q}?;2Dbfi;O4IF>3fMI+wwq-s
z%^#nsIZYVNy<I1rM<!$oE6ko^XiT+P3UV7O%ww6ed9XG-<3K6XRrshjp)##33dB-&
z0}Df1FqKXLUF)Vp1JrN0?Q($)n3b%19EP6kQo|rx4YLKKtu)>)Vt=Xa4$^02SR=~^
zk|Ty_A(3K8nPgY2z`vEc^*QMo-1;^#xG={v&UYThDLo#gQegL+d^6hNJDUq5ghljt
zF=pAm+i6`_sJr%MwF7mL<kv-WEnd2eJ9_%`HdRU?c5*r|lx+K2B|BKaC8r8^VELi#
zR!R4gkgg)Dh9@Se#Z57^>PL1%Z0rO}BX_MHyWf%o<i0vE7sdVfmeZfq6@y=k5;-<t
z6>&2oEV>z%6`HHnvXT@J^tu^qQ)%7Ddw0dUnvKD123+Q9Et<E|i6zj^cp6p3Uu9oU
z>I|sPH0EWb4AUBiLDt}4lzv|mDkyyqGq&t2=yQN&siMAKGr(S0rM}km8yJ?thu2NF
z;&@@ZEA|k#!yunvblQ$H$-V^lNDLXOtSL)DTGmQrf#`I%%brT{7u6UpO)Gr+<znTf
z73TC-2B`^JAaQ(v^-V?_Yk^ohR(^uzTM*Lznt{f>RFN$HaD~;z*q^<H(n%AJ38^^0
zFN))6BP@H`^0z7bW!4~*F#dq>8maSzo|&*A7%%s3=9-fW@1ug|Z`$o}ZrLb^#*n9V
zGK%ZYrF6k@+*}Qp*}_&yMw{I?>!5YUaTMHRq2@yhrzRmmYm|)(ePbmT2@P@Nlw(*a
z9Q&zh-iRX&)JoQ^>o`hhQ>pqpcm)y`As+Fh=e3IKbFD}Zu5j|L)+>#I9ZVXr3#r~Q
z-zrEZe#F*;z1in4(NQsyig;t*j@520>stRg!}KI(Dr#TF;9B0_!tMX12H<e+(0FA^
zmed<<;=?Nlvr=gcEKDm4qv=NNBV#LAt_rzPu_v$!Vyr7zBpsjx%;F0P>2(Okmpzuf
z8(oC!7l7M&zo=L(h~_qIw2hb0Cta}?P1tdKU*>8i<$H(j)pBd0MW;CnxHL!sOKD+c
zAG}etvW?WAe0BPb;Br7V!GOhmlY7*d6IS_xC%(&RDQ8%^_Ex-8k#NerJ@j4T4$gnh
z4)?o>T8s4^?|{b2f}06(Q7y;(u@}wZKK!0dyStd7jTNped}w+LgC7(nHSL-lK)?Z@
zbdC5O(^=7>l|t{-qXf9EEm0Ta*$Iz&e9O~NB}eXhe1wQvhZZOt-kWZv@8>0N>2sZ^
z_DM!sy-r!AN)AeiN2SXiYH;qY)aCXZs&e(>mFV-x$E8+YGsH6U6_f9^j@v&rkD@Ir
zd+&rP&CgP}=4mAHyunGqPDARoL0y_NhcraUCOcFfa0(ux?JIT2P?f)^h$-<luB7Um
z>YSJ0hLhzt9O!Zr9*xoYzWaZ%X=l$gB5c^~-dMB8$c&yy?Y$NrF2_wi!9CNyu;nI<
zX)wYxJdL&4NQ|4iuOp0L>9j0rS^HB*sH6!#6aukN&WA8v#N-vVFDP$5VM<4&7~y_L
z#Mz)j6SC;u%R0?yJ|Phr9llb_{`(m$z6{o^*ezo^`1_Ysqmt(b$&FCuHXB3eVh)CH
z!8&cC6E9I(EV;!W{g-77QKk1&*<wm%He!8wrB<CSFs14o3&CPaRD)OyEyecbggmUB
z`b8}mAbp}R3CQ(@==Yw3kZQ-YB(B_*tY9?uJTuuM07p97eEp_{HQMy9v&l1n-W#Oc
zzhG3>#-XK-$fgeI_FOuUJ<_kUuLNV&(FwI<@EE%&`VzU5Z}amY@+4pRy5}03gD1K(
zxKCV47bg`!cNU*loNCS~_rQ3o)Y93{`q65Aslp6L>2e@qrd@KK_>tJMOf4gPyS1U#
zu9`>-S%q07sqbf)0v1@K;8he(wpp`clgCjcd2ho|H%ZA}6RE$mr3Mzd?BHZlLT+4)
zwTdYFHG+=*aH-Ix@U3V3C^Wt|jAMSw-m`A-5iS5(!NAibg!({H4b{q1Ho@N`y-uo!
zOSbK$M&?C!Vi>+uAWCxM!r`7-x4`8v`Mk*{vZC({vc7HtL&5rKLh}07*35w%oHqim
zc|lqSQiUXx1&U&wld5WTrb3Rg5JG7J%X$oN%Y){6;0(B<4(hcwdd16`we@5mpP>+k
zRV>cnJ~2bXXuH)Ay(%K6bTHq`jjoNfP?OtLrXH?JXwjdXwW{GBq2HNWYF^W8>B?tj
z$BD_>g07cCQ(9d7;i^Yh&@|1j+kcAHgpU}@%E6giFxSEwCpO$IMsqPf%><vMaE+Tl
zhMcyQI2ZZmjOAxjciK!w;-fF2n-&?Eo~4_X2|76*ha1)Y@OMWS6Bi1U@%3fjP_nz+
zt$CD~^@xVKXrxMXA!MW;CyZ3rz1NtDkRpYbv}baN{Jbp$Ij*1gCp$4WP1(-&?}1sn
z+&4c8YhbnLBQH|&@5jCOR$$2<>P?!??uQ%DOOZpLE}}WEi_5Ti&tve#>~<jn%v_ue
zc4IW|<DSFemrHr=$NcelazPtCM95&jTDlM=2MRWFz4VXvxMcC{8y%}*yiAPF6;#Eq
zF}^HZ*J~JCaN#+*k<nUmHycA_xbCG|6!GA>8MB_{8MJf3OfpvUp82O}6+VYt{&ZnU
zfuKx&sZ|``^IvZ@{?lU%Bf#%MH$#XrwZ82lNVtycLndjy-K996qyx64mPqT_+9{^J
zoC1#Y=vBb>&<dl)irih)${sGq{bw}bu}>UT)5Z`67viqxhi~u|Ts2bY<wfMBg3p7|
zGOT>~gF%XO7)pbe+JNj$i4Q{P^aeH{+C_1T^sK>9ju1qDv=|+L$KST^%ECA=*Yiuv
zDKcptuX`6+-!FFAI!m|+-DMigD|Ki}3?aHonUQhmaUG02xCoH%Kl;iWgdW<%4=4Q+
zf$Oz5`YTX>=nY=;V2bP)jus`s-l(vB=bR8IP;idXwlgpcjTE|uwG;XGav_+2ojxvZ
zbr@Kn>=pf?PQMN-=m)PQ*?W;>a=2NMtGZrsB_o!H3n`Hxp9kLnLBuUwRdUg)1CH{k
zTE}kJb;1<SAhZ+v#zov`P9G={u@ILFQy7|q_KQcvUHKgLwHykbN$PLO2U|Q0%-G<U
z9D@3$qs;emkB-2%{uU9i*<@`=OJKZ<H(t9bl1Qi<We)znJzSjJ+a)X8cI|R8INFA0
z&1maBa!CQXb}f~^Ub~KwIJ^riJa=<yn?~=x53{Q+&Sh4~k=wQj-T7Nct?AhdF>JnZ
zxP(%RpZZ%k!A_Z|fgQ8-*wIv818bw543Kf6oUK2F2l=+YfGT40DmuGq;!|QpotAe2
z^9I2uM07e;bOA#L>~y}=$yeIjHTmA-sFHs<f0}()#xj53vh#{wnN-b!;m?WoP8EU*
zIQ1{yO&8M4@{0~SO#^m$uZ=DpFb%zWtcklLo!2F4)J|nehSYPN@F8pC`;vAB35Fqt
zd9u82PL3?P$PQFXrpc3mxLk{J_M6%XetsTvFaUznq!@ih_XZ0t5M>GOa7n1XG1c$F
zAA@W2XhL#vbF_|y?oebOXLZH~5jsyikK>E1IQTfE8e*b36J8a>Z_wGwkl}($WOBkB
z=EG=7jP^&p71NVGxt(&EH`g6dk#RQ}zMj3wlz}gRdxbEWB`eYP&B|~GX;{&Wl0%=p
zV5r%sd_tbaWLa5ZWQ4bKy=H1spR+jiI7dGUl9U5T4Yd?}VlrW1i4O7%Nx1i0YFl9b
z9F8oRrDKh<#<t$cth7(>TvZA|klA@VdxlZAR1Y9HlDq|6F><W>4eW_O5T^+ufi#cp
z!lsA!c&(uLk8w43h*L<`8aKh}bmY!Mz`c<y0!iMXI+I?evfI4}E7GYtvs&XTpKFBi
zzNY~XmBb;~DP*g}Je6&UW_m8gMS7h(vb@fX`WB>F6-N<T(*B%W={uD1E>18^-tNTt
zq%>`sQbqHA?Y6_tMF&ra3PRH}>zM4??KzRNa_y$xf~1X;vrmSRSrJ4Ha+4=(pX}Pn
zncW4-zP&q(b&ERzH*(YSvo=<^25!cDZ}a@LnqIgD5AGc4MyeT{1t877+<jONc}E}c
z%jJ=&Z(6yfEv0W7XO8sZVp(LR@2w5Ggv_<f1Q~<o!ez3ucjj|Y_?^}qEh9Cnm@lCQ
zYm@dbvgTxmD<*KO%#JD|aiuv)$`8J?*jX@7#Co(D&7~_nHP73zsnpF}O5gF%Idq%n
z?$5wQnH06?Ken%mEA`J=EhhwPtS4rK8Kkr<*}EetI5_j~TxgHNNv@qVZ86i03fTW_
zw02snAVPR3uumb|ILRl6x0L#^1NQ^DDRG!mULP<Bh?2n?c{Y70I~VQMy+1UAHAW48
zRkg{<SA|K6k0UxkP?XR}$)M3$1qrNELz4&r$Zk-sb>c63$Z*HLc@Ae#I;)bJYjl;U
z{$=d&GBd@=k*U#^V(mVqubPTlc^7?A+U@zuh=qb!7Ng&VkV48iwuO=cY=E%~?99f)
z$LEf8&odj5c~br7Lc*-!%8--XIm%@<v6B5xs7KZOYthS)7r*}=gVhKa|Iw`m#!0{~
zhj6hz+ZuqCOq_`%uX%%$uv56j+F!;2Mf0N+#3(tT=n_%;2X(5@jsJJ%paaP7^?A}S
zM*bo<5s?1k%;4W30z6z){k}K5*l?sZ*B`^yBP1pEIn01qS&(ERmRc3y|G6Eav1nOR
zOtWDpLy&OjK@0L>0bdV>ySp%j2+(B)?}O~Ob74>aj^h&48*(}qz;TTzQx5BzfKbD#
zt1dXV;^P4s;H;BaGaF8jsQ0i3x56vi_>u3+8d?u&mJKVO=A+`;UcB2kospx--ZEYa
z`-uL-boBfFJ=#3`FATx!`K04Y&3Trj9Ldc5`v~OHM(URVR9t)AmCF{8%BWeF5i^)~
zb8vZl*bxXrY!fT6pl`#Xd5ln1yrFI!;2)Kg&6V`U0yb1pDr$syRtR%EeR;4%ok6zs
z0$xJgE9_58eab`{!(M(K`|ivLvyLmKcn8d=;k%Ul=Us|6;U#<LZQm4Fu~HFp0K|;{
ze5ugArAeDR8Uqn<ZD?xQzBXF6I;tZctW_kYZTE0(zL`m|vklGXjedg8u20yIyON)N
zY`!^3${gNuJHG4h&1moAIWiR^uYWF{XoiVj!x>lGJ(@-sU&eI<${C1^a?veW6vBOK
z>5vI9#_wWP$TiMm#%u~uvG<CJwA#WAs>_gP!R~5iYR%JeN-Gi`7xg+Y7PXOp1=^%g
zssq+wVp3G(7^L`7_rr6%F}`u98SsnQOEk<k{yg-~_mN-EL2}MgvpiL{BsBtQJOzmb
zn}D;9WgM)-Omfyz%^CDiptSVq2q{l~?LdG9e;;4*j*#U+3%_(W8>-!t<!WC6$^`T$
zABin1t#Kd|_^=YJ7jJ0Wa$*NIe3X1vw8aHVZ>~x#_R-zoTOEa0-H+a!<!571Rb$G>
z=i0Nvk~pDJ>5@!X)0E{>lf3WA6!Ue!P<7PO$zbGT@h8i==^P{;jnq!)YNdD&!!m8|
zJuTAcznf=qmQ~T*pLnMjNIX~(7&2)*Sgn;gOzxlO$&YtK&X${X&@Gqix`Tg8-dlFn
zkHzwEHR^3XiYw&?Vk`8R_|38aD5%%ra*xTWAWL(~w8Gkt*-VP<y6!PkB2U(2E*Z!y
zn$de-g%J}!$i?`p<>t496X2WX3|85MQ)aV;A)BraX|o)fQTL2*0j%G5GIPhlR#=fK
zK2M@w5>J+DV0>8lemb`SS(4Y)K0}566JX%opR}mo7zXub%13}fPU+`uwGIF17@8RN
z6r;j4A9(dxJo^ezath)4bxlZ03H>RR7M<Tm2c1ThpalnvGPbc8IPUnIG(|Zq%65^y
zADrx|%(Z@=;$D&BJXjgoV0`&XF-zhb@yLjl){~{OeW9;6oNC&#UEio8%LT=aPeV#~
zu^Wmx6KbHB&x$lrY85)(hOwli6@fNWK>=%*RpE{oTp5nmmC|O)a`#G7|4?^OgkOn5
z%z{|OpiD?M?82Eb{u`yj{KZ;H5}Shbot`U`$PG?4tHOzKFNU6sM0$jLjvAW$sT&2v
zi*AgATFc!X$XE%zR$iiHQI9KJqQW7J{EIgv9yY6UX@`lE^>cFC16F!jCK5Sz7en3G
zkpb<9Oa-{uyAzJAhX{A_TEb{Oy2X5g^j=ani(3}52T4D(G_R^X5m<OqYfH8JH}i1A
zYGXb!|Dm5B_wa*vR&NiJA1|vS!Nt%d&571}THBL=y@%ij-NhzVNPfP5RGocX7wsl^
zzdg8IpQnzJbkH_v_VH-jEHq`kJH7_-y<WVoKT)0)@!@>ju<^a!|9MK|`xxc>xc~Wf
zn+4b&Z?=ZBFBmYbyed5>oSc4Yf23@_uWtT)>8$cRJ-O@rxGmb%7dvjbADPbT&>}II
z4>VtgS9S%5d8+T}e5(3*{P2F6{U`|qTdZ}9QVF4(^yuK_aeks(xDDJ?kl}h9L#J#J
zG3Tv1`go-KSrq!*lG9<GzaJ{|Y=3gtAROmilDQD0(wZriZc3%`Gbb0?e5~^t>UG^_
z@NvBJ^*U-(IpGe?u=DF;-Nnf%ey<MQ{>`XUB`8^`y+SFU;{M{-Dw_}Y*E<nNHjjws
zwe}0)<I1M(O-HhYC996iRd-;t$E#7fbC=4X`}Gm;&fGp!^{8^kK{^pEb(S~p0W5m2
zp+)GyEEB5fS@`7%&!0a!($33!sV*%|vW%a&HE7OHDWcy`gjA=8bvFBSJR$C>@Op+L
zPlFC5dM<D736X9HcaNOnCz+n#Zjj#IbC9MPAESSqfMuB&wmf*FaZbPV2i3@ucpmDl
zbsp$dPhIB(s6RiJ2Mlwd>`UQFKQUwLLtI+Y06n`k3X1a@dbnHd&su6%c4P?_bv_~_
zZY|zqRL$JonM8;8Z$!-E-4#Xb@(*yWdU>0!yVTX#KTJ5^x1H2kdWA~^wjdqh9Y-@s
zQnqNc^Cmw7oKjWXi)}<FSHpA<zBY%8S^U`|H`Z%6uj0FbUPHB*?Q%amO5$C>2omJ#
z+6s#=VIFRpygS(N9jlf@A6GK8v3WaRD}TPAUb<Jom;Si?+B=EG%8_w5QMjv~WxVUz
z!<7a{?U@SOQ0c<@mG+$(yWU~*L-yx2<XFIq_aWqKDBb&)16MX#$HAfq1MJ%jnU~xw
zV`97!E)8(;C+5{&?TT6+&ZQ?aR>S%iNbcDA_Zei@1?qP$oirT=Ab0+^jR=o3F)VP<
zmkCnx`&mmq{6D;W%sXDzr-VGq)-Uw=AJ(k*ytiNK)gBwjs?k0=XTiPaxwm-qV)mac
z`G-IzgTie_-)!)gXjG{z^E>}kF_C^m(w+;Jp9m@OCG%SCv3%?-M868&D5sq*%U#{v
zzr9o8*S?enOu#F>=|0y7uz_3g8hfR6OwFL;v;HhD&~evV_IQ2l=#a^3oCCVx`#X(9
zj;j*i?D!@ik&`PAzx1X1)=Y{c=Z2w(TF3N|x9VQ#JiMwN8Ry8rYO_#ol|wg-&k#_$
zpwwdMMRn&J>hp-LjsM5%-HYz?>-Za$+@HFrd;HF~`T0}%58KzD;pG&;P)62<4vzLl
zdRCv`Z1l~cSP19|K0gTv2v|7S*y#V2GyNmy=Kf5g6LEDEQ*hLCG$Qz0@F~-y2QUP5
zLIMN~1at;^0Lshzsr)yk6Sc8+{4Z@|8hRRf0#-n=^8Y9S^!{lC<9{k6pi^|SH6oz<
zu4iIIKtjOqSLNUJ?2Q0rG5njCPR7X4Oi$3pl|Ta^q6ajbgMfjNo}NJKFLfb6#Q=Q=
z0_Oi@5VN;&vi+~d{9Vak($6e_7o7s2YI{9v2iwoe4BY+|OAt8PI~o1U2?4Z(jhxL4
zjO4`xKZXDFRo=+K#>w8m$bsO~Zt_t7(=|2#|7qV(OGz79n>d;hu>Yr7qGpzkM)m}B
zqLu*53L6>N82(k$KZ*<lY|I?2pJn|sWUlGwsvfQ=B8^oi3iCYcJUp{JDUjb%z9GjF
zLRR_v0|Cb)3TK8903)we3+M~SLqq&QP}7zo@Ch`Ty22tM@U3O2MZh~f`GX{+>;kzl
zii(c<-I2If8-<ND!NVPdw)Mf`qkZ$OW0gfotE!T->N!I}h@4QEI1D1XE58J}=;!0>
z0w1z|1)(q&pV@smkQ+5`QgpGXU@>{h`_UXGkFgwKUyxPp!!+4Jg6D;HTGX8iBm<qC
zx1oN`Hm+x2^wD8W)uG`TeIr%Dk~jV;MO@KD>Wg6k1I8*_wbpB2y#z8O$8=P*^F3Bv
zk!(6wM#2bF^&46v=xmm!p}Wq0m8#VP1ED8ljCe?~E=d~{AkLlT(6BebANaX$bjff-
z92?U!*|ETZz=1Jxs$nQnH3^b%=1KqN1FBp>JFk!NID5{V{ABHTG)XBt*i)coA_mE1
zw{7XY*|FkpI`TCri}oVw>H*Yoau9mEPaN^z$@j2<^hg7q^aK2r#B$HTW5u27^jsUb
z=spl+0UMW@a&LqS8!{WOR}W+Gl6Gc;u3v(&#X)(HsBx1eTW!Pn!XeX5iER}0rk34T
zrwEw`F=wm_oxSn)>Ek1^T7eJChYUpDk6CIk)~PhoJ@wX^1a!Hrs?*iz=Tl`$Ly**|
z_EWO#8uW&;Ster2CsVU3Qz=27zbb<AO-plhTNd_~<=q6Tc--I#s*f);xudV;t^z`v
zE~gAu<-pMDbWEFiJCCCbj$0&>u@NDhTBl}+cxuPa<rtXDg0Q+D+#V&b2`KaWCMVh^
zz0%4si!cXQk>R9qzgG<Ecs#5xigqRsPM#y4u36iik9LOIfc|Q^NC9uO<cOX@e2O2k
z&+kmvA>%X?ixv7|za-Q%(U3WRuGGl|{MylcKXeDHk;Tfh$Y=&W%*eB>hBq27Ul(i?
zy9Zb{U$Ii_MD^Zi{r0PL=K!8BI8AXsPq>}k?{}uL!HGa!uYMsp>S(|8Gaz1XR^jAI
zZHH920kj&T-K<j1uTUX*nw<q|E#kiO+O<9_Raw6!x}==r)Y%y)E1#S)(&;Dr#|kMv
z^A?z*!V!KP>w^WERU~GV8e$^-b+j@Xn^x<vmq)uYt;%tPmB0jx{ao8=UX-|>1<8>b
zPs$lT=V_r~$sDyv*9gmWg)PouX2n_U!*f>NR>Te3IJMJqY1q&(Phq1(qaiZ5oRTiA
z#k^vNr8i`6PP9$RsTMLM<xN9Tbb&K3#1;J1Lo;`zSvY@l{svX1ixqOnmrfk^u;97N
zoY)Ypq*}}{TNe^!{uV&cC&>LRC_dW2hf^He62=MEDX5&AF*P!Apog3_G%9Y8au)}_
z6yDt6u4V#6<(EgilAu)n@QOj@;F`#S=b+}IrVFN83GHkW$7ndCO3KSur@W47wc}Dp
zm1Cue_R97P^HZMF+<9{zd2y)UVa|mdruuIb<H}}@_1=4dCJTHFM08vdw>+X`-<fM&
zGAnW9QwK#^ZG6bY_ttLv9XR2gN@joMyfl+gG1mD|+=nqy{;2*Ia)LH7N3E21FSUpg
zl&cOG#K^CJVFdSwi*~(K0&dw&BjchiC{QKMSx*FoYBNWbBX=o~b=>&YV$A#jS@LbL
zv10X*WuRX5V3yO|rRHKq^*%ecD#5hwc-FF!QOYBcW?EZ!b(z#CqfvBKL`SdFm@5HS
zUG>JIi(Q3<2hDS>XyD{{Dh7OB*1hXU$RP*)GUry&;ZE9sd~FcCr1v)Z2min{NC^<0
zuor4}$3V%~XL5s7h9p{M)>+sQZS?|0>`P4a2xVeWr)<e#%6|NjEYz^U<IJ0#YIe`e
z4#G@sxmhz#D)Zk<e^@I}h4S^}>yrgWe}GrW6#LO3#Gx=!@5L5G7&7D$_GKZsB*P}9
z(dGGDGaDPpYm`5AlE5JeI<W_X8kydmXd#3WnG-RTP>@g-V#ybkttvGjSiVX$#v0x`
zjW)C-S_D(d9J-ol90o!D(zE2P5jP&9I)$onRJ|xwilR&nAKf@)NQ+`K-mZio9K@bj
zGHv{+ICoDTf;MA~vOO9EZSrDi8)gmOixlL%{O3=OkQW?X*vUcA8(!JPcp{c^eU%~7
zA>!CdP;x@liwGj!G4>xn$u5!oeOikK(I|I|jKGtt6JiqZ-;*YOD%PtTu4_?j>UhlI
zZ?m2@PqsJYRI7hPR|!HB_HfW+XJRhOybe+#s^%BqJl{&1HghhgduJ*WLspwQ)kwxa
z2w%;I^G~Z+3-!Qesu9etV%Zsa;srewX`ITpI#kH{_VUG6@c+zls=Vxa#`Yc(^pZq*
zMDu~<55~N((zjb`_c{`TT;$xoU(fFLUSAICL><0K{9MsFxje-mY$eBxglPz4jgZcp
z%{S{Xvoqg@iBF}Y0C{is6nE$f)NzEC6pn||Skl}r=VRZW>y6v^skw$wWa@rXq*#*R
zTv^P$7fTxc^F}cW?}gJTr@cfp?}-0;`da4Y!K%(Jb=f^6tFsr~@-{lcs)Jx41D1hz
z_WtX*%d@YBhCvDzAu)x#;K|o%!R?-}k|L*HSAr%`srn@B1gVQ|9wB~ERR&KA)8Gmk
znBm~cli(q(_Bmf8ROG@NtYA)G>&4q7oQbHv=DU!C!Evmg<lJ}6U#v9CF!b$Wu5D0o
z>0gG4h1S+u3%~v`nyYgAqkix!*Ixv3`wKsZNO~S!t^w9{#!<uf;S%0@w&p*7TAb)s
zfA9b1t(xQ$QrDOq``JF3BP1`newekWmxxE6Ngf$`$$*=o+J;?{W2k;g!XDr*N0Jrv
zj43-@5G5gPTO6AkAt5b|k$nsqGA1TzhIy0tJhFmcyOg6_(ZER~FpIp4@`pdYw}8D3
z7p!2}Bsb@p(HuWZg9vp~o2j$?;CF;pWfj6iytvv_PGG*gI!5Zr;%m$1GHgU{*hc@d
z%6Zw{{0rwD5M;KC#O%zi><`Qh7@eY{djI;qTYh(WN%Ior(j-nP*r<r9*l!lKaI*AW
zU#;m0!So5?Ua7TZ#>FqQ-otJKj>Bda^MhuqikieAQU$!MOy;mN#F2|9smL}lJq@=Y
zCyu9)<!H;XetUSTE%#zS<8Qj%@D1R5<nHbDk(A*tW3Rlt4*n!xo_xNPk{TU_hLy2*
za?i0G{k6Bp=3oyc3XhNKSY)YLdp_^a`tie$H92z0NG~1zJeoS=Dxz|pQtiy{v0-CQ
z?m~dMW*x|vw?^P2Q9#s_gE!@tUtf{K7aB!$-L7R-x~|ZAvu5+M3>kg;y)roLRr5w+
zaWb<Vt}OK@Ep0HoDOsxitSy$o8byri&FS~l-W^62YPADhhKX-s4y;|>BtU;Gln&yD
z;qpU|8wqnip2!}0FKoGB)@33<EomxmB;zGYiPa@{%_6ns<u-a5R9m9p9m5mw5{#uB
z9_7ux(z#ehvvTn!c`_DjChQW3Zey8BdWi34?8{2ZEyO*<JH$&L@?a3cn1>;x!wVs%
zjo~XDTpdp+RfqDCB~k59NG?&@D8Y5v#3S1ZKDj*d|Ax}3E_;=FBK4g7Aa$Wg|J5QI
zGyN@r^as_`ZR-r{i24qJvgcy#8!g|WJn6U@=8UI=dsTr)TIF|HYRvuo*xP8ajUl4U
z0~YWiC{FCc28ll26vX;syVD`}Z{ZQmv9t6YMlH;x1<zVs{J6D61xf7(tEywYabWqq
z0<{vk5IcMW>x8{~guJ2X*T=7%NhKBAdrcM=MwgpdR%7I%?xoRqAsB{s<e6By2tWov
zz*>+FP+>|ZbHO^!^hKj>^lj>c**(GjNV2Q3SkF00q2yQgpru#Nszb7Q&$6pAf@B$v
zL_*@gZsB8uR3S(*Tyc^0Ot<;O$8Qra5q9<dydqhFMsw9(Y%;!<juyj>i(|lQ;);90
z4u`T$(p%jJQr|bz+co^nrfY(!n+P_>h0kP!Y-S=JbL-_<YM2pF?=kh9+Rxy@7s#p-
zR9>9(#a{9tTn%1vK@0KQLQ2!Evw}J|$pLGpn}7o%oArpHL3a0tl!#(2U4(?p?Rxt9
zLVoRh6NMr!N`321$fdbzb!r-_iHY0p4tlq634Z9Ghb$`GYiGI}R|s;x;HtJ;jXWG|
zd)gbD{hIaT&;dc3yW=3w#<$yGy^eC^XM^2h`Z3dCk>eUZ#B0q#N;_*7YH^<4P*Ij8
zbiqL1fPe=dSl~DN(lPW3Ska}{#F%PfX_?&A&J0NVw()GbN#j2`tD1ruZHtc!8i+r!
zejl!zzB26X>P(w=Vs^`5jbM!qT-%Mzo|*A-S-XYzK!oYlP)EL)#4P_&sA1YQeoBg-
zNhYb0+DUwLiCecr13bVYnmQYI+miNPhk=qZ#dv&vfan@BocUOnB=ytI`C=CKNu|VP
zN{C@+Ad|=AV5-5Z&>D-gNWZI#X}zxU{r!-uXfUi(_*I?b<Tufdfr7X<If*2xXi1!Z
z-hMTodl9B{qLb>W4z8o~_csQ}AKv1UfDlSg#5PI9ydZf^on;Jr6~s>U+NDA6%7dqd
zZDtGK!~>2Vthso;wZnFhG<!K&hM~vS<`$Hqt~OP5NzWsuiM2T_tT!E8%aNlm@}bh~
zVBw1FidqJC1nIb655=JCa8i$#$sCh+AnNd`l6Sn1n(T}YeT8dx`qK2PT(Cn~<WZ6o
z(@>Xu3GcULLNBCNZ)O8znSzU9qf4RVpBMR8YgC&A*9J$jexnuHsrwaHp(ZPqnc82k
zaHPJCaS{S#24Q^qmBYC5Q|H3#nLbdl$`#AM9mZ3&xcVnZEF?~|=t3L97S9pbY&KBX
z$^y%^S`6QwNu(Af$taWPs@61H+Uzy6ji<3MJ3j_;Q~879_7AJHd33yEWz!oBhpET%
zVYhvjK1SFf<3xA3fUA!9H4O>P3Ji{fIg{RFE8}D((Lr!QQ-1OOQi<cNZ(R9Eil+DS
zLEC=x)!6;Pp82x-D94BL(9BPDjMf6H@Tklga*X>77diT|Bh?j~7a)R+FIoU&z%ID*
z5!TMlw@|KOvpa}~%JEh*h)R+1F@^3VrbTQ`eJ8&D%O(2b=lh_LgE&ohUD$>-{IZ~n
zUfGvc6J0sgQo_+8g(ZjZ1;R1M{tm4@PL439q&Uu{UI<*#+M1;38%-iMQ@rIUi#>U|
z@qP_fJ>q5Wd!RC-tUC9ZuyMn?^5F6O<trroK^MJ=0OVM3FBhVc0`y^NdyEbrOZJfq
zBU*dJ6FvCfzOD3{ossczl#KXh*E42@Im|llKpwK!?(!jKSdoi)37H}%aI*z_IBs~!
z%>I^nhtXA>e{j{H+-3y71X-4RIpzznnBRR!FeD{@#hDL|<}|>UkMiKbq1er#;zO5M
zypA6ybIX?$eW?7lOWWAzJZ(__LtCzAkNOqIxGTsJQ_8q?89{!76quZ7zuCFqEkaZ9
zknqwu)uxJeTu;Oi{>c{=uzAo5nPsHy<l7AB&<{wCP`5}+A~~;PMsgv^^J!Q4Di{OI
zN1n=TYW_;d6fh1$sD*<#ulzvA04VuLK*W{=kL$~;QJOR4z2E7)R9<2y+uE_Rl1nV{
zEO^qZpm>Ug6a2aPQeEYVzCvMTLU}i!mnh$y&i}}b`;>es9WFLE(9Ujba8l%Tukba$
zs0z%^OZ^(h_f*m?*W!%HOUd_ro$+WxqYRF+1^s1U&tTqKkL@15g^khJ2C%>0BeuFC
zZZb1R^^9i9nn}Tvcvj^%U!NKO6&XnMe!8`{4w8__VAw1kzCQ=&599EuV$D!<(0#nu
zRyx9xMy0`GT?lM^rda2c&GR1*WMDM)!Y#s~Zd`vt>O(z)FRhZ33^J<o_GrhvmJ1e0
zF+|}U;FkxnhGE>kqzt$3(Vt2eUc*bkYA4CnN!qKAkl5@t-K%TRtLV}Www)|!Kj>#h
zJ{f$2F{__e#F|dT%>5>IJ`!y9hv^%Lnj~ngy#JHOmwL~!p)}-4f8^5%ScrtY=&B9>
zW(L4BfLR{?tr$bZ8N-IcVlcWx(2dN=a-jokWeI2j>OT>t_5wP;Zog1Bs{wER-qHYO
z`|_%S&|%lDL$&3O(4p-H|DoR10QFc3f|a&KCv#QcL-*V@4}A68XR>x{WS`+x@~h@R
zNYY?efgICg0qG+%C@<nwjZc``l?k1vA~5<F&!b--nm~t9T|Xfnfr@@s15L2N92}zY
z_v*606tR0NcV+EtMS*OfUuF96K@?Z{FgZcKhWoU9ab<&+g=YUfwnO%2ON12(%}%=Y
z0J4F0mFTkx>8j9W^A!ixR=7(K8ZH6si4eE}JnBjv7#tqukDu7q7LoH7n}ByV{Tvjy
z;2E3165Un=R59XJi;p>QCt7tChPFd@nTOx&y#7+_VDAH%UKF^tK(3CN?>dM!TD4S{
zEW9G*(sgXu<&bZZ=9NB!znx?=Ag1+F<NR<F<kE>hO`5@DqW+Sm*`INS?`A#FSlo2F
z3IW}0kj3=6#NPEaAgtvs*RW>Q8(&XTb<b0YJu7@z_5(b}5moDg6Zp{g_5;4-=}&&$
zRs$|maoR2WT7CjX6*Hdjz`qQYk>sWq05@7=;KmT2n=k2CJ?5(esoK)FBlVTKMz_XC
z1OyEVqT$`X8{}OI7#gjMsh^&2a_|s*+YI>T%a~I)4%yhk76ou!s;)6I_wpB}RNWRI
zGmv+gE@X+TW*>?LAYLOFZc^PpAg(CbBp`T*->G$DeS*G9pMi?V(04-yfZ!p~Yx4_q
z3_zz6==g!>89e%_(aUzJuDP874c&BOnEzoo-v*`&$3yEEgT^T6eFG7FAKN4T`a0&1
z2oktEWDDFInChvD0u#aZ_#HVAgI=}E3zfbY<N}rc`^gA6Yqt-v?W8RP<PqK0MJxBK
zHQn0$<oM+u{>~1tOLTK5Asx_Xh#}Oe)}*8dYhP_1nT=6s9tX#bS$`Z{_iy}-z-sGG
znIze*a4DFalgtD{LDpJI8{__!l#au`6B)j34h)Wx4_C4R;t%}l=Fvs#pd|uF7;|o7
zY+szj5u>TI{jg)BC%?ge2_>w7M2ZgZ*AHgvibA@D4z}=J0!HwQzyLlE%fXc_&G0dO
zCFcb51Ze}w{o-otE9Mi>rViSr33Q=v3rU|oy@s&Ww>)7w_0^QL7zBrXoRI(8R}%&X
z98=u~z8d{YZs%}8CBF;-h$#(?_C59a>(6b%kJT@)qh#-$!0}P3?El-Z{pn==*RRb?
z&-kyWnd5)EV;MeO$bb2y>HaT&?0>sowPHuD{pb-y9^OOM3d4efKqW~06$`M@yo&4b
zf$pP;Pz^9^w=TJML*z@KlY1XG%3^}{*0|ZMH3{9|>&)x|^c-2Y7<K#vj;<Lw6ZUn*
z>NYxdR;4pkAX8SY)a=aH=*vod_x#|JSS+hOY8|5Bp@3qWbQ!`gKw7IDs4DJH-r!}A
zl*N^_{Q7_GXmft7$UsOiUt&ug?zWr{-xocuaSP&gGGPvnp`mYL!eq2&m(J7&nq!y;
zOuTcA!s{P{->iRC+E2_klN3?n43iFcCimL&CVcbdK$TS^PG`c$CsrWjh0F>L6EdWn
zn=Hs;k~)ZClG=`aq8Ba{^qNlkQ6*Bvp>QiQ_mF#;0+6?hwgs9bVlq!=lZZJ)CVGxP
zskf!Js~;5gpu4tGbVzPId5IlhfmD#aW7yHP#Y}I%ZC=-zsCaq<r++Ji|KDTw*GT*`
zXiQ8j|Be~Mr{n)$ANt>(`%i2^*vP@a-ptm~#{Sb0{}<dKt7iqk4rHX&mDEJ2gpJJg
zl${g+F8%+ci|SdKS-KIB|D8nenMUz<qNSb*z<1C1A5Fo((FGa?dPaHz8fI2T0tPk?
zCIHI7#P|=&AmONIX=Wf`ZDMIeK>t@h0SALmn1X|m{V(>jeV;rHBcLmvEfmtT6*n?7
zF$EwQfMWg<DL5KgDHE{&o&S>&|CjmfAz(ThF%o<t2>*>Jd_pMy+Zult=cMoW7kr`!
zz$`v3^_Nso&%x*~Fy{Yd88dqaM<G)^`+p4}t@jVl!1y-+^Zz$D!CwRN_ZcH%4FE07
ztW5~$RLraetR2k$75r7RikYFKsRIC|VPg2~#s7UUvC{vO&dS6}@c()Ppd&!)|6RhT
zl!fgR$@=?XW%>6z8~gv%%L<rYY)qeX>Hj`hnLhC%Ks^lq=Kfock?nuVpeJAkbe;t;
zCqCQriS>M<PXGzv{TKKI0Fi8ztj#`=9D>hl&3_Nv|DML5DA(V!Q_9Tn(@vj2nEZcW
zET>P<>%XuhhX2ONzT4XvIvD`aBXR>hGkY5X23iIdT0j@cO&uL=Iq3j^96)MfuV-s&
zX5c_;V{Zb8zw_5D1fYM8W;WKspI{!jFef8DBP0F)SC-l1APmD$c+V-aR0y%yC3T${
zfy9IaC+N^3mR5>7RGc0=Ewl;Q@?_=beQ}n@B?F>&e1LKXu-|UFCV}5@?$pTJAD(f!
zc!edJTT`zow4DKq&cJV2!E&r@XJ?IwSsc+}`$dx=&x`q)#w_3yO(qH{(JIf<rKv{b
zoFGc-2uc*tsaDnc_vD%aPBlW8pM?lXNN08azpe(_tT%>6x;w;N@bP-L>XqWT4}(Bg
d&*uia_MNbe?_y2@n=nRqsYWDI6zAK;d;rFh<-`C0

-- 
GitLab


From 498ec63410aad810c7a22d784646bcefe57fedb8 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Tobias=20Gr=C3=B6ger?= <tobias.groeger@student.kit.edu>
Date: Mon, 5 Dec 2022 20:15:03 +0100
Subject: [PATCH 295/324] Update logging inside teb

---
 .../navigation/local_planning/TimedElasticBands.cpp    | 10 ++++++----
 1 file changed, 6 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index faac2b82..4167d059 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -87,6 +87,7 @@ namespace armarx::navigation::local_planning
     std::optional<LocalPlannerResult>
     TimedElasticBands::plan(const core::GlobalTrajectory& goal)
     {
+        TIMING_START(TEB_PLAN);
         const core::Pose currentPose{scene.robot->getGlobalPose()};
 
         // prune global trajectory
@@ -112,13 +113,13 @@ namespace armarx::navigation::local_planning
         }
         catch (std::exception& e)
         {
-            ARMARX_DEBUG << "Caugth exception while planning: " << e.what();
-            return {};
+            ARMARX_ERROR << "Caugth exception while planning: " << e.what();
+            return std::nullopt;
         }
 
         if (hcp_->getTrajectoryContainer().empty())
         {
-            ARMARX_VERBOSE << "Did not find any trajectory!";
+            ARMARX_INFO << deactivateSpam(5) << "Did not find any trajectory!";
             return std::nullopt;
         }
 
@@ -154,6 +155,7 @@ namespace armarx::navigation::local_planning
             arviz.value().commit(layer);
         }
 
+        TIMING_END_COMMENT_STREAM(TEB_PLAN, "Timer: teb planning", ARMARX_VERBOSE);
         return {{.trajectory = best}};
     }
 
@@ -193,7 +195,7 @@ namespace armarx::navigation::local_planning
             arviz.value().commit(visLayer);
         }
 
-        ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";
+        ARMARX_VERBOSE << "TEB: added " << obstManager.size() << " obstacles";
     }
 
     //export algorithms::Costmap to costmap type of teb local planner and provide costmap to planner
-- 
GitLab


From 49204645d472e4dc912f1c5c93034aa8e5bfd2bf Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 5 Dec 2022 20:56:34 +0100
Subject: [PATCH 296/324] scenario update

---
 .../NavigationSimulation.scx                  |   4 +
 .../config/HumanMemoryApp.cfg                 | 368 ++++++++++++++++++
 ...oviderDynamicSimulationApp.FleaCameras.cfg |   8 +
 ...oviderDynamicSimulationApp.Roboception.cfg |   8 +
 ...lizationDynamicSimulationApp.instance2.cfg | 229 +++++++++++
 .../config/ObjectMemory.cfg                   |  48 ++-
 .../config/RobotStateComponent.cfg            |   8 -
 .../config/RobotStateMemory.cfg               |  17 +
 .../SelfLocalizationDynamicSimulationApp.cfg  |   8 -
 .../SimulationObjectPoseProviderApp.cfg       | 229 +++++++++++
 .../config/SimulatorApp.cfg                   |   2 +-
 .../config/control_memory.cfg                 | 272 +++++++++++++
 .../config/object_memory_to_simulation.cfg    | 212 ++++++++++
 .../PlatformNavigation/PlatformNavigation.scx |   2 +-
 .../config/ObjectMemory.cfg                   |  46 ++-
 .../config/RobotStateComponent.cfg            |   8 -
 .../config/example_client.cfg                 | 123 +-----
 .../config/navigation_memory.cfg              | 164 ++++----
 .../PlatformNavigation/config/navigator.cfg   |  37 +-
 19 files changed, 1572 insertions(+), 221 deletions(-)
 create mode 100644 scenarios/NavigationSimulation/config/HumanMemoryApp.cfg
 create mode 100644 scenarios/NavigationSimulation/config/ObjectLocalizationDynamicSimulationApp.instance2.cfg
 create mode 100644 scenarios/NavigationSimulation/config/SimulationObjectPoseProviderApp.cfg
 create mode 100644 scenarios/NavigationSimulation/config/control_memory.cfg
 create mode 100644 scenarios/NavigationSimulation/config/object_memory_to_simulation.cfg

diff --git a/scenarios/NavigationSimulation/NavigationSimulation.scx b/scenarios/NavigationSimulation/NavigationSimulation.scx
index 5115bad6..535b4bdd 100644
--- a/scenarios/NavigationSimulation/NavigationSimulation.scx
+++ b/scenarios/NavigationSimulation/NavigationSimulation.scx
@@ -37,5 +37,9 @@
 	<application name="LaserScannerPointCloudProviderApp" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="LaserScannerSimulation" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="HumanMemoryApp" instance="" package="VisionX" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="object_memory_to_simulation" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="SimulationObjectPoseProviderApp" instance="" package="ArmarXSimulation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
 
diff --git a/scenarios/NavigationSimulation/config/HumanMemoryApp.cfg b/scenarios/NavigationSimulation/config/HumanMemoryApp.cfg
new file mode 100644
index 00000000..28099ebc
--- /dev/null
+++ b/scenarios/NavigationSimulation/config/HumanMemoryApp.cfg
@@ -0,0 +1,368 @@
+# ==================================================================
+# HumanMemoryApp properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.HumanMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.HumanMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.HumanMemory.DebugObserverTopicName:  Name of the topic the DebugObserver listens on
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.DebugObserverTopicName = DebugObserver
+
+
+# ArmarX.HumanMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.EnableProfiling = false
+
+
+# ArmarX.HumanMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.HumanMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.HumanMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ObjectName = ""
+
+
+# ArmarX.HumanMemory.face.seg.CoreMaxHistorySize:  Maximal size of the FaceRecognition entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            64
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.face.seg.CoreMaxHistorySize = 64
+
+
+# ArmarX.HumanMemory.face.seg.CoreSegmentName:  Name of the FaceRecognition core segment.
+#  Attributes:
+#  - Default:            FaceRecognition
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.face.seg.CoreSegmentName = FaceRecognition
+
+
+# ArmarX.HumanMemory.ident.seg.CoreMaxHistorySize:  Maximal size of the Identification entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ident.seg.CoreMaxHistorySize = -1
+
+
+# ArmarX.HumanMemory.ident.seg.CoreSegmentName:  Name of the Identification core segment.
+#  Attributes:
+#  - Default:            Identification
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.ident.seg.CoreSegmentName = Identification
+
+
+# ArmarX.HumanMemory.instanceseg.CoreMaxHistorySize:  Maximal size of the PersonInstance entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            32
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.instanceseg.CoreMaxHistorySize = 32
+
+
+# ArmarX.HumanMemory.instanceseg.CoreSegmentName:  Name of the PersonInstance core segment.
+#  Attributes:
+#  - Default:            PersonInstance
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.instanceseg.CoreSegmentName = PersonInstance
+
+
+# ArmarX.HumanMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Human
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.MemoryName = Human
+
+
+# ArmarX.HumanMemory.mem.ltm.configuration:  
+#  Attributes:
+#  - Default:            {}
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.ltm.configuration = {}
+
+
+# ArmarX.HumanMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.mem.ltm.enabled = false
+
+
+# ArmarX.HumanMemory.mem.robot_state.Memory:  
+#  Attributes:
+#  - Default:            RobotState
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.robot_state.Memory = RobotState
+
+
+# ArmarX.HumanMemory.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+#  Attributes:
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.HumanMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.HumanMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.HumanMemory.pose.seg.CoreMaxHistorySize:  Maximal size of the Pose entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            256
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.pose.seg.CoreMaxHistorySize = 256
+
+
+# ArmarX.HumanMemory.pose.seg.CoreSegmentName:  Name of the Pose core segment.
+#  Attributes:
+#  - Default:            Pose
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.pose.seg.CoreSegmentName = Pose
+
+
+# ArmarX.HumanMemory.profile.pk.load:  Load profiles from prior knowledge on startup.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.HumanMemory.profile.pk.load = true
+
+
+# ArmarX.HumanMemory.profile.pk.packageName:  ArmarX package to load human profiles from.
+#  Attributes:
+#  - Default:            PriorKnowledgeData
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.pk.packageName = PriorKnowledgeData
+
+
+# ArmarX.HumanMemory.profile.seg.CoreMaxHistorySize:  Maximal size of the Profile entity histories (-1 for infinite).
+#  Attributes:
+#  - Default:            64
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.seg.CoreMaxHistorySize = 64
+
+
+# ArmarX.HumanMemory.profile.seg.CoreSegmentName:  Name of the Profile core segment.
+#  Attributes:
+#  - Default:            Profile
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.HumanMemory.profile.seg.CoreSegmentName = Profile
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.FleaCameras.cfg b/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.FleaCameras.cfg
index f1a704b3..4e8563cf 100644
--- a/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.FleaCameras.cfg
+++ b/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.FleaCameras.cfg
@@ -150,6 +150,14 @@ ArmarX.DynamicSimulationImageProvider.RobotNodeLeftCamera = FleaCamerasLeftSim
 ArmarX.DynamicSimulationImageProvider.RobotNodeRightCamera = FleaCamerasRightSim
 
 
+# ArmarX.DynamicSimulationImageProvider.focalLength:  The focal length.
+#  Attributes:
+#  - Default:            600
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DynamicSimulationImageProvider.focalLength = 600
+
+
 # ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
 #  Attributes:
 #  - Default:            false
diff --git a/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.Roboception.cfg b/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.Roboception.cfg
index 4d7344ee..5e3f7339 100644
--- a/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.Roboception.cfg
+++ b/scenarios/NavigationSimulation/config/ImageProviderDynamicSimulationApp.Roboception.cfg
@@ -150,6 +150,14 @@ ArmarX.DynamicSimulationImageProvider.RobotNodeLeftCamera = Roboception_LeftCame
 ArmarX.DynamicSimulationImageProvider.RobotNodeRightCamera = Roboception_RightCameraSim
 
 
+# ArmarX.DynamicSimulationImageProvider.focalLength:  The focal length.
+#  Attributes:
+#  - Default:            600
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DynamicSimulationImageProvider.focalLength = 600
+
+
 # ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
 #  Attributes:
 #  - Default:            false
diff --git a/scenarios/NavigationSimulation/config/ObjectLocalizationDynamicSimulationApp.instance2.cfg b/scenarios/NavigationSimulation/config/ObjectLocalizationDynamicSimulationApp.instance2.cfg
new file mode 100644
index 00000000..5bc03758
--- /dev/null
+++ b/scenarios/NavigationSimulation/config/ObjectLocalizationDynamicSimulationApp.instance2.cfg
@@ -0,0 +1,229 @@
+# ==================================================================
+# ObjectLocalizationDynamicSimulationApp properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectLocalizerDynamicSimulation.EnableProfiling = false
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ObjectLocalizerDynamicSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectLocalizerDynamicSimulation.ObjectName = ""
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.RecognitionCertainty:  Certainty of recognition used in simulation (0...1).
+#  Attributes:
+#  - Default:            0.899999976
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectLocalizerDynamicSimulation.RecognitionCertainty = 0.899999976
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.ReferenceFrameName:  Name of reference frame to use for pose
+#  Attributes:
+#  - Default:            EyeLeftCamera
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectLocalizerDynamicSimulation.ReferenceFrameName = EyeLeftCamera
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.RobotName:  Name of robot used for calculating reference frame
+#  Attributes:
+#  - Default:            Armar3
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectLocalizerDynamicSimulation.RobotName = Armar3
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.SimulatorProxyName:  name of dynamics simulator proxy
+#  Attributes:
+#  - Default:            Simulator
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectLocalizerDynamicSimulation.SimulatorProxyName = Simulator
+
+
+# ArmarX.ObjectLocalizerDynamicSimulation.VisibilityCheck:  Whether to simulate camera and checking visibility within camera
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectLocalizerDynamicSimulation.VisibilityCheck = false
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/NavigationSimulation/config/ObjectMemory.cfg b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
index 9d742ccc..6811e284 100644
--- a/scenarios/NavigationSimulation/config/ObjectMemory.cfg
+++ b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
@@ -150,6 +150,22 @@ ArmarX.ObjectMemory.MinimumLoggingLevel = Debug
 # ArmarX.ObjectMemory.cmp.KinematicUnitObserverName = KinematicUnitObserver
 
 
+# ArmarX.ObjectMemory.mem..marker.Name:  Marker Memory Name
+#  Attributes:
+#  - Default:            Marker
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.Name = Marker
+
+
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize:  Maximum marker memory history size
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize = -1
+
+
 # ArmarX.ObjectMemory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
 #  - Default:            Object
@@ -382,7 +398,7 @@ ArmarX.ObjectMemory.MinimumLoggingLevel = Debug
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_robot_placement_with_ivt_obstacles
+ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003
 
 
 # ArmarX.ObjectMemory.mem.inst.seg.CoreMaxHistorySize:  Maximal size of the Instance entity histories (-1 for infinite).
@@ -496,13 +512,39 @@ ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad = R003_grasping_challenge_r
 # ArmarX.ObjectMemory.mem.inst.visu.oobbs = false
 
 
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show:  Show arrows linearly predicting object positions.
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha:  Alpha of linear prediction ghosts.
+#  Attributes:
+#  - Default:            0.699999988
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha = 0.699999988
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow:  Show arrows from current object poses to the linearly predicted ones.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame:  Show frames at linearly predicted object poses.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost:  Show ghosts at linearly predicted object poses.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show = false
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost = false
 
 
 # ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeOffset:  The offset (in seconds) to the current time to make predictions for.
diff --git a/scenarios/NavigationSimulation/config/RobotStateComponent.cfg b/scenarios/NavigationSimulation/config/RobotStateComponent.cfg
index 646407a2..6c912ba8 100644
--- a/scenarios/NavigationSimulation/config/RobotStateComponent.cfg
+++ b/scenarios/NavigationSimulation/config/RobotStateComponent.cfg
@@ -158,14 +158,6 @@
 # ArmarX.RobotStateComponent.ObjectName = ""
 
 
-# ArmarX.RobotStateComponent.PlatformTopicName:  Topic where platform state is published.
-#  Attributes:
-#  - Default:            PlatformState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateComponent.PlatformTopicName = PlatformState
-
-
 # ArmarX.RobotStateComponent.RobotFileName:  Filename of VirtualRobot robot model (e.g. robot_model.xml)
 #  Attributes:
 #  - Case sensitivity:   yes
diff --git a/scenarios/NavigationSimulation/config/RobotStateMemory.cfg b/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
index 8ed364db..062aac68 100644
--- a/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
+++ b/scenarios/NavigationSimulation/config/RobotStateMemory.cfg
@@ -282,6 +282,15 @@ ArmarX.RobotStateMemory.RobotUnitName = Armar6Unit
 # ArmarX.RobotStateMemory.mem.visu.enabled = true
 
 
+# ArmarX.RobotStateMemory.mem.visu.famesEnabled:  Enable or disable visualization of frames.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RobotStateMemory.mem.visu.famesEnabled = false
+
+
 # ArmarX.RobotStateMemory.mem.visu.frequenzyHz:  Frequency of visualization.
 #  Attributes:
 #  - Default:            25
@@ -308,6 +317,14 @@ ArmarX.RobotStateMemory.RobotUnitName = Armar6Unit
 # ArmarX.RobotStateMemory.mns.MemoryNameSystemName = MemoryNameSystem
 
 
+# ArmarX.RobotStateMemory.prediction.TimeWindow:  Duration of time window into the past to use for predictions when requested via the PredictingMemoryInterface (in seconds).
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RobotStateMemory.prediction.TimeWindow = 2
+
+
 # ArmarX.RobotStateMemory.seg.description.MaxHistorySize:  No Description
 #  Attributes:
 #  - Default:            3000
diff --git a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
index aa388636..d3524d3d 100644
--- a/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
+++ b/scenarios/NavigationSimulation/config/SelfLocalizationDynamicSimulationApp.cfg
@@ -316,14 +316,6 @@ ArmarX.SelfLocalizationDynamicSimulation.mem.robot_state.Memory = RobotState
 # ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.LaserScannerSelfLocalisation = LaserScannerSelfLocalisation
 
 
-# ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.PlatformUnit:  Name of the `PlatformUnit` topic to publish data to.
-#  Attributes:
-#  - Default:            PlatformUnit
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SelfLocalizationDynamicSimulation.tpc.pub.PlatformUnit = PlatformUnit
-
-
 # ArmarX.SelfLocalizationDynamicSimulation.working_memory.update:  If enabled, updates the global pose in the working memory
 #  Attributes:
 #  - Default:            true
diff --git a/scenarios/NavigationSimulation/config/SimulationObjectPoseProviderApp.cfg b/scenarios/NavigationSimulation/config/SimulationObjectPoseProviderApp.cfg
new file mode 100644
index 00000000..4121ec6a
--- /dev/null
+++ b/scenarios/NavigationSimulation/config/SimulationObjectPoseProviderApp.cfg
@@ -0,0 +1,229 @@
+# ==================================================================
+# SimulationObjectPoseProviderApp properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.SimulationObjectPoseProvider.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.SimulationObjectPoseProvider.EnableProfiling = false
+
+
+# ArmarX.SimulationObjectPoseProvider.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.SimulationObjectPoseProvider.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.SimulationObjectPoseProvider.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulationObjectPoseProvider.ObjectName = ""
+
+
+# ArmarX.SimulationObjectPoseProvider.ObjectPoseTopicName:  Name of the object pose topic.
+#  Attributes:
+#  - Default:            ObjectPoseTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulationObjectPoseProvider.ObjectPoseTopicName = ObjectPoseTopic
+
+
+# ArmarX.SimulationObjectPoseProvider.UpdateFrequency:  Frequency at which to update the objects in the ObjectMemory.
+#  Attributes:
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulationObjectPoseProvider.UpdateFrequency = 10
+
+
+# ArmarX.SimulationObjectPoseProvider.cmp.Simulator:  Ice object name of the `Simulator` component.
+#  Attributes:
+#  - Default:            Simulator
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulationObjectPoseProvider.cmp.Simulator = Simulator
+
+
+# ArmarX.SimulationObjectPoseProvider.p.initiallyRequestedEntities:  All entities (comma separated) that should be requested from the beginning. If you want an entity to be localized for n seconds append ':n'.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SimulationObjectPoseProvider.p.initiallyRequestedEntities = ""
+
+
+# ArmarX.SimulationObjectPoseProvider.p.requestAllEntities:  True if all entities should be requested all the time.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+ArmarX.SimulationObjectPoseProvider.p.requestAllEntities = 1
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/NavigationSimulation/config/SimulatorApp.cfg b/scenarios/NavigationSimulation/config/SimulatorApp.cfg
index 788c12bd..d7630d26 100644
--- a/scenarios/NavigationSimulation/config/SimulatorApp.cfg
+++ b/scenarios/NavigationSimulation/config/SimulatorApp.cfg
@@ -289,7 +289,7 @@ ArmarX.Simulator.InitialRobotConfig = ArmL1_Cla1:0.036781001836061478,ArmL2_Sho1
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Simulator.InitialRobotPose.x = 4000
+ArmarX.Simulator.InitialRobotPose.x = 2000
 
 
 # ArmarX.Simulator.InitialRobotPose.x_0:  x component of initial robot position (mm)
diff --git a/scenarios/NavigationSimulation/config/control_memory.cfg b/scenarios/NavigationSimulation/config/control_memory.cfg
new file mode 100644
index 00000000..53efd6fe
--- /dev/null
+++ b/scenarios/NavigationSimulation/config/control_memory.cfg
@@ -0,0 +1,272 @@
+# ==================================================================
+# control_memory properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.ControlMemory.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.ControlMemory.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.ControlMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.EnableProfiling = false
+
+
+# ArmarX.ControlMemory.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ControlMemory.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ControlMemory.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.ObjectName = ""
+
+
+# ArmarX.ControlMemory.RemoteGuiName:  Name of the remote gui provider
+#  Attributes:
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.RemoteGuiName = RemoteGuiProvider
+
+
+# ArmarX.ControlMemory.mem.MemoryName:  Name of this memory server.
+#  Attributes:
+#  - Default:            Control
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.MemoryName = Control
+
+
+# ArmarX.ControlMemory.mem.ltm.configuration:  
+#  Attributes:
+#  - Default:            {}
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mem.ltm.configuration = {}
+
+
+# ArmarX.ControlMemory.mem.ltm.enabled:  
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mem.ltm.enabled = false
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ControlMemory.mns.MemoryNameSystemEnabled = true
+
+
+# ArmarX.ControlMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+#  Attributes:
+#  - Default:            MemoryNameSystem
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.mns.MemoryNameSystemName = MemoryNameSystem
+
+
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+#  Attributes:
+#  - Default:            2
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.locationGraph.visuFrequency = 2
+
+
+# ArmarX.ControlMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ControlMemory.p.snapshotToLoad = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/NavigationSimulation/config/object_memory_to_simulation.cfg b/scenarios/NavigationSimulation/config/object_memory_to_simulation.cfg
new file mode 100644
index 00000000..f3deca08
--- /dev/null
+++ b/scenarios/NavigationSimulation/config/object_memory_to_simulation.cfg
@@ -0,0 +1,212 @@
+# ==================================================================
+# object_memory_to_simulation properties
+# ==================================================================
+
+# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.AdditionalPackages = Default value not mapped.
+
+
+# ArmarX.ApplicationName:  Application name
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ApplicationName = ""
+
+
+# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
+#  Attributes:
+#  - Default:            mongo/.cache
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.CachePath = mongo/.cache
+
+
+# ArmarX.Config:  Comma-separated list of configuration files 
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.Config = ""
+
+
+# ArmarX.DataPath:  Semicolon-separated search list for data files
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DataPath = ""
+
+
+# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
+#  Attributes:
+#  - Default:            Default value not mapped.
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DefaultPackages = Default value not mapped.
+
+
+# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
+#  Attributes:
+#  - Default:            ./config/dependencies.cfg
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.DependenciesConfig = ./config/dependencies.cfg
+
+
+# ArmarX.DisableLogging:  Turn logging off in whole application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.DisableLogging = false
+
+
+# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.EnableProfiling = false
+
+
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoadLibraries = ""
+
+
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.LoggingGroup = ""
+
+
+# ArmarX.ObjectMemoryToSimulation.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemoryToSimulation.EnableProfiling = false
+
+
+# ArmarX.ObjectMemoryToSimulation.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ObjectMemoryToSimulation.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.ObjectMemoryToSimulation.ObjectMemoryName:  Name of the object memory.
+#  Attributes:
+#  - Default:            ObjectMemory
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemoryToSimulation.ObjectMemoryName = ObjectMemory
+
+
+# ArmarX.ObjectMemoryToSimulation.ObjectName:  Name of IceGrid well-known object
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemoryToSimulation.ObjectName = ""
+
+
+# ArmarX.ObjectMemoryToSimulation.cmp.Simulator:  Ice object name of the `Simulator` component.
+#  Attributes:
+#  - Default:            Simulator
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemoryToSimulation.cmp.Simulator = Simulator
+
+
+# ArmarX.ObjectMemoryToSimulation.p.objectPoseProviderName:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemoryToSimulation.p.objectPoseProviderName = ""
+
+
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
+
+
diff --git a/scenarios/PlatformNavigation/PlatformNavigation.scx b/scenarios/PlatformNavigation/PlatformNavigation.scx
index cc0fcea7..2c526979 100644
--- a/scenarios/PlatformNavigation/PlatformNavigation.scx
+++ b/scenarios/PlatformNavigation/PlatformNavigation.scx
@@ -10,6 +10,6 @@
 	<application name="VisionMemory" instance="" package="VisionX" nodeName="" enabled="false" iceAutoRestart="false"/>
 	<application name="control_memory" instance="" package="armarx_control" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
-	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
+	<application name="dynamic_distance_to_obstacle_costmap_provider" instance="" package="armarx_navigation" nodeName="" enabled="false" iceAutoRestart="false"/>
 </scenario>
 
diff --git a/scenarios/PlatformNavigation/config/ObjectMemory.cfg b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
index 773e4812..5b38c4fb 100644
--- a/scenarios/PlatformNavigation/config/ObjectMemory.cfg
+++ b/scenarios/PlatformNavigation/config/ObjectMemory.cfg
@@ -150,6 +150,22 @@
 # ArmarX.ObjectMemory.cmp.KinematicUnitObserverName = KinematicUnitObserver
 
 
+# ArmarX.ObjectMemory.mem..marker.Name:  Marker Memory Name
+#  Attributes:
+#  - Default:            Marker
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.Name = Marker
+
+
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize:  Maximum marker memory history size
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize = -1
+
+
 # ArmarX.ObjectMemory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
 #  - Default:            Object
@@ -496,13 +512,39 @@
 # ArmarX.ObjectMemory.mem.inst.visu.oobbs = false
 
 
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show:  Show arrows linearly predicting object positions.
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha:  Alpha of linear prediction ghosts.
+#  Attributes:
+#  - Default:            0.699999988
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha = 0.699999988
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow:  Show arrows from current object poses to the linearly predicted ones.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame:  Show frames at linearly predicted object poses.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost:  Show ghosts at linearly predicted object poses.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show = false
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost = false
 
 
 # ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeOffset:  The offset (in seconds) to the current time to make predictions for.
diff --git a/scenarios/PlatformNavigation/config/RobotStateComponent.cfg b/scenarios/PlatformNavigation/config/RobotStateComponent.cfg
index 22eb7df3..07dc7425 100644
--- a/scenarios/PlatformNavigation/config/RobotStateComponent.cfg
+++ b/scenarios/PlatformNavigation/config/RobotStateComponent.cfg
@@ -158,14 +158,6 @@ ArmarX.RobotStateComponent.AgentName = Armar6
 # ArmarX.RobotStateComponent.ObjectName = ""
 
 
-# ArmarX.RobotStateComponent.PlatformTopicName:  Topic where platform state is published.
-#  Attributes:
-#  - Default:            PlatformState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateComponent.PlatformTopicName = PlatformState
-
-
 # ArmarX.RobotStateComponent.RobotFileName:  Filename of VirtualRobot robot model (e.g. robot_model.xml)
 #  Attributes:
 #  - Case sensitivity:   yes
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index 5cea7144..e9130c39 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -110,15 +110,7 @@
 # ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment:  
-#  Attributes:
-#  - Default:            Description
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.descriptionSegment = Description
-
-
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
@@ -126,14 +118,6 @@
 # ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment:  
-#  Attributes:
-#  - Default:            Proprioception
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.proprioceptionSegment = Proprioception
-
-
 # ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
@@ -155,11 +139,27 @@
 # ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
 #  - Default:            navigator
-#  - Case sensitivity:   no
+#  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
+# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
+#  Attributes:
+#  - Default:            200
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.relativeMovement = 200
+
+
+# ArmarX.ExampleClient.robotName:  
+#  Attributes:
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ExampleClient.robotName = Armar6
+
+
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
@@ -244,94 +244,11 @@ ArmarX.ExampleClient.nav.NavigatorName = navigator
 # ArmarX.Verbosity = Info
 
 
-# ArmarX.example_client.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.example_client.EnableProfiling = false
-
-
-# ArmarX.example_client.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.example_client.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.example_client.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.ObjectName = ""
-
-
-# ArmarX.example_client.mem.robot_state.Memory:  
-#  Attributes:
-#  - Default:            RobotState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.mem.robot_state.Memory = RobotState
-
-
-# ArmarX.example_client.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
-#  Attributes:
-#  - Default:            Localization
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.mem.robot_state.localizationSegment = Localization
-
-
-# ArmarX.example_client.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.example_client.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.example_client.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.mns.MemoryNameSystemName = MemoryNameSystem
-
-
-# ArmarX.example_client.mode:  Which example to run
+# ArmarX.example_client.mode:  No Description
 #  Attributes:
 #  - Default:            standard
-#  - Case sensitivity:   yes
+#  - Case sensitivity:   no
 #  - Required:           no
-#  - Possible values: {complex, point_to_point, standard, update_navigator}
 ArmarX.example_client.mode = standard
 
 
-# ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
-#  Attributes:
-#  - Default:            navigator
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.nav.NavigatorName = navigator
-
-
-# ArmarX.example_client.relativeMovement:  The distance between two target poses [mm]
-#  Attributes:
-#  - Default:            200
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.relativeMovement = 200
-
-
-# ArmarX.example_client.robotName:  
-#  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.example_client.robotName = Armar6
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index f84fea64..f808f777 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,205 +92,199 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  No Description
+# ArmarX.NavigationMemory.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
-#  - Case sensitivity:   no
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+# ArmarX.NavigationMemory.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.NavigationMemory.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            true
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.NavigationMemory.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.NavigationMemory.EnableProfiling:  enable profiler which is used for logging performance events
+#  Attributes:
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.NavigationMemory.EnableProfiling = false
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.NavigationMemory.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            3000
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.NavigationMemory.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
-#  - Default:            0
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.NavigationMemory.ObjectName = ""
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.NavigationMemory.RemoteGuiName:  Name of the remote gui provider
 #  Attributes:
-#  - Default:            false
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.NavigationMemory.RemoteGuiName = RemoteGuiProvider
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.NavigationMemory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
-#  - Default:            1
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+# ArmarX.NavigationMemory.mem.MemoryName = Navigation
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.NavigationMemory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.NavigationMemory.mem.ltm.configuration = {}
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.NavigationMemory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.NavigationMemory.mem.ltm.enabled = false
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            Info
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.navigation_memory.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.NavigationMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            ArVizStorage
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.ArVizStorageName = ArVizStorage
+# ArmarX.NavigationMemory.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.navigation_memory.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.NavigationMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            ArVizTopic
+#  - Default:            2
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.ArVizTopicName = ArVizTopic
+# ArmarX.NavigationMemory.p.locationGraph.visuFrequency = 2
 
 
-# ArmarX.navigation_memory.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
 #  Attributes:
-#  - Default:            false
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.navigation_memory.EnableProfiling = false
+# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges = true
 
 
-# ArmarX.navigation_memory.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.NavigationMemory.p.locationGraph.visuLocation:  Enable visualization of locations.
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.navigation_memory.MinimumLoggingLevel = Undefined
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.NavigationMemory.p.locationGraph.visuLocation = true
 
 
-# ArmarX.navigation_memory.ObjectName:  Name of IceGrid well-known object
+# ArmarX.NavigationMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.ObjectName = ""
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
 
 
-# ArmarX.navigation_memory.RemoteGuiName:  Name of the remote gui provider
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.RemoteGuiName = RemoteGuiProvider
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.navigation_memory.mem.MemoryName:  Name of this memory server.
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.mem.MemoryName = Navigation
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.navigation_memory.mem.ltm.configuration:  
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            {}
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.mem.ltm.configuration = {}
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.navigation_memory.mem.ltm.enabled:  
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.navigation_memory.mem.ltm.enabled = false
-
-
-# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled = true
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.navigation_memory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            2
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 2
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            true
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges = true
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.navigation_memory.p.locationGraph.visuLocation:  Enable visualization of locations.
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            true
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.navigation_memory.p.locationGraph.visuLocation = true
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
 
 
-# ArmarX.navigation_memory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.navigation_memory.p.snapshotToLoad = ""
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 5e1a1265..816fe294 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -136,7 +136,7 @@
 
 # ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            3000
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
 # ArmarX.TopicSuffix = ""
@@ -267,7 +267,7 @@ ArmarX.navigator.RobotUnitName = Armar6Unit
 
 # ArmarX.navigator.mem.nav.events.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            Events
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
 # ArmarX.navigator.mem.nav.events.Provider = ""
@@ -402,3 +402,36 @@ ArmarX.navigator.RobotUnitName = Armar6Unit
 #  - Case sensitivity:   yes
 #  - Required:           no
 ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
+# ArmarX.navigator.p.scene.humanProviderName:  
+#  Attributes:
+#  - Default:            dynamic_scene_provider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.p.scene.humanProviderName = dynamic_scene_provider
+
+
+# ArmarX.navigator.p.scene.robotName:  
+#  Attributes:
+#  - Case sensitivity:   yes
+#  - Required:           yes
+ArmarX.navigator.p.scene.robotName = Armar6
+
+
+# ArmarX.navigator.p.scene.staticCostmapName:  
+#  Attributes:
+#  - Default:            distance_to_obstacles
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.p.scene.staticCostmapName = distance_to_obstacles
+
+
+# ArmarX.navigator.p.scene.staticCostmapProviderName:  
+#  Attributes:
+#  - Default:            distance_to_obstacle_costmap_provider
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.p.scene.staticCostmapProviderName = distance_to_obstacle_costmap_provider
+
+
-- 
GitLab


From fff3eafa63661eb7b0e1c3df0bfc01f5f5ca94fe Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 5 Dec 2022 21:14:22 +0100
Subject: [PATCH 297/324] teb as optional dependency for local_planning library

---
 source/armarx/navigation/local_planning/CMakeLists.txt | 7 +++++--
 1 file changed, 5 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/local_planning/CMakeLists.txt b/source/armarx/navigation/local_planning/CMakeLists.txt
index ff91b53a..fa3f62b4 100644
--- a/source/armarx/navigation/local_planning/CMakeLists.txt
+++ b/source/armarx/navigation/local_planning/CMakeLists.txt
@@ -54,11 +54,14 @@ armarx_add_library(local_planning_teb
 
 target_compile_definitions(local_planning_teb PUBLIC TIMED_ELASTIC_BANDS_ENABLED=1)
 
+if(${teb_local_planner_FOUND})
+    set(local_planning_optional_deps armarx_navigation::local_planning_teb)
+endif()
+
 armarx_add_library(local_planning
     DEPENDENCIES_PUBLIC
         armarx_navigation::local_planning_core
-    #DEPENDENCIES_PUBLIC_OPTIONAL
-        armarx_navigation::local_planning_teb
+        ${local_planning_optional_deps}
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
 )
-- 
GitLab


From 764d5d930bb3a7580bd158e11fa0f6f04e548fa4 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 5 Dec 2022 21:14:30 +0100
Subject: [PATCH 298/324] scriplot is optional

---
 source/armarx/navigation/human/CMakeLists.txt | 86 +++++++++----------
 1 file changed, 40 insertions(+), 46 deletions(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index eb57ec12..836826fb 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -11,7 +11,7 @@ armarx_add_library(teb_human
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
-        ukfm
+        ukfm # RobotAPI
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
     SOURCES
@@ -32,82 +32,76 @@ armarx_add_library(teb_human
         HumanFilter.h
 )
 
-find_package(sciplot)
+option(SCIPLOT_TESTS "" OFF)
 
-armarx_add_test(so2_kalman_test
-    TEST_FILES
-        test/so2kalmanFilterTest.cpp
-    DEPENDENCIES
-        PUBLIC
+if(${SCIPLOT_TESTS})
+
+    find_package(sciplot)
+
+    armarx_add_test(so2_kalman_test
+        TEST_FILES
+            test/so2kalmanFilterTest.cpp
+        DEPENDENCIES
             ArmarXCore
             armarx_navigation::teb_human
             sciplot::sciplot
-)
+    )
 
-armarx_add_test(se2_kalman_test
-    TEST_FILES
-        test/se2KalmanFilterTest.cpp
-    DEPENDENCIES
-        PUBLIC
+    armarx_add_test(se2_kalman_test
+        TEST_FILES
+            test/se2KalmanFilterTest.cpp
+        DEPENDENCIES
             ArmarXCore
             armarx_navigation::teb_human
             sciplot::sciplot
-)
+    )
 
-armarx_add_test(se2xV_kalman_test
-    TEST_FILES
-        test/se2xVkalmanFilterTest.cpp
-    DEPENDENCIES
-        PUBLIC
+    armarx_add_test(se2xV_kalman_test
+        TEST_FILES
+            test/se2xVkalmanFilterTest.cpp
+        DEPENDENCIES
             ArmarXCore
             armarx_navigation::teb_human
             sciplot::sciplot
-)
+    )
 
-armarx_add_test(manif_kalman_test
-    TEST_FILES
-        test/manifKalmanTest.cpp
-    DEPENDENCIES
-        PUBLIC
+    armarx_add_test(manif_kalman_test
+        TEST_FILES
+            test/manifKalmanTest.cpp
+        DEPENDENCIES
             ArmarXCore
             armarx_navigation::teb_human
             sciplot::sciplot
-)
+    )
 
 
-armarx_add_test(se3_kalman_test
-    TEST_FILES
-        test/UnscentedKalmanFilterTest.cpp
-    DEPENDENCIES
-        PUBLIC
+    armarx_add_test(se3_kalman_test
+        TEST_FILES
+            test/UnscentedKalmanFilterTest.cpp
+        DEPENDENCIES
             ArmarXCore
             ukfm
             sciplot::sciplot
-)
+    )
 
+endif()
 
 armarx_add_test(kalman_filter_test
     TEST_FILES
         test/kalman_filter_test.cpp
     DEPENDENCIES
-        PUBLIC
-            ArmarXCore
-            armarx_navigation::core
-            armarx_navigation::teb_human
-
-        PRIVATE
-            range-v3::range-v3
+        ArmarXCore
+        armarx_navigation::core
+        armarx_navigation::teb_human
+        range-v3::range-v3
 )
 
 armarx_add_test(human_tracker_test
     TEST_FILES
         test/human_tracker_test.cpp
     DEPENDENCIES
-        PUBLIC
-            ArmarXCore
-            armarx_navigation::core
-            armarx_navigation::teb_human
-
-        PRIVATE
-            range-v3::range-v3
+        ArmarXCore
+        armarx_navigation::core
+        armarx_navigation::teb_human
+        range-v3::range-v3
 )
-- 
GitLab


From 8cce38b0700faee2d99a2a8a7b4355546dd99249 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 5 Dec 2022 21:27:25 +0100
Subject: [PATCH 299/324] friend SocialCostmapBuilder

---
 source/armarx/navigation/algorithms/Costmap.h | 1 +
 1 file changed, 1 insertion(+)

diff --git a/source/armarx/navigation/algorithms/Costmap.h b/source/armarx/navigation/algorithms/Costmap.h
index d168ef7d..e7f4fc0c 100644
--- a/source/armarx/navigation/algorithms/Costmap.h
+++ b/source/armarx/navigation/algorithms/Costmap.h
@@ -16,6 +16,7 @@ namespace armarx::navigation::algorithms
         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
         friend class CostmapBuilder;
+        friend class SocialCostmapBuilder;
 
         struct Parameters
         {
-- 
GitLab


From fa4a2e22769fabf6a1bdc63f93e6a2a3e6c7dc53 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Dec 2022 15:17:07 +0100
Subject: [PATCH 300/324] human reader with maxAge

---
 .../config/ObjectMemory.cfg                   |  46 ++-
 .../config/RobotStateComponent.cfg            |   8 -
 .../config/dynamic_scene_provider.cfg         |   6 +-
 .../config/example_client.cfg                 | 163 ++++------
 .../config/human_simulator.cfg                | 306 +-----------------
 .../config/navigation_memory.cfg              | 166 +++++-----
 .../dynamic_scene_provider/Component.cpp      |  18 +-
 .../navigation/memory/client/human/Reader.cpp |  51 +--
 .../navigation/memory/client/human/Reader.h   |   1 +
 .../server/scene_provider/SceneProvider.cpp   |   4 +-
 10 files changed, 252 insertions(+), 517 deletions(-)

diff --git a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
index 773e4812..5b38c4fb 100644
--- a/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
+++ b/scenarios/HumanAwareNavigation/config/ObjectMemory.cfg
@@ -150,6 +150,22 @@
 # ArmarX.ObjectMemory.cmp.KinematicUnitObserverName = KinematicUnitObserver
 
 
+# ArmarX.ObjectMemory.mem..marker.Name:  Marker Memory Name
+#  Attributes:
+#  - Default:            Marker
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.Name = Marker
+
+
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize:  Maximum marker memory history size
+#  Attributes:
+#  - Default:            -1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem..marker.maxHistorySize = -1
+
+
 # ArmarX.ObjectMemory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
 #  - Default:            Object
@@ -496,13 +512,39 @@
 # ArmarX.ObjectMemory.mem.inst.visu.oobbs = false
 
 
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show:  Show arrows linearly predicting object positions.
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha:  Alpha of linear prediction ghosts.
+#  Attributes:
+#  - Default:            0.699999988
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.ghostAlpha = 0.699999988
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow:  Show arrows from current object poses to the linearly predicted ones.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showArrow = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame:  Show frames at linearly predicted object poses.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showFrame = false
+
+
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost:  Show ghosts at linearly predicted object poses.
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.show = false
+# ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.showGhost = false
 
 
 # ArmarX.ObjectMemory.mem.inst.visu.predictions.linear.timeOffset:  The offset (in seconds) to the current time to make predictions for.
diff --git a/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg b/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
index 22eb7df3..07dc7425 100644
--- a/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
+++ b/scenarios/HumanAwareNavigation/config/RobotStateComponent.cfg
@@ -158,14 +158,6 @@ ArmarX.RobotStateComponent.AgentName = Armar6
 # ArmarX.RobotStateComponent.ObjectName = ""
 
 
-# ArmarX.RobotStateComponent.PlatformTopicName:  Topic where platform state is published.
-#  Attributes:
-#  - Default:            PlatformState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RobotStateComponent.PlatformTopicName = PlatformState
-
-
 # ArmarX.RobotStateComponent.RobotFileName:  Filename of VirtualRobot robot model (e.g. robot_model.xml)
 #  Attributes:
 #  - Case sensitivity:   yes
diff --git a/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
index c632df10..30889783 100644
--- a/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
+++ b/scenarios/HumanAwareNavigation/config/dynamic_scene_provider.cfg
@@ -191,7 +191,7 @@
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Verbose
+# ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Undefined
 
 
 # ArmarX.dynamic_scene_provider.ObjectMemoryName:  Name of the object memory.
@@ -334,10 +334,10 @@ ArmarX.dynamic_scene_provider.MinimumLoggingLevel = Verbose
 
 # ArmarX.dynamic_scene_provider.p.humanPoseProvider:  
 #  Attributes:
-#  - Default:            OpenNIPointCloudProvider
+#  - Default:            AzureKinectPointCloudProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.dynamic_scene_provider.p.humanPoseProvider = OpenNIPointCloudProvider
+# ArmarX.dynamic_scene_provider.p.humanPoseProvider = AzureKinectPointCloudProvider
 
 
 # ArmarX.dynamic_scene_provider.p.laserScannerFeatures.name:  
diff --git a/scenarios/HumanAwareNavigation/config/example_client.cfg b/scenarios/HumanAwareNavigation/config/example_client.cfg
index 5b947d42..680e39ca 100644
--- a/scenarios/HumanAwareNavigation/config/example_client.cfg
+++ b/scenarios/HumanAwareNavigation/config/example_client.cfg
@@ -76,204 +76,179 @@
 # ArmarX.EnableProfiling = false
 
 
-# ArmarX.ExampleClient.nav.NavigatorName:  No Description
+# ArmarX.ExampleClient.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            navigator
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.ExampleClient.nav.NavigatorName = navigator
-
-
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoadLibraries = ""
-
-
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoggingGroup = ""
-
-
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
-#  Attributes:
-#  - Default:            true
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.ExampleClient.EnableProfiling = false
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.ExampleClient.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            3000
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.ExampleClient.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.ExampleClient.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
-#  - Default:            0
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.ExampleClient.ObjectName = ""
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.ExampleClient.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            false
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
-#  - Default:            1
+#  - Default:            Localization
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            false
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
-#  - Default:            Info
+#  - Default:            navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
-# ArmarX.example_client.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
 #  Attributes:
-#  - Default:            false
+#  - Default:            200
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.example_client.EnableProfiling = false
+# ArmarX.ExampleClient.relativeMovement = 200
 
 
-# ArmarX.example_client.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.ExampleClient.robotName:  
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            Armar6
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.example_client.MinimumLoggingLevel = Undefined
+# ArmarX.ExampleClient.robotName = Armar6
 
 
-# ArmarX.example_client.ObjectName:  Name of IceGrid well-known object
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.ObjectName = ""
+# ArmarX.LoadLibraries = ""
 
 
-# ArmarX.example_client.mem.nav.costmap.CoreSegment:  
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
 #  Attributes:
-#  - Default:            Costmap
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.mem.nav.costmap.CoreSegment = Costmap
+# ArmarX.LoggingGroup = ""
 
 
-# ArmarX.example_client.mem.nav.costmap.Memory:  
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.mem.nav.costmap.Memory = Navigation
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.example_client.mem.robot_state.Memory:  
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.mem.robot_state.Memory = RobotState
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.example_client.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            Localization
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.mem.robot_state.localizationSegment = Localization
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.example_client.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            true
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.example_client.mns.MemoryNameSystemEnabled = true
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.example_client.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.example_client.mode:  Which example to run
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            standard
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {complex, point_to_point, standard, update_navigator, wander_around}
-ArmarX.example_client.mode = wander_around
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            navigator
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.nav.NavigatorName = navigator
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.example_client.relativeMovement:  The distance between two target poses [mm]
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            200
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.example_client.relativeMovement = 200
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
 
 
-# ArmarX.example_client.robotName:  
+# ArmarX.example_client.mode:  No Description
 #  Attributes:
-#  - Default:            Armar6
-#  - Case sensitivity:   yes
+#  - Default:            wander_around
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.example_client.robotName = Armar6
+ArmarX.example_client.mode = wander_around
 
 
diff --git a/scenarios/HumanAwareNavigation/config/human_simulator.cfg b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
index af906f63..b628b0a4 100644
--- a/scenarios/HumanAwareNavigation/config/human_simulator.cfg
+++ b/scenarios/HumanAwareNavigation/config/human_simulator.cfg
@@ -2,317 +2,13 @@
 # human_simulator properties
 # ==================================================================
 
-# ArmarX.AdditionalPackages:  List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
+# ArmarX.human_simulator.p.nHumans:  
 #  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.AdditionalPackages = Default value not mapped.
-
-
-# ArmarX.ApplicationName:  Application name
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ApplicationName = ""
-
-
-# ArmarX.CachePath:  Path for cache files. If relative path AND env. variable ARMARX_CONFIG_DIR is set, the cache path will be made relative to ARMARX_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${ARMARX_WORKSPACE}/armarx_config)
-#  Attributes:
-#  - Default:            mongo/.cache
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.CachePath = mongo/.cache
-
-
-# ArmarX.Config:  Comma-separated list of configuration files 
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.Config = ""
-
-
-# ArmarX.DataPath:  Semicolon-separated search list for data files
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DataPath = ""
-
-
-# ArmarX.DefaultPackages:  List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
-#  Attributes:
-#  - Default:            Default value not mapped.
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DefaultPackages = Default value not mapped.
-
-
-# ArmarX.DependenciesConfig:  Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
-#  Attributes:
-#  - Default:            ./config/dependencies.cfg
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.DependenciesConfig = ./config/dependencies.cfg
-
-
-# ArmarX.DisableLogging:  Turn logging off in whole application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.DisableLogging = false
-
-
-# ArmarX.EnableProfiling:  Enable profiling of CPU load produced by this application
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.EnableProfiling = false
-
-
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoadLibraries = ""
-
-
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.LoggingGroup = ""
-
-
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
-
-
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
-#  Attributes:
-#  - Default:            3000
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
-
-
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
-#  Attributes:
-#  - Default:            0
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
-
-
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
-
-
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
-#  Attributes:
-#  - Default:            1
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.ThreadPoolSize = 1
-
-
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.TopicSuffix = ""
-
-
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
-
-
-# ArmarX.Verbosity:  Global logging level for whole application
-#  Attributes:
-#  - Default:            Info
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
-
-
-# ArmarX.human_simulator.ArVizStorageName:  Name of the ArViz storage
-#  Attributes:
-#  - Default:            ArVizStorage
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.ArVizStorageName = ArVizStorage
-
-
-# ArmarX.human_simulator.ArVizTopicName:  Name of the ArViz topic
-#  Attributes:
-#  - Default:            ArVizTopic
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.ArVizTopicName = ArVizTopic
-
-
-# ArmarX.human_simulator.EnableProfiling:  enable profiler which is used for logging performance events
-#  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.human_simulator.EnableProfiling = false
-
-
-# ArmarX.human_simulator.MinimumLoggingLevel:  Local logging level only for this component
-#  Attributes:
-#  - Default:            Undefined
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.human_simulator.MinimumLoggingLevel = Undefined
-
-
-# ArmarX.human_simulator.ObjectMemoryName:  Name of the object memory.
-#  Attributes:
-#  - Default:            ObjectMemory
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.ObjectMemoryName = ObjectMemory
-
-
-# ArmarX.human_simulator.ObjectName:  Name of IceGrid well-known object
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.ObjectName = ""
-
-
-# ArmarX.human_simulator.mem.nav.costmap.CoreSegment:  
-#  Attributes:
-#  - Default:            Costmap
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.nav.costmap.CoreSegment = Costmap
-
-
-# ArmarX.human_simulator.mem.nav.costmap.Memory:  
-#  Attributes:
-#  - Default:            Navigation
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.nav.costmap.Memory = Navigation
-
-
-# ArmarX.human_simulator.mem.nav.human.CoreSegment:  
-#  Attributes:
-#  - Default:            Human
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.nav.human.CoreSegment = Human
-
-
-# ArmarX.human_simulator.mem.nav.human.Memory:  
-#  Attributes:
-#  - Default:            Navigation
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.nav.human.Memory = Navigation
-
-
-# ArmarX.human_simulator.mem.nav.human.Provider:  Name of this provider
-#  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.nav.human.Provider = ""
-
-
-# ArmarX.human_simulator.mem.robot_state.Memory:  
-#  Attributes:
-#  - Default:            RobotState
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.robot_state.Memory = RobotState
-
-
-# ArmarX.human_simulator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
-#  Attributes:
-#  - Default:            Localization
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mem.robot_state.localizationSegment = Localization
-
-
-# ArmarX.human_simulator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
-#  Attributes:
-#  - Default:            true
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.human_simulator.mns.MemoryNameSystemEnabled = true
-
-
-# ArmarX.human_simulator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
-#  Attributes:
-#  - Default:            MemoryNameSystem
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.mns.MemoryNameSystemName = MemoryNameSystem
-
-
-# ArmarX.human_simulator.p.human.goalDistanceThreshold:  
-#  Attributes:
-#  - Default:            100
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.p.human.goalDistanceThreshold = 100
-
-
-# ArmarX.human_simulator.p.human.maxLinearVelocity:  
-#  Attributes:
-#  - Default:            200
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.human_simulator.p.human.maxLinearVelocity = 200
-
-
-# ArmarX.human_simulator.p.nHumans:  Number of humans to spawn.
-#  Attributes:
-#  - Default:            4
-#  - Case sensitivity:   yes
-#  - Required:           no
 ArmarX.human_simulator.p.nHumans = 3
 
 
 # ArmarX.human_simulator.p.taskPeriodMs:  
 #  Attributes:
-#  - Default:            100
-#  - Case sensitivity:   yes
-#  - Required:           no
 ArmarX.human_simulator.p.taskPeriodMs = 100
 
 
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index f808f777..ce2fdf9b 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,199 +92,207 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.NavigationMemory.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.NavigationMemory.p.snapshotToLoad:  No Description
 #  Attributes:
-#  - Default:            ArVizStorage
-#  - Case sensitivity:   yes
+#  - Default:            ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+#  - Case sensitivity:   no
 #  - Required:           no
-# ArmarX.NavigationMemory.ArVizStorageName = ArVizStorage
-
-
-# ArmarX.NavigationMemory.ArVizTopicName:  Name of the ArViz topic
-#  Attributes:
-#  - Default:            ArVizTopic
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.NavigationMemory.ArVizTopicName = ArVizTopic
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
 
 
-# ArmarX.NavigationMemory.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            false
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.EnableProfiling = false
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.NavigationMemory.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.NavigationMemory.MinimumLoggingLevel = Undefined
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.NavigationMemory.ObjectName:  Name of IceGrid well-known object
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            ""
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.ObjectName = ""
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.NavigationMemory.RemoteGuiName:  Name of the remote gui provider
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.RemoteGuiName = RemoteGuiProvider
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.NavigationMemory.mem.MemoryName:  Name of this memory server.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.MemoryName = Navigation
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.NavigationMemory.mem.ltm.configuration:  
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            {}
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mem.ltm.configuration = {}
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.NavigationMemory.mem.ltm.enabled:  
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mem.ltm.enabled = false
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            true
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.mns.MemoryNameSystemEnabled = true
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
 
 
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigation_memory.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.navigation_memory.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
+# ArmarX.navigation_memory.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
-#  - Default:            2
+#  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.NavigationMemory.p.locationGraph.visuFrequency = 2
+# ArmarX.navigation_memory.ArVizTopicName = ArVizTopic
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+# ArmarX.navigation_memory.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            true
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuGraphEdges = true
+# ArmarX.navigation_memory.EnableProfiling = false
 
 
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation:  Enable visualization of locations.
+# ArmarX.navigation_memory.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
-#  - Default:            true
+#  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.NavigationMemory.p.locationGraph.visuLocation = true
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.navigation_memory.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  Memory snapshot to load at start up 
-# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+# ArmarX.navigation_memory.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
+# ArmarX.navigation_memory.ObjectName = ""
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigation_memory.RemoteGuiName:  Name of the remote gui provider
 #  Attributes:
-#  - Default:            true
+#  - Default:            RemoteGuiProvider
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigation_memory.RemoteGuiName = RemoteGuiProvider
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigation_memory.mem.MemoryName:  Name of this memory server.
 #  Attributes:
-#  - Default:            3000
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.navigation_memory.mem.MemoryName = Navigation
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigation_memory.mem.ltm.configuration:  
 #  Attributes:
-#  - Default:            0
+#  - Default:            {}
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.navigation_memory.mem.ltm.configuration = {}
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigation_memory.mem.ltm.enabled:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigation_memory.mem.ltm.enabled = false
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
 #  Attributes:
-#  - Default:            1
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.navigation_memory.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            ""
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+# ArmarX.navigation_memory.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            false
+#  - Default:            10
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 10
+
+
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
+#  Attributes:
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.navigation_memory.p.locationGraph.visuGraphEdges = true
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.navigation_memory.p.locationGraph.visuLocation:  Enable visualization of locations.
 #  Attributes:
-#  - Default:            Info
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigation_memory.p.locationGraph.visuLocation = true
+
+
+# ArmarX.navigation_memory.p.snapshotToLoad:  Memory snapshot to load at start up 
+# (e.g. 'PriorKnowledgeData/navigation-graphs/snapshot').
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigation_memory.p.snapshotToLoad = ""
 
 
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index deec2b8b..9ddc696a 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -208,7 +208,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ARMARX_CHECK(virtualRobotReaderPlugin->get().synchronizeRobot(*robot, timestamp));
         const core::Pose global_T_robot(robot->getGlobalPose());
 
-        ARMARX_INFO << "Robot position: " << global_T_robot.translation().head<2>();
+        ARMARX_VERBOSE << "Robot position: " << global_T_robot.translation().head<2>();
 
         TIMING_END_COMMENT_STREAM(
             READ_ROBOT_FROM_MEMORY, "Timer: reading robot from memory", ARMARX_VERBOSE);
@@ -220,7 +220,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         TIMING_START(READ_HUMANS_FROM_MEMORY);
 
-        ARMARX_INFO << "Querying humans";
+        ARMARX_VERBOSE << "Querying humans";
 
         const armem::human::client::Reader::Query humanPoseQuery{
             .providerName = properties.humanPoseProvider,
@@ -232,7 +232,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
         ARMARX_CHECK_NOT_EQUAL(humanPoseResult.status, armem::human::client::Reader::Result::Error)
             << humanPoseResult.errorMessage;
 
-        ARMARX_INFO << humanPoseResult.humanPoses.size() << " humans in the scene.";
+        ARMARX_VERBOSE << humanPoseResult.humanPoses.size() << " humans in the scene.";
 
         TIMING_END_COMMENT_STREAM(
             READ_HUMANS_FROM_MEMORY, "Timer: reading humans from memory", ARMARX_VERBOSE);
@@ -384,7 +384,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         TIMING_START(RUNNING_HUMAN_TRACKER_WITH_CAMERA);
 
-        ARMARX_INFO << "Running human tracker with camera measurements";
+        ARMARX_VERBOSE << "Running human tracker with camera measurements";
 
         humanTracker.update(human::HumanTracker::CameraMeasurement{
             .detectionTime = timestamp, .humanPoses = humanPoseResult.humanPoses});
@@ -414,7 +414,7 @@ namespace armarx::navigation::components::dynamic_scene_provider
                                   ARMARX_VERBOSE);
         */
 
-        ARMARX_INFO << "Human tracking done";
+        ARMARX_VERBOSE << "Human tracking done";
 
 
         //
@@ -427,9 +427,13 @@ namespace armarx::navigation::components::dynamic_scene_provider
 
         std::vector<human::Human> humans = humanTracker.getTrackedHumans();
 
-        ARMARX_INFO << "Detected " << humans.size() << " humans";
 
-        humanWriterPlugin->get().store(humans, getName(), timestamp);
+        if(not humans.empty())
+        {
+            ARMARX_INFO << "Detected " << humans.size() << " humans";
+            humanWriterPlugin->get().store(humans, getName(), timestamp);
+        }
+
 
         TIMING_END_COMMENT_STREAM(
             WRITE_BACK_HUMANS, "Timer: write humans to memory", ARMARX_VERBOSE);
diff --git a/source/armarx/navigation/memory/client/human/Reader.cpp b/source/armarx/navigation/memory/client/human/Reader.cpp
index de91ae99..f1ad2e2b 100644
--- a/source/armarx/navigation/memory/client/human/Reader.cpp
+++ b/source/armarx/navigation/memory/client/human/Reader.cpp
@@ -72,7 +72,9 @@ namespace armarx::navigation::memory::client::human
     }
 
     navigation::human::Humans
-    asHumans(const armem::wm::ProviderSegment& providerSegment)
+    asHumans(const armem::wm::ProviderSegment& providerSegment,
+             const DateTime& timestamp,
+             const Duration& maxAge)
     {
         navigation::human::Humans humans;
 
@@ -80,20 +82,25 @@ namespace armarx::navigation::memory::client::human
         ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
 
         providerSegment.forEachEntity(
-            [&humans](const armem::wm::Entity& entity)
+            [&humans, &timestamp, &maxAge](const armem::wm::Entity& entity)
             {
                 const auto& entitySnapshot = entity.getLatestSnapshot();
                 ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
 
                 entitySnapshot.forEachInstance(
-                    [&humans](const armem::wm::EntityInstance& entityInstance)
+                    [&](const armem::wm::EntityInstance& entityInstance)
                     {
-                        const auto dto =
-                            navigation::human::arondto::Human::FromAron(entityInstance.data());
+                        const Duration dtToNow = timestamp - entityInstance.metadata().timeCreated;
 
-                        navigation::human::Human human;
-                        fromAron(dto, human);
-                        humans.push_back(human);
+                        if (dtToNow < maxAge and dtToNow.isPositive())
+                        {
+                            const auto dto =
+                                navigation::human::arondto::Human::FromAron(entityInstance.data());
+
+                            navigation::human::Human human;
+                            fromAron(dto, human);
+                            humans.push_back(human);
+                        }
                     });
             });
 
@@ -101,7 +108,9 @@ namespace armarx::navigation::memory::client::human
     }
 
     navigation::human::HumanGroups
-    asGroups(const armem::wm::ProviderSegment& providerSegment)
+    asGroups(const armem::wm::ProviderSegment& providerSegment,
+             const DateTime& timestamp,
+             const Duration& maxAge)
     {
         navigation::human::HumanGroups humans;
 
@@ -109,20 +118,25 @@ namespace armarx::navigation::memory::client::human
         ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
 
         providerSegment.forEachEntity(
-            [&humans](const armem::wm::Entity& entity)
+            [&humans, &timestamp, &maxAge](const armem::wm::Entity& entity)
             {
                 const auto& entitySnapshot = entity.getLatestSnapshot();
                 ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
 
                 entitySnapshot.forEachInstance(
-                    [&humans](const armem::wm::EntityInstance& entityInstance)
+                    [&](const armem::wm::EntityInstance& entityInstance)
                     {
-                        const auto dto =
-                            navigation::human::arondto::HumanGroup::FromAron(entityInstance.data());
+                        const Duration dtToNow = timestamp - entityInstance.metadata().timeCreated;
+
+                        if (dtToNow < maxAge and dtToNow.isPositive())
+                        {
+                            const auto dto = navigation::human::arondto::HumanGroup::FromAron(
+                                entityInstance.data());
 
-                        navigation::human::HumanGroup human;
-                        fromAron(dto, human);
-                        humans.push_back(human);
+                            navigation::human::HumanGroup human;
+                            fromAron(dto, human);
+                            humans.push_back(human);
+                        }
                     });
             });
 
@@ -169,7 +183,8 @@ namespace armarx::navigation::memory::client::human
 
         try
         {
-            return HumanGroupResult{.groups = asGroups(providerSegment),
+            return HumanGroupResult{.groups =
+                                        asGroups(providerSegment, query.timestamp, query.maxAge),
                                     .status = HumanGroupResult::Status::Success};
         }
         catch (...)
@@ -221,7 +236,7 @@ namespace armarx::navigation::memory::client::human
 
         try
         {
-            return HumanResult{.humans = asHumans(providerSegment),
+            return HumanResult{.humans = asHumans(providerSegment, query.timestamp, query.maxAge),
                                .status = HumanResult::Status::Success};
         }
         catch (...)
diff --git a/source/armarx/navigation/memory/client/human/Reader.h b/source/armarx/navigation/memory/client/human/Reader.h
index 2e693237..91a17afa 100644
--- a/source/armarx/navigation/memory/client/human/Reader.h
+++ b/source/armarx/navigation/memory/client/human/Reader.h
@@ -43,6 +43,7 @@ namespace armarx::navigation::memory::client::human
         {
             std::string providerName;
             armem::Time timestamp;
+            Duration maxAge;
         };
 
         struct HumanResult
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index d9977c6e..86e2f8a3 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -2,6 +2,7 @@
 
 #include <VirtualRobot/SceneObjectSet.h>
 
+#include "ArmarXCore/core/time/Duration.h"
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/time/Clock.h>
@@ -120,7 +121,8 @@ namespace armarx::navigation::server::scene_provider
     SceneProvider::getDynamicScene(const DateTime& timestamp) const
     {
         const memory::client::human::Reader::Query query{.providerName = config.humanProviderName,
-                                                         .timestamp = timestamp};
+                                                         .timestamp = timestamp,
+                                                         .maxAge = Duration::MilliSeconds(500)};
 
         return {.humans = srv.humanReader->queryHumans(query).humans};
     }
-- 
GitLab


From 0c17e45189eaee1c5b55f4b48ae6d628ce40f052 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Tue, 6 Dec 2022 15:17:29 +0100
Subject: [PATCH 301/324] costmap visu: each costmap on individual layer

---
 .../components/navigation_memory/Visu.cpp         | 15 +++++++++++++--
 1 file changed, 13 insertions(+), 2 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 37490d91..882deb59 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -22,7 +22,7 @@
 
 #include "Visu.h"
 
-#include <Eigen/src/Geometry/Translation.h>
+#include <Eigen/Geometry>
 
 #include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/cmaps/colormaps.h>
@@ -211,6 +211,16 @@ namespace armarx::navigation::memory
                                  .length(200)
                                  .color(simox::Color::red());
                 layer.add(arrow);
+
+                {
+                    auto arrow =
+                        viz::Arrow(std::to_string(layer.size()))
+                            .fromTo(pose3d.translation(),
+                                    pose3d.translation() + conv::to3D(human.linearVelocity))
+                            .color(simox::Color::blue());
+                    arrow.width(10);
+                    layer.add(arrow);
+                }
             }
         }
 
@@ -248,9 +258,10 @@ namespace armarx::navigation::memory
 
         for (const auto& [providerName, namedCostmaps] : namedProviderCostmaps)
         {
-            viz::Layer& layer = layers.emplace_back(arviz.layer("costmaps_" + providerName));
             for (const auto& [name, costmap] : namedCostmaps)
             {
+                viz::Layer& layer =
+                    layers.emplace_back(arviz.layer("costmaps_" + providerName + "_" + name));
                 visualize(costmap, layer, name);
             }
         }
-- 
GitLab


From 6038f2be4d94daedda31dfeab7815eb94bbea9f0 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 12 Jan 2023 18:16:21 +0100
Subject: [PATCH 302/324] fixing merge

---
 .../components/navigation_memory/CMakeLists.txt        |  3 ++-
 .../components/navigation_memory/Component.cpp         |  3 +--
 .../components/navigation_memory/Component.h           |  3 +--
 .../navigation/components/navigation_memory/Visu.cpp   | 10 +++++++---
 .../navigation/components/navigation_memory/Visu.h     |  2 +-
 source/armarx/navigation/skills/GuideHumanToRoom.cpp   |  5 ++---
 source/armarx/navigation/skills/NavigateTo.cpp         |  6 +++---
 source/armarx/navigation/skills/NavigateToLocation.cpp |  5 ++---
 .../statecharts/NavigationGroup/NavigateRelative.cpp   |  5 ++---
 9 files changed, 21 insertions(+), 21 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/CMakeLists.txt b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
index 15cfde46..60c690fb 100644
--- a/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
+++ b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
@@ -4,7 +4,7 @@ armarx_add_component(navigation_memory
         RobotAPIInterfaces
     ICE_FILES
         ComponentInterface.ice
-    DEPENDENCIES
+    DEPENDENCIES_PUBLIC
         # ArmarXCore
         ArmarXCore
         ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
@@ -25,6 +25,7 @@ armarx_add_component(navigation_memory
         armarx_navigation::algorithms
         armarx_navigation::teb_human
         armarx_navigation::rooms
+        armarx_navigation::memory
 
     SOURCES
         Component.cpp
diff --git a/source/armarx/navigation/components/navigation_memory/Component.cpp b/source/armarx/navigation/components/navigation_memory/Component.cpp
index 60a7e485..e79acee4 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Component.cpp
@@ -505,8 +505,7 @@ namespace armarx::navigation::components::navigation_memory
                           workingMemory().getCoreSegment(navigation::location::coreSegmentID),
                           workingMemory().getCoreSegment(navigation::graph::coreSegmentID),
                           workingMemory().getCoreSegment(memory::constants::CostmapCoreSegmentName),
-                          workingMemory().getCoreSegment(memory::constants::HumanCoreSegmentName)};
-
+                          workingMemory().getCoreSegment(memory::constants::HumanCoreSegmentName),
                           workingMemory().getCoreSegment(navigation::rooms::coreSegmentID)};
 
         Properties::LocationGraph p;
diff --git a/source/armarx/navigation/components/navigation_memory/Component.h b/source/armarx/navigation/components/navigation_memory/Component.h
index 44420fe8..f9b44c76 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -108,9 +108,8 @@ namespace armarx::navigation::components::navigation_memory
 
                 bool visuTransparent = false;
 
-                float visuFrequency = 10;
-                bool visuRooms = true;
                 float visuFrequency = 2;
+                bool visuRooms = true;
             };
             LocationGraph locationGraph;
         };
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 23c8dbf3..48ae6a18 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -41,12 +41,16 @@ namespace armarx::navigation::memory
 {
 
     Visu::Visu(viz::Client arviz,
-               const armem::server::wm::CoreSegment& locSegment,
-               const armem::server::wm::CoreSegment& graphSegment,
-               const armem::server::wm::CoreSegment& roomsSegment) :
+                const armem::server::wm::CoreSegment& locSegment,
+             const armem::server::wm::CoreSegment& graphSegment,
+             const armem::server::wm::CoreSegment& costmapSegment,
+             const armem::server::wm::CoreSegment& humanSegment,
+             const armem::server::wm::CoreSegment& roomsSegment) :
         arviz(arviz),
         locSegment(locSegment),
         graphSegment(graphSegment),
+        costmapSegment(costmapSegment),
+        humanSegment(humanSegment),
         roomsSegment(roomsSegment),
         visu(std::make_unique<graph::GraphVisu>())
     {
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.h b/source/armarx/navigation/components/navigation_memory/Visu.h
index 843c719e..8e2071f7 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.h
+++ b/source/armarx/navigation/components/navigation_memory/Visu.h
@@ -49,7 +49,7 @@ namespace armarx::navigation::memory
              const armem::server::wm::CoreSegment& locSegment,
              const armem::server::wm::CoreSegment& graphSegment,
              const armem::server::wm::CoreSegment& costmapSegment,
-             const armem::server::wm::CoreSegment& humanSegment);
+             const armem::server::wm::CoreSegment& humanSegment,
              const armem::server::wm::CoreSegment& roomsSegment);
         ~Visu();
 
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.cpp b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
index b9fd5553..3f56e3d4 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.cpp
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
@@ -19,8 +19,7 @@
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
@@ -38,7 +37,7 @@ namespace armarx::navigation::skills
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::SPFAParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            armarx::navigation::traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         const std::string configId = DefaultSkillDescription().skillName;
 
diff --git a/source/armarx/navigation/skills/NavigateTo.cpp b/source/armarx/navigation/skills/NavigateTo.cpp
index 6604e9d3..df262cde 100644
--- a/source/armarx/navigation/skills/NavigateTo.cpp
+++ b/source/armarx/navigation/skills/NavigateTo.cpp
@@ -7,6 +7,7 @@
 
 #include "armarx/navigation/client/services/MemorySubscriber.h"
 #include "armarx/navigation/global_planning/SPFA.h"
+#include "armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h"
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
@@ -14,8 +15,7 @@
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
@@ -33,7 +33,7 @@ namespace armarx::navigation::skills
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::SPFAParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            armarx::navigation::traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         const std::string configId = DefaultSkillDescription().skillName;
 
diff --git a/source/armarx/navigation/skills/NavigateToLocation.cpp b/source/armarx/navigation/skills/NavigateToLocation.cpp
index d9d52ceb..cad2d681 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.cpp
+++ b/source/armarx/navigation/skills/NavigateToLocation.cpp
@@ -14,8 +14,7 @@
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
@@ -33,7 +32,7 @@ namespace armarx::navigation::skills
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::SPFAParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            armarx::navigation::traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         const std::string configId = DefaultSkillDescription().skillName;
 
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
index c30e1aff..bedf8cca 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
@@ -34,8 +34,7 @@
 #include <armarx/navigation/client/services/MemoryPolling.h>
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
-#include <armarx/navigation/trajectory_control/TrajectoryController.h>
-#include <armarx/navigation/trajectory_control/TrajectoryFollowingController.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 namespace armarx::navigation::statecharts::navigation_group
 {
@@ -62,7 +61,7 @@ namespace armarx::navigation::statecharts::navigation_group
         cfg.general(client::GeneralConfig{});
         cfg.globalPlanner(armarx::navigation::global_planning::Point2PointParams{});
         cfg.trajectoryController(
-            armarx::navigation::traj_ctrl::TrajectoryFollowingControllerParams{});
+            armarx::navigation::traj_ctrl::local::TrajectoryFollowingControllerParams{});
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
         client::IceNavigator iceNavigator(getNavigator());
-- 
GitLab


From 6b10280590ffefdb4ea6a473897884a97e4fdecd Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 12 Jan 2023 18:19:06 +0100
Subject: [PATCH 303/324] fixing merge 2

---
 .../components/navigation_memory/Visu.cpp     | 131 +++++++++++++++++-
 1 file changed, 126 insertions(+), 5 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 48ae6a18..5a03b6f4 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -24,10 +24,12 @@
 
 #include <SimoxUtility/color/Color.h>
 #include <SimoxUtility/color/GlasbeyLUT.h>
+#include <SimoxUtility/color/cmaps/colormaps.h>
 
 #include "RobotAPI/components/ArViz/Client/elements/Path.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
+#include "armarx/navigation/algorithms/aron_conversions.h"
 #include "armarx/navigation/conversions/eigen.h"
 #include <armarx/navigation/core/Graph.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
@@ -41,11 +43,11 @@ namespace armarx::navigation::memory
 {
 
     Visu::Visu(viz::Client arviz,
-                const armem::server::wm::CoreSegment& locSegment,
-             const armem::server::wm::CoreSegment& graphSegment,
-             const armem::server::wm::CoreSegment& costmapSegment,
-             const armem::server::wm::CoreSegment& humanSegment,
-             const armem::server::wm::CoreSegment& roomsSegment) :
+               const armem::server::wm::CoreSegment& locSegment,
+               const armem::server::wm::CoreSegment& graphSegment,
+               const armem::server::wm::CoreSegment& costmapSegment,
+               const armem::server::wm::CoreSegment& humanSegment,
+               const armem::server::wm::CoreSegment& roomsSegment) :
         arviz(arviz),
         locSegment(locSegment),
         graphSegment(graphSegment),
@@ -130,6 +132,125 @@ namespace armarx::navigation::memory
         }
     }
 
+    namespace
+    {
+
+        void
+        visualize(const algorithms::Costmap& costmap, viz::Layer& layer, const std::string& name)
+        {
+            const auto cmap = simox::color::cmaps::viridis();
+            const float vmax = costmap.getGrid().array().maxCoeff();
+
+            const auto asColor = [&cmap, &vmax](const float distance) -> viz::data::Color
+            {
+                const auto color = cmap.at(distance, 0.F, vmax);
+                return {color.a, color.r, color.g, color.b};
+            };
+
+            const std::int64_t cols = costmap.getGrid().cols();
+            const std::int64_t rows = costmap.getGrid().rows();
+
+            auto mesh = viz::Mesh(name);
+
+            std::vector<std::vector<Eigen::Vector3f>> vertices;
+            std::vector<std::vector<viz::data::Color>> colors;
+
+            for (int r = 0; r < rows; r++)
+            {
+                auto& verticesRow = vertices.emplace_back(cols);
+                auto& colorsRow = colors.emplace_back(cols);
+
+                for (int c = 0; c < cols; c++)
+                {
+                    verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
+                    colorsRow.at(c) = asColor(costmap.getGrid()(r, c));
+                }
+            }
+
+            mesh.grid2D(vertices, colors);
+
+            layer.add(mesh);
+        }
+
+        inline void
+        visualize(const human::Humans& humans, viz::Layer& layer, const bool visuTransparent)
+        {
+
+            const Eigen::Translation3f human_T_mmm(Eigen::Vector3f{0, 0, 1000});
+
+            ARMARX_INFO << "Visualizing " << humans.size() << " humans";
+            for (const auto& human : humans)
+            {
+                // viz::Cylinder cylinder(std::to_string(layer.size()));
+                // cylinder.fromTo(conv::to3D(human.pose.translation()),
+                //                 conv::to3D(human.pose.translation()) + Eigen::Vector3f{0, 0, 10});
+
+
+                // cylinder.color(simox::Color::orange());
+                // cylinder.radius(300);
+                // layer.add(cylinder);
+
+
+                viz::Robot mmm(std::to_string(layer.size()));
+                mmm.file("RobotAPI", "RobotAPI/robots/MMM/mmm.xml");
+                mmm.pose(conv::to3D(human.pose) * human_T_mmm);
+                mmm.scale(1.7); // 1.7m
+                mmm.overrideColor(viz::Color::orange(255, visuTransparent ? 100 : 255));
+                layer.add(mmm);
+
+
+                core::Pose pose3d = conv::to3D(human.pose);
+                pose3d.translation() += Eigen::Vector3f{0, 0, 1000};
+                auto arrow = viz::Arrow(std::to_string(layer.size()))
+                                 .pose(pose3d)
+                                 .length(200)
+                                 .color(simox::Color::red());
+                layer.add(arrow);
+            }
+        }
+
+    } // namespace
+
+    void
+    Visu::drawCostmaps(std::vector<viz::Layer>& layers, bool enabled)
+    {
+        if (not enabled)
+        {
+            return;
+        }
+
+        std::map<std::string, std::vector<std::pair<std::string, algorithms::Costmap>>>
+            namedProviderCostmaps;
+
+        costmapSegment.doLocked(
+            [&]()
+            {
+                using namespace armem::server;
+
+                costmapSegment.forEachEntity(
+                    [&](const wm::Entity& entity)
+                    {
+                        if (const wm::EntityInstance* instance = entity.findLatestInstance())
+                        {
+                            navigation::algorithms::Costmap costmap =
+                                algorithms::fromAron(*instance);
+
+                            namedProviderCostmaps[instance->id().providerSegmentName].emplace_back(
+                                instance->id().entityName, std::move(costmap));
+                        }
+                    });
+            });
+
+        for (const auto& [providerName, namedCostmaps] : namedProviderCostmaps)
+        {
+            viz::Layer& layer = layers.emplace_back(arviz.layer("costmaps_" + providerName));
+            for (const auto& [name, costmap] : namedCostmaps)
+            {
+                visualize(costmap, layer, name);
+            }
+        }
+    }
+
 
     void
     Visu::drawRooms(std::vector<viz::Layer>& layers, bool enabled)
-- 
GitLab


From e218b01aab5501827af829f2bdbd80b2c04944c7 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 12 Jan 2023 18:21:10 +0100
Subject: [PATCH 304/324] fix. finally :)

---
 .../components/navigation_memory/Visu.cpp     | 46 +++++++++++++++++++
 1 file changed, 46 insertions(+)

diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 5a03b6f4..f726693d 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -37,6 +37,8 @@
 #include <armarx/navigation/graph/Visu.h>
 #include <armarx/navigation/rooms/aron/Room.aron.generated.h>
 #include <armarx/navigation/rooms/aron_conversions.h>
+#include <armarx/navigation/human/aron/Human.aron.generated.h>
+#include <armarx/navigation/human/aron_conversions.h>
 
 
 namespace armarx::navigation::memory
@@ -316,5 +318,49 @@ namespace armarx::navigation::memory
         layer.add(path);
     }
 
+    void
+    Visu::drawHumans(std::vector<viz::Layer>& layers,
+                     const bool enabled,
+                     const bool visuTransparent)
+    {
+        if (not enabled)
+        {
+            return;
+        }
+
+        std::map<std::string, navigation::human::Humans> namedProviderHumans;
+
+        humanSegment.doLocked(
+            [&]()
+            {
+                using namespace armem::server;
+
+                humanSegment.forEachEntity(
+                    [&](const wm::Entity& entity)
+                    {
+                        namedProviderHumans[entity.id().providerSegmentName];
+                        entity.getLatestSnapshot().forEachInstance(
+                            [&namedProviderHumans](
+                                const armarx::armem::wm::EntityInstance& instance)
+                            {
+                                const auto dto =
+                                    navigation::human::arondto::Human::FromAron(instance.data());
+
+                                navigation::human::Human human;
+                                fromAron(dto, human);
+
+                                namedProviderHumans[instance.id().providerSegmentName].emplace_back(
+                                    std::move(human));
+                            });
+                    });
+            });
+
+        for (const auto& [providerName, humans] : namedProviderHumans)
+        {
+            viz::Layer& layer = layers.emplace_back(arviz.layer("humans_" + providerName));
+            visualize(humans, layer, visuTransparent);
+        }
+    }
+
 
 } // namespace armarx::navigation::memory
-- 
GitLab


From 218aadcabd2bf0fedf374c79d780ba7587993b52 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 12 Jan 2023 19:28:11 +0100
Subject: [PATCH 305/324] fixing includes: <> instead of ""

---
 .../PlatformNavigation/PlatformNavigation.scx |   1 +
 .../config/example_client.cfg                 | 160 ++++++-----
 .../config/navigation_memory.cfg              |  19 +-
 .../PlatformNavigation/config/navigator.cfg   | 269 +++++++++++-------
 .../navigation/algorithms/aron_conversions.h  |   2 +-
 .../client/services/IceNavigator.cpp          |   2 +-
 .../navigation/client/services/IceNavigator.h |   4 +-
 .../Component.cpp                             |   4 +-
 .../Component.h                               |   2 +-
 .../Component.cpp                             |   2 +-
 .../dynamic_scene_provider/Component.cpp      |   2 +-
 .../dynamic_scene_provider/Component.h        |   8 +-
 .../components/human_simulator/Component.cpp  |  10 +-
 .../components/human_simulator/Component.h    |   6 +-
 .../navigation_memory/Component.cpp           |   2 +-
 .../components/navigation_memory/Visu.cpp     |   4 +-
 .../components/navigation_memory/Visu.h       |   2 +-
 .../navigation_skill_provider/Component.cpp   |   6 +-
 .../navigation_skill_provider/Component.h     |   6 +-
 .../components/navigator/RemoteGui.cpp        |   2 +-
 .../factories/LocalPlannerFactory.cpp         |   2 +-
 .../armarx/navigation/global_planning/SPFA.h  |   4 +-
 .../armarx/navigation/human/HumanTracker.cpp  |   2 +-
 .../local_planning/TimedElasticBands.cpp      |   4 +-
 .../local_planning/TimedElasticBands.h        |   2 +-
 .../local_planning/TimedElasticBandsParams.h  |   2 +-
 .../local_planning/aron_conversions.cpp       |   2 +-
 .../local_planning/ros_conversions.cpp        |   4 +-
 .../navigation/memory/client/human/Reader.cpp |   2 +-
 .../navigation/memory/client/human/Reader.h   |   2 +-
 .../navigation/memory/client/human/Writer.cpp |   2 +-
 .../navigation/memory/client/rooms/Reader.cpp |   2 +-
 .../memory/client/stack_result/Reader.h       |   4 +-
 .../memory/client/stack_result/Writer.h       |   2 +-
 .../PlatformGlobalTrajectoryController.h      |   2 +-
 .../rooms/RoomNavigationTargetCreator.cpp     |   6 +-
 .../rooms/RoomNavigationTargetCreator.h       |   6 +-
 .../navigation/rooms/aron_conversions.cpp     |   2 +-
 source/armarx/navigation/rooms/types.cpp      |   4 +-
 source/armarx/navigation/server/Navigator.cpp |   2 +-
 source/armarx/navigation/server/StackResult.h |   2 +-
 .../server/execution/ExecutorInterface.h      |   2 +-
 .../introspection/ArvizIntrospector.cpp       |   2 +-
 .../navigation/server/test/serverTest.cpp     |   2 +-
 .../navigation/simulation/SimulatedHuman.cpp  |  18 +-
 .../navigation/simulation/SimulatedHuman.h    |   8 +-
 .../navigation/skills/GuideHumanToRoom.cpp    |  20 +-
 .../navigation/skills/GuideHumanToRoom.h      |   6 +-
 .../armarx/navigation/skills/NavigateTo.cpp   |   6 +-
 .../navigation/skills/NavigateToLocation.cpp  |   4 +-
 .../NavigationGroup/NavigateRelative.cpp      |   2 +-
 .../NavigationGroup/NavigateTo.cpp            |   2 +-
 .../NavigationGroup/NavigateToLocation.cpp    |   2 +-
 .../global/TrajectoryFollowingController.cpp  |   2 +-
 .../local/TrajectoryFollowingController.cpp   |   2 +-
 55 files changed, 369 insertions(+), 282 deletions(-)

diff --git a/scenarios/PlatformNavigation/PlatformNavigation.scx b/scenarios/PlatformNavigation/PlatformNavigation.scx
index 90b9b009..5bce3045 100644
--- a/scenarios/PlatformNavigation/PlatformNavigation.scx
+++ b/scenarios/PlatformNavigation/PlatformNavigation.scx
@@ -14,3 +14,4 @@
 	<application name="navigation_skill_provider" instance="" package="armarx_navigation" nodeName="" enabled="true" iceAutoRestart="false"/>
 	<application name="SkillsMemory" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
 </scenario>
+
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index e9130c39..517f09d1 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -76,179 +76,201 @@
 # ArmarX.EnableProfiling = false
 
 
-# ArmarX.ExampleClient.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
-#  - Default:            false
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.EnableProfiling = false
+# ArmarX.LoadLibraries = ""
 
 
-# ArmarX.ExampleClient.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
 #  Attributes:
-#  - Default:            Undefined
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.ExampleClient.MinimumLoggingLevel = Undefined
+# ArmarX.LoggingGroup = ""
 
 
-# ArmarX.ExampleClient.ObjectName:  Name of IceGrid well-known object
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
-#  - Default:            ""
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.ObjectName = ""
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
 
 
-# ArmarX.ExampleClient.mem.robot_state.Memory:  
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
 #  Attributes:
-#  - Default:            RobotState
+#  - Default:            3000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.Memory = RobotState
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
 
 
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
 #  Attributes:
-#  - Default:            Localization
+#  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mem.robot_state.localizationSegment = Localization
+# ArmarX.SecondsStartupDelay = 0
 
 
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
-# Set to false to use this memory as a stand-alone.
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
 #  Attributes:
-#  - Default:            true
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ExampleClient.mns.MemoryNameSystemEnabled = true
+# ArmarX.StartDebuggerOnCrash = false
 
 
-# ArmarX.ExampleClient.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
 #  Attributes:
-#  - Default:            MemoryNameSystem
+#  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.ThreadPoolSize = 1
 
 
-# ArmarX.ExampleClient.nav.NavigatorName:  Name of the Navigator
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
 #  Attributes:
-#  - Default:            navigator
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.ExampleClient.nav.NavigatorName = navigator
+# ArmarX.TopicSuffix = ""
 
 
-# ArmarX.ExampleClient.relativeMovement:  The distance between two target poses [mm]
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
 #  Attributes:
-#  - Default:            200
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.relativeMovement = 200
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
 
 
-# ArmarX.ExampleClient.robotName:  
+# ArmarX.Verbosity:  Global logging level for whole application
 #  Attributes:
-#  - Default:            Armar6
+#  - Default:            Info
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ExampleClient.robotName = Armar6
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.Verbosity = Info
 
 
-# ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
+# ArmarX.example_client.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
-#  - Default:            ""
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.LoadLibraries = ""
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.example_client.EnableProfiling = false
 
 
-# ArmarX.LoggingGroup:  The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
+# ArmarX.example_client.MinimumLoggingLevel:  Local logging level only for this component
+#  Attributes:
+#  - Default:            Undefined
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+# ArmarX.example_client.MinimumLoggingLevel = Undefined
+
+
+# ArmarX.example_client.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.LoggingGroup = ""
+# ArmarX.example_client.ObjectName = ""
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.example_client.mem.nav.costmap.CoreSegment:  
 #  Attributes:
-#  - Default:            true
+#  - Default:            Costmap
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.example_client.mem.nav.costmap.CoreSegment = Costmap
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.example_client.mem.nav.costmap.Memory:  
 #  Attributes:
-#  - Default:            3000
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.example_client.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.example_client.mem.robot_state.Memory:  
 #  Attributes:
-#  - Default:            0
+#  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+# ArmarX.example_client.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.example_client.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
-#  - Default:            false
+#  - Default:            Localization
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.example_client.mem.robot_state.localizationSegment = Localization
+
+
+# ArmarX.example_client.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# Set to false to use this memory as a stand-alone.
+#  Attributes:
+#  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.example_client.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.example_client.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
-#  - Default:            1
+#  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+# ArmarX.example_client.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.example_client.mode:  Which example to run
 #  Attributes:
-#  - Default:            ""
+#  - Default:            standard
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.TopicSuffix = ""
+#  - Possible values: {complex, point_to_point, standard, update_navigator, wander_around}
+ArmarX.example_client.mode = standard
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.example_client.nav.NavigatorName:  Name of the Navigator
 #  Attributes:
-#  - Default:            false
+#  - Default:            navigator
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+# ArmarX.example_client.nav.NavigatorName = navigator
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.example_client.relativeMovement:  The distance between two target poses [mm]
 #  Attributes:
-#  - Default:            Info
+#  - Default:            200
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Verbosity = Info
+# ArmarX.example_client.relativeMovement = 200
 
 
-# ArmarX.example_client.mode:  No Description
+# ArmarX.example_client.robotName:  
 #  Attributes:
-#  - Default:            standard
-#  - Case sensitivity:   no
+#  - Default:            Armar6
+#  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.example_client.mode = standard
+# ArmarX.example_client.robotName = Armar6
+
+
+# ArmarX.ExampleClient.nav.NavigatorName:  
+#  Attributes:
+ArmarX.ExampleClient.nav.NavigatorName = navigator
 
 
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index ce2fdf9b..74112627 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,14 +92,6 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  No Description
-#  Attributes:
-#  - Default:            ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
-#  - Case sensitivity:   no
-#  - Required:           no
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening
-
-
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -263,10 +255,10 @@ ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graph
 
 # ArmarX.navigation_memory.p.locationGraph.visuFrequency:  Visualization frequeny of locations and graph edges [Hz].
 #  Attributes:
-#  - Default:            10
+#  - Default:            2
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 10
+# ArmarX.navigation_memory.p.locationGraph.visuFrequency = 2
 
 
 # ArmarX.navigation_memory.p.locationGraph.visuGraphEdges:  Enable visualization of navigation graph edges.
@@ -293,6 +285,11 @@ ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graph
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.navigation_memory.p.snapshotToLoad = ""
+ArmarX.navigation_memory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003
+
+
+# ArmarX.NavigationMemory.p.snapshotToLoad:  
+#  Attributes:
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003
 
 
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index cc26fb3d..2c22d247 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -92,296 +92,361 @@
 # ArmarX.LoggingGroup = ""
 
 
-# ArmarX.Navigator.ArVizStorageName:  Name of the ArViz storage
+# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+#  Attributes:
+#  - Default:            true
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.RedirectStdout = true
+
+
+# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+#  Attributes:
+#  - Default:            3000
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.RemoteHandlesDeletionTimeout = 3000
+
+
+# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+#  Attributes:
+#  - Default:            0
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.SecondsStartupDelay = 0
+
+
+# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.StartDebuggerOnCrash = false
+
+
+# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+#  Attributes:
+#  - Default:            1
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ThreadPoolSize = 1
+
+
+# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.TopicSuffix = ""
+
+
+# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+#  Attributes:
+#  - Default:            false
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.UseTimeServer = false
+
+
+# ArmarX.Verbosity:  Global logging level for whole application
+#  Attributes:
+#  - Default:            Info
+#  - Case sensitivity:   yes
+#  - Required:           no
+#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
+ArmarX.Verbosity = Verbose
+
+
+# ArmarX.navigator.ArVizStorageName:  Name of the ArViz storage
 #  Attributes:
 #  - Default:            ArVizStorage
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ArVizStorageName = ArVizStorage
+# ArmarX.navigator.ArVizStorageName = ArVizStorage
 
 
-# ArmarX.Navigator.ArVizTopicName:  Name of the ArViz topic
+# ArmarX.navigator.ArVizTopicName:  Name of the ArViz topic
 #  Attributes:
 #  - Default:            ArVizTopic
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ArVizTopicName = ArVizTopic
+# ArmarX.navigator.ArVizTopicName = ArVizTopic
+
+
+# ArmarX.navigator.DebugObserverTopicName:  Name of the topic the DebugObserver listens on
+#  Attributes:
+#  - Default:            DebugObserver
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigator.DebugObserverTopicName = DebugObserver
 
 
-# ArmarX.Navigator.EnableProfiling:  enable profiler which is used for logging performance events
+# ArmarX.navigator.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.EnableProfiling = false
+# ArmarX.navigator.EnableProfiling = false
 
 
-# ArmarX.Navigator.MinimumLoggingLevel:  Local logging level only for this component
+# ArmarX.navigator.MinimumLoggingLevel:  Local logging level only for this component
 #  Attributes:
 #  - Default:            Undefined
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-# ArmarX.Navigator.MinimumLoggingLevel = Undefined
+# ArmarX.navigator.MinimumLoggingLevel = Undefined
 
 
-# ArmarX.Navigator.ObjectMemoryName:  Name of the object memory.
+# ArmarX.navigator.ObjectMemoryName:  Name of the object memory.
 #  Attributes:
 #  - Default:            ObjectMemory
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.ObjectMemoryName = ObjectMemory
+# ArmarX.navigator.ObjectMemoryName = ObjectMemory
 
 
-# ArmarX.Navigator.ObjectName:  Name of IceGrid well-known object
+# ArmarX.navigator.ObjectName:  Name of IceGrid well-known object
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.ObjectName = navigator
+# ArmarX.navigator.ObjectName = ""
 
 
-# ArmarX.Navigator.RobotUnitName:  Name of the RobotUnit
+# ArmarX.navigator.RobotUnitName:  Name of the RobotUnit
 #  Attributes:
 #  - Case sensitivity:   yes
 #  - Required:           yes
-ArmarX.Navigator.RobotUnitName = Armar6Unit
+ArmarX.navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Navigator.cmp.PlatformUnit:  No Description
+# ArmarX.navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
 #  Attributes:
-#  - Default:            Armar6PlatformUnit
-#  - Case sensitivity:   no
+#  - Default:            RemoteGuiProvider
+#  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit
+# ArmarX.navigator.cmp.RemoteGui = RemoteGuiProvider
 
 
-# ArmarX.Navigator.cmp.RemoteGui:  Ice object name of the `RemoteGui` component.
+# ArmarX.navigator.mem.nav.costmap.CoreSegment:  
 #  Attributes:
-#  - Default:            RemoteGuiProvider
+#  - Default:            Costmap
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.cmp.RemoteGui = RemoteGuiProvider
+# ArmarX.navigator.mem.nav.costmap.CoreSegment = Costmap
 
 
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment:  
+# ArmarX.navigator.mem.nav.costmap.Memory:  
 #  Attributes:
-#  - Default:            Costmap
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.CoreSegment = Costmap
+# ArmarX.navigator.mem.nav.costmap.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.costmap.Memory:  
+# ArmarX.navigator.mem.nav.events.CoreSegment:  
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            Events
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Memory = Navigation
+# ArmarX.navigator.mem.nav.events.CoreSegment = Events
 
 
-# ArmarX.Navigator.mem.nav.costmap.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.events.Memory:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.costmap.Provider = ""
+# ArmarX.navigator.mem.nav.events.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.events.CoreSegment:  
+# ArmarX.navigator.mem.nav.events.Provider:  Name of this provider
 #  Attributes:
-#  - Default:            Events
+#  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.CoreSegment = Events
+# ArmarX.navigator.mem.nav.events.Provider = ""
 
 
-# ArmarX.Navigator.mem.nav.events.Memory:  
+# ArmarX.navigator.mem.nav.graph.CoreSegment:  
 #  Attributes:
-#  - Default:            Navigation
+#  - Default:            Location
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Memory = Navigation
+# ArmarX.navigator.mem.nav.graph.CoreSegment = Location
 
 
-# ArmarX.Navigator.mem.nav.events.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.graph.Memory:  
 #  Attributes:
-#  - Default:            ""
+#  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.events.Provider = ""
+# ArmarX.navigator.mem.nav.graph.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.graph.CoreSegment:  
+# ArmarX.navigator.mem.nav.human.CoreSegment:  
 #  Attributes:
-#  - Default:            Location
+#  - Default:            Human
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.CoreSegment = Location
+# ArmarX.navigator.mem.nav.human.CoreSegment = Human
 
 
-# ArmarX.Navigator.mem.nav.graph.Memory:  
+# ArmarX.navigator.mem.nav.human.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.graph.Memory = Navigation
+# ArmarX.navigator.mem.nav.human.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.param.CoreSegment:  
+# ArmarX.navigator.mem.nav.param.CoreSegment:  
 #  Attributes:
 #  - Default:            Parameterization
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.CoreSegment = Parameterization
+# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization
 
 
-# ArmarX.Navigator.mem.nav.param.Memory:  
+# ArmarX.navigator.mem.nav.param.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Memory = Navigation
+# ArmarX.navigator.mem.nav.param.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.param.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.param.Provider:  Name of this provider
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.param.Provider = ""
+# ArmarX.navigator.mem.nav.param.Provider = ""
 
 
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment:  
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment:  
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.CoreSegment = ""
+# ArmarX.navigator.mem.nav.stack_result.CoreSegment = ""
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Memory:  
+# ArmarX.navigator.mem.nav.stack_result.Memory:  
 #  Attributes:
 #  - Default:            Navigation
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Memory = Navigation
+# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation
 
 
-# ArmarX.Navigator.mem.nav.stack_result.Provider:  Name of this provider
+# ArmarX.navigator.mem.nav.stack_result.Provider:  Name of this provider
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.nav.stack_result.Provider = ""
+# ArmarX.navigator.mem.nav.stack_result.Provider = ""
 
 
-# ArmarX.Navigator.mem.robot_state.Memory:  
+# ArmarX.navigator.mem.robot_state.Memory:  
 #  Attributes:
 #  - Default:            RobotState
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.Memory = RobotState
+# ArmarX.navigator.mem.robot_state.Memory = RobotState
 
 
-# ArmarX.Navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
+# ArmarX.navigator.mem.robot_state.localizationSegment:  Name of the localization memory core segment to use.
 #  Attributes:
 #  - Default:            Localization
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mem.robot_state.localizationSegment = Localization
+# ArmarX.navigator.mem.robot_state.localizationSegment = Localization
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
+# ArmarX.navigator.mns.MemoryNameSystemEnabled:  Whether to use (and depend on) the Memory Name System (MNS).
 # Set to false to use this memory as a stand-alone.
 #  Attributes:
 #  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.Navigator.mns.MemoryNameSystemEnabled = true
+# ArmarX.navigator.mns.MemoryNameSystemEnabled = true
 
 
-# ArmarX.Navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
+# ArmarX.navigator.mns.MemoryNameSystemName:  Name of the Memory Name System (MNS) component.
 #  Attributes:
 #  - Default:            MemoryNameSystem
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem
+# ArmarX.navigator.mns.MemoryNameSystemName = MemoryNameSystem
 
 
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
+# ArmarX.navigator.p.disableExecutor:  If the executor is disabled, the navigator will only plan the trajectory but won't execute it.
 #  Attributes:
-#  - Default:            0.550000012
+#  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+#  - Possible values: {0, 1, false, no, true, yes}
+# ArmarX.navigator.p.disableExecutor = false
 
 
-# ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
+# ArmarX.navigator.p.occupancy_grid.occopied_threshold:  Threshold for each cell to be considered occupied. Increase this value to reduce noise.
 #  Attributes:
-#  - Default:            true
+#  - Default:            0.550000012
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.RedirectStdout = true
+# ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.550000012
 
 
-# ArmarX.RemoteHandlesDeletionTimeout:  The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles)
+# ArmarX.navigator.p.scene.humanProviderName:  
 #  Attributes:
-#  - Default:            3000
+#  - Default:            dynamic_scene_provider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.RemoteHandlesDeletionTimeout = 3000
+# ArmarX.navigator.p.scene.humanProviderName = dynamic_scene_provider
 
 
-# ArmarX.SecondsStartupDelay:  The startup will be delayed by this number of seconds (useful for debugging)
+# ArmarX.navigator.p.scene.robotName:  
 #  Attributes:
-#  - Default:            0
 #  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.SecondsStartupDelay = 0
+#  - Required:           yes
+ArmarX.navigator.p.scene.robotName = Armar6
 
 
-# ArmarX.StartDebuggerOnCrash:  If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
+# ArmarX.navigator.p.scene.staticCostmapName:  
 #  Attributes:
-#  - Default:            false
+#  - Default:            distance_to_obstacles
 #  - Case sensitivity:   yes
 #  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.StartDebuggerOnCrash = false
+# ArmarX.navigator.p.scene.staticCostmapName = distance_to_obstacles
 
 
-# ArmarX.ThreadPoolSize:  Size of the ArmarX ThreadPool that is always running.
+# ArmarX.navigator.p.scene.staticCostmapProviderName:  
 #  Attributes:
-#  - Default:            1
+#  - Default:            distance_to_obstacle_costmap_provider
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ThreadPoolSize = 1
+# ArmarX.navigator.p.scene.staticCostmapProviderName = distance_to_obstacle_costmap_provider
 
 
-# ArmarX.TopicSuffix:  Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes.
+# ArmarX.Navigator.ObjectName:  
 #  Attributes:
-#  - Default:            ""
-#  - Case sensitivity:   yes
-#  - Required:           no
-# ArmarX.TopicSuffix = ""
+ArmarX.Navigator.ObjectName = navigator
 
 
-# ArmarX.UseTimeServer:  Enable using a global Timeserver (e.g. from ArmarXSimulator)
+# ArmarX.Navigator.RobotUnitName:  
 #  Attributes:
-#  - Default:            false
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.UseTimeServer = false
+ArmarX.Navigator.RobotUnitName = Armar6Unit
 
 
-# ArmarX.Verbosity:  Global logging level for whole application
+# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  
 #  Attributes:
-#  - Default:            Info
-#  - Case sensitivity:   yes
-#  - Required:           no
-#  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
diff --git a/source/armarx/navigation/algorithms/aron_conversions.h b/source/armarx/navigation/algorithms/aron_conversions.h
index 531412d2..965857a2 100644
--- a/source/armarx/navigation/algorithms/aron_conversions.h
+++ b/source/armarx/navigation/algorithms/aron_conversions.h
@@ -22,7 +22,7 @@
 #pragma once
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
+#include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
 
diff --git a/source/armarx/navigation/client/services/IceNavigator.cpp b/source/armarx/navigation/client/services/IceNavigator.cpp
index cc1c51b4..3bae4a6d 100644
--- a/source/armarx/navigation/client/services/IceNavigator.cpp
+++ b/source/armarx/navigation/client/services/IceNavigator.cpp
@@ -2,7 +2,7 @@
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
-#include "armarx/navigation/core/types.h"
+#include <armarx/navigation/core/types.h>
 
 
 namespace armarx::navigation::client
diff --git a/source/armarx/navigation/client/services/IceNavigator.h b/source/armarx/navigation/client/services/IceNavigator.h
index 142bebb4..783e77e7 100644
--- a/source/armarx/navigation/client/services/IceNavigator.h
+++ b/source/armarx/navigation/client/services/IceNavigator.h
@@ -3,8 +3,8 @@
 
 #include <string>
 
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/core/types.h"
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/core/types.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/client/ice_conversions.h>
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
index 6c52b133..0221c606 100644
--- a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.cpp
@@ -33,8 +33,8 @@
 
 #include "RobotAPI/libraries/ArmarXObjects/forward_declarations.h"
 
-#include "armarx/navigation/algorithms/CostmapBuilder.h"
-#include "armarx/navigation/util/util.h"
+#include <armarx/navigation/algorithms/CostmapBuilder.h>
+#include <armarx/navigation/util/util.h>
 
 
 namespace armarx::navigation::components::distance_to_obstacle_costmap_provider
diff --git a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
index bd6a9bee..2f9a751a 100644
--- a/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
+++ b/source/armarx/navigation/components/distance_to_obstacle_costmap_provider/Component.h
@@ -31,7 +31,7 @@
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
 #include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h>
 
-#include "armarx/navigation/memory/client/costmap/Writer.h"
+#include <armarx/navigation/memory/client/costmap/Writer.h>
 #include <armarx/navigation/components/distance_to_obstacle_costmap_provider/ComponentInterface.h>
 
 
diff --git a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
index 1b71fbe6..ab0d5810 100644
--- a/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_distance_to_obstacle_costmap_provider/Component.cpp
@@ -37,7 +37,7 @@
 #include <RobotAPI/libraries/armem_robot_state/client/common/RobotReader.h>
 #include <RobotAPI/libraries/armem_vision/client/laser_scanner_features/Reader.h>
 
-#include "armarx/navigation/util/geometry.h"
+#include <armarx/navigation/util/geometry.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
 #include <armarx/navigation/conversions/eigen.h>
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
index 9ddc696a..77d1fd7f 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.cpp
@@ -35,7 +35,7 @@
 
 #include <VisionX/libraries/armem_human/client/HumanPoseReader.h>
 
-#include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
+#include <armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h>
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/memory/client/costmap/Reader.h>
 #include <armarx/navigation/util/util.h>
diff --git a/source/armarx/navigation/components/dynamic_scene_provider/Component.h b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
index aec652dd..11e0d654 100644
--- a/source/armarx/navigation/components/dynamic_scene_provider/Component.h
+++ b/source/armarx/navigation/components/dynamic_scene_provider/Component.h
@@ -46,10 +46,10 @@
 #include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
-#include "armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h"
-#include "armarx/navigation/human/HumanTracker.h"
-#include "armarx/navigation/memory/client/costmap/Reader.h"
-#include "armarx/navigation/memory/client/human/Writer.h"
+#include <armarx/navigation/components/dynamic_scene_provider/ArVizDrawer.h>
+#include <armarx/navigation/human/HumanTracker.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/human/Writer.h>
 #include <armarx/navigation/components/dynamic_scene_provider/ComponentInterface.h>
 
 
diff --git a/source/armarx/navigation/components/human_simulator/Component.cpp b/source/armarx/navigation/components/human_simulator/Component.cpp
index fe429dbe..ce8b6206 100644
--- a/source/armarx/navigation/components/human_simulator/Component.cpp
+++ b/source/armarx/navigation/components/human_simulator/Component.cpp
@@ -38,11 +38,11 @@
 #include "RobotAPI/components/ArViz/Client/elements/Path.h"
 #include "RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h"
 
-#include "armarx/navigation/algorithms/Costmap.h"
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/human/types.h"
-#include "armarx/navigation/simulation/SimulatedHuman.h"
-#include "armarx/navigation/util/util.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/types.h>
+#include <armarx/navigation/simulation/SimulatedHuman.h>
+#include <armarx/navigation/util/util.h>
 #include <RVOSimulator.h>
 #include <Vector2.h>
 
diff --git a/source/armarx/navigation/components/human_simulator/Component.h b/source/armarx/navigation/components/human_simulator/Component.h
index e0f004aa..d0627617 100644
--- a/source/armarx/navigation/components/human_simulator/Component.h
+++ b/source/armarx/navigation/components/human_simulator/Component.h
@@ -41,9 +41,9 @@
 
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 
-#include "armarx/navigation/memory/client/costmap/Reader.h"
-#include "armarx/navigation/memory/client/human/Writer.h"
-#include "armarx/navigation/simulation/SimulatedHuman.h"
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/human/Writer.h>
+#include <armarx/navigation/simulation/SimulatedHuman.h>
 // #include <Simulator.h>
 #include "RVO.h"
 #include <armarx/navigation/components/human_simulator/ComponentInterface.h>
diff --git a/source/armarx/navigation/components/navigation_memory/Component.cpp b/source/armarx/navigation/components/navigation_memory/Component.cpp
index e79acee4..03ee1d01 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Component.cpp
@@ -44,7 +44,7 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
 
 #include "Visu.h"
-#include "armarx/navigation/rooms/constants.h"
+#include <armarx/navigation/rooms/constants.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
 #include <armarx/navigation/core/Graph.h>
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index f726693d..4b8f4514 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -29,8 +29,8 @@
 #include "RobotAPI/components/ArViz/Client/elements/Path.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
-#include "armarx/navigation/algorithms/aron_conversions.h"
-#include "armarx/navigation/conversions/eigen.h"
+#include <armarx/navigation/algorithms/aron_conversions.h>
+#include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/Graph.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.h b/source/armarx/navigation/components/navigation_memory/Visu.h
index 8e2071f7..86515aa8 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.h
+++ b/source/armarx/navigation/components/navigation_memory/Visu.h
@@ -30,7 +30,7 @@
 #include <RobotAPI/components/ArViz/Client/Client.h>
 #include <RobotAPI/libraries/armem/core/forward_declarations.h>
 
-#include "armarx/navigation/algorithms/Costmap.h"
+#include <armarx/navigation/algorithms/Costmap.h>
 
 #include <armarx/navigation/rooms/types.h>
 
diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
index 3571e902..934bf44c 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
@@ -25,9 +25,9 @@
 
 #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h>
 
-#include "armarx/navigation/skills/GuideHumanToRoom.h"
-#include "armarx/navigation/skills/NavigateTo.h"
-#include "armarx/navigation/skills/NavigateToLocation.h"
+#include <armarx/navigation/skills/GuideHumanToRoom.h>
+#include <armarx/navigation/skills/NavigateTo.h>
+#include <armarx/navigation/skills/NavigateToLocation.h>
 
 // Include headers you only need in function definitions in the .cpp.
 
diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.h b/source/armarx/navigation/components/navigation_skill_provider/Component.h
index e620c8ce..6b6068d5 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.h
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.h
@@ -39,9 +39,9 @@
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
 #include <RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h>
 
-#include "armarx/navigation/client/services/IceNavigator.h"
-#include "armarx/navigation/memory/client/costmap/Reader.h"
-#include "armarx/navigation/memory/client/rooms/Reader.h"
+#include <armarx/navigation/client/services/IceNavigator.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/rooms/Reader.h>
 #include <armarx/navigation/client.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/components/navigation_skill_provider/ComponentInterface.h>
diff --git a/source/armarx/navigation/components/navigator/RemoteGui.cpp b/source/armarx/navigation/components/navigator/RemoteGui.cpp
index f1dafca6..42d9ad21 100644
--- a/source/armarx/navigation/components/navigator/RemoteGui.cpp
+++ b/source/armarx/navigation/components/navigator/RemoteGui.cpp
@@ -16,7 +16,7 @@
 #include <ArmarXGui/libraries/RemoteGui/WidgetProxy.h>
 
 #include "Component.h"
-#include "armarx/navigation/local_planning/TimedElasticBandsParams.h"
+#include <armarx/navigation/local_planning/TimedElasticBandsParams.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/factories/NavigationStackFactory.h>
diff --git a/source/armarx/navigation/factories/LocalPlannerFactory.cpp b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
index 967d693b..f619fd37 100644
--- a/source/armarx/navigation/factories/LocalPlannerFactory.cpp
+++ b/source/armarx/navigation/factories/LocalPlannerFactory.cpp
@@ -5,7 +5,7 @@
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 #include <RobotAPI/libraries/aron/core/data/variant/primitive/String.h>
 
-#include "armarx/navigation/local_planning/core.h"
+#include <armarx/navigation/local_planning/core.h>
 #include <armarx/navigation/core/constants.h>
 
 #ifdef TIMED_ELASTIC_BANDS_ENABLED
diff --git a/source/armarx/navigation/global_planning/SPFA.h b/source/armarx/navigation/global_planning/SPFA.h
index 2246f92b..7ac29893 100644
--- a/source/armarx/navigation/global_planning/SPFA.h
+++ b/source/armarx/navigation/global_planning/SPFA.h
@@ -24,8 +24,8 @@
 
 #include <VirtualRobot/MathTools.h>
 #include "GlobalPlanner.h"
-#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
-#include "armarx/navigation/global_planning/core.h"
+#include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
+#include <armarx/navigation/global_planning/core.h>
 #include <armarx/navigation/core/types.h>
 
 namespace armarx::navigation::global_planning
diff --git a/source/armarx/navigation/human/HumanTracker.cpp b/source/armarx/navigation/human/HumanTracker.cpp
index d9841e38..7273cdd7 100644
--- a/source/armarx/navigation/human/HumanTracker.cpp
+++ b/source/armarx/navigation/human/HumanTracker.cpp
@@ -6,7 +6,7 @@
 
 #include "ArmarXCore/core/exceptions/local/ExpressionException.h"
 
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/human/types.h>
 #include <armarx/navigation/conversions/eigen.h>
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/transform.hpp>
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
index c603e85a..1430129d 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp
@@ -13,8 +13,8 @@
 
 #include "RobotAPI/libraries/aron/core/data/rw/reader/nlohmannJSON/NlohmannJSONReaderWithoutTypeCheck.h"
 
-#include "armarx/navigation/conversions/eigen.h"
-#include "armarx/navigation/core/Trajectory.h"
+#include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
 #include <armarx/navigation/local_planning/aron_conversions.h>
diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index 1c1db279..a9af1628 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -24,7 +24,7 @@
 
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
-#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/TebObstacleManager.h>
diff --git a/source/armarx/navigation/local_planning/TimedElasticBandsParams.h b/source/armarx/navigation/local_planning/TimedElasticBandsParams.h
index 9cd9a29e..5dcc0dc6 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBandsParams.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBandsParams.h
@@ -25,7 +25,7 @@
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
 
-#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
 #include <armarx/navigation/local_planning/core.h>
 
diff --git a/source/armarx/navigation/local_planning/aron_conversions.cpp b/source/armarx/navigation/local_planning/aron_conversions.cpp
index 1d147c2e..140c02cb 100644
--- a/source/armarx/navigation/local_planning/aron_conversions.cpp
+++ b/source/armarx/navigation/local_planning/aron_conversions.cpp
@@ -3,7 +3,7 @@
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/core.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions/stl.h>
-#include "armarx/navigation/local_planning/TimedElasticBandsParams.h"
+#include <armarx/navigation/local_planning/TimedElasticBandsParams.h>
 
 namespace armarx::navigation::local_planning
 {
diff --git a/source/armarx/navigation/local_planning/ros_conversions.cpp b/source/armarx/navigation/local_planning/ros_conversions.cpp
index 657db4c4..c348cfb1 100644
--- a/source/armarx/navigation/local_planning/ros_conversions.cpp
+++ b/source/armarx/navigation/local_planning/ros_conversions.cpp
@@ -6,8 +6,8 @@
 #include "ArmarXCore/core/time/Clock.h"
 #include "ArmarXCore/core/time/Duration.h"
 
-#include "armarx/navigation/core/Trajectory.h"
-#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/core/Trajectory.h>
+#include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/conversions/eigen.h>
 #include <range/v3/view/drop.hpp>
 #include <range/v3/view/zip.hpp>
diff --git a/source/armarx/navigation/memory/client/human/Reader.cpp b/source/armarx/navigation/memory/client/human/Reader.cpp
index f1ad2e2b..f5b3398a 100644
--- a/source/armarx/navigation/memory/client/human/Reader.cpp
+++ b/source/armarx/navigation/memory/client/human/Reader.cpp
@@ -14,7 +14,7 @@
 #include <RobotAPI/libraries/aron/core/Exception.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/human/types.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/human/aron/Human.aron.generated.h>
diff --git a/source/armarx/navigation/memory/client/human/Reader.h b/source/armarx/navigation/memory/client/human/Reader.h
index 91a17afa..d6dbaf74 100644
--- a/source/armarx/navigation/memory/client/human/Reader.h
+++ b/source/armarx/navigation/memory/client/human/Reader.h
@@ -27,7 +27,7 @@
 #include <RobotAPI/libraries/armem/client/util/SimpleReaderBase.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/human/types.h>
 #include <armarx/navigation/algorithms/Costmap.h>
 
 namespace armarx::navigation::memory::client::human
diff --git a/source/armarx/navigation/memory/client/human/Writer.cpp b/source/armarx/navigation/memory/client/human/Writer.cpp
index c38c2ac7..ef31d0aa 100644
--- a/source/armarx/navigation/memory/client/human/Writer.cpp
+++ b/source/armarx/navigation/memory/client/human/Writer.cpp
@@ -2,7 +2,7 @@
 
 #include <iterator>
 
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/human/types.h>
 #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h>
 #include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/human/aron/Human.aron.generated.h>
diff --git a/source/armarx/navigation/memory/client/rooms/Reader.cpp b/source/armarx/navigation/memory/client/rooms/Reader.cpp
index a3531ad9..cd8fe7f9 100644
--- a/source/armarx/navigation/memory/client/rooms/Reader.cpp
+++ b/source/armarx/navigation/memory/client/rooms/Reader.cpp
@@ -72,7 +72,7 @@ namespace armarx::navigation::memory::client::rooms
         ARMARX_CHECK_NOT_NULL(entityInstance);
 
         const auto aronDto = armem::tryCast<navigation::rooms::arondto::Room>(*entityInstance);
-        ARMARX_CHECK(aronDto) << "Failed casting to Costmap";
+        ARMARX_CHECK(aronDto) << "Failed casting to Room";
         const navigation::rooms::arondto::Room& dto = *aronDto;
 
         navigation::rooms::Room room;
diff --git a/source/armarx/navigation/memory/client/stack_result/Reader.h b/source/armarx/navigation/memory/client/stack_result/Reader.h
index 756d6f0b..071ffe7a 100644
--- a/source/armarx/navigation/memory/client/stack_result/Reader.h
+++ b/source/armarx/navigation/memory/client/stack_result/Reader.h
@@ -25,8 +25,8 @@
 
 #include <RobotAPI/libraries/armem/client/util/SimpleReaderBase.h>
 
-#include "armarx/navigation/core/Trajectory.h"
-#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/core/Trajectory.h>
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 
 namespace armarx::navigation::memory::client::stack_result
 {
diff --git a/source/armarx/navigation/memory/client/stack_result/Writer.h b/source/armarx/navigation/memory/client/stack_result/Writer.h
index 1c2b3183..81468a7f 100644
--- a/source/armarx/navigation/memory/client/stack_result/Writer.h
+++ b/source/armarx/navigation/memory/client/stack_result/Writer.h
@@ -24,7 +24,7 @@
 #include <RobotAPI/libraries/armem/client/util/SimpleWriterBase.h>
 #include <RobotAPI/libraries/armem/core/Commit.h>
 
-#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/server/StackResult.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
diff --git a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
index e9fee601..ad6c2701 100644
--- a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h
@@ -29,7 +29,7 @@
 #include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
 #include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValueHolonomicPlatform.h>
 
-#include "armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h"
+#include <armarx/navigation/trajectory_control/global/TrajectoryFollowingController.h>
 #include <armarx/control/interface/ConfigurableNJointControllerInterface.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
diff --git a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
index 288fb172..d84d933e 100644
--- a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
+++ b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
@@ -2,9 +2,9 @@
 
 #include "ArmarXCore/core/logging/Logging.h"
 
-#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
-#include "armarx/navigation/conversions/eigen.h"
-#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
+#include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/core/basic_types.h>
 #include <range/v3/range/conversion.hpp>
 #include <range/v3/view/reverse.hpp>
 
diff --git a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
index c83ca794..a30c44f6 100644
--- a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
+++ b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
@@ -21,9 +21,9 @@
 
 #pragma once
 
-#include "armarx/navigation/algorithms/Costmap.h"
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/rooms/types.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/rooms/types.h>
 namespace armarx::navigation::rooms
 {
 
diff --git a/source/armarx/navigation/rooms/aron_conversions.cpp b/source/armarx/navigation/rooms/aron_conversions.cpp
index c8b2e920..280afa4c 100644
--- a/source/armarx/navigation/rooms/aron_conversions.cpp
+++ b/source/armarx/navigation/rooms/aron_conversions.cpp
@@ -1,5 +1,5 @@
 #include "aron_conversions.h"
-#include "armarx/navigation/conversions/eigen.h"
+#include <armarx/navigation/conversions/eigen.h>
 
 
 namespace armarx::navigation::rooms
diff --git a/source/armarx/navigation/rooms/types.cpp b/source/armarx/navigation/rooms/types.cpp
index f5d1a2e7..d244e650 100644
--- a/source/armarx/navigation/rooms/types.cpp
+++ b/source/armarx/navigation/rooms/types.cpp
@@ -4,8 +4,8 @@
 #include <boost/geometry/geometries/point_xy.hpp>
 #include <boost/geometry/geometries/polygon.hpp>
 
-#include "armarx/navigation/conversions/eigen.h"
-#include "armarx/navigation/util/geometry.h"
+#include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/util/geometry.h>
 
 namespace armarx::navigation::rooms
 {
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 9123db76..cbe67a10 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -23,7 +23,7 @@
 #include <ArmarXCore/core/time/Clock.h>
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
-#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include "range/v3/algorithm/reverse.hpp"
 #include "range/v3/range/conversion.hpp"
 #include <SemanticObjectRelations/Shapes/Shape.h>
diff --git a/source/armarx/navigation/server/StackResult.h b/source/armarx/navigation/server/StackResult.h
index a742ce4b..47fe1bf6 100644
--- a/source/armarx/navigation/server/StackResult.h
+++ b/source/armarx/navigation/server/StackResult.h
@@ -24,7 +24,7 @@
 
 #include <optional>
 
-#include "armarx/navigation/local_planning/LocalPlanner.h"
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
diff --git a/source/armarx/navigation/server/execution/ExecutorInterface.h b/source/armarx/navigation/server/execution/ExecutorInterface.h
index 65426bf5..25a2462b 100644
--- a/source/armarx/navigation/server/execution/ExecutorInterface.h
+++ b/source/armarx/navigation/server/execution/ExecutorInterface.h
@@ -1,6 +1,6 @@
 #pragma once
 
-#include "armarx/navigation/core/Trajectory.h"
+#include <armarx/navigation/core/Trajectory.h>
 
 namespace armarx::navigation::server
 {
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 6ff9fe14..70045733 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -18,7 +18,7 @@
 #include <RobotAPI/components/ArViz/Client/elements/Color.h>
 #include <RobotAPI/components/ArViz/Client/elements/Path.h>
 
-#include "armarx/navigation/core/Trajectory.h"
+#include <armarx/navigation/core/Trajectory.h>
 #include "range/v3/algorithm/max.hpp"
 #include "range/v3/algorithm/max_element.hpp"
 #include <armarx/navigation/core/basic_types.h>
diff --git a/source/armarx/navigation/server/test/serverTest.cpp b/source/armarx/navigation/server/test/serverTest.cpp
index 701b55ae..48420945 100644
--- a/source/armarx/navigation/server/test/serverTest.cpp
+++ b/source/armarx/navigation/server/test/serverTest.cpp
@@ -21,7 +21,7 @@
  *             GNU General Public License
  */
 
-#include "armarx/navigation/server/scene_provider/SceneProvider.h"
+#include <armarx/navigation/server/scene_provider/SceneProvider.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/core/types.h>
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index f008cccd..880fdf0d 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -25,15 +25,15 @@
 
 #include "ArmarXCore/core/logging/Logging.h"
 
-#include "armarx/navigation/algorithms/Costmap.h"
-#include "armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h"
-#include "armarx/navigation/algorithms/util.h"
-#include "armarx/navigation/conversions/eigen.h"
-#include "armarx/navigation/core/StaticScene.h"
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/core/types.h"
-#include "armarx/navigation/global_planning/SPFA.h"
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
+#include <armarx/navigation/algorithms/util.h>
+#include <armarx/navigation/conversions/eigen.h>
+#include <armarx/navigation/core/StaticScene.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/core/types.h>
+#include <armarx/navigation/global_planning/SPFA.h>
+#include <armarx/navigation/human/types.h>
 
 namespace armarx::navigation::human::simulation
 {
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.h b/source/armarx/navigation/simulation/SimulatedHuman.h
index b1bdc556..e50bab12 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.h
+++ b/source/armarx/navigation/simulation/SimulatedHuman.h
@@ -21,10 +21,10 @@
 
 #pragma once
 
-#include "armarx/navigation/algorithms/Costmap.h"
-#include "armarx/navigation/core/Trajectory.h"
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/human/types.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/core/Trajectory.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/human/types.h>
 
 namespace armarx::navigation::human::simulation
 {
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.cpp b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
index 3f56e3d4..9005d2c0 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.cpp
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
@@ -5,13 +5,12 @@
 
 #include <Eigen/Core>
 #include <Eigen/Geometry>
-#include <Eigen/src/Geometry/AngleAxis.h>
 
-#include "armarx/navigation/algorithms/Costmap.h"
-#include "armarx/navigation/client/services/MemorySubscriber.h"
-#include "armarx/navigation/core/basic_types.h"
-#include "armarx/navigation/global_planning/SPFA.h"
-#include "armarx/navigation/rooms/RoomNavigationTargetCreator.h"
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/client/services/MemorySubscriber.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/global_planning/SPFA.h>
+#include <armarx/navigation/rooms/RoomNavigationTargetCreator.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
@@ -139,7 +138,8 @@ namespace armarx::navigation::skills
                                                                  .timestamp = Clock::Now()};
 
             const auto result = ctx.roomsReader.query(roomQuery);
-            ARMARX_CHECK(result);
+            ARMARX_CHECK(result) << "Failed to query room `" << roomName << "` from provider `"
+                                 << properties.roomsProvider << "`";
             ARMARX_CHECK(result.room.has_value());
 
             return result.room.value();
@@ -153,7 +153,8 @@ namespace armarx::navigation::skills
 
         rooms::RoomNavigationTargetCreator::Params algoParams;
         rooms::RoomNavigationTargetCreator algo(algoParams);
-        auto result = algo.getClosestPositionOutsideOfRoom(costmap, room, global_T_robot.translation());
+        auto result =
+            algo.getClosestPositionOutsideOfRoom(costmap, room, global_T_robot.translation());
 
         const core::Direction dirToRoom = result.global_P_roomEntry - result.global_P_robot;
 
@@ -164,7 +165,8 @@ namespace armarx::navigation::skills
 
         core::Pose global_T_robot_target = core::Pose::Identity();
         global_T_robot_target.translation() = result.global_P_robot;
-        global_T_robot_target.linear() = Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ()).toRotationMatrix();
+        global_T_robot_target.linear() =
+            Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ()).toRotationMatrix();
 
         return global_T_robot_target;
     }
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.h b/source/armarx/navigation/skills/GuideHumanToRoom.h
index 3524f4c4..f4b708ea 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.h
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.h
@@ -29,8 +29,8 @@
 #include <RobotAPI/libraries/skills/provider/Skill.h>
 #include <RobotAPI/libraries/skills/provider/SpecializedSkill.h>
 
-#include "armarx/navigation/memory/client/costmap/Reader.h"
-#include "armarx/navigation/memory/client/rooms/Reader.h"
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/rooms/Reader.h>
 #include <armarx/navigation/client.h>
 #include <armarx/navigation/client/services/MemorySubscriber.h>
 #include <armarx/navigation/skills/aron/GuideHumanToRoom.aron.generated.h>
@@ -60,7 +60,7 @@ namespace armarx::navigation::skills
 
         struct Properties
         {
-            std::string distanceToObstacleCostmapProvider = ""; // FIXME
+            std::string distanceToObstacleCostmapProvider = "distance_to_obstacle_costmap_provider"; // FIXME
             std::string roomsProvider = "R003"; // FIXME
             std::string robotName = "Armar6"; // FIXME
         };
diff --git a/source/armarx/navigation/skills/NavigateTo.cpp b/source/armarx/navigation/skills/NavigateTo.cpp
index df262cde..53170943 100644
--- a/source/armarx/navigation/skills/NavigateTo.cpp
+++ b/source/armarx/navigation/skills/NavigateTo.cpp
@@ -5,9 +5,9 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include "armarx/navigation/client/services/MemorySubscriber.h"
-#include "armarx/navigation/global_planning/SPFA.h"
-#include "armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h"
+#include <armarx/navigation/client/services/MemorySubscriber.h>
+#include <armarx/navigation/global_planning/SPFA.h>
+#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
diff --git a/source/armarx/navigation/skills/NavigateToLocation.cpp b/source/armarx/navigation/skills/NavigateToLocation.cpp
index cad2d681..70783961 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.cpp
+++ b/source/armarx/navigation/skills/NavigateToLocation.cpp
@@ -5,8 +5,8 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include "armarx/navigation/client/services/MemorySubscriber.h"
-#include "armarx/navigation/global_planning/SPFA.h"
+#include <armarx/navigation/client/services/MemorySubscriber.h>
+#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
index bedf8cca..f0f6785c 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateRelative.cpp
@@ -26,7 +26,7 @@
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
-#include "armarx/navigation/global_planning/Point2Point.h"
+#include <armarx/navigation/global_planning/Point2Point.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
index 41d6b3ad..3def882c 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.cpp
@@ -31,7 +31,7 @@
 #include <RobotAPI/libraries/core/FramedPose.h>
 
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
-#include "armarx/navigation/client/services/MemoryPolling.h"
+#include <armarx/navigation/client/services/MemoryPolling.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
index 7a1ca6e0..3c11ba01 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
@@ -28,7 +28,7 @@
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
-#include "armarx/navigation/client/services/MemoryPolling.h"
+#include <armarx/navigation/client/services/MemoryPolling.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
diff --git a/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
index 8a6db3f4..264b6df4 100644
--- a/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/global/TrajectoryFollowingController.cpp
@@ -11,7 +11,7 @@
 
 #include <RobotAPI/libraries/core/MultiDimPIDController.h>
 
-#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/trajectory_control/global/TrajectoryController.h>
diff --git a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
index a16cb656..e95af645 100644
--- a/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
+++ b/source/armarx/navigation/trajectory_control/local/TrajectoryFollowingController.cpp
@@ -15,7 +15,7 @@
 
 #include <RobotAPI/libraries/core/MultiDimPIDController.h>
 
-#include "armarx/navigation/core/basic_types.h"
+#include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryController.h>
-- 
GitLab


From c2a10bce32bba9e896791e0497a9d486d26d032e Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 12 Jan 2023 20:10:07 +0100
Subject: [PATCH 306/324] partially fixing GuideHumanToRoom

---
 .../navigation_skill_provider/Component.cpp   | 40 +++++++++++++------
 .../navigation_skill_provider/Component.h     | 24 ++++++++---
 .../navigation/memory/client/rooms/Reader.cpp | 10 ++---
 .../navigation/skills/GuideHumanToRoom.cpp    | 39 +++++++++++-------
 .../navigation/skills/GuideHumanToRoom.h      |  9 +++--
 .../armarx/navigation/skills/NavigateTo.cpp   | 20 ++++++----
 source/armarx/navigation/skills/NavigateTo.h  |  8 ++--
 .../navigation/skills/NavigateToLocation.cpp  | 19 +++++----
 .../navigation/skills/NavigateToLocation.h    |  8 ++--
 9 files changed, 115 insertions(+), 62 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
index 934bf44c..c87ce6e7 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
@@ -85,6 +85,10 @@ namespace armarx::navigation::components::navigation_skill_provider
         // Keep debug observer data until calling `sendDebugObserverBatch()`.
         // (Requies the armarx::DebugObserverComponentPluginUser.)
         // setDebugObserverBatchModeEnabled(true);
+
+        skills_.navigateTo = addSkill<skills::NavigateTo>();
+        skills_.navigateToLocation = addSkill<skills::NavigateToLocation>();
+        skills_.guideHumanToRoom = addSkill<skills::GuideHumanToRoom>();
     }
 
 
@@ -97,25 +101,35 @@ namespace armarx::navigation::components::navigation_skill_provider
 
 
         {
-            skills::NavigateTo::Context ctx{.iceNavigator = iceNavigator,
-                                            .memoryNameSystem = memoryNameSystem()};
-            addSkill(std::make_unique<skills::NavigateTo>(ctx));
+            ARMARX_CHECK_NOT_NULL(skills_.navigateTo);
+
+            skills::NavigateTo::Services srv{.iceNavigator = iceNavigator,
+                                             .memoryNameSystem = memoryNameSystem()};
+            skills_.navigateTo->connect(srv);
         }
 
         {
-            skills::NavigateToLocation::Context ctx{.iceNavigator = iceNavigator,
-                                                    .memoryNameSystem = memoryNameSystem()};
-            addSkill(std::make_unique<skills::NavigateToLocation>(ctx));
+            ARMARX_CHECK_NOT_NULL(skills_.navigateToLocation);
+
+            skills::NavigateToLocation::Services srv{.iceNavigator = iceNavigator,
+                                                     .memoryNameSystem = memoryNameSystem()};
+            skills_.navigateToLocation->connect(srv);
         }
 
         {
-            skills::GuideHumanToRoom::Context ctx{.iceNavigator = iceNavigator,
-                                                  .memoryNameSystem = memoryNameSystem(),
-                                                  .virtualRobotReader =
-                                                      virtualRobotReaderPlugin->get(),
-                                                  .costmapReader = costmapReaderPlugin->get(),
-                                                  .roomsReader = roomsReaderPlugin->get()};
-            addSkill(std::make_unique<skills::GuideHumanToRoom>(ctx));
+            ARMARX_CHECK_NOT_NULL(virtualRobotReaderPlugin);
+            ARMARX_CHECK_NOT_NULL(virtualRobotReaderPlugin);
+            ARMARX_CHECK_NOT_NULL(roomsReaderPlugin);
+
+            ARMARX_CHECK_NOT_NULL(skills_.guideHumanToRoom);
+
+            skills::GuideHumanToRoom::Services srv{.iceNavigator = iceNavigator,
+                                                   .memoryNameSystem = memoryNameSystem(),
+                                                   .virtualRobotReader =
+                                                       virtualRobotReaderPlugin->get(),
+                                                   .costmapReader = costmapReaderPlugin->get(),
+                                                   .roomsReader = roomsReaderPlugin->get()};
+            skills_.guideHumanToRoom->connect(srv);
         }
 
 
diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.h b/source/armarx/navigation/components/navigation_skill_provider/Component.h
index 6b6068d5..1190f028 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.h
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.h
@@ -39,12 +39,19 @@
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
 #include <RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h>
 
-#include <armarx/navigation/client/services/IceNavigator.h>
-#include <armarx/navigation/memory/client/costmap/Reader.h>
-#include <armarx/navigation/memory/client/rooms/Reader.h>
 #include <armarx/navigation/client.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
+#include <armarx/navigation/client/services/IceNavigator.h>
 #include <armarx/navigation/components/navigation_skill_provider/ComponentInterface.h>
+#include <armarx/navigation/memory/client/costmap/Reader.h>
+#include <armarx/navigation/memory/client/rooms/Reader.h>
+
+namespace armarx::navigation::skills
+{
+    class NavigateTo;
+    class NavigateToLocation;
+    class GuideHumanToRoom;
+} // namespace armarx::navigation::skills
 
 namespace armarx::navigation::components::navigation_skill_provider
 {
@@ -61,7 +68,6 @@ namespace armarx::navigation::components::navigation_skill_provider
     // , virtual public armarx::ArVizComponentPluginUser,
     {
     public:
-
         Component();
         /// @see armarx::ManagedIceObject::getDefaultName()
         std::string getDefaultName() const override;
@@ -110,6 +116,13 @@ namespace armarx::navigation::components::navigation_skill_provider
         void drawBoxes(const Properties& p, viz::Client& arviz);
         */
 
+        struct Skills
+        {
+            skills::NavigateTo* navigateTo;
+            skills::NavigateToLocation* navigateToLocation;
+            skills::GuideHumanToRoom* guideHumanToRoom;
+        } skills_;
+
 
     private:
         static const std::string defaultName;
@@ -158,7 +171,8 @@ namespace armarx::navigation::components::navigation_skill_provider
         using ReaderWriterPlugin = armem::client::plugins::ReaderWriterPlugin<T>;
 
 
-        ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin = nullptr;
+        ReaderWriterPlugin<armem::robot_state::VirtualRobotReader>* virtualRobotReaderPlugin =
+            nullptr;
         ReaderWriterPlugin<memory::client::costmap::Reader>* costmapReaderPlugin = nullptr;
         ReaderWriterPlugin<memory::client::rooms::Reader>* roomsReaderPlugin = nullptr;
     };
diff --git a/source/armarx/navigation/memory/client/rooms/Reader.cpp b/source/armarx/navigation/memory/client/rooms/Reader.cpp
index cd8fe7f9..c89bd4c0 100644
--- a/source/armarx/navigation/memory/client/rooms/Reader.cpp
+++ b/source/armarx/navigation/memory/client/rooms/Reader.cpp
@@ -31,9 +31,9 @@ namespace armarx::navigation::memory::client::rooms
 
         // clang-format off
         qb
-        .coreSegments().withName(properties().coreSegmentName)
+        .coreSegments().withName(memory::constants::RoomsCoreSegmentName)
         .providerSegments().withName(query.providerName)
-        .entities().all()
+        .entities().withName(query.name)
         .snapshots().beforeOrAtTime(query.timestamp);
         // clang-format on
 
@@ -57,7 +57,7 @@ namespace armarx::navigation::memory::client::rooms
     asRoom(const armem::wm::ProviderSegment& providerSegment)
     {
         ARMARX_CHECK(not providerSegment.empty()) << "No entities";
-        ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
+        ARMARX_CHECK_EQUAL(providerSegment.size(), 1) << "There should be only one entity!";
 
         const armem::wm::EntityInstance* entityInstance = nullptr;
         providerSegment.forEachEntity(
@@ -86,11 +86,11 @@ namespace armarx::navigation::memory::client::rooms
     {
         const auto qb = buildQuery(query);
 
-        ARMARX_DEBUG << "[MappingDataReader] query ... ";
+        ARMARX_DEBUG << "[rooms::Reader] query ... ";
 
         const armem::client::QueryResult qResult = memoryReader().query(qb.buildQueryInput());
 
-        ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
+        ARMARX_DEBUG << "[rooms::Reader] result: " << qResult;
 
         if (not qResult.success)
         {
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.cpp b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
index 9005d2c0..2a638bb5 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.cpp
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
@@ -7,30 +7,37 @@
 #include <Eigen/Geometry>
 
 #include <armarx/navigation/algorithms/Costmap.h>
-#include <armarx/navigation/client/services/MemorySubscriber.h>
-#include <armarx/navigation/core/basic_types.h>
-#include <armarx/navigation/global_planning/SPFA.h>
-#include <armarx/navigation/rooms/RoomNavigationTargetCreator.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/services/IceNavigator.h>
+#include <armarx/navigation/client/services/MemorySubscriber.h>
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
+#include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/global_planning/AStar.h>
+#include <armarx/navigation/global_planning/SPFA.h>
+#include <armarx/navigation/rooms/RoomNavigationTargetCreator.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
 {
-    GuideHumanToRoom::GuideHumanToRoom(const GuideHumanToRoom::Context& ctx) :
-        Base(DefaultSkillDescription()), ctx(ctx)
+    GuideHumanToRoom::GuideHumanToRoom() : Base(DefaultSkillDescription())
+    {
+    }
+
+    void
+    GuideHumanToRoom::connect(const Services& srv)
     {
+        srv_.emplace(srv);
     }
 
     ::armarx::skills::Skill::InitResult
     GuideHumanToRoom::init(const Base::SpecializedInitInput& in)
     {
+        ARMARX_CHECK(srv_.has_value());
+
         // parameterize the navigation stack
         client::NavigationStackConfig cfg;
         cfg.general(client::GeneralConfig{});
@@ -41,14 +48,14 @@ namespace armarx::navigation::skills
         const std::string configId = DefaultSkillDescription().skillName;
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
-        memorySubscriber.emplace(configId, ctx.memoryNameSystem);
+        memorySubscriber.emplace(configId, srv_->memoryNameSystem);
 
         // register our config
         ARMARX_INFO << "Registering config";
-        ctx.iceNavigator.createConfig(cfg, configId);
+        srv_->iceNavigator.createConfig(cfg, configId);
 
         navigator.emplace(client::Navigator::InjectedServices{
-            .navigator = &ctx.iceNavigator, .subscriber = &memorySubscriber.value()});
+            .navigator = &srv_->iceNavigator, .subscriber = &memorySubscriber.value()});
 
         return ::armarx::skills::Skill::InitResult{
             .status = ::armarx::skills::TerminatedSkillStatus::Succeeded};
@@ -124,8 +131,8 @@ namespace armarx::navigation::skills
                 .name = "distance_to_obstacles",
                 .timestamp = Clock::Now()};
 
-            const auto result = ctx.costmapReader.query(costmapQuery);
-            ARMARX_CHECK(result);
+            const auto result = srv_->costmapReader.query(costmapQuery);
+            ARMARX_CHECK(result) << result.errorMessage;
             ARMARX_CHECK(result.costmap.has_value());
             return result.costmap.value();
         }();
@@ -137,17 +144,19 @@ namespace armarx::navigation::skills
                                                                  .name = roomName,
                                                                  .timestamp = Clock::Now()};
 
-            const auto result = ctx.roomsReader.query(roomQuery);
+            const auto result = srv_->roomsReader.query(roomQuery);
             ARMARX_CHECK(result) << "Failed to query room `" << roomName << "` from provider `"
-                                 << properties.roomsProvider << "`";
+                                 << properties.roomsProvider
+                                 << "`. Reason: " << result.errorMessage;
             ARMARX_CHECK(result.room.has_value());
 
             return result.room.value();
         }();
 
-        const VirtualRobot::RobotPtr robot = ctx.virtualRobotReader.getRobot(properties.robotName);
+        const VirtualRobot::RobotPtr robot =
+            srv_->virtualRobotReader.getRobot(properties.robotName);
         ARMARX_CHECK_NOT_NULL(robot);
-        ARMARX_CHECK(ctx.virtualRobotReader.synchronizeRobot(*robot, Clock::Now()));
+        ARMARX_CHECK(srv_->virtualRobotReader.synchronizeRobot(*robot, Clock::Now()));
 
         const core::Pose global_T_robot(robot->getGlobalPose());
 
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.h b/source/armarx/navigation/skills/GuideHumanToRoom.h
index f4b708ea..efe447c6 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.h
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.h
@@ -45,7 +45,7 @@ namespace armarx::navigation::skills
         using Base = ::armarx::skills::SpecializedSkill<Params>;
 
 
-        struct Context
+        struct Services
         {
             client::IceNavigator& iceNavigator;
             armem::client::MemoryNameSystem& memoryNameSystem;
@@ -65,7 +65,10 @@ namespace armarx::navigation::skills
             std::string robotName = "Armar6"; // FIXME
         };
 
-        GuideHumanToRoom(const Context& ctx);
+        GuideHumanToRoom();
+
+        void connect(const Services& srv);
+
 
     private:
         ::armarx::skills::Skill::InitResult init(const Base::SpecializedInitInput& in) override;
@@ -89,7 +92,7 @@ namespace armarx::navigation::skills
 
     protected:
     private:
-        const Context ctx;
+        std::optional<Services> srv_;
         const Properties properties;
 
         // will be initialized in "init()"
diff --git a/source/armarx/navigation/skills/NavigateTo.cpp b/source/armarx/navigation/skills/NavigateTo.cpp
index 53170943..115f6bc5 100644
--- a/source/armarx/navigation/skills/NavigateTo.cpp
+++ b/source/armarx/navigation/skills/NavigateTo.cpp
@@ -5,24 +5,28 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include <armarx/navigation/client/services/MemorySubscriber.h>
-#include <armarx/navigation/global_planning/SPFA.h>
-#include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/services/IceNavigator.h>
+#include <armarx/navigation/client/services/MemorySubscriber.h>
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
+#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
 {
-    NavigateTo::NavigateTo(const NavigateTo::Context& ctx) :
-        Base(DefaultSkillDescription()), ctx(ctx)
+    NavigateTo::NavigateTo() : Base(DefaultSkillDescription())
+    {
+    }
+
+    void
+    NavigateTo::connect(const Services& srv)
     {
+        srv_.emplace(srv);
     }
 
     ::armarx::skills::Skill::InitResult
@@ -38,14 +42,14 @@ namespace armarx::navigation::skills
         const std::string configId = DefaultSkillDescription().skillName;
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
-        memorySubscriber.emplace(configId, ctx.memoryNameSystem);
+        memorySubscriber.emplace(configId, srv_->memoryNameSystem);
 
         // register our config
         ARMARX_INFO << "Registering config";
-        ctx.iceNavigator.createConfig(cfg, configId);
+        srv_->iceNavigator.createConfig(cfg, configId);
 
         navigator.emplace(client::Navigator::InjectedServices{
-            .navigator = &ctx.iceNavigator, .subscriber = &memorySubscriber.value()});
+            .navigator = &srv_->iceNavigator, .subscriber = &memorySubscriber.value()});
 
         return ::armarx::skills::Skill::InitResult{
             .status = ::armarx::skills::TerminatedSkillStatus::Succeeded};
diff --git a/source/armarx/navigation/skills/NavigateTo.h b/source/armarx/navigation/skills/NavigateTo.h
index 085d138f..c0a39f60 100644
--- a/source/armarx/navigation/skills/NavigateTo.h
+++ b/source/armarx/navigation/skills/NavigateTo.h
@@ -41,13 +41,15 @@ namespace armarx::navigation::skills
         using Base = ::armarx::skills::SpecializedSkill<Params>;
 
 
-        struct Context
+        struct Services
         {
             client::IceNavigator& iceNavigator;
             armem::client::MemoryNameSystem& memoryNameSystem;
         };
 
-        NavigateTo(const Context& ctx);
+        NavigateTo();
+
+        void connect(const Services& srv);
 
     private:
         ::armarx::skills::Skill::InitResult init(const Base::SpecializedInitInput& in) override;
@@ -70,7 +72,7 @@ namespace armarx::navigation::skills
 
     protected:
     private:
-        const Context ctx;
+        std::optional<Services> srv_;
 
         // will be initialized in "init()"
         std::optional<client::MemorySubscriber> memorySubscriber;
diff --git a/source/armarx/navigation/skills/NavigateToLocation.cpp b/source/armarx/navigation/skills/NavigateToLocation.cpp
index 70783961..d617d492 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.cpp
+++ b/source/armarx/navigation/skills/NavigateToLocation.cpp
@@ -5,23 +5,28 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include <armarx/navigation/client/services/MemorySubscriber.h>
-#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/Navigator.h>
 #include <armarx/navigation/client/PathBuilder.h>
 #include <armarx/navigation/client/services/IceNavigator.h>
+#include <armarx/navigation/client/services/MemorySubscriber.h>
 #include <armarx/navigation/client/services/SimpleEventHandler.h>
 #include <armarx/navigation/client/types.h>
 #include <armarx/navigation/global_planning/AStar.h>
+#include <armarx/navigation/global_planning/SPFA.h>
 #include <armarx/navigation/trajectory_control/local/TrajectoryFollowingController.h>
 
 
 namespace armarx::navigation::skills
 {
-    NavigateToLocation::NavigateToLocation(const NavigateToLocation::Context& ctx) :
-        Base(DefaultSkillDescription()), ctx(ctx)
+    NavigateToLocation::NavigateToLocation() : Base(DefaultSkillDescription())
+    {
+    }
+
+    void
+    NavigateToLocation::connect(const Services& srv)
     {
+        srv_.emplace(srv);
     }
 
     ::armarx::skills::Skill::InitResult
@@ -37,14 +42,14 @@ namespace armarx::navigation::skills
         const std::string configId = DefaultSkillDescription().skillName;
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
-        memorySubscriber.emplace(configId, ctx.memoryNameSystem);
+        memorySubscriber.emplace(configId, srv_->memoryNameSystem);
 
         // register our config
         ARMARX_INFO << "Registering config";
-        ctx.iceNavigator.createConfig(cfg, configId);
+        srv_->iceNavigator.createConfig(cfg, configId);
 
         navigator.emplace(client::Navigator::InjectedServices{
-            .navigator = &ctx.iceNavigator, .subscriber = &memorySubscriber.value()});
+            .navigator = &srv_->iceNavigator, .subscriber = &memorySubscriber.value()});
 
         return ::armarx::skills::Skill::InitResult{
             .status = ::armarx::skills::TerminatedSkillStatus::Succeeded};
diff --git a/source/armarx/navigation/skills/NavigateToLocation.h b/source/armarx/navigation/skills/NavigateToLocation.h
index e24d6197..fcf5d532 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.h
+++ b/source/armarx/navigation/skills/NavigateToLocation.h
@@ -42,14 +42,16 @@ namespace armarx::navigation::skills
         using Base = ::armarx::skills::SpecializedSkill<Params>;
 
 
-        struct Context
+        struct Services
         {
             client::IceNavigator& iceNavigator;
 
             armem::client::MemoryNameSystem& memoryNameSystem;
         };
 
-        NavigateToLocation(const Context& ctx);
+        NavigateToLocation();
+
+        void connect(const Services& srv);
 
     private:
         ::armarx::skills::Skill::InitResult init(const Base::SpecializedInitInput& in) override;
@@ -72,7 +74,7 @@ namespace armarx::navigation::skills
 
     protected:
     private:
-        const Context ctx;
+        std::optional<Services> srv_;
 
         // will be initialized in "init()"
         std::optional<client::MemorySubscriber> memorySubscriber;
-- 
GitLab


From 5ea741f446dfbd863e081a8190675c9c020f1df4 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Fri, 13 Jan 2023 08:11:31 +0100
Subject: [PATCH 307/324] skill "GuideHumanToRoom"

---
 .../config/navigation_skill_provider.cfg      | 16 +++++
 .../navigation/algorithms/CMakeLists.txt      |  3 +
 .../navigation/algorithms/visualization.cpp   | 62 +++++++++++++++++++
 .../navigation/algorithms/visualization.h     | 38 ++++++++++++
 .../navigation_memory/CMakeLists.txt          |  2 +-
 .../components/navigation_memory/Visu.cpp     | 44 ++-----------
 .../navigation_skill_provider/Component.cpp   |  3 +-
 .../navigation_skill_provider/Component.h     | 21 ++-----
 .../rooms/RoomNavigationTargetCreator.cpp     | 55 ++++++++++++++--
 .../rooms/RoomNavigationTargetCreator.h       | 16 +++--
 .../navigation/skills/GuideHumanToRoom.cpp    |  2 +-
 .../navigation/skills/GuideHumanToRoom.h      |  2 +
 12 files changed, 197 insertions(+), 67 deletions(-)
 create mode 100644 source/armarx/navigation/algorithms/visualization.cpp
 create mode 100644 source/armarx/navigation/algorithms/visualization.h

diff --git a/scenarios/PlatformNavigation/config/navigation_skill_provider.cfg b/scenarios/PlatformNavigation/config/navigation_skill_provider.cfg
index 3f23c22d..e4209453 100644
--- a/scenarios/PlatformNavigation/config/navigation_skill_provider.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_skill_provider.cfg
@@ -160,6 +160,22 @@
 # ArmarX.Verbosity = Info
 
 
+# ArmarX.navigation_skill_provider.ArVizStorageName:  Name of the ArViz storage
+#  Attributes:
+#  - Default:            ArVizStorage
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigation_skill_provider.ArVizStorageName = ArVizStorage
+
+
+# ArmarX.navigation_skill_provider.ArVizTopicName:  Name of the ArViz topic
+#  Attributes:
+#  - Default:            ArVizTopic
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.navigation_skill_provider.ArVizTopicName = ArVizTopic
+
+
 # ArmarX.navigation_skill_provider.EnableProfiling:  enable profiler which is used for logging performance events
 #  Attributes:
 #  - Default:            false
diff --git a/source/armarx/navigation/algorithms/CMakeLists.txt b/source/armarx/navigation/algorithms/CMakeLists.txt
index abdba073..59516756 100644
--- a/source/armarx/navigation/algorithms/CMakeLists.txt
+++ b/source/armarx/navigation/algorithms/CMakeLists.txt
@@ -14,6 +14,7 @@ armarx_add_library(algorithms
     DEPENDENCIES_PRIVATE
         OpenMP::OpenMP_CXX
         range-v3::range-v3
+        ArViz # RobotAPI
     DEPENDENCIES_LEGACY
         OpenCV
     SOURCES
@@ -33,6 +34,7 @@ armarx_add_library(algorithms
         # smoothing
         smoothing/ChainApproximation.cpp
         smoothing/CircularPathSmoothing.cpp
+        visualization.cpp
     HEADERS
         types.h
         algorithms.h
@@ -51,6 +53,7 @@ armarx_add_library(algorithms
         # smoothing
         smoothing/ChainApproximation.h
         smoothing/CircularPathSmoothing.h
+        visualization.h
 )
 
 
diff --git a/source/armarx/navigation/algorithms/visualization.cpp b/source/armarx/navigation/algorithms/visualization.cpp
new file mode 100644
index 00000000..a28cbeb2
--- /dev/null
+++ b/source/armarx/navigation/algorithms/visualization.cpp
@@ -0,0 +1,62 @@
+#include "visualization.h"
+
+#include <vector>
+
+#include <Eigen/Core>
+
+#include <SimoxUtility/color/cmaps/colormaps.h>
+
+#include <RobotAPI/components/ArViz/Client/Layer.h>
+#include <RobotAPI/components/ArViz/Client/elements/Mesh.h>
+
+#include <armarx/navigation/algorithms/Costmap.h>
+#include <armarx/navigation/conversions/eigen.h>
+
+
+namespace armarx::navigation::algorithms
+{
+
+    void
+    visualize(const algorithms::Costmap& costmap, viz::Layer& layer, const std::string& name)
+    {
+        const auto cmap = simox::color::cmaps::viridis();
+        const float vmax = costmap.getGrid().array().maxCoeff();
+
+        const auto asColor = [&cmap, &vmax](const float distance,
+                                            const bool isValid) -> viz::data::Color
+        {
+            const auto color = cmap.at(distance, 0.F, vmax);
+            const Ice::Byte alpha = isValid ? color.a : 0;
+            return {alpha, color.r, color.g, color.b};
+        };
+
+        const std::int64_t cols = costmap.getGrid().cols();
+        const std::int64_t rows = costmap.getGrid().rows();
+
+        auto mesh = viz::Mesh(name);
+
+        std::vector<std::vector<Eigen::Vector3f>> vertices;
+        std::vector<std::vector<viz::data::Color>> colors;
+
+        for (int r = 0; r < rows; r++)
+        {
+            auto& verticesRow = vertices.emplace_back(cols);
+            auto& colorsRow = colors.emplace_back(cols);
+
+            for (int c = 0; c < cols; c++)
+            {
+                verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
+
+                bool isValid =
+                    costmap.getMask().has_value() ? costmap.getMask().value()(r, c) : true;
+                colorsRow.at(c) = asColor(costmap.getGrid()(r, c), isValid);
+            }
+        }
+
+        mesh.grid2D(vertices, colors);
+
+        layer.add(mesh);
+    }
+
+
+} // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/algorithms/visualization.h b/source/armarx/navigation/algorithms/visualization.h
new file mode 100644
index 00000000..df077495
--- /dev/null
+++ b/source/armarx/navigation/algorithms/visualization.h
@@ -0,0 +1,38 @@
+/**
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+
+namespace armarx::viz
+{
+    class Layer;
+}
+
+
+namespace armarx::navigation::algorithms
+{
+    class Costmap;
+
+    void visualize(const Costmap& costmap, viz::Layer& layer, const std::string& name);
+
+
+} // namespace armarx::navigation::algorithms
diff --git a/source/armarx/navigation/components/navigation_memory/CMakeLists.txt b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
index 60c690fb..b4305d4c 100644
--- a/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
+++ b/source/armarx/navigation/components/navigation_memory/CMakeLists.txt
@@ -4,7 +4,7 @@ armarx_add_component(navigation_memory
         RobotAPIInterfaces
     ICE_FILES
         ComponentInterface.ice
-    DEPENDENCIES_PUBLIC
+    DEPENDENCIES
         # ArmarXCore
         ArmarXCore
         ## ArmarXCoreComponentPlugins  # For DebugObserver plugin.
diff --git a/source/armarx/navigation/components/navigation_memory/Visu.cpp b/source/armarx/navigation/components/navigation_memory/Visu.cpp
index 4b8f4514..c450b953 100644
--- a/source/armarx/navigation/components/navigation_memory/Visu.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Visu.cpp
@@ -29,16 +29,17 @@
 #include "RobotAPI/components/ArViz/Client/elements/Path.h"
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
+#include "armarx/navigation/algorithms/visualization.h"
 #include <armarx/navigation/algorithms/aron_conversions.h>
 #include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/Graph.h>
 #include <armarx/navigation/core/aron/Graph.aron.generated.h>
 #include <armarx/navigation/core/aron/Location.aron.generated.h>
 #include <armarx/navigation/graph/Visu.h>
-#include <armarx/navigation/rooms/aron/Room.aron.generated.h>
-#include <armarx/navigation/rooms/aron_conversions.h>
 #include <armarx/navigation/human/aron/Human.aron.generated.h>
 #include <armarx/navigation/human/aron_conversions.h>
+#include <armarx/navigation/rooms/aron/Room.aron.generated.h>
+#include <armarx/navigation/rooms/aron_conversions.h>
 
 
 namespace armarx::navigation::memory
@@ -137,43 +138,6 @@ namespace armarx::navigation::memory
     namespace
     {
 
-        void
-        visualize(const algorithms::Costmap& costmap, viz::Layer& layer, const std::string& name)
-        {
-            const auto cmap = simox::color::cmaps::viridis();
-            const float vmax = costmap.getGrid().array().maxCoeff();
-
-            const auto asColor = [&cmap, &vmax](const float distance) -> viz::data::Color
-            {
-                const auto color = cmap.at(distance, 0.F, vmax);
-                return {color.a, color.r, color.g, color.b};
-            };
-
-            const std::int64_t cols = costmap.getGrid().cols();
-            const std::int64_t rows = costmap.getGrid().rows();
-
-            auto mesh = viz::Mesh(name);
-
-            std::vector<std::vector<Eigen::Vector3f>> vertices;
-            std::vector<std::vector<viz::data::Color>> colors;
-
-            for (int r = 0; r < rows; r++)
-            {
-                auto& verticesRow = vertices.emplace_back(cols);
-                auto& colorsRow = colors.emplace_back(cols);
-
-                for (int c = 0; c < cols; c++)
-                {
-                    verticesRow.at(c) = conv::to3D(costmap.toPositionGlobal({r, c}));
-                    colorsRow.at(c) = asColor(costmap.getGrid()(r, c));
-                }
-            }
-
-            mesh.grid2D(vertices, colors);
-
-            layer.add(mesh);
-        }
-
         inline void
         visualize(const human::Humans& humans, viz::Layer& layer, const bool visuTransparent)
         {
@@ -248,7 +212,7 @@ namespace armarx::navigation::memory
             viz::Layer& layer = layers.emplace_back(arviz.layer("costmaps_" + providerName));
             for (const auto& [name, costmap] : namedCostmaps)
             {
-                visualize(costmap, layer, name);
+                algorithms::visualize(costmap, layer, name);
             }
         }
     }
diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
index c87ce6e7..aebc3d0c 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.cpp
@@ -128,7 +128,8 @@ namespace armarx::navigation::components::navigation_skill_provider
                                                    .virtualRobotReader =
                                                        virtualRobotReaderPlugin->get(),
                                                    .costmapReader = costmapReaderPlugin->get(),
-                                                   .roomsReader = roomsReaderPlugin->get()};
+                                                   .roomsReader = roomsReaderPlugin->get(),
+                                                   .arviz = arviz};
             skills_.guideHumanToRoom->connect(srv);
         }
 
diff --git a/source/armarx/navigation/components/navigation_skill_provider/Component.h b/source/armarx/navigation/components/navigation_skill_provider/Component.h
index 1190f028..bcadb0bc 100644
--- a/source/armarx/navigation/components/navigation_skill_provider/Component.h
+++ b/source/armarx/navigation/components/navigation_skill_provider/Component.h
@@ -23,20 +23,12 @@
 
 #pragma once
 
-
-// #include <mutex>
-
 #include <ArmarXCore/core/Component.h>
 
-// #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h>
-
-// #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h>
-
-// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
-
-#include "RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h"
+#include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 #include <RobotAPI/libraries/armem/client/plugins.h>
 #include <RobotAPI/libraries/armem/client/plugins/ReaderWriterPlugin.h>
+#include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h>
 #include <RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h>
 
 #include <armarx/navigation/client.h>
@@ -61,11 +53,10 @@ namespace armarx::navigation::components::navigation_skill_provider
         virtual public ComponentInterface,
         virtual public armarx::SkillProviderComponentPluginUser,
         // virtual public armarx::navigation::client::ComponentPluginUser,
-        virtual public armem::ListeningClientPluginUser
-
-    // , virtual public armarx::DebugObserverComponentPluginUser
-    // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
-    // , virtual public armarx::ArVizComponentPluginUser,
+        virtual public armem::ListeningClientPluginUser,
+        // , virtual public armarx::DebugObserverComponentPluginUser
+        // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
+        virtual public armarx::ArVizComponentPluginUser
     {
     public:
         Component();
diff --git a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
index d84d933e..9060192a 100644
--- a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
+++ b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
@@ -1,7 +1,13 @@
 #include "RoomNavigationTargetCreator.h"
 
+#include <SimoxUtility/color/Color.h>
+
 #include "ArmarXCore/core/logging/Logging.h"
 
+#include "RobotAPI/components/ArViz/Client/Client.h"
+#include "RobotAPI/components/ArViz/Client/Elements.h"
+
+#include "armarx/navigation/algorithms/visualization.h"
 #include <armarx/navigation/algorithms/spfa/ShortestPathFasterAlgorithm.h>
 #include <armarx/navigation/conversions/eigen.h>
 #include <armarx/navigation/core/basic_types.h>
@@ -18,7 +24,8 @@ namespace armarx::navigation::rooms
     RoomNavigationTargetCreator::getClosestPositionOutsideOfRoom(
         const algorithms::Costmap& obstacleDistancesCostmap,
         const Room& room,
-        const core::Position& global_P_robot) const
+        const core::Position& global_P_robot,
+        viz::Client* arviz) const
     {
         using ShortestPathFasterAlgorithm = algorithms::spfa::ShortestPathFasterAlgorithm;
 
@@ -39,6 +46,9 @@ namespace armarx::navigation::rooms
         const std::size_t cX = roomCostmap.getGrid().rows();
         const std::size_t cY = roomCostmap.getGrid().cols();
 
+        // invalidate everything that is in collision
+        // roomCostmap.getMutableMask().value() = roomCostmap.getGrid().array() >= 0.5;
+
 #pragma omp parallel for schedule(static)
         for (unsigned int x = 0; x < cX; x++)
         {
@@ -51,16 +61,37 @@ namespace armarx::navigation::rooms
                 pos3d.z() = room.zFloor + room.height / 2; // just at the center (height)
 
                 // invalid outside of the room
-                roomCostmap.getMutableMask().value()(x, y) = room.isInside(pos3d);
+                const bool isInside = room.isInside(pos3d);
+
+                roomCostmap.getMutableMask().value()(x, y) *= isInside;
+                roomCostmap.getMutableGrid()(x, y) *= static_cast<float>(isInside);
             }
         }
 
+        ARMARX_INFO << "Closest position to room: " << roomCostmap.optimum().position;
+
         const core::Position closestReachablePositionOnRoomBoundary =
             conv::to3D(roomCostmap.optimum().position);
 
+
         // We don't stop here. We want to place the robot in front of the room at a
-        const auto plan =
-            spfa.plan(conv::to2D(global_P_robot), conv::to2D(closestReachablePositionOnRoomBoundary));
+        const auto plan = spfa.plan(conv::to2D(global_P_robot),
+                                    conv::to2D(closestReachablePositionOnRoomBoundary));
+
+        if (arviz != nullptr)
+        {
+            auto layer = arviz->layer("RoomNavigationTargetCreator");
+            algorithms::visualize(roomCostmap, layer, "room_costmap");
+
+            layer.add(viz::Sphere("closestReachablePositionOnRoomBoundary")
+                          .position(closestReachablePositionOnRoomBoundary)
+                          .radius(50)
+                          .color(simox::Color::blue()));
+
+            arviz->commit(layer);
+        }
+
+
         ARMARX_CHECK(plan.success);
 
         const auto posInFrontOfRoom = [&]() -> core::Position
@@ -70,9 +101,11 @@ namespace armarx::navigation::rooms
 
             const auto reversedPlan = rv::reverse(plan.path) | r::to_vector;
 
+            const auto goalPos = conv::to2D(closestReachablePositionOnRoomBoundary);
+
             for (const auto& pos : reversedPlan)
             {
-                if ((pos - reversedPlan.front()).norm() < params.distanceToRoomEntry)
+                if ((pos - goalPos).norm() > params.distanceToRoomEntry)
                 {
                     return conv::to3D(pos);
                 }
@@ -82,6 +115,18 @@ namespace armarx::navigation::rooms
             return conv::to3D(reversedPlan.back()); // the current robot pos
         }();
 
+        if (arviz != nullptr)
+        {
+            auto layer = arviz->layer("RoomNavigationTargetCreator_target");
+
+            layer.add(viz::Sphere("posInFrontOfRoom")
+                          .position(posInFrontOfRoom)
+                          .radius(50)
+                          .color(simox::Color::green()));
+
+            arviz->commit(layer);
+        }
+
         return {.global_P_roomEntry = closestReachablePositionOnRoomBoundary,
                 .global_P_robot = posInFrontOfRoom};
     }
diff --git a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
index a30c44f6..5e72cece 100644
--- a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
+++ b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.h
@@ -24,6 +24,12 @@
 #include <armarx/navigation/algorithms/Costmap.h>
 #include <armarx/navigation/core/basic_types.h>
 #include <armarx/navigation/rooms/types.h>
+
+namespace armarx::viz
+{
+    class Client;
+}
+
 namespace armarx::navigation::rooms
 {
 
@@ -32,18 +38,20 @@ namespace armarx::navigation::rooms
     public:
         struct Params
         {
-          float distanceToRoomEntry = 1000;
+            float distanceToRoomEntry = 1000;
         };
         RoomNavigationTargetCreator(const Params& params);
 
-        struct Result{
+        struct Result
+        {
             core::Position global_P_roomEntry;
             core::Position global_P_robot; // where the robot should be placed
         };
 
         Result getClosestPositionOutsideOfRoom(const algorithms::Costmap& obstacleDistancesCostmap,
-                                                       const Room& room,
-                                                       const core::Position& global_P_robot) const;
+                                               const Room& room,
+                                               const core::Position& global_P_robot,
+                                               viz::Client* arviz = nullptr) const;
 
     protected:
     private:
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.cpp b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
index 2a638bb5..0b25333b 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.cpp
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.cpp
@@ -163,7 +163,7 @@ namespace armarx::navigation::skills
         rooms::RoomNavigationTargetCreator::Params algoParams;
         rooms::RoomNavigationTargetCreator algo(algoParams);
         auto result =
-            algo.getClosestPositionOutsideOfRoom(costmap, room, global_T_robot.translation());
+            algo.getClosestPositionOutsideOfRoom(costmap, room, global_T_robot.translation(), &srv_->arviz);
 
         const core::Direction dirToRoom = result.global_P_roomEntry - result.global_P_robot;
 
diff --git a/source/armarx/navigation/skills/GuideHumanToRoom.h b/source/armarx/navigation/skills/GuideHumanToRoom.h
index efe447c6..ea0f954d 100644
--- a/source/armarx/navigation/skills/GuideHumanToRoom.h
+++ b/source/armarx/navigation/skills/GuideHumanToRoom.h
@@ -56,6 +56,8 @@ namespace armarx::navigation::skills
 
             memory::client::costmap::Reader& costmapReader;
             memory::client::rooms::Reader& roomsReader;
+
+            viz::Client& arviz;
         };
 
         struct Properties
-- 
GitLab


From 38b2111226317e741daf15de9e2f12c52cc1f0ec Mon Sep 17 00:00:00 2001
From: Christoph Pohl <christoph.pohl@kit.edu>
Date: Sat, 4 Feb 2023 19:17:04 +0100
Subject: [PATCH 308/324] Add necessary library dependency for navigation_human

---
 source/armarx/navigation/human/CMakeLists.txt | 1 +
 1 file changed, 1 insertion(+)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 836826fb..4cbe0a27 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -11,6 +11,7 @@ armarx_add_library(teb_human
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
+        VisionX::armem_human
         ukfm # RobotAPI
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
-- 
GitLab


From f73b470bb194f0469cbfe8b23e4d50aa356fe883 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 6 Feb 2023 14:47:14 +0100
Subject: [PATCH 309/324] impl navigate to location inteface function

---
 .../config/ObjectMemory.cfg                   |  9 +++--
 .../config/example_client.cfg                 | 13 ++++---
 .../config/navigation_memory.cfg              | 13 ++++---
 .../PlatformNavigation/config/navigator.cfg   | 39 ++++++++++++-------
 source/armarx/navigation/client/Navigator.cpp | 14 +++++++
 source/armarx/navigation/client/Navigator.h   |  2 +
 .../client/ice/NavigatorInterface.ice         |  2 +
 .../client/services/IceNavigator.cpp          |  8 +++-
 .../navigation/client/services/IceNavigator.h |  6 ++-
 .../components/navigator/Component.cpp        | 13 +++++++
 .../components/navigator/Component.h          |  4 ++
 .../navigation/core/NavigatorInterface.h      |  2 +
 source/armarx/navigation/core/StaticScene.h   |  3 ++
 .../navigation/memory/client/graph/Reader.cpp |  4 +-
 source/armarx/navigation/server/Navigator.cpp | 30 ++++++++++----
 source/armarx/navigation/server/Navigator.h   |  5 ++-
 .../server/scene_provider/SceneProvider.cpp   |  6 ++-
 .../navigation/simulation/SimulatedHuman.cpp  |  2 +-
 .../navigation/skills/NavigateToLocation.cpp  |  8 ++--
 .../development/TestRotate90Degrees.xml       |  4 +-
 .../NavigationGroup/NavigateTo.xml            |  2 +-
 .../NavigationGroup/NavigateToLocation.cpp    |  6 +--
 22 files changed, 141 insertions(+), 54 deletions(-)

diff --git a/scenarios/NavigationSimulation/config/ObjectMemory.cfg b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
index 6811e284..5984b8da 100644
--- a/scenarios/NavigationSimulation/config/ObjectMemory.cfg
+++ b/scenarios/NavigationSimulation/config/ObjectMemory.cfg
@@ -391,9 +391,12 @@ ArmarX.ObjectMemory.MinimumLoggingLevel = Debug
 # ArmarX.ObjectMemory.mem.inst.scene.11_Directory = scenes
 
 
-# ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad:  Scene to load on startup (e.g. 'Scene_2021-06-24_20-20-03').
-# You can also specify paths relative to 'Package/scenes/'. 
-# You can also specify a ; separated list of scenes.
+# ArmarX.ObjectMemory.mem.inst.scene.12_SnapshotToLoad:  Scene(s) to load on startup. 
+# Specify multiple scenes in a ; separated list. 
+# Each entry must be one of the following: 
+# (1) A scene file in 'Package/scenes/' (with or without '.json' extension), e.g. 'MyScene', 'MyScene.json' 
+# (2) A path to a scene file relative to 'Package/scenes/' (with or without '.json' extension), e.g. 'path/to/MyScene', 'path/to/MyScene.json' 
+# (3) An ArmarX data path to a scene file, e.g. 'Package/scenes/path/to/MyScene.json'
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
diff --git a/scenarios/PlatformNavigation/config/example_client.cfg b/scenarios/PlatformNavigation/config/example_client.cfg
index 517f09d1..79693c7b 100644
--- a/scenarios/PlatformNavigation/config/example_client.cfg
+++ b/scenarios/PlatformNavigation/config/example_client.cfg
@@ -76,6 +76,14 @@
 # ArmarX.EnableProfiling = false
 
 
+# ArmarX.ExampleClient.nav.NavigatorName:  No Description
+#  Attributes:
+#  - Default:            navigator
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.ExampleClient.nav.NavigatorName = navigator
+
+
 # ArmarX.LoadLibraries:  Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
 #  Attributes:
 #  - Default:            ""
@@ -269,8 +277,3 @@ ArmarX.example_client.mode = standard
 # ArmarX.example_client.robotName = Armar6
 
 
-# ArmarX.ExampleClient.nav.NavigatorName:  
-#  Attributes:
-ArmarX.ExampleClient.nav.NavigatorName = navigator
-
-
diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg
index 74112627..37ca7194 100644
--- a/scenarios/PlatformNavigation/config/navigation_memory.cfg
+++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg
@@ -92,6 +92,14 @@
 # ArmarX.LoggingGroup = ""
 
 
+# ArmarX.NavigationMemory.p.snapshotToLoad:  No Description
+#  Attributes:
+#  - Default:            ./PriorKnowledgeData/navigation-graphs/R003
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003
+
+
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -288,8 +296,3 @@
 ArmarX.navigation_memory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003
 
 
-# ArmarX.NavigationMemory.p.snapshotToLoad:  
-#  Attributes:
-ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003
-
-
diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 2c22d247..549c2a6c 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -92,6 +92,30 @@
 # ArmarX.LoggingGroup = ""
 
 
+# ArmarX.Navigator.ObjectName:  No Description
+#  Attributes:
+#  - Default:            navigator
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.ObjectName = navigator
+
+
+# ArmarX.Navigator.RobotUnitName:  No Description
+#  Attributes:
+#  - Default:            Armar6Unit
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.RobotUnitName = Armar6Unit
+
+
+# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  No Description
+#  Attributes:
+#  - Default:            0.8
+#  - Case sensitivity:   no
+#  - Required:           no
+ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
+
+
 # ArmarX.RedirectStdout:  Redirect std::cout and std::cerr to ArmarXLog
 #  Attributes:
 #  - Default:            true
@@ -435,18 +459,3 @@ ArmarX.navigator.p.scene.robotName = Armar6
 # ArmarX.navigator.p.scene.staticCostmapProviderName = distance_to_obstacle_costmap_provider
 
 
-# ArmarX.Navigator.ObjectName:  
-#  Attributes:
-ArmarX.Navigator.ObjectName = navigator
-
-
-# ArmarX.Navigator.RobotUnitName:  
-#  Attributes:
-ArmarX.Navigator.RobotUnitName = Armar6Unit
-
-
-# ArmarX.Navigator.p.occupancy_grid.occopied_threshold:  
-#  Attributes:
-ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
-
-
diff --git a/source/armarx/navigation/client/Navigator.cpp b/source/armarx/navigation/client/Navigator.cpp
index a7c2a85e..442aac1d 100644
--- a/source/armarx/navigation/client/Navigator.cpp
+++ b/source/armarx/navigation/client/Navigator.cpp
@@ -95,6 +95,20 @@ namespace armarx::navigation::client
         }
         srv.navigator->moveTowards(direction, frame);
     }
+    
+    void Navigator::moveToLocation(const std::string& location)
+    {
+        ARMARX_TRACE;
+        ARMARX_CHECK_NOT_NULL(srv.navigator) << "Navigator service must not be null!";
+
+        {
+            // TODO: This still leads to a race condition, if extern a stop event is generated before moveTo but arrives
+            //  after the event is reset
+            std::scoped_lock const l{stoppedInfo.m};
+            stoppedInfo.event.reset();
+        }
+        srv.navigator->moveToLocation(location);
+    }
 
 
     void
diff --git a/source/armarx/navigation/client/Navigator.h b/source/armarx/navigation/client/Navigator.h
index 32af0bb9..8b84f955 100644
--- a/source/armarx/navigation/client/Navigator.h
+++ b/source/armarx/navigation/client/Navigator.h
@@ -132,6 +132,8 @@ namespace armarx::navigation::client
 
         void moveTowards(const core::Direction& direction, core::NavigationFrame frame);
 
+        void moveToLocation(const std::string& location);
+
         void update(const std::vector<core::Pose>& waypoints, core::NavigationFrame frame);
 
         void pause();
diff --git a/source/armarx/navigation/client/ice/NavigatorInterface.ice b/source/armarx/navigation/client/ice/NavigatorInterface.ice
index 806aa2d9..7f2a92d1 100644
--- a/source/armarx/navigation/client/ice/NavigatorInterface.ice
+++ b/source/armarx/navigation/client/ice/NavigatorInterface.ice
@@ -67,6 +67,8 @@ module armarx
 
                 void moveTo2(detail::Waypoints waypoints, string navigationFrame, string callerId);
 
+                void moveToLocation(string location, string callerId);
+
                 void updateMoveTo(Eigen::Matrix4fSeq waypoints, string navigationFrame, string callerId);
 
                 void
diff --git a/source/armarx/navigation/client/services/IceNavigator.cpp b/source/armarx/navigation/client/services/IceNavigator.cpp
index 3bae4a6d..b07cf6a1 100644
--- a/source/armarx/navigation/client/services/IceNavigator.cpp
+++ b/source/armarx/navigation/client/services/IceNavigator.cpp
@@ -67,9 +67,15 @@ namespace armarx::navigation::client
     {
         ARMARX_TRACE;
 
-        return navigator->moveTo2(
+        navigator->moveTo2(
             freeze(targets), core::NavigationFrameNames.to_name(navigationFrame), configId);
     }
+    
+    void IceNavigator::moveToLocation(const std::string& location)
+    {
+        ARMARX_TRACE;
+        navigator->moveToLocation(location, configId);
+    }
 
     void
     IceNavigator::moveTowards(const core::Direction& direction,
diff --git a/source/armarx/navigation/client/services/IceNavigator.h b/source/armarx/navigation/client/services/IceNavigator.h
index 783e77e7..f8cacfd7 100644
--- a/source/armarx/navigation/client/services/IceNavigator.h
+++ b/source/armarx/navigation/client/services/IceNavigator.h
@@ -3,12 +3,12 @@
 
 #include <string>
 
-#include <armarx/navigation/core/basic_types.h>
-#include <armarx/navigation/core/types.h>
 #include <armarx/navigation/client/NavigationStackConfig.h>
 #include <armarx/navigation/client/ice/NavigatorInterface.h>
 #include <armarx/navigation/client/ice_conversions.h>
 #include <armarx/navigation/core/NavigatorInterface.h>
+#include <armarx/navigation/core/basic_types.h>
+#include <armarx/navigation/core/types.h>
 
 
 namespace armarx::navigation::client
@@ -34,6 +34,8 @@ namespace armarx::navigation::client
         void moveTo(const std::vector<client::WaypointTarget>& targets,
                     core::NavigationFrame navigationFrame) override;
 
+        void moveToLocation(const std::string& location) override;
+
         void moveTowards(const core::Direction& direction,
                          core::NavigationFrame navigationFrame) override;
 
diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp
index 933c2f34..3943986f 100644
--- a/source/armarx/navigation/components/navigator/Component.cpp
+++ b/source/armarx/navigation/components/navigator/Component.cpp
@@ -363,6 +363,19 @@ namespace armarx::navigation::components::navigator
 
         navigators.at(callerId).moveTo(wps, core::NavigationFrameNames.from_name(navigationMode));
     }
+    
+    void Component::moveToLocation(const std::string& location,
+                         const std::string& callerId,
+                         const Ice::Current& c)
+    {
+        ARMARX_TRACE;
+        ARMARX_INFO << "MoveToLocation `" << location << "` requested by caller '" << callerId << "'";
+
+        ARMARX_CHECK(navigators.count(callerId) > 0)
+            << "Navigator config for caller `" << callerId << "` not registered!";
+
+        navigators.at(callerId).moveToLocation(location);
+    }
 
     void
     Component::moveTowards(const Eigen::Vector3f& direction,
diff --git a/source/armarx/navigation/components/navigator/Component.h b/source/armarx/navigation/components/navigator/Component.h
index e601f796..aac593f1 100644
--- a/source/armarx/navigation/components/navigator/Component.h
+++ b/source/armarx/navigation/components/navigator/Component.h
@@ -114,6 +114,10 @@ namespace armarx::navigation::components::navigator
                      const std::string& callerId,
                      const Ice::Current& c = Ice::emptyCurrent) override;
 
+        void moveToLocation(const std::string& location,
+                     const std::string& callerId,
+                     const Ice::Current& c = Ice::emptyCurrent) override;
+
         void updateMoveTo(const std::vector<Eigen::Matrix4f>& waypoints,
                     const std::string& navigationMode,
                     const std::string& callerId,
diff --git a/source/armarx/navigation/core/NavigatorInterface.h b/source/armarx/navigation/core/NavigatorInterface.h
index 18e50335..83d5d460 100644
--- a/source/armarx/navigation/core/NavigatorInterface.h
+++ b/source/armarx/navigation/core/NavigatorInterface.h
@@ -23,6 +23,8 @@ namespace armarx::navigation::core
         virtual void moveTo(const std::vector<client::WaypointTarget>& targets,
                             core::NavigationFrame navigationFrame) = 0;
 
+        virtual void moveToLocation(const std::string& location) = 0;
+
         virtual void update(const std::vector<core::Pose>& waypoints,
                             core::NavigationFrame navigationFrame) = 0;
 
diff --git a/source/armarx/navigation/core/StaticScene.h b/source/armarx/navigation/core/StaticScene.h
index 534b4345..e55d7e6f 100644
--- a/source/armarx/navigation/core/StaticScene.h
+++ b/source/armarx/navigation/core/StaticScene.h
@@ -23,9 +23,11 @@
 #pragma once
 
 #include <memory>
+#include <map>
 
 #include <VirtualRobot/VirtualRobot.h>
 
+#include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/algorithms/Costmap.h>
 
 namespace armarx::navigation::core
@@ -37,6 +39,7 @@ namespace armarx::navigation::core
 
         std::optional<algorithms::Costmap> distanceToObstaclesCostmap;
 
+        std::map<std::string, core::Pose> locations;
     };
 
 
diff --git a/source/armarx/navigation/memory/client/graph/Reader.cpp b/source/armarx/navigation/memory/client/graph/Reader.cpp
index 51a9b890..bb55fc7a 100644
--- a/source/armarx/navigation/memory/client/graph/Reader.cpp
+++ b/source/armarx/navigation/memory/client/graph/Reader.cpp
@@ -41,7 +41,9 @@ namespace armarx::navigation::memory::client::graph
         const auto locs = queryLocations();
         for (const auto& [id, location] : locs)
         {
-            locations.emplace(id.entityName, core::Pose(location.globalRobotPose));
+            const std::string locationName = id.providerSegmentName + "/" + id.entityName;
+            ARMARX_DEBUG << "Location: " << locationName;
+            locations.emplace(locationName, core::Pose(location.globalRobotPose));
         }
 
         return locations;
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index cbe67a10..1790dd58 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -2,6 +2,7 @@
 
 #include <algorithm>
 #include <chrono>
+#include <cmath>
 #include <cstddef>
 #include <optional>
 #include <thread>
@@ -12,6 +13,8 @@
 #include <boost/graph/subgraph.hpp>
 
 #include <Eigen/Geometry>
+#include <Eigen/src/Geometry/AngleAxis.h>
+#include <Eigen/src/Geometry/Translation.h>
 
 #include <SimoxUtility/math/convert/mat3f_to_rpy.h>
 #include <VirtualRobot/Robot.h>
@@ -23,7 +26,7 @@
 #include <ArmarXCore/core/time/Clock.h>
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
-#include <armarx/navigation/local_planning/LocalPlanner.h>
+#include "armarx/navigation/memory/client/graph/Reader.h"
 #include "range/v3/algorithm/reverse.hpp"
 #include "range/v3/range/conversion.hpp"
 #include <SemanticObjectRelations/Shapes/Shape.h>
@@ -36,6 +39,7 @@
 #include <armarx/navigation/core/events.h>
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
+#include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/server/GraphBuilder.h>
 #include <armarx/navigation/server/StackResult.h>
 #include <armarx/navigation/server/monitoring/GoalReachedMonitor.h>
@@ -157,12 +161,10 @@ namespace armarx::navigation::server
                 const core::Pose global_T_robot(srv.sceneProvider->scene().robot->getGlobalPose());
                 ARMARX_VERBOSE << "Initial robot pose: " << global_T_robot.matrix();
 
-                std::transform(
-                    std::begin(waypoints),
-                    std::end(waypoints),
-                    std::back_inserter(globalWaypoints),
-                    [&](const core::Pose& p)
-                    { return global_T_robot * p; });
+                std::transform(std::begin(waypoints),
+                               std::end(waypoints),
+                               std::back_inserter(globalWaypoints),
+                               [&](const core::Pose& p) { return global_T_robot * p; });
                 break;
         }
 
@@ -793,6 +795,20 @@ namespace armarx::navigation::server
     {
     }
 
+    void
+    Navigator::moveToLocation(const std::string& location)
+    {
+        const auto resolveLocation = [&](const std::string& location)
+        {
+            const auto locations = srv.sceneProvider->scene().staticScene->locations;
+            ARMARX_CHECK(locations.count(location) > 0) << "Unknown location `" << location << "`.";
+            return locations.at(location);
+        };
+
+        const core::Pose global_T_location = resolveLocation(location);
+        moveToAbsolute({global_T_location});
+    }
+
     void
     Navigator::moveTowardsAbsolute(const core::Direction& direction)
     {
diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index f4c0fb10..68040290 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -102,6 +102,8 @@ namespace armarx::navigation::server
         void moveTowards(const core::Direction& direction,
                          core::NavigationFrame navigationFrame) override;
 
+        void moveToLocation(const std::string& location) override;
+
         void pause() override;
 
         void resume() override;
@@ -145,7 +147,8 @@ namespace armarx::navigation::server
         void setGraphEdgeCosts(core::Graph& graph) const;
         GraphBuilder convertToGraph(const std::vector<client::WaypointTarget>& targets) const;
 
-        bool hasLocalPlanner() const noexcept
+        bool
+        hasLocalPlanner() const noexcept
         {
             return config.stack.localPlanner != nullptr;
         }
diff --git a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
index 954b5d83..f97c3859 100644
--- a/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
+++ b/source/armarx/navigation/server/scene_provider/SceneProvider.cpp
@@ -39,7 +39,7 @@ namespace armarx::navigation::server::scene_provider
         scn.robot = srv.virtualRobotReader->getRobot(
             config.robotName, timestamp, VirtualRobot::RobotIO::RobotDescription::eCollisionModel);
         scn.robot->setPrimitiveApproximationModel({"navigation"});
-        
+
         ARMARX_CHECK_NOT_NULL(scn.robot);
 
         scn.staticScene.emplace(getStaticScene(timestamp));
@@ -114,9 +114,11 @@ namespace armarx::navigation::server::scene_provider
             }
         }();
 
+        const auto locations = srv.graphReader->locations();
+
         ARMARX_INFO << "Retrieved static costmap";
 
-        return {.objects = objects, .distanceToObstaclesCostmap = costmap};
+        return {.objects = objects, .distanceToObstaclesCostmap = costmap, .locations = locations};
     }
 
     core::DynamicScene
diff --git a/source/armarx/navigation/simulation/SimulatedHuman.cpp b/source/armarx/navigation/simulation/SimulatedHuman.cpp
index 880fdf0d..452d2420 100644
--- a/source/armarx/navigation/simulation/SimulatedHuman.cpp
+++ b/source/armarx/navigation/simulation/SimulatedHuman.cpp
@@ -108,7 +108,7 @@ namespace armarx::navigation::human::simulation
 
         core::Scene scene;
 
-        scene.staticScene.emplace(core::StaticScene{nullptr, std::nullopt});
+        scene.staticScene.emplace(core::StaticScene{nullptr, std::nullopt, {}});
         scene.staticScene->distanceToObstaclesCostmap.emplace(distanceField_);
 
         global_planning::SPFA planner(params, scene);
diff --git a/source/armarx/navigation/skills/NavigateToLocation.cpp b/source/armarx/navigation/skills/NavigateToLocation.cpp
index d617d492..d9464ab2 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.cpp
+++ b/source/armarx/navigation/skills/NavigateToLocation.cpp
@@ -58,17 +58,17 @@ namespace armarx::navigation::skills
     ::armarx::skills::Skill::MainResult
     NavigateToLocation::main(const Base::SpecializedMainInput& in)
     {
-        const std::string location = in.params.location;
+        const std::string& location = in.params.location;
 
         ARMARX_INFO << "moving to target " << VAROUT(location);
 
         // execute
         ARMARX_INFO << "Sending navigation request";
 
-        client::PathBuilder builder;
-        builder.add(location, client::GlobalPlanningStrategy::Free);
+        // client::PathBuilder builder;
+        // builder.add(location, client::GlobalPlanningStrategy::Free);
 
-        navigator->moveTo(builder, core::NavigationFrame::Absolute);
+        navigator->moveToLocation(location);
 
         // Wait until goal is reached
         ARMARX_INFO << "Waiting until goal is reached.";
diff --git a/source/armarx/navigation/statecharts/NavigationCommands/development/TestRotate90Degrees.xml b/source/armarx/navigation/statecharts/NavigationCommands/development/TestRotate90Degrees.xml
index abe10729..c1417dbd 100644
--- a/source/armarx/navigation/statecharts/NavigationCommands/development/TestRotate90Degrees.xml
+++ b/source/armarx/navigation/statecharts/NavigationCommands/development/TestRotate90Degrees.xml
@@ -4,9 +4,9 @@
 	<OutputParameters/>
 	<LocalParameters/>
 	<Substates>
-		<EndState name="Failure" event="Failure" left="363.333" top="140" boundingSquareSize="99.6636"/>
+		<EndState name="Failure" event="Failure" left="363.167" top="140" boundingSquareSize="99.6636"/>
 		<LocalState name="RotateXDegrees" refuuid="70E5C859-AC39-4B85-9981-6D0615DEAB13" left="114.167" top="195.917" boundingSquareSize="99.6636"/>
-		<EndState name="Success" event="Success" left="363.333" top="252.139" boundingSquareSize="99.6636"/>
+		<EndState name="Success" event="Success" left="363.167" top="252.139" boundingSquareSize="99.6636"/>
 	</Substates>
 	<Events>
 		<Event name="Failure">
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.xml b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.xml
index 2cd2476b..ca00d381 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.xml
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateTo.xml
@@ -2,7 +2,7 @@
 <State version="1.2" name="NavigateTo" uuid="BCF0FD77-35EE-4916-ADC1-4C7D05B502EB" width="800" height="600" type="Normal State">
 	<InputParameters>
 		<Parameter name="TargetPosition" type="::armarx::Vector3Base" docType="Vector3" optional="no">
-			<DefaultValue value='{"type":"::armarx::SingleVariantBase","variant":{"typeName":"::armarx::Vector3Base","value":{"x":1200,"y":2000,"z":0}}}' docValue="1200\n2000\n0"/>
+			<DefaultValue value='{"type":"::armarx::SingleVariantBase","variant":{"typeName":"::armarx::Vector3Base","value":{"x":2000,"y":2000,"z":0}}}' docValue="2000\n2000\n0"/>
 		</Parameter>
 	</InputParameters>
 	<OutputParameters/>
diff --git a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
index 3c11ba01..ca748edc 100644
--- a/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
+++ b/source/armarx/navigation/statecharts/NavigationGroup/NavigateToLocation.cpp
@@ -83,13 +83,11 @@ namespace armarx::navigation::statecharts::navigation_group
         client::Navigator navigator{client::Navigator::InjectedServices{
             .navigator = &iceNavigator, .subscriber = &memoryEventPolling}};
 
-        // assemble the path, which might consist of waypoints and a goal (the goal is just the last `waypoint`)
-        client::PathBuilder builder;
-        builder.add(in.getlocation(), client::GlobalPlanningStrategy::Point2Point);
+        ARMARX_CHECK_NOT_EMPTY(in.getlocation());
 
         // execute
         ARMARX_INFO << "Sending navigation request";
-        navigator.moveTo(builder, core::NavigationFrame::Absolute);
+        navigator.moveToLocation(in.getlocation());
 
         // Wait until goal is reached
         ARMARX_INFO << "Waiting until goal is reached.";
-- 
GitLab


From 2d6a7cc748935a10fb248dc1c6548731f6ecd53a Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 6 Feb 2023 14:47:20 +0100
Subject: [PATCH 310/324] fix. navigate to room

---
 source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
index 9060192a..666aa7ec 100644
--- a/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
+++ b/source/armarx/navigation/rooms/RoomNavigationTargetCreator.cpp
@@ -63,7 +63,7 @@ namespace armarx::navigation::rooms
                 // invalid outside of the room
                 const bool isInside = room.isInside(pos3d);
 
-                roomCostmap.getMutableMask().value()(x, y) *= isInside;
+                roomCostmap.getMutableMask().value()(x, y) &= isInside;
                 roomCostmap.getMutableGrid()(x, y) *= static_cast<float>(isInside);
             }
         }
-- 
GitLab


From 07bb875240d371b8a6c7ed8baf723d3b5ca21638 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Mon, 6 Feb 2023 14:53:54 +0100
Subject: [PATCH 311/324] fix: VisionX is a legacy CMake package

---
 source/armarx/navigation/human/CMakeLists.txt | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 4cbe0a27..3dd0f11d 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -11,7 +11,7 @@ armarx_add_library(teb_human
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
-        VisionX::armem_human
+        armem_human # VisionX
         ukfm # RobotAPI
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
-- 
GitLab


From 42af217b14b1b97e64c61f72554341acf2366bd8 Mon Sep 17 00:00:00 2001
From: Christoph Pohl <christoph.pohl@kit.edu>
Date: Mon, 6 Feb 2023 15:06:39 +0100
Subject: [PATCH 312/324] remove wrong alias target for VisionX::armem_human

---
 source/armarx/navigation/human/CMakeLists.txt | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/human/CMakeLists.txt b/source/armarx/navigation/human/CMakeLists.txt
index 4cbe0a27..559fec1c 100644
--- a/source/armarx/navigation/human/CMakeLists.txt
+++ b/source/armarx/navigation/human/CMakeLists.txt
@@ -11,7 +11,7 @@ armarx_add_library(teb_human
         ArmarXCore
         armarx_navigation::core
         armarx_navigation::conversions
-        VisionX::armem_human
+        armem_human #VisionX
         ukfm # RobotAPI
     DEPENDENCIES_PRIVATE
         range-v3::range-v3
-- 
GitLab


From 2388ad94c5bb9e66e1e3e67bfee9d225a6045aeb Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Wed, 8 Feb 2023 17:07:18 +0100
Subject: [PATCH 313/324] cleanup / fix. removing definition

---
 .../navigation/local_planning/TimedElasticBands.h   | 13 +------------
 1 file changed, 1 insertion(+), 12 deletions(-)

diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.h b/source/armarx/navigation/local_planning/TimedElasticBands.h
index a9af1628..42045239 100644
--- a/source/armarx/navigation/local_planning/TimedElasticBands.h
+++ b/source/armarx/navigation/local_planning/TimedElasticBands.h
@@ -28,24 +28,13 @@
 #include <armarx/navigation/core/Trajectory.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
 #include <armarx/navigation/local_planning/TebObstacleManager.h>
-#include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
+#include <armarx/navigation/local_planning/TimedElasticBandsParams.h>
 #include <armarx/navigation/local_planning/core.h>
 #include <teb_local_planner/homotopy_class_planner.h>
 #include <teb_local_planner/teb_config.h>
 
 namespace armarx::navigation::local_planning
 {
-    // TODO(SALt): Implement
-
-    struct TimedElasticBandsParams : public LocalPlannerParams
-    {
-        arondto::TimedElasticBandsParams cfg;
-
-        Algorithms algorithm() const override;
-        aron::data::DictPtr toAron() const override;
-        static TimedElasticBandsParams FromAron(const aron::data::DictPtr& dict);
-    };
-
     class TimedElasticBands : virtual public LocalPlanner
     {
     public:
-- 
GitLab


From 6c411ef7ef265d670b7e3a1c381be12069281a8b Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:33:07 +0100
Subject: [PATCH 314/324] platform controller executor: adding option to
 activate controller

---
 .../server/execution/ExecutorInterface.h      |   3 +-
 .../execution/PlatformControllerExecutor.cpp  | 100 +++++++++++++++---
 .../execution/PlatformControllerExecutor.h    |  20 +++-
 3 files changed, 103 insertions(+), 20 deletions(-)

diff --git a/source/armarx/navigation/server/execution/ExecutorInterface.h b/source/armarx/navigation/server/execution/ExecutorInterface.h
index 25a2462b..6e9d4fee 100644
--- a/source/armarx/navigation/server/execution/ExecutorInterface.h
+++ b/source/armarx/navigation/server/execution/ExecutorInterface.h
@@ -14,7 +14,8 @@ namespace armarx::navigation::server
     public:
         virtual ~ExecutorInterface() = default;
 
-        virtual void execute(const core::LocalTrajectory& trajectory) = 0;
+        virtual void execute(const core::LocalTrajectory& trajectory, bool activateController = false) = 0;
+        virtual void execute(const core::GlobalTrajectory& trajectory, bool activateController = false) = 0;
 
         virtual void start() = 0;
         virtual void stop() = 0;
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index e7bb44d8..6ec13645 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -6,6 +6,7 @@
 #include <armarx/control/client/ComponentPlugin.h>
 #include <armarx/control/common/type.h>
 #include <armarx/control/memory/config/util.h>
+
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/core/aron_conversions.h>
 #include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
@@ -20,7 +21,7 @@ namespace armarx::navigation::server
 
     PlatformControllerExecutor::PlatformControllerExecutor(
         ControllerComponentPlugin& controllerComponentPlugin) :
-        controllerPlugin(controllerComponentPlugin)
+        controllerPlugin_(controllerComponentPlugin)
     {
         ARMARX_TRACE;
         controllerComponentPlugin.getRobotUnitPlugin().getRobotUnit()->loadLibFromPackage(
@@ -38,14 +39,13 @@ namespace armarx::navigation::server
             // "" /*configBasePath*/, controllerComponentPlugin.configMemoryWriter());
 
             ARMARX_TRACE;
-            ARMARX_INFO << "asdlfasfdlh";
         }
 
         // initialize controller
-        ARMARX_INFO << "Initializing controller";
+        ARMARX_INFO << "Initializing local trajectory controller";
         {
             ARMARX_TRACE;
-            auto builder = controllerPlugin.createControllerBuilder<
+            auto builder = controllerPlugin_.createControllerBuilder<
                 armarx::navigation::common::ControllerType::PlatformLocalTrajectory>();
 
             ARMARX_TRACE;
@@ -59,11 +59,31 @@ namespace armarx::navigation::server
 
             ARMARX_TRACE;
             ARMARX_CHECK(ctrlWrapper.has_value());
-            ctrl.emplace(std::move(ctrlWrapper.value()));
+            localTrajCtrl_.emplace(std::move(ctrlWrapper.value()));
+        }
+
+        ARMARX_INFO << "Initializing global trajectory controller";
+        {
+            ARMARX_TRACE;
+            auto builder = controllerPlugin_.createControllerBuilder<
+                armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>();
+
+            ARMARX_TRACE;
+
+            const armarx::PackagePath configPath("armarx_navigation",
+                                                 "controller_config/GlobalTrajectory/default.json");
+
+            auto ctrlWrapper = builder.withNodeSet("PlatformPlanning")
+                                   .withConfig(configPath.toSystemPath())
+                                   .create();
+
+            ARMARX_TRACE;
+            ARMARX_CHECK(ctrlWrapper.has_value());
+            globalTrajCtrl_.emplace(std::move(ctrlWrapper.value()));
         }
 
         ARMARX_TRACE;
-        ARMARX_CHECK(ctrl.has_value());
+        ARMARX_CHECK(localTrajCtrl_.has_value());
         ARMARX_INFO << "PlatformControllerExecutor: init done.";
     }
 
@@ -71,32 +91,80 @@ namespace armarx::navigation::server
 
 
     void
-    PlatformControllerExecutor::execute(const core::LocalTrajectory& trajectory)
+    PlatformControllerExecutor::execute(const core::LocalTrajectory& trajectory, const bool activateController)
     {
-        ARMARX_INFO << "Received trajectory for execution with " << trajectory.points().size()
-                    << " points";
+        ARMARX_VERBOSE << "Received trajectory for execution with " << trajectory.points().size()
+                       << " points";
 
-        toAron(ctrl->config.targets.trajectory, trajectory);
+        toAron(localTrajCtrl_->config.targets.trajectory, trajectory);
 
         // sends the updated config to the controller and stores it in the memory
-        ctrl->updateConfig();
+        localTrajCtrl_->updateConfig();
 
-        if(not ctrl->ctrl()->isControllerActive())
+        if (activateController and not localTrajCtrl_->ctrl()->isControllerActive())
         {
-            start();
+            localTrajCtrl_->activate();
         }
     }
 
+    void
+    PlatformControllerExecutor::execute(const core::GlobalTrajectory& trajectory, const bool activateController)
+    {
+        ARMARX_VERBOSE << "Received trajectory for execution with " << trajectory.points().size()
+                       << " points";
+
+        toAron(globalTrajCtrl_->config.targets.trajectory, trajectory);
+
+        ARMARX_INFO << "Sending trajectory with "
+                    << globalTrajCtrl_->config.targets.trajectory.points.size()
+                    << " to controller.";
+
+        // sends the updated config to the controller and stores it in the memory
+        globalTrajCtrl_->updateConfig();
+
+        if (activateController and not globalTrajCtrl_->ctrl()->isControllerActive())
+        {
+            globalTrajCtrl_->activate();
+        }
+    }
+
+
     void
     PlatformControllerExecutor::start()
     {
-        // TODO check whether the controller must be resetted (trajectory)
-        ctrl->activate();
+        switch (lastActiveController_)
+        {
+            case ControllerType::GlobalTrajectory:
+                if (globalTrajCtrl_.has_value())
+                {
+                    globalTrajCtrl_->activate();
+                }
+            case ControllerType::LocalTrajectory:
+                if (localTrajCtrl_.has_value())
+                {
+                    localTrajCtrl_->activate();
+                }
+            case ControllerType::None:
+                ARMARX_INFO << "No last active controller.";
+                break;
+        }
     }
 
     void
     PlatformControllerExecutor::stop()
     {
-        ctrl->deactivate();
+        lastActiveController_ = ControllerType::None;
+
+        if (localTrajCtrl_->ctrl()->isControllerActive())
+        {
+            localTrajCtrl_->deactivate();
+            lastActiveController_ = ControllerType::LocalTrajectory;
+        }
+
+        if (globalTrajCtrl_->ctrl()->isControllerActive())
+        {
+            globalTrajCtrl_->deactivate();
+            lastActiveController_ = ControllerType::GlobalTrajectory;
+        }
     }
 } // namespace armarx::navigation::server
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
index 2e5fe975..90888900 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
@@ -31,7 +31,8 @@ namespace armarx::navigation::server
         PlatformControllerExecutor(ControllerComponentPlugin& controllerComponentPlugin);
         ~PlatformControllerExecutor() override;
 
-        void execute(const core::LocalTrajectory& trajectory) override;
+        void execute(const core::LocalTrajectory& trajectory, bool activateController = false) override;
+        void execute(const core::GlobalTrajectory& trajectory, bool activateController = false) override;
 
         void start() override;
         void stop() override;
@@ -39,9 +40,22 @@ namespace armarx::navigation::server
     private:
         std::optional<armarx::control::client::ControllerWrapper<
             armarx::navigation::common::ControllerType::PlatformLocalTrajectory>>
-            ctrl;
+            localTrajCtrl_;
 
-        ControllerComponentPlugin& controllerPlugin;
+        std::optional<armarx::control::client::ControllerWrapper<
+            armarx::navigation::common::ControllerType::PlatformGlobalTrajectory>>
+            globalTrajCtrl_;
+
+        ControllerComponentPlugin& controllerPlugin_;
+
+        enum class ControllerType
+        {
+            GlobalTrajectory,
+            LocalTrajectory,
+            None
+        };
+
+        ControllerType lastActiveController_ = ControllerType::None;
     };
 
 } // namespace armarx::navigation::server
-- 
GitLab


From 4fc44c6aecfa15af9f3787defcb381506ca7efd3 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:34:06 +0100
Subject: [PATCH 315/324] navigator: updateExecutor for both local and global
 trajectory

---
 source/armarx/navigation/server/Navigator.cpp | 48 +++++++++++++++++--
 source/armarx/navigation/server/Navigator.h   |  1 +
 2 files changed, 45 insertions(+), 4 deletions(-)

diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 1790dd58..82722a94 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -660,14 +660,14 @@ namespace armarx::navigation::server
 
         ARMARX_TRACE;
 
-        ARMARX_INFO << "Planning local trajectory enabled";
+        ARMARX_INFO << "Starting stack.";
 
         // FIXME instead of PeriodicTask, use RunningTask.
         runningTask = new PeriodicTask<Navigator>(this,
                                                   &Navigator::run,
                                                   config.general.tasks.replanningUpdatePeriod,
                                                   false,
-                                                  "LocalPlannerTask");
+                                                  "PeriodicTask");
         runningTask->start();
 
 
@@ -738,7 +738,11 @@ namespace armarx::navigation::server
         ARMARX_TRACE;
         srv.publisher->globalTrajectoryUpdated(globalPlan.value());
         srv.introspector->onGlobalPlannerResult(globalPlan.value());
-        // srv.executor->execute(globalPlan->trajectory);
+
+        if(not hasLocalPlanner())
+        {
+            updateExecutor(globalPlan.value());
+        }
 
         ARMARX_INFO << "Global planning completed. Will now start all required threads";
         ARMARX_TRACE;
@@ -887,6 +891,11 @@ namespace armarx::navigation::server
                     ARMARX_TRACE;
                     srv.publisher->globalTrajectoryUpdated(globalPlan.value());
                     srv.introspector->onGlobalPlannerResult(globalPlan.value());
+
+                    if(not hasLocalPlanner())
+                    {
+                        updateExecutor(globalPlan.value());
+                    }
                 }
             }
         }
@@ -939,6 +948,8 @@ namespace armarx::navigation::server
     {
         ARMARX_CHECK(hasLocalPlanner());
 
+        ARMARX_VERBOSE << "Updating local plan";
+
         try
         {
             localPlan = config.stack.localPlanner->plan(globalPlan->trajectory);
@@ -1002,7 +1013,36 @@ namespace armarx::navigation::server
         // ARMARX_VERBOSE << deactivateSpam(1) << "velocity in robot frame "
         //                << robotFrameVelocity.linear;
 
-        srv.executor->execute(localPlan->trajectory);
+        srv.executor->execute(localPlan->trajectory, true);
+    }
+
+    void
+    Navigator::updateExecutor(const std::optional<global_planning::GlobalPlannerResult>& globalPlan)
+    {
+        if (srv.executor == nullptr)
+        {
+            return;
+        }
+
+        ARMARX_IMPORTANT << "Requested to execute global plan with " << globalPlan->trajectory.points().size() << " points.";
+
+
+        // if (isPaused() or isStopped())
+        // {
+        //     // [[unlikely]]
+        //     ARMARX_VERBOSE << deactivateSpam(1) << "stopped or paused";
+        //     return;
+        // }
+
+        if (not globalPlan.has_value())
+        {
+            ARMARX_INFO << "Global plan is invalid!";
+            srv.executor->stop();
+            return;
+        }
+
+        ARMARX_IMPORTANT << "Executing global plan with " << globalPlan->trajectory.points().size() << " points.";
+        srv.executor->execute(globalPlan->trajectory, true); // fixme replace true by isPaused()
     }
 
     void
diff --git a/source/armarx/navigation/server/Navigator.h b/source/armarx/navigation/server/Navigator.h
index 68040290..82305e8a 100644
--- a/source/armarx/navigation/server/Navigator.h
+++ b/source/armarx/navigation/server/Navigator.h
@@ -132,6 +132,7 @@ namespace armarx::navigation::server
 
         std::optional<local_planning::LocalPlannerResult> updateLocalPlanner();
         void updateExecutor(const std::optional<local_planning::LocalPlannerResult>& localPlan);
+        void updateExecutor(const std::optional<global_planning::GlobalPlannerResult>& localPlan);
         void updateIntrospector(const std::optional<local_planning::LocalPlannerResult>& localPlan);
 
         void updateMonitor();
-- 
GitLab


From 615eab6ba898eb480b485d17a0593fb2291afa99 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:34:30 +0100
Subject: [PATCH 316/324] aron_conversion: now independent of skills::control
 impl

---
 .../platform_controller/aron_conversions.cpp  |  1 -
 .../platform_controller/aron_conversions.h    | 22 +++++++++++++++++++
 2 files changed, 22 insertions(+), 1 deletion(-)

diff --git a/source/armarx/navigation/platform_controller/aron_conversions.cpp b/source/armarx/navigation/platform_controller/aron_conversions.cpp
index f3245428..87d6dc9d 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.cpp
+++ b/source/armarx/navigation/platform_controller/aron_conversions.cpp
@@ -23,7 +23,6 @@
 
 #include <RobotAPI/libraries/aron/common/aron_conversions/eigen.h>
 
-#include <armarx/control/common/aron_conversions.h>
 #include <armarx/navigation/core/aron_conversions.h>
 #include <armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.h>
 #include <armarx/navigation/platform_controller/PlatformLocalTrajectoryController.h>
diff --git a/source/armarx/navigation/platform_controller/aron_conversions.h b/source/armarx/navigation/platform_controller/aron_conversions.h
index 4e158dc1..35682c9d 100644
--- a/source/armarx/navigation/platform_controller/aron_conversions.h
+++ b/source/armarx/navigation/platform_controller/aron_conversions.h
@@ -21,6 +21,28 @@
 
 #pragma once
 
+#include <RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedClass.h>
+
+
+namespace armarx
+{
+    template <typename AronType, typename T>
+    T
+    fromAron(const ::armarx::aron::data::dto::DictPtr& dto)
+    {
+        static_assert(
+            std::is_base_of<armarx::aron::codegenerator::cpp::AronGeneratedClass, AronType>::value,
+            "AronType must be an ARON generated type");
+
+        const auto dtoConfig = AronType::FromAron(dto);
+
+        T config;
+        fromAron(dtoConfig, config);
+
+        return config;
+    }
+} // namespace armarx
+
 
 namespace armarx::navigation::platform_controller
 {
-- 
GitLab


From fde7a21600eb064cde16d52d01510369918a66a9 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:36:02 +0100
Subject: [PATCH 317/324] removing outdated includes

---
 .../platform_controller/PlatformGlobalTrajectoryController.cpp  | 2 --
 .../platform_controller/PlatformLocalTrajectoryController.cpp   | 1 -
 2 files changed, 3 deletions(-)

diff --git a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
index 3e46aa55..7ad11344 100644
--- a/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
+++ b/source/armarx/navigation/platform_controller/PlatformGlobalTrajectoryController.cpp
@@ -7,9 +7,7 @@
 #include "RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h"
 #include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTargetHolonomicPlatformVelocity.h>
 
-#include <armarx/control/common/aron_conversions.h>
 #include <armarx/control/common/type.h>
-// #include <armarx/control/common/utils.h>
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/platform_controller/aron/PlatformGlobalTrajectoryControllerConfig.aron.generated.h>
 #include <armarx/navigation/platform_controller/aron_conversions.h>
diff --git a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
index c27f2f23..e1ce20cb 100644
--- a/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
+++ b/source/armarx/navigation/platform_controller/PlatformLocalTrajectoryController.cpp
@@ -7,7 +7,6 @@
 #include "RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h"
 #include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTargetHolonomicPlatformVelocity.h>
 
-#include <armarx/control/common/aron_conversions.h>
 #include <armarx/control/common/type.h>
 #include <armarx/navigation/common/controller_types.h>
 #include <armarx/navigation/platform_controller/aron/PlatformLocalTrajectoryControllerConfig.aron.generated.h>
-- 
GitLab


From 716cda95c1c8483e104ef036c5e50c086687ecb6 Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:36:20 +0100
Subject: [PATCH 318/324] new config for global traj controller

---
 .../GlobalTrajectory/default.json             | 23 +++++++++++++++++++
 1 file changed, 23 insertions(+)
 create mode 100644 data/armarx_navigation/controller_config/GlobalTrajectory/default.json

diff --git a/data/armarx_navigation/controller_config/GlobalTrajectory/default.json b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
new file mode 100644
index 00000000..e69bb829
--- /dev/null
+++ b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
@@ -0,0 +1,23 @@
+{
+  "params": {
+    "pidPos": {
+      "Kp": 0.1,
+      "Ki": 0,
+      "Kd": 0
+    },
+    "pidOri": {
+      "Kp": 0.1,
+      "Ki": 0,
+      "Kd": 0
+    },
+    "limits": {
+      "linear": 500,
+      "angular": 0.5
+    }
+  },
+  "targets": {
+    "trajectory": {
+      "points": []
+    }
+  }
+}
-- 
GitLab


From 8f8ae1cd4095585b1856f05049191bb7b70c5bcf Mon Sep 17 00:00:00 2001
From: Fabian Reister <fabian.reister@kit.edu>
Date: Thu, 9 Feb 2023 10:37:04 +0100
Subject: [PATCH 319/324] minor

---
 scenarios/PlatformNavigation/config/navigator.cfg | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg
index 549c2a6c..51a93adb 100644
--- a/scenarios/PlatformNavigation/config/navigator.cfg
+++ b/scenarios/PlatformNavigation/config/navigator.cfg
@@ -181,7 +181,7 @@ ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
-ArmarX.Verbosity = Verbose
+# ArmarX.Verbosity = Info
 
 
 # ArmarX.navigator.ArVizStorageName:  Name of the ArViz storage
-- 
GitLab


From 8b76729d2d973b20538cc69d2ab02b51983e1131 Mon Sep 17 00:00:00 2001
From: armar-user <armar6@kit>
Date: Tue, 14 Feb 2023 17:08:30 +0100
Subject: [PATCH 320/324] OrientationOptimizer param update

---
 .../global_planning/optimization/OrientationOptimizer.h         | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
index 46434a42..c9957091 100644
--- a/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
+++ b/source/armarx/navigation/global_planning/optimization/OrientationOptimizer.h
@@ -30,7 +30,7 @@ namespace armarx::navigation::global_planning::optimization
 
     struct OrientationOptimizerParams
     {
-        float priorWeight{0.25F};
+        float priorWeight{0.5F};
         float smoothnessWeight{0.4F};
         float smoothnessWeightStartGoal{1.F};
 
-- 
GitLab


From 225650e09ae1291e16fd6870543a1b3601f41182 Mon Sep 17 00:00:00 2001
From: armar-user <armar6@kit>
Date: Tue, 14 Feb 2023 17:08:54 +0100
Subject: [PATCH 321/324] control param update

---
 .../controller_config/GlobalTrajectory/default.json       | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/data/armarx_navigation/controller_config/GlobalTrajectory/default.json b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
index e69bb829..efe7edc7 100644
--- a/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
+++ b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
@@ -1,18 +1,18 @@
 {
   "params": {
     "pidPos": {
-      "Kp": 0.1,
+      "Kp": 25,
       "Ki": 0,
       "Kd": 0
     },
     "pidOri": {
-      "Kp": 0.1,
+      "Kp": 50,
       "Ki": 0,
       "Kd": 0
     },
     "limits": {
-      "linear": 500,
-      "angular": 0.5
+      "linear": 200,
+      "angular": 0.3
     }
   },
   "targets": {
-- 
GitLab


From c4331b1dde49bbb4e45adf12de554ab6ec69eec1 Mon Sep 17 00:00:00 2001
From: armar-user <armar6@kit>
Date: Tue, 14 Feb 2023 17:33:30 +0100
Subject: [PATCH 322/324] introspector update

---
 .../client/services/MemorySubscriber.cpp      | 40 ++-----------------
 .../client/services/MemorySubscriber.h        |  3 +-
 source/armarx/navigation/server/Navigator.cpp | 23 ++++++++++-
 .../server/execution/ExecutorInterface.h      | 11 ++++-
 .../execution/PlatformControllerExecutor.cpp  | 11 +++--
 .../execution/PlatformControllerExecutor.h    | 11 ++---
 .../introspection/ArvizIntrospector.cpp       | 29 +++++++++++++-
 .../server/introspection/ArvizIntrospector.h  |  7 ++++
 .../introspection/IntrospectorInterface.h     |  2 +
 .../server/introspection/MemoryIntrospector.h |  2 +
 .../navigation/skills/NavigateToLocation.cpp  |  4 ++
 11 files changed, 91 insertions(+), 52 deletions(-)

diff --git a/source/armarx/navigation/client/services/MemorySubscriber.cpp b/source/armarx/navigation/client/services/MemorySubscriber.cpp
index ed515f00..8f081601 100644
--- a/source/armarx/navigation/client/services/MemorySubscriber.cpp
+++ b/source/armarx/navigation/client/services/MemorySubscriber.cpp
@@ -34,7 +34,6 @@ namespace armarx::navigation::client
                     << ".";
 
         // subscription api
-        armem::MemoryID subscriptionID;
         subscriptionID.memoryName = memoryName;
         subscriptionID.coreSegmentName = "Events";
         subscriptionID.providerSegmentName = callerId;
@@ -153,46 +152,15 @@ namespace armarx::navigation::client
 
     MemorySubscriber::~MemorySubscriber()
     {
-        ARMARX_INFO << "Stopping event polling";
-        task->stop();
-        ARMARX_INFO << "done.";
-    }
-
+        // ARMARX_INFO << "Removing event subscription";
 
-    void
-    MemorySubscriber::runPollMemoryEvents()
-    {
         ARMARX_TRACE;
+        // memoryNameSystem.unsubscribe(subscriptionID, this, &MemorySubscriber::onEntityUpdate);
 
-        const armem::Time now = armem::Time::Now();
-
-        armem::client::query::Builder qb;
-        // clang-format off
-        qb
-        .coreSegments().withName("Events")
-        .providerSegments().withName(callerId)
-        .entities().all()
-        .snapshots().timeRange(lastMemoryPoll, now);
-        // clang-format on
-
-        // ARMARX_DEBUG << "Polling memory events in interval "
-        //              << "[" << lastMemoryPoll << ", " << now << "]";
-
-        lastMemoryPoll = now;
-
-        const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
-
-        // ARMARX_DEBUG << "Lookup result in reader: " << qResult;
-
-        if (not qResult.success) /* c++20 [[unlikely]] */
-        {
-            ARMARX_WARNING << deactivateSpam(0.1F) << "Memory lookup failed.";
-            return;
-        }
-
-        handleEvents(qResult.memory);
+        ARMARX_INFO << "done.";
     }
 
+
     void
     MemorySubscriber::handleEvents(const armem::wm::Memory& memory)
     {
diff --git a/source/armarx/navigation/client/services/MemorySubscriber.h b/source/armarx/navigation/client/services/MemorySubscriber.h
index a356cbbe..1876bce9 100644
--- a/source/armarx/navigation/client/services/MemorySubscriber.h
+++ b/source/armarx/navigation/client/services/MemorySubscriber.h
@@ -35,7 +35,6 @@ namespace armarx::navigation::client
 
 
     protected:
-        void runPollMemoryEvents();
         void handleEvents(const armem::wm::Memory& memory);
 
 
@@ -51,7 +50,7 @@ namespace armarx::navigation::client
 
         std::mutex eventHandlingMtx;
 
-        armarx::PeriodicTask<MemorySubscriber>::pointer_type task;
+        armem::MemoryID subscriptionID;
     };
 
 } // namespace armarx::navigation::client
diff --git a/source/armarx/navigation/server/Navigator.cpp b/source/armarx/navigation/server/Navigator.cpp
index 82722a94..17eb7d47 100644
--- a/source/armarx/navigation/server/Navigator.cpp
+++ b/source/armarx/navigation/server/Navigator.cpp
@@ -670,6 +670,13 @@ namespace armarx::navigation::server
                                                   "PeriodicTask");
         runningTask->start();
 
+        // FIXME create separate function for this.
+        if(hasLocalPlanner())
+        {
+            srv.executor->start(ExecutorInterface::ControllerType::LocalTrajectory);
+        } else {
+            srv.executor->start(ExecutorInterface::ControllerType::GlobalTrajectory);
+        }
 
         // Could be required if pauseMovement() has been called in the past.
         resume();
@@ -838,6 +845,12 @@ namespace armarx::navigation::server
                                                                duration.toMilliSecondsDouble());
         }
 
+        // eventually, draw 
+        if(srv.introspector and srv.sceneProvider and srv.sceneProvider->scene().robot)
+        {
+            srv.introspector->onRobotPose(core::Pose(srv.sceneProvider->scene().robot->getGlobalPose()));
+        }
+
         // global planner update if goal has changed
         {
             std::lock_guard g{globalPlanningRequestMtx};
@@ -1042,7 +1055,7 @@ namespace armarx::navigation::server
         }
 
         ARMARX_IMPORTANT << "Executing global plan with " << globalPlan->trajectory.points().size() << " points.";
-        srv.executor->execute(globalPlan->trajectory, true); // fixme replace true by isPaused()
+        srv.executor->execute(globalPlan->trajectory, false);
     }
 
     void
@@ -1144,6 +1157,7 @@ namespace armarx::navigation::server
 
         if (srv.executor != nullptr)
         {
+            ARMARX_INFO << "Stopping executor.";
             srv.executor->stop();
         }
     }
@@ -1157,7 +1171,12 @@ namespace armarx::navigation::server
 
         if (srv.executor != nullptr)
         {
-            srv.executor->start();
+            if(hasLocalPlanner())
+            {
+                srv.executor->start(ExecutorInterface::ControllerType::LocalTrajectory);
+            }else {
+                srv.executor->start(ExecutorInterface::ControllerType::GlobalTrajectory);
+            }
         }
     }
 
diff --git a/source/armarx/navigation/server/execution/ExecutorInterface.h b/source/armarx/navigation/server/execution/ExecutorInterface.h
index 6e9d4fee..2d8d7a28 100644
--- a/source/armarx/navigation/server/execution/ExecutorInterface.h
+++ b/source/armarx/navigation/server/execution/ExecutorInterface.h
@@ -17,8 +17,17 @@ namespace armarx::navigation::server
         virtual void execute(const core::LocalTrajectory& trajectory, bool activateController = false) = 0;
         virtual void execute(const core::GlobalTrajectory& trajectory, bool activateController = false) = 0;
 
-        virtual void start() = 0;
+
+        enum class ControllerType
+        {
+            GlobalTrajectory,
+            LocalTrajectory,
+            None
+        };
+
+        virtual void start(ControllerType controllerType) = 0;
         virtual void stop() = 0;
+
     };
 
 } // namespace armarx::navigation::server
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
index 6ec13645..57569aa4 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.cpp
@@ -130,26 +130,29 @@ namespace armarx::navigation::server
 
 
     void
-    PlatformControllerExecutor::start()
+    PlatformControllerExecutor::start(const ControllerType controllerType)
     {
-        switch (lastActiveController_)
+        switch (controllerType)
         {
             case ControllerType::GlobalTrajectory:
                 if (globalTrajCtrl_.has_value())
                 {
                     globalTrajCtrl_->activate();
                 }
+                break;
             case ControllerType::LocalTrajectory:
                 if (localTrajCtrl_.has_value())
                 {
                     localTrajCtrl_->activate();
                 }
+                break;
             case ControllerType::None:
-                ARMARX_INFO << "No last active controller.";
+                ARMARX_INFO << "No controller selected.";
                 break;
         }
     }
 
+
     void
     PlatformControllerExecutor::stop()
     {
@@ -157,12 +160,14 @@ namespace armarx::navigation::server
 
         if (localTrajCtrl_->ctrl()->isControllerActive())
         {
+            ARMARX_INFO << "Stopping local trajectory controller.";
             localTrajCtrl_->deactivate();
             lastActiveController_ = ControllerType::LocalTrajectory;
         }
 
         if (globalTrajCtrl_->ctrl()->isControllerActive())
         {
+            ARMARX_INFO << "Stopping global trajectory controller.";
             globalTrajCtrl_->deactivate();
             lastActiveController_ = ControllerType::GlobalTrajectory;
         }
diff --git a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
index 90888900..2b1641a4 100644
--- a/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
+++ b/source/armarx/navigation/server/execution/PlatformControllerExecutor.h
@@ -34,7 +34,9 @@ namespace armarx::navigation::server
         void execute(const core::LocalTrajectory& trajectory, bool activateController = false) override;
         void execute(const core::GlobalTrajectory& trajectory, bool activateController = false) override;
 
-        void start() override;
+        void start(ControllerType controllerType) override;
+
+
         void stop() override;
 
     private:
@@ -48,12 +50,7 @@ namespace armarx::navigation::server
 
         ControllerComponentPlugin& controllerPlugin_;
 
-        enum class ControllerType
-        {
-            GlobalTrajectory,
-            LocalTrajectory,
-            None
-        };
+        
 
         ControllerType lastActiveController_ = ControllerType::None;
     };
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
index 70045733..89a0a92d 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.cpp
@@ -81,10 +81,37 @@ namespace armarx::navigation::server
     {
         auto layer = arviz.layer("goal");
         layer.add(viz::Pose("goal").pose(goal).scale(3));
-        arviz.commit(layer);
+
+        robotPosesLayer.clear();
+
+        arviz.commit({layer, robotPosesLayer});
 
         visualization.setTarget(goal);
     }
+
+    void ArvizIntrospector::onRobotPose(const core::Pose& pose)
+    {
+
+        constexpr float eps = 50; // [mm]
+
+        if(not lastPose)
+        {
+            lastPose = pose;
+        }
+        else {
+            // only draw poses every `eps` mm 
+            if((lastPose->translation() - pose.translation()).norm() < eps)
+            {
+                return;
+            }
+
+            lastPose = pose;
+        }
+
+        robotPosesLayer.add(viz::Pose("pose" + std::to_string(robotPosesLayer.size())).pose(pose));
+        arviz.commit(robotPosesLayer);
+    }
+
     
     void
     ArvizIntrospector::onGlobalShortestPath(const std::vector<core::Pose>& path)
diff --git a/source/armarx/navigation/server/introspection/ArvizIntrospector.h b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
index a0a5bfc1..3b286515 100644
--- a/source/armarx/navigation/server/introspection/ArvizIntrospector.h
+++ b/source/armarx/navigation/server/introspection/ArvizIntrospector.h
@@ -30,6 +30,7 @@
 #include <RobotAPI/components/ArViz/Client/ScopedClient.h>
 
 #include "IntrospectorInterface.h"
+#include "armarx/navigation/core/basic_types.h"
 #include <armarx/navigation/core/types.h>
 #include <armarx/navigation/global_planning/GlobalPlanner.h>
 #include <armarx/navigation/local_planning/LocalPlanner.h>
@@ -54,6 +55,8 @@ namespace armarx::navigation::server
 
         void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) override;
         void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) override;
+
+        void onRobotPose(const core::Pose& pose) override;
         
         void onGoal(const core::Pose& goal) override;
 
@@ -83,6 +86,10 @@ namespace armarx::navigation::server
         std::map<std::string, viz::Layer> layers;
 
         util::Visualization visualization;
+
+        std::optional<core::Pose> lastPose; 
+
+        viz::Layer robotPosesLayer;
     };
 
 } // namespace armarx::navigation::server
diff --git a/source/armarx/navigation/server/introspection/IntrospectorInterface.h b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
index 178b1915..1b403203 100644
--- a/source/armarx/navigation/server/introspection/IntrospectorInterface.h
+++ b/source/armarx/navigation/server/introspection/IntrospectorInterface.h
@@ -45,6 +45,8 @@ namespace armarx::navigation::server
         virtual void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) = 0;
         virtual void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) = 0;
 
+        virtual void onRobotPose(const core::Pose& pose) = 0;
+
         virtual void onGlobalShortestPath(const std::vector<core::Pose>& path) = 0;
 
         virtual void onGlobalGraph(const core::Graph& graph) = 0;
diff --git a/source/armarx/navigation/server/introspection/MemoryIntrospector.h b/source/armarx/navigation/server/introspection/MemoryIntrospector.h
index 592bf116..55b5c4f9 100644
--- a/source/armarx/navigation/server/introspection/MemoryIntrospector.h
+++ b/source/armarx/navigation/server/introspection/MemoryIntrospector.h
@@ -41,6 +41,8 @@ namespace armarx::navigation::server
         void onGlobalPlannerResult(const global_planning::GlobalPlannerResult& result) override;
         void onLocalPlannerResult(const local_planning::LocalPlannerResult& result) override;
 
+        void onRobotPose(const core::Pose& pose) override {}
+
         void onGoal(const core::Pose& goal) override;
 
         void success() override{};
diff --git a/source/armarx/navigation/skills/NavigateToLocation.cpp b/source/armarx/navigation/skills/NavigateToLocation.cpp
index d9464ab2..c488c5c0 100644
--- a/source/armarx/navigation/skills/NavigateToLocation.cpp
+++ b/source/armarx/navigation/skills/NavigateToLocation.cpp
@@ -42,6 +42,10 @@ namespace armarx::navigation::skills
         const std::string configId = DefaultSkillDescription().skillName;
 
         // configure the `navigator` which provides a simplified and typed interface to the navigation server
+        ARMARX_TRACE;
+        memorySubscriber.reset();
+
+        ARMARX_TRACE;
         memorySubscriber.emplace(configId, srv_->memoryNameSystem);
 
         // register our config
-- 
GitLab


From efc6373055b6612fd03c6174114ab2a45efdf11d Mon Sep 17 00:00:00 2001
From: armar-user <armar6@kit>
Date: Tue, 14 Feb 2023 18:32:03 +0100
Subject: [PATCH 323/324] navigator: properties for visualization

---
 .../navigation_memory/Component.cpp           | 34 +++++++++++++++----
 .../components/navigation_memory/Component.h  | 16 +++++----
 2 files changed, 37 insertions(+), 13 deletions(-)

diff --git a/source/armarx/navigation/components/navigation_memory/Component.cpp b/source/armarx/navigation/components/navigation_memory/Component.cpp
index 03ee1d01..22f674ca 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.cpp
+++ b/source/armarx/navigation/components/navigation_memory/Component.cpp
@@ -88,11 +88,29 @@ namespace armarx::navigation::components::navigation_memory
         def->optional(properties.locationGraph.visuLocations,
                       "p.locationGraph.visuLocation",
                       "Enable visualization of locations.");
+
         def->optional(properties.locationGraph.visuGraphEdges,
                       "p.locationGraph.visuGraphEdges",
                       "Enable visualization of navigation graph edges.");
-        def->optional(properties.locationGraph.visuFrequency,
-                      "p.locationGraph.visuFrequency",
+
+        def->optional(properties.visuCostmaps,
+                      "p.visuCostmaps",
+                      "Enable visualization of costmaps.");
+
+        def->optional(properties.visuHumans,
+                      "p.visuHumans",
+                      "Enable visualization of humans.");
+
+        def->optional(properties.visuTransparent,
+                      "p.visuTransparent",
+                      "Enable visualization of humans a bit transparent.");
+
+        def->optional(properties.visuRooms,
+                      "p.visuRooms",
+                      "Enable visualization of rooms.");
+
+        def->optional(properties.visuFrequency,
+                      "p.visuFrequency",
                       "Visualization frequeny of locations and graph edges [Hz].");
 
         return def;
@@ -508,10 +526,12 @@ namespace armarx::navigation::components::navigation_memory
                           workingMemory().getCoreSegment(memory::constants::HumanCoreSegmentName),
                           workingMemory().getCoreSegment(navigation::rooms::coreSegmentID)};
 
-        Properties::LocationGraph p;
+        Properties::LocationGraph pp;
+        Properties p;
         {
             std::scoped_lock lock(propertiesMutex);
-            p = properties.locationGraph;
+            pp = properties.locationGraph;
+            p = properties;
         }
 
         Metronome metronome(Frequency::HertzDouble(p.visuFrequency));
@@ -521,16 +541,16 @@ namespace armarx::navigation::components::navigation_memory
 
             {
                 std::scoped_lock lock(propertiesMutex);
-                p = properties.locationGraph;
+                pp = properties.locationGraph;
             }
 
             std::vector<viz::Layer> layers;
 
             // Locations
-            visu.drawLocations(layers, p.visuLocations);
+            visu.drawLocations(layers, pp.visuLocations);
 
             // Graph Edges
-            visu.drawGraphs(layers, p.visuGraphEdges);
+            visu.drawGraphs(layers, pp.visuGraphEdges);
 
             // Costmaps
             visu.drawCostmaps(layers, p.visuCostmaps);
diff --git a/source/armarx/navigation/components/navigation_memory/Component.h b/source/armarx/navigation/components/navigation_memory/Component.h
index f9b44c76..77220afe 100644
--- a/source/armarx/navigation/components/navigation_memory/Component.h
+++ b/source/armarx/navigation/components/navigation_memory/Component.h
@@ -103,14 +103,18 @@ namespace armarx::navigation::components::navigation_memory
             {
                 bool visuLocations = true;
                 bool visuGraphEdges = true;
-                bool visuCostmaps = true;
-                bool visuHumans = true;
+                
+            };
 
-                bool visuTransparent = false;
+            float visuFrequency = 2;
+
+            bool visuCostmaps = true;
+
+            bool visuHumans = true;
+            bool visuTransparent = false;
+
+            bool visuRooms = true;
 
-                float visuFrequency = 2;
-                bool visuRooms = true;
-            };
             LocationGraph locationGraph;
         };
         Properties properties;
-- 
GitLab


From d72d4bbe844a83e0305ab3dbd3426b9f3a95e2a4 Mon Sep 17 00:00:00 2001
From: armar-user <armar6@kit>
Date: Wed, 15 Feb 2023 09:35:30 +0100
Subject: [PATCH 324/324] parameter update (tested on A-6) (FR)

---
 .../controller_config/GlobalTrajectory/default.json       | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/data/armarx_navigation/controller_config/GlobalTrajectory/default.json b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
index efe7edc7..43186191 100644
--- a/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
+++ b/data/armarx_navigation/controller_config/GlobalTrajectory/default.json
@@ -1,18 +1,18 @@
 {
   "params": {
     "pidPos": {
-      "Kp": 25,
+      "Kp": 15,
       "Ki": 0,
       "Kd": 0
     },
     "pidOri": {
-      "Kp": 50,
+      "Kp": 10,
       "Ki": 0,
       "Kd": 0
     },
     "limits": {
-      "linear": 200,
-      "angular": 0.3
+      "linear": 500,
+      "angular": 0.4
     }
   },
   "targets": {
-- 
GitLab