From ad27b27eda8ecbb9f82a323f1fbb7de8982af443 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 2 Aug 2021 19:39:36 +0200 Subject: [PATCH 01/18] Fix logic to disable server default plugins loading (#953) Signed-off-by: Diego --- src/ServerConfig.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index 97b738c4ea..fc3bb6d122 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -826,7 +826,8 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) // 1. Check contents of environment variable std::string envConfig; bool configSet = ignition::common::env(gazebo::kServerConfigPathEnv, - envConfig); + envConfig, + true); if (configSet) { From 8620011303635a76d515caa9d31845d67193dc8a Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 4 Aug 2021 06:15:33 -0700 Subject: [PATCH 02/18] Expose a test fixture helper class (#926) Signed-off-by: Louise Poubel Signed-off-by: Arjo Chakravarty --- .../standalone/custom_server/CMakeLists.txt | 4 +- .../standalone/gtest_setup/CMakeLists.txt | 36 +++ examples/standalone/gtest_setup/README.md | 27 ++ examples/standalone/gtest_setup/command.sdf | 26 ++ .../standalone/gtest_setup/command_TEST.cc | 129 +++++++++ examples/standalone/gtest_setup/gravity.sdf | 22 ++ .../standalone/gtest_setup/gravity_TEST.cc | 86 ++++++ include/ignition/gazebo/TestFixture.hh | 113 ++++++++ include/ignition/gazebo/Util.hh | 2 +- src/CMakeLists.txt | 2 + src/TestFixture.cc | 215 ++++++++++++++ src/TestFixture_TEST.cc | 266 ++++++++++++++++++ test/helpers/Relay.hh | 6 +- test/integration/examples_build.cc | 9 + test/test_config.hh.in | 1 + tutorials.md.in | 4 +- tutorials/test_fixture.md | 24 ++ 17 files changed, 962 insertions(+), 10 deletions(-) create mode 100644 examples/standalone/gtest_setup/CMakeLists.txt create mode 100644 examples/standalone/gtest_setup/README.md create mode 100644 examples/standalone/gtest_setup/command.sdf create mode 100644 examples/standalone/gtest_setup/command_TEST.cc create mode 100644 examples/standalone/gtest_setup/gravity.sdf create mode 100644 examples/standalone/gtest_setup/gravity_TEST.cc create mode 100644 include/ignition/gazebo/TestFixture.hh create mode 100644 src/TestFixture.cc create mode 100644 src/TestFixture_TEST.cc create mode 100644 tutorials/test_fixture.md diff --git a/examples/standalone/custom_server/CMakeLists.txt b/examples/standalone/custom_server/CMakeLists.txt index 3c5c395e62..fb8597cf2b 100644 --- a/examples/standalone/custom_server/CMakeLists.txt +++ b/examples/standalone/custom_server/CMakeLists.txt @@ -2,10 +2,10 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux") find_package(ignition-gazebo3 REQUIRED) - set(IGN_COMMON_VER ${ignition-gazebo3_VERSION_MAJOR}) + set(IGN_GAZEBO_VER ${ignition-gazebo3_VERSION_MAJOR}) add_executable(custom_server custom_server.cc) target_link_libraries(custom_server - ignition-gazebo${IGN_COMMON_VER}::ignition-gazebo${IGN_COMMON_VER} + ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER} ) endif() diff --git a/examples/standalone/gtest_setup/CMakeLists.txt b/examples/standalone/gtest_setup/CMakeLists.txt new file mode 100644 index 0000000000..db209afda5 --- /dev/null +++ b/examples/standalone/gtest_setup/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 3.11.0 FATAL_ERROR) + +project(GTestSetup) + +# Find Gazebo +set(IGN_GAZEBO_VER 3) +find_package(ignition-gazebo${IGN_GAZEBO_VER} REQUIRED) + +# Fetch and configure GTest +include(FetchContent) +FetchContent_Declare( + googletest + URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip +) +set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) +FetchContent_MakeAvailable(googletest) + +enable_testing() +include(Dart) + +# Generate tests +foreach(TEST_TARGET + command_TEST + gravity_TEST) + + add_executable( + ${TEST_TARGET} + ${TEST_TARGET}.cc + ) + target_link_libraries(${TEST_TARGET} + gtest_main + ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER} + ) + include(GoogleTest) + gtest_discover_tests(${TEST_TARGET}) +endforeach() diff --git a/examples/standalone/gtest_setup/README.md b/examples/standalone/gtest_setup/README.md new file mode 100644 index 0000000000..ecc6edfd5a --- /dev/null +++ b/examples/standalone/gtest_setup/README.md @@ -0,0 +1,27 @@ +# GTest setup + +Example of how to setup simulation-based tests using GTest. + +The example contains 2 tests: + +* `gravity_TEST` is a minimal example to explain the basics +* `command_TEST` has a slightly more realistic test + +See the comments on the source code for more explanations. + +## Build + +From the root of the repository: + + cd examples/standalone/gtest_setup + mkdir build + cd build + cmake .. + make + +## Run tests + + cd examples/standalone/gtest_setup/build + ./gravity_TEST + ./command_TEST + diff --git a/examples/standalone/gtest_setup/command.sdf b/examples/standalone/gtest_setup/command.sdf new file mode 100644 index 0000000000..b7c3f7c690 --- /dev/null +++ b/examples/standalone/gtest_setup/command.sdf @@ -0,0 +1,26 @@ + + + + + + + + + + + 0.4 + 0.4 + 0.4 + + 1.0 + + + + + + + diff --git a/examples/standalone/gtest_setup/command_TEST.cc b/examples/standalone/gtest_setup/command_TEST.cc new file mode 100644 index 0000000000..f8e4f4583f --- /dev/null +++ b/examples/standalone/gtest_setup/command_TEST.cc @@ -0,0 +1,129 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std::chrono_literals; + +////////////////////////////////////////////////// +// Test sending a command and verify that model reacts accordingly +TEST(ExampleTests, Command) +{ + // Maximum verbosity helps with debugging + ignition::common::Console::SetVerbosity(4); + + // Instantiate test fixture + ignition::gazebo::TestFixture fixture("../command.sdf"); + + // Get the link that we'll be inspecting + bool configured{false}; + ignition::gazebo::Link link; + fixture.OnConfigure( + [&link, &configured](const ignition::gazebo::Entity &_worldEntity, + const std::shared_ptr &/*_sdf*/, + ignition::gazebo::EntityComponentManager &_ecm, + ignition::gazebo::EventManager &/*_eventMgr*/) + { + ignition::gazebo::World world(_worldEntity); + + auto modelEntity = world.ModelByName(_ecm, "commanded"); + EXPECT_NE(ignition::gazebo::kNullEntity, modelEntity); + + auto model = ignition::gazebo::Model(modelEntity); + + auto linkEntity = model.LinkByName(_ecm, "link"); + EXPECT_NE(ignition::gazebo::kNullEntity, linkEntity); + + link = ignition::gazebo::Link(linkEntity); + EXPECT_TRUE(link.Valid(_ecm)); + + // Tell Gazebo that we want to observe the link's velocity and acceleration + link.EnableVelocityChecks(_ecm, true); + link.EnableAccelerationChecks(_ecm, true); + + configured = true; + }) + // Configure must be set before finalize, but other callbacks can come after + .Finalize(); + + EXPECT_TRUE(configured); + + // Check that link is falling due to gravity + int iterations{0}; + ignition::math::Vector3d linVel; + ignition::math::Vector3d linAccel; + fixture.OnPostUpdate( + [&]( + const ignition::gazebo::UpdateInfo &_info, + const ignition::gazebo::EntityComponentManager &_ecm) + { + linVel = link.WorldLinearVelocity(_ecm).value(); + EXPECT_DOUBLE_EQ(0.0, linVel.Y()); + + linAccel = link.WorldLinearAcceleration(_ecm).value(); + EXPECT_DOUBLE_EQ(0.0, linAccel.X()); + EXPECT_DOUBLE_EQ(0.0, linAccel.Y()); + + iterations++; + }); + + int expectedIterations{10}; + fixture.Server()->Run(true, expectedIterations, false); + EXPECT_EQ(expectedIterations, iterations); + EXPECT_DOUBLE_EQ(0.0, linVel.X()); + EXPECT_GT(0.0, linVel.Z()); + EXPECT_GT(0.0, linAccel.Z()); + + // Send velocity command + ignition::transport::Node node; + + ignition::msgs::Twist msg; + auto linVelMsg = msg.mutable_linear(); + linVelMsg->set_x(10); + + auto pub = node.Advertise("/model/commanded/cmd_vel"); + pub.Publish(msg); + + // Commands sent through transport are processed asynchronously and may + // take a while to execute, so we run a few iterations until it takes + // effect. + int sleep{0}; + int maxSleep{30}; + for (; sleep < maxSleep && linVel.X() < 0.1; ++sleep) + { + fixture.Server()->Run(true, 10, false); + expectedIterations+= 10; + std::this_thread::sleep_for(100ms); + } + EXPECT_LT(sleep, maxSleep); + EXPECT_EQ(expectedIterations, iterations); + + EXPECT_DOUBLE_EQ(10.0, linVel.X()); + EXPECT_GT(0.0, linVel.Z()); + EXPECT_GT(0.0, linAccel.Z()); +} diff --git a/examples/standalone/gtest_setup/gravity.sdf b/examples/standalone/gtest_setup/gravity.sdf new file mode 100644 index 0000000000..ee1161fa5f --- /dev/null +++ b/examples/standalone/gtest_setup/gravity.sdf @@ -0,0 +1,22 @@ + + + + + + + + + + + 0.4 + 0.4 + 0.4 + + 1.0 + + + + + diff --git a/examples/standalone/gtest_setup/gravity_TEST.cc b/examples/standalone/gtest_setup/gravity_TEST.cc new file mode 100644 index 0000000000..6bae7b3e78 --- /dev/null +++ b/examples/standalone/gtest_setup/gravity_TEST.cc @@ -0,0 +1,86 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////// +// Test that an object falls due to gravity +TEST(ExampleTests, Gravity) +{ + // Maximum verbosity helps with debugging + ignition::common::Console::SetVerbosity(4); + + // Instantiate test fixture. It starts a server and provides hooks that we'll + // use to inspect the running simulation. + ignition::gazebo::TestFixture fixture("../gravity.sdf"); + + int iterations{0}; + ignition::gazebo::Entity modelEntity; + ignition::math::Vector3d gravity; + + fixture. + // Use configure callback to get values at startup + OnConfigure( + [&modelEntity, &gravity](const ignition::gazebo::Entity &_worldEntity, + const std::shared_ptr &/*_sdf*/, + ignition::gazebo::EntityComponentManager &_ecm, + ignition::gazebo::EventManager &/*_eventMgr*/) + { + // Get gravity + ignition::gazebo::World world(_worldEntity); + gravity = world.Gravity(_ecm).value(); + + // Get falling entity + modelEntity = world.ModelByName(_ecm, "falling"); + EXPECT_NE(ignition::gazebo::kNullEntity, modelEntity); + }). + // Use post-update callback to get values at the end of every iteration + OnPostUpdate( + [&iterations, &modelEntity, &gravity]( + const ignition::gazebo::UpdateInfo &_info, + const ignition::gazebo::EntityComponentManager &_ecm) + { + // Inspect all model poses + auto pose = ignition::gazebo::worldPose(modelEntity, _ecm); + + EXPECT_DOUBLE_EQ(0.0, pose.Pos().X()); + EXPECT_DOUBLE_EQ(0.0, pose.Pos().Y()); + + // Check that model is falling due to gravity + // -g * t^2 / 2 + auto time = std::chrono::duration(_info.simTime).count(); + EXPECT_NEAR(gravity.Z() * time * time * 0.5, pose.Pos().Z(), 1e-2); + + iterations++; + }). + // The moment we finalize, the configure callback is called + Finalize(); + + // Setup simulation server, this will call the post-update callbacks. + // It also calls pre-update and update callbacks if those are being used. + fixture.Server()->Run(true, 1000, false); + + // Verify that the post update function was called 1000 times + EXPECT_EQ(1000, iterations); +} diff --git a/include/ignition/gazebo/TestFixture.hh b/include/ignition/gazebo/TestFixture.hh new file mode 100644 index 0000000000..75d371f437 --- /dev/null +++ b/include/ignition/gazebo/TestFixture.hh @@ -0,0 +1,113 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef IGNITION_GAZEBO_TESTFIXTURE_HH_ +#define IGNITION_GAZEBO_TESTFIXTURE_HH_ + +#include +#include + +#include "ignition/gazebo/EntityComponentManager.hh" +#include "ignition/gazebo/Export.hh" +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/ServerConfig.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +// +class IGNITION_GAZEBO_HIDDEN TestFixturePrivate; +/// \brief Helper class to write automated tests. It provides a convenient API +/// to load a world file, step simulation and check entities and components. +/// +/// ## Usage +/// +/// // Load a world with a fixture +/// ignition::gazebo::TestFixture fixture("path_to.sdf"); +/// +/// // Register callbacks, for example: +/// fixture.OnPostUpdate([&](const gazebo::UpdateInfo &, +/// const gazebo::EntityComponentManager &_ecm) +/// { +/// // Add expectations here +/// }).Finalize(); +/// // Be sure to call finalize before running the server. +/// +/// // Run the server +/// fixture.Server()->Run(true, 1000, false); +/// +class IGNITION_GAZEBO_VISIBLE TestFixture +{ + /// \brief Constructor + /// \param[in] _path Path to SDF file. + public: explicit TestFixture(const std::string &_path); + + /// \brief Constructor + /// \param[in] _config Server config file + public: explicit TestFixture(const ServerConfig &_config); + + /// \brief Destructor + public: virtual ~TestFixture(); + + /// \brief Wrapper around a system's pre-update callback + /// \param[in] _cb Function to be called every pre-update + /// The _entity and _sdf will correspond to the world entity. + /// \return Reference to self. + public: TestFixture &OnConfigure(std::function &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr)> _cb); + + /// \brief Wrapper around a system's pre-update callback + /// \param[in] _cb Function to be called every pre-update + /// \return Reference to self. + public: TestFixture &OnPreUpdate(std::function _cb); + + /// \brief Wrapper around a system's update callback + /// \param[in] _cb Function to be called every update + /// \return Reference to self. + public: TestFixture &OnUpdate(std::function _cb); + + /// \brief Wrapper around a system's post-update callback + /// \param[in] _cb Function to be called every post-update + /// \return Reference to self. + public: TestFixture &OnPostUpdate(std::function _cb); + + /// \brief Finalize all the functions and add fixture to server. + /// Finalize must be called before running the server, otherwise none of the + /// `On*` functions will be called. + /// The `OnConfigure` callback is called immediately on finalize. + public: TestFixture &Finalize(); + + /// \brief Get pointer to underlying server. + public: std::shared_ptr Server() const; + + /// \internal + /// \brief Pointer to private data. + // TODO(chapulina) Use IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr) when porting to v6 + private: TestFixturePrivate *dataPtr; +}; +} +} +} +#endif diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index d83240f98b..d362385172 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -184,7 +184,7 @@ namespace ignition /// \return True if a component was created or removed, false if nothing /// changed. template - bool IGNITION_GAZEBO_VISIBLE enableComponent(EntityComponentManager &_ecm, + bool enableComponent(EntityComponentManager &_ecm, Entity _entity, bool _enable = true) { bool changed{false}; diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 339988e4c7..e20b7b2c5b 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -60,6 +60,7 @@ set (sources SimulationRunner.cc System.cc SystemLoader.cc + TestFixture.cc Util.cc View.cc World.cc @@ -87,6 +88,7 @@ set (gtest_sources SimulationRunner_TEST.cc System_TEST.cc SystemLoader_TEST.cc + TestFixture_TEST.cc Util_TEST.cc World_TEST.cc network/NetworkConfig_TEST.cc diff --git a/src/TestFixture.cc b/src/TestFixture.cc new file mode 100644 index 0000000000..8f1dffd9f5 --- /dev/null +++ b/src/TestFixture.cc @@ -0,0 +1,215 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/ServerConfig.hh" + +#include "ignition/gazebo/TestFixture.hh" + +using namespace ignition; +using namespace gazebo; + +/// \brief System that is inserted into the simulation loop to observe the ECM. +class HelperSystem : + public System, + public ISystemConfigure, + public ISystemPreUpdate, + public ISystemUpdate, + public ISystemPostUpdate +{ + // Documentation inherited + public: void Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) override; + + // Documentation inherited + public: void PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) override; + + // Documentation inherited + public: void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) override; + + // Documentation inherited + public: void PostUpdate(const UpdateInfo &_info, + const EntityComponentManager &_ecm) override; + + /// \brief Function to call every time we configure a world + public: std::function &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr)> + configureCallback; + + /// \brief Function to call every pre-update + public: std::function + preUpdateCallback; + + /// \brief Function to call every update + public: std::function + updateCallback; + + /// \brief Function to call every post-update + public: std::function postUpdateCallback; +}; + +///////////////////////////////////////////////// +void HelperSystem::Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) +{ + if (this->configureCallback) + this->configureCallback(_entity, _sdf, _ecm, _eventMgr); +} + +///////////////////////////////////////////////// +void HelperSystem::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) +{ + if (this->preUpdateCallback) + this->preUpdateCallback(_info, _ecm); +} + +///////////////////////////////////////////////// +void HelperSystem::Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) +{ + if (this->updateCallback) + this->updateCallback(_info, _ecm); +} + +///////////////////////////////////////////////// +void HelperSystem::PostUpdate(const UpdateInfo &_info, + const EntityComponentManager &_ecm) +{ + if (this->postUpdateCallback) + this->postUpdateCallback(_info, _ecm); +} + +////////////////////////////////////////////////// +class ignition::gazebo::TestFixturePrivate +{ + /// \brief Initialize fixture + /// \param[in] _config Server config + public: void Init(const ServerConfig &_config); + + /// \brief Pointer to underlying server + public: std::shared_ptr server{nullptr}; + + /// \brief Pointer to underlying Helper interface + public: std::shared_ptr helperSystem{nullptr}; + + /// \brief Flag to make sure Finalize is only called once + public: bool finalized{false}; +}; + +////////////////////////////////////////////////// +TestFixture::TestFixture(const std::string &_path) + : dataPtr(new TestFixturePrivate()) +{ + ServerConfig config; + config.SetSdfFile(_path); + this->dataPtr->Init(config); +} + +////////////////////////////////////////////////// +TestFixture::TestFixture(const ServerConfig &_config) + : dataPtr(new TestFixturePrivate()) +{ + this->dataPtr->Init(_config); +} + +////////////////////////////////////////////////// +TestFixture::~TestFixture() +{ + delete dataPtr; + dataPtr = nullptr; +} + +////////////////////////////////////////////////// +void TestFixturePrivate::Init(const ServerConfig &_config) +{ + this->helperSystem = std::make_shared(); + this->server = std::make_shared(_config); +} + +////////////////////////////////////////////////// +TestFixture &TestFixture::Finalize() +{ + if (this->dataPtr->finalized) + { + ignwarn << "Fixture has already been finalized, this only needs to be done" + << " once." << std::endl; + return *this; + } + + this->dataPtr->server->AddSystem(this->dataPtr->helperSystem); + + this->dataPtr->finalized = true; + return *this; +} + +////////////////////////////////////////////////// +TestFixture &TestFixture::OnConfigure(std::function &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr)> _cb) +{ + if (nullptr != this->dataPtr->helperSystem) + this->dataPtr->helperSystem->configureCallback = std::move(_cb); + return *this; +} + +////////////////////////////////////////////////// +TestFixture &TestFixture::OnPreUpdate(std::function _cb) +{ + if (nullptr != this->dataPtr->helperSystem) + this->dataPtr->helperSystem->preUpdateCallback = std::move(_cb); + return *this; +} + +////////////////////////////////////////////////// +TestFixture &TestFixture::OnUpdate(std::function _cb) +{ + if (nullptr != this->dataPtr->helperSystem) + this->dataPtr->helperSystem->updateCallback = std::move(_cb); + return *this; +} + +////////////////////////////////////////////////// +TestFixture &TestFixture::OnPostUpdate(std::function _cb) +{ + if (nullptr != this->dataPtr->helperSystem) + this->dataPtr->helperSystem->postUpdateCallback = std::move(_cb); + return *this; +} + +////////////////////////////////////////////////// +std::shared_ptr TestFixture::Server() const +{ + return this->dataPtr->server; +} + diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc new file mode 100644 index 0000000000..244e5b1846 --- /dev/null +++ b/src/TestFixture_TEST.cc @@ -0,0 +1,266 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include +#include + +#include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/ServerConfig.hh" +#include "ignition/gazebo/test_config.hh" +#include "ignition/gazebo/TestFixture.hh" + +using namespace ignition; +using namespace gazebo; + +///////////////////////////////////////////////// +class TestFixtureTest : public ::testing::Test +{ + // Documentation inherited + public: void SetUp() override + { + common::Console::SetVerbosity(4); + } + + /// \brief Configure expectations + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &) + { + auto worldEntity = _ecm.EntityByComponents(components::Name("default")); + EXPECT_EQ(worldEntity, _entity); + + ASSERT_NE(nullptr, _sdf); + EXPECT_EQ("world", _sdf->GetName()); + + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name("box"))); + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name("sphere"))); + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name( + "cylinder"))); + } + + /// \brief PreUpdate, Update and PostUpdate expectations + public: void Updates(const UpdateInfo &, + const EntityComponentManager &_ecm) + { + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name("box"))); + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name("sphere"))); + EXPECT_NE(kNullEntity, _ecm.EntityByComponents(components::Name( + "cylinder"))); + } +}; + +///////////////////////////////////////////////// +TEST_F(TestFixtureTest, Callbacks) +{ + TestFixture testFixture(common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); + ASSERT_NE(nullptr, testFixture.Server()); + + unsigned int configures{0u}; + unsigned int preUpdates{0u}; + unsigned int updates{0u}; + unsigned int postUpdates{0u}; + testFixture. + OnConfigure([&](const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) + { + this->Configure(_entity, _sdf, _ecm, _eventMgr); + configures++; + }). + OnPreUpdate([&](const UpdateInfo &_info, EntityComponentManager &_ecm) + { + this->Updates(_info, _ecm); + preUpdates++; + EXPECT_EQ(preUpdates, _info.iterations); + }). + OnUpdate([&](const UpdateInfo &_info, EntityComponentManager &_ecm) + { + this->Updates(_info, _ecm); + updates++; + EXPECT_EQ(updates, _info.iterations); + }). + OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) + { + this->Updates(_info, _ecm); + postUpdates++; + EXPECT_EQ(postUpdates, _info.iterations); + }). + Finalize(); + + unsigned int expectedIterations{10u}; + testFixture.Server()->Run(true, expectedIterations, false); + + EXPECT_EQ(1u, configures); + EXPECT_EQ(expectedIterations, preUpdates); + EXPECT_EQ(expectedIterations, updates); + EXPECT_EQ(expectedIterations, postUpdates); +} + +///////////////////////////////////////////////// +TEST_F(TestFixtureTest, LoadConfig) +{ + ServerConfig config; + config.SetSdfFile(common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); + + TestFixture testFixture(config); + ASSERT_NE(nullptr, testFixture.Server()); + + // Check that world was loaded correctly (entities were created) + unsigned int iterations{0u}; + testFixture.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) + { + this->Updates(_info, _ecm); + iterations++; + }).Finalize(); + + unsigned int expectedIterations{10u}; + testFixture.Server()->Run(true, expectedIterations, false); + + EXPECT_EQ(expectedIterations, iterations); +} + +///////////////////////////////////////////////// +TEST_F(TestFixtureTest, NoFinalize) +{ + TestFixture testFixture(common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); + ASSERT_NE(nullptr, testFixture.Server()); + + unsigned int configures{0u}; + unsigned int preUpdates{0u}; + unsigned int updates{0u}; + unsigned int postUpdates{0u}; + testFixture. + OnConfigure([&](const Entity &, + const std::shared_ptr &, + EntityComponentManager &, + EventManager &) + { + configures++; + }). + OnPreUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + preUpdates++; + }). + OnUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + updates++; + }). + OnPostUpdate([&](const UpdateInfo &, const EntityComponentManager &) + { + postUpdates++; + }); + + unsigned int expectedIterations{10u}; + testFixture.Server()->Run(true, expectedIterations, false); + + // Callbacks not called without Finalize + EXPECT_EQ(0u, configures); + EXPECT_EQ(0u, preUpdates); + EXPECT_EQ(0u, updates); + EXPECT_EQ(0u, postUpdates); +} + +///////////////////////////////////////////////// +TEST_F(TestFixtureTest, MultiFinalize) +{ + TestFixture testFixture(common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); + ASSERT_NE(nullptr, testFixture.Server()); + + unsigned int configures{0u}; + unsigned int preUpdates{0u}; + unsigned int updates{0u}; + unsigned int postUpdates{0u}; + testFixture. + OnConfigure([&](const Entity &, + const std::shared_ptr &, + EntityComponentManager &, + EventManager &) + { + configures++; + }). + OnPreUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + preUpdates++; + }). + OnUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + updates++; + }). + OnPostUpdate([&](const UpdateInfo &, const EntityComponentManager &) + { + postUpdates++; + }). + // Nothing is messed up if finalize is called multiple times + Finalize(). + Finalize(). + Finalize(); + + unsigned int expectedIterations{10u}; + testFixture.Server()->Run(true, expectedIterations, false); + + EXPECT_EQ(1u, configures); + EXPECT_EQ(expectedIterations, preUpdates); + EXPECT_EQ(expectedIterations, updates); + EXPECT_EQ(expectedIterations, postUpdates); +} + +///////////////////////////////////////////////// +TEST_F(TestFixtureTest, ChangeCallback) +{ + TestFixture testFixture(common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "shapes.sdf")); + ASSERT_NE(nullptr, testFixture.Server()); + + unsigned int preUpdate1{0u}; + testFixture. + OnPreUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + preUpdate1++; + }). + Finalize(); + + unsigned int expectedIterations{10u}; + testFixture.Server()->Run(true, expectedIterations, false); + + EXPECT_EQ(expectedIterations, preUpdate1); + + unsigned int preUpdate2{0u}; + testFixture. + OnPreUpdate([&](const UpdateInfo &, EntityComponentManager &) + { + preUpdate2++; + }). + Finalize(); + + testFixture.Server()->Run(true, expectedIterations, false); + + // First callback isn't called anymore + EXPECT_EQ(expectedIterations, preUpdate1); + + // New callback is called + EXPECT_EQ(expectedIterations, preUpdate2); +} diff --git a/test/helpers/Relay.hh b/test/helpers/Relay.hh index 7ff35e2cd8..f30323e4e6 100644 --- a/test/helpers/Relay.hh +++ b/test/helpers/Relay.hh @@ -17,8 +17,6 @@ #ifndef IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ #define IGNITION_GAZEBO_TEST_HELPERS_RELAY_HH_ -#include - #include #include "../plugins/MockSystem.hh" @@ -51,10 +49,8 @@ namespace test class Relay { /// \brief Constructor - public: Relay() + public: Relay() : systemPtr(std::make_shared()) { - this->systemPtr = std::make_shared(); - EXPECT_NE(nullptr, this->systemPtr); } /// \brief Wrapper around system's pre-update callback diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index 95b1d75b63..d6c43d9750 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -21,6 +21,7 @@ #include #include #include +#include #include "ignition/gazebo/test_config.hh" @@ -144,6 +145,14 @@ void ExamplesBuild::Build(const std::string &_type) { auto base = ignition::common::basename(*dirIter); + math::SemanticVersion cmakeVersion{std::string(CMAKE_VERSION)}; + if (base == "gtest_setup" && cmakeVersion < math::SemanticVersion(3, 11, 0)) + { + igndbg << "Skipping [gtest_setup] test, which requires CMake version >= " + << "3.11.0. Currently using CMake " << cmakeVersion << std::endl; + continue; + } + // Source directory for this example auto sourceDir = examplesDir; sourceDir += "/" + base; diff --git a/test/test_config.hh.in b/test/test_config.hh.in index 659f8e6fc3..e80b8c4440 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -22,6 +22,7 @@ #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" #define PROJECT_BINARY_PATH "${CMAKE_BINARY_DIR}" +#define CMAKE_VERSION "${CMAKE_VERSION}" #define IGN_CONFIG_PATH "@CMAKE_BINARY_DIR@/test/conf" diff --git a/tutorials.md.in b/tutorials.md.in index f1b5451408..43c4a3244f 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -24,10 +24,10 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage triggeredpublisher "Triggered Publisher": Using the TriggeredPublisher system to orchestrate actions in simulation. * \subpage logicalaudiosensor "Logical Audio Sensor": Using the LogicalAudioSensor system to mimic logical audio emission and detection in simulation. * \subpage videorecorder "Video Recorder": Record videos from the 3D render window. -* \subpage collada_world_exporter "Collada World Exporter": Export an entire -world to a single Collada mesh. +* \subpage collada_world_exporter "Collada World Exporter": Export an entire world to a single Collada mesh. * \subpage model_and_optimize_meshes "Model and optimize meshes": Some recomendations when creating meshes in blender for simulations. * \subpage model_command "Model Command": Use the CLI to get information about the models in a simulation. +* \subpage test_fixture "Test Fixture": Writing automated CI tests **Migration from Gazebo classic** diff --git a/tutorials/test_fixture.md b/tutorials/test_fixture.md new file mode 100644 index 0000000000..1ac724eee8 --- /dev/null +++ b/tutorials/test_fixture.md @@ -0,0 +1,24 @@ +\page test_fixture Test fixture + +Ignition Gazebo can be used to run scripted simulations so that it's convenient +to run automated tests for robot applications. This tutorial will go over the +process of writing automated tests using Ignition Gazebo so that they can be run +using Continuous Integration (CI). + +## Example setup + +Gazebo can be used for testing using any testing library. We provide +an example of how to setup some test cases using +[Google Test](https://github.com/google/googletest) in +[ign-gazebo/examples/standalone/gtest_setup](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo3/examples/standalone/gtest_setup). + +The instructions on that example's `README` can be followed to compile and run +those tests. Also be sure to go through the source code for comments with +helpful pointers on how to setup tests. + +## Test Fixture + +The example above uses the `ignition::gazebo::TestFixture` class, which provides +a convenient API to start a simulation and step through it while checking that +entities in simulation are acting as expected. See that class' documentation +for more information. From 0431f9e3bb7683e24885fa92b1e3ecd726846d6a Mon Sep 17 00:00:00 2001 From: herobank110 Date: Tue, 27 Oct 2020 00:57:49 +0000 Subject: [PATCH 03/18] Add 25percent darker view angle icons (#426) Signed-off-by: David Kanekanian --- .../plugins/view_angle/view_angle_back.png | Bin 1467 -> 4026 bytes .../plugins/view_angle/view_angle_bottom.png | Bin 1473 -> 4033 bytes .../plugins/view_angle/view_angle_front.png | Bin 1261 -> 3852 bytes .../plugins/view_angle/view_angle_home.png | Bin 1534 -> 3883 bytes .../plugins/view_angle/view_angle_left.png | Bin 1428 -> 4023 bytes .../plugins/view_angle/view_angle_right.png | Bin 1662 -> 4194 bytes src/gui/plugins/view_angle/view_angle_top.png | Bin 1891 -> 4281 bytes 7 files changed, 0 insertions(+), 0 deletions(-) diff --git a/src/gui/plugins/view_angle/view_angle_back.png b/src/gui/plugins/view_angle/view_angle_back.png index 71ea99f408d740d3975aa9e37b826e8d252436ce..a2a447f09abfafc2144c437772ba5c2250e8e660 100644 GIT binary patch literal 4026 zcmcIn3s4hh9uLSvKPOTcf#Ot(jRsm7&>f@@8Qmv!ToK>%9ea?8NV|#bs28h~`>hzIGHebH~ z|NB3F-|zqbzO0-%V`^;luxOP^6`PZ7&I8|e<i@bd(xNqy%)s~QqGlX{ju z7s+*H@})v{jl}2I%qU=M%2^|)o-`4fP)z~@4qm3AYKPtFCaX>AfL#)dm1(US3aH5C zCiN7>A!N;+31x~B4-shy%p!;mN;jsV1dbDk2GSuqM2qOPs18O662VC{9qM_hfj5b> zk$L8<9$(;>NnI+-E>f$ls;Ww>!qP-(o)$G4jao#f)#+fM0lODCWx5)6y2tcdF!OF! z5?rz%Iw8d(&4?AUNev?HPQl>{nsvH+U;=I)&_#o~u2NAJ-KAn5ri0>V8~|u@bAvvf8;ipcbm5jQl^~5CK%T4ZE?D5=wRyZ- ztdLmVQVGHw)0>T3&f}lp`4Y>4dT_BU*!ozjNS;ZGuNL}HRU|=G7nv#Xv@A*mqG<2s z&dgpEAsw2ggU033tl(5|9j|23vxGO(GH+5VRDx0PHWr`;5=Thf@H&E$2-2;ZD{_Ku z!LzD5v_OZFdW^)LRRuieXqkSYGRKlOQF72=7X$}AkJq}K^VCpqZ^=y2E=s^Lhz@&t zJ|{DCrX<<~I}o_@re;7nmP`UQ5(KPELj&RF=8`#1w@f=(KF4fQgIv=Dfg=f?uo-Pg zI*juK4&xkZgbf@A%F1X!j0POn)1XWhWWai}$W|!4RMvNwC?~SO#*^?^1m_r@wZRNQ zU@(!6<1k}na2R0-J;9|jD2p3!bcalj&L&>2}CBVZ%Xb1<%FX%H0{ zF$hO648a=oHk%q!h(Q7~AS7BTMUxt&8kn>y1hrRmPZ|;BrA3uzkG%K=@+aa#rvUas zr-l@2b;F+zx*UKR_zKL;6smc<)hqyH+}%MSAjc=7;va~VmKT6CTW|w%F6e1W`TYEz zkzIfSg-FtDcLJ}4JRY2k z+MkgQjk0>oz!_nJKn*aCFnXBAK*zEnG(s@A9^>df(s@po`qk56U&w+NY`nsaAW`~; zjpHTZDIPq{wO|NPfOWr&zZbIZy;u^tcgGO2vK@T z0EVY7biGsHmZ%Ja*HiE#c){hJpmrs2ef?ea!&gaHpjLwz=iPt+WkNE2?XJ*SB=j7YVEUtKOL2B{o zyLa!t+69$|If^)aNmOS_bIUC#)=YW?D!|FZKx-eo#D(AVF~de@JxFJ$kP zEZ)*;n%ysZgHfa(Pt-~}|+RspHYquS}pQwR7^L-lYp?bbu7ww5ZKGo;7cDCK89z}Q}kN3CE z)of|I&j^wEb=P8=qBVP{UA{%C{Dy6@(~~_nsZ{^RwL3ed#OZpEgp9E6t^cMiFM4~- zaSQTW>#;VOX^GfAcv@7GQ?tHJX0JtHb=RVsqP%mc?Y=oGtYKZ^iLstrREl3$*W9@; z@dRE}hD2*h+Q<3w>fWL+^v`NYj?G%h4Qj0$G^gmB^#P4oDzyC(@aKn4P z?Gtadg?W>^hSFCH%kQnCzI&zcs&-#xNq7o%?~64>|Clx*Z|~9gt}VyTk9sucVP$!n zz2n2M#*TdvC$coDz8Y&$?S)mA5YIBpKpW-}kVH)$a?wA%-v8wx%~DH5LftvraL;%j zZXHYQrJ7aK8u_FX$(l=4XxD3tZKIoSB=&237~WB)*+dol->qv|u`TA^gMZ)VwPv-= zIeI3*o-M!H*WrlkakhgsWfDCy9uMaMo zi-g?7Cb7F$8OQe<>^s!5dR^r7As!tv%D=DvnpnnL;9tq7OLW5{knt` zVMS@k75|yq=EKJZB!qf2O*!7_)K=>A+UCwTViN`x4QlcwB<((WWaA&(Gdgxfrg)DI z$+w=N4u`cauZ@q)TA3W4P*-6H^NvHxG>N{=GyUqenveWk+p(>TrFPv;KiB>+IsSn4 z#=m4@D^@{nI<<4zj1*bD^=idm$_5uDoexPe3`sN=C0WOmCrrM$!GG;fU(cV_?C^do qoGktGh))*n?W!G}epqejnp8YvGaU2w{#TTL*EyCM=DitI{r>^(wvFxp literal 1467 zcmb_ci#L>M82=12hL411+*-4BHi{v-XtN`SIO~#Dna1Zj!!TilWn#u)^p(YwTdg7Y zj#L;KwmC&%rWz^Hmb;dw+K7y$TtoJo{Tuc@@AE$Ad7j_z_q@+J?|HMmkN>Q#X{-qV zfVR7v%SpsXD-DZ5&OC;158~7koZZP-WTjxkvXEFK&do0Y!4D}-#d&ur8%Y|mTp^ZE zEQ6I45+4pEB_&x$#xN7;A#vf>vGJ!%XGz8Yfd0|l#fi)=Q;hX615X*I&zlpxqV$cU z^!G$W`(HR&Sd9(JD%G$q8E%c68ZDRmZvsx!ojI_{uTz~AX-)1KY+~GtR;I+b??RRN(j6ApnoBq#+AjP<;`Q|E^=F}8L21jgKAXY3{I*I%$W&lEQP)qp{2^p9 z_ICU4NmN}M*=L*-rJ{5)SVH4}_=Evb@E$>901>Np18NTzeGe3et|rT1zI0o+F9uJ> zBH3n9)lP&`n2pAzBiLx-ZlhyODW_;o*@!~DCg_3kAyNw=ZxlkU>x4}assRd229WG- z;zvCMyQ8TJL=-YQVHlxYk-#XWdkAkqpyt`=?-1EvjKK;3X=W&*=^#)Uj6NelboB9m zBgMUT#ICZo%hFNQ5w$^~xDitpsYPS5Q*PPXtaBxkV=o8i-q!roM=j@Tfc_GpSp6Jf z{^q(CK=sf|WmPI6Wykf;qQ|sT<&%Nb(tZN->fHVdF|2{FJ)6HBQ8LjPY%ElhMAL)UGt5g$+}oWuq!OVt=?DF>8`uUT06_lu<+lbBl}GgsA;y zi;$(e;ulw@D}Qi5#fWXVvibrrAN#(ez6gl+j0K+7_tSaHpS3m&er__Hv&*%F8A9@vBLY9Nz|zPiMG zzuH@nHB-USq&ck=^8JKUskvthP|()Ino!e0!nF#=8?7=pPRS~iwjTWgJx}_&x`SfD z;KA1*(|X3G5pjE3V_k4raTIcS-$g@wQq z1@iv`Z^N_NPo8KBoQ3X$dSyO@dnriOGJ%MXFumB}+&g!@kl&#C?R=;>bikP|9aj#G z1Mzp%yC1b0Mc3WqW5Cf$t@-S=gbw;SNBlcTv^-)NAVJITiI>==Ycs*`2UZnrDKP_g z3EhEtC@>KY-$bcOPOF^G7DtF^lgwdM+|j6fxBI_I0+!pRnFrPl1mZ-1of~B!ujz+v o89vEbgNf;p^X6%o8x-ND3WVFLWhTcqAs;Q^?t0wiwlfX>7a7x=1poj5 diff --git a/src/gui/plugins/view_angle/view_angle_bottom.png b/src/gui/plugins/view_angle/view_angle_bottom.png index 29e6d836cd53d21271ed5d155a6c9dd4c4eec3ac..a94bffc10734613b4596dfea46c9af6bf635eebc 100644 GIT binary patch literal 4033 zcmcIn3se(V8V(q#^3bA!Y^~jCv{X%o%uJFYnL>RK6ciLg!~wO=8%C2%HVF`PJr&SZ z@WGz7&EneKqpr3VDUH_pD76i!?5<+1_~_QE=d^ZpkB@^|tAcyny%Qi}4^+>#%}M5Q z|Ns7v?|%P(Z>n-;PK$|rE>fXT#AIfeE#PjGe}f{xwMLkG9NY#wGxFU){)PMtn=)>b zSD}cC6s@F(%+4ZM$(}@W62m8X?M|SrP^3)sI%#$>?|~S;P;{iK+8aMrK_Zu`nrp~L zvYlysk(jZ>#pf=WX=RrzW=))G;;T@KmjDLryoZLocALXZcvDqDy99WahqWpwsNz|i zs+uf2gvjh1C{1$l5T1m z#V(dlF9BhW>B+|JvG9-Ze2VEnJv7-P3jNHLC66V=d&PcKWl2cYNu;@W+9SEFl4R@Q zPEHSs5QZjU(70@x6&*6J6ibD#0lDnyjdi&?AK2s76o%LAq44B~BE| z9#_RsD~1vVJ)y@RQw2QcXb=5FWsW5T$z`X(Du{Nvkk>jLg(@htwnUm_lU%?th)&mg zJTomV$0Z4(4G7$pX;Yxg^fVkb;W&&Xp}}yovx!WH+e158KGU440=XuMB1af#hGTFV zgK6HNgY}rs1k)&j!v-E@Q9Up~qxzotW{EA9c`48DDp5{ifsIGu2{>*v>P<9EvkVO< zGkRbR(HUR?*YQSL&mt^__gI_d5ox3jw}QQ9jy!!ELTW5=CM=Rk=goT&65h6GwB!(rVXqBE_x%(FpK~rD2ie_)Wjw82AS2eHR-2rA#yJX!qDqL z*E0l8iSlFUcnV%Z2VC9(YS#shub1zi{aT?=F32=bwtCOqxNu^Ib@qtBtw8*ZF>m1O zK7FrsTm0RZt@mHwQ#3qjtG)WKJE!j$981?tgv7YmwQx1|U{`g)8$$WpLPbPGvuE00 zZeH%Zxaq;g#(QtM+f&!HGlE-tMc0nDwr(ojQSjai-(0U+MXAZ{mKRUnx#M}i$YQ;G zcS2R<*rvlRpH<=JISmcNO#VUjFP&Wb&N5%%=(Yf}z8-t?l>VkB!n}!V8e4z-^PM}d zoANGbGM1-PG0Jz8?E#hls!%>8eq~%r`)G26FD1(AH)?*}^o{@T%U_~9B77^-!|P*x zv#53c&zr3N--hKjO&OSbjGZ z7Z(++8R}b1mH8(HZZijzzLCd_wL>&>10L#E15d5|S9oobhNXyIwr5UN@ye`Z-*M`r zU3)4w26o4_Dt&oKE{RucY;KDXh8@F^4P-$ei~Uk5Jf}`hQ2Jo%S@J+&v)`tuY(5$t zQI$SAdYF26fXVk@0>tyJ}&RX^fdQ_54;5*y*l*Z!^*}>GhSRX z@FZ%Xz9;wnao@B*jr{M$l!7CRmhSJk@=&vP>iXBq=P&*6pWg{f7TsRxf5;r)j*r2p z(|#nl;Ij`mhtFtMg-wl%8c-h_PbBb~A|y^@MXr*+rxstj;GRGhQL$vyY5(Rx8?|Nm zmlXrU&qilGR8|tcOn*H|Q8=?PeBP*QN7oJv7u3GN{*TF) zCRfD;o6n~WLY4K76-Uv)#}L;vYIr!~2)i zS1o*%I#NzEUiH4D{T)EV_;ChB*&!q*nBX-m$RA}E? z6Fpizq(1XbRr%FUvhfhK@~h#0yTI=qZ)}S^|Jtf|&;RFvBB5|vitrprq z1Oi!4r5vDvm|_T|F*uf<2>%lVqYNJ^9SOD^kpc2Y4FUDpS;++#H)r}X zGDA{NWO8EC;~^Xl$0g|$D za8Vim2>!)c-kpI4!kA@A-S!@Cxs7M#a!Pw;g+-HtO}m;m|0J=|uk=2BlF0D7!xSbq z9;rax(%iGjTG0N`1~e0wI(6N;APR?3maUG?+C0{obCuU|0UNYdZ!Vf@4B|o6VtH@D zkfLDuC@cxX?X_rz6c$FXYK=(nd0|vQLB|GYperjIFske^B^QU~$IF;DY4rZW&_ly@=mGTj+CN-~dSN`PWQ zbb!SFUKm4LgWkADl|H3}K@FgS4KM{$AB@qS{9R>@$M6eAw;9qXKmorN`;e#NUs9Sq z3pK)CL4vDwfM`1?!4x6v3qWoney7DDS!6uZyAX76M59r#5PbM`Mlb}FKJDS#fYK>A znge&)qMk5^3)~9WEbZx17LNL@eRL_i`7k8G1c|Oth~;M$J03Wb*9vv^ z*sIIwpSJzFhjB44pxx9RFTYqo#GtS(6N9=<3%Nt5?KAR)z3R2s@EUkOJoP;{QrN45 zZ`sjWj=Yn_e0Ho-l$#*wxcVxR&~r|MX&#YMs#-5U<}j02X+Yoq-chl6jLH)dc{Hl} z3^4n7-C<&K4hO$hBm$4rtVl_BugRh4t}Me6H82DW76A0a;khigZ|)Di4iC^+cUMex zLHc{qX7eXx{H7uN>@KWEj~#oDt4h;%y)#%Y%+78#kjv#gQ#W?@P-P3(o~ z?J&)ZR^9#)b?*|ha6%}M0Jn3h$@Py^u>9|evnx&|6U|tU-1btT;BJ>PSZp@ZLU>>9 zIdM}X6l@khlzW}u=Q_3*dxc0lBD>V^%gu80g#MLc#8io)0$Z7=N+?j*MhHTG#F~+5 zGQ>y^T{wO2meDh_B82LKf#V>Cq8{_#`8hg<(TwMCU^~IZUt3K?vxm02(9vdOlY#DX?A4z9!UvFW(7Xrt{JW+ zvndXWuXW#B{mQJDZ!O*AlrqxuejsvO({<)rp0wp#!4p zI(?kvc;w6Tk7Kx^*${6gl>T9*r&}Vw?E2X@X_l|#FAo6rZyH|sz_dgomvPPqeYiz| zJd0d1+tAiIsS%bH6GCTwUCUuZ-9b6)ZkILbA%P*V7SowVYw){;P<;arNPU?6{{Y&= Bxw`-W diff --git a/src/gui/plugins/view_angle/view_angle_front.png b/src/gui/plugins/view_angle/view_angle_front.png index 05ec1e2d61203bd7bba5b34b0f780e9ae655224d..a3487843edd82cc02c3335632042c4df08ee1669 100644 GIT binary patch literal 3852 zcmcIn4R8}>8r~FIN(<;vS}L60x+>B(o9s{ib~PaVK_U&5{t@7SY<4&8(j=SiZrc=3 zCKP)ry^b?*)`G|gh)T^!>gd#-ho)Rx<|sV|PvzHhv?DOwA&1WOen!fDo1~#Qt!4Dg zG`nBE_x;|V=X>7w`}$nTipOWB%}awIXr^shVJUcf)Ng7Ecs}o5JqTXY{ma(KKz>^N zYVsGp6o8=gG@;y~IPAqVD|&SdC%SlD!0QLv5cKHcfS+M&cm;OxRf5loTzmgR1Qs|e zvf60J?EV72T3EJO;>$L#C}%g+#8Sz=}le(qODk>k&Ar zqSRQCC8|T%VK0FTM2Uw@It*nojDXFQ4mTMLCQJ(x7=h_AqaG(v+(csr8aKo74+6YN zoSQB!TpITUep!)fMe);meM3Wou7T8vQk5R3C`ykJdV)ZK1}ZoD6efWB&tE5bqRu&1&wF?; z?^9%;izjsb)uJNG)#3!E6XM$(0BG&@gpYA!@p=<3WTmJcq!9;XTy43$(a-Bkd0DKJ zSiYzpg!#Z|HnLL6-@@|_mIL*~VnuLIuvV4amJ}ZlCQwx+2~|H`An}YMO68*H8RbsN zD2gzF>j-$EonZx^iffLVMSKZg$SAxOQK^LD;EyWDEwlln4VF9%r!g$1Y8N@d-FUky zftM3FZ8QSy+f)IMIYwb7RpwaQElOSn?1JEBs(8KMSB1cdy`>98k0=4hAUbmFyse<1 zL=xSC2MFZS$Ma!ZQGp4kOeU1j;n8sIcG~8X6~@Q%wn8fca@7d}M-vu;H{dLRTFfkl z8jL)TQj~>4NepMrCXRF)Im_t!LXoXgd8w|Cl_)2&z{aicEG)%xMiN6Q3s0bKi-AEI z&h0`86JzF$X4cG-?on$iB>{8^#xvHc8WjgDvKE43dD4VZJkNosSO&FlVC2F$lgnjd zEk-x6qY{G#We3n(v9!mZw%Fy-bh+IUD0msf@3Uk30e#Ekv4O zV+pV-jd>1eZ7y1ch3aJkO}?BO#Kgo#DO!yg_CB~=r)q5 zfhCNn3-A?ionk2y=`xdMP*f9u1j^b#&<1j}tbZIxaqDa~EiMa-a~wvx4CALWPM7-G(_trN!6X~6aw9>MiDBb-Nf^U}v0O`p z07qH(|M52|>+Y<>j>o#6d7Jd=%_Y`$^xyADvEPL;ESIV^8a>?U@p{jl@(`T%G&nFO zIYKbr#Zjb-Lm4CM1`mS;b-7$_6vJ_xAaRNV2Z_pR)tdNIj}Wz&L}3_np&Ok7w?uWA zxSoO^i3=|81GOuG>ucYU=Jz3J${V)ACFOy0S3k4YWUQLge?5QwdviBF77{X=n_Bj_ zY)RgD<D(RR=xh0?xog)zrXydz2mjnzuj=A zZqu^H>JEFI^M1!8AAh@j_8f4;J*yO=!LmuoCd&x*{m?^*xZcGf=FoEE-2 zRB>}h2?gGVy6>Kr{>N{+R?pJT$g|7^@i;1`wj3>;lJ!i5F>KLhI&F@Mq~%9vPa}Ie z(%PrDEo{%J%#0Lw_C`K(zHqO0W?QObZHU-*u+KGZpsAuVtaXH(YdVjowq>@=)ZSHj zHu8SKAz;BGLX}bhKS(Vqf&}H>X}G<6?+JLTf+H>;hx&QP$sKX-O}P3VI27mgy$P~>=We{;oDOcy%g+~YXc zW9cNe*0Ms%Q2!G%7i>M4S)7!Y**>RjDVC#UF`L%w+~HX2)Pxp)Y~9q{y?60Q`qs{e z*X`_mV(Nj`*AFeqIyv}Y6Q5K$Wkq#O(~BG#-ZuQn>BXO(e2TpGoif-vyno(1^FI9V z{DHrQk0^7xHlCYxT0iyt^PA4By|5cvx9YC?Gk^H^^~*i?9PVgcnIF{5a6(hEBTx$V zqlYK#)2`+n%W#Tstj>RGTKkfre+tL5G8bta#oH=xTuD{?LX!=#Hh&#yqTB6ETVdy?8Q$69T0 zdQ)=vgVL4-$27%|HZLnOHFCM}YpyRTn*_TR#GB4WlCm?}Q7{ais_i<&&UZla4EOwW z=d7M2K(!sM;x0&rE~bHr$gf-22XzCl5T6ejYK-UDVg`r!_ZPzv|i@-XGBo`F_3cIksr)VA(Z|;gd%? z_I)wjyQ*Q=%m4aZFe)GApyr!*K*Gl#ORa?=D!ng9BP5%SR Cy*8cz literal 1261 zcmeAS@N?(olHy`uVBq!ia0vp^IUvlz1|<8_!p{OJmSQK*5Dp-y;YjHK@;M7UB8!3Q zuY)k7lg8`{prB-lYeY$Kep*R+Vo@qXd3m{BW?pu2a$-TMUVc&f>~}U&K!dV8T^vIy z=DfYTKR-HDqW$CX!b?*+wryeJWZ^i%mPCVtIzZQunQ8oAMvgBasQhehfluj zbyE(pTYFT_;cB++H-^tMZ&p5tO)&nZ(^(?@lB3D<7{t*{X6t%x3exqH}v?(-&3Dyy<;ltLt_5`pbsxrQAO>-?@C8 zb;#;)({Uv&pw80=`VG^&LOH`;CJXYe;W=&jy>v}wQdry87aKd6)O6xybvhV;RICmM zkDAVXtq1`DpNM^-8x;g*Y^d?wpuhm4HZDjuNc?&0Koj4=mZ#a=+*VA&)7JayykGz- z-L`Q-Do}FQfhIAa_e#zR=elNp%l@u3uUzcUIO#v?o&OHrd-6yu*xS{4 zTiF)-p2B-tuJMg4U#V_5BNUOwsk517S|rnHoyOE@2aLQEW|A-L`9^+PRP$MOxj9yU zj-2_X+*?%lkDW<7JGZv#|5@=xXCLl1-Knr)QdRTe`i9?KhqE2Jxw*B!Dt!nktYrU@ zP}F+BE6Vy$HvbHrjGFtF-(y!4&%UYpp!d;-@CQxB@A|7Zw@SI_u0QaL$Ks$wcJ(IN z4=RnSL83YW5kjFynHpW!^NDfjWTkzxGTq>ia8YZ6-EuadfY<7z#sf{}?O&xIpO3T- z&DY=1Ff}39`uV!+JNX+~Po0TdtO!))!FnxK3aHQum}mqdmT&E4WqPe+yxW7je)BWo z2zJqk>5aZoN0=J7-jlh;du;yZsDnUu6z8>V#qXw@ombp2jjNHBDO=UJdMZPN!iHm_ z5#bySK!K199f2FCjvioYTpOYTH2CeAH==19^;!-wHC|nH;8&C3HNE6D^PSHrZ0G_y zs{I&KW2ly>P6UJ5of}r7RTEl(sY0yb?p>ScWbIY|Yvd zt-btEUx-Q6ww0mHw(F;v*c86X|MN=JgN1v6xm0g`p>cK7$0!xkXrl;&-;;K5{}ITZ z;PQJONB-UZ*Y}Kh4xIVbQyw0>PxI0L#j(%t+`ZxKW6r$nlK=d}Mz7-)Hcx!~{_7qU QV9~_j>FVdQ&MBb@0FuTnW&i*H diff --git a/src/gui/plugins/view_angle/view_angle_home.png b/src/gui/plugins/view_angle/view_angle_home.png index 80feee40e2e47d90cea313714953572c3e1b9ac2..b1384f2232b93cbd9f5ac9dd7bfed5d7a32b543d 100644 GIT binary patch literal 3883 zcmcIn3se(V8s;S^;DcKAXtmCUvsI5wGLy$7Ga5M>P^bnerWi`qOlEGvNRk;d0fN*P zwN|Mj?Xl>wdaUanwG|%$AJC%P^x&gKt1H$=V|^{FxVjwntX=ik*6y7IBKAP>Y_}P1 zGWY)f{h#0e-%CYy){KGiqv9hXA_it=q~*Y0hcx=f!tW~E+^^x!03jn!g!GHjh@3Wl zlQ$wFA)YgtJ!a!9is7Adn&quP?sW=~J0fCos#l<)ysl%DflieD`ZHJ#Z#!4 zO_dZPW@9#D;N1WriQ@9rC{K%j-H*2GE z(x!Lnf-}9Wz~d1pg`%XSL|&qj^KQEWCrMI)DHTd33OP`*)a9YQs7p-ll8^>O#?1*H zj&~uFMB2(1dGs=9X~+eq5EknaJHrG6rts2&0+(ZwOF>4K3G)d>Zbwi#%P4>YIDyL} zLS8(~D-`e^UM%2y5gjH!r2vN3XbkJ<(H5sOtU~mp7ehBX1JWb6Xet$eA_s_kk(&YO z#n8;;E^kCn4tNsJXV?ze!<#*vt(UzLEN3fynpKIL zlsKg!AnKlCg*awu58Wp-%TPAn?WAEAI45lf3c+QUA>rIo2HwHDp<-yAs{4AT!I16d zZJYxV#GDz^kj!)gfs+J*D&=_4T%(c7bcr6?#emE-y$t#)=Qx(qVHyp_vKVS5)Fi5A zX%$M+1db9ajasAB0^G`guKj5|QzYS1+8-)WmS>=hC+1lJ$!Jw78%k>#H3~Fp93>eI ziIOa?rU{1BDOE(5wApSBb_v?iU8-ai3nel-CCLC4fsz2Qs9M9&sE&niR*WUAR)W!K zY&IDp0fT~Kph>h;ih3DzHMnS&0O}|TEs~h@QQ*>dCq1tZ`V;c2E)M2GDMKV^g~C4v zb~zYks4KXZ&3S>toW{Y(h#?~|U3XI6FGy0$ld6)+;6w<{($1zd2Q2D*b8two5Gk4o zIlxFT2CS@end>2q&la$d*pdPOL-i}*4zY>6%~L|V!Bjhp?=zH-qF3{IS21vRb3mZo zH0+6-F{7p|WaKT3A%Q1PPY4T1lx@U1j~h1*uayQ$V}y0G^DB-{6jo&}y^{ zz)^@9qxMCkpyVyo8M~P>I+fn?oBZcN^p;%6rYBYGbQ$6*bXT>2r?J0O* z^l^k>z{-*;D~r+^2A(4twFGFZ4aIOASE_K5)dG!Fq>?oLw;mxDkX6SamzrsmmZReqo~zzA@j$JiF=JuU$g{_`P1xby zmU8^d7EWB#BpfFnh+A&eKinI8b;G@%F;z$D)wU&Vv$C>IXWsna4>2kI;A5EppU9c; zNidIk-uLqM9M7d?8+?bqKa=x`>G9_lb43ZB*RFL8Ff&b!2~`I!?HGQ#WX`aHx~xWF zv48Cp|Cya5=O-VzdbD(XYkTZka_OW+4*#Q=cZ?4Ye#N|1E=FB2V4L6726T@XGz=D_ zF97WIss#aEvGb$r%gT!)6Hor@wUt{J{t$N=OSO!NYC3r7V!z#izZ}i*2O^qs4!3}h z1A|&8q{N%oSsG$f9}KBE)KNRdQdzQfcJ`dI7k9?&-hKbZXXVuw^UX=VxdU!65d=eslSx;ENWKh{TE{Jx~tr5kHU)E?k1=4BhA&zf2r{?uk^crG<|>&>fQ z?Ap7W#?c=ahC+^?L+Ll=NVD(pn$K=i0l9brA--`6#qzr&ZZsy=+AFh;j5*glqV3?Phdc7_Qg!MT z<5Z{i*6(KuD|ATbx5-neC->xZ?f3)ee7T=(W0&9@uO z_3h_NH|N`5S}82rcc}m5RjIr94I`VUw{T^S<|W4hn!t>*Pj@o%Tw7bm8vW~bqW(tm z=#TaUmS2oMcgjA#>~7rtvU^xs-j$&+W21a^pC!Ybl=++Q+=3aBMkP#}G-{%AZx<6u2S?G0xfhl?)nPP~ z+?E`ol;+f7ij|HLO3`xM&Y8}6&R^&K=lguW@B6&(_j&*L+|k*VDuGKw6P+>sFi~W} zPUc_MRRuumNv?rOe&nd6RANFTC^a<|8G9x!F@hK$i6kdPSADeC0D;6aFfNDu)2f$h zg7Wc^YJ)(Os~d};X{PEU2j6P8AZNpGA%jV>7d#V9>Pe{idgY&CE+H{5iV9;oje_U& zob~j`rfbyKe<+XylNLFV+gXZF2M5~o(WWLIX+37&RVtD~*0 zJxXLGzS>f+tLd7eoCCvinEfzffqb8Weh$J7=2awD_HRP#^#b(vfRMy@=AXfYq}O0y z7HOJY>1AWZ@E}#$6FeEy5>|a`5DshBN1BFcg?;&)Obaz1pFTn`iub=T37AlAXj!He z*f1YDlT5Yra@_7=m?Q`j6_{H08Qx>PR0+yW#FAM>Kv>D5*N;n@)MOT2Jl>iKUE>NF z!HRb(-iO+fuE9(pNb}EYO8mIVVlk|T#;pS#$P)kDi5}|R+ry7}gLRw+P5|2=fEK8V zsqZ80mFIa*bM~V5d);uJ@;LW6b-1nd;5W|sGicnNuQ*rv`jm%&P)?KDU!;Ker4?x zJH!@m!6k33SoxJ~E2t5oNy2_g)_XMXPTcBm;Z(5!C)W9d<||aWGP>7LR{KbsLleCq zhqg6a$8#7-CyV--Oohx$qOOl-M)(YCa&WW?Ig`%O8iL~NzN0z2` z9`l(EG_9PZOz?bDlgs>2?!um8_Y2=9C;N8npS%ek^w&nq%YZ-b%P{J=eo4l-rn1!m zk_HqGWS9)-nLM@vpKdlLAo}v~R62y7tVLRF5x?)vmB2w40?U^cr~*m>4t}8UoW%XZ zT=N>Jk=awB3tybiJF1`-L4wSBr8kf$zI`ODepRDQ9ceJ4x|kY**z#X}=qy^dw7v9e ze^vtlYDdZCSYSF3?^U8U^!SndtAOvk_{f@8xmj#P?ZD~W3CC>G6e(2DA?`iyY8BGz z!UcZOU@Jv!Wb&2yEYC5i$`*}s#L$Sw0i~!6@Ur#(YotWaQHNa=1F9=++hKVYMr0R@ z;eE0cy^l#RP*>nvj+^iDJNoN(#XTs+jb3e&7|x!((%TLRSr{>hd5E_FB=lnpk8sJH zYFo?Q!4_C9+YMcbZ1z~sUzA48A)DJO4bQaeq^KTCTZbEtM75$<8d*wKNrrqCLQ?hd zPe4>#h+SOgJJWf;)}TMHhn8X187CULLZB*Or=&9MXtwuB!EZd8S2?4XqW;5_;u!eAAE$)YVhbnaVU&{AxHG*H)7v} zV6>{kp0KpAdd5qRBIhVyhwx>zjR1#$Xgy-j#HMso$Sn*2=L#uvxY`2?M8+l#2?lp> zxYyUw3+LHR5>XJ@Qpvzmf@TJ_r1U5GFy7@=aC{R37={*gfBni`9`jgYi?Q@_UOuT6 zdKb#~eYo+ZxHy-YE-7;2aCo>&?sq8E6cqK1zZ245Qm*Fnk0E*e{kOXM)`fR?z`=Y&pC^+h*~c=(aQIdjTrk<494k@!cjfu+!KCH(mSvR^jvbEN}{a uk?c2gND%D%#A!SMK z*j5l*wNk9r-O_`r6}LguMLcTofu{wnt@Ul))3x-d=vueuv|Zh{dxuBF9w?r6_iPTC z+`0dM|HpT~|G$^jdAai!5cqu6y!a&i3AJYwI-&f$_zjpl zYqLip2@m59w2RKkrdYu$V>rPCWFD&>YD*+@p7Pikwgk8k6DZ^N}hf##*lF`Mg z96ZOK3X1uR3I|wNk!xTpN?09-KJ`0fj)#HTS`$cWlb!!kRN=L4ru z=3qgZ8-_V!C>y6MA3VVG5tc)B|6&(!9%Zd4c_=C1;YU#wC4N;qmFfVDOK=zj!7{|1 zyde}3l8}+etQ>~rZ6dBuidhUU0eZ#-l2MUL7y7lLoo9eC~)S_n~P+orK$;?T8)u1qCec694gc1bTKv-Wa^Vqn5&HEIana9Qe`3) z7|XB#Q<_a2rUN*Gky=)xVRZx)nTFQu1-4A&rMP~eL^*+lHXekhVNF`ISxaJCjY@&3 zNhO1sG`Jb#R7%`Tm;lKVV946j4jy(1#xmTh7!?OCvRYEd0)-mJ0ys>mVi`=!!I25) z)FzXf)vC;96cLF*K{GHUMl8i-6sFogNs9!vlnqSkaPcE2#OI*Aa18ka@gf@!_ku(b zky-=rFN9qV!VG=&&*kwRV4?LqM8-J~1g;$}D*Ta1YR#tn8)KgZBf{Wux-PlLq4Gr~kD zG?>Z^*{Nhn6=u@09Hzi^tWK>kX%re*RHJ|d%UVfNO2trF|2&Wet+U09tq8!AQT_|k zAvp%9Aw6V2q6yx#1_u=&*6X z!4KoXaIX17K>Att-|;sl>mIGc{vWnUF5X-Q+K&9k9ckcQKY(SrSfl-iJ2g`8c~l<4 z)1HC{#u!Hk4osX*0goX@#hT$msl`ktlNrMaf*=)yj?(~@$ZFA=@Jo*nv6uA2FziA% zGzD*o;?RFRg)jaKF0jGcb-?TEeS`a3i6m%Yrar~sxpe!}gC$c^Vo%)tz4TVvWU2B{ ze0qJH<>Pzb$1VS1btO`}tGxI{v~$+X*0yyu6V}T*XV1?IkHUI(3i@^1qtKvJne>sX z+&6A_xp`}m`-S6wZC`b8`WHtJ*{}RVefGJ%iJ#{-1}*OF>gu8my9y5I1DjIz6dc}O zpU@b4VZldFFNipM_QOc&xRPAuE&fh|H>JQxEI)_5adc1b{_9cL?%;4X`B&}t`xZ3M z=}l^^*&BQ5jHmK_x~_M+FfZwO`HG-A-_6j-SLgVeyx(8FlK)kdG%Sfe6)27Dp6As{ z)y8`7iolYZC9&KPcVmNO>4}Qp7&*&_y9$H@1#b)<%&`5 zeI}r7<;L)yn1*oUJ}+5)@z~!Z&6ATRH(I5qjQd*is}~qcgWvJZ4^CfoJZeo?*5hj? z)lG{{XqZHQ_lNk$3exX&Z2dtd{9tUGxv}rP>XfywbcFUbADbUEIb2g0WB=;POBr5+ z?^5ODLiuM;6h>G+bD!vLc69%{qPbyz#|M{hChhGxx5&0>-J6l${P~lPtNA<1W?wnI zrR2S;(uu37=C5C-kg~jYvu?ij3A1Cy+oxXkbzH38wKdD~Y_a{o_1D&_C4sR%NeEsU zFwyvPhe;DJw9WsU9$zaol{O{LHEyW6_HAd}t^2#ae*flo%e&iG+f$?6#!2UjK4On- zeJQczb>sctq+b4Gj1>eYGS5%Co$x}1Ly7e>mp+3 zNoRZ0X{oQ>w4gG9Syx@!wL4;4Ra#ir^zKCZ%RO84Qqnu2#l7vZR%K*ENL^4*v~(I| zK}+@i8W5L#@W+f0Q4&gkwS`dR5Uql~=~ za%Lr%A|1E$Xy^I)e88DiU}DPzy2E#@VyeEI@~)|j4$d0iXp`PHrXBepJdruM+T9ns zL5+v@)%DTKeAx^in1mJ-;2Y>AzS`Q2!BWrmHUbhPioRc4wK1kAq(J6vVw(fnR&9K| zXS{R~zM0-vYIbgG_^$BT%={I zb66@9TUJw`;HcRf2AOtRrDo1KH8IWiikb!m19#c}-JiSX-upfG`99})?m72!E;l-A z2f>1D0YMNUY$q)i=po}W!-2grJ^m>W3^OE*ZU#n?*;gmQ**s@w0u$u_Zd|AkO3g74 zB;|*~`El9l`K*+@G>FAwc^>%sATu>3C(ScEFQevd02zX?Hes}2`Z4~S7m=AxX%6!D zi|OG@KSXD_i=BH$Lly60@AZ@)Wl|W2t&=f|(hP-=lKfrl`jLQd`fB=XAFxlZGFxk> zThXU|wtbnSqBJbX_F(UO$@zdglUpsQFzVG4-*e_drM? zBup%9Hl<9;1g6R8E6o|)`g?3YJ~Mm?>4L_98cjt6YO0Oeg@$2pS}cpiem`Vs(3*wU z%C;68>;PLJ+RbOKpN^>iQDd+{a(nc%E59g^x*23g)AICVu5YTEXBC5Zk%|4O${4K2 z{-^5#TZ@JSO2fs?=NYc>Zb)gr@+yu|wn3V!4-|jn>(QRqbv#B5+j+I0YeY)W7gECZ zNLP6Qxr7971;OndoUKTi>*-P~N^TiWw#SokKGX&)YUYwBlKR_{I%kkG`+$Q3W}_oM z%V?TYf3X4P6-k{NFsmPM$iU1Z<2x}vRCf%q0+kNOQm78boU^c(vE@Z+oeK~$9F2M+ zS-pz_|^^+QKg-O$R(ArBhe9oBXJCKJ~=EE*@v~DVQy@eEe`ieSyN5wSGGB%j}f_ifA+FZ zY8MId<40=~*3?kAd@hMaLowu9!t|!86TQ_B3xmFA%f|RRw^8YCboZ+}_aJ=NtvBVP z4aL(Z3E@pnb6b#eo{WsSJb6+Bhs5)>BvOn*B~nUAJUSL{3m)>%5kVcAh{1U%5(g$= zRU8VB<`Cps@4ok`S#+uy1`vaqi@$xnqgT?M?Ie1&-l5DDUOqK^d9CtNjAW^(%d@kf z+FM!|41miM`BZSR1Y_|vL|-Ufl@R*^j`kUVM95XaX?K-AuJ2v#9?`~sQ{}cB_6J7- zvg{>^5%G|Qy*J%BKPxz>a%az=g4xWrTSHPPYGSc5RnaAk-&pcoo}$vfL{*Ze?$gJU z`x+nVtnJj7l?@EuBWs?fEmAYv*zuU~ pwx7XgIu34I=r>L85c~t;A}X{2J$cdB?+o}sp|H>>+O-gb^EajOgIxds diff --git a/src/gui/plugins/view_angle/view_angle_right.png b/src/gui/plugins/view_angle/view_angle_right.png index 31b0dc025e875a70e2089c6cef96dcdce2ddb175..503e37738a72c2fcff39e17fce8087819433dc03 100644 GIT binary patch literal 4194 zcmcIo3v?4z8ctJ6p|w?EZBZ=F1`g0Rlgvz#Niu6d+8`7fDQO!AaF6p$Gd9VDB(!PI zBBb4-<+(iCrMyI>E-M965LO;yf)qtT&Z!6mZ4WAnQY*Ty3aISfY1&Xct#DS&N#=3? z|Nf8fe*b^(No~PnQ&N&1NRr89DS1=PR&aMpzafLcb%p)$li)VgGj)~^$j?f@xSa9p z12S21l2AnYNlQM#iY^t+i43m_xI92xCVO~dz(cd8ydPrt62Wa!Tsiof0unfr;&Gh? zv3PQMhcLC$%NJHYR>W48vPMoZaRT&kfB*(uyq|^wE~nc^1Wbx40od&u-D|#U@5C%|{Br#PFk?ZAYzvwLzMQ1N} z3VKn5FjR#><1I8RxFuXOr7U`;@MhZ2n-mh2U=)0fMW}($B81kEji3aAL{%*!C)g`) zRmIRE3?+1WLZi7w74Vp&{q${>IhL@CUKb5kL2%I}yxQX~Q9!Y^C2~cl=mm~Jbeg{7 zdAYd-UePW%fxu^-k^|*U&c#t9j>DJ=?GD#sA@bZlKka7uJhMpwa#aZeM`&=PmP1(s ztY;7o)*_4nX6ztmT+itlEo#tfb$su9v&hbqcqz?~mMAB(z{bt+Xgg--Ig|!fiECht z)*4|0gKJ^Ep2IN%!r-)C*K2KtR{&jtcJ{R@Ma2P&tN}B!yatDjJP)GMu{3Ppz!QiO zXBeC{=t`aV=6vA z(Zf2sP6KOMOb0VYmV-5jku~BPMz7I>q8b1sP}W+E(8kL8{{yMVI_sd_B|O*})xRPg zhUYL2=Rk>JEJ#O#F`#tyD6D08M9(lfn#I`u)9I&6{qE_ow`IX?7GB~;j3@)c#_?XE z4-fisEfxaQ&AQ*l-)&iUXC1ab*8R@Qq?S%D(YB-hc}I%Ao1<7hD%EKB=1%n2d+wBn zV7Dj0hH;xM1mPLZs9`vm*0FYQ(Si+$VeBx1q9~?8jhvnbTSzn-@z-u4QZMO-q0fP? zcLBKoGh3c z7nc*X7NzdbdGh(oiJ$2&9EmG_@Re2VV+xWMR}UYz^U%5f98D=oeYGg*gN5;1wm=2h z9rEBJ!`xv(c@FmRn~%Q3b!}|l*l?*~ewnidF_z2@oUG|r%+o+ikcZ} zO-)Nk9;D2&t&417gv2G)b+(X!oE`ayX}njds>efPNFjcDRbzrO)3z?Wipfk|9jr@3 z?kA^3IJz+|Kdl}^8ps!`j~}(l$BulPL(Y+{ks_)g=|%bUthHIn;gKRbFTSvre_-u2 zWhV7fbH2QAS>1^I#QIE%2n`E2{zTU<&p z<`7afi5^-#iJ{}Gj}DW69O~Gey63y6+`A9|G*Py%{eu;MBcG?fIC=LhjsNQpE^iK* z!@CE)ysshnW#>KQ%*fN*UUQ$0ym$P)mc4bQBhP;K;(`4)URv>?yfpD_iKXk}`If!w zJAFG%Pdurew+&5S^3J&L^JVWR2R0{8{M@lASw0&1ZNAep+k9vE%{%c=nM&$Z_V`e8 z^&4q3tDCznSWNF9A zLqD0$z8?yN&o4{@QtQE|hF|?Mj(Q{1*s&se`2G(4w_OvPmNnvIwNzUOir7MnHt0x4 z7-1#_(WYy)&mVq7`3H(@hQjq5micb%zfn(Kpw>3~tI?+2&xtD%k``r5AJ=BRa%@)F z9t618Yabk?}J?gH`1q-g4 z&b)AbV~zRP))eK1^t(=zS&_62mQz1{`0mQ)mxB$@HYP3I(IhOmc$Oq*hx1#kamQ?D z3SaY##p}Ju>SnGQer5fpt2KLSLu;xMD3|`LW~()v)_$@O3#|z@#!XKnTiSng973+n z9$Y^x^fGl^w*8ekqn4+8TSHr`8;53RwjEksflRnQs&j7F@*UW*F)2%5Ux#O84;?XQ z*7v3avNhcL?0xCZj*~xLT9yiL53iEf+nNj@@+ZYFHegLhsW`G-h%8RBm0{l>YCdFb zGE>4Ei{-YmJ>{=%scdSaaH_Vdu6_BR2piz(9Kf%)+?TqnbIFl_rRzgS!uB5scSXxe zdy^`I9X5DR%JvL$|E_PuU8Lhg%NmuEMp8Q)Qpg=Z@1Q$}9vVylMH!bp#JO)lXUY}5 zL3wZJ<9*E6RQiH1_gk};S2488=4*DKdb#qFv#we&pCA<_mS-fYCqX^amOa?;NioqyH8Jhh%)Zn8TZ18 eXU9fD9dQpHA@obPF%zVJ0rDn4X5N`YRs9cF_w2y{ literal 1662 zcmb_di$Bv{7+;$qiz2pKN>ZqPsFzG3O>T3mX7o$9Etg!%jAcY`+FqGAwd9&n>oTQH zwj^|6E+Z5rm(;923Asc`&E+-kZ*Tv?d(L^z^Z7pKIp_JF^PKZJX?uO$wY9KXFc?gm z;Ne1q^a+({szW^|bpK08sl_@INSaVd(hO!pcyYAHfmq1DM^@esla0$P7?b|{rbkCWY6L|$)(A*360Z&3QrmF~ zj&fF84jjHCTDx8a^-#_*6%_M)An1Ayc`|u%j^!o*G=t*ZY+#;J!3ZEs7m8;p;vpfY zt949Mh{bU|R6aDdFdT?iar=~v)P~4lFu+{|6wZ!<*M@wh+9>$`QZ>;%$tsB>zq4Ai zCreR7WlvYuK3ZhP)&W-%> zY2482rmZn0dBg~L1C84}ZIDNdT$~s3zc=ZzKfywsjr{6u^s%v)i+owp*J67ElM8o? z)QwO|AON~NyCueFe^8*E9a&dsO*@2hY^eKoi=`Z#Z@qpDF&I=Bng9+Pek-gUm_k^= zr+~hB)QS^His)EBR+pf?nhSpUptV;`9@vXPiD2FSypMKmuB_3O^%`Ev#2;8)X2P@L zncgA!=)va`p0EvM8LeQB^&y=l)ou+wLXD^-yfG#eFU}pI8uv0PLvSH_0*$oNqegVOxA>sCI#oT}z8B3_CDI(Yv#^+SLAnZ+eES9^$g1ju3$ zGU=3Uc88JJEYs?aCxNeI9tAI6NLDV?47XmfQW1Xe#3ac zCfqA?D$%O|aBht)ssLAhIWG>4FzQ>?)t@liK=j-IUb~Mq#Jw$fx#Ln<@M&GaL4>K) eX@+V9j5-;fRJP){!$#0w0VBBjy4-grGyett#0o_K diff --git a/src/gui/plugins/view_angle/view_angle_top.png b/src/gui/plugins/view_angle/view_angle_top.png index ad30618e88859fc24212c3c63e799b252396f92e..23b2e3207de3159c3806397d16884d0adee7cabf 100644 GIT binary patch literal 4281 zcmcIo4OkS_8eRxQA+bORwY=MMMUWkKX8(6&HRLA9((~*<{xSdcTN3+h zg+LGz%;aDWOqYd{tR;bXyC24MM8$sidHCe zu+ElD7c%Kij?Q*2%^{t|q=phLUL;JcK!E`Z?I45|7PHlkR%k_DyC@j*(-M);tKulu zijsJTLQJ<@n9OptP?-QjBn(T1Dop~Sl*^T{SSW?1umn~}5GjNxQCN;5D&goy1iW#S z3Du{hjrsy_T2Z0HVM8U7^78V8a#;e)6-W?`Mk9fx5~&md8j!ux>L4m0t37(mLJDms zImYH-SgVk?NEq2thgJk49ZA7r^O?2UM_~ehNh%1N1WADTl)Q=*>C>~7a%Qh{ij>f1 z+Cp0$cA$&+bZv#KgS8j3lbH62Z*Tyh)#-dbCXB^m@wu=&Qp-RZqkv4PZO^H+(Gopv zXG=MfPAvmrMvrAfagF1%7+pfA5Dr=^;;957;7^l-s8KnL%GL2Og2M2Ks*a@? zQ{|1SQY1%;pb9l$-3_XM#}wfpZmLX?sEOq)1lR?}LKM&vo3%hB^zAL0%$ivaI0n(l z#?NOYCokt%6JrJfyZ-(q!i>~pC8AL(A!!2Q4Ogc_Gpu$8VI}E|6s-v4n!qp=O2Z1J zhE}Q}LTZ#ka!N))ghH)=G%6E8AZl1eDtzlxShAGoCBJ^8L@Aa8Hm-+95E_}us8&J< zO=}>PTCRc!6`_GNv{Yt7R5SuBOk>e3;~3B-2=jQWd{h*$NUEh8l9nmKLYji)3X*`- z6c`y{N@+AINwvZR?C``uff*1I!Iz>|1VZ&rVmv|3r6ZFXnEyx+{y8eoyNUd|*kEPA zUPwhko?0XDXM-*WU%iKa7lK+ek1rj$*W zjE>BV&|8QoL5?Iq@-(I?(daZY!8YC+U?XPB3uyq=uaJ90&CZ$}i_k}Pp@S6?Hk+9ty&Ebivr?no)5kHw>!QmTNA8j^x!u!htqWk!`u1&V4CkU&|>rKnssR@T1_q*3c+Az>|` z!O1B39qAxS5&VNlK-dIGqW))E}M>c~chLWaD{m z_=qw&Y!uBg<9INhYrYVKUe^78{N0pwx7J}NV%;CSO%nd*GSYS=zwAgO?1cWde5!$5S;cXI52K^{D#;INTg-#)MH%$Kf18%ti+ zC$0ay_Q8O-JumHSXv_~gKeTnrY3`e^8n!Gf??kf zb^n|%^GganTwi`(XMUy4lW*vJzdp8WWjaq&iVV^f4}_#8s2|VPW65_7-|{F zpz8w3*3XtMav$q>=I7gT{g|!)+5RB@NV6`WxGN6Vkt~%H3M&G z<34`xb})1Fi*QH5Pa$H78^J%_k@V_o&s_66nI(?)Bw{b^;D)1G9w3+?vh|VqSa`oK z+_Rv*F`};h)Rv-Sxm+t%F$L*etu87&4F1mobC*%o1=AztKcy9chM}LsDbmNBU7uuXP zmzsa5-B#Tgx@!R(S-fhQ=;^PpiYTn8)qizm>&BUVLHJ7@!2uVv+lJ16^}R~`b6u4v zvH8`fy7qkftvkNq!!CMO5BXYs>7LN94>e6qdoJ-=`MP)QvJ zJalH;j{VhrOLnI|d{+r{A^)B34|)c=&aFJ5-|gDsE`cr<_3mHOr{8^Kvz0h`{&H;f zEF`1eUg#I)5ln%r{cgtvxBbQ;*08#MF!lDdmpgjjxCR)>CC+JInMEuc|QaVvv0d79cz_(w*F zBk&$$T#zfwZH7bpq7LN6zSp;@X86azcMHW^aH4fnP3oPQkx|3iy=&X`{*eapEc^{) zMvzPDE`;yI^leow?v!bnf8HD`X7HivdBL3r?3_NpJ+sBx7UmZ-J5!BmiJsuY#7}9g zIRcqa;CG)Kc(9`>Fe}mxw>S?4hs1TPQAUtJP@ zHxtmT$I({*nqeHW1c(>IXRsuXQn|oA<6mj~aBEuoWk0)v3=CYTb8d2EZ?QHXpHA;T zxa4EQm#2bPWqn6RC zD3y{_L&eZo!XTxj(hkK8rREVH6*Cpl7w>O)_ndq0`P}op_kQp9-tW0I-^*w<6@3*D z2&CqD$=zS3;}2O$K_*M1{`pF#LDX-yX8u1+(f~GUG9l z2aXhw6h$KAZ$yH~WHOSN7?(o8Cr2WaZbVmaxaxyI3cq{0qp-JXM04Kp+L4CCTbu1x zzUNWc23T-tQI(#ZV)0omjB9?9VrlP1nr&=4t?I$h>d4?KuWYM6+Pa{o$T+`1MUSv! zOErsKeziT`iz1TAuIue{_aDxtcAuGmX58@{;E#`e+Dy0WF6+?9JeqsbZR1ol2UNE^ zmB7i0Xef`PL}%S@jANaOrgUbX&;yTg8_LguuTs92*=&3$9)KU?v+13v1LgY@S4Q*X zF1Y9Wy5x!>CzXi5;KGy*#+D??58WO>@Jr$?f|9|o5;Gz7kC5g0khYw9$0!cM#1AKBJN<+JZ*zM;xLxcE$DuRL!g?gr zPR5M<=8|r`Gjc)^cXLEqMB%x$mq>BFX&)`;j8#8YJsFNT-LFCg{&JV-%N63`Uz*={ zexf5$-&h(g&GvzhXu!7~_l1pSEF|!i`;X7ve0MLEb^a3^HsEZI$yn&A)OxeB#^|fy z%R}ww@z)t)m@)D%_XY^;97xp$(=2eJ`5b+D!Oi+X2k>MGIYgpD^ts`<$A47>uHQnQ zVp#Fht{Di-VG*h@UKKeljL17Xk$ZO<({3mbHc%kPs66Jj1S4H=4f%wt#iK6D9;WNF zlzz}w_e3*LH`2C38xXo4x2^)vwS6x1fUcFTSogA9mS3Wv%;Bo z&vv|0OgT&-7r4&&W05OF7uGw@R3{P>-A!S95Tal@V*|&^oHc>?8Hg}1?In*4pfmD? zgjzH8_>6DrT1t=;jrQFHFmwh~h%c@&Q;pA9CAB(pjJv1Si_H<0r*YaXYx~Xpqt?fr zYg>Lc`nAK}h42-$Q4Tij9Doz^vQ0h2`=jfacI!qKpu&VQJ6w~mVJ`;yr1E+C229{9 zrk*gSml-=IMSF0R7zynySWrvQ;ij=v_@a(kZ3o3 zyKq}kn33G$jnkAX^WO#4Jv=SQ`M^=1-Yg9xh|wQ=)zQH4G6W zJqstxeQ&%rVt$_3YTDTYeXkI&5K3HnVgFW=IOsu^2cQynMjS;)XTcT5f|TArt@u`PJm&b9D4;m_ICwrL zo(V=!ZtCf&Qh}F!X@QgS-#aN$>l{ilG?LqbrMfs>`M#~8)Flmg2mXFh|DIAM1|DbQ zq$MO_JWAgQ|0JRLAG%OJ8@q$E5CIf9o6_l`^6kVKE?8=%Q-)iMauNEk;?*!*U(HPzb9~;*|tvDMcYUYd+T6pN0-LAKWbRML} zU$sa>=;W|z>Z}vp6$QsJUwb2d1@SYZ9LgMF4GaF)jS&f7qzvyL{O3JY>VifZemjhA z#_)dA<`Ij#7kYTre{r2JNrM}xkUyVei^8RO!v*1L3aI~(s|chSe_NWvD(l$*bv*bm zk@+$_hD*KQiQP%cwoqBqvIqM3!4{YAvaLn^*YXn)F)!)$!~V7ui0FSMH!^`eE1h!{ z1ss?kr5z%##bCqwJ5~o%K?7JToktM$C00Eyo5KRO4-4SQW=zfTXvGgh4zNLe zM9jHki{9eR_+jb_+ol9kHWAtkPLi{vmp|Qe%nPW=d?u Date: Thu, 12 Nov 2020 15:06:23 -0800 Subject: [PATCH 04/18] No install apt recommends and clear cache (#423) Signed-off-by: Juan Oxoby Co-authored-by: Juan Oxoby Co-authored-by: Louise Poubel --- docker/scripts/install_common_deps.sh | 10 ++++++---- docker/scripts/install_ign_deps.sh | 20 ++++++++++---------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/docker/scripts/install_common_deps.sh b/docker/scripts/install_common_deps.sh index edadbee4d7..4557350cf2 100755 --- a/docker/scripts/install_common_deps.sh +++ b/docker/scripts/install_common_deps.sh @@ -5,13 +5,13 @@ set -o verbose sudo apt-get update -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ gnupg \ lsb-release \ software-properties-common \ wget -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ build-essential \ cmake \ cppcheck \ @@ -20,11 +20,13 @@ sudo apt-get install -y \ g++-8 \ pkg-config \ -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ clang-tidy-6.0 \ python-yaml \ libclang-6.0-dev -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libbenchmark-dev \ libbenchmark1 + +sudo apt-get clean && sudo rm -rf /var/lib/apt/lists/* diff --git a/docker/scripts/install_ign_deps.sh b/docker/scripts/install_ign_deps.sh index 56a2fb6cd8..18d9ab52f7 100755 --- a/docker/scripts/install_ign_deps.sh +++ b/docker/scripts/install_ign_deps.sh @@ -6,7 +6,7 @@ set -o verbose sudo apt-get update # Things that are used all over the ign stack -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ doxygen \ libbullet-dev \ libtinyxml2-dev \ @@ -18,7 +18,7 @@ sudo apt-get install -y \ uuid-dev # ign-common dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libavcodec-dev \ libavdevice-dev \ libavformat-dev \ @@ -28,7 +28,7 @@ sudo apt-get install -y \ libswscale-dev # ign-gui dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ qtbase5-dev \ qtdeclarative5-dev \ qtquickcontrols2-5-dev \ @@ -42,7 +42,7 @@ sudo apt-get install -y \ qml-module-qtgraphicaleffects # ign-rendering dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libogre-1.9-dev \ libogre-2.1-dev \ libglew-dev \ @@ -52,20 +52,20 @@ sudo apt-get install -y \ libxi-dev # ign-transport dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libzmq3-dev \ libsqlite3-dev # SDFormat dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libtinyxml-dev libxml2-dev # ign-fuel_tools dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libcurl4-openssl-dev libjsoncpp-dev libzip-dev curl libyaml-dev # ign-physics dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ libeigen3-dev \ dart6-data \ libdart6-collision-ode-dev \ @@ -74,8 +74,8 @@ sudo apt-get install -y \ libbenchmark-dev # ign-gazebo dependencies -sudo apt-get install -y \ +sudo apt-get install --no-install-recommends -y \ qml-module-qtqml-models2 -sudo apt-get clean +sudo apt-get clean && sudo rm -rf /var/lib/apt/lists/* From bcef5097a770e7e5d44a0d115098948026d27b92 Mon Sep 17 00:00:00 2001 From: Jose Luis Rivero Date: Wed, 20 Jan 2021 03:00:47 +0100 Subject: [PATCH 05/18] Fix visibility macro names when used by a different component (Windows) (#564) Signed-off-by: Jose Luis Rivero --- include/ignition/gazebo/gui/Gui.hh | 7 ++++--- include/ignition/gazebo/gui/GuiRunner.hh | 4 ++-- include/ignition/gazebo/rendering/MarkerManager.hh | 4 +++- include/ignition/gazebo/rendering/RenderUtil.hh | 4 ++-- include/ignition/gazebo/rendering/SceneManager.hh | 4 ++-- src/systems/air_pressure/AirPressure.hh | 1 - src/systems/altimeter/Altimeter.hh | 1 - src/systems/breadcrumbs/Breadcrumbs.hh | 1 + src/systems/camera_video_recorder/CameraVideoRecorder.hh | 1 - src/systems/contact/Contact.hh | 1 - src/systems/imu/Imu.hh | 1 - src/systems/log/LogPlayback.hh | 1 - src/systems/log/LogRecord.hh | 1 - src/systems/log_video_recorder/LogVideoRecorder.hh | 1 - src/systems/logical_camera/LogicalCamera.hh | 1 - src/systems/magnetometer/Magnetometer.hh | 1 - src/systems/multicopter_control/Common.hh | 1 + src/systems/physics/Physics.hh | 1 - src/systems/pose_publisher/PosePublisher.hh | 1 - src/systems/scene_broadcaster/SceneBroadcaster.hh | 1 - src/systems/sensors/Sensors.hh | 1 - src/systems/thermal/Thermal.hh | 1 - src/systems/triggered_publisher/TriggeredPublisher.cc | 6 ++++++ src/systems/triggered_publisher/TriggeredPublisher.hh | 5 +++-- src/systems/user_commands/UserCommands.hh | 1 - src/systems/velocity_control/VelocityControl.hh | 1 + src/systems/wind_effects/WindEffects.hh | 1 - 27 files changed, 25 insertions(+), 29 deletions(-) diff --git a/include/ignition/gazebo/gui/Gui.hh b/include/ignition/gazebo/gui/Gui.hh index 377d36e2f8..e23f99cfea 100644 --- a/include/ignition/gazebo/gui/Gui.hh +++ b/include/ignition/gazebo/gui/Gui.hh @@ -22,7 +22,7 @@ #include #include "ignition/gazebo/config.hh" -#include "ignition/gazebo/Export.hh" +#include "ignition/gazebo/gui/Export.hh" namespace ignition { @@ -41,7 +41,7 @@ namespace gui /// ign-tools. Set to the name of the application if using ign-tools) /// \param[in] _guiConfig The GUI configuration file. If nullptr, the default /// configuration from IGN_HOMEDIR/.ignition/gazebo/gui.config will be used. - IGNITION_GAZEBO_VISIBLE int runGui(int &_argc, char **_argv, + IGNITION_GAZEBO_GUI_VISIBLE int runGui(int &_argc, char **_argv, const char *_guiConfig); /// \brief Create a Gazebo GUI application @@ -60,7 +60,8 @@ namespace gui /// IGN_HOMEDIR/.ignition/gazebo/gui.config will be used. /// \param[in] _loadPluginsFromSdf If true, plugins specified in the world /// SDFormat file will get loaded. - IGNITION_GAZEBO_VISIBLE std::unique_ptr createGui( + IGNITION_GAZEBO_GUI_VISIBLE + std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig = nullptr, bool _loadPluginsFromSdf = true); diff --git a/include/ignition/gazebo/gui/GuiRunner.hh b/include/ignition/gazebo/gui/GuiRunner.hh index 421f49e47b..85520e0446 100644 --- a/include/ignition/gazebo/gui/GuiRunner.hh +++ b/include/ignition/gazebo/gui/GuiRunner.hh @@ -27,7 +27,7 @@ #include #include "ignition/gazebo/EntityComponentManager.hh" -#include "ignition/gazebo/Export.hh" +#include "ignition/gazebo/gui/Export.hh" namespace ignition { @@ -37,7 +37,7 @@ namespace gazebo inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Responsible for running GUI systems as new states are received from /// the backend. -class IGNITION_GAZEBO_VISIBLE GuiRunner : public QObject +class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject { Q_OBJECT diff --git a/include/ignition/gazebo/rendering/MarkerManager.hh b/include/ignition/gazebo/rendering/MarkerManager.hh index ff9d3d43e4..691d08fdbc 100644 --- a/include/ignition/gazebo/rendering/MarkerManager.hh +++ b/include/ignition/gazebo/rendering/MarkerManager.hh @@ -20,6 +20,8 @@ #include #include +#include + #include "ignition/rendering/RenderTypes.hh" namespace ignition @@ -32,7 +34,7 @@ class MarkerManagerPrivate; /// \brief Creates, deletes, and maintains marker visuals. Only the /// Scene class should instantiate and use this class. -class IGNITION_GAZEBO_VISIBLE MarkerManager +class IGNITION_GAZEBO_RENDERING_VISIBLE MarkerManager { /// \brief Constructor public: MarkerManager(); diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 92d191576a..6e8e82f98e 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -24,7 +24,7 @@ #include #include -#include +#include #include #include "ignition/gazebo/rendering/SceneManager.hh" @@ -41,7 +41,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { class RenderUtilPrivate; /// \class RenderUtil RenderUtil.hh ignition/gazebo/gui/plugins/RenderUtil.hh - class IGNITION_GAZEBO_VISIBLE RenderUtil + class IGNITION_GAZEBO_RENDERING_VISIBLE RenderUtil { /// \brief Constructor public: explicit RenderUtil(); diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 2099ef7b0f..162a307b96 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -36,7 +36,7 @@ #include #include -#include +#include namespace ignition { @@ -48,7 +48,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { class SceneManagerPrivate; /// \brief Scene manager class for loading and managing objects in the scene - class IGNITION_GAZEBO_VISIBLE SceneManager + class IGNITION_GAZEBO_RENDERING_VISIBLE SceneManager { /// \brief Constructor public: SceneManager(); diff --git a/src/systems/air_pressure/AirPressure.hh b/src/systems/air_pressure/AirPressure.hh index 68be696d37..93cbb5fd4a 100644 --- a/src/systems/air_pressure/AirPressure.hh +++ b/src/systems/air_pressure/AirPressure.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/altimeter/Altimeter.hh b/src/systems/altimeter/Altimeter.hh index aede9336e0..e044e9b864 100644 --- a/src/systems/altimeter/Altimeter.hh +++ b/src/systems/altimeter/Altimeter.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index fb874c0272..e57be62402 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -18,6 +18,7 @@ #define IGNITION_GAZEBO_SYSTEMS_BREADCRUMBS_HH_ #include +#include #include #include #include diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index b8627f7355..a7204e5a80 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/contact/Contact.hh b/src/systems/contact/Contact.hh index 98d77f4258..73e90b811e 100644 --- a/src/systems/contact/Contact.hh +++ b/src/systems/contact/Contact.hh @@ -18,7 +18,6 @@ #define IGNITION_GAZEBO_SYSTEMS_CONTACT_HH_ #include -#include #include namespace ignition diff --git a/src/systems/imu/Imu.hh b/src/systems/imu/Imu.hh index 74d5d87750..6194c4ec99 100644 --- a/src/systems/imu/Imu.hh +++ b/src/systems/imu/Imu.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/log/LogPlayback.hh b/src/systems/log/LogPlayback.hh index 90e41cb3c0..07086f63c9 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -20,7 +20,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/log/LogRecord.hh b/src/systems/log/LogRecord.hh index 6bf80578e8..f03edd4e35 100644 --- a/src/systems/log/LogRecord.hh +++ b/src/systems/log/LogRecord.hh @@ -20,7 +20,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index e8d54fb3f3..7c2a87fc5e 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -20,7 +20,6 @@ #include #include #include -#include #include namespace ignition diff --git a/src/systems/logical_camera/LogicalCamera.hh b/src/systems/logical_camera/LogicalCamera.hh index bb17adaa32..8d2ab28e38 100644 --- a/src/systems/logical_camera/LogicalCamera.hh +++ b/src/systems/logical_camera/LogicalCamera.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/magnetometer/Magnetometer.hh b/src/systems/magnetometer/Magnetometer.hh index cda2e5e970..5294fe96ee 100644 --- a/src/systems/magnetometer/Magnetometer.hh +++ b/src/systems/magnetometer/Magnetometer.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/multicopter_control/Common.hh b/src/systems/multicopter_control/Common.hh index 4d3fdee009..d0e41f7689 100644 --- a/src/systems/multicopter_control/Common.hh +++ b/src/systems/multicopter_control/Common.hh @@ -19,6 +19,7 @@ #define IGNITION_GAZEBO_SYSTEMS_MULTICOPTERVELOCITYCONTROL_COMMON_HH_ #include +#include #include #include diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index cc39d373a0..38f7f10599 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -46,7 +46,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/pose_publisher/PosePublisher.hh b/src/systems/pose_publisher/PosePublisher.hh index 21ceed3a6f..abd794ea25 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.hh b/src/systems/scene_broadcaster/SceneBroadcaster.hh index 5a23d01d9c..aced8c4bfe 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -20,7 +20,6 @@ #include #include #include -#include #include namespace ignition diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index 3461256bbc..1e0602644e 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -21,7 +21,6 @@ #include #include -#include #include #include diff --git a/src/systems/thermal/Thermal.hh b/src/systems/thermal/Thermal.hh index e033a21fbc..9210a06a0f 100644 --- a/src/systems/thermal/Thermal.hh +++ b/src/systems/thermal/Thermal.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index ddbcb58de7..316177f2d4 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -17,6 +17,7 @@ #include "TriggeredPublisher.hh" +#include #include #include @@ -27,6 +28,11 @@ #include #include +// bug https://github.com/protocolbuffers/protobuf/issues/5051 +#ifdef _WIN32 +#undef GetMessage +#endif + using namespace ignition; using namespace gazebo; using namespace systems; diff --git a/src/systems/triggered_publisher/TriggeredPublisher.hh b/src/systems/triggered_publisher/TriggeredPublisher.hh index 2834d5399a..1fb7d61050 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.hh +++ b/src/systems/triggered_publisher/TriggeredPublisher.hh @@ -153,8 +153,9 @@ namespace systems /// The current implementation of this system does not support specifying a /// subfield of a repeated field in the "field" attribute. i.e, if /// `field="f1.f2"`, `f1` cannot be a repeated field. - class TriggeredPublisher : public System, - public ISystemConfigure + class TriggeredPublisher : + public System, + public ISystemConfigure { /// \brief Constructor public: TriggeredPublisher() = default; diff --git a/src/systems/user_commands/UserCommands.hh b/src/systems/user_commands/UserCommands.hh index 6bbeb67afa..3db285aad6 100644 --- a/src/systems/user_commands/UserCommands.hh +++ b/src/systems/user_commands/UserCommands.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index 7b83c4e16b..0b546525a1 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -18,6 +18,7 @@ #define IGNITION_GAZEBO_SYSTEMS_VELOCITYCONTROL_HH_ #include +#include #include diff --git a/src/systems/wind_effects/WindEffects.hh b/src/systems/wind_effects/WindEffects.hh index f477c7667f..3aac7ab967 100644 --- a/src/systems/wind_effects/WindEffects.hh +++ b/src/systems/wind_effects/WindEffects.hh @@ -19,7 +19,6 @@ #include #include -#include #include namespace ignition From dc50b29ba6314063e985bc52c4db65611ee1b692 Mon Sep 17 00:00:00 2001 From: Jose Luis Rivero Date: Wed, 20 Jan 2021 05:20:46 +0100 Subject: [PATCH 06/18] Add missing IGNITION_GAZEBO_VISIBLE macros (#563) Signed-off-by: Jose Luis Rivero --- include/ignition/gazebo/Conversions.hh | 9 ++++++--- include/ignition/gazebo/ServerConfig.hh | 2 +- src/Conversions.cc | 1 + src/LevelManager.hh | 2 +- src/SdfGenerator.hh | 4 ++++ 5 files changed, 13 insertions(+), 5 deletions(-) diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index a8740a291e..27dda6b76d 100644 --- a/include/ignition/gazebo/Conversions.hh +++ b/include/ignition/gazebo/Conversions.hh @@ -65,20 +65,23 @@ namespace ignition /// to the values contained in a sdf::Noise object. /// \param[out] _msg SensorNoise message to set. /// \param[in] _sdf SDF Noise object. - void set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf); + void IGNITION_GAZEBO_VISIBLE + set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf); /// \brief Helper function that sets a mutable msgs::WorldStatistics object /// to the values contained in a gazebo::UpdateInfo object. /// \param[out] _msg WorldStatistics message to set. /// \param[in] _in UpdateInfo object. - void set(msgs::WorldStatistics *_msg, const UpdateInfo &_in); + void IGNITION_GAZEBO_VISIBLE + set(msgs::WorldStatistics *_msg, const UpdateInfo &_in); /// \brief Helper function that sets a mutable msgs::Time object /// to the values contained in a std::chrono::steady_clock::duration /// object. /// \param[out] _msg Time message to set. /// \param[in] _in Chrono duration object. - void set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in); + void IGNITION_GAZEBO_VISIBLE + set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in); /// \brief Generic conversion from an SDF geometry to another type. /// \param[in] _in SDF geometry. diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index abb0283cde..dc0265d19c 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -49,7 +49,7 @@ namespace ignition /// type and name, but it can't tell apart multiple entities with the same /// name in different parts of the entity tree. /// \sa const std::list &Plugins() const - public: class PluginInfo + public: class IGNITION_GAZEBO_VISIBLE PluginInfo { /// \brief Default constructor. public: PluginInfo(); diff --git a/src/Conversions.cc b/src/Conversions.cc index c582d230b3..88b5b2817f 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -61,6 +61,7 @@ #include #include "ignition/gazebo/Conversions.hh" +#include "ignition/gazebo/Export.hh" #include "ignition/gazebo/Util.hh" using namespace ignition; diff --git a/src/LevelManager.hh b/src/LevelManager.hh index 5e51833ae8..556ad87d29 100644 --- a/src/LevelManager.hh +++ b/src/LevelManager.hh @@ -74,7 +74,7 @@ namespace ignition /// when the level is reloaded. Likewise, they should not be deleted. /// * Entities spawned during simulation are part of the default level. /// - class LevelManager + class IGNITION_GAZEBO_VISIBLE LevelManager { /// \brief Constructor /// \param[in] _runner A pointer to the simulationrunner that owns this diff --git a/src/SdfGenerator.hh b/src/SdfGenerator.hh index cc278c59e0..5e267e9d9b 100644 --- a/src/SdfGenerator.hh +++ b/src/SdfGenerator.hh @@ -44,6 +44,7 @@ namespace sdf_generator /// \input[in] _config Configuration for the world generator /// \returns Generated world string if generation succeeded. /// Otherwise, nullopt + IGNITION_GAZEBO_VISIBLE std::optional generateWorld( const EntityComponentManager &_ecm, const Entity &_entity, const IncludeUriMap &_includeUriMap = IncludeUriMap(), @@ -56,6 +57,7 @@ namespace sdf_generator /// \input[in] _includeUriMap Map from file paths to URIs used to preserve /// included Fuel models /// \input[in] _config Configuration for the world generator + IGNITION_GAZEBO_VISIBLE bool updateWorldElement( sdf::ElementPtr _elem, const EntityComponentManager &_ecm, const Entity &_entity, @@ -68,6 +70,7 @@ namespace sdf_generator /// \input[in] _ecm Immutable reference to the Entity Component Manager /// \input[in] _entity Model entity /// \returns true if update succeeded. + IGNITION_GAZEBO_VISIBLE bool updateModelElement(const sdf::ElementPtr &_elem, const EntityComponentManager &_ecm, const Entity &_entity); @@ -79,6 +82,7 @@ namespace sdf_generator /// \input[in] _entity Entity of included resource /// \input[in] _uri Uri of the resource /// \returns true if update succeeded. + IGNITION_GAZEBO_VISIBLE bool updateIncludeElement(const sdf::ElementPtr &_elem, const EntityComponentManager &_ecm, const Entity &_entity, const std::string &_uri); From 7f711e056c0ee38977674bd12bd51fa81d94c6d6 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 11 Feb 2021 16:59:05 -0800 Subject: [PATCH 07/18] Examples and tutorial on using rendering API from plugins (#596) Signed-off-by: Louise Poubel Edifice to Citadel (#945) Signed-off-by: Louise Poubel --- examples/plugin/custom_component/README.md | 4 +- examples/plugin/gui_system_plugin/README.md | 4 +- .../plugin/rendering_plugins/CMakeLists.txt | 44 ++++ examples/plugin/rendering_plugins/README.md | 38 ++++ .../rendering_plugins/RenderingGuiPlugin.cc | 145 +++++++++++++ .../rendering_plugins/RenderingGuiPlugin.hh | 57 ++++++ .../rendering_plugins/RenderingGuiPlugin.qml | 34 ++++ .../rendering_plugins/RenderingGuiPlugin.qrc | 5 + .../RenderingServerPlugin.cc | 135 +++++++++++++ .../RenderingServerPlugin.hh | 67 ++++++ .../rendering_plugins/rendering_plugins.sdf | 191 ++++++++++++++++++ examples/standalone/joy_to_twist/README.md | 8 +- examples/standalone/joystick/README.md | 8 +- examples/standalone/keyboard/README.md | 6 +- tutorials.md.in | 1 + tutorials/files/rendering_plugins.gif | Bin 0 -> 301592 bytes tutorials/rendering_plugins.md | 138 +++++++++++++ 17 files changed, 870 insertions(+), 15 deletions(-) create mode 100644 examples/plugin/rendering_plugins/CMakeLists.txt create mode 100644 examples/plugin/rendering_plugins/README.md create mode 100644 examples/plugin/rendering_plugins/RenderingGuiPlugin.cc create mode 100644 examples/plugin/rendering_plugins/RenderingGuiPlugin.hh create mode 100644 examples/plugin/rendering_plugins/RenderingGuiPlugin.qml create mode 100644 examples/plugin/rendering_plugins/RenderingGuiPlugin.qrc create mode 100644 examples/plugin/rendering_plugins/RenderingServerPlugin.cc create mode 100644 examples/plugin/rendering_plugins/RenderingServerPlugin.hh create mode 100644 examples/plugin/rendering_plugins/rendering_plugins.sdf create mode 100644 tutorials/files/rendering_plugins.gif create mode 100644 tutorials/rendering_plugins.md diff --git a/examples/plugin/custom_component/README.md b/examples/plugin/custom_component/README.md index 5d53652d02..c752fb36d4 100644 --- a/examples/plugin/custom_component/README.md +++ b/examples/plugin/custom_component/README.md @@ -9,7 +9,7 @@ See `CustomComponentPlugin.hh` for more information. From the root of the `ign-gazebo` repository, do the following to build the example: ~~~ -cd ign-gazebo/examples/plugins/custom_component +cd examples/plugin/custom_component mkdir build cd build cmake .. @@ -23,7 +23,7 @@ This will generate the `CustomComponent` library under `build`. Add the library to the path: ~~~ -cd ign-gazebo/examples/plugins/custom_component +cd examples/plugin/custom_component export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=`pwd`/build ~~~ diff --git a/examples/plugin/gui_system_plugin/README.md b/examples/plugin/gui_system_plugin/README.md index da2bec4278..83c9f1a26b 100644 --- a/examples/plugin/gui_system_plugin/README.md +++ b/examples/plugin/gui_system_plugin/README.md @@ -14,7 +14,7 @@ See `GuiSystemPluginPlugin.hh` for more information. From the root of the `ign-gazebo` repository, do the following to build the example: ~~~ -cd ign-gazebo/examples/plugins/gui_system_plugin +cd examples/plugin/gui_system_plugin mkdir build cd build cmake .. @@ -28,7 +28,7 @@ This will generate the `GuiSystemPlugin` library under `build`. Add the library to the path: ~~~ -cd ign-gazebo/examples/plugins/gui_system_plugin +cd examples/plugin/gui_system_plugin export IGN_GUI_PLUGIN_PATH=`pwd`/build ~~~ diff --git a/examples/plugin/rendering_plugins/CMakeLists.txt b/examples/plugin/rendering_plugins/CMakeLists.txt new file mode 100644 index 0000000000..3978b17d4d --- /dev/null +++ b/examples/plugin/rendering_plugins/CMakeLists.txt @@ -0,0 +1,44 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +if(POLICY CMP0100) + cmake_policy(SET CMP0100 NEW) +endif() + +project(RenderingPlugins) + +# Common to both plugins +find_package(ignition-rendering3 REQUIRED) + +# GUI plugin +set(GUI_PLUGIN RenderingGuiPlugin) + +set(CMAKE_AUTOMOC ON) + +find_package(ignition-gui3 REQUIRED) + +QT5_ADD_RESOURCES(resources_RCC ${GUI_PLUGIN}.qrc) + +add_library(${GUI_PLUGIN} SHARED + ${GUI_PLUGIN}.cc + ${resources_RCC} +) +target_link_libraries(${GUI_PLUGIN} + PRIVATE + ignition-gui3::ignition-gui3 + ignition-rendering3::ignition-rendering3 +) + +# Server plugin +set(SERVER_PLUGIN RenderingServerPlugin) + +find_package(ignition-plugin1 REQUIRED COMPONENTS register) +find_package(ignition-gazebo3 REQUIRED) + +add_library(${SERVER_PLUGIN} SHARED ${SERVER_PLUGIN}.cc) +set_property(TARGET ${SERVER_PLUGIN} PROPERTY CXX_STANDARD 17) +target_link_libraries(${SERVER_PLUGIN} + PRIVATE + ignition-plugin1::ignition-plugin1 + ignition-gazebo3::ignition-gazebo3 + ignition-rendering3::ignition-rendering3 +) diff --git a/examples/plugin/rendering_plugins/README.md b/examples/plugin/rendering_plugins/README.md new file mode 100644 index 0000000000..9ad374ca14 --- /dev/null +++ b/examples/plugin/rendering_plugins/README.md @@ -0,0 +1,38 @@ +# Rendering plugins + +Demo of 2 plugins that use Ignition Rendering, one for the server and one for the client. + +## Build + +From the root of the `ign-gazebo` repository, do the following to build the example: + +~~~ +cd examples/plugin/rendering_plugins +mkdir build +cd build +cmake .. +make +~~~ + +This will generate the `RenderingGuiPlugin` and `RenderingServerPlugin` libraries under `build`. + +## Run + +Add the libraries to the correct paths: + +~~~ +cd examples/plugin/rendering_plugins +export IGN_GUI_PLUGIN_PATH=`pwd`/build +export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=`pwd`/build +~~~ + +Run the example world + +~~~ +cd examples/plugin/rendering_plugins +ign gazebo -v 4 -r rendering_plugins.sdf +~~~ + +The ambient light on the server scene, visible from the camera sensor, will change every 2 seconds. + +The ambient light on the client scene, visible from the GUI, will change every time the button is pressed. diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc new file mode 100644 index 0000000000..e0c629f09b --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.cc @@ -0,0 +1,145 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +//! [includeGuiEvents] +#include +//! [includeGuiEvents] +#include +#include +#include +#include +#include +#include + +#include "RenderingGuiPlugin.hh" + +///////////////////////////////////////////////// +void RenderingGuiPlugin::LoadConfig(const tinyxml2::XMLElement * /*_pluginElem*/) +{ + // This is necessary to receive the Render event on eventFilter +//! [connectToGuiEvent] + ignition::gui::App()->findChild< + ignition::gui::MainWindow *>()->installEventFilter(this); +//! [connectToGuiEvent] +} + +///////////////////////////////////////////////// +void RenderingGuiPlugin::RandomColor() +{ + this->dirty = true; +} + +///////////////////////////////////////////////// +//! [eventFilter] +bool RenderingGuiPlugin::eventFilter(QObject *_obj, QEvent *_event) +{ + if (_event->type() == ignition::gui::events::Render::kType) + { + // This event is called in the render thread, so it's safe to make + // rendering calls here + this->PerformRenderingOperations(); + } + + // Standard event processing + return QObject::eventFilter(_obj, _event); +} +//! [eventFilter] + +///////////////////////////////////////////////// +//! [performRenderingOperations] +void RenderingGuiPlugin::PerformRenderingOperations() +{ + if (!this->dirty) + { + return; + } + + if (nullptr == this->scene) + { + this->FindScene(); + } + + if (nullptr == this->scene) + return; + + this->scene->SetAmbientLight({ + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + 1.0}); + + this->dirty = false; +} +//! [performRenderingOperations] + +///////////////////////////////////////////////// +void RenderingGuiPlugin::FindScene() +{ + auto loadedEngNames = ignition::rendering::loadedEngines(); + if (loadedEngNames.empty()) + { + igndbg << "No rendering engine is loaded yet" << std::endl; + return; + } + + // assume there is only one engine loaded + auto engineName = loadedEngNames[0]; + if (loadedEngNames.size() > 1) + { + igndbg << "More than one engine is available. " + << "Using engine [" << engineName << "]" << std::endl; + } + auto engine = ignition::rendering::engine(engineName); + if (!engine) + { + ignerr << "Internal error: failed to load engine [" << engineName + << "]. Grid plugin won't work." << std::endl; + return; + } + + if (engine->SceneCount() == 0) + { + igndbg << "No scene has been created yet" << std::endl; + return; + } + + // Get first scene + auto scenePtr = engine->SceneByIndex(0); + if (nullptr == scenePtr) + { + ignerr << "Internal error: scene is null." << std::endl; + return; + } + + if (engine->SceneCount() > 1) + { + igndbg << "More than one scene is available. " + << "Using scene [" << scene->Name() << "]" << std::endl; + } + + if (!scenePtr->IsInitialized() || nullptr == scenePtr->RootVisual()) + { + return; + } + + this->scene = scenePtr; +} + +// Register this plugin +IGNITION_ADD_PLUGIN(RenderingGuiPlugin, + ignition::gui::Plugin) diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh new file mode 100644 index 0000000000..7958c38b07 --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.hh @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef RENDERING_GUI_PLUGIN_HH_ +#define RENDERING_GUI_PLUGIN_HH_ + +#include +#include +#include + +/// \brief Example of a GUI plugin that uses Ignition Rendering. +/// This plugin works with either Ignition GUI's Scene3D or Ignition Gazebo's +/// Scene3D. +class RenderingGuiPlugin : public ignition::gui::Plugin +{ + Q_OBJECT + + ///\brief Called once at startup. + public: void LoadConfig(const tinyxml2::XMLElement *) override; + + /// \brief Callback when user clicks button. + public slots: void RandomColor(); + + /// \brief Callback for all installed event filters. + /// \param[in] _obj Object that received the event + /// \param[in] _event Event + private: bool eventFilter(QObject *_obj, QEvent *_event) override; + + /// \brief All rendering operations must happen within this call + private: void PerformRenderingOperations(); + + /// \brief Encapsulates the logic to find the rendering scene through the + /// render engine singleton. + private: void FindScene(); + + /// \brief Marks when a new change has been requested. + private: bool dirty{false}; + + /// \brief Pointer to the rendering scene. + private: ignition::rendering::ScenePtr scene{nullptr}; +}; + +#endif diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.qml b/examples/plugin/rendering_plugins/RenderingGuiPlugin.qml new file mode 100644 index 0000000000..af4e0f4ca3 --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.qml @@ -0,0 +1,34 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +import QtQuick 2.9 +import QtQuick.Controls 2.2 +import QtQuick.Layouts 1.3 + +Rectangle { + color: "transparent" + anchors.fill: parent + Layout.minimumWidth: 250 + Layout.minimumHeight: 100 + Button { + text: qsTr("Random GUI color!") + onClicked: { + RenderingGuiPlugin.RandomColor(); + } + anchors.horizontalCenter: parent.horizontalCenter + anchors.verticalCenter: parent.verticalCenter + } +} diff --git a/examples/plugin/rendering_plugins/RenderingGuiPlugin.qrc b/examples/plugin/rendering_plugins/RenderingGuiPlugin.qrc new file mode 100644 index 0000000000..ff99b777d8 --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingGuiPlugin.qrc @@ -0,0 +1,5 @@ + + + RenderingGuiPlugin.qml + + diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.cc b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc new file mode 100644 index 0000000000..2054975787 --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.cc @@ -0,0 +1,135 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#include "RenderingServerPlugin.hh" + +//! [includeRenderingEvents] +#include +//! [includeRenderingEvents] +#include +#include +#include +#include +#include + +using namespace std::literals::chrono_literals; + +////////////////////////////////////////////////// +void RenderingServerPlugin::Configure( + const ignition::gazebo::Entity &/*_entity*/, + const std::shared_ptr &/*_sdf*/, + ignition::gazebo::EntityComponentManager &/*_ecm*/, + ignition::gazebo::EventManager &_eventMgr) +{ +//! [connectToServerEvent] + this->connection = _eventMgr.Connect( + std::bind(&RenderingServerPlugin::PerformRenderingOperations, this)); +//! [connectToServerEvent] +} + +////////////////////////////////////////////////// +//! [performRenderingOperations] +void RenderingServerPlugin::PerformRenderingOperations() +{ + if (nullptr == this->scene) + { + this->FindScene(); + } + + if (nullptr == this->scene) + return; + + if (this->simTime - this->lastUpdate < 2s) + return; + + this->scene->SetAmbientLight({ + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + static_cast(ignition::math::Rand::DblUniform(0.0, 1.0)), + 1.0}); + + this->lastUpdate = this->simTime; +} +//! [performRenderingOperations] + +///////////////////////////////////////////////// +//! [findScene] +void RenderingServerPlugin::FindScene() +{ + auto loadedEngNames = ignition::rendering::loadedEngines(); + if (loadedEngNames.empty()) + { + igndbg << "No rendering engine is loaded yet" << std::endl; + return; + } + + // assume there is only one engine loaded + auto engineName = loadedEngNames[0]; + if (loadedEngNames.size() > 1) + { + igndbg << "More than one engine is available. " + << "Using engine [" << engineName << "]" << std::endl; + } + auto engine = ignition::rendering::engine(engineName); + if (!engine) + { + ignerr << "Internal error: failed to load engine [" << engineName + << "]. Grid plugin won't work." << std::endl; + return; + } + + if (engine->SceneCount() == 0) + { + igndbg << "No scene has been created yet" << std::endl; + return; + } + + // Get first scene + auto scenePtr = engine->SceneByIndex(0); + if (nullptr == scenePtr) + { + ignerr << "Internal error: scene is null." << std::endl; + return; + } + + if (engine->SceneCount() > 1) + { + igndbg << "More than one scene is available. " + << "Using scene [" << scene->Name() << "]" << std::endl; + } + + if (!scenePtr->IsInitialized() || nullptr == scenePtr->RootVisual()) + { + return; + } + + this->scene = scenePtr; +} +//! [findScene] + +////////////////////////////////////////////////// +void RenderingServerPlugin::PreUpdate(const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) +{ + this->simTime = _info.simTime; +} + +IGNITION_ADD_PLUGIN( + RenderingServerPlugin, + ignition::gazebo::System, + RenderingServerPlugin::ISystemConfigure, + RenderingServerPlugin::ISystemPreUpdate +) diff --git a/examples/plugin/rendering_plugins/RenderingServerPlugin.hh b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh new file mode 100644 index 0000000000..9f9218f4c6 --- /dev/null +++ b/examples/plugin/rendering_plugins/RenderingServerPlugin.hh @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef RENDERING_SERVER_PLUGIN_HH_ +#define RENDERING_SERVER_PLUGIN_HH_ + +#include +#include + +/// \brief Server-side system that uses Ignition Rendering APIs. +/// It changes the ambient color every 2 simulation seconds. +class RenderingServerPlugin: + public ignition::gazebo::System, + public ignition::gazebo::ISystemConfigure, + public ignition::gazebo::ISystemPreUpdate +{ + /// \brief Called once at startup + /// \param[in] _entity Entity that the plugin is attached to, not used. + /// \param[in] _sdf Element with custom configuration, not used. + /// \param[in] _ecm Entity component manager + /// \param[in] _eventMgr Event manager + public: void Configure(const ignition::gazebo::Entity &_entity, + const std::shared_ptr &_sdf, + ignition::gazebo::EntityComponentManager &_ecm, + ignition::gazebo::EventManager &_eventMgr) override; + + /// \brief Called just before each simulation update. + /// \param[in] _info Contains information like sim time. + /// \param[in] _ecm Entity component manager + public: void PreUpdate( + const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) override; + + /// \brief All rendering operations must happen within this call + private: void PerformRenderingOperations(); + + /// \brief Encapsulates the logic to find the rendering scene through the + /// render engine singleton. + private: void FindScene(); + + /// \brief Connection to pre-render event callback + private: ignition::common::ConnectionPtr connection{nullptr}; + + /// \brief Pointer to rendering scene + private: ignition::rendering::ScenePtr scene{nullptr}; + + /// \brief Current simulation time. + private: std::chrono::steady_clock::duration simTime{0}; + + /// \brief Time when light was last updated + private: std::chrono::steady_clock::duration lastUpdate{0}; +}; + +#endif diff --git a/examples/plugin/rendering_plugins/rendering_plugins.sdf b/examples/plugin/rendering_plugins/rendering_plugins.sdf new file mode 100644 index 0000000000..8fbb572bda --- /dev/null +++ b/examples/plugin/rendering_plugins/rendering_plugins.sdf @@ -0,0 +1,191 @@ + + + + + ogre2 + + + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + Camera + floating + 350 + 315 + + camera + false + + + + + Rendering GUI Plugin + floating + 350 + 100 + 500 + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + + 20 20 0.1 + + + + + + + 20 20 0.1 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 2.5 0 1.5 0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + camera + + + true + + + diff --git a/examples/standalone/joy_to_twist/README.md b/examples/standalone/joy_to_twist/README.md index fe7b7d8e85..893bdeed1d 100644 --- a/examples/standalone/joy_to_twist/README.md +++ b/examples/standalone/joy_to_twist/README.md @@ -11,7 +11,7 @@ messages according to user-defined configuration. From the root of the `ign-gazebo` repository, do the following to build the example: ~~~ -cd ign-gazebo/examples/standalone/joy_to_twist +cd examples/standalone/joy_to_twist mkdir build cd build cmake .. @@ -41,19 +41,19 @@ that can be controlled using a joystick. You can run it as follows: messages. See that standalone program's instructions to details on how to build it. Once it's built, you can run it as follows: - cd ign-gazebo/examples/standalone/joystick + cd examples/standalone/joystick ./joystick ../joystick.sdf 1. On another terminal, run the `joy_to_twist` executable as described above, which will convert joy messages to twist messages: - cd ign-gazebo/examples/standalone/joy_to_twist + cd examples/standalone/joy_to_twist ./joy_to_twist ../joy_to_twist.sdf 1. Finally, on a 3rd terminal, run `ign gazebo` with the vehicle that will consume the twist messages: - cd ign-gazebo/examples/worlds + cd examples/worlds ign gazebo -v 4 diff_drive.sdf 1. Now hold your joystick's A button (or equivalent) and move the directional diff --git a/examples/standalone/joystick/README.md b/examples/standalone/joystick/README.md index 1b965b40e8..9e05e2e172 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -11,7 +11,7 @@ The mapping of joystick buttons to fields in the message is the same as [this](h From the root of the `ign-gazebo` repository, do the following to build the example: ~~~ -cd ign-gazebo/examples/standalone/joystick +cd examples/standalone/joystick mkdir build cd build cmake .. @@ -49,20 +49,20 @@ that can be controlled using a joystick. You can run it as follows: 1. In a terminal, run the joystick executable as described above to publish joystick messages: - cd ign-gazebo/examples/standalone/joystick + cd examples/standalone/joystick ./joystick ../joystick.sdf 1. On another terminal, run the `joy_to_twist` executable to convert joy messages to twist messages. See that standalone program's instructions for details on how to build it. Once it's built, you can run it as follows: - cd ign-gazebo/examples/standalone/joy_to_twist + cd examples/standalone/joy_to_twist ./joy_to_twist ../joy_to_twist.sdf 1. Finally, on a 3rd terminal, run `ign gazebo` with the vehicle that will consume the twist messages: - cd ign-gazebo/examples/worlds + cd examples/worlds ign gazebo -v 4 diff_drive.sdf 1. Now hold your joystick's A button (or equivalent) and move the directional diff --git a/examples/standalone/keyboard/README.md b/examples/standalone/keyboard/README.md index c5e3a342ae..8912a81839 100644 --- a/examples/standalone/keyboard/README.md +++ b/examples/standalone/keyboard/README.md @@ -5,7 +5,7 @@ From the root of the `ign-gazebo` repository, do the following to build the example: ~~~ -cd ign-gazebo/examples/standalone/keyboard +cd examples/standalone/keyboard mkdir build cd build cmake .. @@ -30,13 +30,13 @@ that can be controlled using a keyboard. You can run it as follows: 1. In a terminal, run the keyboard executable as described above: - cd ign-gazebo/examples/standalone/keyboard/build + cd examples/standalone/keyboard/build ./keyboard ../keyboard.sdf 1. On another terminal, run `ign gazebo` with the vehicle that will consume the twist messages: - cd ign-gazebo/examples/worlds + cd examples/worlds ign gazebo -v 4 diff_drive.sdf 1. Switch back to the first terminal. Use the arrow keys to control one vehicle, diff --git a/tutorials.md.in b/tutorials.md.in index 43c4a3244f..0a96bde98f 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -9,6 +9,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage terminology "Terminology": List of terms used across the documentation. * \subpage createsystemplugins "Create System Plugins": Programmatically access simulation using C++ plugins. +* \subpage rendering_plugins "Rendering plugins": Write plugins that use Ignition Rendering on the server and client. * \subpage levels "Levels": Load entities on demand in large environments. * \subpage distributedsimulation "Distributed Simulation": Spread simulation across several processes. * \subpage resources "Finding resources": The different ways in which Ignition looks for files. diff --git a/tutorials/files/rendering_plugins.gif b/tutorials/files/rendering_plugins.gif new file mode 100644 index 0000000000000000000000000000000000000000..19ff4f8596236b3f77d5d055d5f5fe4c8fee26b6 GIT binary patch literal 301592 zcmeF2Wmg-__q9U^?zF|BI20&aoMOejP^6UNuEE`cL(vv@cb5bYP#{2&0>$0k-SXVO z&++{CtMhW!%(>Q?wP%mKqMVSh2_EWe;4K;t;6HiS17b!1nX7<;LjV$hQgQ|igaQkX zP;)j=OV>e(f3ZpqvFQYHad8OQf6dsU~kx`RTQs+<85~9;V@9DV|nCK{& zI7FCPIo_pBa!P4)li>1v{KPl$B8UMH{A@4!j`3qst2i_MCn0v()++@WSw#hH#nLHd zLl@H$~C@EX4*I8VXr%66OWo#eeNs?8tgOCuqJFrm{t?+w z-_X!n)iANrFx}Kx64Thy*f`SJI1O$5*W7q`)ztpCsiUT82G-nB+0r@P(p3kotAh@Y zL;rL@{~f`gEwJ`JSVtoa-T)hFf!#c}*4DT7G`6)jw%0eb_ceEPRd@Vu>G<2(+1%Xu zi0pzvyL#)pcF()*K6kgacmHna9)NaFBf4k$x@UfO&v(P29q`sxcy~8^ysxLfv8TVK z=fC3irME1hx1+3gtfzPEPw#kl?*zPecDz3^q92wv0IMGuYaI-77(^ftO+5%`%TQzQ zP+RFx_rTEKj-h$P(8A{MpW)&Amyz*_k*TiHfAF!%sj-=!@qe=uw$c-@qKWC5iP_mn zSkL72_~hKk)W3hzu#D-pzG?XI^z`(HhiI z+4=eTg|6X+!Lfyr%7w9kMf)#{i%ZK!f-4JCYogd|f1zt@Yn%UR`)F%-ZM(H(due=o zdwU1su$%0&ySuw*NO`!oc3k0i5~OoBUV335aIvv{rN{K3L;a{t_qg`^@!|eS=k4>? zcQ0RPUhD+ukT`0xU$j0+X~^<&a-*XBhXdU`2n`#62H^M~8~?*3;(x{eLGpi){Qn9G zCK7OuMWs-e*As&Iip>B~m){pb$e@&^P+!m=L&j&jgs3kZjHmq+O{LgSH1v~ItHNNY zp?D;f+iW;Xv9V+{Q^@sTX{fPuJXbOVn_8)<>~EpMPqy#FP32Ri8ih*PO3fAjD)ky| zmxr4xXKRi7qN$Zzs^%N5rz*aWv{Wxb!JEU`%FvqScCX8WG@YIhJS4vh+|ZoMz^ z6}#adnDeq}Ld>?SN^8URh*15V283zVJRwawhDKHYgW~uGd^F?wK$}P9b}hI{H$JB$ zAeZNGWmMFn3->jvIpUc|CWdez@vZvU6RbP&{$W(BbUdfa>tS#7Fk-w=VqyN72zjd7 z)#3dE9vuH=tjqh6WLXyCYURJu{dlrxGf2AHXcdLTy88a{p{y@H5EIR71%k^N8AdE_ z{5M{qSX+U@?Rf6fILFzvtGYz_C?7!}P*yNs<~a*79yIS=QXuu0pLO#`+xDw;bDiR} zA0IE_eapf3V)CY<)7nXcBzrR<^ukcE@?TKFTVO^g8aA# zGjp4udHUv(O5s#?DXWLdyOO}OVvHePWP0dTRlS-HRK4w~Xoj)m?&_5_LTyFPSQvG5 z5ih9`Gdfq_cvQZriYY>6a$;OLtl zV%8~laILf8r{2wUuVQv3*or6VqGSBi^k$s+j7G=(IiiyP!(aMsE#a)Ij@}G@is2Af z_me6C%lK(|3FVtwM0wT6?J9v7{)@Rv>z|V`-t{Y&da2LT7kODv&v%b*o4e#T>^x9e z)K~KZABw#r8T4w`2HdfWgbswUL{-`+Ye+1peO{xgP!!-_S^mxTxk7#OdU{Yo)1u=k z{VbI0FRs<=twiK=Z73zy0)(qi0mP|C{1hpH6O`}UQ{id-Zn{3v2%Q5;gz zzeq~^Q^YJdG^FNp@iPy%m{neJSTp0|SD8vNo9@uCPTNIt-H&1pE5#B0g^Lu}7cGFt z(1_u~MJgP(ggZj`R{=Adg~b`b<$+LYheyPmzit0 zr9y*>V=ft&S?kj!BDGN`KqiJum(sn936ad5bh*Hs}cUb%w2(qvM`RT0y6nVfL+ zUngP|bdoNt^3eD8v|5kEct`S@D zrBq3~yceE9*&ITR{TcIWZt3TA#K zD}&=wZL@u~ky@CXEFdjYt+v%2S(s_NX|9WPuvJyoZ$P^6aoyB; z7sfk{6MNHk+j$mS>$j`C`mi9_)vI^PrJ)>CPePAB&j`eVE3W}5@8Fnfbr8}&#%IiH zJ%n*}p)4xv*x&AY$;Rr!1^=w$``-1@;@3yYt85Twru}A&3>Fwao0)1LrC5kO7qIMz z1<&0L2#wXpdH&g?dGs3muo5nimLGdl10{Wab`tms2ze!XKco@Y@T*j1o9)~EZxEs( z1^Q>3)AxSF7{4)XP-TZV^Zt*uT4ToSpB;hrd*mqC!!^43T{uajE+v0Uz3|PSUGc~J z@gV%BJPg%6@l`#b}yqhsm@tw=5#~zMAjDR33hFnY`+O zX6D0mnObv&?&yI|`@_GwxaKM=>Onsv~;7cEZ?}-oky=^XP9+ z8)W0K0l~5JINzsDT7p)DyxK)lp=iG*5_bK~mku}J@sSD;81ctS?J{HWX-8ZIF zXh5e`-ltDworo}MddI8s_UB`8eEZU_+HKon=f1YCu+6uc*ea)wM?nN)bAuRYiaFae3ANqx0k=m(S!U)bnU3-=hfirwvNv9U|~?`*Im)(Us=5Jzjjx z*XeGu@)_4e&+h^{{(Rz#d|Z-YcAeAJL5e~o&0??#E)=C3gcl`7*{NIp;kVbmVS_SoDIKI(9p{fg^qD5g* zaK?rM*x)Ef0-?CZ&cdt^dTR)4SqLUL6di6Oif|CU3tbxs5hDvz7YaQaKw&cmXp})T zSWsvI=#~f&DJ_aAEPRp0a7*5|X$_K18uD5wggnh(@Xmn+4)Q~Q6cfVVlmaXiLJw0w z#$absILHzcJ+Les9hrw}9SQlI7Rds4NFWPenTZG}LtPpGSa<=G<{ZNj;p)05q+q;R zI7kE#)dfH+x{G$SiUtliyrD%=tPB1!2)rHebHNO8BMb5<^EhX5hG9Cg0Wfp{XwhDH zu4^GzB>)is1`ph^(hDVD&q;9&2V55|0zm%-Km!>A^Z^(_)&Oj9^f$OeXddR+okQwG zbTlSLY7htu04xmxo$18ZMTU}c$DnJ(K=mBoz(HL>AUy<7rY;_P-;Ed!0w*M(Pb7fP z!VYhOcA!p~w-DrQ48S^~NB7679LQJ_6hDB{0mj>Ab%N~SOu-yQ^qj*n(YWC#A_x>2 zK%zb}57UM$4jmk=4tLN8W6xkZc1dE2Dgb4`c={Ugx0p`C)?qmBoQSa!i4_w!Z$PsE z;2TLm5@r}K01YgO^{WnD0S+LhjWqX0`vt~RmjtrpVg3TgGa~@lK_IYj3J)y`CLBd2 z4^0M){R<2v1)zBjNFm_i$QY$RxQ6A?}$BY<}2v_j< z7ZE%g5kb4}z#)kxA{i;OhQpGViY^IMluR!@0}+E$XcJQG%F&25P?ktgb=PoK71DUX zp>^e$U28b{YoX96kS-Wo7mlJ2Mw2fCGGL*ZwxaXEZJJ@|a4anCAnb%XY(*MBtfBIyl}6d zgXQ5ldpK`>u%)B^>vm9dU9Jomg@rp$K@t=VkBchzNmX!R%u4}lBpjDHI_d>*kOor- z2j{%=r@;!m5Ok#X28NcQ1@C9*0x;AiLHcVrA{sG_6&Nfc7_)h(KHezcwPG1Cnol0) z`~3v{AdvbRjtVUbmSk=!cV2lpnhzkH-Wv_or_>JafVYohgpKBd1mjijJ3zef_JtgU zTYoO?{FH3XkNx^<*(3VKCjQPE@GB23$qVHdJU3jgR0E!^Zwvsz%b2}>gerl;u>(Gd zxX3DD$wz|}*&MsTSY+6a%w-{r@W>B}1^ckn1VzxgS1}bFI8aeKou1K;jm|OQpk4+L zCPOV#jFiImmWsrG3@RpWb8e1|mYGO88i0)M7P*oY|0Vr_<`uNzk)a+0QUIWpg3FMY zz%EJ9d#}cXr3XIM2ZU3a*TN!z(hvI zU>PbKIM?q!ivteQ09P;XL{(y@l;2k;?nXV<5vb$=2@af5z41B-(@$=Kns;luFl*Zd zizyTwseJJUqq6$u>r}vK7U|(P3LqopnB}y(pOmQU2ow=XEUd%YWM7o4dr+bh+6sD^ zaTzf9U9-9*mJMb@jdy8vR0Cs0+YTnsR1r%T@T-9xMJ%d(L#R;38_&TfOJl7yZ`h%W zyZmE$*X*R+t`}J`Ybt6k8kWi1k?vP0@WG;1+l|+Jg_J!s$|%k%J*7~!Dt*B z@o0)MKQnzMqKlW2G?ZM$jxrcoymZr7lkSJrL4dOa4`6R1W$Ss(;iw;!bgp92HI2p7q8iIj?ikpQol7|3(VQrJgj5Q`iwfk?sSYvsQ zaGL!P4Ay|rMF)Ax-^So}`K)lMsQjhFKZhefRxBZ@6MglEP46zL ztG^lnfxopF?zQCDL7LM6`2L}&SZGWLfWjIMy2_A81jJ+?R)+bT+A~i7$bojPbGIb$ zDK+ubcDN&Ac*Y8&51AHGGGD!L&nSCZPH!}ki{ym0DzNBs{>hlVWBFF26wTceC3rheM*j?CQX zJT%L9efH#Wi1d&=_HsGOe^yl)=T(#S7?XDUI1JT8WLA@DX_G+mJUinyb1yVS+P*~Z z-0#?ZIdfB2k1gw7-5+dbYP@o3xf`gAtFA*Q#y35HYVd$72hMVT9I%Y% zwk#8m4<;jUrXZy-0lkdnovN!!Og37-r+nd&7dl-l)J$f zk+Z>C!UBl$amYJ4YO8Lo-y&Na7+k1%Ucel4Zgc=N`#bt#W|^j!%I_tZri1*fGmRx9 zvFp}Zy-paDEYO=nq82elXV z5C6Bgjx5|8ab!(Dyh5Yq+JEIWYt zm4VG)57J+9IpF)EdND!No9iC)@xF(H3_m%M=-=ET(lDBd@ed2tBM*f_lx@W37*YW;UL;AoX&u_NXXT62i2R|7UUTqlWU^$L|2 zI$S{?BvwCsi)e4F=%zUBZg=eINbBjwKMG+v`XE#*5L^8@(s_F!>Z+t}Jp5PbL-?Mb< ztNo%?_pM*IPe+%F-)5XV9tn$f+S#Qyw-P2My)gO76aC%Ea5ZrdW8ESOL=;YH+ zbDy<(pR?){N*O^Lc+Ws^TYQ_CoBL4F{oppZS*ZSSlzLw%d|PGo*b?|C!#1oNkq9Ap ztap0oQ!CbvfBbFqG?43T^Y$)#|1pi=iAmj!CGcrd;(1!a5q5m|XZ5L&Gy{&*4eB#` zUVHnpo_jNw`z%blrOozo(Eaioc}q%e*6H*DWSv?F@@O)?FdBb(=tlY(xdVvgRG9TU z^K2GL#R4-g9<^A`rP;#vu zl?;A|mEY-FyJ|Tf{a-*7U-mQ#WMgS$GrsI=mZ&-;8JqMgWl1*$P^-WaHv4{j?+id| zug@O@FXTNJXlvRkp{p%-g;DCB7__+`uk>f?o~~qTREI`=I;#)}!=-jX%hYo=^)MC9 zV8>Ac1x5-#!K{2k$dUeeA?is}2O#$m(q;-^tYtpgx zN~b>(oyOn}yuqPJSWiC?#~Kp)#zicG?B;4ePBi=x^SCAZrwlhK##_TDuZ!)`Tju;; zw|_lV1X>XU?e+GEroSY^)fsq2s01?HQfQ>+by65_L%F4~Sc>YT zak!e!e(+&S9g~JO*}fMiB5ib}OPC<;j}vm~tCJ-)3gwX_w<@Za!`+1Q$Wwc6)yuyP z1o0}+MKCrfFvQF7Dl(;-Hz=~?x=rHaGsxJe!Z$9% zr^+g8(x@u98p@|8yj#?$CVKjtPyOTVR-?KE67)es3WNF=2^$tF4^o7q*?hX-egL9E zX`#W`q^Zo+|3OPtaJxxM*%yWX%V&9}<}X_6vi#cGx)#max<+CAI$y1dn{~c9bzYNN zRH!u7%LOhcbv2}YmLoHWmlgPGk!sQM)hbt(guxs z6V$+UTvqVAyY8X;XXDk_y}yIvyvpBwPp@0_{KMvR&WPq7B7J=Y@R63+-m+)T~62{S=W-hJq*|G&v!4YIC4#d z{(!L659s<=N{6&^Pt*Je<_E)E{~ckv?9`b%i_+Y15!>?8k~XAmW$l27T{U#4&91f^ zUDUpQka^K&&o5ipL0*}o-2qx$Lspa-#lSrnEFIuJ0(mj# zep0Ir=fSrTVlG20Zw(wq_zJ{aM==8DIZPNU@vg=_sXw|+%E~{x{ZqB-beq+3qQ05c z&Hd=HU@`dYvFxzhc@<)~BIea&#@yw#880vHy`5^+<-MC5A?~wZTH57vSUV{0du-O# z@mSY_A@P(kh%LV`K2AXGe?4Ut=zqHyf%L!MEDa2JJRC#@JfBB|le52hV+4rV{RkwP z2*Qvt2EKtwq6;L*nB}V?(|Dw?btWLBzm3uPVN&=W6UdOaAQMbkn3RnJswMvG&y!zZ z(j+YtVO*gmxE4a6C}t+Y1%I31yTd-w+)PAB7|>yd3CS48Zd);5(+X@<#iUT8!cfi~>~faF*re}7oXm{I&g;985xTbleGKs;yCkcGPe zV$HKKETs`FW^15ax(WL0-@&Aod%<6{XhH0Rg@qEw5G;YbVA{O({6Bj@e4V=J2+Ka) zcM8FDRkl)Jg-k%M$x^Q)*JoeLtXpmB$sq|t^L`jAq>!^$=L!5dL&dXSLzUk{qfF*O zYqgccwAnKffYAa!EhR%%?<%akCvZ&DwkvI8A>45&O?+##*rwFB@8^Ywib!T*gZ^|{ z$s??#Iun$9dOd_)3xNKWe`L&F00Ii^SPPCGRO$&x(}4z%?F>l5v=;34JptvFeK6rR zYXqTy%`BY_IfH#`$xa3E9 zq29v;@+xG^4Yb$B98nlh;aT)4nqh0V}UmWhmTMi z<8FAFDGh-7iF<@y$1jRretmepE(}WqY#|^C#|DJeVrtT2a-~Xw#M1U%b@PHh0CXu= z?xf=S=qBx9>o^2)XQAv*IJg*6eXpnG620LuX0!~Ht9L-Ii^Cmf)SwaS`rH zguK}kpxh=5CJgeAq8@?QnZtg2bxTGHyfURkuwqcss}L|m1`+nArFcA~fuo~mUOmGy^3_v_d++xG!2u8I4F`!9-4?)TGxP32ldGdeIxdDedMyVk< zhc(i*o|Sm+d7g-CUi*C4Q5+u*l#anUxy)I@O>E+C8HfSzG4EFU9El04u@>47WmL!U zh4*ChL1F&N9YAS?=)rpK;N*XQHXPm-QPsiWM4*qZ*aC&1PqZLXIWYPw858`Z>|RXt zjzz4U*-nz_fu2X`4|{|$+A0`UysEEBjtC+PiDl&!(ExEGj}E@x-o;q?%+tROKAbc~ z_4XzTeO(11n@J09k0Nqq_~x3@`@UjKR>DW&X6ec(@dA{KgMw*Ji)xJgI--?*_ukr! zN;*MGSnoMP3< z0WVA&i7{Iu+S)Lzfo$J`(-+^HpNZ7jiSu#4_k7hZ-N#|Q1|+zHkTjxk)j^1UiCXG~ zJC)Vpe5*9_s$}R0eocs;91V3jL&seUcGP=!YbLdO__-a${@8noGmciuy!;(_{Sp6s_>lGN^_BE?n~t5V~7P;44J93B6i8vrm3T@09 z<#vZbLlsRIjn%~9+851mXIgX<1PT=`D9$we&NoP@3X*!spA=G)j@oTc2q7RuGsgtJ zzC%l~6O^8-cESwR28iJ_2wODtIf3Ng4)-~SVq#LY@#{r6rFC)9qSM}?F#k&7o&$J1 z!Hp!*o!}_1>uO)U7Ps^YBQ|bxDGR|MgQP#8f96IZpBUKZ1L^KTnC5_=DN(44Xg&IZ zkni>0aZq+RAsXH{vQmmcoYMNCyf|h61Vdw)Mjga#4@f{(KVlpHhXLddhHx&uH<1D6 z4uy-9@!;VANz>#ML?Lm*XnfYyFW8*I94%n;;gT#m7plRJew=kbNz4F^pAc=l5CLgI zV4lo>r_|`Z6-JNBK{^+NK3BN_L1#Gwyk-U79{>c?-qpK?1OX{b)4D#=a$69hQ6PdS zy_8>D2hjzE^IQQ)y+()-_4XR!5$qB$ieMr_2z^;F9vRQvFaU}R#M=Y(9B|_SI9}(q zgoA(th+uk5Af{fh#9B>m(_j)1NKpq<=;$umD#>&mUYZ`Ig(!*r8fGGcA=8zh^a(&3 za0vC45KS8DJ1`Im;d=X%-#`yC!~x-~6H4ZdsXSC7Pk;y$vh(Rd{QH_X!N8!xJmoSygcm3*=z;}_-Dt)B}U3Ot$8@@C(%?1@ijRM(KK>2K6D~SWx51k9 zX;pSm_)Gec-i9XzYXSY}gJkjVQ9?8=Fx6*_rB9UC(gX#Xkq2x@KA%rtU8)H)C}GN< zsYhw4WO)gmC%OMkp;1ktb7&Fyu>R4Ua+97C(AJc$78bi6_-HW=I+~h#)RIY_wm*_1iDzi$-(bSxS)w_CMT|9zz{($;3u z?bqIf{ImF}t$+RRL&Lu>!~aY^R(#iPQEDqP($-NuVC4G##WZXN%&Ws%$vFOP#!i;O z`mAU@smS_z#yoRoo1*X{U)Y|1R!X*@)wyuuamK@<1nl1s9*OH(tjjk%3AT>(cA52G z7WUHS)LBTTqSg#%nhWNigUHT>XwQXO%!Rqng@?^WB+o?_&mp7mqJ%m|#kOZ-sf#5s zLxs+CeJFIT_s~8gKyOff{^}=6jzvvzpHB{(Pl=sRO`gvvp3lsl&uadf-9MjwJ)eWN zke*EZ85Zqsp&KW=Adej?dp1|%zTjCGk)U0yWQyLz{dyX{usE?$wY^Y%y-zN zj%l%;f3ZP!u~B=m$>Lk}aae)7POR!eYky&}yMC#~g3z5_$+KShF~f!TWINGPPbXz= zeNu73;_p$0_Rhrt_oaa_{q8sPCMFrf%}XPy<)C@xfPZDM-*BsWdG~tdG>l;XjnUh-l?(pW%jT7%?UhBe z)f;ys1B%tVQM#+*)raQQtL<;c#fD4%t1k|Q_h`nHZL28EYruh(r)@)|_S$#6HS`oZ z)bKUT6yp-vwZF@&Xaj3vZfkfR`B*n=1TSk7qiaNlocIDJZ}eAR8|o8Ut^+L%h{M-4 zKCZvgS-*BzrxaL|1cRt|)+Hm?-{KdNm#kATZ_wZ9Q4N^T>X@Pto4yj*V9_yQ>@uNQ zS*JD(Wg6IMvN6R^*?11y;F?+G>{{hu-n^UJz#}n3a_gAkkeEFdo6>Y`@TP3m2$^9x znlT!had(*=WN(TGM2I-9eazVq3pbStFk`8SrFB_-SXJY1cD+*HggCL2kDsY|X)N*TZ&qJ$5(X#wsvp zm!xL*4b7S#dZGW$ZlKOy*voDZ&04U>x|*ChGQ^NJRML9fV(-Vy-VcvGOqxBH8lz~n zOhwv#X;x57mv#U0Ub3Z4?8)9`*q%y?wGoNU9PNJQz`ml;{;!jzl$-rr!~N6%YkPE? zw3_`|#D3O_O^%vDp2tC{rA_{dp+(nfx*%>tR=iZ`bC3_@DXK)^Zq5V(V6OAlP-Fo^x266ADYQgYO&^3E1~_9sbri z(icCxC_ZQwFnT+-(S2gule5?=e)Olyrnkht*YIeZ<}h`}?y=dnig|qu-+n|+e|qO= z#?oPW#y%_D_Gdsa1sL?R>sT7#(CBE7&er2wB&z#W!K z9CJ^O4+E?NmmN=5bkBF3&TgDenNP<8PHxnkfKI2k9!}(CC}_~*`KM7X-KG zZ&}VcNiS}hFX*AcVGNhNPUlD_&x6JkXJE>achbeXw=-;m7sA~xvnS`*I~TNEXI!4A z+ys}rT$faYZc?i#AGi*^4PAlZ7vCn2io;#mj7}6%-Gpmh0bC%$LD%b(3))>*2^JSg zjI00Nz$wYDskyJUW{>X#-12l>S!Q=+CXbZ7t|)V_^r7xaHE#H;7b@eIsuE{hw^#HS z?!2V#nk?5^@;6!-5N!!JSG6mkp&MQF_1E~BZ_pdNL605IBk4JJ!&z6Z(<|e*mnPl8 zrd-$Nt0sBZh~w z;GGNC^?#;h7zTve+AAW}TdNlI)6ugn<*uyd#G7=_bI2>!Q#+pJ!LJsSbnBVKb^lWk zEMAL}Ea(*)cwb)YossJuK>(rkx~n=p%3igOzP%^u^2!{u|4Qm(@cyAG*DZncK2Y5! zXwWs->ERdGU73@2MZ|qZ_e0wFL)Gd-RW88b)b{s{Pil&%j@o8F=0hW?cC+WxoVX7( z(6^Y&yH(zsj`Y^~tw;HwZ&Y6Cu^-EVgV zYLtaO?;>9?B9)Sv@v_X%XnRAkNja-P6$v<`tn`{ydgo{ZKPZf**Y@fe6yo^hk~nNO z8Haxf>NJ?An+@WniCRup*<9}6(~3gorpXyG6LKY32(!6|{{AgeNM&;vzAB#zi!0Hr zw!LPXsnUnK93NaC6x5jxCcU@2;m~gko@sD6ym`L_v)N6tu&$eI>F~L|I6l1PT7yF{ zUUAyrac>}hN0ah79^LV5b>JV-o{t3BII&00>~2ZLcR2G`S* zXVJT}jlrK*Pxl?)M=}ISWy%csWTM{4{^WGfH#>N$`r00Vw^*#wG%t{+{^7i3O0DY| zJxi)z*m^01hARx;W)gqCCaJ!6aWaLiaCXG^ zUNlo5ORx5ELkRnPe7?b91N==nS zw&xd~bZgnKSmtQLltiWI^_1kCZKe{(s5cww***{N%JM5<%;m)`-W8dG8$wpuZwK8AYd0iAlF%U~B%T@9W@Q zY+K1(vE1UlnI#te$W~Q9woqE#jF#~;uLF%ps#eBEw5sl!H_V{nUa5_v+e}#bdsCWf z%=;cRN%^-DQ*c(iv>$2QGk{T21>ROWiazcQ>^-H@td z_bj*;%s0Tl9!9xxJ!`_w+46fUCsts>wlStCDUAM@{fBd|yx^|7c(&l4{_*J1w*Z^~ zk%RJ6ccH`T_L}tXF(WI-u-6ha-?nV+mN@fM&EjA?zud+BzIa3g_~{gyVWjR?h$6*i zYLz8AuNuFdI>^NBdOMy-5md9QccBUrp7qo!iaord?|%6*Y&9o#bv~lbeSN(+etnI+ z7wl-9hZ4;Dw|NYTp2u>z?yze=M9LSp*E{*2DC0csu=HU0u)Rt}2}7e!lEO6vfBY|E zh9zE=J??W{EE$=G+%wDm!I>rYf3V_u?SIgbIXzj=~)#2CfQn0{IR zCQ6xza&(&;FJWyxb;gb9N+OEIG$nselMtiwxI}t6!^M+QpAc@3OQBdcKtH(`8`m_C z+#>sc(l!$3nUyGc6)7*CF&^*MxcC`})%Kp~BB4ZV+nBg~c;;h6vLM4G6;V?Qaz!tR zb?Z_EKG&yM?A_oP^m=;;UPKsdZfaa6#>}hLI&48amOKVpWW@U-{AvC?C40z%c?7Dg zdF^7ZSx(Gdm_pL`hA(|bjKwIeTy0dWF?-?zF|I4>FZ~xs6JJIIGqknN5nVZAJ(S`r z!bZi7_$uvC%$jn!d?M3AB?Hn%|Ixt)uDN`f^RPrBQQQRAc)2tOzGqeV95vz2*;Evr zx#Uo0qbOs;=lEuHSGG0%6WU8dq27bFf~!6vv0|!7{G(0q7uz8toAYA6=yyP?jK0|a zBB){PrD}z2GC91Lr8?gYWN;$C+^!{pUo9V4@gB5h2>fFgN@mk%Qut?Kh-|JF9I2>< zd3?6le^s?dR5{f(1aEMWjkS3`e41%ff)dYs12-2R9@%~&pTDkAIxbkc%XrfbY-t#K zRmFx=`4vFr0ZfPGijywt4Q^ZuxuBMsQ#iVF8IpM zlvFyr2iM-{e;7!qYs91D^YmU!+0psj{(i;gmIASg4sFAvJRy%coaxh)(74)-5JPnB-=tDc_dO5M07ian`3Hf3Sb_9n0%czQzvZ;Ke@m*#&{%lbIM;GUY z;NcqmLCjWU7q9qBQEEMB%yK?EV1NDjW(~y^riJyw4I$-7Ku2EnAg5x$^vR3b-*xnA z_pX`iiejqpJYfT7K%O|)s!i%kp;wGI&oQ9-zAOvniM_FDt(CK&5$+U=5M_3)8l;SUyrjwucX(XX6~HU zUu7O^31hcXHId( z`Vf0Wy70#8@~`iWg%ecTM!B(#Cp~~aUT}F#&3B>Qu85D~es51K{{Hjd?J{kh%|hIMDviV_)%VI{jTGacVv2w0)5J&pIoi*q*KjR zwNuFcibvZ^o}oqgD#1<_dt2Y_qTU8m_F?jk$ecQ>2iwo(6`Wevvl>H_7Q5wRp$Oll zK73t0cGwAa_jQ3$#7(+{7&OkdeRT@=4sPUhk}mMHjwDaNOUo2JE(!2kWiUD)(hBgn zYT;U!_;K${kd0`&5$i4ldjI{DepRe%FcOvSlULidSWW7_OJ3{IP9i@DDD7fBN z*L^=0D1KGQ^}HMSd}A{54D&R)TXBs&sJU%8Q+4p$`sVkrBO&oHYUF>|?S4i$6A;{b zy0!Wrk#*yjcSBrfSC`$$JtK)nVO)dHL5O^!ry--;zi$!2xd{Fo@$K9frd*^dEgJ7z z0D7K@h4zy}`VCzk#=EuK?d4~F5|CV8i#9E`+8UbaT6tEE@o^5u0x4$B@?qGjY;qnJ z@i*)fA(1WSzshJC||E6A4(@C4TKxb-7X1j6hym9GGT}78iQIo&3w;W9s$IB7Ic|y;1Q^55?&wXOb ziNDE9XvR&$z{||QOU%GWQpiVP#>rOrL5+c5r;y)}LBO(5z}AefVuLNoq!0cEnYhd% zV#-P~wt=!?wYDMPX!fCnLF~emZ)}qf8)^1&l0kf>P<)3$;-paGhC%YBP!gR{3cpB- zgz@7_p`bJ!drFRwP9Dub!P95~$;<|(q1O6`UeN&tc@J}bibDDDB850c#grliQ^KcW z8X-$#87Y&A)zYCw#Iq_Z+kj3I5LV^MJ&q8i@yvPE4DG2&@h`amvBxpRn0RI%6(zp zvbc(6DhW0vaakdu8PjKDR-|CI3P3Vjt1+2%Wtc&V%`@J1oEHllGN09(pwtXnhFgmI zl-SRdIHYV@TV{M0-?E7_>n$%~dDxDbF#obrA}Uho%v|c?WA13W;3#eBRIo;#WC3nq zwru<2%*n!!U*h3W>ZxhwO1$7YLyU5w=a#eTM4Vy4OZ=YghjBnDuM3Oc7>oajsTcl& zm%e6vcBvEZH;Wo(-;L~+4lDm*vtSxl2)qN?*<_L35xlwx=3jUY=F$gmZ} zvCM^&HH3u8yo(}KEw}!8*T*p-r~o6Fq%7Q}EM}!7q9$E;a>_bx@8Vx(lqroC4Sr0O zwSUWA4Ej6kfwJV$vVfVg*aM_Rl$y0Wy0tIw?{!Jk80>e+9@Yocrk^0oiNrR+^LuXi z3sIb(wWQ0}0X8lfHpwOB1}8Kr6y+fzXDhsD#~+-E#rpD zsoTo$ez9a7kcB?5{5;sp?v3l#?qx5qvHs63(P8_BUXd3ropO^!P0be1R9^aTUsIsM zK+%ZlsN6%TqPXTj+w$Pvp`u5)?8=+1M2-a-#U?CJQC@K1Qo&aFa-iN;ai7mvHJni; z_qKW?Ej9e0V8JGgBJQfc#QA}(PNz~0+Yb4LJ!N#_6|-H|O-TXdT~Gn*dYY}LW@U59 zp@JzplBn`iw7U649&`Z79>`k>6L{C^qS_P};!;rA_EIU|V23t9jY700&0JZnW6~JM zW+%s9yHL^%toq$j2-nODc4q6CWM`(g@8l$_QOc%}v-_>aF{EkJe_>o@7}qoWE-Pmz zX@$MeHla0zWAx>4=wz**;&9uqGPdQ&+vlivr{a&C5yRP`L!A96vjgu+6&XdwDR=dF zcyVv9{j%^;6WjY4bdD+Btz`bRQ|l_YT=jo zyG+I9KQqje71b-8s7v$(Esj)^SMRU9t$VReCQO&Q3XWGeYxuEG28MMys;V|CjJ(F) zXVY*teto~f%ekwD+}xVUZ#PUHJUiOOcie`s`}y1N5Id}R)Ep99?)z-6>W}XY)b!`n z2&y?OyDTnu)tuUv9-Er(x#)KUIh=K|ohUgRm~whBot%n0xzIT2jX6G|L|kpyUzir0 zG^9t`a9#z}+8fpi7HoB(M4U%+A(u->IGyHAXXYVXPXWviO3Z7-{ZE#rj%=sfEvHh~ zj!!RKM=Pg29@R@&mBZdt*b3lzw$ zV_0XtQ?*ZowjW*BVOa-kJk2=&wVzY50jXOkIP)G>`#b?QWUga#cj-jmdm9e__b>yml2;(E^h;ycfPz;V{>en{j{FKd~#XIh5fc3@IV}SwB?66X=t?#RnOj zGmVr+wkc{!7VA%vT5lIjS37=}SJi*n1g&^)J;k9OIERj_ADW0A zbiWB|n?gMuq27%g_N5J74K-d)){-z%ZKv{&xkX$9=Z2xm;{oo*j&atszXbr-tJ8Ta!%4x@GT2KN65d-H#& z|M35Jc4KBR7-NmGlclkgondStjU~obGxkuCWPNMKo_*hA#+IZSkx(&qS%)_5Lr9`% z5vd&CbI$E{KHneCIe)_Id3!yV>v27<$6YUXKUrHPxj=rmK-r+^NOzH%L9t$Ju~~Pq zyFtmB-Qu9`l2C)v3*BYW2IZ06dqhC%?~}}t!E+c znsn{M?zN8wwO_kyKN~Q9#WME08KQ$=yjZVkZJ$mu8vWg zq+aKh`0CKTj>re0UPfKD@d;UboksV&>mNKY+rQtF_uz8-?*}jTVn_FS%=8|;HtI9d z>s5Oo@nO4U+o-?leh=7)#gou2e7axH_~HGl9Xt;P+KrkF9u9xJe3vJF=%jH((5vAq ze}cgeRQ?zaxx}a37azO+$1ls`VW!1U(OzQx!||Die#rw9*JDa%A5MQfsxqIz8vH~5 z_-9(cWcJMFb*#yp@}nQpkLL6qJ-KrGuIZzvCr$jXh&?-F@;rTm9$@k!`oEd;k6xrd znwQ*~FMIUz!ureWk6zs|d42!U>pqh=qmSOqn7n=Q=8G;ZPqn6N*L&CQn0~(B`?=3_eYAId#&qLF@5X!6FCTjk4*IXZdcW?QZu0bP3Ycw) z_HD_SeN*oHcEs$vUf*{!vmZ8nKTewcbnp9l#%w#NZ~KDTujsyCSIlC^))w?-LhB@zQq9YlNkXpdb(>uILQJ6f!7yrv30yO-X#c(G6vB;e)hw7{U$nIkH? zXfX@`lh-k)O=)&Bp9)Ul4+^wXIw5OSVJF$0o!`cUSCVr{m>U6N5f|R~(RoBot79TQ zj3y`l6Ra~&7sRTBW%veIMhT#CVe<@gyAm{7H%yEvYbE<`?CR^v#fGdjIR;@kQ_+7& zlo)0#_0o6Zaj~j^;p^r?azavGmQc$4K!Myq^KiMU1V^JN%lE7TRJL-VE?GPKhDC}t z2kA5kglA5&?_}jYIeIDMV1ggo^nVXfLU?-#kSl|S*LVkd^zBPQT$Sy970@th(2q-XoC2WDxT8i`q ztD++6QsnVw^|`7f{tqaxi&G1c-RTTD)RAcbf@n@a_+}*iwfLnfzscqs!4Dw*;i1CC zO!7iI7phg>e-E{)A+a-{Kxl&?!>6!Hg9R|wwuJJI3cYR+D!L>m3Ma!bxp)v%8$ef5 zg&AsNEL4;VKo|!(-O9(v&~X|Gzq_6c@u0dC}s9!Eyv^Y;*%6tePC}-LUw-g)arcH1`xvAlnl4tc8M+PEF~#%5k}?!ROPR{wmmR3vuCKwTD5;9zu}Y2HtD`X zEf1H}sN(h>)7lz!4a*u474|+~3dsVCztRwJ(Qo~4&zfP6JLX%#%N5h3&h3aM9k4I-K9HVl_LN~&c^&+e+W3j$9S>cvA zsRbLeckOxKii3=mop@tlX5SgIcl{6v>h z1xX%MSxo;cJ6|e{naXT!Zy{p5{j_U19je~YiQ}JEXJXc#)JaSQ<8&p`2MvAO=$jwR zz;>2~O&Hd~pK1qJ!`8W`Wz-Eb07Q9P^AV$Jr zp2~h|ZdXY2Y8VZqHYQ=cMoNNtA3k5Nngc@|D@_^@zMJ)D)kLQUKKw-w9idN56sg*O zpTHj@lqzAV@F_}TqgB|)DH^`OV~A@hLtZ~W+f){$K2|I_25g);IZsNG9Sd>t zw0JE?B7ljQBxEEJd^nKxL}y7pTa-G&fTXcEdzL{{uMpbg#50a^b6!PN@1DtN6!;-sN}S8okaF|?yP`M zT7TX(ZVGUwVtwB6V05@s9YM;lXbvUnx+zqXu3YTNlU)8PPHKZklLrrJoar{g7F;|o zd0B8TVSVgq{7Xn)Tzso{hndmFy@|M-#+&DV&K~+TEKa6?58U7qVZvEYZcjqFFuJKzo0p)0^;?^9w3=aZWhHDtpOG{JmyS@*R`1dZ)ASqL5lPj

1t28eQEq!dM(}Fkf3zxmjB9@UxT?34sVWHY8{vVK$F{z;` zcG5her584#HUM+S-xfxq{~}ex#fc8*;S&kUKfdb=x%K64-f5WG%+#Fp#g^j}w}NI< z-Tz3>N&a2+`>=EJn!sPS{22u)qURVW8Qrheh@b19(cK;6GZG*IMV6i9br^!2vXFh;z(tyJy`=My(l`XyA8Jd2)Km2KTl?Y9SH4o@M0|lioSE=ULMPk5 z86_aE&E!aPst8uFr6gD#SKx5JU@!nq4uhDVZT)&-H31(`Kj znJ&D{Z#wcT9l5t4v$7!4%ACXBT3NI$P_kRSocpx(0vjF5HaxMn$~%yG``W+-fwI6e z!8ounCB+cOzs}`Rr<`N8u2ZOS>Xhpwxwz%<>^$yB zCKoy92sRvn_zyXr1}jLB@&G{)IZ%M>$~*70!_WC5Efz$+4f31f;Nw=1Dz<%M8?c$? ziobw-!=vQOJYg(gI;SMx?Ej<2*L2^S20RLyFvKC|xjc9p0(a6;>B6J)%p0bP-<)A} z?^J&QT4oczvQ#v70?nm{=*Yix>D_*rO)Z%(=F&k6BJZ|X)dG7NW9)?K{xwo<^X9B( zNbTJ_e2->UckptO)}~=h{$Kz|Xc*me9{J-o(2cuqOylWfa3lb*6f1d^Hef!$_V-B$ z!CB#WArIG5(|XIGP9ALg;d0m=;4l7D7Qv87%JIsS0Ao%0TqmWL)+T2HEM!UY(e20E zD9m`6gET*%Gf?k5LFrxK;Ye1e15NcWBHWIK;1IYmw5Xa5o?r^tk^x6G*`zU0ru<8D zg8UJUOUFXyu>Gi4RO$WReB`by9vX> zx>I04SB?3DBxj=I?F_^w;ZPY+YpG!bKUMzbw7efRZrmQ}D^%Q)ty6PbapsGGH#;mNYwF-@^1?IK(-|2YOOZaY<7`q=u>hA+&YsqHSZ1dKJwyE`pXSVEX3cfnGriwcuC)DSHx@uR%wS-}B7jyedlpDl}>2IR5V ziqOYV)3h63RUa@; z(Z_AtYlmI~g_T^RRp({!%tPMoc0!j$g8o!a^o_dtN$ z7?b;HhYSzF8Qi*jPBi-dj*44EICQMLMnmHEI_ao3fBD{?aUJR%pfNE`B7o8~@#0s&KbVW217S>ky%&>dB7uZ}Sy(o!?3={SDo< zf4lW1!f+>d>8cvRXG+T+_k-ClLB$NQz}?u#{nZ+PYZ{lX>HIhpy4{zUH}{HKozso~ zx{!6^ywH4jt;bHSlVPL4hg^HdJl^}#{FP;YWg*xerc6)uR7Kshmo@v?`U$c6K>{*J zT!sY@UUG8%3`AxEg*Tab(Dvvv=31eStQvCTt=}!Pv;DR`hx80lzkxY|p3Ls)CZtYX zq~W!*vB4Xoi6L%B-fN-OsAXUm-UI-WOHCWWeq zdR;7EF?aY`+o0jy3$I#d#BXU;Al2?&*QpBEdtC?><}rN@I_<$*Okolk(Cy#S(sB3R z8t`|VyjvaHsr5(o4M_7xou*LN;nLy*)2GgU55YKi=~y@$?0sE59gFUAB&1fYrz!NI)?&}y&$Ru^!5X*?9ura%bFtvrTCCA52MLsp^<4vvOcgNpv%m4RaePW=M_xiWV zx$OU5PEKLI7|kBR`cv$T&I(r3kfngQeVQfrse*e`anr*F4*!V>o~(wSpRenArMr8y ziuX*)R^EN$Ewj&be%UhxedwIp6T92bmLGvRLkDB?rjzz&lJBjXGWhkz+r@M5*7*3;@$aW8?=ukn+3?i#?sSE6t+J>@jEd_sBAR^Vc?1SN|R2-gc6eIAco((@q4hsk&Y!_FeCYE$0vzjx4)j&+JqhP zxrmqe&v{F1W~=pwmC7An^*i3-r0?g)4NPVP2{YLD>*u>D;3fcOfC1iiCA7+Z+f)=* zM`Ju^@xe28zFulwz4Q}5E({W?KE0F?lIT<3Yn}NgGep?XdA&DCs7e3*?jBi2B)0n6 z@7O)+*U(b7oI@_qj0^Og%R}=SW^V$_ZN-VF(9-?S0>CM9=X)61uFcaKFtzMwOae8d z%7JO;`2loytV};3oQ&Rgf}P?;Nc1?+2`<^f0(`k*dj(H8LI|;D+Tp7m4U@871o}no z0eewCn~)QCJ0XLm$8B#dpl5Y4RYK0a324w^7adK3Ix)ZY0gcxx_q089=BUW0D)G+4 zb_Kr9Epk>$0dldTVaL7O8p;7T@aLS1JZhh|T++LsNYak&Dv$~}epSg!sme6R@ae*V zN%q9WC6)YjosPkjv+1fbeQzK9-9-uxBtaF2H@Bv39J|8R7h}FplnJ;Py$%}S^qx1_ zQ`7wWWos~9ATDP0@3-B{(+|YD)?SEe9A1iZZggOf+Z}Vv`u_d>v$wY|K%s&7Z7Fn^ zbOt2}p*cpm(gt7J?}wntTyq}lfV-A($pjh*Ax>ghIG6>qfVO-Yo6pnb3S8$raRpeU zf_@61)In;Yt^lg`ryq8b$j}~yNL<<>pJXWBdm3~yhcoO-^iC6jotz)2bC>&LKBp!v zMIGfa*T451eB$XMMkVwpAyqz50$3`nxG7?PSal44)umG^z*!(O^6CK5aY}%Lh=B18Zpf`}rPpEi-X6;`Tiqq*^7Qk$zlnIPI$9mcnVQQL zd+Ngz8by6LXB9njHU0GMX}ZqL&7iL9N(tYeMW0C?kmkK{$4__ukHzur7ih;MV&_^f`=f(m^@zW%l*K2=}tePG4B z=(+ca`+PCnBmqZ#y1+k5KiE}F$JO?Vt2qf1pt+bTDjvfgls=Y8LrO}AHz(@zPMhZsh^9I04U0N_R85j>ktHr+8wNit4_`=|^%6@)z=#ePgFH{&-L2RfyFks-aLMKj zNw>{w2WJ&JJ0YFKz@);^Y##D+6k&_u@IW&EiFbR(adkO=Lm#sX_<_-6(a7co;j(V@i`3y_- zI>Ee*Aq8noh`_vs&UQ(eVKD$C0JlH~=hIbF7NW$^7Tt~zVM|z&%DM4)I};1il4x$9WnCwa^r+`t_;+dO+bJJ_$$5 z<`Y-35Fh#0Ob%ZFpV;w1TjOBNVj9A03?))YO{tsr6*9>1P*T!TGjWndxqBp)6Cz*| zmI8b(cylq7(^X_(Kxq&`2Ij_s>u>AJxjY3}4HRJ<56vGR^ktc>!$8TDyG*RZNljN}Tb%2fPy5mJ} zc|~;rS7B-4%3kG6Z#0K3>r({6G*~5wG(HyfEwC>N;rbV`OGVDRpF%hgER?}e$g`=odN^Y=6G>L9+i&{Qps1dJ=E zj&P(q)L5X;01QjBZ_&5+iYXf<7W~6=YzU@S&01a#)}`}f+7u`xgP4%wpsX*HHC{tc_&`3 zvvp8zwCf_R9B8o4>!(rR(%}8$i*B#uUcdR$Dd-2xN`3n3^-^zC=Lemu1hLK+uJOa? z*n(kHB9GKYeuRH)*G$6wCoc>FFN>DG4YRxRedM|6kA%BEUsBW(7Fur+9mV-06x&zc z+@kYk#-2Fp{=A&W3qnWJN`fe4|ZDMwgpF+O7m`06vcFN~| zul_7`^sOYFx0#!E4Qav+vs2lwa!o7umgg?vM0(LKDBUOmBg9@mdbe!0G&{K`EcV}@_cQ&frxRJSM>B?_Z+*PDIkbQ2j&|(svBWzI5`pQ#Q9?Za z*DtKu#G>XCTik;8UR*h}N=FGH=^U`vA`JJPu3Rp$A9P9A{XY?StRdvGhP#Kmaw2*) zu?k4TX39OLOC#EEZVGuzPKWMmc|YITqRp=j6)NVB0MyKqoP4kQAvBDG48oR|0q zF*i~B9A(R_7}jts=X{D(YC zHo?+t<1Uh|#HO2zzOj5bSgwTk6a^Tpy?-7NlqmxO8WR-X5}jl&YF#<8;Gh9Pd?qAJ`>M>`*um<^u&88{9gBIf#1;L7vh>i15s9d80VceXLMeJ7&X->- zo!q9!#;xYMUo9EAs4vaf*SE)m9aBMvaFF{tQ0Y3L1=oxIRMwdQ4m}F((Z#E7xP=0Xjhv8czXP07Qb$o(bU9R6#?i^Zq}J5NP4TCUcWBG#H}Y z%a`|*j3QJl|4LaQ_KGFcyA3B9BbI2J^Wj&~Bhlh#E6K-HQf|7*+^s0iBlFfp#jZY= zh;u3N_*B&wdtm-U3v5Eg7hQ$Efl>hw_?7{d13XFLJB0^IGJrxCA&wLv_yh3j6G#+A zQy|L5DIaR=lqaO+j-db@WQBDFfr0=bxh)5upRx%lMX*%lr=lxGREJEvZ5i~O30_>$mmTwr-JOrl?KBp-^#1FJDmCpN5^By+3>bc4i`=VTN> zg5}ri6XX;+=pZZ!^SK+yIR+92V8!Qv0cb=K2Qv2|M8A-sBdnT9WHjR-ib-a*PP~qI za0HEEK|&VMk9(o7^L=A9dt4O`$=yqf|6R)bWa~<7mJqO$sdB1H3u!)78LK+poby{| z;Bm=MIB;hb7FFzYXi-)<>A(~2y4!BnjF)?F0aRXupTmQt0a!<7gDV>bX(N;X_6_)G zkbeV$xj1>3Z?LwPdKG(zwuVS->9qoWe znFkB>6b)R@cxJtAI{ zvTSe1xz(*?hHiv(*i>Qc8}thnT}}MVFoYzk8_XAd4b1`gl3@B5_YErKO&cl^JXIjK z3>d4c!KE0)hCr?op&dP-&U{2D1e;4i1?piR+qU0?wsJC+pU6QNmr_l%k0eHb53%5m zT#)uASeGT6^GQ(bV2?C2UW8Q2S7wx6R}$90YNmgcLF=|M@D#|Dv9#~7wePV;-muRS z(q#f2!(n+$pjx<`ofpqE}Y%&fvC9YUdK7aJ;phU9Y2On)%32uH?qkI3Opbhg1I zvT!Meo=<}>$M{|Tx^-PRMsLF=A@jG)s$E^98rybaU!s1@rjrYws1T}51`AVwZl@rf z>>HAs_GxXxxGj)W2`GKb3D<8te>E@Vl(V>%QQfk$1*=h)3sfb+MAh9t)-^i9dINsC zRsedPhvm3ljksCh88mq%9vhMA`f$FZ;i|gjgQ7ETR|UGdGsS`&Wj&2<+y*-gpIXOF zx5Fn+@q*IWAC`@71xQA)sFAClPQk96fJ1kFc%}n=QmjsQapB0>GgASQ0W2OTxR0%& z#x1MUoG9379L)D2&sK)#lb^+**##qn(^wsiB94V`SQ5s7VoDs@il9zfbet{F`%g@! zJMDa;ijGUzaJ|F0D!F&$UcjpnLR4YE(V$uh#Nk4nNaa`0C5j4Ee)I?Mjr;qJ(9dm; zCpJy+%JoS9W^Pl(GVJOGy~igeCwYV>r{3V^f-2iRnzifoRw^%ZTBlx5PJxb2zDM=E zRiFOgFirHA;Tm_p^q&4aIlb{leO0~ri~7uWhnaB@`)BsdZtKk6Zct4&MexfNxe%V^;XYtjIMPAn^ZT7O_BGKr6sW0N{YxLgbYqGblhm zXjVo<(G7yScUF@vZ}JFMhGi80!hs9g~CMzy9x(UzB=tLWw%DWBSLIIpA~3+ zOz~K@3T_bHO!l_+=MWCml4NMeVx@(7vRExMDR3S@g*F#Mdx~wD<{3;oo^v%=?CArYX52pL^@d52qbT%VrL+1_V_|zHn?gMgeYtf*B>Wx;|IG zZ77lX=5R(m8(V!L;-EiR-ujNzM*D--2C>={#d@WtA=<_LEDOX_RRUBbSN=-ATW8Kq z!b-(d+#6Jce^xL?j4-7;pN)ha)*5D<4OFla#3-dz?>l&$J)YYG?S=D#LJBvZ*f~Yn zI&GffeHUT%=lHXLLC@O5Q=4v=gULF{unOQT8v$*=jN8GioM>V}w$#+KgGb@x80lc# zAY2K9$r8qtb6@aCsB2%dHs^3NWF4~!sj{reO@K&l%3=zS(>j$y?QHu=MEi(ghAwSZ z1Wc+~0c4?QsCcry=;x>iA|g%9LR>R28#ll^BCu_W;u|SsH3u`lTvKR5nqg=;>m&z>{za4d= z2^wRJGX!i(?TNW|)=ZIm9d7%_!)*oIW6|Ka!Ly~ERzA!!|K-wvD zdw5R@{5<5RRdNEq>*HJ~iDr)J#Mzqz(FqKnP6G_fR_W;QPBB5sEsHKD*89s97+8)6 z!K|c8T|0vMg+|2V8L}kx5%s%AB<@Z6XUX5gSllKs^yP%@WEU)CCE^}Mr-^GDxDv#m z_p$_?)1Sek%bXgoaSDN*of1gubR)OQ4PB0+ZiNnjOc z0S47|;+^4-DCl>Tlqx8mk}cTRPl8F3+q9n)pN_tV8ZJEa0^t=N?c)r8G&%ye=%VIa zRMb1i7v|-l?HhVVe8`IPuyiw366zY^H|g+UU>N2?8`$FGlMB$4@J_^~jKYQs!H9@S z$U6F7SWAbsb2-7>$;O}yvRe0PIv$vtk~)x8b{3za@kG?e2W&y6y7PPdo4+ZG{&YUa zd|0HIg;ISu?{G*g?7hkCb1pkfqtmv)9AkTN20lchEnZT*2;DUYuYxmiA=RnTi z+c{3^N==GBx)DO`7!cYcqu;SkzPpG;c1qLgTV-jDGs4&-+*c0W>`F>y1C+Q|A3tGxgtztYB)r4au@PNtI+e=99tRb z+>q3YRDf<0%zH#&I4x(ppiNNUUCYu-rL8qWpWzY>A1tpIEayLcBWXP*)L!HH?SEso z1XL2Tfk;&hlh>p2@v{az6y(_uwpeH@ojN|+jG=&)=4md0LPtul!)F3MCy_FoAu?7P z*t5VI+4VvFFPFHy5tZC23wpoy!?chaC%6Kyeo005q!r9~Ey>73y+$<6 z!j=klCJd_0FCF&!^Tq0z7gccUH~kQbKjh9!f=dGlMtq);kNSCuvgvF@&}}$4b{PV8 zHKmzkh^!8koaALXSg+x&0aqampVtjE5=da8ZrIu*ZeLVyY^<}lg4b&$?o@!J`uU0l zCniYflqxZXWdwK`LA;$wUwLgvf8yMX_B)$sygz;zG^_`j|? zr0&|YmJ-!u7`;NfalF_fjYnRt*fyeWI8#j7G^}gZ74P!E;pguz`%{mLlw9h(Z`@U! zDAV-24fzytiskdjV(|@BU3sk9BntGiTW9rTjb%E*s^@9&Y=c9d;i z%CJK{m(I>Hobs^e43CCByX8KSc4F_|#>@LBKVH_5ytq7>l8lsbeAu=1VXR2)%)4z4 z)s0hcU+eg&=jZ2nrrz}QqX*GnbCH?*N1C%9?z%0{)}EY6d=&q4^Y!SJBYmcS_r8CB z{UYy5-~M;#xlW(x3VaZk4p(aCCZUdzU&yv3C@-YU^Vu$>iaFZ6H2)B_x{!`bQ(4SV zC=Fh`s?yZ#OB2>uxt5F{IlzB^PXydIOL};tY+||!* zV~Y}kDt*U3ueYCsO?+Yvt*ol1KMuU9Q9ohvdE-7;N#$JiQ@7A_b+4OlYSv7qeg5)b zlmFQ5s^!Wo*`CiUH;ea9bL$yw1 zQ0rC(A8~zabjB`$+Aorqy*Z+C{f*ry?*6)Vi=2z?#mB;@Z+@FnZU6Ia+IUYqGFsQ~&28`1NYd$)FOCFy<9r$mR^ zZ7q-`9_%bLOmFY5v>N98S}OK(5MOD~8{hrZ{6M7p5-GiR`)T87ZqQmsz2iC(ce$bA3wUcBl_dtKVu@<`0oH>=I^&r(|_WefGs~s z0N;qwRWysnlg%AO5i6nEEV{r@EksX@1@X)e?2VwnN=6T!857Aetz`e;qXX|NHd7Zo zeGpTM;@HmoOZZ9Zn6VyF#IY$_Z>XAoKYd3{{2+K2)Imi*wjNSyS&OxSQ2DI7hT06a zGE3_y7*#zhMK`SgGRluZU=C}n@#zr$$cYV)jT|k|N(@{-EqbHb`oDWyxxsOMYKtl+ zy8Nu%i-YyJ+6Eg_%}s65Ejb+V=$N(kjr_ERGlB26N3FES3(Bhn735=wCKc|=m7-jf zY(6ngT)dc8)Nw|F_*l`o$JxBeSW(&KWkoivutXuQQIij2?;%lGD%K#cY2Gp6t8~4r z*J0%*%|OCS>278dzDYML*&)F5iQQ!Nhr>EzQ)lCf@XsDL=_5;~JQKfFPkWc?Xcd-U z=+VJ1NL@F+=Q{0L7g_cAZh-&013X#pP-G3@mbZyX_jEi~SH6iFXeL@&b_Mo>c~Y|3 zQrT|SN9#x3r3e*Ey;q%?aZk0M_BY#psB_A#?C_U4q3Um8I9GbNu|YZKhJ)79TxAoq zN#_7h*5>!5a`Dmuo-E{~&jG(mBC3ga?yOVZxNELbRD=Dw7FXbJ*8=OP7V@LOQ(AG) zTH{WYdOZqu@3V6=O)FvgY25V8i+P^f6m={79>r^K_j%W=d-0LWK|Wu{UvQRxUW?zj zN$KBqPn3vYWt4^)vsJ+I2S)f)IW?&Vp>%k7NDgE;Mqmz>H@ z|N4@Zppz4x?v0)0jpuHK8T@?ZyMOy~XV^$J$SZ!?uz{zB=kkeBaPb^ zRWEtF^GA1cmd{4&RJ>XB{AKuL%3m?g9O=VJ!nUk_i5~pyvzhtg;j-e_n3U0+Y}`Eadoj9i|L27(yGSmOr<@JaWF-ktQXmJ;Wb`psVtdtN zYh5`FQS6v3q_C7PatAGbeke_6eF2#)HYooEpN0(g<%=vIRy*I8amL#ho31~M|F@ZQ zR_eo{qOMVumA2gEKObZtbd4!(w`JxS`zgFGAG3GVE{;@Rmbck`?AD}RT9ptW{-JB+ zH1=Xick43VOCN*zpLnv|_Uexg9}QpcPRC5Q*Zlh5@MIQ}zd0F>9d)8ptJX%pXY>Cj zo~)xuZ|eUKPj=$7=j-3kyQc5mj-L8_dhdV3lZ`oc-YuJ24>a0)$@!mnvd+%?Q~!T> zvJ+q9UhloznZDoqYwGI(TkQS+#FL%u8W5e{Of&kkfX?e0Qg-}*!;@A0SyI_Q**)$) z{jC%%DdNLQnnZ3wb%z#Ld{mM!y{vQ+9 z-d5S6rnnIy6wuK*)SLuvseTul9Z>SG7TCO@h+@~wpRDjORnh?FhoqS91I zuZ~{h)jWVxDcPE1P*k{g_`zc=JVo4;mE^hZvk}HNM<;Cp;ky0kHg+n;nsiB)v9MLO z9jmCl5E;rPe3@#t0LE}qr{2>x8KWIDL1(T8ssq8Uco@GWH|_X*9Xw3Wa{b7m%v;eW zn9fnQaI03b$mCmWh!*5|+WS>Ij4bM41VY4uo6uzj;B7mQXW$4Lti{D_j^1p^Z$UW7 z)#bv@pi?!bIpBN24BmVA{ayJ(2tR!}6qN+?bO&^jcSwL$&2*(|uO9CjdfMRG^aCCC464V)hxJN@=zYi^9!Gkza zMfqTPTC^hgsgZ$51}Ew{2}-r0g^D5CxDa_9EPw!3p}>PFd?8vN>rNvWFEE2?=3vng^oJh!EYWBrIR2T!O#)5~I^Ij^8zVrer&VekK zU13mA_tR5bS96{Oz#prCoB*`>AfyWg8o`D8(7^Jf$Uq!4iv@qJ2k|20MPk#eUL;DO zp`BdF#*0KTG_--tW9bgyBSG$QqEO;N>0R(5E<6`U8=)aPDKKg{EI!<&i-Ph+!)kw} z$nFL*_BlEHU1@h#n!RKwiU&8-Ng$6jJ%MGqDmtjYo= z2VFfU?h$??|9lzm6c-}F!J4@9+7rNz?6R=kva(dfmFqy2gHFR{VK^{X^mw`lPsO!> zRC63e1pqXs!KOIrd|;&hfjz$>x+d1+4*aq!JN@iz4ipDD&xI&$LhrLH+;%HjyODfo z(KC3EHV$k=0E_2?h~a7MSU1xbC~pqHmW6F7$Nq}}kA4Cjh>LP0i11Ez>VC<8-lVhu zv}h+Itq2bd`v_}LuE~M|We7!Q`(fv_qB`d*r+I5nLTO7cG}AJW=d|J(6l4}9?GNuY zVcRH!m+67s3|h1uCLs*b{&sc!18Eb@*`-l?#brtJ{+Ru9QM5iNPR2 zeY>EK$H09a4Pr;jOb`f`ZFcy46eB;|CcjFW06kCPYqO;#UTu8x6cRwm@?J}GVx`H) z!pvzvUtEH&JB+K6dymx==IP*)k8SuES@l znpqjX=yZ=@n9n9SU=7xV&Qzg+9J)ZMU9}}^c0NI=GMucE)yPh6d=?(mC5{}yK?yjB z&nD0~|4K_wOO8J(gnr}DCNSoHnx0L}C7v=hd|B~0^p#5Mmxf9iG*sthVJ9ap2+tct zfk=lR>@~PE=hm;W?580PD*4yV=M!ysfZQ9oA~%3js>%8UpfCxb7tZ+P>2TB?P)BIZ zB^4IYV8^Z(2GM9oBpAFCkqjK-Z;yQlIb%`?F?#*V&ZnXhd{ig8RZz{gQ(WqQmVGF& z@IlRY0BVOr07wYr|B*iX52Q~W0O|jfK9StR+~MOuE$DX2VK$38sOeT$%qwz`DyZtH z5IDZXs<%mRwkFLJfEH-oLuwjr`E-jkkVLO5XgI(!jSuZcTij_=9@NOHt_Gf>JO-yB z#iv_!ZwR%Bt96PIQ>m%)B*qZQVeN^ZIH`!`ILroPUfjZT#{|no@unRi>r^z(-wT>| zU{*%NhBvT1GP`^?cJMc7N99#B8F;Ow(6==wSJL7RFRJ$6RvUL^8>JYK#R)P-f=yf`GPi#a+7 z^T@^fTL9D8*RP2yVmQvnEojcX#4LZItU&Yil;;>eDxfB*|D`iQ9ZFjqQwUzyT8M8O zN|JI5_D~oR4`yI$ZG<#CM2MDJ3S~qj^%OZz4|{g0z*gzTQsMty52`K~ySkkXIElFz zY%O|bU5j+m<+u~A+%fQMnk}kezQ|KN8_*9sA$Hfd5F_rFf)tlpNK52rMvRD?Epp7G z?45OoQO^EsY={id)=BX*m6aNQJU416Dok}WUzRcC%&VDoi8_D~-tuVBvd^H6s6nNe z92=uk`-^aXX%fy-JXcA40wbS7wG~yA+8VVc2VOkDuM~5uo3@6vdHM9;goF8{GuT9O zVpQ>nTc@sz)ww}M4_mZB7j95M`Vu=?UT*t`AMm}kc|(C)hVR59#-+CBHKqpCVTD|l z7Ln)Vy!M3zc}u57H=k_u^-39ySu{i@#YwKvom#p~NJCkkB{GMSvW6oVTXKcRnNV!r zWT26-6VDmd?~}SO{x9kC`!uO;&Po&&B?$F4?H@=Ju@&8{y`dLaS4u?d3hLzj?r{Y` ziDJ&dir&N!NdMH%4?Etl1(8gT)bpu!yvDXaH*BKvPo#MaH66Mu%>QC|1fJEnPk~DC zHf^Z#sfhVz9K{)RKyR8uwtx_;hvN-20TeZSUR|#vRYfx3VtGReEylkgT+rag;=Qot zbLU(ncU@hBML7gur^71#dgLv4$s(NyL5rs2d_8cYez8^)rbxZ8HS*S|=(vIb1D&p7 zblEahqey+BAEMZZFJ848xp*u#FnyqC*t1LwsqULH8&ClazvVZMH&Reg$^O>5|L@PQ zulxG|6s4&1qU^DRe!eI=)cOD~EW&$UXw?%Ko*-0Mm2U|@p`E4GvPll*;XjWEQ4r!)VHknP2=hL(I{_ba=bH3~R&RV~< z&fosU67KtbU)Srp-kpI|eJoF`H0(uS855pXLq^m-S9;iQAfgQ@q9XeXA7=D%#5Z?C z&E9volN#*6^2r?%@ebz|FH2i^rY}ixZ`lwm>$7c&SrX<#m!|U#(8|eaQME+@((h{b z*N7hc5rF``6SrwdRv>1Q)zRW81Y=%RfX1CtzL~RAA*(#x5nXq^?h9gm>10II;;5Vw z1D=$ug-)zYz|ipRYDefK-|J9aXQso}ByZ*9ir=#*W~`1Mv?wuhvnO zQ1`E^mAo|y?ea?5$Gv)sHJ|SYI8BJ^lLXuHJ_<=R5PVSe;2*c;?*HN5LFX33>OG>)xaNgGPDO(~~Vi zms=XjP0S)FGIu1ggf@(JyS6BQwFI6?W-**JE_>hh7ST5Gyyk2t8xrfTI=^sF=Y6r8tbHd`oK343_6Lm|M-|J=@2b9hl75-TuBUdA- zqtp_G0HXgU!xNU~o!5XhTei-0Z#RK(HIo++ya7oRe{}T8&3^Z%GIuFC`W8XW>xOfb zRL$J>EtYeyw5m2qnShag110W|LmRsvq22D~&G-j&l^AtGWypLA=Ec)`nj`Qp2E!Cg z7=1L^L{EVnj2z~p**py#C;{=IeYVOj0k-J^w;+r@Y^7vVyq5HQ5!HgYo9t%urgHY& zf1HQ&fIfD8J|ED>+^k@6#6&F289S&d?ovie^T#sx=hZ<~pTl8c%u*Q~2^xScpP`Dt zG|9N$J?^G}W#oxJ!d0tt9_5gl3RnM(%pG(o z>F7k_iZX9q?;TTIj0EGTE61%@i)i%;@%tc$Lr zpie^OWc6*JGaRghwcB8ji^A9&j4z4@;?i~vc2Xrm-YOE zvVe_f91PrzVL#KSx|_3l-OV+G-cuPey-I}HtPr13HNw$>%HmsT)_NDWIV>Hlv(|=_ zLKLnRt0kr*if;zww%p(2BxzRLdo%I;n5~F*+?p-pL%~u(_jr&3*)nr8MQ%NF_nlcis%8`{zOr$Tt)`fSI{Y=Z5}7g)eC(k zszGux7gd()(dJOVIlL7X)enn?RoZ1vsV`O8eFaJNu5fy1+<(e)tRvHQ^h5~tMw#f2 zYUO-Ii*#~@jAHW0>bvI8WXg>!%Asy9EEm9PZR4Y%3Vgmk{o^(H1bwtk9IFGZG*cto zM9Iy{?zZ&y&gHsepIb7K$m5_D>L^Ugx&(B=${svHV-mwij%is`f@VjeNMy$m{&o>$ z7!O@;0K+9wdAal%B9cr-q*eAz?BwwW8iJ0d8F#N02c^q7yz)lAd1k#45tCOrMY3}% z8lqXAZ=(4b*o3JeUtF{A(f0X}>OEA7yJ3RX!V=X8j1(%Z8*S`d0tzK}y)5%g(Xft! zz7z9+W6y)j%hlDf_Daw`6OF*hUT>avw>;EL)lNxY?UC4?RkTL=A9xW_9W=7H6t3i( z8)6Ehol~r#bPyM79b8CO6|`UomSDYEHryVwnCk#I4rUQT0rCK`So2a0TZ2SK7BeAV zEeBQg#MsC5%{YwR0QNAQpVK7ZqLY~>nFXFi9=9250>k#MgJGIBo8K+Ivx933a0=2; z8D5{U8eLYQ_o|r|h=TB62OYe3y-|3p8ZnSGT zeu)>)+z62lH2_PNl3^Eil$(SWSRc8(SA6{g6lPf8qZ&I6mh*Xt_gkld9jRbU2SgOf zVxkNd%3hPYaT0s2@i+|siF1H-W^}hYvc%RymVk=4xcG1(*x{CPq9%H*U!C{t#-(@@ z{l8DIc96~Bo1mG045=&6HzPe+2?!Z&zdn9RR}xyyvDm&2FfDj%U_#hx>HTvAt5hX1 z_qkrSx<{2?f4v4ZXY=;fVuxGTTnY>$mnQo^sg309NI)tVt-kJcw$9Nm563Q!RnV+V zcPKPg?N0eaRMPrHWA&2@AXBaeDRueDEw8Q8CM^$ipWWUiiVIrC-JB{foJegQ+!Owy z?&J?7uIR$_bQi@KX8SMG;<9tgZ_~o~;ESP_TdyDRtkP6mS{vRxtn{efH{9B|{DdDk zc-iGn)7$6GhnHUr-?{z%rQq+T#YkJrr`P{5ExzBUO<3*SU+Dj1EqAK!?8YYf7eC^& z=6kMuEqL+sd+OUq?N{(Gf1OJH^7iGSg0pA4*Z*{Y(wXZidsJ9b*N+j{8;SSn2~#^r zz!~Ee2ACEhl`~wWqyMvMF`KH}v^Wber+=9iVRISg3zc)3mTQZ1=g9vwE&gLjUE(DHr|Hri4HNNUc=tWvX7kuASy7g}xSS2gZK3c8A;_Lo=S{Q$hqiLl zWaMceuvAlYB2p4tKqDi0!00Tm8PB7Dsl1X+R7EVGO{^O?q{0<~fJdw!;QYgFc$hRb z5|-w4<;K$uqeL11FdCG^V`_CHym8YV7+>!|Yw#|-v5kn!bQMiZhY(~7e*6x%64f%0=ww_U9J+wBe zz;26_Z#Qt}Yjv~UQm&WLtici3)gB!+>lt`dGmj0HYMk^1!L2I8howd9+&VEQIRQ?R zB=Z1!s*#Y!6uVK%>J^-27K+q{dBzIWEp#zyGO*k_Ho9s3l%oETvb2N75thPkikciB zrl?{_9N9nki~izwX!BOWM~xU<5YITXyysL?yO4OntT4HF)uDqB#jwEsYSNWyMf6>}cf$T_t3wWl~s0(>k>2suBU9%690+OTkh}h?zykl6oI9Pke#m? zAOd*9s!KE-Vlo9qkL`q)(Gi=ASESUcmGtv@;9nN1q80_+>JtVKqEb*~aDlbl1SeI= zb9Fb$kbM_PhkkVFfCi)YL_~MMkP|doIwVnzo5!LYiI7g?u|zjW(P*=YPRv!KCFUvAYI#m+5@sJ5Gnof4Q0e8-f=D-J;T<2E+@S2u zpwerQHl01a-q!eT;f}jn>Znlf{b2G}UHKQbnzNmfs&!qp3DZ^5b4F#y`AL0TAZ?Ig z^h!fVi|C3pa^#`PNp=nc%HjPe>l~SihPW(E{H#ARn~h%+RD5yHf)tMBZW0$*+jY(o z)PV4T`+UzEdWPsp16$cM6=)k-0oubHp-@!E5v6tHjCU0Eq<6qkN)#e5#~WM>5~KkL znb|s9jmczf@vPsQ3F^^tobE6t)S$AIc4_)--Vjk7BOuRK23=D~6gTC8Ao6`3a=N>n zfwufp%E=JLGc*g@gs6nWG8GKuVDyKWkrIiS6h|`5M0hBW>zsV_PaE6H9n%QhjtA}C z({L}Y-f3s3FNw)b*s{`5ZXogIFkh3S_p=^k$D2Vg(TO0gKGt6hWJHfP>TR|oU$;5UsO?JW*|1%ONbs1DfiHd} zqtSG2zbCj7-ogVQcm_euRE(y;^hXGmo3RY2XJz>*wPskO3g>pRv%cQ)tCsm7>KSf< zJJOwopn-PX`_dSqw`P>+K$OmhEpCDDyk1Q897HCPZMNq0v1(f39KzVU<(Tqypa31yOU-iQ z_9CpnYxJiR?wdET13qO(QKfx0v&eP{`IW$bnHGPhGUW^tRqdmsJW}n8CE5EHy91E& zh!D7e69!oZy0To?i?Zg!{ICYaC`u2diN*}vN(q1Yv{UddF->aa;2!mbI(zd!p-RB#qT&{De_1jJjEW#|mE!@eVU7$OF4!5HUn)v%~8f zwO`2%4@JeOVC3~IpMnTj@VX52dy@C-xM@_&`A&qca7B{ta23UxeJX6)>ACAQDopdy zdA%Wl=JwX6Oi|WxUCo(!8~(TLh8in*7H@Fof%UTwC{1<{$p42IpdI8pNFKBkm?;Dx zaR8Btp1yaQXC&*_N26Ds2BA%h%~y%cWHBw%hIkBvlp$_$bO=$e+MTBMN4_pWT7#OX z;oAx=mwx4tt8e_MEdJJ9$LVcOmzA`uK$Uqg!aJF*pGjj0rR1$P+k|gCtKfD4vIxhj z?i-R;Z=p_2HBWDaJ^Wumhyz32atn{|o$iM$h#!xi**VjfBUo^kP%QR$l@P#2k@czbQTr0Je zQOpt2VmQu=sdpz zo9et9Uw2-ujd_2`Mcxy5>at`)AKj7ie0sVB>y*FL6m#u<_U40{KGzSk94{oOzHlxI zTg<)cRQ+P_bwSTibzpl9RJ(EI|2!!DraNvOd z6~F0@%Ch_eOTX!krK*~yrKM_q?}qkrO~Y@xdXzPST6SD9161cp$Od5JOGZ=%q`iH6*dt7 zyc)4&Fx+i?tmxePCGk~xMl#D5%meMcMK0k445~K?(w2XNj3yOcLlHFHW?ds2nb1>h zw2|g+X4zU|`dww2_kOF&Io_e^@tJ?c9&2WU)gry1gh$h80qg ztXp^D7j6UX1g3mlbuT`wL2K_=T}@iVDB_*u)Y4bka1u?p4nUhqC&wCJ zI@5F|F0S_ImEL~0T|d+u!;!H`C)*@KT-*f+Xj;a5Ju?pihj_BvC>CikNw$J(p(rPg z7lKf!D|KaAR3eXFK%SUpY4&AENQJTWpkrI_C#vE?NgxSeqo_hW8ERudBSwtEbg&Rv zCwqD%R2oL(K}40w1(!^L|* z^)?F`aJM;i@~A@n)2Oicp{puiCpHK2sC!({T`FaWvTeD7gNjTt2GwCpNGZXM8Fh-> zGgFU!bWPr`pbU^7LBzaBj6aVeIzTJyKF$PwKitbDVAos$Mf6^lwJNwq9s%{u zmi*KriYftd#n1l(GMov>)g>d9FdZr`B|)0YGxuB3>VfnJ;-PqTHSsKK_Lt;LUO}Lu zSgftd#}CDe&K2A4zJh9xqYZ^QomfOja(l*G*1P3SIi>p>r5F=Btb{z&=XhMxJu-b(pew*kM%PGMcHlk2$TCYfWS}k>riN!Lu4!)a<5NW1O&BkckTmQw zW1>Z%l^77y%s%hABRDX@wm(>6ZxoB^vYMwC%Vf8w^9g5G1n7Nkkc&}$=kVSgO2MhD zD<=p@y#^b!Ge0>}Ge}H}B;t|8Pn60S6(g=Q#VzUVAaEW^s?AFYQJ78RGoUU8*2(}& zA~8RNKZ2&BTeCzC)KN;Wq$Hwf{C4(wmGmFH4vDBN5vejjp$>an>>0~We?O`|EOU-Mpt+CArF4U6gi>P^i`_Qng!G*e; ze$DZpT5nWmUwYBbw7EBT=e_@QSF)D0>rk^{S5KyzvA$Dt&8tD?@dG_W7PTQ6m#n(x zTXr|RsXMak|N5E!zq@_DeOi22z5l_zyFb3J&JAAK)qd~SkM&Q>X79r`IvjpkK&F`x zoVnO(_}c3$WHDS8frZ{#`62=N&aNZ@6JlS&6+L>Jk+^<3c_vBed^6)nPFZDXD&g_% z*)&k5_iVc6NTpJ``HQ5v)NgMKO3&;(ntUY{_NtkXE{@y#>YRhVRuI4z{y)Ecnir~; zZvt%La;*Tav%>Gj9bBpF)2v>pANtJ}3T<`XHUJ#q+s28I>bFgkM}M=0T%C99lH7y( zlwO1<2Os4e97W>CeSj&HU;)t~#C()P{HfrPBn$GzB;phC?r3e1w-_f4hPfNFqvP(6 zo8*XGeg^{9M@Nv}LojRv*VzWG??f|T!xcDgOv68d$gDwh7+SO&a>R{_R6sE7NjZHq z5Q&G_T-VZEcD_?I4dK~|e#;F&$*C0(I&t&TmV!t^h*(1C9$296|gaBWOFR}2+4Q*28)e28{}R~;hK2B;GVh4juX2r(KdRA#K&); zVdHKf*~;nY?oGW8ejt6=cx1Hk4g^PBpIXLrl=2XFr6G-Se|;8lA*mqWc*q&VgY$H= z6AV4DtBGg|^P~FY`&qW5s1^e7v|yGjaXEZ4Lqbw#Wk=R%UFaA}vEli?4`|5S5i^P# zme4Ej?v42zeK{2JS1iM7{KBE(E|uPCLZ^z!VOnpH=)Gsal~afAM0C@W9akj7zBoRU zVha;lP$IKE<>JGAZcu_f7y*gtL`5QJf;NP zI9DJkR^O(H6(B500{M`vd&%K^aj)oZ`7(Q$*@P-?e(B|g3Jxk~4#8HglEIU-B?LB;w3cl(2+wD2t4oB_J~k z8Bpp(SGQ!R08-Ea_0WX~nO8evXCOF+d6x>gu+5tXmT2N9svXEq0i9v(Pc`mUMG*%L zrC*^!;=REEZlJuqb>_A|i_|D@$cMptvGAw<77xB`;y==f4H$Z0e#GqNiD#cKfBROB zRa)D~c@X1408n#-JzS&~mV*3Qy7|Q79;O7D2MWv8gY@^E8{<6VER2a4Uif1Rrd=&)a(BLOZ?)$ww33`e(%St(M!>`cX3g1j) zPo8e{lRbFgsoxVJ;U_WZeSP9gQ=i8Ne1e36cZVvuuFjj8NeCF?{3J8dd&>`1&R;J; zl%lx_Hgt;$r8qkWE#;)#pPZ)1S=GTh_BYOk^{ti%0bYbXs-W8>Fc;O z5|r6`qV^B%@N3PL5lTYB!_Ul&K;$Dv%cKQ*Zst>qFarqdcW{||XT+nT5!%yuJ}H-R zb)Ew2^=sO_*GOH)mCqdXyXG^Nxmo7>50MG%a+ZVV?7hd+KJr5$mv2Zg4y8tNWs<$o zZTguKD(0QI@q|=q9)Lb&QRU$$vhETM5DEw=yeln%fB?hL2#7+FVU{Cm_dU_JdDyYF z@z|NTw8x|v%0SZ-5;=Ouw%-KWH8X4N^VxloF~;|jp={?)oIAR&*T^jiv$Ey#atu^1 zga)cm>86)}dZca1uoHWYcifT?i4hlYS*NCB4*5cn0Z;lqGjDFx!^mAf$T8bkh&Tes z=i`O`oO#{$jE3wV>H#TQQ@`25yW9NbBz>4HmB)nd<8mTjLHj)g(r~Uj<1#e-bNVe}X380DsP2gv-td02!?TmuZ*6{XWoH6JS-XKWdet^Z)&GP{MQ=2W zBj%ymSOxg2w+>7V04jeiy(?9@I&aCAfiE}muWrzLemiQe^U}rf8l&{kily>_W3?~u zF*lHs&hh-2&SWVa*P-~jK!I!diyNsqHUCuk^Qv|SKT|*a50yXXukqo?Sfu9_fhS~j?d-IY?fv2rr1sIHohAoE`dLd z<{T4YjDrske6EKg?K~H3zyb82&e-kNb*a07m>d-jtDz^I_B%yF9E0&_0=egVWe24< z@d~KmYLXezL~)euwuNexL{~P6V2+|2oF5IwYAJM1VYQlBdAhK48VGLF=1t560%Mot zjWTaP-{Qt7Pu~Vh28A&99w5*7>p7#-fyg>@LL*q(k&uC*QS*we@cq)WY3 z9L-f0U7Co=2wXs!0e%voMcvw&t2UT9i1}D9?o_~s z5o^=Quq`n4noV-}>z}N^J_fgSrD329H-+o^d&1+F#7;!I!p29#54ZNw$XmQs_B=J( zg`?R9o2Lw34Wd;YeuvAwopG-5%ZA6N4vqq!oIUY<%+>x-yXBVG%+{!*T~n z6^;43jZf;;D9AEXuhvLQUp5l4dOCw?TUniMx?Ezh_+n3qqtNW?JKG9-TtOWKO2gNJ@^|m+sIk!9EQ00ByrCJgvv!;_J8vQXYeii)@CHaNLO{0d z^a4R~Wo_2afogfb+%7=|!$~t@1#3jk*sL8y;F%Ec1Jb1z#DEN52HAoU6ix6Ez3{C zf^4MDQ%aLD8IT}8NWRM{CAYg8TgH(6+&}>zU46LaL(aBcMl3@9RkM38iM#;=u1u!E zK$#dZ>HtgHB#pN#=5!->&@J!%fj*tw@G@~%lGWK(%x&!uD+?aALmc3!=NSiT+0FU- zsY1>!$7}SLAX32sEi<;57`Ua6w%t&bqw4t>eRCbIc$Ar~i4v#z4PbC16z8<_b)zrEG}@jZPX$-{4S zvB$ITdR9c?58n(LylL)RU*BWz{EP7mtpmeOp}E_QR$B*KE~TLMtcN_BDqBlf)Tnit z{NX=3eylnCspGzP&uB3&G;PD0puT*&BUKq$dA+k%Qn{xxp^U zp(2Tg>pH~8E*Wz__F*^7?&)S4u+!6hWe=_QExW8n229S(znjo`>2K(@*>C3Yx_9r~ z@M`3^&iuEvVBMqrhKCFNg2!qKiu%7N8b$qlK4Wy-d>GOdc{%XYys6CIzO^s0G2v9k z_FD_XXU`by9YKW+u9)eW!sD*gr56qb*NrmjZrV1?Y`tf)@bH}2)=Ilyat7fZyB7K)At%N~l^^@)?~;D58GxqCu%msQw(l(jd(kF^i}mnjcu%?5!3f0^FnQna>zW_w-<6u7?F?wWVXS(32<#_RnjMJwuLBOFfWKA6ukHFC|C$_{Sov zt}5ANX|mn7ZRA`wc8&M(DA>4OyrUv8&tj|nA$RhglZh~PvUFot#DM-E_Is@LGq0;o z!C|?Ev^cSwSSK(72uKs(>y;FvV96gch$zo&2 z3D&MAK?V@n!|_&*Xavq6QB1+QWeJC%KmR>d3IKG(v2rg7JD0f6Z%C6`kABm@tBXnG3N$H2P z&ijG6ujacEIzw8?`YqA+o=45^QRkJiVXBw(U}Qigsy0t>LMr29gIslZao14zQ!|c^ zp|}nHeQlV!jIu0@|ACp^8m5&%x`>VLIu8F5J{2j2qz1_xenl16H;?1lT$GCVprZG} zUhcA4h=GP9nuLAjB8m5Q8r0EHnt7SDte@wRSr^BrQtG?E2i+Pip^-1K`EF$F;qh#J zx2Ks;(=o7!5}z%1vD09I^@6AEA=vNIJmy&E6s8WAua{RfKU=N6kKICd-QSjUUN@;z zJ_fwol3wZwj6eB_P7CU(gvfxbfGcicGc#m@f_ebhC;Ax~v&|x~+-wKI#pzyJ+w%J> ziZaCy(Zc|KbQxaa4oa~;QQ{9Ko7b_bwJ<4HlUi_0YyG=HEgJmJqM9_4K5v8OOCRmO zUw8+GqTFaX^c)aU~$KeyY#Z$QHh@1d9w9ah9 zdiA@ro(n+~Fc#r!8&Tyu66I8h%ewS{BPW2#CGPSkBa?1s`D0;-Awx%3oXQ$o60d& z;t)|544h->=AEUCcVRx!+)X>toV(Gi!sCuG8-qWxVfh1WQVXj|)S zSj8(D3+o%IUL(tiq!oL)A%{$KtmP#hjX}?+vOCl<+*2@ zD2Pt^7i1zb^Lx_Wc&iJBHieKo(FuCL#5`IGs2CGRaZe~Q+Xiyo-q*+^&+-A`0nNeR zgDuT{(`#ro_u6S`fY17@Di`P5zhBNOM-X3G3vXGT#f#^(7#*#pbVTeiNy7~V9M|E=3+H?xn=;@{h@)mzSy3uK>Reve+;Ap_}=PDYvTlL-^JiQE% zHD(QWHKIbkf|(1Z7n*p%15tU)GIKkRwfZuYj$93xS{^C4$w{n<-{SP*L(%QF#T~UL z9uB_vQgxwaBxB3Lspl`gk9}=R>v!-f@CI#PebWBt+bw5d&eI^EWK&ch*fL!+4d1*j z0EGl7&C-*^_7rp;W!4_vbLSb=V7+6LWL*L*g1$XIzIX^8CtlTX!Q2KNsPyD^n=_73iqOtKK9FPPr>w!iOn@~z_XF3D}Ln@0})P7+Rr99{qR zAYSG5_Sm12JAWq$Ge2y{-3^ngH3gD{ab@yTVGh3E$8xTjlp6v`!uGunFRnFI+W805 zFxG%0)X?l(JLZ@_02-Z>PrKTFKKY?YTdf@)~bUu@0Tw zm+t%Z-BcS)U%`L*b~LN)?g)I%VS+z(J4E#B5zG8*^W6nArq_l{U6r<9rks_Gyq`%H z!f4f*IYnQV9`pCNFAUMJde55=$@LBYXnOxba8_JOviK-CtS?8+%+;d!Q#9=I_G1zH z#TFy4;g_F}T(XEfI^A`0!|cy@Q|teGh5hA&_I7}khm)q6P+Zu5rS})76VSH*KZ9`p z&lPs}US2@YO)u-2UTPf{?IdSo?*>;WQCCFjN6=Uiq>Y*SZYVa0+#$N3St{hK#T&RI zPm&Z{6b{-v^irU3ib+N9=TxK7=2%vzs0~NSN!LA$IUtS4(!`h| zg9K|yMfz&b5M;NsxP)3d!5S@JHf^g56#66@8XPio(EM`;!>O&wpqhm)?ei6=o5Tyd zHw}9N7k)3kjw_?_yuy0$|*CT7004)x>L&7G7BC=!KztpBxSG2UW(|(QhrTHE}sqyC_)HVk?kqEL`4$0Ej5gzxWNCT zuAmdqNl(_#okpA`k)PYTGeMaTk~NEqnE@SJl_sa*{xV>x>Ab8@65YvOZL?>P7>-gi z8UDvASu}nc!LsDzM04;8Q?iCTX73|Q`HAY3QCRJ-RB=TRl{&pu%(!h|O4I(NJv03Gc5G9@>E~_!!flGHw6s6hkt&8r| zHsrKB0z}=xTfOAmlnq`8e+Fz-;A5e2f0xLO!Q(!MeZWO{;)xre6j&G;909&@JkyYZ zn4=>0#S0{{bPS6Gl8id$22BLogUJ*nYj8J*PDWu4(ntZAT3gNPNZqFi^76TS5u`e{ zFYX#G$>Q22jXYoC5eV`UF*9Z;?Gt{uC%5HgQW&(spB$k+W z>Cka7!(tZMoO98Tmj=w^2E=Az5V#V?Qj3=&N7;wep9)Eb_&vhq6mZm(KD_u-J`f|& zwJMvPLG`h^ZXnLifdb%MENgK2leMyr7Gz}gGudIM#9AJRvzpu)e*KK(=xUfnKN zYI4G)f>w&SV0vWRVMYgJXT`l!sjES({f3RR&OUUKW1VY~s;5)7*0XFQsowdCH9dzy zM0nng!bk5O?>jK~{g+rXQ`luFqqeW6*>LWD=9Ff-j3`5CJ4`>cx2DDT^@EF6CvlM# zv2QqkC(Zxf1Q*j&e?)WO0t6vGO*PjTP@y3Mdys)>&q|J%+-0rR9+%2AWQ;?Mbh)!; zI$~Mf1go7ds|9ma?VeW`fgvm-`mGZa*eMV#@+IhO35cVKqiDXGWp#37!*&{d&SF@J z5REQmX4U<3hi7HpqsQ3I{w7#3%&{~JBPt$mUf+|SqvfGuqQ%29uIbxM40+dScvOZ& z7$6LxRb#g48SaR1FP;?@b1Lsyeck|y+Zg%00KtYc&OxF~=K`+EsSY?wyGiJuiWlSR zQU6$T$t$%7n=0+kNS=kyJA2~e$F=D-ATBWz>FvuFmKr{`|FI+)9N9GU&M38DgKXIC za;+vORySq7j9e&7jo58;lRpyLl>9}tcprVRtZPCePk6K*qv@zoAHGV#SWI_&QJdme zqx<$37~0^uJdSv*ZeS2{Vo!FLz=h#o=kCVw!Jq=M+kL8V{GO0y(i=VfLts%9FJoKJmO>dt4rM=h&E~(@Wc3DnQ4S>AK0Q3SmNy8jvbU zR?BgAhbt5|1UnHJxij$APq^8>yRh!g#|h2m?#TimEGnbVNUpoz{<*L!65NEP!>Ok= zI5$%>B;vE9R1ddYa_2e6l58uHJ#tjNTHW7q$Q8rWo1WKv8nOKP-!#ElI=!mI8l2Xs z#k(=j&p0z@zG;s4_DCZnR3d0hxM(4R4MU$o-#=b5O|=4RMldP(*Q^W-4^P`*jLN5l z`Ejt6f>oH)%5k7+ekz5Z_yT{|y%X(wN2{?%mdmXxH9j8FvgscXc*c`35kYlnFnBY zBf#^7Js=(W5Nd~o7e=WGp@dC@*cxJQqsN%45W0G-8)C}xwGQX@C>e4} z7}0?xG26K6G~QCcmgNHM?Ys)r=k zF!iFwp-eTP zF&(TcNx(CzeNsSB9d0q#qw>+VM zp_W+*TMRzrHZOu}3Hd!)yHF3wQ*Tq@B94y3e1L*2t8eCj?B~OdK1Iapw;F1$D^jtEo zGXQ$O>apsXpvN27uNpCy_oU7M*K2OoE);I(SXVK`fc2@WYnr`rZowom`CeLV zcHHF;*UW)>oMQtIFMt1BK`uWBE~i1Yd6b<14<0-?{81P3^uh~%FW-|$(8n&I)6Hc_ppW~azERKlvfEQ9q7Q$)|~V6 zBxoGW46>{2IDb|%nj%9Ew$KN7*8z9g&1?iUS;Y;=6C0ng%1N+2i)Ro{Bblp1t8*w3JT{oHIy z+#}|x$MC^sQ8KhCyKj8&li&-$R01Kv+*;~@y559(01JtEN7OD9*i0k&e2BR&E_Ai? z?$Z691cy~YNr4pl$KP*YDF_3!0J`?C=b$}*T3`%AYx@;s&B!OA6&+8R8>;rC;f%c| zle4e(0*>h!XZtZ;e+~(dU@Z(hz!xCmcTGO`(KL%pV_pE4;^tkK$Y+sX92zP{c{bT9 z$^dZXQBJ$!*tnOxFl=w&-x<{3cyN!;Z^!h1Vwl6la+e!#`m+X*2#>Y2Eid;oMZ{H{ zoB1eb7TElo6@NvzqnH%5%qlN_{F9NS4w1=nm)eZhlPLTqPFfCyGl9xZs=*_ zR5Yw}My2`f=g^R61y5CgGPk$W_2QpZD!1Q`sa+^_y00whQwwQ%m8#9VbdvRUs_X2= zSIIMN>mL{UtN&%3S*)sk8TfeqVnshuXa3`{A6|P!gRv_Um_m!m2J&#=%TI)v)rY zyD7c%g|7M6d^2Bj#2Dv*(jobXu*czQ;m_iqmRy9Vt_PYQ{xje;kMt+Rti$SH7zZ zzHdi}pl%4Jr8mFp5VKQSz5Djv#fWyygY9(<>s;T}J944LtG%hFmXlq?w4Yo0SENyD zee+c-TLwksetc-w8r0n~toi(?&WPdisdv5I&sxLdE{Cf*w^600o znml8AaJc7YQT3xeX5zZxklTC9pHPy9S0<8ePp=KKK31(&M_iaPYz%wzD>1lABNPn zoWvvUc27+tMO|u5tQINK*-uY#PgaiUCibo~vJTzD&tE-z=KD(R`+MJ4Z*SW8@$t#7 zjbEQ$A8P+|{r#rx-=$I#l#xUv-%~qU3OUM&F0Z~jPsJAUMblAZ2S-pZr0Z! zd15tz02CyN+LQS|Ga^m|WS_5pEgxdSKlwt3g9^3pQh2t?H6JRGJl5Bx@_jXl3=PoS zuy!N&!^ByIJ~M+2uc=Q)*~v5x51VA)qvcbV>fKg~yVcjDccLzh{<9R{W#4P)gGt@B z0{ha?)Yx%E!uAq!c&vE6dmC;w^XQP8%Gb*KJ3oFncLt?S5Y_6VN`K7aqJk7ykMtg1 za*UR*cUS8FBDeLOo_@hlnWkBP|7|~MgHyzeR@&yquELMGmCohbd-?~wT0iFT(*aw? zVbJH<$9!NRv;MLE!F}I9UJ#(J86-Ij1t@$f_`QYs0`MH%_Nh>qe$Ax9VfcX0r=p3W zYo@pRhoeq>x;TxhFu(6G5?l1?FWmP@|H#qSPnTBHD=c3-JopVz@148b$&n4)LzslTFeLk1shbwK(21YYae7;JMxNdLfICj41 za~a9yy5pXKvHaH0IM4)mlDr4&aOud7Uedx27KctWsw1=bogprk8;(cDY! zLC}~iJ#3IPplHV!8e~bv$9FDZ>y8EcaeNU_QP>1~>j~7HcNrPJRi*D_3qZ|B5M@dX zdZl7P996594UiI!3SOdtv;jcgZe3*iOJ9&5mMmgJKV*D@fcDd+h%n-B!nvSX_OvPv zD4g-tJcqvsr;Q$mJON@*a&VhYkLEG~KKhcwL@+-ZboiPc9)sL|;N zfAcuZfwnwW5b-f2oQv_I!2<%P#ksuHB#I$m5)%;qczg83^L<*1bFwxdh#ZrE_RM99 zp5@!<{+=y@N+)4V7*KLHvz||f8LfjQRrruMIOshOL5C`nFJcx)5n0}tH?b&JLY}w} z!8YSNkjT{~V%%PYf;aT!L9mQ3AK0rUj0U#?%}_y;Pz5v#>sr6`7jtRfhbq_+skQ%@ zbO^v_R!+lJjxmvSi=BvfzA1!e0Y*Y|6>*R7g68=QR~T*9wyT~~C`T7ljTVu6tbaG} zR-3exJ_u%jhBYVMy$5+Ckc$AcajambZt=+VQOikqQl}7~#UBt;g|8KLK-C0-=5jsP z{F8Dx;qxvP?vJC!WGRXDMu53=LoBc%?Vq`|$6{FU4@CfT>3s-bE|~@h&S#=#U((@2 z(&1a$HTrJ3$shMcfKIaALXe9f9`+%6+qFQN7aUzd`$G=sl0ro= z!FGc9j5Qeg)xNyd!*;8IQayoYtFTOA$bRyPM8Ur9-Qg4-n8jl}J4TDyBWgqj1K%>Y zRZ+sV*mttWHTj1OCTRVpBFbo3#Ht9M4Et=0mR#I7OoK^HpLLp`LA)R{vO#$C5p6k9 zs+r%^TEHf+;}VTfHJ;y@qo)if=!G;)dP?wyzAD$Z>PeX+qkWD(ZeIj-f{0tAD zT56ukN(AzXP_JpY>5M;&0CN}kuWUwV0t?B7NBxNY+R3}1A>hwI`IqpxViObwItz(8 z00oObw@uzp_#a%obySmq`}aQv8x5nRy9UzTjP6G14u`a&k}?L2Mvw+UK)OXrKp5Sr zDBU0+Akw9K_W69D-}#>3^Z)+3&)I$M_jO&b*BizE(HkqIBY$O7WK5_r4eI7`PH+$B!-A*Eh2_fzLV~e|v0s?m_VN$q3Pe`exeO(^|+P~X6)Y^fl?+vV%H8|p+BwulC_+vzYEv>qU$V*4EfNNF}E z(KYVFoA6V0#PaZSn_U;y%jX6#aDFzSQ7jG)J<$YPqTgf4s1%UT5y*1_&_bl2nuAyx zoPqA7iYLjeEva2UQ)R7Olc(W0ghZn}kQM;31_aNL4MYk7$@3-Y%Hk>fbh5H??dQc~ z^#kun*&5M#Ha9SvA)ehd2LMfoTVTG}n=#iB!*cgb1sLd~OE%V>r{EX(44hiz2(B;m zD5h5gH2|TSxFEEh6IN`uPT(GwNlsvt0U?q#4#)k2;|2>Of9c4Fw&SNIZn6SUiQqui z13);Az{mI(T3B%)-sybaiA2)m4neYC>@Q4d&c~GCO>XbknR&^^1a1iMdY~;q1eg_t zwUmKD*nO+9OV+hvnj`UI7NJZ_7?|C$59?pvRFuVTNpTJi){$1z;N1{`V;ph3!e z-aq!TShJ)@DXAOD>Px(hG8_Z86180S`jlwjYh&0?uu?9N&zQi;9RdSKo5RA!vyGqa zMuevjrDRf)XL(Usfc-~}?KHHaL`Ojk4ZfHdcb03H@G9dR1aXKoPTVV`hfESo1nA#T zK{S`z7xQ9Tyx;~zoZwg77xRYoWd&tMA^zywBq@7QItbu@Q5FEe2|$Yb>3@^e|9gx2 zALB#<-Ty4wuqX@XAfHHMiOyTztrFX~#!}rZf&ZW^RAm!6(w^8`R5RX@_v~2Xgzodt$tgh`FgE&gZ6=E2PXdC0Hl@;F| z{r`*;i5o~_+OFER7T|cYL)U%BXPEa;GtHV*XZzXz1t~v#2JUu|V-zN9q|T0CPB!<$cdT(@@ymy;WVy!Y4meBebPH0u z%R^*u6o~$-MdPD=`}=;lAniHxE7o-L|7w7I@JinR^M7#LjORb+dh3GKWaqlP4w`)B z+*tX|O`{;E+4&);8UiS%kZ&aD%$n(Q<1@2;cEkSAyYUWEnpX|m@@GLe?RM>~?WyM|<{ zCpG>yG)p0WjI~&VRUS9X1Zw{<6JX z#3AmOc+Wx=C)V%vgS27EznC~_S=I&Pb+vX$#7HL5Br+%@v2ju*wVoLA>o9CXf1yrl z!`9=)R`!!>VVCGvs|h~~!-azPO5XSc?^nF93qGi+KMvmTy?86Nk`wbTYaFTO5{UD% z;@f|c6|2_oK4PQ$KZCpu_ou_+^`U3OxWDhurlPlz|;zuI>UcGt}6 z-R#w$>Iv_4MjGP$?p|wI8oyT^`&)cp9{%tC_wR5F;Ql=TR~wDP(10LNC(6%|nCo>JmIoAY3YB zo46vr%QuO2p)Tf#*;C>iePeF7oSMj^GoovK`u6`OE5qQ^wAY6WY!sS>WiD69&nq(LI1AW!_)I@iMGO;P_4vXkxtj2k%M0rrUBU?9nm@M32d_BT)={qKj`&YbNy551b7%i;Obfh*kq+ZAphTF1w4zH z*e+uq${D=aIV-$AFUKY;;|Qc#flE581cj~%S`wSA2B0!?@ag#A0B`#LBrE<&b|Tke ztR{O*^FPT-B8fj~f7l+Itl9&L-=tR>j<{jxfK8?Hq*ZONvB|2Dx?I)ZX=UQ*x3XmO zO5=favvS=>sT`73mPe+Ku*oXL{i53HpvrP6*Ca%fss^4&G8cCTd)y zs~09UGaCzOs-1-Otm6YOo8B1+KDA(6{QjW1sUdp!=_9?R1lHexS@;u4qCH+~bT73}1B$tGV_!9}o@(%9Odyn+BJa9?_ednhqGogGHC;cH zCL>Pgo|<~;dXU3MG~w0ZD(%#xL5{MIW`6qH99xz{-4#8=f#a^^ciARk`KJNvr`S5c_^?Dj}e~i0Nk*Q-wB%!c(KgZpKiPguQUW(>u zFuJfC&`(4-e=5We+oApTnL`ZysW`v$XBGec6hcU}h}U4Beue?F7X721FNN^5b#_iU4A@vE-z7Z-0|tt+cpy6@6;cPrkD7Jh4;Y zxGh`agy_JZ#M6Whg$+Uck+FwiId5V*<;C%VDo%Rlj(iVHi5Y*5&H$SPOV z8X9m7RU{xbx&8XX>y*bR|2x5Fx$nHiFQnd=|JuX38~3z_l)uTJb;CbdP);Iiu3xeA z9y)~?`+1y)uI%F71kZkLKJ5Gy_}lE_ZjF^Pkn^Xv(ldPd2{)FL*YaIMDZeYXdDl`# zsTSCxvZglJldnG$Z|_pHg)AvgZA`ZYoR>Jn?wf=LwGA=<$$9ek$H2eZ6=H>h=GMO& z{_jKHGOn%QtKfuDho|I4DqiNkem#;(ZohMtb~Dl1j=B7k2U&Zibqu1D{X;7j@nGvD3B2fr@6L+YK7Cc@ljcF?8Ur}&3Y|P8v(FH zX1qkACB68wBN(+g?s;E1X9Y-DMoMLS%3M1twM632W1%QS9WUh9&rpp$Z!NeDZdugD zP!xM(u!s!A1R7yB?Dq(2I~X0kQ67E%2T7*=9Cm_er$t3bqY|-J)A>+%MKDWt3?)v? zB5%wlx8;lMkXLl9hI`@O+Ciaoh}ZKT&uC&xFw(K8pAmL@D3a7zjkZ{z=Hq0UprPrw zg6p`BEEKvGwSN`u3y*V(jq4qJlz08={dIf;T|%QwLI*15DS>~PWn4vUd{uUw#$3Fo zbV9F8V!vf#p`}xlO#Jh!D9Fcz$yoa@ZSlpt&WkNbQm4fE?4-r{IOf2F(&3j=bjj1h zVR+Z3bnqmIKS@6u$*=k3!|UW@x;G~>Z%!@W{H{nE84j+yiU@%w|BH2)(e|Nxk-WDD zInaJX;PHkiCxsyHO{!(=Km25jOe#Pp`9WLgH_Md$wiKq36y}>$LPFNGSc)U9R32IX znF?dP%2ZznFhnS|f0yz*NzBDDmG}uV8gh!fsP}+ky1eX)3@pIT!QX`A`z?xSX;$=gpR!cOH-e!rb?SZ;JU6 z%VqPRpW#)Xa|8Bs+dpSo7bi8{A6`QmelruS(zbc!(aZ^w)Q(!Zj+3#5J zi>_e5GP`x4;D|8iCFRk&-Jhvn&}5Dj~@&F=#A-EtaT^zB87K zFqO+1hLkzWmAP7%xd)fQb<6tUrTWNH>)SFrokY8X*A7oJJ%Y;vbIV=Y%g(F{tVWAe z<;o*0%JnMCQNb0lqh-3iCE*yN@)EvsaPs7e|wt=09Yw@ztXtPXlwC9O&_&Q{Ye zS2Ji`)60<1GFnM0oA_A{-VvYNC07e4s*&s^A#Shf*sq*=>N@i@=^I0x>(g2Z)zX5B z+VR_xm3Zg1cI4)5-7u_9(77%@whk}8`j@WLQEtQuf8D7y2NkTo4_=>qP;--Oe;17S z%TR~WbKV#e>(Cy?c#+`5>YXKbf0WO35cc?{W`Dixux0(;1o? zHz3YCiWTaeCPD zC#d;xUUPX|%iqeDlF^p4jTRN+)}Q>XOI3~89<4`lt))aQVZU1QbQ>7+vU@8?s?p7% zo^78-xzat$UhB0y+ao-cRDsv9_^iXHf;cbvXeY!Vue}_c{E8}2UQ^Y*HYKtCG-#W zX7c4~3a@TZLKh*thww0;nWIx-k9B1}q8jn;MZ+qANKGAt-xv9B^Iq7hGkz@ijKFa%eqL^Wv+;hkvb!3rge3@yY z)dmd)Pc{TkIxjLVkW8H?lI#ogeD$(F9PNM{ie_L@~?dJ+;d);zyFeI#JI(f!@YUc=#zA-V+72fqPC6;J9eSD_) z5&rkP`O_{3=I=g7;|lHLDiO6ORzE@~=34T~#!fyve?iBOC9yhvLjE0iYVZNxo@{0? zhpj#xJ^aD2G5;p4KUJ{xVQs_Tgaw>n3LL$~g87B`u#!E7#fzBHiZ5lk%oODEKUxev zwuLSARxLJ=eyAnw&mbMHXI!G=r)bY#8V*|?O`7Q>9jqbkeX!hFs<%ulw?u?9|E;!T z;;8c#=?WSnxMH8TvP)DmX16*Lwz~Ue#an+~hH)j%ZeSBTvKTL$XI@*ZSk1ayP}yG% zVXnLUGA|aqh#@V!PHMe9np^w3`cZEEwftIh(kjGfm6By++-_ZaeAQ!QO-8VqWOakZ zaQy+xr_j(^Ks1?ztmoB5TtBwnux2-V@+Z)Pf1Nv>`w*?*Nj zUZXoslM`A#zuVF-*zTv>R#n<0vD%JLtk6~3F(;eTC+krYdSmP}(qyyaoX|?GwBgLM z3klib?fP)pwo|;kV^8+s&*GA}&o0yP=2^vVeQ24tVezKIZm8kz0RK;g$+?%SW7&Dw z&z=n+W@Q8My7HaE-mupkilspF=x6%m&jc2<57`!@&unTzlJDxmW!S!0-Ot?DgZVyN z0`~h=bxXxQ6?6xC1|bIn*Zb}TE47ASXo-Fa@crrw{Plb3Cz|DBS8{oT-2vz5uaDZl z`nt+1z8rd3A3kaCe4B7sd34y#a2V!u6xfy2UYGjqxFxpkD7vm~)BaP1Puc9hPs8@d z5y=aOlZRh?4uyjcM*kgu__uR8xesGG>Z$#ZTJZZ@`vK7R_u|CwudBNkWG7FOe;?YP z?5+ORJlG*({RC9r1vngm>yOO~PN>M&G(!I5&mVz4|6wNIoj?A`EnK$0`d)YP58wMX z^Sjd}j7{&*zb!H44jQ9fX4Zaz-&;cAXDG%qs;M)g#Vwd}m#px{Z^QEk)?3Qq=U)ZS zcP7sz-)|bP_4rjEnJfQ(9DZRO`t9A(q0R5#(Blj9cjpkLLl@RRtUlPhGU&8+;Hg~7 za(tOAaDh;|nzg!msXT1Tc=fFA%6;T2%wY^3zHA|Mtyj5+9fmskHpYebC}P%<9Hs)_ zti^Yy;o9H)t@*thyw$`uSFC(n;&59Qep~VWwyOKKX6?2PbKAgr*Qk8gkx)~d4HEabwd(%Gf_)2h9K!ckc_dBOknP3l>bf(|D6o~``zL1 z0%q#(w>N*+y8o`%|6Ni3w`%ln!{Og%_rHU+fBTq!d#sqB%9vdT%pp1EJREcCi#hJb z06vl|2)T|$5puyHPCb#h^g`x)BF?=iYWByWmc}`n$zxK%hu0=tLoVC~1?oAbJGz;I zdK{7TX1n^ilHRNRIc7f%3lzit;W3!+85fMl(rW~pdzhB#?P?8TH z*IIn)JzvatIRDY6JC`OzO2Dew?MJa&-eVuzcE6*pfnSe(ZMvTSKEB9n^|kAXz@bvQ zf7P(yBI3Z|NwVF^Z}NZMARv?4hhw$o^y&0;DpPIiqSYk`S(3|;>D-Q`14F; z=*VaLqt-1PPfV3H=KQ#aDo$NY=O@zDRGIsIiJ=x>7P3+Ip@Zk!k%z5JliF0D@x=9u z8%a#{#Xa)G3~DD`KN(yNd(B8o{}d23l>6O8X~_0xTUH-*v0B_IC8ke} zmOIs0o<90pxw5jlps5~hz_}hoc;~!KOCI#%i~bvu=5M(?N7Lqyx)~qMJhE{6GiLF` zyKauyBcJAxZc=aak998tV?&2W+%GI$>~J6Sx;O|1SUpkHd(iXbQPSL;M?JT&^?ifn zBMb7+APZjaR?^n5>b`=~E7^nG7AwYIR_5&d7QPs*zIrtvEg$l+^r|zgV?uhp?B9zP z2M{5+**buN<@@?69hh!)j;(BNV_&NDde%rBJmU|~Bg z$Wzue?qSl+be2<{)sFM?##m!pIzf>YayWJO%XWB1_)+%G z*KmQAkvVp9=Bgh%o+}p%f(CXMOIEcjmn(ua_pg2jU)cp}yU*^ zm&J0C;Z|!eyZb4IIrzBkM?vt3|CRmPpSY!ep{Fhu;W7t*e3Yl7x9SZ-ZzHlU|J{cC zz})2AWs#oQ;=#Uri9uZItl`jKD1(%SUX$9U_p@1+;~N?q=k(=()Y4$2nj#o~=4D5a z3LVru=|r4KVgpo~*<025COTnsnm8d+mHw@gVKKLnR$~A)km3fjF)JF+_`g}h-Ih9Q_)0Q{R#Rf&YF^q z9-iLR>wu-}{tC2z$Vr|{Ua*Un$Zo3P%ElJ;U(12r{6Ddg66s7|0=3np8sT06u3Xh% z9i7LNy6LXjV(Apb;&>cn{vvq7fvKc+0-I^&_uI6)5MuMfQ(`yEuW5}YWDm8ANQ%`p zr5a}vgtS#iqSgoWvnhxz3!f1`pVrhL#Yqr^09_W)(KKBMJvUb@If#iZ<$i_KiSiJ` z2SL$zY_JG?CU!<|z!N!kV*r5!8pAVVCmj>Og;wMiOl%i;_|30Dg@z881STi7*L7cDfiP8~`9KPH_)AvRO)Bd09YA z)APVpY-OE{_Mrl49kFQ&k~1+~d)!eCtc3B41Qr$otf5*oEC}oi6sKJ?SqwbSzrsz8 zprttmh)5nXI>$QGtU=M#ivV*fYW5P%y5C{XGuMEjPQ@SyPGC6aI+)s#jKgg({{w=? zq&G-=O=Qr&qXCbihJ8khtzWK-Jqk#W!2`6%5owNy|5xWoh${r337q*ZG!1*80Rgg4 zp5RDKTMT-Z_>b(>M0=Uz^hM310z#&@9Kpe*+Sf@%aq0SSs2T&$Iu1L_7nGO42LjeY zkZ@B`Qi@n4z5D!6ZicN`rftNC1mM7a$1=IvbfZemGEz`~eaWJ4F?~L#o7^PJ8d;nrWv3(|lIXz)$agYD^VQzga!MkNdD~)E)diqu`?6$mqaH z`R;bO;4;|!ua21B;EPJkKmV5QFK&4rp?v)L~56ABXPS>E8qVn`;UCLzutcpS-?{c^`J! zx`r8XP~KXimF3K}lEdXY;f_$f&2~35%z={oyjaGQ zA7M;X?|+RFgW`tVlG;Mc%x;0ICyH#hO2?kvch$;wAEF=4_X-|@tgoX5`&BXWsFP2< z7&WzRVl$Qp5w^dAHrVx0cmIR(FXFMozTS`OeHUg~o>8q`Bsio{;4pP* zaHpDT8$ZD{f)G$nsvYsdnom%q)(ia*b6QW`#_z{~`dR$YJ`vzIilCYhwAZcz?}?iW z3@A|ZyvW9(Ym2Hz$QYbNK1>se2bK*tv;v{EF53M3exR}T_$H2F-wNDf0eo||(GL|O z>_@=KcD!_59Ck~TeM$s=U(G({>|Q@VpE)XXspnTGKl^nw#vc7p5Ka#FLzXu6d?B8K zM~-^y8UezT_P2VKN0|JTMxV9UYJxZBY?v2{2cgH@fWah6i*3KzcYk%BOm? zxJfx*K8g8R^J1U$XKOx!{D>D~xWW)Ql7>hjm5m*T_0F( z|3t10;)AsNoAZ@dH{e%Pn~cS|$)mhekU&I~6x(R$rwK9y5W91oiZXQ8Zh~eyHd-|9=L8y$+V4aaFd+TD&S_@tb@+2ZLO$~NUQubC9*5YwQ*?u8cFvA@}c#mvnZE_#wTG2 z=x_%#1P~la=#6fYENnSV1gZ?rI*L6+j>|jCfIltPm*&A#*O3%(o^NVrP}HAH&kSLK8+s zu(m{m>B$7=a5GU~-{77J`$PwaqG{DzA*n!wpk*3w(rm8!2!AP3Z@yH(%{Hf@)hnaJ zHXFze2Rd>`&Ob|xV~}Z5Gn{;ZBnJo+4~kEzPR%CGEB;k=9S2#b#Jn7~Ofe{D`n~}~ zZ@f&we=@6)FRQDnvf&AVGl(z_8^q08((I($v6pdws zJ+z+cUxKqqTIHPuHO05rhQ*}}Fj$>{QV;U8~Zo`r>YN%(| zID6?*ZUmK9))BxqA~;M7`$rSg*74l~u%L<3sDMnc}jNojGlBbH`AV89*nB_xsH^;$N z-oW%=1AaCXCJrh1)tZNd4rvdMs-y%zc*L)&%^&a!EW9pj7u+Jl2JU>ylNZ`Z_zeiZ zj%I@(lOLe;;i&FepxQMEP7o!04YKk>g0GP&Z-ETiWpdC6*N2b!p@b%IywZE%$_o-+ zXaxB`cZC;D>-oF35KvGye)7@0tKn{F;7X8R4E=W_(Q$W=Ol8+}@RJn$S5QEz0dH!? z)DxKI-PhfdzHgq`&X)+VH2_JG4X}*@&=OZLRoD|qMkwKm`Y{0QW25sr+K&&WG5q)p zaKHya&~T>L=yxl>#X7HSU=eP)($|5!h8D4jhXnH#)z{$k4lFMsRXY#zc|_jnaX>t2i76YOLU zFFX^8vL)z!w^FKlz3do|W-E_YT}LBSRc%C~Qrda3#9HGW>Y(F~PeqiVumr~aq&?ss zC5DLx@Az$Z#OoeIS+e5)Cj4I27_2eJXWZRrnEdUUxsvz@zwY?!O{CQZshXQP{^v=j z`J|O(&_XyA0rx{)M!DHDNp&%zlc#j8pX%= zQz_fEbv&Pc5#TzB?+-=D`GL(&R0%B92-gCLjFcJqUe?y>)>22i#)5RFUb<&p0UJOz z^P{d@_WNIrRE%SQ#wUTkm!HAT*3+K)Yh8rh3(sRx1KudbOXAsx;9~rM*FjUh;tkR6 zFTV)}405-;j4QteR>XveM7sJJVboW5pY}yr1k&(bX0G(w&W|b%#l&H*nU5`l2)@0& z_zHUgc1bzU9g4{j1_TX9D@g`z=RYuXxMB3T*;CVm8N3Xy4+@I0^Bi7L_MYN)zuLOI zt`tVR1egm&xgUvlKeMuh8LhZYIIK zzw_jkS6XPJ!`ouqrtX>QV#578Y68r)xB~{KqUNTYUc_F0VY$LgDQ8a8{-qWTt<|&} zqy?$LSB6^u0-^r~SV4*9_nR1ef3$CXjNOZ2-J~C3Q>>S0(W^D`)b*@+1#)vW#N9US zuOCyot<}3b(*L&KgMzMcpOh)>oGoqB+)r}S-E49h0lCTXW4(vLlmhSuM_EfTS2p&N zB*zx7rKUgFdeQl}tO^9ohkJjvVDQndoYd1&4q^9&(dblDR0=wB&5s767E3GYO2MpC zgiQOu4lC)q~~wlp>5uhzH?p^^cSywP;@2K?_*E zy~?X_f7IP2ov4$yR+^Cat;E5%Dg#!}qg%%8xzj=xvGIy*kPllEI3P2ahe z#{ov;8<;J704&lIx957;aJtGi)PaIFV&5_v&He-=qI&?`|}vM;iU^MdAG z<~dH5-d-@u5sZ33vIrToPXOe&NzYM%tS~=3Ly)K$47@FA3}EOaxuOkWZu3u(fIL9- zFnuNcHW12cDrzUo@)X+v2>ZL6WBcwxb&Mai?l#PML5(JNQ@n+1^91e8(bp2YAqt03-7D~>eAEW6+v?ktRTyevcg0zAU0B7x-Zw&G{1%ILbzTZrqg zVvoZd3yFHDGR=l3+_IgbN^$xE7A=6S;RMqBTWG`!;ZWbO(;8nLtAOyG7ZVYI*!mLY zJI0da=}kP7a^CuVr6nXK)%ArcAqbvb+pC?x}HaYO7fCO%(ij)x{4Nlqn`N-K~% z2kjh}q=Ym_j-b16GvCm+$mneGo4kJMKQd<%&M>^-Nq%~<5>o%C;;A!ia1^BA_f}d{ zf3N6Qr~b#?_+90hPgN?MeSD4>ND15UOHj>>J`USS1flx6FdqVeFMz-i#sN3Q?p``u%goEeDES3T_2n$m9kR|Yl&gsE2b!mtTECwQ* z5@D@7RI4|W?9lQd73$O9u*&DFb2dMQCGF!)=#a^p!BO&yGT9pI&f0mY1tMipAAeKK z1~18TaXdF0)(|_D-Z(?!5{X0tB@p;D8>)mvSo=!0lLm=cq(C8iqWLxnI23EUCDfZz!SHgqf2;tk`E?PSyd=uU-NIo?2|AiNr2!v-c0)hf;s;AE6;>k)oA69wFUsAR&W zPAQE{Grwsluwr6Y6#_gMU9cQr~#Yc(IiQAqI420$v;O|KJy*93@K?;!TtzHjjfvy3%`UH7})^=H#7uM_ahE~R_xOeLvxI}+Z=OG$0vV&k>pSX?rG|$}sd`w~&vs#?fTKvWF;`qJZtNGLAzi zhDyCW$rp?9>01Gb>@6fzVINE$@PR`7ipi+hsB=7__+o?#eANCMI9ejMx~kf-KG@MH z2s;{OdGtWQP$j@ZK#TT(6D#<4vbQ*&w6z!$re8T0Ma2$qyw-E=xp$#3x5wxoAJ5V) z&&)ug{e~WNKZ%ezQB|_z6Tr=abi4$q5Ol-9JTVQR=Zrv< zf(5uDzVHEGA)1Vp8ibYQ;W4`PF)nu!n>=)m6;bzvzd9Cs!_DvG`Mv{Svf3h#q#cs5 zwxVwHY-B$y>=fz;j%;*^bvD2IJrLf%nv9{`;&k9~C%`432h3Pt-larnEVHM5p`SSuszpc)n z7<0pflcDgy_mKFF#+x^UgkB@xTX0a`rRf=pg!cFODf1BuZEA|+nQ!`4H+DdR*DL(z zs+(V8ws+Pu6jMRFG}QZ@)TdRsZHsn8BL$nZHDc90xA9E-V`+dO(Q!K0lU{CEU)c+G;Tk+H z-DutPNP7ZjSvpm2VR#I7d}Qt`Ubl zZJco+V|E1R@TR)P6e+N1`+`mUJ4#Gx3p+@jCsCIWT!R5d&6#H4+FO})lNU$p62bjy z*{F?a8kPR2SB`}$jwIC$*#40%$)_$ViJS^87!4W9er7UL#RpMJxm$d}gErdVgzpnh z06Ls)eG2Ppeje%a{i-PhDGK2-X`c(VyhXDstxk&gL@i=mHqwl3_cAn=|SIlh+>z>T;dm6EmrR zovBrsBz9=u_0Y%Sm=CJ3hxVw+#ks=>Gu?7TXG)%Z;j%nHSxA{m?IG!txvhmbVc?SG z6%CcQo1Z7tl%Yn-O_B2Ys@x^%YdMbR)4j0U>|+Tlc6CFh`5sycw{2rPCYn+QQ+>E4 z30c|BvuJKhU3YdjH37Urd2600J`3pp4A;PQsogXMIp~ni9n^SuGsR zvxUa*itehq96oSmQq`TCdAnjr>cgF(?v9|G4U^i6kJmq|1d^_gzVEC^>P-*Td?GyU z?zo!yS%a+QbEG6er945Uq(Co+3zN*r@-*wZ7J zN!-`}xT_rRr`_(qzpXS`)re!@59)nl+u)Ju^z?(=Q}V^C4D=83beLMr1oJ^vLnFAh zk-M3>H0j+zPa@YG$Vf}YwJr5Y`egLSm*9cJz2wcRD=b;xR8S2ccp z(uTx1$RLuwGpZ!p*%#I)2FIvL*MMlfhKz9F>d;82R|G&+T^1J2h>l|7i8m;T(hZGF zOC5j(Mq;16*Kk|uz9d-jnpWWMD-6f`EY#A`^?(0 zMu8Q>>g6ivM10)%q}QshMQ#ltuH>GMdA|u9S3+WdCppqOF;YxjS8AP5_e51TP;D{5 zOrx-uTD|8%R3E)6rY^x1w*=2-Z&!T-NZcv3D#NAA9Ds%>s4q0*3$o!hLdWVPte^KU z`)Nneusv3;WX(VuKR7Ya#nT$F_DW~iQI9@!Zu4%OTyKeYUtT?0wy%LL)}CM1<{Tbv zIr%=lFVB289s^gQSqI=9Y7tqQnx+i(4ID2EMA6Oz!0J5{+34|Mv`&dChK}^b3mno| z7(Gc8{WjolJeoEZCHM{S4Q@Ohhq|d0u7^5od#KU91qJ}d$^#){T&Wm>c?Q==0TLQX zRA24&v>Lm~rULbH#?kwy6>kpj{^VK7Nl}*wu!7JyuOF4V;Zt9%B zpl8`Ev)h=MIRF@!A_*x0qwaj;sDLAoj>Zc_N4=YxwzQP}3j(Me4oW>=yG!)6sV29$yxsrangygC|V3``5v5qr9@?041tKaSl z-tsKJtZqGS;2b+D27e^S_C9RyZ$8A8y@G_GQtL$yhevNqvx2uPVrj9?0w`(loBJkcX_4y1uvlV#$9 zSaIT0fYL{1Gw_~7&^tn}2a=6Fo#!7REo6Ppgk)yI=TCpB50?3}KP6i`f{~nZs-5;* zW1eN1VEb#%IHIQ<@apD5d$_070E${xidr}ddN-ySlN=c^Eo~fuNFk=>FHC(>HSc6A zjRlmW)Rl1n6vM(KYVT`%rlCy`NHm!{u26%|H1&J@LNsZj7Jg^$EV~M$Oazq$p^OfN zs^1JG(c3TatSWvtxxF&(a=+=oZ{dOZpRTj>{!fZmV8tJ2rr}covU)>BYusMC7XClL zjxd}+HJco>M;E}rI9kZ|xaub$**K+KY0d-Vrb!jGNK+iz)KiFE#!d-ANVYv`QUHG_ zK*DIKtVflCI)c85jNSO0TV#|dz|0VW8*`SX7tQV+5#Rj)kRAB!#b7*5^t19B%H1iZ;5XrF+`vaVIN*_V2c!Z_u_-yY_1m$ zpmNnupeI*B<#7*83XcEEyiXb)DN;hj_bVVQT_u7$XQZ|8?p{6<>Lx=FR%TOC~rJ-bV*=6c!)kSktif;%oNdzB8 zqgeL2@e2UC_Pc}6KrOSkNJ3Siw6Bzh=8LWf(6XK;XY0##7Iy6jLOc};=t}iTL$;`z za7pjMDZsV!109{JFocN=9#IFi%n6Dh-oO*220D8j^IvPd%DT!vJTb1vv{oI9T-xf# zBQL|mEyBjk(=4#aEK4j*O&CvQUj<*d9~q1&*w;|G{xYINfG4a1z$+{`h(pnD>qm|E zj4HzDWAUPl(RdXFAJL}}tYKq&Rg4Dh4?`2Z)7o~6q=lXv)&e9Tk)bL0cyb)coQ_5l zD#cSQjv~V_f(XKMt--c4*Sy+t&KF!-H+qUU`f+k2ZACo)Mx{g5Y-N0eB~;mKdZ}OI z)`cBY&Gw4k1BD^I0qW`~b|gIf6xHH85^u~7L?Q;T~) zT?G!6%)#)`HG74MEBRq%-l12aBjpO?@tw=2Z$`E5M_6aarW8IC&91aiPxyw8dm2q% zg-$%Y>Ah1(I98Y<{xZX=_q*y>vcAn>X*ZRF{y)%2y{<1&pzaTT2Nv`X@@AEv4Srg$I zH-lN(j=4J>Mq;;qAaA|B_hL%t_qrhO3u~>NP zL-UJ?id*UUj%7DpsFuk8 zuD#O;g|KPW5%|)70mc6I2mj0IFp(wqX#ZbMhyPuBFEuRG&LKD*{zvWIuUPGFzfj#yH5q&lDi-#J2_9cBX@G2e;?V&dr4wh8vbxp-W3?a2i+}*lKJU|31fNATM%=1 zf44aGwt_>^J!R&tETRDcK`DzO;XRN2tA@Z&!Tjy!?JZsJ)X4A9oWoc^~&cu2&xS zQpg@2_rWxTPx|Tad7lix-6~H8*`6Jq3?agWPltKZyiZ5?O9{1i;pW5BG4Y|l@t59b z6LLHMclb*~4Uup2ruXiDdu#4i_3fSYv(Mk&+lPxhZQSZU9bkUge=@*G?UEGBZzD}Z zD%OtRE)wCR2Pl!iq^}4Lis9oZLm7Ez!ub~#frwa9!aN$6=uhq&Br=s#jgU0K2J6Z^ zaTh1vRJt8UA-N?y1LOq5`uvr>kcE_z?an4~5Fto?>+5!LI=qC`F%EM?xyRuzKSm_QyQNAUMLkuIsl-`jdk3WE|I}L>@E87)yS3c` zED!_?4;~{C&4iK6J3K^e4688}9ES%BtDxTkmdRIKBS7Q%K4Ol8w34`BO6fHs_cb+O zaxFRp&-r}uSQ)5p2mmnh5Rn??F+(j#)H)%|#t}pk4GyuimG+d0fdJY;BPc!O6XIif zk3da0P~@=@1;l}b+64!cgoQ*3wyy1JUk53}=$?$hBRCc1VKT{BKpFx!qRU+xo8 z1!_$q8%ZSKjipF~eY!q3MDbv4E&1zik8txz6s=-DVw?cX{tmlo5ridt2#FNh=nCCV zQ^Z!b3t(tnYoBj)hxl-n(k*L29-Sgz_QxX_M3pEkxiB638HyNRX+`pEdpHjwQn zp`5S+a_)1Gn#E&^`=$+mc4Gu>Lq6q`weDx}DgzKfS(vTO*Vl{jYC!ZfQnf=ei;(!F zSBCb{C{m{jJF1_>`9=a$H%Ph6i8diW72Edoq1?O9K+O}v8+ii&)Z-3JHG$`o6VSSgpRLHVN@C>_=Az5G!dw3 z(VyTmZE>^+ya4uwXqO0sjgfK3LWq@mGy@SJ5&u3&)#n2C5M++z6+neq+KgSh+0cy1 zg$%;6U{XPUz3dZ zD}#xBo#tz!lxT@EJp5D)z8C=BYEeApt8EjpT%j#=Ypxe9iZFieK{KGa24X$$eh?x^ z&kz&erO63JZG}muO2m0$aRtQmVGIR`Rm6RzaN-^{GH44B!WPWreFM0vfRk%;ae{*7 zx#L4nt7dS=bRF?L8C4@<34-mBnLQ^$&ys4v6Q^N3-K~TkqIjt;Dvllf7NIH-GmTMQ_XlKq0Ld|Mo7n#~?=A|BCs}k+?7v2_`@#Gp4165mGQ> zC72^?@Go~wqxKlWudH)R6HF2(ZqFJ3$mA{x|b{?hdzLkACR}O z&N6qvFlLt^#yi8dYpN1f^!>pU9Y~Td97{2eIAEFud=MsavVLk}L*_PYFeyKvpE5|P z*LDH0YK$Z~y3wj$A=oXeY7`M8GZVQ2!-yj^njbh9vVzMBOPR;Hf0Ioi7|b|=EF#vT ztS;B#vc~+C(`c7jJzxA`5!aV46+CqFC`crMNSsX&|U-h7;%8~ zY#wehrUfZRI4a+*CTEZZK9S;57mGrY&!*In4euV1{^VC`o$Y&Uc|N%5|2!T@m6XMb z>`ibhiftuaO0pxWgsu1XKyU}dfDmARdNS0GB7U5BMnHRSNsZ<6PoTyyMuO31UfnYo zXL?>N84@32xAr6NBfe5X8-@P5=>C{T#1&}F4mP-c3`C2ElJW`0m=|J4S97s+s@>5e zCT}Mt?0QH)+BA_qzU@cI?=dcA_&cY6Jh`}w(O->?rZN0>A}&Y@lSZ8StvSvt3#}j- zjR3V?h120L6|;h|`kb3sVlKFHwTv6jO-}bU^0!XvV%EqFgSt8ZiO>wfhJrOH8>Tj;u8VY2ZlI zc)9D2AH5wQYCWSw#slf60V+trX&h7@YkmFcgF-s;!SEmvW7oxL2cJ{pMI?DFz~}?O zdvT2dJnb-JBKS6m@&`CjBGG0v>2}Q{&u%H@h2lF;n-q>2{+(Pz25-FOBqHJv#*2UI!~8duots<6Q>x})7R^OYyF%I!6Fm~ot}G7vreFu8hM4*SRgN9+4`i+*V4PneMPYVZ@Huy&BgN)m3@J@7lOQib2~va7@*=Eo zDrpE~@c6Wkd~L(?dHUPW5Tlw+O`{|@FoiHIO6iVGH;LZnd8{lKz3*3~Vj2H5lqI=# zTkIo*2OPX4*idVzs-KsCPpV^3JHhu<~JO#EuOyX+vUS(5m=m%YDlbIe%`u1wD z+tw-sc^V|kbLnyI!xShwLs?dcQ!~mQSM@jZBzGOv7!QpNb>#Bmvk{m$5(@V z0+J1xW}RR*TNLBlAU?zQT8*|CA<&G1!q2XSTT&BrkE*Z!Tt2vw9W?ecy+&Fb?Fl1- z*Z0}9J+F-c;SrwbvQW~cFzBdc_38wWy^25ocs*J@1w;9RAMsDz~slz#a?8F1N#=`O{E!w_I z#{c4lJo-IWz}O6-9raI$y6x3XOfF8^i9QV4TI(fh>aII}SOefaSKcovqd21^Ci!?e zk322Lvo3s!;HLlJ`|?}8nvIYZ@-&5#T)df+iYV~CfQBG(VrK`BK7x~bxvp+N93faFhng- z#ssJX*J&!lRAx|y2<~j><~qK3S-_#xMdHS%=aD)OaQAu2EH}Xq(B;=h>z;l}CU{>6kP5{MP9Scuk^(}vq1ijl?$$a&Zo`D?6j zT5;a^sEG$^%0JEM`<-QOHwxK(saT{94kouQ*^OwdS1WwZDeFR3$Wrwoq-mkQ5b!5h z+bt*rDJ^f97vS|Ae2(NSFb7!T9Up_s2F3i0<_{`qv4*jpSGvh5%xg4dECdM{%C{#n zvL|0%1W9c;T_xZBFba6N*qA&Ised>R(-$V<#FOGW&B@c)M={7KEV(rV&C<2NK@xXN zX$Ss9J${~WBS@CC$r6|kdUN3T_Ic;mClMTLy{7Vmyyy?3if&ZOzCe+pelWy)jhszn7)tS}Czv8SP=l;U$k~EfTKI?9 zn7bEnSq@fATa*euSCI*NJFNerFfA|zNQ^m-b|<`v*Fx_CDI8kE6bum_=4wp=8@v+G)({|VsAb<6)B_3VnLXb+R$qm%M2EpJ^2Y^it>Vs< zxeEn;Fex)4iK>KW@gc0{!7%ARgAflFMk%>`GPdI0@iMbD(ZCkvfc=D^NiulR@j%@R zg4*o)*Y^5!`6~e*nTafykwVG$+LHkKiA+H)xQqN$0Q-81?~-sf8|Zla)Cgm&AWb3}S+PLy5h4}>n$$Zcs7rLA2~?zFF=^Ybk(cXAS> z=Q)Smj>;c=;ziCq-O<1|ov-zzRN=Fi?bWbK{Y6794c&q3O;)+wK7Ehu@=S^weBye3 zQ`NC&UdM{RKCFElzj9y6v46mij5^6~`P9e0y(zYQ9QVVz6Q1`-YJ16LaJq@T{!1T3 z^CN&-&fIbF!3e$e>fZOUo`kuh&q&QR*lWC@c84#O1LM5-75lvQR&Zajx8otehQ}Ynp7tb>ADA zxen5IZU(=WKK%KP zpXxYzHudY{uRlM!sXLFu4KCMNug-@JI#1K4F1K%9T};33{90=8d*ABn=fYIy_vWd; znXqfrU03Hr27gYot}b^Cx_-W&`t!Z*>i6;MuFD;RtDhgP{+v&B{rNF<_2(Bs6$VFv za12QT+|e9Ey7l9}B@8(S*~=g+Gr7wB6t`RbF~l= zdLEG|7ny7xnd%>zo*tQrkIY{9i(K>%6Sl}as>DC4EIq0mA62;!RsCP&q6YKmCjV%B zdUPv3x_u$K^E|p69`g^mXwW}qI6Y<*A2YrXGkG2}4Ue6bi=}-?@e4;i?n^O*jHPyu zC3t^^ak0w_sE_Bdi~fIMi}upv*5%?r=5ed=xP!8|-s!j_2=yj zuXi!51A5H%VNp3;@RXAs5}z3nd0C3 z$BrW@Soad>JviFB$zDv8CQc`cGbc&PCrMi*iR~qdTm>X4SR^SfCf!~n&5KV`j!aT* zNm7$fzLSxx-IA=kNFWy_8#1RDUnCF5qqgwW07Sy|#RTif#INQFZAuhv;!uCXRM&u1 z_l#7}mQ?RIsU~ld{ijJEE+#&*NP8TR<`}G416=8j3kxpDYlv8~Y1OX?_vg z?|9wO0^oU^?ukl$ES`~Uk&$YV;YOB`*^==(AoWE&DV902Kt8j`BC~ieK?o1pR%)?(!H3%MwXgBlb#unnwF70l97?UnC<3~ zInA6iy_o8;m-#LuO+-GkE+cDsG3Vn&j${UD+m)8^k~tu9F{>vdw^u7WjWe|nmNCkl zmu!(UF_JMQkaHfHH}8@9Z85_&Bku!QE=U1OtdO#Pf!Yyx-TNk&;%CZd`P5^9yc4aw z-((p-GVo3A^=M@O!2;q@&KPgxm0j1lF3nkjJ7rV(juSn zXC8BAVNpvyn`fcRo5BLJ0v?4T)zKV2?KsW;0`k@((ac0YnnJ1P8RH&>36X_JXpy3J z@nS%6zCe-M&tm(fG!4t>Hbf!eHOJJl_|9mt!f2t(V!nTONy%QZgJtQ{@?7OMY`+1nm!VqZbL-{u|k!8`XZ|pKl z>vzkHEejJ`OVZ2pe3tUXEy^<#vg$|PR4=`W^(=XjSyEJ9J{M4ao29e~imm)v-l?2m6TX>5{~?OeD{nBWHpH`v=_;$vZ@*TAwOVW}iu)j2>Hv4+W*L8UJ*vF^=C6ud zZBY`@IJuh*?>!reqZ+iv-sn_B-4S|YU{zn(T4@~p#?-1Y@_FMMNWPL)onc_LU0@{v zTjZeKRA!DNK#n~KcB8S%`v*;`(B@LjDr2kWhW*B8Z506(&0M3+C6N4AV~sxq@u50+ zAuoJX6ux-3S%4gG^9#RkiBJ5MldKaJ71$CJh&w88@n>zxA+Nx@w@BY?C9NPS$--r4 zwKiR}6vA7p+Hg-<+v=iQ8(0gPgrX`x)TnsXla95)Z?<(Er1h{y;dR;veznF&wzE~V zk9lEhpEoU9wyO$t%v;sHy9(?uSZv3hx9^X3%vNNqX4QQX>eSKd%#&;XFxIj1tCg~? zbL61yNGSdIAaZ-G@~c%BX<*lRR@Y=}*JW161xxo{TLw6${&RHqr^x8x zJ%S>=vWK3x4>2F+zq-mEczoCs>K*A%Q5GIE928R(O)(tX-u2o#GE8_RNx1yMayIYt zkrkFcvHq@TbW{Hj`wio;pj`2+}g_W5{l|Z;mGpCk(SD_ zRLj(t%VQch$1tqpul>jR$49HY$0^3fM#oFKF3Ts!Bl_A$XLT#*h3j7gO<*!7vRWr1 zAQSk@i8;1OOYNjhikgPyUh?tDwZln@tke;QF&k`vVWOfQ#jW3Sx7p{Bx8{{?=2c(JtLMyXcFZex$bTwJ zFl2vgeCw^L&D*;+xt7E;CW>>{t>%PRQhx-YPYIqz!d7f?0}wb(0D zbrzEEFQl%#_gx9`qwJ2>8;JeAsODAS6q^9vvkB=cX*XL|LZtK0@ z%USho&07>$BwG5o%Dz@6@=-?fV|3suw?5I^zU4GtCCy!9 z>0D!@YWU7JS5*0lt23Y7c6~2!mh<+yU}q}d$MqfPI#W)q(CrPLqxHtvbqS74>CTOL zj}6(*)d5$tg+fBsh4d$2)75z8rA2)^LHYq7Kbo5vBZMQyGt`ZPNJ6>DXM}y{6 zo66N&uRm-#>yK!4wtf-VKCs%h(VsD{-rgMF_O8ybpxPM~-f_|2vG>^t@+tSXU3v0x zC&Z`j)$Qe0IcVZl{BBg|Zp_EsxIeq`9D9kk_mXY*QeW<+=k8^8?xoy@hN54bnaK*KEUZ8l?VSgme-3&k5BjJM zyFMNa*&Ysy9*%rG9RG9Je{?uQ^?6YL^Vsdr3$~vZUw&R9L|y)T9_2WiJ^H*(^|=~H zzLR^j+j+GA@#yf+(Gka&!kSk^5`<|2uygHSb0Hf`w3$3 zHd~1Y6ii`8_MYnM9p%+Ao!H3(y%VMfCp6S2@U9bvsS}pf6RvBgJk+OrS10^=C)aCE z1-_gJU!96xJLA6UI+e6L6}fXJ``}Fc_1Vpuvm4Z>EUU-L*S@NLIYvhYlja?3Q@^#* zr0Dwnl|1;skMkSC;u`^2WS;lUvg@1m>Nne~Z}!)|JKp*3Z1>&u)pz&2@19-Xy;r~c zTz&Vw_QUVakH>aDp1%6wpZDW=*N>ppA1|+dpst;V+&M?vonu~|M-W(;UFR{Y=W$o( z@z*XA?_4C?U8KIcNYA^-?7GNay~w?~z+U_L|3EH!^$VZ(tF`M_`|7XGt6$yME_?4> z_S;Nx>#9)*9B@ynNaPYOx$@nWlTjC3-ox!&n;KW!)Ez9o%Uj@hdr6t9x@c=m|~nBGHe{RbtXj zo9?f4hOyo|vTl9ySzVZPj8`{q;OO-CzBSTy%ua`PO-O@XUgW+SET~ z;}oUc!YdRfwug*hs%dPmvKz{^`StV&mJu+B6!+_y(NQ0lr#b-AdhyNhx*>3yu+A^Ut;>75Cb9Z=b#T6NY3{Rws6tpunBgx?)S>Hs@+L{lKTyX9OP zMhD3#w)w?11WJntGDD9i7#txivN6)mNIf>&^D z--pZ!=HJIB)*IZpB9=B(BIRu`RH0UrzA{o{a%nKqxE3aDtaZJ(!B|IZK-xr4cB{d} z;12kPsgVY6qp693+6^-Tw5ZYSLlMj=->)~m0A+_(;ji;C~&6wYBz9GYE35E1_g8FbFaNG7h&Q@`1M+~!h!eU7V zv#NQhRp1x18>|8aH{6AtcQbk=+@X;0bS_<35$dGDQJ+|(iH6ZG^7_YQxD4zxt!4L} zG6~Cd!(G{u`=fh3e6|hwaxN(%>}3Q*$ljQpjJ6z?NJbn@0SbK*6PY2X?O%X;a*wZ- zaE4~q)Nz5TPb!W9|Is?DRT73^Z8M@vTbT*}N=f$`8 zZe1^atcKrtd9hR4_43!3p*ydB|JdnzrF9mi0@%QXq46M2n`1lB!463!LpLKIj-6N% z+4PXjnZa8ULULY=q-rv_g3y=@QFzKIIC`rvlS|Mjwa+LqR@XqTAtPi}@fh9#XM0Ea zg~{?HOrLdS*d3l#8CxUNb^Ca@mdijNCaK6)#5Hbk7%-hd2%h< zg&v8BTY^Z^PAu%D%Ld|AJd4nimbzf}A~uK?hmy|?o>26<&&@>_$!5OP{w?E-DYUC} zvAmw=-MP&7SN*OsjV*dUPv^2$iQVJ|TM9ZbRCfFxhO>8`#)Oxd~V za%s9wRn}XdwOA( zyu)9Mh`8|floEq<9de`zDq(_g4Tj>6BiE?)b$Ga(K+!anuEj=Ruh`B{lr)5#X*()? zw&)&gRd<(ZTieTgD=Odl5}ArQ58)(!C{NDV4L=i9u_dpCI#0gET?AMOD*EzVyMZO6 z*b5OQwS3=7V#pa3J|O%o{)AHG;hukoFj5SCVtAu!JwVLM)zvI3&y}MZag*8L-{VoN zAU8l2;5s25bp;@I7s4Li>j@>HNlGK%` z{?RIGJ>e1=X{>tR?6c9EBh*}d&p}>A6ztV3w(|EA8bxDwQ@l5s5aYOi?Z%+}H^D$% zX1}em)I6?~n3hMbQ`lz7t;?3jyK^O_af~-x#Ct&f5j{SZC?*M9lG5qV#zmRoky@8R z;ds48S=)N<4c zuHHl^ia0PF>k-O=(iUQzV7h*P6A!qt7$Brb3FcE|hKx1Xb4*4MZ;{MWo^hsJ3k+KH zH}%rqY78+Nfo2eUOk5Y0tz-c!(m> za-pNp>;MqWicJ$FyF@xHTY8!f^!CaT{sWN2SG@G`TVg+%8`X_C6#b1&ZYO@t)7sx9 zc6`kD&IoyRz!y(qjuN$laS16c@|d6?kGz=?7(_|}y=a#Jk!pkCu3(!NSHLiwpso>N8Sc5{(n*aSEYI2jh0|Jo&6(ulHgPn zjlxuCdeHu*fI9OrEPtPvyK*Jbd(MdcUIN#fyQ)u3aP zmwkWxDOh3Li|7jgYi91cNHqO+?+7yDtlq z5~hiG4Db#>Nm5$lFjeIT<^yS0F_NUN@y=44ZF=(4_lS!<05ZMj7+D2Cc`WY^e+b>! zgBape0hFo>;*I*gVH%~^t%8RY2u!2o^%!?N&R@CEI`L0`s75S=r<%W;+FdDz4-Dl| z#sYKOYq5-RqLMF+b%4s8V)2U6dKRbj%+n^fD)v;PfX0@ZAH%L+kQF`#8k6u0649PI z2qg%A(ABRiYkuJWNh>d;_=g{GtfT+LS_5Z&+~>QIiR80j)5K3MF2!U_XE zsC#(*o~oAFMxBeXs{2(Q%QjDF+{QIc?`L)V&xxFWl9LTr;=&7I+_E@8Z?r1c*v;C0R!z+qVcWm#7;?l8KM1&?XvT z>82&+nOY2ITxl#;S-U6#au9H8(INO zQ}c3XY~?!%ru{sJ`T4gj+n-VIJAFrTBY)nspE7Uiyn6B=G3aqz*hNY=+($gLOXySa zZdIsUFo)4CxkQ>Q^L~EOhf!MN>vR?810uGy(M}W_%pc4L<*FaXd5mx1#%lmi0b23F z!kYy6;;@Q-T|!FCChyIb5kuFyyN?M#BMR^h|Nq<^RJzfVav!j!E1uPKS7Bhf=Bg@Q@>6w6@weHa+C zwzcNTC)H>MZrAoQn!=$tgnX2)Ikspd9AuJc{icq0EKSs@H(Q{dZz4ODzXSc6HyU=<9}s^qZ$R@*Zd_P7MkCbulp-#a&unjFGZFzgX?VRa-09ztcZs! zL6PP0g9NOL7r)o@f>Ox#kp5)Gd$GYoWiZ;$ZW!$E;Y32YB$uRo$4wL#AnD?q6y_>~ zrCjoGE|WMjwz2;pV+)Q^_IZ){et$fRoc{yCvMJ*@{5WlLoWf$q`@lTS^tV;O$?{~r z3oEG}>)Ga=!l|p<`wL|a*LaN}G<{>$KR^P0k1*T)#AkWn_2k3gf+CnuKWy$U6Q8#s z66TH_)Mb*Z#A$mUGuT6X)JE3(Ata*&ePqQz^P=2Xa*?jsT(E5NvpepFvotMAh2vVv zMW0M$tRw6rLR4Oupk7=%o+g*5dV3E56;L(mmKb+`L_#%}aPPg*M}QfvUr)v{5{Ofx zD+D$qa1;c&>L1VKFR1&qQ{a+dJ*8u0yp4`T>n{#Vdp|_ zAKql?ILR$TOTewyRNrm2+F>SdgC~4U5(|cs(W)-`r{FEE)goMo_|RV=+UqvTDHvWG z<5?!;{ZL(?ce3j1ieAVKAD~S-PlT4fcRb-uO6H-nVt?%{cLfRB{95`na@BHw#UcGb9^~1=bjTqBRBxlcdr=+Ti?%jagyc z&T#|EHt5W2Rq=YzMuTx#Jc1m~QPSsy8N^E6#;kqCT_;rU-e|e_8znM60Wsj8@{NF! zyTR?zODEvzh4pxJjB9$)GuLV4Ud)gX0l-OQ2TK>(bfYyjr}6;<(sQ-1UvpI=m-qQ# z=GX3;=*vl^#YdBFxRg?rIK4*U*KOMdMdIe^w|LU&MysKQ(4@6No)MK`p)21)&PNk_ z;poZ--0eSy@m*2AibHqdPM;zyj{Dx6CI@p!`v$ z2pVEa0V=TIdfw;slc=QmPre^%)JX0bp@cwN;T@7Qz2dmAO?vxqtaWVmB!8YM4VTs; zWIzieo&}mj+5MEWs5ZpQ-FGgeV&PZL3t0=v%W;l#(w!^Gbx!7|bCQoQ(5!E~cOEEGrc+!}#N&qu}nd)`Il{izfGjTT|ki!g~ zPMq)NQIOPv1!-z96l3oQiKB(I6GMrV?7^?ZQ|?fI=VB?U=F!UDmU#g0)@iQ?sG+X= z7j2>eGtgq*gcYEP2Cvvfy`HOi2ts_D{rcA^{*7}zpfxsszQs7EnrlK9g8;YZKqOn_ zc;WT65n*?enYKXMduRk?K!n}^&zvUJQIFP*l!#VUa!!ono~lE<;a|xx_?S4)LVr{# zPsQqx7$M0V@I1UGK{3ji?cLpx$C!t=<;}lG&E73+aK&ApC3*Pt9eco2J}o4znV0H~ zya5hU4XwfwBlYvUCF66L?2D+pQ_xbWcwBAf)`4eu!M&pDGBd$4Ahjp6)6ybWY;y*k zh;R7K5Q(1y_{Z{i_<^(v)e{P#6SN-2<@bfdxV5v(e6OKi4Dov|57!oIL^6soUTXf8 zl_XWM9gnCh9!sMzi$ZJFZ);@;-QQoG_{LRVVb%AtvX#2R%++zukH_^GE`jsh@C+hfWiQgvK`0&m*ugg?q6BSminD3tV%S8UTeeNT$xFQ?Sv^@;(fJ668iVg>chB( zNAEE&SPPC;YXa{O>jyRaq6d<$-ANB>ezabhr6b$C5j{&!ZAC)IsDlE0*EJxaJ~cRgBskbfiQZ_A_HcG*Up;`iN+ z*GLk9&3IKtkIe*4zP~Mxdz(py>H=HIrguHIQq2FhJU-pqO0&lZY^OV?dTeL7|7Cgf zZra<<@*Nb|$tGkacX9}p$DQ1u?|VCWD2zFkuw6Ed2AiEXr;*HJgku=J-El9uWci|_ zGU2}$phP6JustpNcb|hk!Vqa!7WOE{>MxECL$1u#*9m%eM3Npm3w@7HWl>eszX~1w z$K^1oaoy1}LYG73jpwkq(>R4o++~kNa}@l!P}-~`o%5LB&NrH<27&ClVX`!;KV+_J;@@yE`4uUSkWqD48<)o zMJ%{$O*DI2c9EX5wtM}#;!@52IDm)~r1Mp;-#FO_!-;7KT&l65haGpnmocTHq<3x= z=$z&{n~+WX6LqLb5__h{3wdD@C*Eba@}XWPYaCW=zQ?-zSKXz_Sr1)%Lvl>mL6y3MR2jm(dphLwfEGb&GQLk(knB ztChQ0ql*a5`Sj+IoVpJqbENUC9v!?#8c5q$(Sy`5b9HuIw@17>M#FzhaXn7Yy)GGsy` zooyc?zihy)j06HwG{8ME7{>NQZ zKw{7NSR4`5;HUiEvR8u=IJIQ^C*vv+oY3xQj}sJZqPqwBZcS-s^Rv~s_J|4?){%{&q9L90)RC35( z1vox1XjfZ9&Rw>=*ziOrmGUqnO#rw{?>b>Oj3OzY=lC&vA@p3hK7;t{_*uCH$`88^ z)I?!EAD3R;`Q;*Hj;DvqiAjZsSu2Zgm4Qea0I_QVp&^Xp?*>|1`hsoMVg1t>$nQN$ z&su^$3jIki>0;8+hLYL)xSMXCN#wN%4fD{js+3O)SXxfVEZ3Oi#1I!1rJ&0AA`1!R zM*-FH)y2n<7;%=&DuY%Wz$nA=?aLm?Gs98mrjrE@>XEnA&%agh*78YZ1IY^&cvw4j zLm0jzWf%GHGszP^qS1&WOt_Dt;1WO_S5ImGu!s0s8RHzRm+`?@K-!jXue8W$#sj@E zD4+S_-HcCdZyCDb+vFcTi<&?jMU|Fj(hyeYXtWCjH(1%7)2nkPjOwz76>OfNQX(EA zSt`m6FU!gD_Ld0cJMLxW^DiiZD_cpzxL8XWLe87CS+0-UgOvfwWOs+}{@N0L=-pGI zRG&{ipP78a7|=`Ua~w+Z*dBbMti%3TUBZhk0T$X@di$OVxcdbW^9TNLGCA30IfOI) zx65qCcFsx>xXBG(6%vU~nq?aoml_hIL2kpfU=o0C<8=9MO#1&3<$-cO7OMNeuf zJE@3bQ1+dhu5F-yuWCL9Wdf)HT7*l=WB?)OFZb7^BBp~%L)NgpA(Y%)ro-ZneUZdJ zJQV#6H~K&%Dle^vX*T-esWb|twQ4stVufz;Rk|nej${h*#_@PO`sb4JKaOAjR5eR` z>;8fnM7??+>*P!YG5X;*S=aoZqIhx5yse%d=)6A^tx@ z_OEl|;(v8Y$$qK*?@npEbo(VA$bDVW|WS90v&A=Mw%VwaMU0F4#Pd2X(keeQ*L}MU0H>R#P z?uJPQCGyfn31k+>D1akyGvWT8$U?~o3&U>4aY&zf?jvjn4YgYPniA09_%v1)j5I{j zTdy4hV&9NmZBVAdlRrTday^qnGs~)@@7q9TsbdI}Id3{jNSB>ANGU>n&n#qy zZPmB7r>;NSvYWKwQZnp$ue23_`O!4SoEi+_vU}!2zoy3yN6bu!^(AYO<8DIW>`JA^ zwO`7P80^Uhz{w`ym}d^ETQ<1k_vA2eL*z`wP{V-|{i>k0Ps?+Ma3A2Wj{?d!dXu@w zQkiMi-GHLP4!w-%c1aLJJAJn##@fDUk{ax;A_0$EFwu9YXL{Uk2+^KqDCtwXhDc#wr~E#VmI5*#qJlSS-RKp)3vFH z_0w|Pm2oV=LBkxuNu#97rh5}d@Ck3e{VsAFl#ntOIVRY$6istj;C4^J!2NgKV(4&ePc+Gr9w9rJ84n*UwIyE?{maO}dU;X=7Ra9kX8!z1Q_ z5rIKHNL=K$w&N2h4A+eF=|}{x)R7H8 zM;^T7kYAaV_J4!JdV%2%L?lq(8!>nsAnPZHI{a<}$bTPVCZt0wVJvg!a92%H)w*9h ziH4)3fZS#cas!<}Y5#3J!1X6a)UTUYYGoiy88vMq_mnu?Le$dbQ*W6+e=&yy1-B`d z>#1hA>Q9H#XQS?D5_CK^4${jY#xkq!yVF$5Q(@s*XdspfZVO`$q4VPE@7?F4H=qoL zWk5+p#n&mN?41#-=}XYB!+F$ZD%{)`>SB(jD0%bPMCJf9N`Y`rd;3jTQ5#43Ptp?W z^kBvX6I0$mZll0_CQjkltL?saFh>x~VR#F3eyaI0o^}EM3VLWCeuBi@G z_FSXF4+aJeBdSPPgDn?}=!tLq=5&U8EF(pY0X!X=B;{P{($M2R&~eNiHDi-z<9Li2 zYMunVpk!5pF}}DQAr2Xa?5ghI(_cE5=*#s=t@5GAKC5wG3WsP>zB3o|bhg;2_ij$- zOB9vMr&u@`+`3GU{Yp#@7UKu7ET>h>Lmll}`IYHXEi&z{9)}mRW~j)IJ|xNQKxi-z zM8KlNtyS>rtlkSi^-OWTxj#y`N9984(zAprVhb;_Nph*sPYg4lMGecGM&yn z#Kd0gJ$prCHt;ztto-5#$$!I+u5s+)wF*5aQxm%t>233!lO+F(U$zNlB<&!D$eFq< z)yDbaF4A{mPOgP^YHH?=e{v{2-f=1PvUpmnkNbv&ojNQfFQ_iKh=)sfOK*ObmC;bj zjaiX&fLh6k@}-JLDvhUegf8@IIEmjfxJQ2&lr9^eVGz6M2XFE>mx&pveMx!gD9{D( zctRtoF;Ba7jde)$TF4mYzHT<@9Sd2Bk2-PWyiOtyGOmU-TWTL>X1g{UUMP4nN<>%$ zZ3%_T4_oT%q|HUMiJvWw+^vqwxX-rJlnx*FiDQU=R=FejzIjF$gL@*A?fz9=T{Jwh zq39xTSL$qVI;Gk!&w(hT8Gk;K6BnJYrdR*lQQ=)jzEm;0_4W&Z{k0J5hvf;@c9u^4 zqgB;Z<@Y|jIR0V*bTMj{Jo}x+&uV4uHF)-l>DK*K{*A@yKTmKY)@(%4n=%clVlR~X zd}i=%E60qK_&)Z}{vUp=^a4z7*zdbOWC9q!}(=rZWqHX=Z7yoaIS=E{VI+YsTo^xJI5#_pH0)_2Wu zEYa6i)~%`A7G6kx@%`d-=x*>!ee~ti#h`svN+=}Qo+$2WOwr8{ z3JGiyxAyPZ0p8ZX{F-5Rd7yPIux~2&dq&r-eVdwJQ)8X~KPx2YpQ8=oVa9S{rsiRH z{lm=D!z}S()(c^_=VA76jH4XJ*&O5Qk8w}Oc;YeM3mBhsj4wRgPcHnidH7TRaR2o1 z=lJlTh47c>;V5`Sh+G8PJObk%5s@Adg^!3?h#;iEBI5rq*6uT?$;N9JeG-xoQXn8` z=mF_9bVS6^dq<@x()6LJ2o^xa1VV42N+Pe}B1J<{QBZcC_doAB zduE@RvuF1HmalwBxYu=G>$fnm|0fFxl}}KEXjYb&Y7#HauP?{nW?}RDbQ~)rpfM! zg?N%d%;f|&6Ap7Mh(t*m^G=4)kOg|sV;J`w6_JNeUTI8XJ4g^FgQRT06D=rSBC?;L zXx9X~inE4;kg%$xRY!;{{xUxu2s)E8M1ZT>fOVOO0vggqPne^ny#JVjfT3OzkaNd0 zC4IL<2tK8sh8!ax7u~?WE0abk2-ufo_)x+e8YxW$ZBM2B8A{m4sW{URx{_&Z?Sy#% zYKVqdTSf`eSPtA%{~Xx<2|~_Ok;+vm@GOKKTCt4^M&Tg<&`CQtR&XywoW|mZRwdJ+ z)=n@8Is;|`mtg3lslXQ{oXa8Rezb9Zp3ZqQma`QX2$V|Ub_)g7_GK6mAu{ zUEqqeJ~Rt;p9|dhD?yM78IyuPw_$I?W$Kow1t@Y#bHpmP8cT8Xs7O7rz1-_X@b z^yGfD1BM_yM$=Vj$9V;?aYS;$&k$Y)SPS$*#oZtp1duLG|H9n)4R54)0N8K2*w6;h zPGM{@#;&#JVETP~}&(mVrI5(`Hk^JS{+qORB!LDwKxUm);!7N9fWOa$1qoxrTE z?c>v(ZP=|S1xX#C7Cb@~%TjM6#!I{0ybH)rBUnD+97VH9krVl``YXM5PA}a|h4VuR7O% zl8Gtch1;R^O6GXFuw`(~T7Ddej{;O^N1oS(^$rn+2#Ll4Y!@OhnuSXahE+Loos16&oQhaadz4rze~^MnSEa7P+9+ z=>eRwo17$a3&I3(5ho^AUCOs3dYi2DA&}TXVBsbMQ8bq4jI_s1`H*GZd!?LSfCkp} z>~Z2aC#pJeKA41M8qb}0H*Qko)>&+MGXB=ZW zi){dw%hp^bjY3o)KLcRvR@X+?m0$q$36!~IFt5#7SsZJ`W`aKhkT-&?nomFLcCL%| z#2ODnfmv+DI*2ZW4LXY~6*`X=o&&I9=-?G%=`({f5UP3cTpd&0F(&J%;UNNAoz~>8 zwH>!Ezh&e(DoYIoX=PJnRz*no4OGNJ6tEp@xK0;JQc-Bqku-Q}9aI)x3xh!ts*~Sm zgOt$@O(O{gX0Ta0iy$6CCA08^ru}sxkQfxR5#$KHv588xMyKy%d&EZ6k~(Zo_!CSv zp1ct?IzJEn9p%queVkbBDW%yxy7w=e^^S%?Sklf2RN$Q+!gs*t&2qN>sa&>fRTP6j8`q z#}ymKamjjgRW^DKCJX4^G;qXTCjPf9WuD%R9LY0nF8`losq|S@gBfY|d)A=#%Lal7Ss-DgLr6VBhkOPm}k+Oqbbp zg)39a%|ex?MZKdaI6wEU(!1IG!}lGuOt3<{OKs;oCFuC1 z1C7%Bv0MB8v9QTekmYb%$$bCaU6we0+f@E^wF@<|pjn^0XQV5w9&qcbio{qvc3b$)*UmxGiZ z5YbWiHiHMs+*mjX^6tr1uP?W+*{ewI;N5}RgR}Xucv66!1tgu2%Bq)VpbtH5qZF-C z3Qq9=+GkO8xw9>Ab7i;Wk^W7AHOLx&^SvUu@!U2=k1fR{&7~nscBb&Gm&7Ym)R5Dv zz#z9xC6DxY(S)hX&?-tn7^Br^Is&Vs#% zkBiL}&UsW{1v>Y5d={WW!c*m$AprqfqZwfi7sRA~GL`L5uS8-VuEbfyo}|8%fr#k~ z^FWw6eNG2MIzlR!JAfq|`Y5jOE)MQ-{Y22J9zsF$4rQQ(!yhOjzerJ~Xk2%bF+)pn zuUfKW*3Cy{#RYa&EY?%B(k-QK@S3yAa*LTiy*+3y42N8nf$=ln?ivfClHcAc8pqhu zP7Z&cHU|o2`F}FK7H|pAdHSJ6uE+Z2uW$UxVlv1l+6H( zNzw%xoMUPBlW8$*R|;w##us^Vj+eW!|N3hKFXk`&0-p2znTQIFb2Q7*m+^VWs;t9B z(7IhyeN}r9M?N3Pj5+&!fjou)R{EjSBVOg1KKES!ThDN`CN zH=Q|?8u|*}Xao(1gBv%bDkQ9eD!H3cJOg%m4%Gq5;3$1hLae?>EtKL0T+@qZ%ae;a z$El5c>?VV!sbfjZVAUc+WoQjfSCr-^_zyBTa=bGHAaWkXX*$6^v0i1Y_BlpQzL<}l|9 zaEOqNH*x3T5qN`V+;2Gj)mrd^W^9)NSlvH1kfa}DD%Hg}hWrAUX58Syu`7RMs&{shRZea9_6=tkk)0ab(S5gerLGT2()Kh3kEfX!ZmM zwgTZ_?iDDtC9qK{0k<6^HS$=M(;u#&RHg8!-z`M$gbFJ)ts&DN^unAgwl@GMZ_-U} z#nWH6LLBUE&uP4QnFcO0lj%c|mc2Spaj$TMS-eVoS9TKd~yDXo4K%dm$Nzf(ac5M|OViH59&FTMh-jivQ7Zs%z!S@I#>I(jiEqr)QzTbpt^FojT}xFx(KfByCV1!(; z@H|=Qs3vH{=E87f!s@dxb-pSkM_R06`9p?`6_it-)UHZM{u;tx-%b07W<6^&$F7rf z`+lbjO!~pxuz6Bo@-}@9@I<~{CrQ8rTh?ZNIe|F3c zMcu7S8{fKq_Hd4#)Y?*Ex$Wz6I6phl+WKsK`{n~COThlD?WN_{z}&-k>sHS?-j090 z*LnD!k@T$Vv*owYg~P>ziDx}O$G?Rg9xeem+Gwm+jBx&=Wteqa->C^k)Y+pICQHyS zX|?lTveabTpvJ^b(gP+-z|lTrY_*%3d$cNbY~4O`iOCXl9k6DTpc|!Z?_V`S3rX z!YVuj;h;eJ(T`P!B3%NIxM<`&4ssd`)hq)V(-3oHl(w7YIeerv5m|`?*)7A%Jc*K= z#Ioa8z1^R4;Of z8aPTu*-?SUZmgGW{++!R2`o1p+0VNXyT}BJH}o_Xe3b@OYJE#K^LYEe*k(;;+O!-lsAjw-YItpnfz$#Re~K!u(8J!bL&=WC#P%wTwK2 z1Bz-&Ff>w6ALGD`Q$(fc>vLqpJ(^&1R_YM-F^QfksT&1hM0KNKQ2|_Mod9dNc(?Ub zDO*GlB@i%-H1o;8I7Ul50^DM_u40JVPIoW1hyBYE%w;Z~%#LOw5MKRA3Dp#iQAnGQQZbzqeZ^^z!i># zbH->$ls?fgMpiBZt+5%@Q*?(Cp`9O*1pTagMeHr0kuP*S(q=yb%TCZNAqj(Rk5kia5}humebFlT(pV-XNB zi^~rX*J8uwZv)a?4;muJF=r15-cp~yWn7gGVUAOHx_w5@ z9+*BCRHzIdcT!%Waw(8w?daCe32@jM)`9Gxf5$bP_FM_q)$r?9%RpWmyddD*`JYiE zI5x#9t|c;?HQQseY&J#T$n(+Hi@Y=D0c8I9=+rNndQ6tUxisx(6djMaMujX8@<(i7 zW4x)7oJECM#30bQ=9ohHCn#4OhzYjIx@F3Updjgae%X72)^iX2m9rjqp; zkq4T!5eJBeXjqjq%$he&m&d!9j%@n{9_cHT6ah=vK<_QX`>6%`RLDIy81s4w(1*>{ z40v@OSmTy4hr7g$)xN!&*vSIC8mKLiEh>0SD91fRj#7}X(WGzD$?pkVM-|9E24ctr zHX6Y7-lhe2rfiAv4nLX#>D-p;&QAh%kVArINR#w()w5ulF*cE z*}>J5h5AjboXg^Jchi>y=0``iKEMT?*yZY(h44~=86Wg!odAsi!u&W9Z2&RCJn)A@ zS>b+|bP+p~^PB@9FgAsML1c#jwr+G&5ytw%aG*62DGWQo{3is#bBG3VG1H+ZWK;*a z;w~mGSM;&A6DtQTF@7}AGJtgSGi8nn7IuS;&>_|BTvm<%$^mK#jW`p~d>$U;fJI)I z1==uBYc^nxYaj<&t?X31_$y}SgDwOgGTAyV3?9Y|EinY}jb$)uS(orCw<`w8x|6?h zqFbioc|fzK$#T>j6(mi2EI$>0POA_@k1|>hybX9P-)LO+C2WqYTa9LuBqmF9vP);5 zXF~?r5*nkhFw;>k5``UB1v#;0H;O|_iSW9+L0YiL!GO~pn}OW8X2)DElhvpzTH3r= zP&h5^QZd&R8<1Z$&=NpY{E4vW$~~HwIxt4g;n+vq5Ne^LWxn?qGi# zZuwW0h?sdl&YVqVrS1~a`0Qoke9N`ds;4IMXhAHKY{K;mqMaXy;;%mZY1Q6G_}`(m z0f0~diY4biUBmwkmr*}XAY19w|FTq8KAvoM@%9eRfIj~3QrZ90*ErWkd@0}qk&yd; zX>I4b(HPzEyb#2Tr~h4p_#shup#{FRX()ShfmxT|ct85=n_Xwn=KOc_|8xx{zpCK^ zt_+Y*n-^HL2afj!e$ilCP^DWqQemCq_t((d@pK}$s5|N2 zET?hQy2w8(k=To$qlL){j-s(*8x60PC< zGhcm7>O}(H7+U4!FZF4*G)cnf*J_+hN1K@6CvNgJvz4q96B%v=YpY4tNxW-GB*vj%9nqdES4SDVIy`VB>6dO3xdEx$DwO*WHq$){CKIvPLmXJt81yUx4NE#4rQK}4*G7khO{1heGX7G{MH5Luu$xwL0z_L#bx-Jv^GZ> zqn}&$GGhSh`EaY>GpV{R_RrvnoguMkhn-=VU*67$jCn4jCP?e@?wIOT(k_$M&I=lq z`}wYMV104^*0{lmy1glrk7Ik&I)#UUROM6h--k^9rL~P!>Yh$o2G)F@achYCKI`S# z{e2EE>)Y4PEgI{j<|nzdq{E#DUltE{pKDBNf9o?oud%&5pLF!y*YMlXkLmkM z8sF)B$$t*ae2%q$u0LpCvJF@L|2&s%Dnb1Uty8@JyJ4Z>cz8Ki`fqh&uz|QxO6;#G z4#h)R{=XB?y1>we$Kj!cg%dwvH!uu>|7|zM$rvqEHAlGghs+GxogSkEmWca1lr7C6 z8hbT45PLZ{M`nuowi6x6`>=>T;weoqTp>#Tf$hU%vtT`edhtg(=|YIdPx`+-wZ2?Y zEE47)tb4kkEYfj5ACU{|5(?zJjpr^xXX_itUcVJ9@3nI3Flz99-ITv|`bF+KeM6OE z@%UhW&y&wg+5saJKw?ZkfVEObtcUZa5>h0?XedW{ekU$8!Ar>g^FUKO1)x|-M7R=$ zL3Bbgf1cN0_UxycdYra)36_GwPA6?U>{6-zZUaY-1U|3b%+^{WUil0ez`o1Lt|}&7 zlQ|>^Nl{Mn62Ig+Jm%Q9dtaeVOjonr++sd3r+v%|mwm?K2TxGakiRRWrqZHTbuVwi zph8?Oh0RBl^yI`&8Gu-&=YB8k=757&{ow3zrdOtl>^jn0>&YyPkDHb+SVctnQ_T6h zY?6NpxawS6FL4mH$p~E7bAlr^&wq$r1GS0xLw4L1n&Wf zoD%ZdxXkBx15UL#o}}OV6?l}darAs=xR8T{^o1(3v>2moP+~dvch2)wqBD1mL`$@v znq7D{^1427za#|t#X7wsB7@7IfOI7KGcQiL@{L1+-kh&AHRnQg==b{I@lCDszBZ%@ zud?fEF?I+5NuX=LsQym1O9)9y{f|NYow`lCeY3d{=X(v#UXr$;2V_BRw=z7=L`+Y~ zSy$*{wBI$^mljoxmjvy_$>J4WX@PU|$MdaCk1WmIi8L3d;(Mua*KW+yXB;#8@3r3R zt_yrJI%Vgm$DQ@A)cGFTc``1uWmfRo3HzG)bhb;b_TjQdN%8N7m49|UlQ+DXm>MDY zjv_iEk4N7_gNebJ&ki7<`|j||*$O{g8+;8MWJ@`BGoQ4sTL!r1Bi@&_JQKxdDe8WZ zU829akL9csvoC!6z9LM+^>i?Cs@)Q{@WKXKd>Mx{L`)nN&Wa_F(ZR}sEl zpC1#U)%IsvvEu5tZS5>p3zcUT3+fafA*fz`BX6+=@2PuQ$k&udX8k*`CUSIftipp| zqiza;H_VCQAPP3;p{a6OjVu{!Fnf%3d)j#K=aY{&zhbT*@Y$bk=~|-@eoYeCTPWRm z%cq5n`gY3{A1w*YhxhX)>%6-aAUUGRwbMR%p0|Y=fPB%tpD`9=+H@DO`>7Hs#%*xJ z7qqE8c9vsvI;+*R;vdUR=lkv4W!^a5k$0!WCHY__VS&1$=vd>5y=V4cZz{P9`sK|2 zo})umD?@I4D)~`1+*i-QmxjAL@E$^= zxCT%N2tWL_j9pUoLd%nlp74oe9@ib0ew=w={o(z)r}r0=LRg!6zAJ>B+xnAwU*hbM$d#URp+S?ny|PN1Y)9u9 zPNEOVFLkEo%FpQo>W|ixk00Lb*F1jLDf#D14T<|dE@Rk_=LH9Y#{0v9%9~#woL?fo z?AW+=DQvH#^v{1>#?7}rZ;kH7mfuIE-24&!;6T!B<>doM?z4YBKNiy^{OdAG5gr2X zT0lKHd+!h54?sD(EWLdY*^f`RC!Unz;%B;yF~kQV4|XIt$xnjC9i1eHv^j%AKEBmp zs*PCA2&T)p@$A&V6R-KtXi;yr*H0ospGGK&6ZI~s>q?P?+)2)uh|rXvQz!k=BH=m9 zq}M;M*?5O?%s#9=9cG`UdMPGSpfNJAk{GJ%>88o~&^YSa(4&9WFW6OvSFt|Q+KURP z)UgBX|Z(T6Xi!eMMo zukmD2Y;{&x%}T5qYg`c~_P{e_lKH$F6UW^cS2Gk_KYNF2a=U5vp5~jg&tl@aisGv) z`HJcB4L{=_pGsJG6``}PHQ=3qCMM)$@mUTfSg$AOh{u&x>Hwu~U->67Dkd?eGO-L7 z{;n;W$u!boVV$4Pfiy3D!f>r;B~_+GZ_g%uYrD5&5?f%OycV2%DkV8Oi}?qzL1vT3 z4w3^UBBveCfPKiqL~>9TAMZN38z2DOgVd4oB=AXq+}p zWiB4M#H6}Zrd~T9N@Zd|0VmRwvpH3(BGt2FHKiYF&81?8(=L5XJ0C*Ubs|;t-rtN# zGMo!JZc95+rNYD-d3KmsBOm!^`URi+#?o;u!OAYf87EdU3@{mOgPH3ZneO*9OwJIc z(lUK{IRn@tY^C83=E4Gp@7(#7k{SIZA z{V2q2zJn~0Q`ubES{Xjsh~Dh)Ls{j&!V65pzrm79Omo;$asZXtg(A6zZ8^}lId^~M zP(#qI!(s7ke0Ia+=cc5#s+*MTsIIwOh;816ac&-G=7e!D}KI_qC#=$}5zmD^hQlJkF`S z9a6D=Y*;BaT#+(W5T{jDimnXzbxHC~*@*Vbo3ASPT}9!mF4n3p@GZGzT2YfARJZX}ri&9|v236z)*g5%OsS^dxwd(pw=JiZP*vkPP?Jk% z?dw1fYSqnbR6T|Bj^xyhc2v8lCB>3qQ!;h0wd!BR)y{|3qlPQ-Yjw+f^=!KJ46T~C z)tGhXhOZU%oBj16WY({t=$(zKn&86dxUwJ4)Gwzhe~&c$aYi4{S5;^EZH3f8&o+8( z)WJKcd_D%dJUvYEi6d)G^1P78=cKYCU}#PaU=> zjW$Z>hS_gYFXUEgerY+4cp5F!`2N?^EBvj5`DC`v<}d9}XPrsDqpkk)@s9DV0e-Dy zVk@8HvwNN81tzVS2Q6X5q+`A|P3I_5C-q@2CWgNu?y$7sZQCE;wgBNBO_@4t$4X8if6b}o?40rk9Y*lLYW}*~T)(=7lc^)wjk28+J^@c< zYdJ!z+jCEf!5exGbEi&r;p0l$pe;96p1q3g8b0i78LWSVXMNyOT2Xy6r?dRyv2%Cp zoX?gsfbQF}EDN_i%Tsz-%A^@b&U!C81LixsojO{bce>kt_b?W+h=W~-xa#)S9{s7F z^pWR(;s z*o50Xo+esbbjGDG(uFF)&m4g2@PQ1V{&8ar&-OE(Q%Ou&p1Z__9+Tk18%~9`O?z;?MO6aStd{Tb& zEH7`M06Fr+d{AW!9V{@KnlNHjJJKr9(XusSIyPzq8~)=mTAMK1_5j`KKgOmt%7z>p z9UJt$49G@~-;o{9Oc*M>JRXtIUsgM=7&BIZXx%U#_O2cFGoJ|59CYpK|EH_>>*dJ+ z?K-xjzGeT(qptCrTb;386MwYnO5PLsXD82E(BY3JkNuzhmZKvCryh=t``1kD%S~an zCwnZKVU{m>|4iY$>B5KfQ>bZ)b5p2ujle6@lJBQkq^5t&PZ74JRgV*=`5)Db<dApFcB|H{F)=N~mterh7&szfx9k#`e)`SC^T)p)=1C zUb{XTvdAy9I```8l{ck;SBCHz>l<(UAB|8u$}h{0-8lF5pL4GjwBDFlz70)$^UCS9 zU)@{(@wXGaZ)*^wUq^Spb^ep-)8@r z%N0xylbgK1eynAIyY8{__+x>3txQ;lPSn&S+ z`=xy1>-P&E&n>PA5{Ad$f7yOtk)PT`uiuwPf4>6wnZNX-d+A_&>G%63z~3d%*Cnvf zGDK$?TCfc3S!P{ahJRf~{$1u`uTQ1d9LTfrB&~4YTnEj<=)O-%cx%KpIf{9cg;oUldHlfH=R${T|aqSeew=pLZ5Hwd=9Ysd?DoOYW zttT*D#-8U%LjSsqvA%CJnJy!Hk5~N}M+;3pT#8RaY-=)U$UM z{@!TP*^E6i(Gs@VCPdxN+w5BW7iFXgZT0DF^}B8jhHVWMY>o76jV*3X{N17pZBOfL z&$w>C3EQ46*q-m%W}YBj{JXs@^!0L;n+7UY5!3yt+p5GO_x-0Q`SE_JV=J~GN(yqesE>3t)`S|>v>eW5<$9tNE zds@%;w3qgDj`#4w`+Dd14X*ARJ>EAd+;0=wG*jHSSlZX(n6#PPwLAY^;{4N#g}Y3e zQM{pbeeAo?x9_d&KX?>>SX=+V-1-5C|H0ev z+2)3{!$BZeSQ(XVBN}lR4+#el+6V{_G&CWAb-m)Z9Tswn4Bh&CVCM$$!NJ!5f!bqP zQ4xlmi&l_PNnz?IASpIdXp!%*22*Rx0 zQ9)sDN7J`heB6${L?bR!fe;*&W(_xY1AaONUUlnbz9a(d^pVJ_rPyw%VxJSz|35CH zLAKr6NODyeH^GKtKm_p*8Yndu89-rZ^(;EG?r4ePhkFO7NZCpM>oVRLvGX;#OtpLH z))H$OE8=rf{iAZ90Z=*DOxNOC-$0c5Et+~vDm)X4jU7{-0gJ&D6oh*)o92Vl4tT*I_l7AKHo3&v?ynYw=kf`?2B&V6${g_qQ z^(c6EZQS~GdNm<(cu`J+u^aW}1`LB&5!52SqJh+=2o*=^i{+f}xB*dCog&3^6-!l$eDKQt5TQYuB^J$h@Z*el|M@SMG2J%p zi3cA7B(m7%sgnh7Ye+8=mBNO@Jf_9)lDCg4t2yk3;2B&(!F~J+%#)oOO(%W5pYe7~ z2O!m&T-=ikOx#~YNG$@=xK*x8VIxF~5AX@<=jTjGjjuv3G{(4k;y2LAW)6+v1YBx@bUfz%b z#V8Pl#$&neNi9e7>NvV1*D=iV_55GUL|FKfG+)cwm17zWqRr;K-~#iG9+4V-vy7ww z;V4aySjnjEGEl4c^;jevUwdZ-a#f?Sh&E>xE>C6bjCUq`%U-&D_(*xU*B5(TH zI7G9SBc$Hkfn^H$ODVCQ;BsPDlvMU+;mCMB@F!AZBx)!gv?_SN78Oh`Go5_)ndveP zyb#Y&HS32w(LgHI9GM_(Gpcs=)6Ut)*6`^k-4sq0&u~~olZxyNLeKvhgcIc3t)ygh!NgI}bFpR!;B=X;!dQ(1d_<9+PXv)Uh$QF!`ku@;jZT$|p> zR(d2in>*6*K#%VYJxZg0#lWlW#hX=n^m(uc`rJ!>Q6s|`V*?Ma4DU+Olec57Ngmu~ zumTCL+i{orJx)H2NtGE1h`$Q<#0(se6$S$m>_bqzb(KbWSHwvFkURy>+ZoLbr-(N+ z8VG%liP07XafKb77GoYL#_vvXMa_5$dH!P%-!+w#Oe!^4UvD+Z5lal6=@;44G%>j| zomL3GhE>acX#tl^M5kQMqFpe(7}ogEH9!wo%82}1RlzFsn=%}r3wI8v;6}(0(CL9A z=?OJ3SCa^AroE1=g$O*nGO^7@#Qd-PiBs2)v-D0l1f7abw}#ut@YuIz!lg}gk@we^ z^s9HrrKq<~bcz|u6f+{#@2M0_H@y%%GKjltMMSRdL4~`p(68Ks(q->FMfBO&&f{i^ z3jImg<17<9t{}JOy(Jl!_9@vnMPM@-8W>B}w5*lXP}*{^%yG-SzD&5D>Ahe!^AU*R z#zH1fL*y>|hG!k<5=y0*x8$40#1hw7cEg8MRj9-i_Uo7L&J*%i_sHM<L%iGl1h}63l<9d;Q(73!&vlJn)1{uC29Gol zePSOc!KrQ$`BW;#%$<#=noC9?vi6wkyKx${lmhT{x-8R19#`G6<1UGTNQ2#BVbyxv z5op8VdtY9IRNcAr^Yu7uahQr2(Wi*m0jcyk^yQ;(%$tfsPvQ8;+k!ETy0~7Sk!w8kztB4c{B*mC`rRv5Y8rWhZ!usV2-kD_P9wnH4tMQsLF*Xmy9#KA!Rb z*R#W>o$yR*l)P&idNh4)D5F^Bp^MiAIRnKVEK24!?veIUXren8+6?M17|0c)ku%0@X#EDi%f ztWpep865ygSFHGI%HG(?R&_|O7zic-OALU#g37k&DzH|MKb82oc$)k~BmQ*csV+30 zJxBgbYX^_mMkilPjCa>-Cl{4!24TNRn#E2kMI(%yTj;D@A4&qB*8cJ`$||dmN{Cc@ zCz9;cssHBh-KPQqaFg=|j{PJ^iU%t~ba3MJEYYx3JV)6PST{STVG$|(rWq*WxPtzO zpqdWTa@oX&7ldtQ0xtMvi|A5V=8D*AH7?pCX2eXl3&sQ&7t+25$Z^%y45|7JkQ?5J zIO+%A%sZ{&d)&2B4bIALxzR=kFngwTZn5)0SM{I`M!KjSi$J$4gz&@G+hbl%NqW6ce9=ppV?cX?4`dPf4Xvii-1uB~Of%q^HEt(gVZ_zy9 z+Gjx6cY2bXm4{MO8_t5|=o4G_$^lnxCNES-r1+fFMId9#o@)Tk{!OhD33as>)F$vE zxv})igp+a`Sdx@??27OMRhmh9!KooinqffSM>ntRDHSmuHpO2seA+7xu)A)%ll`n; zS<}L$V=3_l-Su&C8Rmi^3(wwx@p*Va@&m?4p+5mSI^Mg# z70N_Vzb@G%O_Te>mqqZ-N9&v&oJ0vLp>2(g3OL9*xgY6A^Nx zbx9q-Ph$~Nn-Rg)#8biGavFCOE(+vLxZ#w|-3By!08>Pu9GR-!FM_;dn$rp}St(Z> zs|JmS=bjepnr>GQj&wpt*RMo_hV;UQ`s#~fo!nST{3=n0V&-mOJG)ko6X*4sWRGn= zJgq3vs&RRK=BS`<2Wpok0V5e7IhcgxnzM^B06h{L zrji}vAHm5WWUc26JdlmW>vgTbElDfnE? z(zcF2SJS3JYrAw*CBq=pFPHCEHh}oDl-t|drNRe2!B70^dHnm9HrYu{HM;XP4mg(k zS<&)adWx%q52XNKK1PQGusYIul)Bn&Q;le%`X4^Z2Fd9gRBIU(zX*9J&<+EsR3?sS z#vNomzfls)LwKqy7QwRm{4GNU<{dtRQ33f!B#Rnw;AvX3S)kwuUMk_3o1kioi!fNu zkEN5!i^#iGL~criI*!IL-bhoz9BbV0xGFps00_MsLJtkG`g53H#0r5=gA8 znhMH}URyA_>0o{n%&J0&R1Z*7u9YoI>uBE>lP;wqPU~pob(A$rg@P?=+_SY(*j{}h zOnrGtl_l`F2@vJ_PxWTk$FhmI8FWVU|H(CgOM#Saa@ie0*fzN{0a)ft~t_%Zu@(6?;CJGR$ zik69rHmWMK$|j6wzxg7Ryai9Jr)7dVg!s};Qt;-%dk01j$vsbJtaFxGkHFC(S^PaR=f5_OcJ8xy;vx5`)*G9wYb9(h<`Cn9 zQZN2SS_{3#G*X~VP~4|Raj2xBGh&NC5FBDL<_3kx5>vR)k1lhGF!EtkpjL1LOw%?w zoIoNE!DtGfh5+o5fKz0ahb1vvjR~+J0v0pw;0O|Hw-u2Wu>@p^-v&OBgIv}u5NibD zXZaQIvNJ_&1yY2JSQ?6!5InCrI08hhPaP-Pa{9f)h!Y7Mj0lt9vx)&(S~#HEYrxrS zu;d&9k}epU4P?Jkz3M*+94WCD9fe2a9KM@0UbD`@u^>iutW&MkyGFY|w1cFeIc=;@ z^CC?XTQ8KD_jl0k%d#BW^v~lWl&BGhE0TMhq-v804UD8YrjWsz$a4*54nzH6L%n_R z+O`s|OnqJF1D>KmZc#}WZ?Nbya_!<_zk#HiXX1C=Uu(=pu-QpouEhDtLvEQsOmHmD z)u;>SgrgYHTWTz98|=5TX6RW@>|l{D(uLX{BqPF`D`t_})0gzA@s1{u72J8jk4Bn< z$?7)sf2-^+W7UnwSSoT<-)`o(>rS*2gZ0S5+~kV+ksKgIs-tADRQJQvl?B-l>g27} zzN4AGzx%Tw0^~AX%}VQqX1cM%fYY@(66Eki95MxOEtTV%k;JPi+>7^sn?!%`A5WCF3d$bD98csw^8u{S4;w)!c}^jEZ=8bSa3i) zmBkx3e1E^a<{ArJwCccpQCn=j8?8iffagxK)!_c{FV$zWBKh?_Yv^CgmVRH!R2Nmp zgTN~{W2?I2BEER8RE7_3&qT)YuIjSiv&Sb$5Z`()P>ZnIoD-2_q4v7kSGU6k{o$3iGVm6jK(O1nYdPcgL#z zb>qM2xl!|BZd`9|0B8Q)96$KccQ8iSTjL$4^n8F z$X$l{F7JM^Lz8B9omWKb|FiXZ{bAR7oa70L!shRmEg9mrhw3*O0E0_$w-2SP*}yrXJ$I#NA&?d->hsal+!33zEZu@c3W#9rEV<0FW`I>Y0m zxDWEW{?Sv2Wt83L<3O~NNn&3}|dA z;5h3=e39ELb^r(u2zLo(5qPB}RMRAkgG-aap_~OsJTW6DMoG5WL9rPGkNPP#qnY%4mz?t_Q^UB+uJ7=L-1@ z_xgQleLaP-I^i5G)#cDd8~8W^jddRK%p10k80qX9Tj-i_(Uid&DxkG_p+43 zeHbrEcb^LML0^*{=nDO*$Kx`^C2A7>2kiT5&?5I(%L;+JxpknlI+VCc(My=6t~g}L z=St%ch3AKh5i?3b?TNy@nOLW30~xuc*`|M9)!#T&|N5@u{@&N^Lk-4qU-SvZn-A~F z*d-3r!Y{b#S%srj0c?H2X1Sn~a7NY?=3+jQH+by!70!o57#bckvq%gfLbd6}Xvdck z)79uV2q!yyg!zLD7igS|7LC2=s-X`C(2MVE4cUw-rFMdR46>P^1USV+^h&TzKmY$A z?>&Q>e%L%pLj0IM zA=M}#25bzr%LZr2?K`**i->BhY5IlJ|L`w(B?^r%Dg#>@B2{^_K1=>31B<4L0sR?= zD3ONaCc(wKd6pp*{QOc*$ibiTv^>kB3iU;&;uIRn#v7&%2!wjo$yvFAhI#w_gupGl zpLaTJ%BCuP+nOC7u?s_Du`+tCY&3}n~i&LqHu>sttK?4&)Z zqj_)(=!o0iJOdSmMsT`V852QJ6Peog?cTqT!#6utN4(;Wfb!w0?gVt|**P`SO=Ef~ zZUtuFWMHYNN@bqn5%6P%fhC3>HpVm=ZY4?NS?47QCR=YSwzSS0(4*ejFzVVLi*RVSAlVx4zpC;Q9be3PYMd7iX z)iJFnPNx&J!ux4H1xBK`x6_PPXzFRg(dp`wxKr1L%@oQPQnIwuUB9H^F0a~8OLL8p ztwe%@{=oXDW~{ zOhCM3x^r{P*EC6Qr8~Q;iLuEG&$w?3Sel5s`5>fogkEV6-`YE8E>$s_k6a3`80TE7 zy;M~zn?|kbedW85XX-}zdBkP;7N!{qj5u-#2nHs}gJtr7vg-COC$b zwmr7LBNTQCTpIq+M0_$z&EKAr(GkoPtqnZOFV zCe_89KHC#mZ8KXhB|URrT8=!7wjb5X2yzV5d^ns@NSESQ%YsR|7`()VM;|^b;mryx zk0lw|zRj{$d(+wdh<;crcSo3Mot$~Jr!GBP;S_juRX7@Ikr1Ds9Kw*fCt^s?4$zkt zdDJwn)zz6Z`ffEu$c|9GI>lwHFn;XKrP1+A53}OG7)g(C8kdy?M6l`Dlr|P%0rKX7mn-8sTTw*ibCbf=Hlhfy)m@>T$NARt~gVf z?b_%@2b-sgQE@0Z;y9MbL)6cfJdiQDvl|gS66&Z{qwpYhz91<~$e?7?`9XqV!R6zA ze7JMLvtzek@$Z8;mCPKjL9mZeSw?SvE#c-MH(zO-MD+_mKsSYJq{WwICOzCki9|0%EyQ6mp?7Y&{@{^#ibalT@ zo{_UGEe;a3_E3D%Y|qcWd1S*G?4R6FM>p*EtP{ZNz}S#akkQu}C2U>&d7gb@t(C70 z*apFTOijzxS{GJvcx|_$mU%hswW1e?(i2DJRcAkDix;1$*43^-Im#*`lL6gAye-6SPCDTg>z%s2`qtLf{Mg!o=oxI12Glbi(gE7}Bh zZ**Tf5O!9PAzwNJ``TK0qyE8Gi*RjJp;p!)ubP6w@;m#V+07eZ=SR5t%?r_&d;YWp z7PL5mH@mofOUo`GblgKe`t?@b^+2^>%agU*C(F0XbUrKj{TzIDS-bdrf|G{dGvnx6e-hLS zrDX@?ABUxlzr&L3BdFX>Gt&bWCSY}X^1}Bfuq!guZt!Lje1XM%(qp8Rjq6FsA2}mT zaY7%ora(eL5dH9H2aZO)dCgoH|B`Us+pEU6rk6h-tM$dM$H ztK)WmHJh%LWlG@L4AF&PEKCx4oscS!#zd-mzSg%-H$->xWXYrT;l4Yl6Tv#C#Vc{C zpcjK!GCI}GC*cU}(W~%^^qXxiIUi0ILol{MMpD_{Mbbk7NC&TdqZD)F%mASpj*~&A z9_7ThqFBa({EdfMZL_JeUS7=c?Vg%rN>{U%B8y9R)oSGw{W4Pg=hZb&=6zmXoGX6X zeC12)Tr$joY5+r`p}NeoNO=NS&>c-zpu};Ah9~jE?CL3J zsT`{5BiJ}*zA>eiM^k7RMr5?uGsrM`dD4|5M5wX;-fLkvlJ580!iLM_f|z!evZVn< z(t6T$E!dVbig}S6o5Y_dKb>oJ}7e+;Ab2n@H zhP+OCt$nw#Ugs6xc~cwGB18z6%&U(Fr_y8Pmc0dh_j`%?5y6CGX5r)!5nsVZV=u?G zOvAFk$8`vrBE-tV5_4Z~V4Xx4)PAxT9`#`i+>8a#mlRUnZdt_y!v z>x0r##ypBR*brv{D#^ktD2H}s10roLid5G!L21=t%a8rf_3%PuWNuBa3-a(w-Wyhdx znS!(li=7Ehv0PbW0}Ww5I@e1D0=ALNyxhBRjki!bCFRZ^>YCzIDf-1svkI3M9!6aIJ*zw1kG zpEEom&hZb$WtU3O`PX-+VDbX{-U=(y$L*2LH9i6XjN7>DAMFTyH1KJCvQXiuqN#yI zY3AQ;_G}I1%LL=^fP~>AxDQx<830OS5L2v82L)b#Cjmod7bpB1xcS1R zc#=3;n!j)qYRx5F?7i|f(SgO_9vOYiJ+@((2`%cMCOCkgI=>(gJAn@i~_)}xmwAwKn?b8=6@GaKU#4pPYd zR7>9HNq2jy(_@qQnlh(#M#rhssL5&6mY8TZsHF$GF_vNs0Z+_WZWCk0dFzb)`|xE<(NFea(_$l%E~ zSe|EipX=G+7mhEUhI=at0PCtbV{<{%&mcPk2mMWM%ZMn zj^Gn=>K`}zq7a_GHzAF0UL`TQkVF*z91p69H) zXgrz9okzxZ5km{#h080P(P{Rad{?-lQ2i#@$4>V8!RqS23RGB&)pv!Ok!I>aMfMNo zO@764#g@9`inMm#x+5Vp=aza;#fE^EhI5K+Z+K&(VpCd6Q?6ojaZ7WxVoO6yOS@ug zZ%gYP#kTR5wmHQcPg`!RY+eHX6U6u*CER~Nj8TO5PE1SXdC9!9 zW-Ogw&9ky!P1-C6cOvtf`4^nQMZmtreX5IX3cx%4HFTx_ciByI_n`;Zk0(RK75@b> zM*TJv?rwh6xEg2iKd$$tZ~hBkl*s+Fr){y=hb_Cg-+N>EX5j1U1gpOG7q?;>r(e9+ zWXo1+5YY6f3Ek6H~YV=-7npDj;b8!4(zKCy>igz*V&+Zu8|f> zJMT;8$@X`rera(YG4N^+6kvF;PA7$QcsS%Zv)nqK)BRD0gk~eB*E{`%_it{N;9mB$ zzKF8jjdWUEs`id0v`NR-8)r0;6B`zw~r%)*QtsTcldCmqF~aZ~^1yid=;v zA_J|IU|XuDzl{@ak;!sBU>aTIGlX z0SOfDOTwKL|JZ?49-0gJi08hsXK({_dj?Ny)3Xh+2@@kr@I}X(^%BNH{=8V@Da3Mh z`|t(n%m@4+w_JSui#qw0Rc>5A8(!FB*ddqG5r{dH5 z`d?|vvj+DMU-{BH&%iWz%{&2cA&2iBu=UTeEN{4EBxdJqt8K;8n*!C+`h^U&R9efw zsaj8K@&wb)@mNt)FPouj;ot28(+M#|2K3r&?r2@yu7|+vmTGl=Q^w#{d+9gz@^j_D zkOw1mY`o3>J&;Z$VU=y4s9B}P-Gjm8p2}MxwZpUMi!BbaS-oA2es3niTGzf^R#fpG z5yq_q>2E#d^Rx~!g?m{0$a*ke!0fvS23VAHE7ScU65sv_IxV`lSzK>en17fHVtO^n zF$GDK4}J{x^CCNeosE?@bcQ+3^b17UcX3Ygll9NrI-RN*PI zBH37A>U(e%;`Q9;l@*Fnk2z^eg;a!X_nFmxO=&0I3=|>V`!mhHKMC9h`WwqL8dop~ z`E77`lg~Xzpr%kYrW2GEB1%J#DoOs%5+D<&cwr^#cfNCHa6CTn(9uUj?B-QgwN2HT`f0`GuX(P61sLECkMy(#o zZ6ak}#}t@60}4FVyZFeF#LMk=3G8|}y(m`5|0Xv4y!IV+(U*!v`{NMTFrK?RX{tvX z73~m`a1%6n+Ao$v>35P~4@&?y;R};{!EFPIm(#of(MU0I(0TI#eWL}_wJx8k=O|og zu5fR@yl2Cii_d;*z86_w+!N)NWYZa{E+Kj2Tsk3vXIpcLRwCLyT+q|mU z2BtdGT8is)FEtr|4+`#WDQTTIssF1k<=k!Q)PCV+n+N#psYy%e?rN>(SiASG-J4Gb zM>w$(%7;ap`e|g4EUUq z+vFGPiz&$ph+KNgA?sD->75awIeMD*%qq|2oqIT*&U7>DSD1>OQF+_WOqc(V-E?LL zTE7-q-Wk`K>&%Uwd3|tiXM(`PKF+gVlM>yXG`H=_FPT}B)7zaQ=5`e}TCXdf-ko-x z>niS>S^wAd9?ySK!abXLbL7_U{%m+|cjbR5;pV!lf6lx;&c+x0bG^rDvtcOuiG z7YY9Hx6&MWnEhk<_z&+4^NLo?9*A+=ay!V}HBO^A-MB%^<6R+P1k-r@d*e^35Kw>I zqsGw8Mwb_b&bLlI0ti|+xcM^eUWz=8FZ#x6cm(^MUV7S>sMT0x z6Bcm#)>6i&$euczU@R0O-7L><`3+i`+q38%BTzX!tZ`#=wD0W>0~1R7dFfwvaJ z>PZn@?BMYh8_|e8upRn024haIRnVvZC zE%~}BteB1{X2K%bY+xodkDjboiqvF*?Y3ZaB5(i=G!r?6@sPuGuzYwbp+6{_6rlh| zy{|>cnIn(w03j^yNG7PQ0LkWa5O9DA9zxy^B4>{$(TKq}|>uOJNdKd$Kb^&BU30D|~XWK)RsA=~7!1*8`1B9~10EzJA%-(o9 z5yDFW^Mb$zxCF&v_^Sy(Iy_s{3%Eo@0Cd@M&mP}zkj()$H z+>b+*d%?me@yR4qn=dSay_m-#DM7(kN-@z*nDPaT@4~fVZ3@(l0z<^FFyR5=DZ(zG zAt_*{6f>&*4=N~`j(`LQzjpx%P{FHLBbsrC-ZX;!;Hc$i2@-f%vR6bs1!=_qtk|er z5}d~5a>8YH?Nd@T8Jy8<+Kv|x&AcK-fC&o+3k4P&*n$f8K^^21?O9-g1&8JqESXd& zBpXqXUU-HA?_zS966NyQ)eH4(p03FvpV)5~0Cps5BlH zyvtFmlNQ!oByWxkV{*u{AQD~>SNm+yEr^^Kbt)M13o5&~I36e$(Md4i8(Wk^amyiFal2l*1x^4zlLn#1oyP}fJVD+EDQ8D-Iw zYdvzc`8%YRGK}>Ur&1Y)#)2N(DxZ9I{d!umJhj%I0$Z89=F9<)rYp}fV8;rQ?3kQF zZZ&MotRb61P3I6xud{w-UI9lPV{ins!Ch!Tr6r<%fy-(OrW-1*LZw0Qw(dk#3WqjvcUSFRJC0oao{W~ixAy4JQ=IrUQikYsvZQ`OpF{>D$H&l>1 z1z%;5;dCV&>Rm`s1+FYk1h_^(rYyq2MpQ&SOL<8n#b^umehDP_rR!=`Vd?@@?QEGN z8KO#rWYH3Y+04!zu+gn^2bQ_qnHouD`(5}4n-CmB}%z%rei z3C*V*<+z3Dq98pfV6;MFIfZkD*cr>K?rxR zEI&|xaT>}AUjcbM1I6e(j65u!0;@xJ zD@bzsZdo1dk5C$E2pvQWH+74a{}+hQKiw`Jl*xwpum$MYohPk?|EU0dyM%EKR}?HZ z)hRPoAm>o)US{vALxJ@DDgUpqUN)-+802nX)R-42dQA5y*!v&M;rR{x4*|N;vkuRD zWO1cl<;CuRN4ZtIdE(}cY*=rVRY`++oyL<*ll##f|5EmRQo7mxj~8!Q>u7%j>tD*A z&|*d3u~Ln*JV-4?>uIWN7LQF_&yz8{-pk)VZjj8q@1{RdW|luAGLmrW$Txdub1tK zc9hY9>T4b=yNvfy9dU`RPc$+Q7!X$mk=S9_T- zT0u}KT($Icu`pQ{5;wNXF+=_^%pxo}2}xPE&d^w9L39@a=Q&c)s+ka$&grBfKpBaX z;MNffk$eFyIx3+nNyM^*9Y`>TfggDShXja*;1qLz2tQEx+8UkuaiW+YQn)H&BW3SK z5ODqu76^L0E(va~rxU+7DFh|d4WmUcSz8D;M z;hl{#8KB8)5s*(ZfT9zF7n^78C;3_nKHkicq$_ zJyVb}r_aHQe{oj<&)sCwPpQ9ssNMHPea!4GLIxtdj@=?$IIJpf-6z3sd@pldd7DvV zXJU|^Ul!t85Q0m1ZNsUw_Qgt<22aVPF1ERn3T8UhM$AszKKa-OiNv>rKm7YnM))E& zdwN};I`7-*QU3mr=<&U>cf7M(gVkC9gQ{c=vsHr#zyCPsIrM1LJ`jAV zJ^bi#c(Q-@A28jxY77l&jGg*`K$Sn~U z5^9X>cbc^~LW{Iv;xsoBKd$Br0Xx9Sm%{~7LwVu@1h=k+4q5>pk+{1MW*zdq2yrh+ic2Nw zowQH5V?MH^{GMd42}CSi$=H#^J%}^)VPk)uYw->7GvMm2ux6epT|M|KPBJF_>W{+P zWgreg309K!47w5j{XQ-LH6pQ}_9(|J%$tY4%WdFCO3wV)1UiX3v$CL>d^4f$%2kki z_Hp~pGct7`?DWZcuD&8zKn|L*W6Env!f`w#f$>RfTri7cflEK{){d} zEk%h&hiWCYaNRkAHEKSiU#V_^*jyzlH1)1`iCx?9b-`jrq#rFf8+F|%^#<5Vu>P=o}(+O~! z&1jd)&>%lv*DlLf7^PDA{7vWi^#cLYm;0v~V@f7YAAHKR7rVEh4uu}~y=5;y9nVec z*4b7b@@sWr?*AC=xX8bBM(^yY0n*dni?U&1yO`&$bB6&1d$?+r1~EGyfCi8b0H^H ze@%*GaZ-P-Ge0$cP4w-~gu%HBl!(eTMYaH4uc0e1QjAme@*}$!bp*6|C5gfia zGa4zy7S*u3-E+Abm2Z{Vu-@1?v6+8$yT@KG&L!|@a=OrRYB$P+$+kV|N7^<_^-j%R z4)|7g$mX3T8`fJo_b*nB?d4yOs602D%xpI8D}Ft0vc1{jGP~)_hV{~OZ?^rzs#*TU zhV|ZTkDh(+$%geZczWqqZ9e#j?k!B(_I8#0Z-n*k^hyqI9}m%IvL%xfC+@tZRJgAd zui*yLZO?tVMjcvLys~@$XXTfyZud0+J}{jlb+K4)@D1wjzylQXYwceA8-(EC!;Dw#CbYtlz+o-k@k2l}tOcoxT`_WtAu~NUl z3Ho7|Y2SA2gC3{Fb1**o=F4NBB^LEw{l3SD$@3U4?RRa~q8LTAiKsrOw8Oblq8nk>%=e zD<$?1=0_*}j5i5fp-h=Q=RK8;5DlpOxS%#ufRcBBEkyK=xRk^m{ODGHCaCFr;y3G^ z;Mb5Wqib?AF@3BBzohHNV)-A<-E{6&{_Y)Z+PG%pF3uOwKoarGzZzAZ^rC4=fQA;!@cXtTWRfI}%B9yCmp}+`zBGh>;C9hKQkMh%1=uRnKxZKrt{E&%i)1 zk`)5199}6bq0r?Z(GC;~uq*ElH(l(HEE*nJqyvr`RjuC~w@Ct0 z0;fQ)g1a^zH(x6-DLhkG!$a4HZ?M2>8^L{+f0` zk(JE2tpdL`khOHpHd$79r~7o&e|QP5)7-g+aN9y+bd$F zHHRre4Pvwn0&iS^ka;BQxWkA|af)5)weSMz=^EpcPa0r&)&<|?s+XWkOvqa>-LgoL-cK9 zJ3w>Gi~!jrSFMp!^smQKg`yNDj@Oj5N+r^`<}(&Bf48&{ zAK55DdB(vxqhZKnmH}Jf_{5O!diqKr&yc*?gAitlt~*M`gn8fq*F)OK)CFz!NRCj{ z2|t8QJr)`vaFsa16+oX*3blA->*%QGeJMG0YjoD&hk99l<&7pL$<*%jO+NpaF_{iu zXGbS?wd1kg0_6=U_X!rQT02)Xpk#hl=uy^Uk7<*lQm$plRfk4X>%2o{isezrfg^SOnQMC$2HvLtTRg`VPmk)*gk?FiP+vXijb}QZ}>@4RFvp%ZF z*GO{iX{wqIbhv-2y|nixy*|^)$Le&`zPzufC^9rG`aSy_PR3 zGzOnjYwgrPK*Fb!H5DBjrvwKVs@kLK@4tBew`Y*`=Tp>eDNo&^XM;~>+hdlx&B-xpI-dv9e~l1z~Kt|`%6&f*X<6{S3MSpZ-)W?d;SX8-3zQFG|X)p4*G~+ zMZSGDf=#27wSV*S9Cl@-%FBX{Fu9b%3(@~&%)gygW9P#!ohGdQe_+f%%PxF=J*4FJ z(Eb++pFGira5uqNi9Pyvic04J&#MxsHxV5ff6khV?JcrvpsbSF zP+z^hCFb$o9y|R|9}Urk<+O;t+aKS<(w4_w%l+(lkaI4i;MVgG0TF`LfZe=Wqe z|LEd)@!`ysJ+r6B*Z*_<@tb5St;SjCa9McZzECTv!x>veyu>|uJCXa~gJTSI%!D)!S0pfGIT*ET^^ z&2KT|Z9p1VKyT!I8@Zp=)%rhvFuQV+8^Vso(Y7qKpMo)zQg`cEX1S&5utaXLWYZ#r6=2^JO7I$sTrWLE!c8_b+jIi7;nsX$ zhSxTFvELh`c))eq`iPOh7OD}5FPE{Lz!h+pJS*~=*O@N#Jq!Ley0lO(zir56X%0w! zJ|fo{mu+GG81}ZqTYQqMABZm)L5_$O*yu`8FIiaVmtV@TI7923=VSrP&k}|1)(zK!nijm+VUK6*XqunVsP^%BP~ml>2fBa zx@U}1IiqB?0p!~l#rx%Izb|!V@g8us=XDky^1`UNE6TRse_-L4mtVwB^_j>!15R_+ z(~_(cK4frRSQB)6C)Mg?`xl0wa{!8`8p_Xj`;i7~_T;QD-e#t4~e1#U@>Q(%iS;1$!m=@Uj>c#%R`=d1 z-9{EZmW=wtJBD_#0}&daIj;;cvv@l24NLN!bmXZ&XdxNM>tnMB2Q1TYRf2O=zh9*C zKANjum|q=_i2O(+nMLlY@hix3bnNhaw~tX5@PZHMPf7m$h7Cv5R8Q`h-n5?Yz|t6i zXb=Hh`cAp9-yllP?%BDX?eSw!n_ys)Fz`G=%9xxClMcZ0QG-`K(ksStS8e@PVScpER~w^$4c z8f`9GxE}hGBV3G2r+%M6ydqEQ3^{-Vx6N@jkwu zI${qwCJ84;@jQAQ86NQ9ud=sGCRWBVZQ^83@I8Iegu?RLk?Y8ub2c-1K8p(%yXD#u zirtGrSBMq&nGtFupVsB48wwZOBzpU|Hy>DRb zVn_T7Jx{gb=sP<()(MAWUjF{|6Tc_xd1c?q>n^na9EU2M{Pu!Zw#v?MYVcME&U*C@ zBU<)CYk2D7GXIvljx6FSJ-z;NVR-zG%(RYW=*e5J1iE*|RCCp`1C?KkJlYvQGN+as z-S&FHa%c3Pm_d;g(w!&va*sSn#kg}#PGfhN%Qgr;ChT{cXF;|JPy$|BvdA|NFs9rD*511iz636hd#8;l6XwSj zChdU;J=Z)wo;$p^{P^6Dnf5zB>c6pUHcBtjS(&hKp2q!pUV8+N^&_@Kb);dv^VC<>I|8kI>XW_u2KR zpT{j%x34AZFYoQ6QzuotFKC~xT~HQ`l{@t}z)Ev({Y}F_rAhl&oxs|K=?}Z*lHiO2 zy8A|`+|l`$TnH=l?F}o5!ADicKh~KgOd4O0d(?OQd+QaQ_oq9KKASif+2Q-)U69M* z;>pS%Jsp4EhnejyuZl+ZJ*c`KS+e)yOj-2J&mP$c`+6&1RdVa{l7a8?*9GxVE^yl{{Fuq!BAHc zEQSOxB_aDsTni+g9THk738RyQbxjh8N%{v8+@B=2kaTb-2`5CB(jm*ZlI3E^@}*?O zeli;atjdN23ni=TBx|}RABjoUDNR1wpRB)-e0(RFAe3ULlfs4so5rM=m!??ur&v$M zu}Nt4Oqd;0T|Nm#^TAYvW9q$N4)UmS0#YFf)r12a&_EgR4 zKa3a@UI9vzZ~=tTU^Ee$7mlH`GCZh``JOd#w*S?`5i4g1mB%BLJEv z0fHt|;Bt2AUg_Dl7P6{hGD6IevtCg4sy~m2q%%3J=p5oy;7mH^&^ovK7WgziJ19R@ zlM{8t0qO=f62U`r`k@j;P&pB_Ap~U8b4yB*9i?pHY-Th8*-wPZgHWc7>^xQ$K;f{W zAmxTR3#2bSU&yQ=Ws8JEv)P+zf(`FJ0u>2j$28yqQ|WX(gclDn!NbK7C!LvGC(ze2 zyz-|?mCQiqQQ?>h0!1Q_BErgf)>B{;p6x_AbS6F5BO~L`aC)&9EPx337{M%sp}{Qf z6O8N(uMBzKJlX=sY!CPd&M7bas>IKHcr)VYF4zcNZ0dzsTi|l1g6)`va__RWVhj8j zz-SD|2_}aG9pa3K3%G&mSx`+1@&tRAjsp$^7h$iWINge9K@eSh$t_ap4mpO5Jr1Gxkc*Ha*Oi~$-IRkWK}Ld3>a&0VFN`e( zT;T>B42O~l$gq7PrxU)wlL_l6< zAh!h*FDrLPgJIKG4>JqdLTJe+SNk$h9(-Vcag|wzP$h6ss0eoMWl95lmP2% zc0V%}1?-nnyhIv&jy4>Hqnz2{3@^@L z>UE{<%zh@|fCKy)8TBrlf4jh;`yjoc zpvd#+3h^!2@kQ94d7R5Bq}mjaeKh|xD9xP$4l*obhdx4L>KotY^?SiIncx@_hK8#O zrbDH1fV>yPkX6^%2W7`M2wT8;UBg3aM+iiSCr~4%-OJ(@NL?=oiB;Mg&3Pvn zQA;ekB6?XF*=Hy^kgqpTcsa=v-RMn$rA=e9<vslY$(d><2hx8Tbmlo!$44x zEr2{Cv$51Pv324Pv5bAQ7FH z_(igM1FXczn7~5Y+~TwlC~-Q3H<-&E4Rvq=>Ep{}@z6>*>M)Mu8mXKbXj;C>O{bJa zy<_)n?FsnoDWwx&E(GRxYydkj1cKAq*|6~TCwh1nD}as%GMf<6A7Z19g5`KKGpL9s zM{E2okcp&{^wQSGx7-)JU_OLgwk|#W66Vt40NtxDnm$0AXp=>@nuxTz#$nc){!5l3 z3(^iEfCSlD3g$mTB>Dlyog_G)qWdJh#wZN{3&opv)|#YaG!70;cD^1-7nVK8z8vrw zN|5IkF?Q=(A2S1d2P@rp?S~;S34<@)-G^qc1E4X@g{DI%PY|vwRk~6)?COZuEmI3G z)i5*mMEFamwKnHkkap94?;f9h)*X=G>8{A@{q#ogL-rGScB4sqxOY$V`p!SUdlKau za;bpYbldTdA}my(MmA|rS#kvxB}X$YR;qB8} zi+c?gkw3=%uXBq95cOYjqoVJ%MOgwWcCZ6-#zB;tku;RFVdW0J_Ffi7C1BJ%uWme7 z)QBv$+bN?Gw2Ex{@8=P|En=ng|7>^uCor;P)$p*++=+)B7-64B5G&-WEF=9Nx4N?D z7UlF77n=LMOmVB;_s_cV_u1zWQSwWDD$DG-#WURVTfpY#3nhWW?srHWM&I|G*>ej5 zqRwQdf7@m(@Z$6Z(~Cvxso)Yf2hP;{Q&k@*s+;d6ywAKXm zgXdk<<-)M=Cx;F0I`7#wWj#H7swMmF(8s|j!{D)C@JW^52LhMp;y6xjw8b2ro#009 zzs%se^>5iT@uki0Fe+R2Olz376m27##yil$>ufr) zEFZ9;5M(*w{S-4ro?gaFO}tj-;$%CE#X$}zY2{UTNcV4uTp*+n83G)gHS=OkF*xV} zlO}Bl|HT+1OSGbinn`8*tQ!Ffi#1vkTw8aWuyi(G_2pan9W1NTRcKG*YLg$lSB!{t zAaDTY-l>-QGu|^a!2RgG(oO6ZLqIDw8FjhpsM<)$BtIHwbxLTT?R~b>c}6R6FmN*j zU!;(;EYp~@O{9d7RJ!T_-H#}EYi`>TY%?=_3g^2tV!}3^zv5C=xa0*-QM`d?HmG}T zr7CF&KQaPe-YL#j_9w39l*WuVG;!62&aWgRW=}CB9*-HO;v8boVFvvyW|F|BqZ*q) z?-|6_KFiBmg5_~+?em$2A0K#A)>4$5h`H>5%Qs1xEHwq})}fAp$*Us?r{N>x@SA^Q zjT2VF4T1~L9DHVF7d_`42=<3d1@TJ9dn>7QA6yj+Of|ghu3A5dOIFM^%xtn0649h6 z-)%R~(vC{|6>ezPj_yjp_$p`OYJ3Qrihn~Qs@$ZL_fz?prxw(Mc_(xoIAJO6qOCJo zZAUppXE%TMYB%ZQjWuMq&}R*su!QwWPu8JH9)eEi@PO9r)SH#B0wiPA+cJYecRm`l zWXY>iapHkpwAv)JOSQ)?n!7`#)$)9WGw24{D|Ax6>BHdemz$Z-`(A2$ujC8Rt(Jxb zf~0MTX!)4eqp2P-j5popI&Zm^mHf{|73!leB#s?PH+Z>gd-07i!uD&LVAt9}i@0Uf zX@|m;ASu-F6v(T-#TAUqZ=B=yb{MZqEsb*K3ovN~2@ny$IU?-srS`b>ffYN;Uh?6s ziF2^v(_r@BBp27}Sp|lPqL3q~a@HX5qLBHM{WLFb1=(u?RSr{?Gb}(bl6Bysp@*U4 zvj#Tr6eT22Qv2(8_|)^PsB7dL)h=g{Oi{>HL;0e)%)V5v8*9Pt)F)yjQZhcpK=z@C z`P+p;KJO-`ysQ#QpmLS7$TbaxB9q`K3e12lB{(cnFc)(~K`~S@XgkjkR;zVLkLK-R zgkMS}PYyu1lF)#piQ;h_)Wb11@Yt!O4+5?Qdqi)O`l)}U(6FD)Daeqs(#uibdtm|u zj;lfd-MOVtth#c6nJgr{W^WhdIbJ$&P*Cdu$B=q@sWCP6 z=`a;Hupo&937FWzGi~gQ1(%J#??WF^xXo7B^A-;K(V_PPdCL#sv z9B~7pFQ376u@ujZQ7pn58><@Te|1(HO-dO-ogrPbX;LVt3{`X(A0C5~(VPwqRNsm&k`NlZ8Win6J0W!ruA$&JzxMy8Nw7Xxr+EY~{ zr~xe_h4{qUq7KAIM4;WVocZNEfPf+ad1nju{jrywXi%8}`;a!+a|U{O=bBjKlzmA* z_QXYb^9L!!lzP(;TYq^1FQrEvr+ed~0ot(M65ec>_ZcwR;ZWEu(4511AuL)ET|<)W zn|ua<;qwu9Tq860EnBfBK_h*RqB+eY&L(7ZipCHx?9L$WMDe>aOV;SZ#n?KOwyR?g zttd+YYfx^^WvFvf$mtIM5mn<=1i<%&tK!2)IS%2aNc)SP^iOL;4K)^rFM##FJx#g2 z%3l#{Q$X2PFTAV2`^jnr<<-t`Im{_wO$I_;Cv-~HxL}`?4~dn+m9j>1EVkU0L;1Nh z0wngB_|rOV*aH#`g6t+f9c<*&U8aLqaPCaMKmSTl6gCE$+|K-N?<_2S!}vxP8!k#*%P^R+E{^rhUOF$#QmJ#2@q8`E0VV;`Zwnc3|XAne^CR z|IOSRZ6o2O(y}*sdMgcn=R$hQ#YfnIk<~A`0fN-U8>&CL*mh@|_x)_U^A9^h+y4u8 z=kvWiYPsif^eSGnZ(qg@Y|rIgu3TH)w>8suocj_@_kAtDA0-`d{Hx_?{PRST@mzG` z*YMBoZ;yV~?Y}a2vF38chJp5AZ&L0zL&d5ko4{X>TDdb?PT$^inE3IeqxyU3`P=WU zCXW7p+V1?ne{L~(r6mRBL4^K|;LIGsG%^2Sy*sl2_Kn3j2^HYw;Yoo7(_?4^Bpr=o zPaO=N~Fl-<@SeObvLq%kkz}RiS_!e}QrD229Q?x@?5Rm1J zwCVyFyUr)Elp?9@cR>8gkD*g^FM?2XCOCCpC`Boc$nHsH(Exx?t)L^CDM(d1gc6>9 zwGUtu-_5A7E&{SW6`sMsAW~8NTaf=o)>(!%-T!@m8yk#Kqf20PN(%^xG$TbyN z%p05@>yJn7S4cvpsvg6}7TC;P{ec%1-!S5w0Lh#+V|&k=Sb0Esac@H#d% zAT}P)+FtswnhmfWoEQ%a%y4i@QBtgQ6k3sh#5XwtUvB?ekw6#)&5?;!vmp*Jg;iq- zDB(bBQ{xnG|7h>HwJU`u_-q7L-l2>tV22EaOXS-Xgrve8@zkA4$m`AC~Wg};d>y6^lJp$w0z z#)#bm1C`P7XdD6KDhEEqad+1rUs0*Dnh?Yn$1DnN#zzzt1w;Om-T;tDAVBsuS+OJ8 zmshVP<^b(RfK)@kb2S2kFQnv8bCaFOxKSXURgeMVwUG=+v4}VZO~8gFj6-Y3coX#z zr`PWIk!qL)%|VgucRDABA|D5A;^ zFkLFp5y{<*PE;5q=yxuTYmdaIG=kw#0j2=p`73?CxDG6#4L`IDUY^1mXV^iNgDJNj zqlzyndl69KoKxYt__ARkQdb`uAqrjn!YK?SdF~zg<^(c*<!h_QnQ^aV%qV71d+XH3?dum!3f4jEf{viUtJL% zYUUMEh{ zZed!Ee+0U|8P|Z(gw=%CME!hiXqw+n(-^%Ci2x8Aq(1HG02z%^y$Oe6Tp`9E5*kL! z6F=l=WCN8IiPCaRgnfy`0y8OBLD*gYyV>Np@93Zx8wU1mdkUy;BAPK;0gSmC23rG%5BvGO*= z27>;z3rQjf@ZF-fUN*$|4h8EgAYRyWjw|&l;>Gv>-P`vs)QnPidKZl#U_(Hx;H9r) zNiyR=Qlki2l7MCee_bYCvHM4*O|v1DL4aJ~`X>4fRz*PhqMDp)Vw~?#FB<!Ga$m%&2voX(ETP@1CItJIJE(aV8nD#WB5<4l`$Bch1pi;- z!z_6F;(uef3vCg%s||j8k&;!i3e7$gL(DFmi1aB@i@~=PWL7nCen??d@+37Y`hV?< z|K>IXAnVKjWncWCjp6^o@c-LB@NY}OKN$Ys8^idPg7$yy1OK)Z{JSyyZ%Y9QtIj|6 zfmrJCukDR*);|aZ9TH#}njJDT_~rUYvtQc-iUgmU=p>kIVRJQ@g%258-DYY?-YEQ$ zeSUzcyQKAg{Oe-%3wJ>21({6yC^pfS`Ugo5%5$tg@Qb>ZwuMY>LCfXrR7m&b(Q1Ff z4aI}do}VW>)3u+4zXSx0r5+CRBMSfizP|dg-#&f+<;|bJ5a=rEV$?|k=yNLz5e}0Y zS&bm!aVD~h(&@0YEy+~Zcj$$oC|cE7|!;9Qg4Ft)!5^5Qk*;;ZUMDw^->D ztF?_PJDIJ>p{%>o*UzU?A*7o2si94!_CPJEPOkK@Ud~N9eR3X$SEi2Do3AZj>~6lX ziRRzRvVZNeg+C3|TRHCkYz%w9=iknIHt({X@4r?3&&KfXb|H#TV5caO&UL3amZt{4 zF)X#WQ<|zSuv?aC;<{U&<%r)H&U>-9TUit>uvb;~+I6qGs-kAErmk&ouNM9OMqt0L zb>4NqzGDl&G2C;px8H~%6g)r=)43fqjqubSG*3wFAGBcA1rJ;2OxzCNE;!a6wk^NF zZw#+S3m$cBymmY4+^MKN>N;rKKkCN47yQw4Ht+VM_iC&5N8j&@{U7}RA|V_GOz(~x zfb!Pi21%t4@EgM#LdU~2kKB*nF*wy7zrW>oaQp!gBXlyt^~U{Vl&`YxWK5|2;AC9% zgV5=O6HBC!RfRj(d{#=D!s?q43fA0Y*t75@a&_$#_jVtBmBm2ahZMn z9j*6BTLXT`sf$2jOBBuuk?NIt4QR18@m5>CD;`_zKUseVJN{Mhaws{)#;4O%ZnEIh54Mt^; z#|5Mc@9;hzpnvcGAe!5M#Y#~C;;cW+)90tJ$O5^g6fF%2MuUFxlq*M&#Bt3|P%&I7 zbLgy-eJ!^^@pdW!a~{S3KtG@mv}OK8Oy7U%mQa+UiqW5lDd^COz#oKZ_i5%3R1wbV zv`p|QV7f9jVi-Un$v(jSTak`CKn3^$UAdG7qDNmT!fpa%;;H0UNrEhtfISam$bwfD zKYUz)E{a0kCW?T_4om)=;|L0UTWTsv6`Z(!Bp;0;DNl9YAuOg#*L#3~$6JY5$Gb;B z6_Lz%g(2ENQ4M<(5%P!vN$wo0Skl-M80@IWUAIbR%b)~2 z5>+})Q>HVIfUtZ_y<@hD28iqAZ)%0<7)TC53(wRA;!}bAJ;gMunKqh6W+q7n+k$T+JL#b0mMk70Rj!hB`P7A=;$0^ z;^A<)vi4v!f8T(=*P#8pG9l-VJ8_6_YZf=jT`@@Eh$dJ>G7Ny+LC-owhw#N` z>K?A)l&}3G*=H5IUm;5XGFn7|fdipgAE`P5 zHAc*7eXrj0oUOgon6PoqFaxpPOf10AmMOyNf#PO+6 z2!gv;gKGEQDUy)_{cwVDpS666uD&2(mRSS5 zVl~w_E~~_5rPiJf#l%Lb!erW_1I#NJ4B@S{>|)4@$RD$G3U?s4%g6vJq2k-b|y!2SC&XRR_HWM>Er`R!}~UB0~APm6?J< zWTHsCpun_v`M7!6$tQDaqH}nAh;q3o^v?XJoO)L474&u_We+>0WKZT|$FAuo_k59={ua{&cCBh5P&*5ieY zIr8=R8(3w-gZg(a!Y6Jq>UT4p^iFe@8aV28Wa)WKK zgy8a*EzrG)%5)V`h7ZUR+Gw63pL-GLuC_^cU^?OoBT2ZiqQ!?X6MBDABGNE!1T}%_ z0>cVqkOK@kYtx3N!{L#AQI8hp=G$& zUuMNW5t&W%z$r88t&?dxpOag@`dc}DZuGZbU90`jCc{A}bZ^+;PYe)T42gk*%{FTY>_8;FMPaB2xgNhCoye9dr$>naf zT0wl@(i+ht5-pyv;4ezUY9q?`g>E_t`0m^L+O4 z)boz^=|(1uOioLp+1BBDDIquf}v%5n$cJ3AF37aTf8&#BC- zk{-Ge=vL%aES6Lj>2+;JF^Ar`?1|*mxb8>v0+@EQCDwnIJNCCe-$#RHLDgmAR#)~V zO8`NkCM?LQPQ1IT#y!3{8>Wk%d9lCLnihRs)41k5Uf;fxL+EKgKN#;^u%(cD)KgS1 zcvLk$xG&WEJJivud*l7m4-DU*+`8^Km=10b%&4>T_J?D)$PkU3yk{Skm!QZy0*geE zwoSbWu>n?syFqkeLELz((578Ysu19->cvKw#p&M zL!i_xDB)49C5hxlB&_o0Q2O>uBJ!)%aC*I~wP@bttMz#4sjKfV4PD%eG#>erhgzAu ze!2+Gr+mL%WO3ZNW1H%Ey;Jq3;Ci>Fed>C@_5=Q#5k2iGw+{-@(`T?+*8BCNC?XlF z^+}0^Z}tsEt4(zRp>_ga)B>f(ttUoo(dP>ZKD`%TyncjSu09p{d-*-)!QY=-mDYc+ z*Qt&ET<;8d{n`F>pC*PSDz=%n%nHRAo>vup)4*8o>&Ct zMJhq5%EB4)SpS~1ziLzSaLgRTo}6Ve0~II&qmae0Me6ujbBYqsGm&id=$@fmc;5go7f`hJoXPC?N zIN_1e`YD!fxRgCfT{ZYowazOEb04*r-oXX8z9T=}U2IDB?`GKkP)=} z`>;y#&s{1Si1@G9R_4r)^gM{nyNK@&D6a?pce$nPK&2--HWtMTxWay1{9RhEHsl>GWRLiNh%UASrb^3TocZbBht>bNOHy@4)sLzRLdO0V(Y?3& z|L;<45V4Va`#*+oPVEAnY`#_yR$Rr9C$VLFs_6c|N&MZ}st2`tlYwvd=h4>VJoR@a zw#GW1?*Dt264$~>==2=x>7hOXggJg3@In!bn-GRwKxS zcWffzdd|g>3?^CZQDC}Aw$Sq^zV%qH*Rhmxd=;@Au{>Mz*1)UkswWAO^UmLs7JEy- zC(AZJwFWM&GJKKRTK+(uA`h$HNY|0#r%(U!d!!)aDT^OlrqRDd=Ls%P0p)+@wwTC& z%9U>S57F6$22A-qX|A4gP%FqT%fk~LZ=7dnR&i z-!4i0hv*($m|;q@0=f8$qh9<&bkVKOrHkI?0_ua#5-wG>{}LT({x z{X!>GJJtDE&@KfX%Q43Yi5sw-?h7>kO~wG~!^Pq&Y&-NMz&F?Jt zEiV>On25N1OzIqYF(O8_ z9YXHu4}4KY^BXrv&!&O^J!>~ z8RVQ~R_T-ruzh)paYN~!Ke!~Avp*>k+616y2LT6lK zqnlw|KNi!Rb6)3sZ{Or|{A`879X~m;TFY$7`L4zD2LE@07MEiW;{somKP9V+J<(bi zq>`$Sy)9@>zcifOM;jHMbP!CX{belY6FO^B$e3~5jFOPYSf;DPD$=iU=t(csR6Z-mw+{mBDR zD0^%myjgwBFGL;KZ`qFPF=T&_6g2w$LNE2PsW4MAzIV>unmnjuh{HrUu2x`;`d51v zUBMT2nAnCoc=w%maZ~!6JX>Zzh7U|rVxE2nMAW|)(r=8#ER9W8l>x+~Ubf9yA9S|9 z%l>@-^;NS=bk= zGw)L3^ma!*ri;HEpTyS;alK_7I0ipzs_k^$(M#F;*#7>s0iQw>zq}p-zrZCE-8;CM zqL?YEIZw;z&2$XPolt2|0!Hf`DF^4yhC1RJ*(|MWDY~1!OSa{uPI^2n{Iwzx8b;!Z z1BK9IAUA}nHE;eL{8aBA7*Idx{^oSpJ|(NY*x=WGtn2eDy8GL2sS%Q4-Be$S&h_Ej z{yCq?)}n%5mz>7nS1cLWH-ed=Y!4-J zG(FV)e5+GTwTQ(ZN^!p%rVB1Ag+h;|cLFwe+599(zMjDPgSJi;wCVRN zeiYHi?`Yii?>s01$aM_-kki{(xBlAYTll+i>FarJILmvm<5}BNw(GCjIcHCOdX#<9 z5iB;Bnx1-C@Ya-7xKbGasA#&a*cIi;1H`ZH~Ce40^t&g;Iq){Iqp;*J9|1pHKSG_#B z^jZXhQs=in6(i(wYzAfwBpAgoBzQNyH-b zI&7u*JY<}GbsnW2=Kup{bRvm@dQn=4)0%jn_BtG#1X5h zz3B+cj-|}^Pw3zak3n#VAmQ4v@fD`? zY4jN|F(xY<0tX8$B!I;d1L;EVK%;86;z^tgr>+un_>vA7qPvlBKGchowWPAxXpm1d z;S6*&%W3^8vT7@k3K`{S97g>rdCxiFFe|kS8V`CHNF2+$;GZHQ6O4by1=~LVb>&eP z>wSG5e`udd>U_e0PHEmq_%~hI8Yz%t< zC6{J81n4agkVGUFzkHQWX9kbw%h;YzG2M3B%(8f+;f(l_L4BOTnGIJVW)mU~KJ(8c zI)0`T=cV`M=|;y(S)NpaT}NY=SCnC|U|%>EM#3*;;F|o2cAY^EooS7g7KWpy9=oq8 zfNzLhI3DjNeKiI6#k~pW419Q%$tvY-xbsG)^HCUo7MW7kp(zI?ad6z1>~9NM0sOuX zt1aB0XJ@&@;rJ-H|hc-$f31*-w;1FauRV z=GJt)@ft}By=&M#noG2n+drB>IFsPIlLL8391DQj#^&KF^PF4~rEWB{X&4?%6X(bB z<#+IL3}Qx%_-_s zi%dbqDa)2=GDV*#<_2@A>NPxz+nWQe}9qWL^%QDK{N^#mZjfx|nahn8_4a zB(zxK&s}a5U*U3HVa32^-c=qv7UyH`V|#5YZ(b2lQwgH1QoR|e@aW1YzWA00Vk0-9{!AcD{rbe7B&npacJEv@S%x$#BW@WDd z#NG&CMo-J~q`+$~Ybt(rxvj=k{k?7g{Xzq^8;O{!iRD~L;BTrRTKR&fcfE7$sf`K`I&Tf-nrt)S*df~}S%`4$#! zh=sSq#&7>JwaJWgL)_ZDgG$AIy;T}-6By^tUTya2Znw;BaNTcs5!7yx-aata9-LeM z%;;I-Aq^I;az1(P>oDoX7n3gulM5 zyRC#7U1ZUv64a%!lvQZa!nf2_D%TMv*exfRQRCL#L4s~v;z~hv_b@jPnRaV4_Z)Y1 z=_q$h)V6;hX_36@9%t_TF55Gm&>JP!`?==j*bPbBvS7nhE!TIs`W5Y7lvD3|P~X}< z*O6Squ3)q7Wgpou=v8k2b$9>orT)La`T@)RhQRJ)lE%~VYQ%>=CT0xjGKPEtV_|@y z2*M-=dR^={QsfOV9bgC!xH1F>;MxOWi|(-Ce&*mozPf&MDi|WMh2wWc*NcIpoI%Op zL6!-wcT0m!zXl)6x^gED+_^POUdN5C9nu*ey4T|*{<~gzc^DWxq@6yb?%s|}Y_z`^ zk~kPPpXfIW?>AiTGS(^6X&avGdgqweuP?-9o!D#ZUMdm&PAB-iV;;9#aG!@zDWm%P zZh;SudGBRT2A;cr@ariA6Mk@*_+Y;L?&l5j$g$i=q@`tGT~%z|yHIz|5&$MqzAw41 z0A({0BtNQKH$t8_I@3Lx!#ElU8`HHMz2iH|uQT@EZH#kwG`((2NoY)obi71x{D7|> zGDGy2iMY*jsBW1fwr;$8e7v2Zeu>#Gky?gN1B%kF3&){T& z<)m)Vq|L|#1UJFkJ-J#p@Uds=m*A9~&Xm%~1WFXTUDvdCfG@v1@U=e6SeDv}FP1Go6KDR^Vi8|4Op{Hy zI@2MFM7#2{Hx@G-gR^{=v((G)!8i4@RAe82B@D^@858gAlqa2$`if@j{V4pHO{MoE z@A5~0;2=xyEHb}ei;7s|&zxBO9ARD`AIsc;&ZjGjxf7om%fn%lkWbC~wd_em=7$Z2 zle1b>^B?5r*8{r%@^H%fdE3KJxV8B?($72N?N5{D^>jbUlzd*D_#E=M?dd(J%b$9; zd$azNERl!P(YNa@au;0T3lBUv)9%e==+>*deaT9iOQ~l`>irV+^~>OOb5Y30?5`XK z9*d$$i(i8pYH!a4vJlgeEg9Wj>JO}c+xyA$_9qBxiM?dWc5-O?gFAJ7zX?C(Q?namBxyRR~r2eIci{JmueGMs(%O_gKmWu_n+F|^(a^6$-m01#5}E^R66Qk_)13>x^X*sx!r%Ab!y|!{&zLtyg}%9 zy`vcBm9@5z&70f}t+h=Jg$*U>=40V4Qk_lKu&qaWTWlSha#LH^g3GGx+g1ge3~sCb zm`#kww#skH(5Wqd)^Kmu&9I|>lA9IE7~$=RWT>p?P68{25x9}Ive9!G78SbnY6TOg zN2%Sn`y_cerD3po-M7Q}|Q&1%=KcW{&48v7v0^_sSWPK{q?U0%!yx3gb$m^r$4YB&i5TIAN8+WZiuZM zt}7g^>5MsA?QawuEfh;8RZ!ZG)^6Y(4Cy+_Q)@v_Gfg{MkWt)eeaWp7U3g|@Ih*i*DVqbqFY z`f;k>e^yQ2B=F!&hwZ#LxigUU$l&F<^HCS!)EZ&Rxs})V>^!}C2x7r}<^2ov~Un@YI zeoOq#l~w3eaKXD&>!0$WtFH@xiib{P>wXrzTuZ$F)93fkvTxt=`Z48&*WV|vk{hoZ z8kf?){cODdD>CV4>&suZA=f;Kzk2#V7K{AqW&4fzdUat5NJqdwc>Nyf|2_8Y_vp>< z35q{cY=7qN|Cty0vta$_%gaBDH{bp&-~3r(`@16YclG|?E$hEK5B~1G{JUTH_p8Wn zT*?feAUsr&2&E4|+1y;D++4rB0RUr@6%`>+a!DEZ+CVrdHC1qjzU@#PCBO2stfmt6 zMCN-h!2DtxYH8e>1+7`>rJApxY;-7Mv5N6G5+sX}W`>m$`H}&D<}fl~q#`S=Dlk zb`2_Y^A)0)jQ5OcjO(r546+DL!;I!xr>eM!e`e&#$| zu3M;{Z+`ANU;ns2n#JP6eevy$$G7+S7MGqYy&*S*td>{a>+h1-Gzu(#`fg3;-;ZH^ zeEn?iQ@!QCUs;n)5cHtWB^*XM`dJ``Htg#P{W z=Y~jB5lF;^cP>(>iYh_q?a@j^Y>}eM#Jpu_WfGBLQ57=j4YUfyeXy7+r3P1%D)j?Z zF*Vvp_DyQ^){$cBj80`u>Li>4Vj3)d8T{%o-sN)HN8P(WhN*jG zFUuqz+`q|7exURV+^Vk<$1HjCP?^G^b!LesYEDmsw>_@sc_EvY`J(d#_@d@lOfFTh^fiu7Cg zBaMI``Dm+afnLYjA3CW8+qm5b|Ft-g(8edRVp}rz zlBADh?2i>1OzkszInBOjJn9qPOfic#lYL{I-08UGSnoi<^~|ZIU;871i$pC2Py4y7sYcTZ?W@ogn7zrs?-J?k#wgSK#eu zPdU$um1qmk?xd3Lqweoh7C(BYkGi+}m&h$~13;1GA4Ao8mdEc3J(rI^WF%XjjD|HV zpNv1BvOJx%J6b-SenkHGY(`D^>)A&!y~pRDcs;+Ke`cP4M6C_mDFFz=;H4-@gPD7k zU!R6oCwz?&Sta8cn6Ckt!uXU)#ld=N)LHQ;&7Wm3q{Edsl_u9KqlwfKsK^M?uD%pj z#aSuM(8NW`3+u3ZA?BtLNl3xLhX{u<@uAMI>BER=icoj6*>uPk!a!Wg9%iF)ga|+e z&WD{~_#>+U%qE-^-^3b%86O35+GQ@&DiVy^MY7opLc_jzX#z8ZR8=ur!$u@nlv0_Ry@`PPNfDqU zOBvW!q(JXj{X%?#82a=iRu`pD5Zs}nCj_9@bzdig_(xK_G^M?8_(7>Igd&Q@^nyg; zaE+!&Hhski>ER{-g+GX25~y(ee3cMls!eKLGz`)Y^XC*Q&9s5Wv0;WY2HkA9o@Hrd zsVYJZMl`=&IV)d_l>qMTV5nnxF`xydpg18EDct7+w>*Gnf1DVBAG2VtN(&dVbmS|2 z_MUMnjcD}7ZuZpX1ab!r=Yg+Ui#yzm^J zI9QXO5L@KfL_b8u(Tej;y3A@*i|5(h_<|H}Q8toYbFC2RPl}P1* zbi{dUzf#Rmx`SZi)Y!3nB7xXedvuIkJkLfud5gVNi;nG2c06kNj zbeR%$Snj5lt@1-w0`;ekf7=|McEreN8q+Y=qw4l5q(11bm5gQ0uVpy$oy$OE& zRU<{96=1(G%=YvI+g$f5{1xXbo-ci|11-u@+Acfd@ zm~ZM3l@`t<%MuL$u&79;h?{ZIp-6bHKs+J|W)Uk>k=8qIdeMsUnNLzR5%&bF%Ab7p zo(-dP%`2kM`~YQU;G*Q7P$Y=Q#^8RoyrkC&yO+jcbX?*?z{D5s_hx+A&ul&3;!gb4 zQ4Y-1{X9g5N|aTOp4MWp%x_E=!oP@jU!y-#rHrUPHUwIHyQfTz(FSwijXdH#?5$e- z7>0Ej&F%EC#9x0XhvGLB+cuEYwdSHm-W!+^)%EwzE@LTgz9^RUnDV=3+dr|n$tznB z^BTQ$ZO$m1XyEhm7(1?Me%0vSAY|b&zQ5-?*Js%vD&aA)D$tTWl))g?o;}G)sG7Ga zFL=Ldqe81OuvYAS2!)56>7c1WQo|I= z_zp0EQAf13?Sgs#=>QhwSU(km?@A)IV)8TGc*+OZ zA+|C>J13&iqRlxt6>>fcfcbq89o5YiY#`lJX8Oxl|JQy!OE_%V^wMn5mPG$)?`{Yi z$4A3UX^gE(BM8w7;J|hUvZuw0vaXT6M!rL+D#5-DaM4D7tx3i(M@ch){54WRT;K&P zh?Ik>9QU{>#1ddIToUUySDL1}a-N6aSWMpVNKUjsu{)QL@rgn=;wmA%>dG`TTPl>C zazjQ&KotE2CC9`EWvSp^KrR||QP4@F9xKE9Ad8opx_GI5{>GBb&;vm0yi8ldd~X){ z==!bg;36n1Y*#y_y`1x&Q}t6>v0v}cKK)>Et@rx+I7iXx1j(KN3LeO3wj5y2ETkUY zDkJtw{q>vbIt+nXCnB}<0P4dd5j3b0ih3cA7S{aJ`(d)TIcIppF`dfcky4^z2iz`0{HU+4 z2&=#{0F?kKBBI&3iWSK*6JNz51D*_G1?1GthR5Z&6~%M`RrQNOiji_7T&CWQs%Tcm zuCS*;U~PC2pFROj0*Js7++F3k_9>L|4YWzj3greeR1^#q!^-8h~O^R3(*)U4pl4<<`?8L=X*9 ze89h9^`xt8z7i#DNIsxA&y^b$73uK(F@Q)Fft_s4QfWhUdWqeW2vQ7dyeyc~lH+JC z+-lbrm-E9%&xM@a#Y0ZHO&M<8Ncw$MQ*P@dc4Sb*l#t$7( z6ahG|Van8!-&OiJ>y*~lVn7(8;0~f-R19b}CKMINWM9vJOZ`QLgsO}>dt|FtsbtWp zgrmFqoIgEoruwZbilU<}GN*2eDeNvs1n!i5|6w_^EJ#yyI1d+IZ$FY}3WN(FL`h{K zhCQIwu)9^YK1;=%BN}9_s-v94M&@;H-9wDBq$;FB#$ET<#RTqq18uJd9tgz0FyPvJ z5)ZN=uoH+MU6i^Ej1cAnnsc&pGLuLLX_l&Vac+pRbZO>J5QlaUWvzm&ZbfVd$(Ee8 z*tK@;mP(XAlieLx)^}^EG$OkRRFZ2W=?CdYup+A%T?@To_xp1(k2xA-y&Dx=0jvn& zJGlBgk#UOh>Dg!6_+dH;ntJXl6fZJT7oG*W3gZ_b5#|G!Hgh#!aoze7ISQ+1>_Xfb z83A>Kv1Qh_$0r(9sp`-1tkpgUb}dpBjiBnN06`Vm&R~knx_1R9Z6@OKhGT+lRC0s> zFLy>aGbZIDx)vq-N?YD>W-14kPRi`JD--Bd>CmqSfCtSv02~Fk5v;O&dh3jlAFro3 z_}lWZGo(8*8G--?M1fMyGzc0YCyQZaX9a18aWUyr=7rI&>V*XqP%jE*=@THb!ZuC_ zv#{I-3}7V$t14f~&DT9G<_Th?4R}x-W`{&5xwG3`4{ydn3_1ul&5%ct#EM|Bl`O|g zjtDh*&`l3)hDP}X=OCvffdmfZy@2=Mu!}eoY*TB=xwSthh?JL`;e1v_Lpww3@lY{n z=HrzDWRd?4TF|X^U}sK-xm1Pu6Az&)cUDzI^2Z7&L%4KSA@SaQYAi~sW5{2pbbpk< zs;iWFY*rUVY?sbX1_+lM8*=lVW^@gYSY$uWDIN}wdNRm`M2Bh8)HBC}7MLQ2a1pk@ z0F0*W#qr^E=5c@uG3d4qw>gAddc zJj543RWUcgRWXblpC})zD{Ft6#VL;qq7Edv@msN33-z?vnOg#F$tu&gTsT?8!=9Vp zWpy^mDk8W9k31faqbVxn-K11WM3I!d)rHry$skyZB3>tf8`s~H?w}TH8vbS@WECTg zpqzq51ixV|}(WL#7=5WKo3x=GAtiUx})u9()r`kov0JM;~_S{_t0 z^&6S9X8_q6yPpVrN-Su>6tK2DpOF*-#tqwb9bHL6$%HL_;KnHKM$&^$k2pb`*~t6}~C! zO6ECQvPd*~ma{J0Fee*plm#F2Yr&eu+G%gb1YX5RRjrZ;k5$asNYEvyor>>cq{E)u zner9idu=Bb86}3Q=g*Vobnin>#RWP~ioPaToLGG+v7x7AuWq=p=r*S*F`0+5(XDv0 z0Mn|>80=SzVkuwGts4!f5*>GVIAPrUkTAhOA?J>|1Fx`hR*}8Q3kPkFO`3=}34cBk zD_M*~p94>U7Tt!Gy0Hz9gYE15^^QLEdyez#XvelKEfxY_sa3O3KJt&)r|P^`eO=01 zj*U3Sq2grk=oSqRCoL({rwUFi*D>~6qBdn)G;T4dsW@bmLJ8@nb%RrL=k`tZLwmha ztVQCa7)}#uvJ*Js?9^uGq~{p*SCimwgaor;Z@`nu_kDq1F= zZGP`0{w4Ck#pKLynDj|0%_~1N+2wNFtqn_lqtItuVITE&H&?GIuVOEaaK}M!n_tx> zP{Flqi*9Kke>Fg~FobGEIZP>C?(%1TwNa)8NrAT^_Z_VWtNqgUa5q~{DZ3>~`-Hbh zMLA^E-KW~|&KdVyhoYpQrJ{UdG(&FU_|Q*gF`s|r^-oUA)9^KZJF`6feqBcq=gBHZ zmEYwX#420W6&p!BF3+R->Zg_)F818+DmAkp00J4K%KNu~?3t$oCT?$Ulm_m`C47nR zmU*dscXLxcg`o2tXD5r;-AsZ=Mqzd`8N?eq6}Ni`%Ef}eW||xkU_9T)9|TSNV-g z!T@p85W5=D7v;CeZ*N%o{uyqE&ccT0=_!4O7P#JBn>4Qz=acg7GUVh)4#vZ^o# z0~ioin>_N2;y^BZLP6B25x5mS zrCVLZ#tyT3jy}#d0x@v`aE~-Pm%O%J;VObzPiL`dck$0+o^i#)vgP4(J@_47kL zbFu<eCT8Ebjl&{_#3zc0WmTAU>csd; zyv=Q8*}?-z&4TRxLNa?ohf80Qj(`|O0v|+0Y;Z+Q#6>Uby-yg4(>Z^`DPF2SO@VB4 zParPCM*hux-WU`2H@C<;LErMhkLru?$byrqwkL_x{?E(pgXB%!`hK{RZ>BxSO;1t3 z5#z4NXWyEeVqEmRmwu}1U&S(4d=U9tS`v7mAk|r>-O1EOhS3iHrr0N>S}Y5~aGevT zPb>6v3~eaoSxiumd%^;Bjt2@jF%jjlU=MNs=5IVV@}?vVTqU9L7 zDYeLC{#%_A(9|d4&tby1#Mpg-6l5}&vDjivE~vUMnDMtLZ5<5<%sw;&I-f|(LaAV0 zRgB`%g?s{JAD5$~!ymv>nYeb?OOzm5s#dyKA0RSOl@{YXK|Fv(kg)P&_+~Z2{Z>rV ztyTx<{ad+ab(n7-qm%*;Rq6D7p=xssM$bP@o6w4XiegkVHijEBF@2)t`Gd1tGqAFR z%s)V-I?!;YQK8Ozj~ z%1K?1iFS`da#t`brQZwJZgYa4y|>Ac z;UZ*P=g5qIi!3kJw8_DSeCj}GI&~?QMP|MaVITFO)t)V%T?>6}>Kn@k`*@h~0AlqyL1HtPuI2L#$zm9mVh@=2R`fCx0+7yIc~XbkEti5<BK=A#QdiB6a|zH=_3pNBQ-Y`@f?-I8 zfi%7;(NX?8L+=6|-KM^=ntVL{+_uW&V^FT^iUmZP2{rW4s}Oo9VkjcrP(_*%5ot<5nrsUy0xHVHz0W)6yyu-Y zYi7-Sn6>6xKK?&st>?F%=f1D&2yZfA&V`aczrtl74AGElvz39gatSgxBTmpa3{yYo zOOPkp#;v}z6%HKxUWVtkpSs#sG^V?yf-BCxP={x)jQ0KxvrTlo?#WHoHnXQ}5kug< zS%`J-i^s607LTt4Pty&q>8h!)w)T4&3M}JVamqfk?d1m>8`_Bwvnwrd{N+-{Q;)T1(A7)S6{@?61?lhT&&n^T2tTI*XyV?KF_GTul(Hk74(zrY<5oG+3!An zYQFzd^{^8>9HfxjMC*6Bp`IY~?i0h>2Wlpdv-r5x?Hb*yc9Q32=ubIotSn;OF(rfQ$4MPKE*ta-n) zGNtjQV~TyYO;*ob|Cfgk!bPXVZL^D}5jBlT=ic)@NWFOfV;;Vp9_knQVqD8>n{T(` z=lV&m;2zuOe8XtGaI&1nC9k;$b>~h8-kd#aNgINJ`M_S@^2?ykQ%xZ&au>eC7ROU_ z%aYy`&OYm2tg!!de=UgglRPFGQl3j1T=EU9mVZ5<*TfntHXPjE^jhfUd}lgqt^D@V zlalp`ip5(MdS}ucxqylq(AU{J!Y99QMaJTJxZ9jm`Hx zJ7(4cuY7JKXW25?MaB^;7JSvVL5tzE^h=16MFHxx94wI)*lJI(bvrqDn0EW|q`Kqo zLA_#U@Qe46ulBgY`dvb#+*YMm%ics7Moudc;+v-^KJu(zS8AjXt*W(7xSL)b1}`MI z=%BZ~!4i9OV8K2K)Q4pe$u#M5F($yQ0sg|738%Q*YuGw4?&kC&i8@vJ=bq%KmizS! zO>N6JT(~=e@3nF@IeJ55H0z6A24uy!xrnOuJSVVB8SeX9m`nJnKq!X5okRi1WD63a zoPZMMcmyIFYX_LEUN5yS7qM0NC6aL88cJ&Zy&{K7S> z5eK$(7nwMulUp#1R2q6OiGWJ{20pjwg3)*HQG7C2KNAi;F_T&Q>FkQ(?s9Mqij3+* zVR93xn)9+mW7o^ZFM8jkm&ujq=slpXf;3Z9FlFCz)nutez_-dlSn53TR2Ry&bZ3aY za|OKPW(Kq3#X%#`*#tlzKm-;i_>o3iZ1I&&;T_RarZ5=jrig2N$9s1I)-hUOjr^w4 zwBRV$m95UEo2-F9srRnluWKjOgdEOXEAuy0T6$x3R~uk%_D&=MfHrrU%5z62D{)AO z$u%H)2nYe@u4WWB+FGrS0JPNKP&04cwVasS(^NAIfc{&k#TI6He; zS~jzi2d-^JkVN>br(nUHTnQo_gDeV3+*IJ&=}|-7k)9)s&# z3KA9N7E4dJe`kXUM+1B|#zuY6F;3=JwTu|jfgI-z_@hx6pRxBTX&+iWEp^-yv~W_G!EfJR z-Qsww&&e};N7!uxrS2|av^9F}mm|<0%fHWps1d$WgkhI}bmmp|`wva)CNTGj@+hR( z8cc9=kFf3mg`1fre2n%iF^gOjcr@^H2#;%*IdI$}4q@5VjAn%9@JA;MO|5~c<`x?) znBz26XtnZz!F5BQETJI-TOXq&dakkJ+@PgNACM0nx0^7sPhgX{1v%I-l1m?n%^TW8 zVtL0gVgL{=-D4wxZ50XjN*K9#YXk*z@QIkY=HcR)ZUCftpKtTM0AMp>xzI@5tW(dj zNVk&X9SvJK#H?&An@}?|Hc&rt&t~se7-mWabxLKV=do5=QH~970gNbQuu52#X+HI8 z_=WxA$r6NJu$c9}z3IM=!yttRE3<~5l*I&gDBKs8IX zF*+BTBPDOUBr#DmVVVR(M0i-hCJk_`a1pNk23yHS5J&V?t(@_kLJo)pdI15+HdEva z4wkXSilu^dxB^R54O5{l5EKUPC6+3o2ruP(hn9SaBzkbE+LE9SS!@swzQH}PtpHL6 z&~FNBK(n^kX$Pw~7=rnl_|62VHe>2XG^FU_G-tE{&|WgaA6Ki{EQvbL!$ToM=Gi9$ zrI zDpC$4(~G|GNK1G1Tb9n~7k^8}mPxpY)&v3f_#|`8gs$Kq=0dE3l~2W|tq;L&?4ls1 zV7_x-V2Zaf1PsUJzRHwK0tRH!8*9$95PL~MQA6P6A{#VvUlwU9N4~{vDnZ}DB_y(P zqoF*)f*2#QATElrn5?C`Ayh9y#gIv!05s=f-J@+l^-yB25%_eB@dY2r4lXf3+!++q zP4Wg2s;?m9$an#HJApqX)R+MUcLu>&)v@ZE47h2;rk`Q3vQaV5xgq>1^&`)CM2yL2 zi~!`l@6+TnU&y8sDMvUxwiJbVh6@b=*$C(_Pd_Gq9qil`lGWe@XddX}zm-tw>SzBX zjn0Hl=7FSV*NcQXwc_%M%oMJ6j%}6HNTN(ELPI-Ss%z3oKFx@Bobia zHaMdlTQRQZj} zdGa{}nA@5TmVzIBI9LvSa{6%P)~k@i*Ad(I58p%|o_si5#WE@$(GqyBM#yy)sU#Ys zRP=0aoXW6IF!kYepG!AC?ihqxCL~C2?06LdJ$wb&HW1eq9MB;W(i`A#+!}R|aH+>l zd(AwZDyrxvanu+MLFu{cA##8wVw!KxM@V$vea;i7OSJ*mWA`|&0kIqI0JsPMW5j>S zm2E!9xMsj0|GYdBLuU)nDfNav071X?uXFlP#Ue813OohP`4h8i{wb53@B5zKPWQK{=6^LlrqRa1ZCfZBN9 zoLxy|xVBR$X|$NX!i9^fYFOdr0D_qf0ITUo2g6YN4LcP_aa_ z4RR3^1i{VVQ+wo}#0*y1yv}sJ{B41UplmDjv{yPTvpHotVH_iRLE9=b31vBKDk_C1 z>9gySQaqvZqNE}m%+~Rwg`a;f48Dkc^uB?hgI+fICwSNf^ z=9tphYbYj691cd~c3^=b3e?_2-|5$wz3Ku4B&204P=El!eKt(#TtUYwNh2c*^H}u- ztaENbnICK5S)Cmo6+1fn9X!Y^)P?cpj7x5c@PI)G?r>WyUfE?P#XWxnrwnjGC0%p8 ze{nop5ym8ImM+Q>hOSds{8q;=EE>ITKFWR-gfkVgm4v7PDJT^93|@t`3zew*j1u)n{}*@`6W|KqJ?LMC_5YQsHKX3omref* zJnO~g1JIV5WWwy&#gbFxS+XnrxMZTk-bqM#|b{oMEO|#+|xhLLwh+;6aC}yM;@8_+cBn|Bh;|VS5^Vy7EvEw zZeCVmE$|$JSD5WUtLE=y%vS z^XZ$#q&2sN%KEpNy5+YWm0Dp5LyQ>f&udC=z}XtA|MY^L-eh@*=^*K^#`7HGlEq;q12{;IGEh8;0c7f*nc(W0q0ZnfmU57 zSbtzb-pw7f8xo6&V^ER3Sn4~qR^tXCs#^0B<$i1_4UXGVSQ}x;ku*)Q{RVA_t_MQ& z4Xh@y7Q*`ihqkd-u_i9(_$b`hbSZgTM~7!!^Sd{LZqmeXQ%P=i3(Gi}%%xJ4fcR8$ zD&w`W?Q!%bl8iYe!!ND}1h7jaxJ?_lp!tl$T`3}(F{h@{VK50t^_e%=D?lCVCQ&&_ za%sis%ZQvHWJ0sQIbBdHN^QBtvG0EN?*cHGRh^qW!m#@L#$KEBy4EK;JnNDZy+2cx z_9WwK%w|tQuropwlIKy=YB?uO=o~}R0opJ#LwSr(*X$^x6-$jp5Cg}Fo^8zFX=aOi zayq?315*cL2Ee2_>B3h(W-g*zAQ8=mR7jth;~Pkq7~*sj?AN5cBueE;mP38Zk6mZa zbC0U@Z#l4)*pR+5-0uh2VOhTCTncT46j?Q+jgcM?R$H9yDD|KWQK}$%#~Hw9Y-<(X z3&|6NoOuk${W76LsZV23$GXWzfrP5p(4!ZC`)-V-$A{?iJSdZ$C+t~2FMVqJNQaOd zoAkqm;>o{2uIGZBfSm{#XQl*imA9iWSV$Bc1s!`s9*cwnm{IRhY`rBzV;h>nxIBF; zDGA4zf$e4?D$H;uRbbUt6mgM*nHz+mZO%LPock3=&-&Q`PjrZhpfCrTBNcV(8jf#YHPezMN9dS}zG49>XHH;<~(IQuzDa=bWOx zn!ksjDK@Wbm1`M2VW_Wj|6XYETRN;RHM|LO?!-#(t4!RE4OPQ|~kbUQ!Ex$z9|z z_xn<|y~$nwsyV8m(dz(BRe!I$d$hXc>k@ zqX@C!4~^pr4yQa?b)&rx*LE~ng;qoLOmF+T32v#<50uQ+-HWnRUE0l zy!mKY4_IvUFONLmyIS6{WG8GrJb`yc1^|JoHY&mNaXI`j{#lO%oAZCW4O4SbIXUrJ z-Jsxt#yLwy^M!~I+q(h^@wLdKgW1B;`g6>1M`^7FP*G30wPNol=>=}&o+c}2{)oJ{D-U>?`bXj zviFf?fVQKeK_<(E`s_WgnIV_Mp2fj5gBj9MUV7MUDEz&jANb4dT)E_J^vA9=()Mri@)DMSMg`}TAAbD z{wy{y(;AxeQA#{%^JEi08b+OG^Ou>TakyR?mSnR?{ccM`^d61ob4;fW>%Zj~J{r>+ zv>T<;_jko1+I@vXU))f}!8XO+K1s7f!w9mj3?K`ZrT#mb%yccl zk~ZnySeC@rk$9rZXXL2*{J2yqz|D>y{YiB;idmuh1IyaEsK{qaR7Zyo2$(Go3Q>Rl zOoQd6UHVV921QEa<$Jphr7o!JGGT&FA&gFsU0(Gagta(k1iJE+E{r%lB!^fAT@+b< zc^$7o4r2|npX_-#bI?GJ&j@n3(u;8Z)zS4;kbc-q@#;Vr_Po0PF}(ff>yMe5ecPu$ zMZWm?=3qv1;P5p3)}iYvVEeG|iYp)_*n0(*rKU#pzKTP?T|?ZC7?QU73@DcrZUY`xXDM%Q1vPS1MgAI*GgiTd@o2Yc`TpBUB| zkJx|i!ICN1q(|%kGJ84-m+%BemvABQI9xprfQaMX!C@KWM4fQip)ekkxTq^}(nnZ@ z@!NC*muy#@ivMl3qqwZl_=v)I?eTc6E}YU1y;_!V>q?wJ7kkwnOv69n24kFAQG(7+ zg7FU4qA1~vN#e~zSg|!A9R;@~CEiX>u#-tLK7z3oCHh4qq*D`uU@=uF_)`M&BLedb zIyoGleA_8Gswg=cpL{cd`LogzH`qzj+5fG6zW??m8}o$$&2 z_?)hk^o5k{os>MSl&bNR3a8Xclhk@xDjiFm2}@})Nom5TR>M-;{Zk(nrFP1s^*G^u zP41>6;FZ?Q4?~$BDW{M4r;nPXKaEJAz^4x#rBh)U6J6;qoHFJkG8X(ZhL6&p@Mb(O z%AnB^)moVwPMPaF89POpyIq-E3z;8}GCvmGrF3Qd?UeNl2H%OuSXoHli^%-8kOkl) zfQmB?oak8ZEQVqN{A|Y2VcMWmIwN29xC!BuX$B~Tz+9Zo&y>lzn9bRpjryL+dNvCo zn|)N2`C%vHrBn8rKSA_+4)eQg)w8*~uw0Eh%wJB92|xJ<%l=r9z^6wcW0sAW}_R`6n{MXLqX95anre$+y%MAj`KQwdWp5i;Q6(7D6`F6_$CW?g`EBa*1MdA0vd-5NiCH~|ql_{y}?XJr1 zE|ZEZn~<%RHLJeASjFso8k|xS)8#C%l8e4iwn_OxmzBhL47Pl^Cw7WF*z{_s!lCrv+ zD5>TBW({$C&0~T2t?=R}JJ ziX0heM(&Ahitet2$v47XYgm^X;Au^U@CuHo`cu7RuBdxFrFDGftpWmtLh^MYO|7EK zW#T$@lFV(=lNo}gZRM#g9~aur!rK{7dfG6i?RwwaG)jxJQSIj%+Dn((gTA-F?zyMe zRG@3#p%l>Z7k`bZd5c9U!OFD~4X?J*DdK*bJ$&}zh||OUE0s>A4?n(pI05VYD&4tZ z+NsU_z+e7u;NL~T%WYSgJ7C(6BAD~5e{_E4d9+si2>W+qH1pk9opNkc*LFi){Lk3L zrhE9GUEJn%X@AFN^wtuhy0e+@^7G#E}e|M*GnS)>~ht~tL}}hrQ5Wk zx*fZFb{*jvfb`C&-mcQ#p5ETR<=%mxy%d4IA)USv*S@i+zVXt&iOJq#D!sYeM-}Lw z)#;}Sz}re=YZ1wnh~!R6{~LMu>l5aIRe^yGoq;X+fgRU@cToeo%LDI!4*V_f_@n&e zJ)Oq~u8)t*AODDY{Im4&@z2M<1t`CCC?BHwck7w55KQpCf2!8U6olX)r|uxqZIC;9 zkhg4*zi&`*Wl;Ed5XCZdO>0QPZAgkl;#78B#nRQWhLm)g4xM8`g*()+!s; z?ih`M8bwMUVNHjRp3N1+R=xpfORrXsCq<9r%f?er`o_~&#xsw{34%{^bf4zAJuQfST2%J5r0;3j%G2`Wr^M#4 zEaizBHv}04F$9=q@4*^~OrY!u(DO7r89?lK>FT8Y*5hXJt!<2dW`}r zKtQcfjJFXJW0;8<3sse2BM1T3K!JqkBQ7D-I0zsg<%upjx?dT%#sZ|%`zLh~i^m{- zvK9}?p2~>ejH8LFTliJPd&5HmyTiNSzw^MA%YQVK18|+ zK_VPA1^xvi6R199YKf9dCp3IaE04q`$Qvgiv){IP+5O?JX zuU`x{85C$NB7l1Ol>XV_4>S^REsOR?U z3xLttA`k*J9q~ucagDhB{v2W^e(l#KNgu?l=ZWyEo0bSW5+wz}^ym`cFY^hmdx(~) zrL-1`N(+LgD=wsHhbX*Tb$++TeYY-lmsGynD13|VQn0fId!nHQ=MY^4cm{3K2eth( z20^zIlY$|aLmAr#c1J!>ulE5@?E&p(cE|)7Bx*A|6X8ZzoubSHLcuAP??*Y9tUP8K zs1N}Zcu^4%LIb;z)h}Qv@8e;R)@9b|XF`D4C3isrg&I$QlTjd9%0}1p>x-0ESs$fR zs0j=wumUQJITm;U4gYE-$n{~GOa#g!_Q0p-nJPY}&?YW>F`bu0Tth6!T!r{}Ewlb5 zxWvl*7j5nBo23&gsLF>4NpD2K35`*TM*k-8Q2LJKWq}xX@T*M5I3XtT-luox6L|?B zXH`V9FjI&-M3VLlH}JLTbGtbiD4_oS=IMQ&2TUmh6%dB8H+HVNkEv_#lRf35ZI(a- zmYFV|G`5~AmGj^suS_gvq!Ri6Ig|fCjk0`O; zI4=wop+V|SzLPw^pWK5*l*63N*V`hC1YuUfx3`9%}?z5dtljmy8a1}6Jh-a}BfEyKSrTb1}cc{PsK6RfeKQaTh_Oj7ZyYB=Ng{ zrDUSff2~@(ayVoOVXV;$&#kR+jh?Ru5(OMTy7h#8h_%S$nWrbOC@h6In%! z%A7uXjd6&a3-k+pu^M;djk3i><6(qB#<{ytp+8k?E)gD@Ey`>;E_^{F+M41Q@E=v{ zQkgl%PB}$q;YtO$`>o0M33dnJ5T702SyMRkpYyz9_)<0G2a(P8JKX|mMeyAua z*&C7iZ`E3i9dnvDK+E)ke5bymDm-Xb3y)N*I`WeG$UOw%maWtB zN>`sHUp11hNXQX4nc^LcW7WWVK#X9ZD*F1%Uo88Dpq_66OhX0$5>-rVv(#LTmdV#h zrHONx6v(W>R28m!rONW-LD{10vqM=b`|D{ZsWh5ThYg?IbBXL-jXNofswU6D1={>t zVjMNXoOX}>x*|~4#up5~jT!{EjpQh*`meKII0LywG+2C*iK3TGJ z#26JY4Ca4>@-}zTi5bbUz>RyvT@rB?i-Wln2K#`(u3&MAwSZdN|o zP>xR%7Cwr59QtY0QO|sd=$Q~%sdxK@48ZeIT3o_u6o=7%d@a3*>)}IeKG)$=m*K=#I?Cue<*^GF?x^+^4!^*Q!vJ9HkZ( zB(!^eOx@;1;)bu+>VWK5v&9=4zN=ane!Bp^z6ySldH=u_wc#@bY3n}dRtO(oFcSa7 zCaWAC^z6RQPpmI4EDiQ@g1D`_-GbqPl25CcrL6;Pgqcg_mM27avs3L`_*hRC7_QO>1Tmw=RD z>7#g@3Hy56mo1)J+QyAZeWyhl}y{s>47;;mHXltmXFVI2j-E_Do(qkxmKUms6 zR~9CbbV?GNP@Tfy;CDGxfi0iApaxr9uI!da8Doo~F?%e1kPt zi-l_BSmZW2z2?02ySpyMyF~gWK`B>x?!|=7F>Pf1l@Y*_4q@THk2VutT*|k@`Zp?T zir@<_Y<9T3REB@t^F`b|J>0;)Ao0W2w3wN1G@{^ z`>Eg(Gxn_t{abP+J?1=HNA4pWx3y09a-HKogK@C&IB|#=A|l}qlNb^-D-b;sm+&upPR&hVjglrY04Va0_Q7Gin7hnD8NKgm@F9-%Yx$EF!zI4= zLAQu7&~w|!fwc@aSS6343o!3wMvQQpj5mBd4rJT%P~tovtau~aX}bBMgxnqFi*K6D z)Zt_}pL@OG0h1+%(Ox3Ak^iL|vnZa#N?Bu!99-DkJbf&WVuYkX4(Qg8oL3DX0wxe0 zB%U>aNo7Zh^5Zx`r!zli%F(2&MxL8b{rV74*TTk+0I7wG5)`>9 z{_mb9{#xN~(*PL?iNo|n;h_mR5xx=2mDD2WHV!n>06;k5L`^#G1^;4{DbJa4meDjM z#^@s<<7n17Sk6^?vEJg;xGE^Anh2gQDl}aSXTc19ptS-55F?zCvILKLsnc3ZObA7N zt+{Cu4kL>ltjRsmJ}>oN-mHY7XrNtaIuUQ-Z#``_wjT#lR>7UvuziQ`F-FBmo_6FM z7tZsp2!PZ3qh~VE{3WN|rz!=ZW;Un5OXLkMQJ5hhKW5!t%AIJ0io<5AaEu_+*OD5Psl?qUU|8P1vbY5mn`HZI)!Xr~gXEj$hR9o*PxY;e4Z9zF zf7Tv!k^#kB7GR~`N?U%t)tO8Ac0V+#cWLcQLB+`C{Tp|K+_t1%bx#V>{}ck3)@^xu z7G8&7-ixPNAW>}L_+j9vz?;u;j(w|;Pcdvo?oSQb`ZvxIHx{DY4~#zcf*L-BZ!NnY z?P?Bev3`nK4Z8dr6!G}zR}1!glgEi-L_aVo^zNoB-tD*vV81w5XMkb;Luy6+Cgb%j z);UVMMr6*nrrJ%dbM&@PmrC>ZszG-Z9eo@%#_URoe2Mnd^^P zx+AkrbNZcC)Q=ZLwudBR%U#>jA9EzDhmDTYyAHiSUXn8(Hq#xMF3UgWyXYv_+tYu$ z|NQZa!q!PnwtVj;@N;3D?#L{he($IAbCH_a*+F+?2D<*FJ2E>vA5H%sIx^2)G3XND zn2*)$YdHPs_J!Uz9|trCKKyzgvn{anyWmkf!|zXir}}7<=a2e|WA zpCTPs)~EbNM1`-zj9>|?GkzoI4?e?!{_+w5Tw5@f&_4gcf~dPGS#cohUj8LNN^mKg zcy_Ax!wtaE%C_8(?$d*5F0^n{QVtba&?*evXTK-gx*ZW&#NO&j_6${SDFp=>O*p z@{kLwVa<#2htkDd_|QuIM1+8mkICoCku)x8mnr=9YU2!)PSQqEC~64w$4c?v-XPa@ zr|6oCXXWV2dO8uI#OGBeS#p+i&Bcp4x{N%-EUfWmqtgRU1xoY(A_#Lh{i^d{LDzVj1Y)5rO(g5O#+2C*$D3r(bSyhrBUSr1q-+_>3zM2Z8T_-aD(S`|0Z^ ze{}H>Y<<26<~(J&wDI@LDYLKIADovzkjw3w=I^-_qx~nNMf9P%;r{MVGHb(yOCIgM zxM!K1)mdm)8x?1zi^LtiMulYrl&tN5DiglZy0mo z=Jh}u0e}6vNMYnP;V=ZENl6n7_B9$7Kpi9^J#ZwNYl)#U@w5BcA8S~Na^BE)?*1{{ z%7*?oVQN*eK{XDbtDc+q675evq-2jn#o>*k6(1c$J-nzgs3V( zR_DiGfyW7+e04W%{48eS2>!JvsJiI$)(9BEjZVZYHanx0u5qI+%DM(_v#2bRwMqit zD#W|{@3TxuhBxM`2&8dATPq52R};a}8713XHI4cDqIW3+#)kfrNLt(}@nB~P3_|Mh z2QD9v8s%2ANn8R7BT>7Baeajk%%%&dBa&Mj2@^H0uc=$5bYe^}@EbSz$yHZh1`EOz zw8^DnHmr80D#(O!8t)3n3@eS~<&HAA1dGd)l4|AWGb>w7>NQ-M%%6o-KBs#5lOpy; zhx$gG0Sc9^y++h&k_I`$a>}L-`Ruiva4uHzoRWHN;=vYt=!jIw@)&%NmNq%YXijYW zc5-+Vn8IdAeO&1qsY0WU?*h3JNXz-vR5TpJ063WBI(HE{ZRo!wBW{q;_)-PL^&%;W z1vBPz3B;1%|Ds~PwCTXeKR(A(zQrz&3{hGXv{D{hlo20heJt^}O3>KWuPgqq5u_!K zO`nff9K&>9`3f-=3YT)>3+Y|khs2Q zS0IlS3I^BLj4DNYrnvdf6Ed8TXjq#Zdh<;?+#M{cHxA1{YV4KENKBY7$StUx#Jx&n znF_jjjW)ur8=3$Lo(cD3@B(f~H-MrUxcRNQJM6cLGgaizH-5Hiz>Bg_zXt?B7UCvc z901|6e=E^A6Xk;snB9q=)t-=yP!{n+*+k6*o#`n2~Kmj%~MWRGd05fVZe zl!K!+^pQkn^97+rs&YSwXv6$yB1uyn*7C~(#)Z3q3hFz2&>|y_bc0WG@IPVsV-+fsbEv zZ(Y7re^|4>jf-7*?;I6i>0hp%9Nc&M>SR!M7q3>rp_Zka*komAqw@(iDKQDBvw($} zZFfAc0YiS6V!FD5UYj&v;d zv?&d=#{P8_5UYr%3M%Ju${I-PJf(3c4cKI&@oBZy&xKi=kYMC{4~t4Z8`g{}emB(9 zxXsURt^0;qYE&5bMvf<}uks6pbSWm0Of!0jX2MNBIFvUe*fF~MJS2ygVcwE371sE| z(z>r|+y+aQtrLP(EQ!u>)w`FMmW&_cFQ|E45As4TOLp>}Y9(X@drH!A^5;L23#Nm8 zg_{;<&L_2(v!3=s%P-O8OR061A3UjzOY;Yi=$4ES_o7ti#giqC(^57@rfoyZO-G%N zD8KH9#+$Fy?-VqcnYG-YvyHa254))uEw}2I-E084@^jNI;g2R?e~c{bUOQ@ucw+wM zOUYs1j^%^MSCelJdJg;dG9E;4o3H*@IvhBfeh_;&x%&IZ;bQTf zo+%ns=V%a-NluWqScAJB4e`#9lQgH+*rMne2ewwcvBf%P>CuRcRcor_)H*jk?f_omM$=>;JK#M- zPMg$M@sbbkeR!g#UO=&(75BD+gL;?z4-Ou6hxlF3(pmJ?IP4OY4GFyabLB(qqxP(f z_Ypc#%T;&-^4tC_6YJj9&GX?B$NeF<%ztt`jZKjGEyQ#tN`Mx0{y_ZveZQDVP1Ju$ zIR2Ub|3eSTj6MamT%@;aSvl?Tp`Js@Y~mVa<76>|RG!mjbNK7tV_Cxb;er8VEM0PC z*XZ`NO>#0G zO#lB#IMO!|e-e%#{N#zOd`gpQ7p&@{Z@5idUyZ12PHzUZO;lT!8in^zwrZpvg#;B_ zmcE;;x)2!OKi#RiIO4XXNNMi)JM2l)aP0lI1Ji|;Cm6e{eH86ns;K$T>$do!IfyOd zM6=l0w`}G0eFSrCTUrV$?K;xwrFNgG`=;f@4OP&9saNTBjTu!8l9+C)hb){8> zi4Q9jg8Y05sHJ@on<~X>heZt8KbjAff!wk6Q*Txm zyd~#DRY!9K#L1gebY#jXFn@}|1dK4pD>FWly2IUKI>5aL5#@YRfK=2Dccui-_XOG| zLQHG`{EZo!dVC3a43kj5^#IQ7ZqDFY*5RrVRbRE!k&WcM%60nKR!)JN>mWl@G;-S_ zO!F5??2~w;x+6H*A!K-nSsU?|;sCRioWJ=Exp#v+g?aRMP_WcV&y*&S+oJ~YxXhrY z;;hn=Wx%}Ept$c7a4DTj^E@<3FsI~}YM|_9q|=ymj9qHq2!2e=Os4C`#$DM>qlXV= zRjQ|aFcmdFVl>{mU7C2=Q&XcF^D*##hS;_>Kon51Khh9%bK2*j8U$~Fkf|{++4$`s zYuzbzKlhxO(Wz4jERXHCeQFdWU(NM~dEcJpzUkc^_rs6It4ov?ePD@|VjWD2lYX9j zN|~6rVg1ojT6U;hU3nk~l&S7)Z!rvHv8Igs|i~3AOL%;vM2b%V0mp0dQQ$ zKns3dCRQ^CfZSlFim9{SDMieXSVW4hoM;gbGg&?NR;AB36;qbiSCS-QAl)00Gg_dH zILhXG6B*hX_^}H3FQ#V_-5#bI+@73oRVMtkk#Q)34I6K9%{2?TvP2TNWfIJswzM!- zFeaYP08cO-F)?fO8cKgRRikwQlM%vS(DI*fPyC%~!Ci6=luHQKLRhmwLg=H+CmSQfi~jbqiWp-;q#a*~*&SR&4P) z)b5O90@2pWTQDT>*}Vd%$!oE3+a5wP1Au5rlN)k86(Zc=b1P5tA$x*O^oGcb8_};q%39490P4VBdn^F zGa4+en7t@j+ON}^Zm_yN@uK_(T_(fYXq{{}SH=I0WMbK9TR1USr~R$LI-}9P-t1+g z%eO`+x=iNL#LJe*Z%rPoO-@hD=Kqn&ST?!5nwanGq3;7Sn%uU{Ui~AJnQn4FoOm_x zN9O6G9<1L%LcqSLdwCNj&jAkEc`t)}>Xe*j-_S2kPoQXVWC$ir6H#T3I zEjj2QS>6wHoLrjkIe19UxF3AwUztp2*Yy3Xw>9WHpQpe1 z>s@-nap8YV|HEDy>x2JqO@CEaJ6xKIMI}>Ggg)JhxoJ!T8Tk;u_=#tyN+tv_@beA} z@Y?uFJJA>}7pY$9wT=_*1D?VsJp32>qNT z6cH!2U*>FrUWX_GMua>D6B!MFoCSm-#$9s4DK0EWNtim^hk`etRI#yYfn<00aIzFH zCSJ-{qQHk_U9q7#(p8W`Iyp|0=EWp}8Wwm%bT&U4gvtUE8oG%%ne<(V{1Gn20hOrY z-HD9f`pPp-WkK5wGOJ@dIy6ynf$=Ww)$4--Mh`)%1ie!!CL<4?H$%OG4%ixsK+K}F zI1SPoM@fW%SWh}mbI)^rR1qN2N81M37f&>pj0%inVb9KcN!n)`^l=QrjOyp#nz41$ z6OK1vLwaz#6D>W#HwfeWG66RT{)X@01RP5+iUA=rBp^4#sZr!ltxlp0**$35XmTg{@ssG)=|eCp%?mXc?W;zET8;7diFTfljFNgbme<^GUu0M=X7)= zM<^$P80bg4aSw8r9<7)LgkK=QLlEE?J3wHkGy5To6dFwrLX=noN)av>{g_IK*KCN; zbU@sfWY~JWv%Mb^9ZjvS99;hmHcf%DD}(XMSgA@V@mnB2%HPh>rIhi?honfOBbXZv zXdD{pV&swzVAAlQua6UIeVGdOV8z(T^ZwUCM~Oc)lYE?#{79|}-Vi&Qc!2UPdW+nF z2DaRbxrRzgPh{YrAEOaKS@KO(GN&b;)0lwEPK0@fMv;{v4Gw^22Y}i$JZE48C#BFY z_l&=>6C*#>`1JMbiH?wq_VmKj^$-A9--MAs=8Q*0YApoVe@V{#2D2mFR!2a5$jH(s zP+=!POP5pIAuN^(4WpO05lUvBEJZS)TZqKQD@=I$WquDRZw-L!$H;z$Ss6oxt|X^j z^qpA%K6e6$sAKEvfU<~drS%ypn-F>&2D=xCPzFx}B;?m_*$|`O7(1&cW3`Pl6b8i< zkig;bFv6%0JyYWahy`qOvL9g~=2eB+FUl8lzlx%eZ41WxLUA zIOOBMvBn%Ss;Z zIy9rN%ycx)HO$zWFe6_-diq|fK}|D7H7G2orZ;;l$uiCQ+RP&)b2_Vnwf!aBf8EGs zf>1y|!1jM!1wH=x-v1Ol3UDg${v&uieLnJ*4Ci1vN^&@+gaPW^MIck zl{MpSb(YDJK;#0CEayZiI-dVl!_94}3V}p9U(-3%g&Onf)TuklQnSXk?JmJC53ktX z_Yk^qhV)ftp6t(Md)gWam?{r=D;&JbUH7#9##he7ci|Nz%PO(W>CzXU%!{f9*sT7Z z{Zuy`%cW$reCp%c(<0`L=+Zl(&tg<`lv)&=)IGcE?3&!CdmjExZyimRTlW6bI{H`e zxJrrt(>m(<{FdH2x;)d@{ik(gUSZYW^X)$bkG+SVXv1kIA{YL&j&@!&U4Ayu|MT!) z!Q;TMpGRN+UVZlX@gMQ53=IqB_NU=sQY2a&i^d=EtdY!G0@A^MEs@ucw3Z|oP8ZMe zIolfZxI1}zA$@A9Oyw>iJq`H-s0J(I=1%BAFrNVt$W>D08OJDM;9(swYB>UvgEU(M z6pVED4CMTx5e8x@f{&hyXNRs0a`;eGhv7a{pgBUM!)7zxu`XwVO$3kwQ;=*{W|SyV z$i^T8kheF*8zL$(9QGPt^%*a8dJf%FsY>xxyQq#f6vNlp8bigq$UyjQ{@cD1?x|=a zv1mO|+9@3qn-S<`WZ{Bo!7ZC1#5L?mV~SL39mpIGIRZA;6)30-@wA?wZREmIKqF8a z)D5ZYDNbHVP&9RL+^E4KTO2GPDEh(q$!kxTeFFiM!sEqqEX$=z(=uk-t|XvuAA`pPjm=acJne)*x7KWao)qgO=z99as$%lvCT=lSSccnBQT- z@+kWJZYJH#ksf=R+4Tvf^c8+mUU zmGs{4fiip%dieMPBN z7w@Xp;jM=s;Pvrx7TAQ%%BP1cE=SP?PBNt(_B59PlP?8nWfsQk>@>62d0Z<@5@+zTh4uF-h1-q$LERs%i)$i$fT==Da_JLOC&+!MWk1d+{u@p>U&yx zvLI&BQ^Z0A6T<7ifl9iSb%#$Y*OHIH3S$oho1Xr1!0M z=LF;yx7#K6txS7yz@ua;cIh(GK4j3Y-f7tB#omon6g@uYLu%X!v+QII%+G+MlQA-< zBnry&_>)_^EtHu^d2}28wVmMy$ah0A5eg+ z$iqG=&#^7)s`U=elK~bw8N_~}YIHRijfVxI^bIyc3$biq)`g1NC$i*oUnZeWwYYof zZkL>jCbeaWQf=Kx=~A6hClir0#Kq#$uY$*HUn460@@jipN@tmv6#mLE{5u7Tyrvpx zZjwL95b+Hvnb`QjnmCea2IL$+0;flE? zh1Ylf4aM(A4L37ZF8s$Vxe5dhEcvg%0n{RfTG15PdI7JPZ5En)!+w_U+DBR1nmHs5 zP^PpS3n*@0l4T87YS_a5)rs`evE0SxEppZzkfjDO&%)2YJbl!h%k=U2B6J<7afF_Y zw*)n^!47L!e}A`+x`Hz`){&ar8`d*INy!+` zb#HQ)fG^MwgK)u)ou8s;v=hv{+|E?sLBWD%`hveNyV4JJ8!o33$%|$c_h|_N$4N6aV_sJod3jf=-8Vvvy3G_zNuHIt%G!Fcu8=krtwVQ&UEAm(C-2V< z&r0pxq|Xt1hw*&o<$A_iJdpL;)k^)H^1A|v(eAKHFI}UH^IXfdF`)bTnf?o;akr8f z{;{n!#!ZQqjq^MeDRU8=mkV3Z;8BYhyEZf~2fuiDW|(93u6-}(vB5_$4S8LRbeU=nz8FEPR(#o0=(hgG?Y5WInJC~Nw_(Qcw-&zLQ%2;=E?(Qu+8 zmK~>7Na-2bY6w+Zdn`{ce1Ka^KknYXIY*ZhDs027Z}GHTRVzRyLw`taLqWfPRkT56 z+^HfgOMj~&A72}AYFVEYEYkfz|FG9de+JOsO?=$|jstSz5N=tTb6!EKnFvZhzkIsX z*To`*m7Lwd!YsB3yLAn=V+po5LTvH8!^*ZKnw=sPCA|u#s{a6ow$vpD>U0hjxat#|Y683LvMP4> z;=Mqe%|IBu6~#vYais9WQKlMJ|?ae9OJc+IonJC%RW z#ZmsbX=*|BAYc#}*fe1vP1rwjRsPRE+yLIc#s7K#vgcZumiCeJU8Y=2$RS1y8vUz$ z90CjQ6)7XNIC*~7KIK`bXnh{l{HoMblh+J6C5x(SXM|clWzI-ym}>*~>T;QJ_g63s zmA6<%eP->cBonm)55~;b1L-UlCaey5dw&DF9tvwGZk-|M-r==b!+&By){^=lh49NHNCqX2om)+Zig8XFlUYH}<- zH8Yi~sYi~`YISQ!kJE;)H2eFlM;VyvCy5 z%UQlIrITjfa`Z#dtJQ?YJg^ZzD1awXBK5?cK}>|64+t#sj!BKo)0Wmn_=RWL^%}Ynlyhh5*3tzFsUhLhOI-eSg`;01!_?FwlzBs48&;7F6sj z*{#|f8vg|}&?f|&SrXXq7E(}6%f}~!dVo-ubb`K{3rE56r&YnOp|EUFH#+_L!U~1? zULgFO+R_|Wx;MEo;~<~TDlIUr4?Sw-S2VB-r>vTK@%BIOpNTc!XB&G_N+STlgzzN~ zkHoedeap^>k#{4=On*t_ik+cCLG*X1YCm$&rB7n7;F7rdrSB zLF;Hp4$J+ttYL%3#d7>XD&Ip_p6C$gE-UJ8H3_O*=$z*JW!WhZ{1($UhWjsk4A_l!Zmza z%q*{WaBDHEZtOpb>4scGT6Asu%ucg!)F6`mQNgiwiDN2cKIn1R;bCeXg^GlOhQIeX zRBAcKLDd1$Y7(T$*>sA&`!oq7p2*dC$lU8Ali0sy!`}zKT3zSaOR1HJOc~c!C@Gb` zi#FrDxsh737U=Lfbq|-;YJL9xEnUkZq)4|NEb%!7!}z4K^`66sjlzRQejiIM&!e!m z_Mx7P%#-5l<^lhFaP~o{z-jyJ*J(@EhzYC(PVxUfZ3!;BXm<5|g`}l%2L}|j{UsDP z*J&;v2-Ki@R1NS4Y(2qToUN`FD z+d#FpJbR3FEcir4VAa_zz9%Ej8fZUAw_e}Ky7})wjem(vPCoi0>zCN%_a~QyKgA~h zlWsEeKJ0V;Ux6Brub)5jD^SDO_d@%xK#l(or|ss)9Vr2{Yl=_cyTn&3p1lM$uexlr zW>v-;#i`8;cXa+fH9zy@N~Xy=@O&ks9*>bRVET7Szm0DsZrrXN9DGPJlmVQ!lsv|ilvWWxC1YI3^|lQ50p1!J zt<=jhj?0q}V;U#1QOZi-X9mw6=73wjW4cT9tm8CjzkVAn*C`Nk3En=hC_J9Rrb^dO zA<>Rq+dP(fuU5k>s(YQIk<0N)v&e{g3Y3~6|H8z}Qem3ba5V^(zn2Bkz!(B;R$AH< zg9Bzae+a>Z8j2Io$UI3c)}T8IVKl{cMlT|`OQ9dBHwp2^GM#x6MBsGQ5Dw_>n#pVN zC(wt?WP$m|?boI=`-|Lx$IGaQb2>0Gn>Lk8NE_8&!>mMO1HMH6<5-kk)DyY-#xr3BH~u z+=n`G_t(}ncv+)+)SY#0uL7~rj}4;14cIdu%+~0GW{ErX?fPJ3A0`-vXY-gw#)}*! zE!(RUZNIjzL&&p}Fk-Aro##0?C2AN6r@6ku#?T-dX8l94gCXzV3&lp6i`r?{L92zc zr{LptEO4fsYeKKge`7|t*Y9`p@O%9F7*!S?zby!QG^i6PR&IZK~{*ccP0KifBb&1fFcFA39Yn7oOgaW^i})yXh~fRCmsoiDh*l62Jk z+Q<40k@o0oxShu%j*p^)?#x3^3=sxLazMww8HN}(4$f?vuur@tWqy3f-a$7BG4sos z$ukKEUAg5$+!(LvohjjtG5#vW&z-Es-I5EV4h!it>L&P0&@(hd zveg{~v55zO>vnw?yaeAW>^=Kdc~aIpMQK%rbUkL~6*NX|``Y6U?w^1c_epIgWZ|x) zXY@VE+zly(umg-xrSVsFJ`?X}w9v+6TV>aQ1z`*cK0TP|C z$zUX|^3IQw;K16u#4!~LrmuqMPabAD&DgFOPPF%)bOqNlS*x7;b%nK?kblBBeLmd~ zc$Es-HQ_#3nV75j2h^SNQ~?27N;|JN*<{M9JwmAjqLq;Je84)f*^=CUA*ROp0T?S0$<+^dzaR3KX2+=Jhl-4I-4!kTo~DfofyDUeG_Puu@(DoiZuyHIK7gQfbLdWycx)_YVTmrXfxw{PYi`G5N$eyR`*(w|)NRfswFk%CQ) zZ7v;TAxXbUS%deFRaHxRgVVB5Pt;Z-3YHWchR5%$A-rY({eyD9C_ z;vu`pqTo{oem=NuB5v`>-et$X*kAo!;hyj)$&T{hi1YusKA!;AXOI7^&x^Q9VE!Qk zCJh2=Wp&Hpq%}Q3M}-6lX=&oacsu?vbF5F&uu6`lQjC3=m;q_SwF6|6HLv+m1BRi{ z$ZZL!>@u?6s>ifMjWZ0NDsN8q`Snd8LMUgYd<5nx9j)WU4mnn1ag9V9(4!FxOt3CC z2A43!r+VG54?CN7L+XlXU@I++Ma!adE7&ESG1A%QXAK9oJ^OPBYEZYpK&lQ-f*gmH zw2Rhsy2F;w-0p)e`Ep7D!9>`=>nq)B7^CIqQc8CH-PIXb5AnP#PY8b2trzO;k|b*M z9LRUdU3Jq%D@Z*}@*0wv_p_Y9 z-cM5di`w0Xglk=JGCF={0iVbQgdM|pH#X2!$LPVB5;y7fDW-rqA49Z4cc3`$fn`N6u@f zB}0FDYigfh_*xk)`~6#z*bcOE!=4P*I!*SnJKvOFmT}HBd!M_9=^2Hyc-h@A_P}l& za1~O-I(Lam0_GcuYeG*tIUWBHkeapJ-Pvt3Zq}-FSgrreREXeeq}6sX>W;PIUAwox!;te-2@}uq8PuK?l9RJ%A#rufKdXpR zW|SLPXS=!Hn*$L2wekEc=;m-CBnvA^wTYDc@L?hsBByn3L`HyziGSn~U{Rz~y<&$+ z)km_e8N(3ulp55M^Zi2-!>0}%GSH)cL7i(?6sfgMfwuCgLq&0OVA`%%AkK9fgf}BM z7E&XRYbOD2)hs9tfdiv4k_^6Bh!^)u?I~28vJ$ec`7B$+p44%ghDPiiZo2(aV`6cmgnr!f%@+x9OnN{(Uc3HgsfPohu^eU!K?5m~_ExajIf^uGk)<1xCB+w;GPD`Fr>j{B7 z1aP6?p#4}SWF=)PD)<;gHDH%V4cBzWkRTRz;${Z$!SGg%(jhZR*?1%jYR`}4FfcpZ zg=K4x@eM|q_-i|XV(~L0k_r_T!`sK3BvGSXo^R62nr+O`@s<8DTm8@6!1P!Gnb{U+&@UD} z?9iR*wt%hBzl#(cF~?hg%)fdsLz8`586kcQdn>{+IYoBTdT5)d{`?X)oA_jP!G*U?JUPz+n?L!{e;;5jCZ7j`X%mqmeb~^=eHNq44(Wk zOCR~>v?8v{6aV#I+;WQy+s7YSU!T7-dwbHPjxq1?&$)RH7$+|O7$>O$OWOdn#I!7r z#|m$4!^>xzR5c!ufD8*~viUe7sZ8~{`Y#d>H4)t{Scevh~AqzFo5KM{1HC~v8 z?q_X$x(n`oV2fpFvN&GaGw>$V$$0BI){MBwlj!bJNpj8OHJ(quT=1;aR4g+~FxGrq zP@ut3u??jv{sye9cCi3M21I25(93iOXJjol)TU?8aQsnu zk|7ipRW8CH&IL26%3(RxOFwa$dm1(y<4)bTpHv#sIzQP*YADX*nc6nH7BHhwj@5MN zvZ}liw`Vct+-nIv`1O=x_h%v3_En+^gp`sr?o&{4+u$j}izU z;R>Rk<4hmr-DJ;Ee3Z{Cy0y8Fyc?#68u6#aUAMc1Fd5iZSG4qAATwi2y#rJixHwSM zl7|^rkZcDB1f|GllBJj8yub~oM%I%xEY0mc-HkR#PJQ6MZ3PcPNF)X1<|T8)475ot zB{%X$;Hhpb<)nHuHKW`gxGB1ZyWNv}Mz83wYC+vPL>mPT;~uYO8K$Iv0>jAD{@9qr zMDyD&-`FEQ$!^0Ul%csW>?+FXyOSFdD76oweFG`iwQIi}K%J}w0tF3P)3ac*Ej!%3 zdU4x%GrYyKYK{&)30ZiRa{Lw2WTV{L9&OYP9>Bp$CnZR?-s;JH$$pXDOegPf5S#(m z^0ZtV=oEm>Ol_sxC{cKiQCy9EUi@tfi$+o=YMNR-zGN}_4(`s;aH@aUk{9u~Wcdyms&Zo{Z*E*-_efD(j@v4r zetsK32&2FYh95#;*Y+Z)D4KsNls(@KXE1w>ocj)P=hkW4ZUO1W=VAjgm@dqDkjYSR z{*CK!oNboK1U6TSbB{ukon6}!ujCwPj6!2Ni%rrfmqx}|P&f6Eq2o3tc~O&96fOj@ z5H1jF#|x1<+e+{bwGQ6Q9)w2GxOP4h!@y#eGaE~HH>+%{Cgc{j51E+va)dW(&gGx*A;QS$W6ERIB0DOMC$)&(X2hcP#_d z;2^(rsS$#LzZ^u+sH;Ws!lsnOeqFJdCEwzf1;6u(*>#XD-=IInV`8Yf9YeszcjI)e zn1((W$-C4ht9vUUrY9U=jMi5>ly*JH{xFGc<76zE(WB!d7c)AO5Vlz{V0>#cz5LxK zTZ~xSK`pZVep718fS?QVml+Og!nbAwNZM!D{{3Bd*{r>}>9%2!*;r)!7p*7)nMF;h zOcKk66Oio_#~2u#z6l6j?HE}ks?A+vdj+IR5#6VxX-(!v;6aNUj_HPosjoY|SYDn=SFs~xKTZ3q1DZ4EWknSjr~ZvIaZxe6FVj{g}$W9436 zVEcr}t8oLvd{N-W0un99YP{0Iy-n_UMOt^YgaW5qs?6OG+T>uy_sXGbQZ2ZHH0vd; zCr=ye$d=(xFXo0WWy?k8%0X@ka}}Noi@$E>9e1DR75n^(CdXsX*S4pTD6+^X7zCiI zFoJ{B*gfpqOCDA1#0L!>TSlwFc?06NWAOg#)J*0Zj>Y4aZB1B z=mpCNG5m4S1Thudy_S;{N{w+tI}{mLSzse2cgD)C?l?|TujK2dJx*_*&gbMYQUpN> zn5HFWOCt`(U`n}}Npjdl5H{)=2kipfvi8S0+eK!{51JRmG`5@Ji<@gkP4_c&twVLQ zXs2nGfg+FCn>Yg3E1;3piudnDL_a)m*rS?j&jGf2HGrC>2ZBuCwP|EGlhq0@Y{VkI z3U4^3=1_6Q^TRkhf?7oUygw8~3s3TA`T=m-kS>;O*A27CR@{zx<;nFjj2=+riF9Id zp_bK^lRV4TP(FnclNCpGtCqZ|XO^`#$zrrl^kL*7`_}*OF?2BfcEaX^%JfMdev^D~ znA?&bnM;TW1u(=76@vqKW3~zd^N63ig)@#(K80yZS;XoRJ28s-i`-Q3zEnge2u{meB*gH|H@8xS}2pAkNJTW7s|!cRG4RowwgW zSY8d_@|fOs+2JqTrAY&!LWW7P`S7BIWdVIqE_1Y^MrqAk5?i_qU?^fFcec=&fCzS- zIbQz3ETf!xJZA5%Zz!TM8_Y-R_0vYpyo)gI2BG`tX74@oC9D%056sNR(fgS zyruP85EzD7cm0Jz(6dH$?izgHAe{zi06iYZgEi8ZdSecoUrTo72VpBWS8mzx`cG}t z3xliQTn##7{vP)VpZ(+gf=b4%n@Aj^Ie}?GTHPNF>kEe)P z`CIs3iCNa{p_*3Z@^M_u@om$UaXx=D@$RmW7aK}2y=w?Hj~V{^v_m8RZh%YQ4DX+G zhdfh?*2uWjBfGAQ!)9Br>^u%qkUTs3d&@$84ElU7tcES-cB8}8V$${6QGPc@-bGPCWj_hj#8(ZHP>QLL$L=SBU>s9mKVLBWdHuUbIo zmadOltEDmCa;dx^$^L~|DY(Gja%Zz;s37W0SQPCm-DU&)IrfjR`b#I%-JVmdLnDTL zzj9`wh7Po4MW7zk{o1_s)lzql9z(YYi_AcxAJ=2rMoO?%+OtT^`7~R$uZ6KOKHgg zGn|3~@2$9uuKM!lH7hZZXL967rr4BdCPiCGSjS;Mufo^9+@+HG0O~oi!duI^(9y@XM8R)EXy?SZo&XAzjWtaoYb_S6PHM;<`Qx(x3;V=gt$}9 z!ic^i-oN+x%D520%z-F7goMl4SAlBtfj+(e>p8M0%Ezg)m}r z{4Ib}MmLn0z`x3jLbs1#QXU4W^hw=mq~D}P-Q2R+YKtNF5+Pk~l&;<0i_)I#aff=y zPuFtH7j-`=GXFGuw5nz})ZY+l?ix+Y-&+R=9353|EEAXrpHBA?xgPsQSeWi@imQkZ z;3$0RHXQV>OdKIi76VNg=QI3Ortp!(=LolWhyBfmoI-_%$en^7fU^f_vi71JVdS-d zG^wS~xUQ8kR9(d>gB6Ran1#NqHh{txjo{4vS%}uycR?UZg=Z%;AOb+p0=S2V7&D_b&X>TW2EIV;wO>{0iy%%yg(b#?vgJZUMkDWvw0&G|+n z!XDF?Ol1*<1;YUO?9_BryD=+Z{1j_)CITNR~-#I2ny z2b)(PrmQq{R(LP<+xq2M<>vRM{{`KOur_eVDR=yv(^i{|$T4bjn0sxqzmXXp!>Tk| z$+$|Ymd3KLk#+*Jcdb-j`TE`Z>wYk9?H$!joV z_w4$@janoFG3XV<>zVfJvP5<)BU6*hagC9gYXl)@3k^38hb2mz=wy&}~I-s8Oso zz&z3CtKK!5ze zK%dR7nL>e914;V;daV!8EyT@vX+v#<7!2+)@M2r02Z0P{Ra^8UB_?SgH!GfL;k|ny z8VCQ9BVezn2X|Hm_N!X;gJaD~FK8nqa=XIXdf4h=$m8;(b!`JN)+SsLlj5&v!*{Q8 zs_nVp7?{txABWbqt0=Z~$i*e85bg{nv|hd(DWgM8YP%6GLb0f=b^|PO-}W(>74vU8 zp-~ON2q$v!Z30T0XYbs@X;I1uSl@yR&ay7=W^=`X1U>FM30EGx_l=WLDA;5dnPmYw zuJhH*twW;Z`H72uhXxA!@Y7S*2ZtxIt@A8|@RP_16Bp(fzfR~lk|#aqfyzqvr*U~4 zO7o<)G#+E|ov9FoLU0|g49J!irewl^dG%c~3;mZ#!asp9GzbBH4FQHUY5_z(>)`&A zS3&8%cQ~swy#m-+|2s&lYarpyv5m&8y;`1Wjh+gIck}92z{YyOD*8gX#;+i)gx6g_ z|Lo0;MQGIj3ex(YHr5Oav!G)>xkgs!tnZzPyFw5D6{MB=)Hu-lfZ);TtPiixUR$2> zk2jz7jYj1 zzI$+P`%`0}sN=)GCG#CG{v(-hu8sCySA1dR$5(gHoU!@y;=d*HAAY<%|1Zh><<%EH zy}5nj@)6rTUB4vrS2rEL_%F%)Z|@U`CfRf5osahZOERxN_C)wE$$VJQ#1^D+%S8Th z_g}gK)I&g@*#ht?xR#-GqX=ZZn0`C{X|YrN-Kl-6KfP>-HSB*mS>!ksKds61~)@J|^HmH9<@Dm7oAzNWy6&u$2 z{7_c&ApKzWr&o*P()jC-9@?p&$SB?Yck9dgBCn4Fh4wltpVXBHheg*H14SLp@YR+L zjb&k$uUmAZhF-O{Tzb`-T^r}|`nb|^q3U&8`|PWPSUJH$-6U& zZ%_4nF?f6WI@;O#l+qNCWj0tmczgEl;m_9Xn*2BKIyBbTyz87c?pV?>(R|#7HC6HE z{U7@edB43dxA%cf*ZlJ>`@3pyzp*|0`L&f=k`nb)Vq*sIXFMQryzjg2J z(kACO){aM4U;XsgNG@W{+-Q;hJA+aGr>%~+0zbb>@8E4d@oX$8^U?G1x`ZX4Zbux@ zw!RyEbdUL+xQ-i*w-T=ww>(JK`w?|A?L{*6LB{8W6V#i#kb7I7NETL{nUIzZWKI^X z+MRh*=Akn=RUGo?;epc4?1o+tH3c8@i8Qb%}U& z^3Eml<8jNhI6ytS(90`kf654{1XF7?3T4c})$hikt7wb;S-$F2viDQkA#+Ptvh z_MOZR`XBD+Z?b#&_`t%&`In2Aw|#m0JACg~weH!y-{!nY3qPtJg)RKu+*Pvn>({3y zKfZsytlsG*{AeZspUGsx&aD$^mOpM-krtf^T4oM%r3$lae&n60T2 zhQv$5m(+v5pcGgqO=@n=Dkt=-cTpQ7UnFI@y?o}MzyE2Z?n2pTH;RLw)D0hjE#^7{ z0?kbCn5ZW%^Su-9yn^(GD8lwkck6S$g&T@C5-*0HL*(&xMAM@0T+iwsZ{igPY6=X4 zK69LHeD`g~Z!~(xX#etzw|)0?^q+@6dN9$m;&H2(X~@oja-($$QFM$MD{mF|wQp%z zIr-(`xWUdyhccaOp^L{qdHOpf#WvtKSop3`);Hl2kH?tzJGCAP`D$Hpx|ev@HRf9B zq{D#^_hYy0I)7>t(fQXQbBJR?gL7iUA<(^*Tw| zTs`SV3upPz$i7{34HWHG?*Hh48m+i6*Yy7<8|(Tlxy$9;svN>`UU0`Fig*963PJl*`q3yFB1>|V<423*-vXrA^Ps~A5i<4d0=)FYj#0 zV1RW;nMf{b5-PNtk&FBxmMx})jCd8+ct*hRzSoKBk{rd>dZyDl(SztYA$qT0tFr*l1iMg>{+WhHf7oXjc2V*j z8@q8O1CmvGks7{@Jz7y&IX$LenW@PXCXajN;+|b^=w}jKWfMD&7U0TdKv4%p_ot2Z zpG6&Mt1jKbaYc)5USo1U=);Mv@e*R9PHNKxgurL~Zi-gFsMs)f$Y}YH@X-pmX3>Mk zCBj?{G!v{XU&RXt3hp@|k@lkQ$DFnFRVI;JlMMkO&T_D}v3eu^Y_~?Z{I7Ns1v>QM z1S2`#jfw*o8fObM1-iR!PN@BgHTxb8BOn+%HB77*JD_aofu7u#fWiwf?DZE`J-wdA zM?J2xVS=gemFbnba9p)qtnvE#4!5;!eFu*?J^AZ_1X3x0AGn-j-cy6NdU&|!$l5q; z0VbhQ4~~nQXJV(UlUq_EW@A8XTD9o&@|Jrr<4Pf>>&^3tZ%YpMqvjUwXv&`w8v$v% zN|l+pT05^UT$UZ@=)KDNA$4a>Q z;q9mu{aNRNLEe#u)Iz ze(*XVQ(ll7#)S)jEt!I!ybTJLqrNG1;dWs7LT$pibFiJEAdDIup+=aX^7GSC^}^g% zyL{l=m;Ay{L5WDT!#6L+9|_$mo!FSK)CB>K?GR9f3N;n`GXpsx6`9f^+cJlO-u63) zDEd7Fq)-d0Lh(z^MVX-rPchIJopv}qFRYDO7mC&RlT?`JQLKWkL%YWYnxgN`7d;p# zeneUqV!98c-1nwa_gVbD(~^B5qT;s$`@VsS)h&LHEB8H(FZobeQU%)=RJZSAd`Ue> zzQn!cW2dw*OO86vhrKHL+^GRHZkRRg`^-=f5)_6($Y8Z1SPgeQC579;aXaNoOnR^Y zg}$mVgln4Hfq``R`*(8P6ky!Kd01En7^94Ke^E-xMK4uBWBel><96K+0pVnMIu-Fh zkmV$T1`xRMZp?4?%x>>tIeyUZh5(ihgfV=(0`@5ggNc7XmiZ%OM`Wwt zo(?EW2*Jpc23v|0N|?DSRzN<`)}EQ&0W%sfPbKf&elAnElUK7GKNkcFmxEnXk#To6 z88gcb&sUCz8lTaJ%l$#i=IsoLd$m>24TFBwt$uq!sBnJ>kQWahhI8%V1sovrJojQ{ z_10VIuJ+&x=}xW!wL$=f%fWpz@N{#{d5Nad9~7;O$y5tkYWNBRNu%`fTfm98hq@S~m3K4J!I7YwgaW&auFjoE6;gs45`}5eGg0-dga9cIRkqI?WgKbhJ(=Qr#AJtF}=kN_QYK9vP z09Db2)|sVvg95jLnZRC%k|TT1t8M~Oa1CARfW9w9Trf^4X8|UuY2V$X4 z0{t%pw&5528X&~_ghy*#5}|I*HFzi@mPQ4tKi-7=zWu?aB=1w|_}J^r!9dbREEX0&#CE_l!1}??xHaQ`Q{&vUDU!kMX$8MkxJk$gM6&YPs-j z@jJ1@%J$C@n2-&BqdYSo;6cV?xjt}u3&r&tL7iv%-SheI9_&A_=Pm%Fbp9tsDflmp zve?`ka5tVRrE8nz0II~Xfj&101W$3a5DXS+=$cTo=Svx*{RiwcI8gyqG?`gMa!-t# z?k)?AbAfr5Gnz*ZY(%pyn0Z%Kk`yz&1}qFDmzcj`Hm6791|e? zGOaruaAWtWQRqMr$^*CT+lZ*hB$V#JK84CW9$wGZoO@Yw%r8&N)+zfg=9zEgl@f=| zThC2{uLUL_1S$A2S4a+FwwLiij-@R(ywUUHy$qgZs0Ewib;5w&K#iDJxALRlWKKkz zS_F@A(|dez6MZPsv`i0f2Q`|uvU zGl)oXlUUOvLMu2jrFuohFSkptAu%@aDqy4;7P%YsR95{GA6l>BodTpFsog}fqARN^ z?niRJJJc&~dcXN@8Q==y>my9rKkcu`xLDY8v(*{3a4P!!8C_~rB2ZpE4xY)~U@$mt zp11-Hs0P1DX9aN;?U4xL(mA*$ONfER)r5gYCu=2B`Q-i86MVp!jrY&3hJUX@nSouz z7ImqQSf$|#)xzv6Oo@|RLErt+eUs$)Y4ia+zg@&NTC-aI3~5W6i!kD(t0lw=eHDs& z@$1ljJ!2GJ1UO(6`Aj-@S4<~-u7!nPLa6mTD{;VCgd}H0UNt%fF1 zYZg9!La<1SGTWAtka3pPs&}bzMnDu>iu?=C=m7!`dM#zO7LCu*+)|h*-hKhoXMN;Pf zd{J(J$sqc_-e^3750n3-$Sm>mEt3to7{baV(kZGLuin7mc<4yKHd}TqYoY~%r4Shy z)A~tM$e^S`N9F|xxh%`1^Ig^xav;uLTW?KN`}TTXzHN!I?=if^t>#rbo%V#LTaLGA z6-W8LOn<{Fh`3TvY><#7;(q&-Y+#jWBHSbIJqK4iAI^w$ z4|`PbyTiWajf{7goOMa#QwuyUMmXZXv|>x|Q}Xd<&&eUF1v<$JaW=kn{eDCs{^)ED z0EH^ zRFUIPywdr33s5Zl>E+WBCc!te+FRm?vwQ{puN)q zoh>m&xwHO4ZASQ2ON3kK=?0FQ5lqwL69L5DlzII&Q*SlyS|1DU!%Fnn3kmD1)qegG zNdaOny7eF#aZMl5c%_065GW%lxONuDYho(=nEsd$#58 z!`O^89q{c^c&)pIF7HNg_LL{B%U|7rS%15G)(yNt@DfWwbkvP*jWG8%NRYleQ_>4> zxoT{~He#XsGo3ercB7Nq0Z9a-D0MsJHwg<2P;Dg)>s==h$FjApJei9nH*%d*CbuX?qAaAecWnGl_{|Oo2_~lV@ z+=N(T)2v;(hoXJ54{tsf_t7jU%MO;cU^D&o4Z#;I2|S4|+)uBrbc(Noke{-lZj1I$ zd0f4G(yMJWpj)rNy28mF%4;`Vt;;I{6rHlhsdK7L=?fPYO;k+a`&Sbt;U+@C6|Mef z=l&R0L9s$lgo`?t-D{3T-%=UA{k#(WP@+S4I$%^$Yg?MF(tOBT2euTWmd=Q@^ma+; zp&sXl&Z{$0xKOjHOkyr*N;@x9I@l%1cT7btzr127bwM28MZE93WrH574}{cr1lw3& zmQ4jwCofnQOckswjl!>Rb^jx|zMzIwq5p?l-<~8_d{B0M@wv{vhvl}o`0PU?yJ&rf zdq)b_CYlAeH*@TFyfDksEB%eb86dCdMMua7_V0qo0s&T&k8v}YFE{%c+Yva#M84;* z&PxZU8~i`)y?Hd$efLiN5b4Z_us4BCYzJGepeQbCd{;G8A{d)bwH2I9`%!**>B(i-@1u1qH{R3 z&~7Fe|7;q0nfKNaV>T!sLIgeLWM{k1^ivbf_V^)I)_NnibC$RUSd0sCjsLb&VDa!e ze*~~TsZaaIyoRY=FZr)e2(OScF#7NSS*7uvEoNCCkOitu9Ew!DQp2&h&(%7a$^!VT>rhM|r}rQvJIeFWjeEfsD0ak=5~8$#tZ8>d$P+r`!op2=qabtZ$G zdeLd$jzPERuz7bK*AnkU!!Uh!RYw5K=J@|-Hi!ILR?ot~?l4a><66T|4<9xb*Yyk5 zH)D7t$nBx@)r}*EQAMP&k<%*R@s`#)EM?Rjd5-9S{PPOV(|NV@dQ6uqAYNlb=T{k< z$khnJqc~6Bo#H~%ZcTh~{YZdx23n>&H8VO4l zs23G;)$*qoDpH8c(~V$8UD>U$Z9!_)l(RuTU}AKa`GFnf2xfJLJ>LW6^QK9 zE9iKRSL%Pe(`=&Ia6Mi`)G4I9;0jI3x4XD%Yw?BqN*alTCVrMwW2l=V>1SxfZYDew< zgF82_4Dj>?mK&L|LBYKSj%T_pI z*haIi#U2ux#^R-ZP>h!oKvAitO8W6S6>VG?hGWfmbM033Ze88H#qSJ%YMF5T{EH$J zJ8FsUtI{ss^SvxAVQ8u&C90@JCGbX5t;;& zL!izDYfq^^Uv()wL&1C+2>B&S#YJ%xzt$U+X$+7!qR}NblxLO)#YM20wEc-hO3;}D z2`WRU-d|$-3}D_328~ z>i#;#1s>xGueh5DS%Z2h&6{*9xuS>IsNF9Ekn9Qhe!Xwb>BI0GIk+DSy&1e1z?V1X znTS^)iqSWODD!eY)eqI_hnY-Lb$(~?LeK92VC8A7;g`n`{SrzAGBUJ+n$0)L)~=F5 z3n(oA3feD^4R+#O6?aye9G)u^Ld}zX$>Kku?Xq1j8k#GPH=_S0B3&D(QnqZBAmJQkYH7hyy8dLaFn_!}{^`UMU4Xc@~GR4Ea1k zmM^K1R=q!c0*3wUY-Ywq#E@@MWOMMct^Guq7L(DJZ#D(Vzs7VWv5IL^)3Q~EXx3lu z17_4->5W5_xk+YP<0KO1P^RWhN>;hpUC-%x-+Nm}$TjF^b5^H|R;k)FZpzHG>~k52 ze>9zG9YHR8r-}+*LTh)Gv#l$~6%Oiz7GK2P&4i)xSw<)Ip)}^&dl-uqQ1- z-pqCgT-=i)l+2&}NziAn!s#DeoM+V@fqbQR@fL(2yGA+%jvWuXmF8)@w@t69*hOGW zFFL%9k59`s#(7e-pUW3~(hh75hr?&PFBlgJ=S zal`c*?CO&D4}{yVY(>^AF15_Q64&_H7V97`??%yswrA>ZNNBRvYIZsIR9rxzbZhMT zbW$g&Z@tuZJ@XXFQGM@ADU9yzwl-s3-}7zV>)Qtg z9^g6M1}Cn1P6Qz<TWiCPNj2ml@bPkwYPc+Y71@8Ds7`a6;8rC_{A2(^*$p!*$Vd zkA=ocXh)=l4BzQ*F&9w(Wg~wx9(&~__x_a<wpby%nNEPlBSfwupQoM2|cu zL(SEa*iZZ8hM-=vbZnBaJ>VKs90;|f5d|*S`K0lPtbtXm$G zd3)0`kLsw}t2pfh4et(RsM^95`39TTtp=f&?-iU=^L`fZI39t~!;}Vp-TJx$IEfZj zF2~duRPJ_6GdQt*yz@+DT(4n$Rm7*MofZ3FIaMdqzpCu4&hj&estGZF6t%TrKR=@O z*l1Q%DLdy9pHvh%tXR4%>69~xbQ`0wsuE{1sSS*kh)iX_gqN&x%_vT7ebk3m8dMGb zID@0aWHR{%-q@bql?2tWiw@n;+j2k*NNONN@lpEJLd+VLX;E+&g#aiN%N1dL@;}6Cla^X1IAgh4q6rvVz;f*^~4wa#wTFIdH z;C6||wdI_+wa4{iW3ce>_P0r1P%Rn!@zjkGpxjW45=m(Q3Zmq77|c86t2^bM zn!J_tE63R}w*OA)K6A@-CFs+3%*VqF@qrE3g6}^}ymox*;k9ejS*m#^UdHgc!GAdM zm?}knF1cQ~UGfLa>=CMN%#7Lbt$t1j6>u3&Y`*cW=b|*sxsWn0mYF5g?ev=WYlzg% zHX8wy93}aTHkkC27?#;5{$niYm5x~;%Im8!7xyDBwsBt?0sb)A6Ox{r=m<=-mxB(G zo2K^O$%fbAfLZydQ{|fkvV)Vr@{ceXD;5!B?R%SYLZEaVWG{!P@wO#oposoN7$vHd z!5T~NoQaTGcQq8PUXR|~K|wqYP#78!WvV1lOtiRgy%Vf7l^sNkn>^1MBgwM*DzV!U zpKHL@Zq{W*hf%O7y+>r2@}vj>j#O~_R}19Bz&sRTcAtIEDMm3l#7cXJh=G{9g_#}G zAi*?^v*ndboG~fkw6yMHIR#5l`P#|;Eo^&W9q*P5Q2wgo3`@J1L6r?t;2p)*Tbu{C zP72Fjr@TyW1Js%TqkC$W7i&3%gJIeuJ4msiq*C(lu^D(585< z9OX`>pM>6?nZt;Obz=BB>>9Z?Dh0+Z?C%CLa0YEXWvT0m$2+2t1~x-7;aG>|l+Ob4 zQ*Od-U6c4v5f{%B+adqHI{q)0Mb+S);`8r21vCZ%d+#rV)rA&YqWb2cQ1f#`;L4!|j9h;VuiHO{_#IheMwJb>Z z8l?J}e@oeZf5Z}{PXFFn(_2f`rwzTDY-MwZmvS!046No`ZX7Sh_+_hcC>1Byn1M=i zosXiZ8CK}s#gV?U*IeS1ZotO^A$H;-&@K<(LrN3F!n+!ml2rE9iz?F_2lJ9044NCx zTI(wEYE?tWADRSTx!x5G-qNMWUJr~vNc(N~-2Uv>!3%K^(O$XLqgUVWec7X8VVeKN zCgByg-e>2oUtR33NA2HM-luFlwDkH#s_ynvKMzfPo=+~?o~riq``MSVk4xlte0g6Q zyKaIB)q1t4`bQwp@e%%?N~z8GgktL3ExcirN|eag$cNqUCFNy}QZqKdQ@9AN&Im_@ zx))Jk08GqK;p*-n!_4IlQxvys*Y1go4+8$+VS7L^AuOF>fnq|WP|^043KdNBGoT>c zvG*T*jtv?=lfT^7q8tBErf`VpCfi8e(u`hIEouh+%T6Kagp7c*=vw{swJQFQ%Kb{d z+WYOUnY~2No>BnsmTO9UX9A^ss0^{=4b;n&wovYI2QT4NzmlanW&;#G1!WQnnt_&m zzcQs7b7#`oF$l3v;9X)3(e6ho;JL-L#z{v34v3XR`fs_4bsD-uTbf^>2MXZ*D?jNV+JxNf|6Tn05bK-YhrPb|H zRK9gwb23+7_p*}VLn`*N*F>K}590#Wm|o*te4rN0KoQ_7(uO0u#wE&0c4274!tO#$ zh#I!I*m;%b;$CPtX}>YG%V74VtQDcH{BIeg+iVTxV($*eIBIw}nq{e%Fti6Q1O3KK zTnKo6;`MprSG1L$|>xqqbF2;Z7BD#LdS}DP;G0z@5KQ; z7mj*RI}PJS@dOLope6JAOe0PnFr-%SaD({x!E&=fuakwfKD+rDhF;UKI|iD%*)kDA zkLWiUKVtB6k;{K|%w1Ui(EaVh@<$QU^e1?y-1X6b1(@xDHu@SeRicB?uFA4z#YS)Y z`@DM{72Jp!O{iOp@NW);%~+5sEZ*_zfW{(1Cm{ZfewiFX3ydtwP#rzaDERgxPJj0) z6;0fjq1zuKEkQ7~%!*o}2f~m)cE(NIxSn?RaPxf6sx%I)BiN1DA=svIP%%S}B1Bo6 zZ+EX+cMQR-PI-9{?pgy#CmazcS*W4*n-eoepU}KzPp4s4UV(H8JP|W`?`W#Og~jSE zJ9sG&xU!3wyBa?o3_$yJ&#-`t?p`sM)v9)2#5mIg8SOYoZ=MbWdgG}ese>mbcqe9) zulHcrQN@IAcJa<0Y|=SHhTiyiJpm)HH>p;mqkL<~(e_iJAg@+$wezjc323q(i9;}1 zjlD^mk+x~ccrEXZOgmgny`G!#%*vZ1_wzgitlI#H96~8e*4}{d9PS6Pey*LCe%$BQ z^%LYwL(Y(?v+x zsSRpcB}dx+p@xil=5LQbfYrCyO1`pR^Rr2b|3gZW0P$NxAao+Bh1Ze=R+L^DdXyA# z1Y`ybU6f5MgTeEsGp+n*gWJ`qsprUmjVKO5Xvp!6dzgirjFqw*lG;=9#Y(e(h?vk! z%YJ_bx~3uYLSFQV+eB)PRT5Punv%1NRY;%(U9c2P8+fp}(iTZQtD-ylUc@V?>Dylr zT<{6LKD#JopC;o59K;C^#9+_qNF4G>(X+p=){jpKsi+p1|jC8)$l-YhfSZPl>%dBo5$ zvn-{JUBZ`nHFl{U9jg1@-Pyb?@WRIB{e$C`w8q!xAAkG!Y$IQHeU*1-?CT9Dm9sDW zaE}dYtaYm%pD;|!P2ctKgkek1%z-?8Ow?GdVG+r-anE7Oq2FN^+>|@`D5=K$ES+>; zKP~%+y<-%r-bO4vSjrpj3PsA(yrsNQ4VemW3de-$`nW|0XoQUr7u+_CBcV z|4Urp|4zau`9!w6z&-jpW@3VE5)N1(3gHG)DH z4XkAT1vh9Bl40KnV)OCM#?;UdPthz5ZqOmcea<6LL}B8FNZ12?B45W;0#_ku%WjXXw-j zlnpaO#4FRi(&c-M=phwP4l?Dmm@WLw!$j{4Wsbxv6S+pc_SVS`yo4&;*EPTZ-hzG_U94X#au>6Z5w!jM%xj>3_NFxh6&-_GZ8vpqw5_rljt?* zob;@u>C**Dtexpu+A*iXS8aYWnIvbcUOphuwo^%-Ogw@64_Vaz4r|houya89z{ta` z8XsZ>P&hqfZUBtalY6L$y`fZuc^sQob@-Oqpy<#h3f%~ZVsiAgH76X^4t#ysqXZz; zZzbJ9F#zK_^N8)WCOMBv^&1H}_Q*K#-YSX#U`22(K^12=OM^lVIfjZ=XMJWn1O5JppjZ_ zCfln?>S!>MMurlmAC8pq z1eX9rd2`<4Sch)T9p3RQ++JxIm)MFld;Uh=&j6lL_WsBnR-aTB2lZVgDhpG6Z2QV^E!0TF*y#3{f~|?v>rrpm zyk)j@zkK}q-k85|K@!nXmM_F4C<4O`h3mzzV78Lm*|JkAto%jP!NQv{O6G7GIrFUa zJkLx;pCMhuSE9VqNXk#?S|aj$W#qO{%rmGQjbd=gtac{ra5)uf)yzfJPRsHn4h|zs znDEZItQ2ZLVF{3auF<1iG2KT}@H&HFLR0r>-+lj9$knFwYH!V>J=DZzKIDGDMemlv z=FAH$&cw=Ci9HoRf8rS?<$`?;eQVXstMozczNxTRt%P6dwDiZq(en}0#+QH70*Q}$ zvT$AG-euP-&zlw_{fHe|{{6(z^c?~7meHE4l6lbwm<-&{5^O+ClW92HUJdJIfRgDs z-gPt)m#rXnAV zfE|b0-{AlT0zi!aC$ictbN5KGLDn<9OA&@!N_G6kYeV(^PT)$@TrSsg__C^lcuvG% zMz$Qz$Z>e+)9h&zAgi0Z&H=9C@2F|#yyLZlfW{BND0W2jmzHnQWL9^k$!PdfH?^T{ zEp_!6ra_P{sodM?qz2IM7VfMdkoOw$y^KL;$~f{__oLahQw4GxLd%D+J7yo{3VsS3 zxQyv11{H532n%6-*|J_3yC1v9inP=WAp@^!v~x~@?zZ=Wzuj%VhNYN*#oR|m063n6 zTY}3wfa7r{$jnQlB`!sJ;^hEF%b#Lp>AV=V{v!+|?A;QK)75Op8=WTEaL>SiHTtm`nv})kK=A zeWD%~u9~zk7|<|6_S4}I7aP2wjtR~5 zU7zW^Kjk3Renw#9g4ez~J>%)_Mi~89|3HW0$c6%}fh9I%U!m^|HG=OuCC}Wuwt9jM z^SVsbEg<~a*he{T+jobpEjF+U^DQgaeYW*}#E}&G7%>YkKr&?&)?-CpA}B>TqQ#6j4$8|jTkCrM8dq95p|A#>fRJ9K z>!e^JX15o%oyiK4l?WJZir)(vUUYR88g!Sx$7JEo>nmaYgQ#JG3GvSmsM(ckd&@B?&j@_S~u`8ejuZb z&L0BL_md^!i2)V5e5em>_lm$OU6+Q1!q5|$(D8O%%7{i ze9QtE3#GwUg*;x8@y4(Le65nCPpZ@XsF#H!PdMrnuQDNNTKquD7+&mpIGM)b7Iu&Yo6tcGTqy@93tPm%nDd!tKKRYef|b z6GM(c*8iO?mA2gVpMGPIc>q2_vET@4i2ZyM4G;PP{&=<0mm%+OFSdZpYLb=?#!w!7 zgp$J}gV4g)jB@LJZ;ctPk+)A$(o5dI`FuuvnxQMd_N{s2y?R8cl0N#fk$0op`CWj~ z{hEO@fqjD!&VCb=mZ+OKhiOVNkJ|OuZnCA7;GSI7|4V6vRziGsL-Wm}6Ve@Ir(6K4 z65_Ui4ILEdYUcbaTl)W;S^d91LMK~yKmV_6>D*{TcgV-rw^KbYUf;0%_3`t*yC$i> zzx?=m_Ql=JM>em_|NiwYh%@rs@T^r`W2WhZG2S{^e0=&%KAS;*8b3K z=1wNPZk($+{MAs^IM`o1im)A=w-~1dcv0{>+`fSX8N2`rU@gJ-u@A@vJ%goriFC*4 zy@NFo5bqGsh6x%&`Q##A=2+s2mpwj0FYK0XgC7^S`0RuW`HunyE z2QNU*wg-T;0&1CL;OrFAncV2+9j5Te#UNPV@rG+bstJ6jbY)KAbO{p zJ-))R@3>-H$W@F3E3o3P*LcI^E^kW9RWNXaS`#hB9Ao1x?<=3AmqZmc*5^fq4WfM9 z7C>S+Wfq3nuNMdc6ZF#B_DToTl)YN~fonGiI+6c3qJKc6`6pz#zHl}oTAp@ zLX7gvGi{8KLBt=FxE&jQZ>Z-|f72zkXFZtBgg7a=(q3;kmR_bwpX{62wS+lZU(_dU z`jg@yWik!bWz%zLFL#IL*yKObe8ts$S%9w)_AT~q5tuQ0G>>~D^H=4IFC)>x~gerEfU_Y&KZyT0( zmfAj1GSqKi+hU*Znu$Nd|MxrNv5Z=^A zn34er0$7sC`Z^J4l_3h8gyphh!`AyRb5Iboi)MPYvL4fE*OL+*vg}~k{pr9enyBY# z#0P0a`AMoV6g{$0nE%@dGJrJ~0WH;VH9M6(LrjiVhY&ULh;=O{NpvmP%xvAyt)fS4 zi)V{q&Lc?+J~`BeT&KIQuB(pf81;9P6yD-ROodrGdyJ~!A%UFtjlMB5<*i+J_}QC) z9XB6YzCdbCJ~k|nAoe)gAHMqbxV)iN^}hWqY0K`TozpfeWOoL&G7eRzZCT9^Pmz}s z>I~RFxY99rT)`@QJ^;${Ldr@+azmxDh1Y`}iAgh91%s|r>X%Ph;>eC(9)HN{*Oz(mc=Qp=@}Rb!B9D>rR4|~B z3D&X{fcEe`7N%E^7|F8|jc{_8i1AAOq4u<@i&aB^SEN3I`aZ;O;h6qpQ#&}yiU*Hl zg37o#ds(X=HI0{F>43@;mKa zNl?XciP6wyZhP)!cx@K5IkMwMg4ky%*ADgb+ZDU@~hk37=94 zM{7||$(CG(+0@$SNLqW5lcgv8W@3Xg+%grI5}4{wij=(u!H|ZMep`LvMgdcO&&INx zebH&{^rSuwqBdZmXYape(mq~ksdGIMc8=tcX^~65(60o6Suv%w3r|~NcCR@h-FwcJ zl9_9jG_#YJBo*ztrXOnZ7xlxqbk3VCF6sa7d1*zey)O{YBz~|deGr8(ItlAr7O(kFiOr5%tMEd>wi0$&?tY#t-?zB znH%HMP6LWXvhB!(!q`BX;~`BvUm_TA+^8IH%w{xBlHtoHh@*S44!QZ6jIu2(T()|^5r{-wLWyB;Hy&5iA z6aKn`@cwnizt=%KU>Oh=#Qr}Aef|`+zm*GkWrtEDR%sZyfmxry%g~~R7=twvi~>klR)X^}qDAC7xiiI`=Jj_^ZAjh~Zq-H_JMDN(C%CE2@Ls*g zX_L$|Vh?6{CZ@mT^znBOF0gLod~vagnQDo=R}=j1GUW{Hno`K|ZN!Inuda$-cVdk~ zJ>^D{l#}Iw%VG3=X$sOZJ58R1l$$?q@o}@6y;`tr;&fr8Je1Bg{FbQs7uoX7J^Y)R zkc|?H|2GYa8r3I0KDm+W`}{+_ot9+k_VP?$mFK}PlG}j=aw`XymlqnJ$8F!f@_Xg? zuLIi?Qy|_fu9SS#blPDEY$$P6*8w3HSn@iV4s(yH&YYy980ml=Y9?DRhZIbK{I|AJ z1MA}-L4^OjjVSN_;ch4x{rB5w2^+u#2XueGjhv3&Ab}tBr9XWhsYm|Q#}Bee;ln4K zTO)heCi~uwES&{E=>G|B_kA;3Z&T@V(&ci~{jpS#~wa@nhivTZ)U=`kLU zMxGy3!X|WH4!Hb0Vaq$ZOhUj!zqI(%w&}q6w#_()l?R4xTa8tfH^ZxEThF!=frf-F z4|bz-bT?haFI}4Ir{mWcKddtGX0_R?w|(i&Oij&LJgQ83zdG9xvZI=AV^FK?}vxB^k`NTjr*Dqi5q_(ETzLfzYTW~KIg*L#*^ zB75Hrs>A6IM%!p^{ke?+k*|m7`-=Mp z5Y+3DZcvRUU6D}x#kL3xp?C(91S~Qs=@;of2*ra%Q$CiQ9DmWOEX^ETL;RPWpb` z3*@t>uA#g*+UT$FmUEll1ad@IU0mOIDj&gFVA{^X3=x4rUtORKg7QQ-#%X|DxBm6y z7Ml=Z@aD{2 zd3=WSGwX#&WqoFkw9(nCeh_2AacqqzSHYWTyfV0Vtb)C1j)q>R%o;=)9^97Qp?#FG z*!lR&;vJs($b+i&jX??eHGmA%@XU0J7fk-jXRYUCd#bJI+v8GP@}zMsNp{)3 z#Jj#IAUH#M%dlG(hPnA#vQY&8ad{P)49|-SwQseU`d)Vb(l3gKjV?q5*=l(?m(~+6 z8lpq@ur4UJT~xMF59nIys*w(&tl6F@65+b{nqrLR!ZywHzI_dWtMjNb`QDBI)e4U^ zh>l(L4$!M!h*iSZ_*hnW7NYe`)5zB4E-LJ>ybt$i%;HK4Z#;ZFDG0FQ3+{ z-%d8oyFr>oCNcAG{MDph+dx=rekJ|u7vtTHs;kyUP1{tCwWyai1(;T7Z`^-eH(b@a zKisbc<60ME+euC*KH9gz^isqD+u58V0UH5vKX!{5Zo(6< z`o>w4m-j}xO(%lU)N|*Q%xU>E2cgxIwZx;rdi2z!=bgXF)tE5UCZktSvlCt%n2E{m zg@hBX78zNV1Z}BxlQRg*iQG`PV@@^_&k>IuSHG&`tL?XyjK1y%>aI1Kul?Dl_AA;@ z8!T5z^sc}^A!pxS?A;kOKCguuJ8oho2keJabC$cdo_MC-u4bgEG zENA4KSw|E9=%MavX$y#Uvy(r4&xK^%5~>=N#U5Bc*_^JCAG4~slaX#7j#!;{&LdJ9 z^WlOEvw8*PV5J`b+#Qd<@l>-(wRakXH1Wv+O_)#_@-g0;Q{z{3=~E`&MbcHXN{!ufYe~uVmqHeGw&pg)e@J?|;n~MDW#ffd*F*2( zpZqcyxIrsl8#@4-9wZRfM75fFt{Ry}sL@4R6Pq(upYQ}s%X$f$nln!phc*W3b!c42 zWXQQZ$EpFk57sSs?`aLSYD_XzfiC2h*T|e`OB(dxo8^Z-nSJzOsb95lp&;8{D|XR( zOH%ThZ4>rdYcX}VT(6%jN~J#0-!OGm&AFwp*zOeR_Wofe;&ZXoi6>;WOqP>Xya{tx zHl?j|1+pjK;>6>hk?VKIjVib7t9s`)2a7VrDpy+wO+U?1ZkLPMRjuHijHBNDKDxI# zQvLnN&h^X5cT2A?3V*53xwt;MSMFzdN}4;4(X>%lLg$g9THgA#{owwEg${z!2Sz_vE&rUO$aRUcJr--!e$6vHyT(gL7td_?^@dr{HBs;J zr77^&TmQRV586k+TsZXW9ZT-&G}Ip<;u@_&l^7;-u?ac>dG%k!Hu7Do-058sgM8t?bK)A+FtocEU@!9u8{@!aEuDD z=n@wCak>$JMXMHKI;H_1F+5s=QZB^QVL96+D9w3XoB$yZqWy?KtN^vT6yqU);vi5v z2v->@{ku>{c>x6>8EN3qjUqGEW~desae#wcJ0!)Ea8-H$6_%75#7TyrO^%AMAOk)` zKo#ON21ip_FfSt7zy|_?A2cXHBN?z<$|xZNDnuYoKv^RM8i{}h3#e(ujr&TmEdh;Y zV2}yuP!K#$Jecbjh(S1E8fFq<0MQ~1=|ydU*{uix@jhIhBqI+3H;^DgI^YBeyitfw zfJkc*;kjkF6p5~Wt5%|r62ajbBBc|X8R@W%dJ$+s13!Xe0SFNZ9Fz?Qb{LzXUW_5J zr8ojqv*-_cgwH}ZQ+RfiT$O5c2?XvsjU4n@UVXF5QWO;Bzto5%Sv*^~X~79Znvq3^U5e)l3o;a8ThAz5y}QbPJrEF^K!-unuP`5h6gy(Q3CCM1s%Um`?*_vck&(R^mHjQ~~Fu=ef?UH}_M5L%{opf^YJw+j$&7T^`^ z!VD5T{7o@o@1};Dwfm+4fMcz{6P?0D`ZYuCrh#xGZ%sqi7J)^%f58U-f;a`;gI8+RD`QM@oo(QsS@8P0&vXAwM#I*_^1s>+oTN17ouY+ z>s6XFlxL7CU$Tw-A%st`UBqI`i8KxK9D)}yupA7Pt#@e7(|^bZp(#8LDuRN@Tj3Nm zP9wvyX=nnk0wO)P4H73lnN7s}n&bs2nxhljF;npTT}t_)Q3j2K9Y;b z!39qhydoTz&f(?>(a$=CnuV2wg-Tm4H`hP^=fi5vAJxPkhvlOXic!co4qp>09n1p! zrU5@@sYiXfdMniO5&RROQiW@Q6F?QnQ2oUOZ%cR_L^`1rSn9;(iH<3u(Z`k&TqzcD z9OPhvYdfK~4=P@QFwR6bM4`jNJxFAf8MR zoBN57hsl7xSkDtFt;?*$Hp3EF=-Wf*OcjAt6#R|_)I^MkBR0CM=EkzCqB*GKfb_AK zRoPhdt2QkVUSpk;P&AC1%)zBj9`|IFXxm;~47m8U;!raY@L|LEV$(vmB2~yIRHo}m zKN905WuK$q&8qulR0@X}0QyH_$#g1q92zG%zdaj8VS#52d^-gZwi5)LAcDwJwkj>`))DK<^dVD!#`Et`-Y6>|sOn}&5enGkAlJRhj)@_da z`Yb|`t{wY))P@2BEEF$FgN|QtDn-RG5MNG{Vt?3mT{=YvnUM$1DwY?-y}^C9mO5?2 zZ@QImfJoogRjeg|aj+R1r?(KG(iRe^76+DEf$+bbkh&pDRtz2B;ld@lZKQ?`M7RkS zY6ZE(3ryHh27Z~&>9e@!lc$dE%G)A_c!}DbkR>4^>ky_{VHxi20&v@!e_;ty{wN{Y z5Pd(;-c2j_;z)`2ygFcr=!FTSue|)DIGA9 zPZKD->u#4C9nt`W_nAAD;8Nnrt=2!no7=1I(iSxwOFd>3JlxiJukLZ4%gLrsjrY&` zx9-}=xO{fv{GVaX?fYl9l|_JI5jFgysdnS3;ghbVLUKov*MpN+<4%oS3;p;yQ#vX3 z;t|MCrDwK;k71X23M)rqwy?uni*IToMBDa8)|WniR{ZK5q-RUR&LR`ykY!I)mw#o} z+CZhX}g2|;MZAY^V9O(_QDNUOB!pWuQ_Gtu1uxg zNcg;BBAM%A@2v09N_c(kq0txk&GswNHkS86wtEU?ukLW-HrE8nfE!Rosd6LnwHX>e z6tOgghc*^qWqGY0imLEzy22#57O&0)q6G38V~Ga2=`{_P(vy*i3+XPM^Jj)#c3=}~ zLM#WoMPP>}F+;mYkyj)G@Z|MeQr)b4j(k0`!^g!guS}f^J4&9+SiiBMk_{yp z&+ctVR${}oKdyo{JwR4_Q;JE+(2uJqLcPya>$`h{p($VQml_-ITv;wPsp;Ur)*jGY zWGC%VX40=}J%D~4r>U6_PnF5%zIJyrKl$GKtQs?6A(bK1unWxW^YHMTKTT3|o zXX+gIr(XfgU4!ygyfNxuiK7>a*6*puPe~r!YDV8C0jqN_ynMPb4*J@=aX)nAlUp4U z-|i2|0Q?2xvO7BbAn!bOhZNu2beguBs(iXXb1qPs@)o1v5=2e|+IGthMwmW5qY^Uh z_1Pt>dXFM2!FwKd65Co}AafC7&K$V>GxEf4#WxOZ5=Wy*r*r$)nkX1uUTo>nQ_uRcDKrO2=u)m z>s)oM`*5!hdL+`sI|duKEEeIi+Ba6J?FGR&FmuN*c!zz z-m^wt#h7&0cx|suibnRvaZZ?F=wiNJ<)J#7_a#G4>NDUnOe6~G?3mRm_F3)02u1rg z2Y!r*P=4)qOzCZl5&Y_jpN`lJYc^T`l{2@n+bmOdo=tr!|KLK#m(t?AMsJN)h2y+0 zneG~Jc@r~bLxpgZ>02PZld}VQoo^70XTc0-ywv@?R=Oq{Kge2=S;8QN^+avGJ%{|6 zJ;MjwN{cTBmFP}!R(W?x6dNHJSH3~Iph$u<@>D+pz4bowq&_Fch6GjF7e6Cwh#ChH z(@s|Xm|b%~NvK44FKg>{Nr#H+Re44Zg|cj&S(j+rp3SFa@gmy&+^bQDI>0Cm3)HMF z@{vt!@GSN_Hm~tg#d4eW)^qoy_1|RClb$ps?pHWnL5dFFr7`CgVXks9|M=N~ktV;* ziIvUMUo1|2U-Q>uj+;pJYjd*Rdl&5O$vz`1lcPtCcjT3CxfO7QToC+z$NCM*!&b$u z!r(}<{vL)`J?WZM@%E7&P2DdvNZ&t|UUhqIu0|hWS+!O?JRxt{`hDfjE=`LQb8d6CkH3#5jkZ>O z8=2d*{QWLxRhtm$K5wt~L(KDNt5Lo)@3`T|m>|EccD4H(m%tz6Wut9p*57&Kap=cA z;i}6GPVR5LD}PKhcwBDUdgra*)gSkp^Dm#<>HaR@@s9@`qn9rnxbrS#`Nu=isw@A$ z@czFM-f>G#{=Yx1;b!7b&EUr-ucd;%ga%$+8?+_ox)v$OQ>|n}?&1vtiVF5GA zjI4=spBf>QPqwD6Isp0lD*KfD%}%sFpOGmW+WRNzB?Sg(T-XaW=m-`JyCfo{ohtIb zMv)2+qpd(gn2-hO)TJ|~6eHFc6h9P-W!a;Rqnr``Y^oQ)NQDx;;HDt8bioOvPX5s= z%}gXgB=s6(K8nrN2LOTu=pX}H&4Bd$?)d}BjZCB}#r#eCh9~Cm2sRynpnlY&D<#Qi zzDa2a0UkTK86;w2fkL6YfRcjrhxn3HodgIzIcB~-McW&GfS9sT4D}Qts_hY=5F$yS z`#FccuRknnEwzS%FkM0wie;Qg9K!_^pR=KnV`1N{GrKi?E<0I>lm=g{`vs`{&yej9 zX<*tyt?Y;qH-!h{7O}ut%S;zi+Gd_SD7hk8M3v@)ITHwg1$eJ4?N&i$@yP(FT`UDq z#3y+3G#tl*nFydoI>@W*GfQ^LfFj0;g3Mzb1P2NBWLUTakzOWW0zt)!5seZlx>y^K zho9zg`wt{HuZB~^07U|IE5n39;PxzFy#RJtl3BVHm~=ptwfope5cDDWJTk|J1#5=D zH&76MLTI=k70lt3Dx)jJ`4{bxwE|SK$i!=$Qv=BY#|E-wIA54)6qRZbm1auKUiqXG zK{nMb&VRdv0%cqZ3$d9A3$I0clM(DmDJ=?6DL!n1J?b$HwW9zb)4=1KsKB8#Pa(Pl zsSr)J)nP)K7jv&(5fn_rm9Wr_EAl{78OD|EpoO)|V@Vl6P&|p0^)_&ond85NN)+(o zD2La~SnZKQC$fkUH8~;zKTmKloQUXZ&uOG!V#$bj0m3H=T_6eGT!x{cQ5*`wQw7~9 zz<`67vkj?h_T~dZG&qF#Y>!ZG*nK9u^o=sQP=LzbR#w}Q^91|?!<03KinBXY@~~ya z2g=LJ%PSfaOR}ZG5lXB#qL43NHHB((LPVhz8rzdWXlI>>aX{1p`?jDOCKCSxBrJYb+u! zB!BNH;0sPnJ&@TffsQw3I1zJ+80n?*qW5p)i-)9O{#9dVGWnF#xTRF@X{eV3Q6lDK ziSuQQ{ug&|`4wgSzH8463=BPVcZY-^At4}L0!la1Eh^FuJ%rMYbmvGnLwAaFgGfj# zjXa~@{5^Z^wVw67*e~`!ao^YHy3X@B!aTFzZ#59H523;BQ&uURUqU4?i&5(eOlN5{ zwqtN~%6l74%n3@cRk-h)Y@#4QJOgJO%V6FVTV%XGBXKrRiyy`n8_7WkB%A<1bK`!b z5XAr>%g+InF$pq{o#C2*$ooB29=T7oEqFNEWG3~{A1b@lu`ulCau`_` zUOZap)CfNfhFFJ~XaatPZL(a}<6sU3aG8}CjuK1cp6K)f1|LG)Q_SUe6WTclXd~+9 z1;;@-W}#4^^f7n_?t*riw{D2w%)wHhr$@cFX#pv__1T;O5}{n^owis$mjw=pfMUKTi$dreV<1qi8@HmJZOMzD z@k`%{nmmgqRf0FETuSr+-%~K&A(ED^RRG zdH6JVrZ@13B>VG&wavlr;W+-3;5Mux&d)L$6X;s{9FkO#MJRUa))kTQ z8gK#=*a~tw~`9-aPe$W%BNLh2lDBx4uyfbwpkPQZs zKQTvxYNFd`he-IKr^CEBP}OPep#9=tEl|yj0;a(=5II}BPnr9cKd3C7$aIa_G3|XH zGJq*NqQl7f9U_1p0jf%GqhM&czNt>1km3peaicQfVV__I4PUoQ>u=KVo$}6Yi{MaS z4Zw5oG1Htjz~CC>>Q+Ky?A$5>R{n{hvLhHif$^3hNKra2%}qWH37@{kn4<)pQHjRp$N|Zn-5-nyTd9WWIbse-UTXehVoFtO$YmPA#ScHgy#Aw3O7K&xz zL>mn<;Nm`O^PClrOzz2guz60vV6xMX`ot2V|K0*%0bBs}ptFDF9R68o`mgi*-$K(r z&+jPl-qVO$rLrwlKjvRs0RF${_rk6?QRjbc0fJDEmjp(Qc=>;B0g5#9s3ap^pw928 zEx_{7qrFm{u{RY&(`EUUppNEJ)cO67iHhKmdyQ2--i%cqZ<@NHYPAD~hC`Oh+>Ig? z(aCXgmL)`i%Fz!g{t-=F3^jSvh^%8Pv)gs&c{@pbF=y-(hkLn^$0xS=0Hofx^fQ%sADPhEc#C z|G~)V{{k_1vVfHTL=z1XqU*)}L=zW!^5S&`lpNWCWGXv3 zL2M4ixp3Y+ySy;oh41+Zx(>SqDSxyV86JDPMcJV!?L~f)!(K^oVd-9JdHo(rd(n5# zwO?L4bBshMcRKEbu$Lcq z;fnk??uIJzob-_BIi2)U*!~wr?sR}9+39qUqp19Jh^OJl=`epk&)JC3tkc=3==buo zF^P*GXXDbC4}MO_kvsqVZ}Fbu|3DTQzdQIfYaaICe9kJ_`F!54sN#IVso~&!(XIc% z#nPKu=Zj^}?-ds-z8Cig7ppK#-pjRMa+k|>ID6&gMwH0m8v)zg)le%UWe@QngG!Aw3JsF^{@;x2l zJMujnea3wEb6U^!?$?}c)!q5h^P`)KwJ^Tlms@2kcjw4`8teyi(EE{_<9@#T+n=*$ z_orVoQ2m(Oizj$H(~xWcrVgyUNtN#NXq_gn68&oCn|7e?QPJh}6e_~8klh~$K`0!vyEOWjK?(}0rkj`FBXU{!#ZiEde zjyYn7`z2^R&*ssSa5d+&*QramrhJGK^_!5_8U47MV&79oKgr9ItW4*L$79})ze^=Gj=D|74e z9IVTX$@O)eGJaLe$SoURI7l~akmh)QD>FwEoof00sH%kehjGvlo&yb8Wq{5P!~;+DDiXYJ=xN_lGx-)=vqT{IZD#;<)cYG?n>+i-ejIy0yEhl2sN)a<=!ZDq|{ zu1hCJt;u@62E7OLu66V3-Jpw-I$B;~O4WtU+&bU%=e!C*>_*>zC;Cn~?~KWH8ti+J zHRp^RQur+zA0?5sPLdvZe!Vg}qa$yV)TzRe!Cc&Ho^3ro$nd46c)YZ7(Xle@>iBI> zd=+$woFjJgEiha=uz_|$w=)CTN5md#H+C$3m4C@RvMy~((em>4n6Jcf2|r!bhe_je z#Pf#v^UTX$bK}oZ&(%yR7AfKc$39=a@Y$rJ*6FA3%Nt`NTqL@=93Tc)e^=NsV-dd^ zbP?iDC{nYgA!|Tw0ZxCXlzrp%nfFe3bei11v`H3!HDXXHkT!d3MfYb5AXQnFvaV)( zCfqdUxs6CT8?i+ZauuNpmYdgrsaf-ln8e|O*> zxwy0?)zJK9)a6Z!&+?Ir2rBMy^0Tj@?QHbOuST3uoLipLN#IyJIB+eO;j&XT z)-8zHc%9&#Xg8zOt8fwDb@FJ@KF-XO2-l?z8UnEa#os4!j<;KMu8Lm$dc3Hm$?Z2D z_NE~tsn@C98QUTaULz*$XK62uiJwFUPlTAla)_6AVmX>86Q$l1();Zyz4M;R(|B8K z)V8bBfBiM9@>k{SyZz^@-g9kI9thRD9|j^m3&Ud`wUNsQR$(m*tL+|54Su%&J%jvj z(HkxxcR(m0@gLbh66jCvWTaUw`u`kGl@3r-pzY-e!AO` zY~B+?f1YM+{%UKO!ROaEN6H#oc*K)P4<)bK-7m$@%l_%)dO4h_-coA#a00>+0THrsN zTnZfP!T)e_*%Ysb(s=wCPD1}Wx$HK=IsVV}CU(DP!7#XXvV+MSc5>isr8~L0Qrgm7 z{+=?u)UhPT1I&#mAO;~gAr_uDCpjgLMJN{oqD(d&lE(r&X(F++Z0;}M|#zOvB8PQm5Cd|9YF<&ObDa#c!rO~O3GX_Xl)%ZIx zwHRo)ctOBGC7^4J1r{^tgMb1R`7qZ60xzJ2FHckP!Q1x;C4pYTSFN!alLQ5Ef9b)P zZ{J$QbYf6SYxYnZi=*hlysikDv8h4EAIt~}6dL%k$o&gNEQx#>XUs41M1!b{@FZXr zd^|G2tdYQP4>bO9_xeqe=K&a-7I7CtFP@F;?`5QCJa`QUSjeDD`^xmm=5qu?SRVed z%riLh_Y|Zw`~kbaIqs1y;Xrpfzzn)YLe-vLD6ycx?vLeQ=oW#rjkBLS37?5y__8pF zxXGQMh+mppFJgeIq&^qR8Gn%O1ARU?a*C^ONMI_cLbp~wE?&?Wi9|LO4}~u3u9jmO z&;!V!dZ^FcbbwM5p&}WFV$R2)a~NC2wgHz%8h>|9_FI{6wd#zmMsT)k3`qq~HwXTx z9NapzNM0TmY%>Z1W{jPO0n%%bk2vGZ_y4Q{cSU}J=G8r++frc&N5}z#`9ax(d)i48 zJtSO(7`e*(7{4FqyhT9Zpouj+Wnu{09cv5$2?Lr~@mSp)LIP82D*!YPe9BAyDa;<` z8s_t&ED#w(m`zCLj!u7Ho`_A*Okj=kivINroj~TTQf*_H5=KM}#y&rYNSGf;t4&I% z4`2jQYAVs^=OGlWm6DHIAeU~Ta>fw7PSEx*n!ZbL7rrF}iQGhrT=Ac$s1Y}R#lHLq$ zKdoc!3TPEX!xppw5m-s1>FzMSIh<%z`mk;pI$>}oRS;g0W`XO#fVTLJXtPnE(a83pc9x$wpWxGY=j*F*)v2b4xNNbCnubgu@X-$r{BZTYB- z0&Aq1^j(IfEW4pvrinTdGzP^b$fyPwk@|`BIYR!W4i&C4NeRdB3t6e!9JFb7AUmC> z=E;Wjh%7Gww%uN}j1p5`Avx1EVU9G$D*aIAIh3(GQY7>>pIU;7NH)mohcL$NH+7?L zoF@;b58n~%e_Q+eDE-fO-;b92xWbn+hD(Q7BzvYpFTQK0Qzcm&a1>`Yj;7dNOTfd)7<*t ztQt|8y0&IN&fb2wc@pYU9HPwGHvNAV#$+CpqRGhcBDN2WRYu18#f*&1wda& z2I7#LD*$@PXTjhZvjGc-1~W>v9<6 zU8mh>T3gngvc$e?sIR>!VP|zOZ}JcUB}sz};ky)45?)wSQXg&fbkP?Ib~2bASH7rN zAF5X;0F8~+pEhWT=8w~6Ns}N7uRHkm??-7vGB&T5umxr_cx?mo>C7uVwalF^48s)eNJ>tJdlFg&b^;E{`(`8skm5MYW4LfX5co>%xFM(V@?E(a zAs$Ee;)q4;oEj%j$?0*fynmx~5G}g3N6!?w{6l#R#f%Yh0&Yg4;OKXk5yb6WuTbS& zHm7VL0kNPgs;ov~8;C_fvwkf9OC8wrlnVF$vx~f1mv+y}bAY%&H(J0~HBti29Btck zHd*XQikK4`LwBXg&@w^Ew}cGQQH&w<{wxYFHTkPBiW03@$EC5d3#&rzaFK2Pr>@@A*5Qxj> zZo!Xlxv}qhlmIW1&<)P`3^;;atQ(6N(@8Mq2*L0)$5LJDg#ME4 zh1h9>H6}4ppF0@Mu-SwlcGREkx31Y39xUuV#*Ta z03`HM(s5lDo-J1Gq@~WSS%J(2HK`Qf zOmWD!Lf(?iU6nC?3HG_j0oz}?nMe3g3ck%~AfE-r-h)1-h~>%-6F=}#@D;O^{!e|! z1>^w;1H}Fv(S0U!b+Z2gk^VEH2RA-j`@`2k)puUe69lRIlg8*shvMoKi2g|tSpzX| z+`e+6biYHOT;V2Eiio}2&qj!3psv(BELJL>>s!-Nw`LGk=uUNAZK=+On}^xbN^v%m zW#-*nOXTSC*g?&>R7@PG`c6cxHz|n{cd~JVX9Z|3y`f4UfN_D&=i^X6`(?{V0!sn7Ah$-a&K!O4?^hne|4}(I%`T!Z?aD;bES?t<|oQyLG00)oI z3I&OP`kMFCV!nzEz@sM7g0X^~zB)OlsR@LTPz@LX{vz^7;@m7^ST%MQrAgq8%@wR^ zX|O;H_a8$LCOA^NA5Fq(gP#RF&2U6Q>x81SqlDc9&S`caWojyZ>Tp))6sR1qmyDsS zHO+1bNf=&!ji46-0DCZns;?0eTXw_<&{EGDr$T#21`Quq zv^!N2w0n{>xbXJ2Rb&>7`sbo-3C5q7E8S1TD1FGSl*yS%j+;opz7`mj8RKNiT!|a3s@$?U2rrz4>6qMp4i8oGX7Iz@#gGgfpg_?EU1d&~0vit^ zUo!A*YboR363f)!!50f>K6l~?Z^61SgyrbM*=(E`dbTr+NSQOF(VomnL;PYuQ`kuE zd3{;p#>ja#rdZT`$bcE{`4o5>D){QxA-*8@z)0(HAo&C;csYl}f!T!HyjTZn0nBA> zm`dqL%<)Y*kQ5Ftv7StKVpFdLkl**MJ+x9@$J60J61vTVK2}?|HMK)y0=x>MQ9E*% z@yVnz21nB6T$(fJ})@|8dB?B@T*og9NQY0232Y@;mjN-5Y zz;MVyDHCI}iF__TB}W(aS{QULgqzgV&IA}51Mx2S>`IQJstlNms9jm$y3QGvn8!kt z0G8HP07_;#fzkpjb^Ae|ZYIZfG4rX|=3>4q2tZs-0!o{!4(iOs!CWU18l3>Yr`$@bKMf?!o|Qh}x5TC!cqzkx=t-pr{={7t zgo$lliG^$NVwsYyFU{gU7++$YAxQ`_Bdw>RAm=PT;1m4a6ZW`9hsakvpK%YDODMQ` zFW~urG|4oQ+nAz88UyRac`vT({W(b-?`E0cV^>p)jz&uIDE=;8z$3a5#{A~HWt@;AgQMVCq7n{S z4Cz57ZTs1#F7)v!JDWh-f$G%XlCFLY-DSm(f^eRkrF2_bK-C+Mfo4dwGNsN>jD6%} zcS~K~cySK|r*oSA)X1gJKWWgqqf5XF>fKW!=t+V<;2}Vfvy>0^NFocs`db`N#TJz` z^{WGV^sVp$1%iCZAGcPgyVS6Lvrcj-o*#CXRvt#}53eL?0j%HQF}6)&2Hck#OmVknp`S?z+j$_A<^n;{fQLB`U{!#f_;cupVCg1^KN z#CZV1Q_+OxS5{!-aY&bcuF-|aQW$B6>JQ^viqu>=LBcEXF?ej({SA3jz!br<9u4C9 zBu9{(OpSUnE?sZZ^$8pOz-$>-Ou0D{G)MVgZ;cbRxSdWs<}&iCv0-6KRwP{K_#$s2 z9;v~WEt0_NW-?Q2ji5CUxy^APEq1k%ysbe4Q%33L<8*_N|89O0fGhxA0D=FU5!aA{ zU?`VyO3XTC7?fJYS5$zhHJg=(i zs2e|o4S9YZ$-8X!zhd^h4rV@amrENbEHbIC6jr!f+kvw!W^`d^i{sf(Bk9zeYj?}j z1dS>s3?2@-fx9~C8Y^B~+bpDf`p2dY{JM%)(NjAX zhE@L`ER9)y16Vt2LD0u`8h#ji$qeFXoW-ktHS&KpbrBfp?hs3*n9$o)X3a3h`kma! znpnG>a8S+w%`3j`;+Mg7T6SYm?A0|n?g+2?%~+-DzSL;x84jxm;u#yOxEH#VRJM!! zsb+y1_?$-0DF!IQ3A-~}denC}16b&YRuWaJTUSY{uz_wdTRL&*<~HA}bIxtPi3zXm zX#2FwEit)0EIbo`;WR6g2`lBC5Jx(d{PZs9&Q2lUIg?uUTOz~a4_Xdr>V+AF3%Nzv z8qMEAsQvHl_xRFE9rlCT093oFf*V%_HXXHZ_Yt5eP)Ytn(@U$|MF2O?=LwK)`NNjx zQm2UORBUy`q{seZZEWauY1O*ja7DvT8itG2Ojm?m=C)M&VQY2;_hIpH*FI0%t-pPCHwkj#@X{vBnE3RPMm+DZq9zwIiv$5Ut@(*PpmAl_EsfiDqE7O+K zZ9b@uFVudSlzp%>{^DheZH4~3vbyO|-8N^wHe=fQiZ;!bx?*b|XRbU)pGdtjV;rHa zVCB3FDDT<0*uJ?*-D!um+9lS03wf&|yKkC1Kyg6*R$h_IH$RO-j`6@%pF_lJ8YhDtG zp&H2%GDoOLWBGzU^w(VEtG4rb*CW4+wby*VFE+!T{l3~RGW&hKQ&Z)Clk0e|N#jAn zG^88T-nJT!GvqD&pb09^_Jg5qm-2s}5u>uv*+o0A=Uus-BNs+E5_7)oa*Evh(EY@g z=^{$|*BP;ktobJ%6tEk`X#G#5fw_;9zdBzzj(s!VIJ~+*C7H);C`y^Qa5NS5 zEm|sh&OVsM_$Sg(Ta0oD{xi}5&&8G_rO-+EXQbiZ-y-4i7bSWnnSMimBMqCVVnah^ zpXvYlErR=Cy>M#yyxAYateUBo%25lNc=+@=TU5>WvFs<2`0C!ZyHmx_$}~p3>-J|5 zX2Wb1VuIU4|GFAPt)n(B?G=snpplPe?YAvW($4*Lq^rWM&1e6-8ss&Bw%ZBrCC18y z&kj9C&7`FGB|Lxr<7#l)baUB}{#>C9P*Hpb^wfp@#{$35>gyI~9a3(n0_KX?uvZUBD@~;_hp)GIov z*VsGD>XK<|`OMV(3>0mNJ>12=Xe3h^3oSEMAN1#HaEl6QIQ5!7n}!87y+uBs7M2M zZd131YGpH`85L;|!&WVC`Dqx5iZq;I9JL>u``98O>=N_H(~pkFAF&mAKAYgK-XJ~_ z+m^pFB3<-35vLC0d8kc$w$D}l`y(pSV7j-6Xr!+}MHR(@(pW(g!`pfd5uE)?P^5?9T;*aWH<9*}v z1t3n#XcirD_`@EjSveNccPGq{+wWRNNBC-g@(sNQ+-3pLl#oCw1PmgP4I&;uf*&IS zpuXAY%u1d2znJ{O)2VM3k_E23j{Rx@>qmiMe75qt>akx!y>$ov{VlRp>ZV#i2u}>I ziKz{A#`vKk4Z&G=_lNJE5OEC$v-`%2m3E_OODEx)ewfs$3Z=G&3y1` z4)ATyrHnR`FSvtxy)I@akD%$~gImdcA8MER=}khRMG`@xV@B;~nGe&8q%Jt`Bc1kS z(=Ty%hAx#S0)J~}LzeSp$Q?A_6P;yYec))KP??N~c%DmfmnbhXq!soXKbI2EzDQJM zDsJj|KF8O1Wxb&(|EY~EdOs}{+q8nDg`b6(1tl7e!Cx}Zr}Ov{cQwMW>9eSQ6_c}; zYQGPfE__T{%wSUbf|(h|NuK}$_!_RX6pQP zVst;0>3?^as9E^R>^xd#dXYBUF!ihInq}Vvlbf&|RcwGCloLVZ5#|M8XmmyM} zA2O`3@b@dX>ExKJlX+hKs;S&gQPr?PcqXW5na4b5CepmNo_rJVz*t3fap8VJxUTfh z(N?}sZ%##{UZbhPEzD=J>^HQbNpeqSBUbg@$s?5aoYx4hy1a)kQZwl60I^tj!dze0 zuz6YWCfRcNG%dNg?~XygX8+4K;R`)qu)<1TS;E=EMf;38pU=;(K3$#*j8RzhKw5Jk0l(;Zoi#xEh^ z>S`NpOqYJ-ef&XqUB<$aqBM+bu95G`^~iC1`lWdR(Iz7^e_o$a@`++WxMLx~^(u`YnY?NyT2v30di`#5%MAEbBx78~PB%NIr zXJ(x>-Wi2{3bG*2ClB{<<{xq1ML)Y*Jn=nux>$&`UQ1b$&3We>AQKe0l=|S%<3c9% z(~L7tM%6{%JBe<|)mGgVyzxf+Zz7K2MbB5i-Oo67-21(Xfwxwp zkALVQeCWimh1_2BxEv;RbPv_`o%M1)%{I!6{nRfqNi&NN^+5bAB!}&aLqM%h=-l&) zW)>x9g+8pR#@Z3LG3(Acj;x~vgV1Fdv=n{jv2qU(XA=8TRi*D;B?%+ne`0oV6`iVy z$}GUNz(l)hnFrqgtgdPUJRZMU{ETza>>|l%+R>sw^2Fmh!Q@!;iO&Ki5m1iZ^aR@P zy?JqUHu!LUFs{GF@b%%<40H2=lqYD z-wq($Y5n;??R0OL_;RjD>EdGi{x|U|V&LLs(mM~dSpPtB^dojCA;5J*zGwofxL#GHvI|+llifFbCPYVfu zIvW82Mt)LaO2dpmFAl}Aurw%+v`CJCrs$MGqM(dX861%g9Dxwg4^Ic8&iW%YzC}*$ zL`)aMAIL`57s2pyqLv1tev#`=QhdY{__(FS9Lye3+4y1KGh(Gtdkqqe%NXrt$E5Zy zN=7r{Bqg{!Ec!|*xMc46(M~jWP5_ZuEQvuZDOQZIW%Nd|A9hnr!p`$MNGz5`EQ>)L zn^zq1?)yjX9vHh&@;Q&HhA6tG$bEVE>CYIZdoL(QQ@q4{JevWt^JTP#X#9R-^g2nL zm_1agDM76%UdTO)fDkvb(R<-MR8Bem{5)zTI9}N+Q2i>=oHLe3uj8)Rs4)TVc7ip7pW-`%C5d*O8)an@sw#~sccB;G@*m5uQm6oNj!5ekj^%%x+>EWts`mdn8s&mskeE zL#Ky5wmmT;wkaciK4VBTaa{Ssl>J+ldxNx9H~1V@%0km86U($!gJe(2%xU4w@X(C! zshN9&tfBLnHCS1LHgWU(X4&>xfnsdrC0WR;%-g1ytXR1HUYQ`qY_uWP&KSG``#22m zG_2BWB7>Y6`^-74oPefGnuU0B@9ebHoZ7@V5-cP9h)f2mqoh^^Of0Y5N7u%zgSq(4c@oX6=T~`M6rY|t=!>M~DTn8q53+VMB=QaAS3%;R zsTi=?=l@bJc-6#O@hDfkv>;=yAe^+|0axM6QdT{OLYJXTJE{y>?{qVjEc(YqQsG(p zLq(?sMK5>qrv?iZv5PqjBwhp-OWku8*V?DArxrO66^kt7B{U~|ybk7YD7Nq}AuB1? z*eJ0`EfLaB4^|0}^DfS9&P{4A%~L6T=vf*tP~x*!N+gDBL{wDIm4|qo@DAI%WTB)5 zyHriPu!SnE?K-Zb)U!4%qn`@58(`sfT{Iq1K1fwIoc5~Iu&i69aN4i};Z>26T0t;d z9&=SbS<1TRUAPgEwuSAmxK}=|Qm#^6>9SCHQ{=O~m)4(FX<%6ei>TVXc0cj1JS(jP z3>Slj{lpupfX!vU7g$a%DzK;#IE#MOk1fH&RsAYeB1FI;h9Xkc5^`~0N+S#WvOFkv zMUKj6X6{nf7C&~!Jo(b1)BAC~}BdRkl3wUnidt_)peS=tDs5V)wGs7wQ3a%9kuYAhQ zLhMuTzF+rzxWKWcw$!j*6;%Ctv4PsK;hkfh_CmevK1&;*&Og1;UbU{^Q9V~#gK9M{ zQ+lJ{OlGeY6VGeE)R3FynNM@= ze$(5QD4c7&+GE^te!RAumUik^q3@Tb1e8J`$g&k`T88 z!qeeK4Wyvy3fLQ zZN|vx7AQxuc6Ceo_FUd%Q2%J5jp`BsA(d!)g?&>+mwGa}P`iWoHQc?%61}JTUHrZ! zq%`!ti@i1yUDNtqYQ8lFsy&SEeQr)U_P9MXBYoRO%&#)~-ABS5ZgF)bdIZb+1Ecz0 zLi%KR`W{sG2Hm#~?5hU(-S#IuZfShXq%bm&q*g>>HxT37+dbjR2MIGTgGA%Jg=rmM+i+ZM0e_a|K_~F&LG$MX8GO0%S<;UpGkN9SB zym__yPvVrX(#KBA$7+#d8@}~hxRk9D;9)DWAZTnYLdZ*EyI< zR-42CcD-_*d}K0Xg8Kywob{5Nx$FFT$TK8*mmRP?!8AJi=(hIb-CT4VZg)0rjLCeG z$$a?e!0Wp&#=i5JALg@Y7jp6DQ)zqCm%nmLER?n_lrJxQG+Cf%opZu#t29}x_gl=v zTijKhsTpl*yjw)lE+tni7I81W@oVn-v^3PVRHeT3+Gio;U~xopdAee0jJD2ad6Ca( zd1-lh=H71^fU^vI(6C~%vi)Fb&7`7lbl%oy5<=x`xXz@?= zMuqfM0Nq+c+p0_RN-^p-khz9^xPbmUx7BZHr+JM?YQ1!M?c9ECa=D76eVvAGfeb(W z?o-qL!a9rTM)%!%T;hbgLh?#13!roKbG+KhOo<~z)Avz)Jm-Hrqto4*h;+M zVKm}qQ{nff%;9*@=-jT?mWIogvP-PE=_>qsOV@u(i#L{FY{l36o9V}I%2MBcFMl&L z-8TQY@w9RX=CJK_xJ6&NVceeQEcM+*W6hrK<7<`g-lpHz9&9sd6!_5X_*O2ye#jsShA07-&Yu&QX7l!^#36u^&@z6 zGcNqc*zXN=+C2yS^l{UJ3EuIv%=G~KgQdfb-KetWHTv9h?Qvec=X4( zS;x@(V=&(d>CrJ6{mGuj!Sc!p+u`UcKkh33>5%j(+dUp@^eKDRDNn~KZ`CRP>Z!o} z{pmxqGoklqf>~$6RcE3dXHu(Y(&J~c_h(P(f6Bf8sgU(kzT>CxeHz{UPx`E}`1EhD z@P6q&+jx=n>y_^>yp|3GKyd=;{H;8hV>| zv#X?ztB;vinFOmD^w*&4tNf#t-1pZsX4j==E5)nV9qreMqvgscH|mr(^?WzASvMSB zH?8B#&G$E?^EX{)%Sf}^?)SG}Om3T^Z$~VC{jQh%9pw6ZZ+va%{l)(M@ABo}P6YQq&DKxN&VOay=lb27Row#w z)YhZ}!FY6XDVpoDp?I`X!4z5>-R7hZOnXwaHc{GSNq=-o?JcD^R`pD|RPApnNe@ig z(Z#g3)zTh0uk@ro|E`fK=|>k#`C>;i7v&h1PkXVe9r@&wR0x&M-iuNlzlXhPI{Uhn zCT;!)b~-=wtF1>fa@);lt7_q%KErPe<-?+UU0EuW!( zV%f)x_av0YpnAD4@qt<2h{vhT*eA)05gNmvc2hi0vJ^fUKAM=SFzN7UGdy=%h`qO1 z?fZ1&>b%nCH~y8@_|mPi;{&}SUE-zt_NWTO}klQUWgC{Wsae^vn4_6R7# zowf+2Xy2m~<G+iez|x7!C4vsb&)$u!7=>Rd}3a)qjH3XB)F$$9ODB04fhjF6MoI7iA+NGS|9@J zS`K;ogDNfMte{%$Yqs7Otg0fP_?|y|v?VlsD#iMXS?d{X)e9X#**cv=-H=BVdbWwY zGdlLYq+&)oqjh?#9uL0iSsb99f3b+xsnCBGYd!PCTEJP@a4a)K*U*tM&tuB5;Q^14 zauZmD-<2A#VX3)Ka@zRq7unf~x2q4zmZjGVI4JZrDZ8Ttp|5%q-IWBG*I;LlHY0`H zN}jF>v|n1Lm{`#wXk4*lHgNPjC<|%Kt#)Ox#jka^DS}CV%f_$_2gqadp|68e0yTM& zxG_N|c>s0(K4nws-M1VR=KdTEJ6PBgs8X~!Rx=C|hyOT&Qv%|>3(~$szuy4vbL0Ss zspfLxqxLzn(eWNayAorPj~Rj>(=)Ir^EWa+L3mQ0-3|eWmGz+Nuvk`1cDFGDTS+e$ zNQ!wBM|J>#no{!zfm%AoeLU<-b2RQQ{InASrn*I&Xn>(4a$@f7LU#b2ep=LqCIR~&kYje8d5&)#4>|Wm_zv(@LWsn zu8E`CfY)de9=pjn#d()j6nZfy%P!Zj0Qn#${z7&;Jx$JaxT@5>IrtZrWnM7H&+IV5 z7q+78z5v3Gv(!~=0M6#4ml)v26pai$_8s|gY6Tb-CH5LRgv9(F*M_>UCr}sybu}u!eD_C=-t$k*`K5vH9?V# zZdlUNrV|m+;L`(;n{et{I#(k!i?I?2_FNX zp6s0QPt(LdsuF9%)!;#+6a_KHv2=mp+TokrtHEg-c*M|$`B}#bf>QkGCg{x6tI}(D z6?Q$WzUE#l99@`1T2KQ&UOOO7ARQ_Rz~{;Ii7>!Uj@1F`LdER66+(n9qqy~mj1+qGZG*Rv|=nX=jlXufHO$$X$ra4TA<0t6pCCJ0Ax*{ zp;zw60;iGT_H1>ks(!Tm{6(Rsq|(lcb9VO=Z?FZ3$r#=-`7KOINw-Hm2#BS;l%}4d zz-360CT{^Ka7jVY!+=M`&pA35oRC=PL{>Rat1K)v{-!(0X@s6E&oe=>Iv= zfJZV4q0cOi0x@{`T2|y=c5<)0`e=RsYLj}_lUTsNnkUz3lU2}wT)G~TRKsJ%>zF!# z?T+Xf;RkcRh$iRd1x#d9$GRt=Sux^L5x~~XurTsy-o|uc%5Z!Zc)=5h5s*r{!XqH2 z#E9L2V9IW@0CVF0Y^L6)c)NOIVyth0ZDxLW#Ihao@Y!|q3QR6l@6~69zQ8ZKO5OQE zJ8(gzt}j9xkeEc{mz@2LBn|Dq*i?YusA{@~_*Mjd1U~q|OTO4|rZ5y7+cyBg#j9$* z1WwQ3#`0Q?zGcL<1p;_v4Bqgeaq?5v*PY9o@IQK;;HVGjFoX@VcI6=SSvG4wu^_I1kMBpP`rw!j6t(NyFf)&8V3be9#v+w zVttI4okg|XKA7=DvS3~f^|e=j{P4jkPgFk)Ja<8)W&pDQ1mPt;N>5LW#S=Np9qrKX z%c`P|N{@`C7;uy&F--g5G@wG+;YKmO>RW9gAvuW`zKWK4ESt8U3t^54Vpl1e3>eTs zQ@jl3!Hz*Y0P9ZR^8n_-v?ZDcLWU z>21`XLaJJMI{0kGGBN$$cS~%gEyh5D1k>j!u^>X45V9B1%$bBCyN1r`zZQsxF^Zjb zxrbQ}5EXyMxCr(PfGT}PCqI@ZLwEx5A`s|!*+}egfGpNy24(T5xwR;sP++u@I5Wz3 zTFnpwf`Sg37$A??2-DDL<3NZr^i)AU@8g1R${_+u=qa2q>$wn{wK6ejs+-i5L=_@I zyCC<)5K{o_*Hj8zxAZsI80=6EJ%-E~tW-`4pcDf;`(*&<93T>lQ)TaSM2jfpP2=1b z^q2e?Z(}f762e$sgxMTpD8xuE5I51pXC|Q4PrZD&G%U-tRlOb$1>=MQf~n{zg0yzX znFE_Z`e=CQ5AF+P0`P~jb&m`8!(o2h0CKxfx}EIa8W@4w(?ZIk?w4sG(ZKCfd^{eI zB!5P>a)_{~xMnG1U`h^%fddg9D5Vs@;F%IW39BeWgJgp?CIMV-ses&`^qXvpOLTGo zh};KAZWqEWOABevCKm-ge;nvW4Ka5sdlA{mcqwGSAB3+DG?)XsN`rB;LA(^eN7+r` zEf5BYHk0RVvq4})Dp(DYW&lZhEFGex-!`BAkS0=K84ZI=LhQlMM+S|O9@DZkIPDf^ zT}co@6Q!rZX#jFhG$C%l*MJtAYdHl6G+y(3+1pBvYMw`k%={CK$8P1IOAzrMgMJFg zqdVtbNG-@+i3S(h>P(G+*OPNW0I%AxQ-2!+JSk+mw~baQ_BZI zo&Yj!5fvfEXV{F?hyd!cf$dVrj~o!iZ9vm2P%bCnhzibo3^>gRW3>a&At^pscMgr(2K>3^i^CfxRYT--e zjG^EVq5;$k6)BpYf;Rx*)I=kOQSChqz)H!m7l+`{1gg5FMmPmEF=e?%AnEeM?&lec zyK6wUB!PYl%v{B35o>ava2dV|>TuSD7N`#Ca%&G;!6M> z1w>mZ1epsQ$N;@q2;m)oz1r)XBvxG^9+_5^)OM4U;Q=)Kc;=79tjC=I=?{Za!2b_< z?-kXAzqRWoA(aG3klwp=Lhl%Q0EJMc2nG~H0qF{enuJ~rh)NSe69mM7fK&}lkY*4I zh+!_)yCdO)Nq$pt+sPiWZ1m?%CT0Zs7KTf1BO z&W+WHkpf1Z z(3nHVk>&8!6s-KbyyEB_h-@;Ts#;&*Z?GrV)aV%5Lj*|bgwIF-C{i@Cpf6c5#(77m zyGU{Bj}nCYXX)8`WNqMe5y0#zfq4+01ibBn{T+lgwC8I~#UyyC_YWh-2$xl@{Cq(N zO3e$VZ%m*hESb1_{sT?iSMWR8h_!3mCjoOxhn(%EW`yMPJ$R(hb8vsCIXkVcc=X~< zr7)drv7H{%QL9LyQT1xou`(w5Kr=S@t|0iZDqy`x**HEUZgV6McN3!VQ@$pXXUR&iE#6bsW;laeXys zpb3~LnV!$NW5Fz^xzEvp=P0a4AXQ2Z8Gs4LXWW@<)h!PlshNDdSguDl2lzy**Qo-a z`$9~JOluuZy7EqS+|vG;G4&|XR7q;dNT&|T`Z%q&}7C-&~}!!-7q|m`4VYWvg!r< z_QZOfWK6A+odE2KvU!U8rmMAP0>utp_ihNVe=3tr5-xRrpa$xgELRi@$c=^gHQ{e0 zlLKEEWiPtRz||<1%h})S8kJ|@Nx-CAy}4c$!c7v<@YaZ9H)utm&uUp-G;)_3KtokF zkVY1jGkxt{(YlqsIV3T@L()M%1cmb)W@L!_R`9XN7VL&c#S&>$kVCoKPW=(_kw=FZ zQ(iQeR8{7T;Y$4mj|;7dYG%a+*qlTZfI5_yO#u<5?rGtgTf={&$ip@Sc z6#mM4HtX~#L``yB-Ml-v5TU5?Ua3yEFy8VA0}`*ouE&HYKAS>(U-)zUl~>gXN)_xF zCv(qk!gt>AVD;RIORNtUd=?HULtJpB6m7N{17epQdd9)>k_KdYEGtXDi$<^Vk*Dx* ziCUkCeb2yl_!A5L3#Zm2k^wMpZFX{IMwzzX(Iv|s5lpWNHssq!vG=F!7;C#P*Y;Jx z@EjgI;X}u>NB8bUj)hvk^ZofER2(Kk)hd)MxtK!)xb1 zUJGS~QG6}LO(=%DZE+^g^OAdIRgW;~`WEwd+}8BzV1s&$fu(k*ZOikt;|7jXVt5UJ z6Hljef9FB-af30u+G-0<7xwZ1hm_~W-m=q~=-Inw6{3z=Wpr%(S_KGMG$HT4Ya zKuZ7hBh4u3)obnW%9Nne{fXD@-bA!xilJuX?)|O@y3kvq*Ho}b20rP;OXey zxQXSg3_LpN#dOS9eUj+{t5Af5e8{se=2I{F@3{;y_Hl@E79+M6 z1(fS`8zaV|*`_zXbVeiJTEVl!3 zc=YF2M&Ci4D1i4Gz&kPTQrwlL=v`O(jSiXhq254dhJy}BR{*-N*jQ35?V)Y?L_fGy zt5Jqn&mTjUW~bd&ukb3pr%<}6%4vT1>!*_G4hBb#;K}{lueQg711jN0f9V_4+d+=w zU>}jM9*OVf6(C9c?lD4Eps-p=`U6n;?9;8{P9~`D4q5 z9GAO>f$@VL(P@~%ZR`4^DWf=-m~Ex#tdOKHW+Vs>d$Let`~ft&=K@xGSg!Gf96X66 zppKjVNb`!=5~PzV4|?-R!AtW1y!i5CSB&`50SAstz!&bmH67SPv1w*fl=Ns5JFn3= zb&^AZXNl%~hv%LClaCL+w5#2)BM8}hlz5Dm@pu_jct_d?CXM+jabV7#YM;kfO|u`J zOxp{*^JtMQ^Eg9F72w86Z_T4PXTcelg8xdbWpU{bCz^}^a6A?5*O88wQ#x?rMUMvK zHefVcaKA@7T;qzYOSw^0v9ilGZK6UN5E-_qG+Cm4xFho8rt);D-igPpC%>tVo9k*wLavDepLa?o?SL}N zL~9GZ#zy08@$#+Sk&jt0OnkX;Hm!#58Xv@}GbekrqG%5V5j-Ck0^})k!~K$pRW6%? z`$kFF={iNzMXH7dzWdg|7O-B*^;;haatqj$L|#JCq2J$l)XfLA)Ua7D*%fnUtRF8a?bjr4T zw#qGIg&gJbB!yfx8RcS(j2(a+qCj;Qw4(@|%G$zEi}`Vj7s|<7nXd6oyfAfJ7eHFdS9hYf^rmdDuNw5M}9Yfz3K@KBqszyIkWz z5fNocf}7BqOTFL1FizC-$%iIuHvf!ND}SXTm3dm78FcrF*h* zfYA8~bUGKPr&L+-R(*dQFh$dsbbN2Q2W^L){spcKfM2HA@K<3!&4(viaKcR!k7Lzu zR;B3Mqdk-60JPTbvr?%IR6W`D@9Hg)(&fM8gRN)H&Y|UyU30Tf1)p9{Oou%9fYFfa zx~BCqcFOYSOV*3?#>>fd6Sc6RWV2I?`;&e> zI1I#&1~8PH5mJYtY6&){Orz^DLY56PD+R_H3)J!bma2D=Cy{qe{e@+zx<`O2%(;hx zD)2YXz(*%n4w<&~JdU{f24HmLw^Y=_s4pZjQ4z^XsPzgMO&I;8AXdqI)O%~ zhaWRA)ee3iXZuqhd>mTo-l@{u+lZ<~C?XmtlLsbmXn57XIY4EXKR0lv(zWbl?%=Ps zeQ}rZ7onk%J$ry^ATPr>hKzVQW1|Z!N#Xp@#tITn^j!^%Ru`SePv7;2>oMr*oYB zdA=K$d{AnP^Wak1y|ei%2SAVUpg|RM1`baOWcoX3ws#-4kMNhbP|>@LxVum9PT8y- z#tGU8mH2+^yjJ=Ij9prpvrfx0^%omXSOMP>l7m;3*6>X$2+P=A%5LMVV5~NBh90hR z$%KA4&uq?gcIFskj;o+yNF|eQO#=#w(btjG&Tq1XfKj>h^I` zO;>EJ%FzU#(1&u#nxluoixW?bbPXYo)o&iQg=oHGwIJNtigO++z9Z^B{FZlG!z?4* ziJts^F?+S)5rdPi&vvR^*KJO$a-gzGy7_LZk0i4|nVVvU5|{G}y_QSUG`>t8j!vzW z>SMQPZc99mQ>x|5>2aQ;#635{+a&j^jjQ~@TBJ%82&8dZ=Mq-3=K0gkEaPq+by|VB zCS@rt%Rywf%NK)2pGw{WWNQ0keCuk??7!we8>n&a1)DuAd3`%d<3c;{yA&QYiKJl= zVCZ#8DDh%GktjJ0;P+KeR0v}~yaEc7N_%&t4IiM8cwN4tVk64QWIdc|Y@ zEM@)Phprd&O5AP+QthHny>4iKIvD}=l~Wy*{5bK#MB(kv%?`dUsS&XOV&=E1v#3LS z?;V_hw?b5UXU{-`xzMcXIBJN{FjJq#BfU!F^&Z9gu+AZqj_q8HlKBF7k9*?4i#-RP z_W14ZEibe@Tv|52EuEdByItiY{%!V#RaY1I)~OgsofN%iNYZNHli$35v`TMv_P6m# z@w^!n1TgzFD0bPN7r(D4JO1#u@xYs(qkTf3ZQU@uMQya{YLTnaZ@zOYO5kbVl8VA! zjx2K%5;XB*>Als@?9 z?S;EnnX@|gi*7}F`=pFItQu0{s+KeMB{wlXe;rNJ-nyDFz~=o?qH=)%QWhWl=(?9w zXQrcN{a@Ejq)4KWL>s-aj-3aC6!ywH}|C2 zw)cO(y59EFBY8yk=|j#kk1YFgxN(~N{jF9p_-mu;#d)2d!cB%NU#XtI*82*tyx9A_ zztzqp@0*nSDk0BQaNu$fo1(K5o}!=5SAFk$v&x@7@5NU|Uj>($_bi7MZv{E0EpzT& zDlau0O1|yny%;9&am3~JpPc^XH+4C1opPPO&us^p%}=V`#evcN7FaG-S{KwWKKIQBeGfHDS!%|<=QK10cSGQ)Nr+`cOqp#gwdMo0| zLK9>S4(L>gt!ar(Q#N_iL=NmcB%kE-NRB8DC~{&^#0RXyir~&v|6eNtrCp-6_7XpH z0WL88yFprwo7#u$qk?o+q zMS^%i2}8>zuV}l+mw$K*zxxFwvpl-o@gsAru0Y9&vg*}A-d~n4*}xh_l`{0Rawp%F zoD#dd?L*>5q~wD{>~S6dZ(2f$Emm_xrz97vg0}I0o*2IjiFH!AtTY^x@aQMXc95E@2^hv6ajJ~D1dYkj?zFyUf|}=Z z6vhS5q%OgWS!c@Rc9faca2Hbr5SbzEH6yjeB-VUqm3*W;kq?31+@qN5y-|FxSZuFw zKq8|DJRX0LL>vGJ#0-nf;h?D`v=ZnuS5?@9YYHa`bH&!&)7=4*=sGB%Gx+KNLo{Yc zAOY73v6W^5{09Jk8-@jXaG0&aCcJ}b43Jk9$_pQo^F3mF1|Wb+)Bc0w$BS$~8G3xH zP+|k;gc{MSFBx1KnkFfeNrKIPin``XMU#_B8046?(LC;RRuzeF>9$fUau#C4{em; z)9lIw4fLk5y8vvl~(zTgG zsI5cdd^{m3vuFmCZV!Afr*?0f{b`He?eFCW$pJ@F8KPc7C8d}DG(Fr%vX#`d#&ixL zu_bQnc^Uv~fprEyz#5SaFpp{)|NPPKD$&G$c|%RXH&@2rxuxcGMD2wLxR!dt?%Q)W zT%eq}{ppiFLIwK=tVIqTleTolaP~l&UXXpO)=kT#O|)CV4wIKX+$+S`*ZOHcHm3z- ztKMzHsBG?ScSVOY#Joxpz~TJ)vnSYvX=5#;e}v)+9-y#I``)$6YB$;NSOoneG7 zl{YP&1(Pz(2N{|@vzmH2Yw?=}au16{_#X%{f&6wj9u6*$_rbkzl0?3Iz)J!@5Meu( z0W)C05*QXw+4pb&-mRvS#96e#wbkh%p;8>b5EPiK~( z(nPndC88z+o{)v`ph~mcv+LlqA`c(dt}o&92rHK?udX`wXzF&U&KPNbTht72*k^j4 zqOD1GifXj8AH_%&aK#4et_Ojpi#Ugd%X;dwp{M6X2O3r#?2H@S?NDh$_ZUx{NBLtw z$~NNKG<&Cp3~};o`eWc{&7lMK+#iK7<^moX$@uhZG*a7<)d9YVdC_M*vofprOI!iw zgsd^u{^=m~&Y`W5E_}1o-?Z`}*zBqe`&nS}aDwUAurlP)rR_dy zw|VmGi2Mn8mFn0X;?FAj&GXR*ZrH){CJ12LMNkG2GB)ca^v-52D38WOQP?Gi3VAoZv z<5aJ8sJlq1-;Gm&f&T;1`QL)j{uf8r|EnCEPU;2y&r?>3i|+rHW2-vug8p%I<*#`B zBgeimLs<#>^irIwp!{!g?9Q7WRfI&df6K9bTO3|Zb{u~8FQNLHr}*tcG`+No2Ltp7jfjL@E_iP*<%Iy{W`=g-EEf{ysU7L}o zJv4LuB3YX-s~Sof&IUq0f0x7tCurT?&FllTdzW0?*nAPOpcCA6vF&^BFHzm8>ifUm zDZ{^oca0`;<=FYp)w>!CzSVyJ){Cd*D1P0OdZ8iWAS6p6Sno~+P=&k()c57v7(LKw znXc5K59h82_2Gkuq2hthk)kTCtVQFXRYJxnf@p=2b);fN5494bC`*8?bcRd+nqN|@yA5DfUGkZ~WZ=mIouqPU}u?~=~-Xg zVW;Mh&faXv-`RYwDi1hqhX*RRo(gY>@YftJV29q-Vb? z3yK8Qt#m}U(N9+VOL|@P>&fjK2ZX7i!274&!J{k!0QL-AW-kP8U1FM2qB?NOj`cbc!ZxPI)EGpRwT7 zLBu2>hW7z=ns>~P@7>5l8Gtp8go;Uj3v>u^!+ddTl0h!M5JP}E8>AgADhu)V?QS-R zZvZ$tDJg5GfB~hd$_|6hQ^+UR0 zEk}Q0NXJIo48*F7srjjJGlkRNR_xNYk&+OCF9|08nQlM)_=1e@dynru!44TaLMgz5 zA~ESdnqCU#er8n+_U7h_#CZPK+h+Oa-3w+$Ez1 zngJAcS;1aPcai>>ORzzmf3clM87ApA;3#V}8(Z8ERCH2V23-M*-2lpztO471>`n2( zivH|czbWoLF!o0VB-!4Uky5knaCY#obc@u9QTTDvj~0-ZttW1J4s~+7XhxXG*E{hb z?+u+-PKf0v{;>?n@+IxWKo#*U!F#Er*Q0R?ao5#I(np3MawXOwgOtLm?&BgvRxOXs z_5%&a#0OgE>ypuv6L;;3b5-Dq7ZN)h5I$J!*xxJ}_1fx3dbKrk(lrOeh-Cxs?I$F7 zGmcSoAE3?5_z0?WeWaz5?eXzGi)xA`BUd-@0ABFQROki(xF>go( z`hGy>5;9+9x4Y|5hh@!<4T0*5a{78afK~>upd?#S(Uc*@OK;5z=PN!2HX`rNrqFNzvpnZ3n%=;MOdv~h7O@FZbz1R$4J}?>`z=WayKji58eA2t}+N;86V^%-NMHa(LbH4!$ ztL5`w?WQCFJKbmR3;&HKeLcs@)9x996vo(mkYqtWoE@3_9g__^B7&+;O3*mHkrwgt zzSP(4aqH8u=O0xpEABP+3@OUww;1ZICeQq|B5lN!+?RTmcB_OC}y zZPC>N*WaifFiRn0P&sMa@16huB**5Svi|1cb;L*@6B5{$1Wh8rOG&&vB-8?lf18BH zpIRmG4-pYu8LfFE=2RVKh``SvYD(*(6iiUM-yvs+y!|XbIuUw|2o2*vj-pZhOiUCF zbAkZqpprlN@O%Etn{7)=d%)C^#Gq~xLE>DM7ztx$LK$N5^?w7VQ7H$|K&w(9nhGkW zBh4l(wTcN49FGSFvHmQMo7*RHfcDrlXcNT9o!(CMl5zFTL0tActfmNu`Svcy;1~3_oQuGCwe^6QQ1-uH;)Sv?+nu^!n z^Ci%Lh`k2N8xxdUcwv|a$dQ%L7R*vdASD4{9F@la3;IhgUIidj2w=VJVrdMjUlD1_ z;HhTH<**8n$zbs&qyYe2g-x@h$t|;#QgHev@rF}WzCHlb2z$+l2vQ{SxN{Ig=pq3Q zWV;9R3U9eK$Fs$ClQUotD)oa3l1|OEXF{_%>7I085DT$jqc8Xi(zCR(4}NGA^Xu4?|&ga^_H8%5c+Jslz6Jw-SU(PvRQU<`!B(|rZkK%4VprOpSqyV zrf6+LV(A&+T*oL5gaXKs8^!EXMd~bE_xr%-Ld@7l%8;ePt7zptECmb=coLAq1rOeM z3@|_-m04+OSeRE%q6Gq_)JwHs#B{L0k;FoOVkLwGuiI8pB*EHPFjoT1A*Ng{IkB0| zmlU2SCQs4zhKS*ykIFDp#B9>Xnmn-vpR+{@c!3)y>(-KQ2%fC_;}@;&ROn^~3(QS? zq(;#*1J5E#TYMq1G{~+=?)lEDbEb`9xpfwP{H|EgsXba{^TQhgj0Qw6LSioeL?2k1 z2D4LduyEp4rSgP|H~gB&z4+-8N!)Oj%@^Ny)937sNUnN0rg7QH4#K!rT+Rn}#tJ9j zlxAL!mPk}!*IaDQ?H|#1fFs{;gQMsOFfY>c9WR3gYvR-&XF^kw6NUZF;j1kWEJP6t z^{|Ez2qzOJc`>}TpP)2{U~dAFR&R|$ZU7wW%w zv#S}1&fL1=6Sd9av|U80dRYrXqFvCuU1;sR;1kLTEHs)B-OiMQP@$3=x5Z-V$Ba=A zh@h@Apqq!W)p2z+39Hnje_IcFDg4aL9+oGi`PxBaR6P+<*M!6oLD39^-Y3_Fk6I_r z-bqn!IlM#f*Y9*CfMRSLBsgF+@{Dnwj5ZPSG6$pEP$NzAVbI*FahY^L-3{k6%S;{| z;U8zU1q1Q@TZMWB^e_)to5`y$R%qaKM(b=*HKFjlX;lXkr-I`-&q5@%AggJY2TIRy zo!wZoTvJ{{aU!Ie<`&RIk)&QbagBO}1Mp&!zap{|sX*a}5RWz93WV{g!!UhL;}C-@ zmPh3GmPE67d$0%F07&jleW+-KPd3I7u59HC*vA2e#1!56Xe-VECNStBj&}J3KrsQJ z&sHCyA>!zWHU@HcuL&u{hDrXe3VWU|AwOvFt3`O}-k0C^I2Gr19z(S!Xl)VMH#rcE z$;-03V+yJ1XCM%_ zzeDTK2@VA|<}&DDo3;EqH-YWE+3PO)HNSJUG!r|@^DM9<{5hBIPu>vYfRC3adQL+4 zIFM$%KqA*vp3)VYl3z60Z1pEU{!{vL%*er3m!aIO<1tMEjk$Bfm&kp&{5fMJU!O-O zTLN1XOZsz9<6&WDxptAGBUHY+JMp@9@Dn@3zNv|E46>sbxW+8E9)L_r0$-pZ#7*F! zMi_&JpnEZMy_nD(^oa9*u=!#Bq=})79`h~)S0!)A6})fOAuS)a@m9uqo;7^!abU}g zqWd(?>_yiy;|_!aml!HCL!#QKw~pM6e_YW*DlOF>x-Wr21OAgh{1Y^^08ady-zS9r z(emFgzLog78a*=T%HPKmv328IeqS!iDX#uuv8r41!H01TQ&+Lxr-gcMDGpWKkNGss z<@Y_R!d>L$b53ZQtHobZKQt+H!nHsw1L3LC^gUq8)EoxT0~9_e-YplVE=S95lwy6bdO``ZUpS(n0t$sMbcr8*I_)5#mS z=BW8*Wfv~Lk89dE3kmEZb(3?w|1oWx`P|g~k7>hPV`Z7ar9>8-`^U6#Yj?KXeL**5 zw2fEEhou%A^widK@5kp>Ec;17_1@nHYyC;7Q z8UOXi`R*g+_~!aT8LNe3|@R<8Hz5mg6KQ)2og4?VOl4>#20QCbSJ_Q#2d&FyDqi$1muu2mzl z?GWO^0Pr=l=8WdjQ#E_vWgT+Nd;y}$@OCBLkxuo4(#qUC0oWwCdC2GrakNednBvKR z*@TRa;EuP^xb|a`gD;RmXbb`#g{K1rUkPFJspdl1lV`l6)@~Y;f=X#P1tCI<$k(U5 z!2$Fm5?AhxZ#N&w_Kk|Tt*MqxD8R1T-PCZH-0~nHA>n=u4bPAd)Uf0rT8p=J8l%-A26NS}JI>!{`UFMMc10c=AMAjkcoXy`NR!ExaZe&WBME%W z3+mAF=S?K+uP`9~Jl)m%_%qKUHD=$UFtKjX0p5w469Wb?=pam7(Kw_P8=pEuRB93f zZ4`eI@(kNsdUsv08>%mCf8p3i{y|@f^zcP^*|7S`A>rvezl}~t3qx2_td`FiP8k|~ z4(99@@?FUntq=pkha%JD%l7ZhHup1yLIo?X7A6|2<{Lt!a^?hCyh<6kEIkwDB{9C0 zNUxE1FQ@7?G+#c$60f!CL{73bnsJYj-zFb~-1B&!mwY=T%tt>q3fn|q)kaH-J89aM zt%v~bd97NcfE`AB#(rm95Oe45b-=8z3`KjkAN>n{3?V<^B@9!&fR7VRst|9(3Mhno z9`fitEK2bc?fQEg+Zv=65OSgit%G~lO^KQ@4l;L9!t7$s@J+2z>abA@5~6`=u&H^s9z2x_Zsw(>U9#JMVn^mW}Xy_ z$RD}1ys!H(>5DKCn$H7W?Y?21k2@C8nSG>?&?qAk#jF7 z9Tr4b!mPqofVWP!h+#`29U$^pZs(o>HeV<_*0MPFQi`v^x#0Q>iR#`!IXXz?CPL9! z-8KOHw2m&k->L?U=Yv1AlvJ2MV#7PEPK=+DvSH!pny$;|j*cQ5f`wf;Bt8}V9@N%IhRP5wx zx?ZFK<>eekV!_GvG{%MkVcYlf?x%{Pi$&vA9Zfy(X~V5_0H;pgA>vxw&K4#7r@I4h z;*(*io0k-q-4A{=(7R08W~;pFsq-qtw9j>B;&1lVeZePPQ4oKx>7|P*x&SP=iK~cl{1OWVma;@B7YfB3;-e0(s8w>7KLwt*aSY zLt;}`7d(s%bCLxDmGgYt@{J7L&ufLyvlbs*Fyz8#KZiBUOMbMdfVa53aQPjp>4$Ag0s-I zh2;l_jXxO1oSn~m{ZnuJ&T(;6hC|)aUp_wv?%#^cEV$#3{Qb<}jkHIk&@^jNX<;P& z(CkH*{PJ(w@$EEA*9$BCSH3rw8b2&>CPobej;e3pH~tcRgzYOmns7s}Dbyv5AStdA z{r;h2=4Rl>j(2K~;=1>_oJnn^+=HVlQ$+qdrDOR;I--E-P?>nC$EokJM<@2CkGtL} z|Iqs0xXy1jRs>!-)B3@1-p?`l^tVcVjAt0}_!I;!sAbpAcF^CMD=ajq->>!2*>mUd z)meiZ;)4Q!^)!)QW@nSJeYQ*(S$4GFYx5n>9=KI9dc zJAK0STlvzT_a={eXV1=ltNQ)t15TiindQ1wEBTj=ck6q6ZFcL1`QML({}wdxNBBh+ zt$q8kBXXbr%$dCF>!AmJE)G_mxpQ0kbJX)6ON%l;2BstW4x#Y_JKkty$$&r%xz7-s`U@KnSo(s6J ziPSlNn+NotNk)o0$t(hB|Du0(2@_QEX+spafcn9Sn3|DHw5)SJKDKr&S4`(rI{Xlk z{4Zyi6PNx;WzrD)e2D)z!~QKaovGkD!(KkT95#6wm&R-FL~WS6`maeQ;pY4eLbY>& zb7J$;X5ZVVq9z5)JECkya`|ow`UCHTKWaWSb>{yu$^5*9y>pC5KyKEk7$mfSrdp6!od;=Z5Fp#|YVYbfpaKBW~*4lh~#3QaeZ0$3vH)~He`uXp(y|SKy zzww$zEYN`eJ=ibt-JLtkFQPGfx=Xl_jgOAie!If-D(txGWnv_xZG0+acf;egZjf5f z>kGVLrB!}{xd{g&H_1xD0lU`U(~5JnHcrS=#I?8ck}HRl^EKsa=);a8v#?S< z*HWfk>Ub$v?y@$=!SLD$Vc$|9c%TP5RPO1RV+$58DA5*q^{SR@B;6XQC${a*E8G4A zc`2f5OxE8a^NCBOIzVdkwZds zTOCGyuZ(}6NK7bxnIx21tq>fuk}7wI>;bgS?{ql(sKe(&ZOCGiE8c{+`58(Up)jqt z6y(c*dyO7uP^VIlO*z(Gcw*PqSI-<$AC1wa>B>7bvChR~d1@pfB|89NjnF&q`3ATA zKhqc5O0cQ&p_dDcol~--uB@$i00ah~EF$$}O^10^J!yS+#73;kEr!_%% zO;P%^qia6S0e?-1021VxIb4V--=)Z9yW9OLLfFb`80hGOe1O7_8`Py*)x-y5}dCv`Mqf*;(q5^Ve{_4a(C z$uk^IFz?bpEx=3l#UA@c$4B?<(-5L9aL>bCBgF~9Cmpv0AI(DQ@?LslRMsBnn&eaBui2xuJKj2R6A{YA_@%zGH&6kyiJKP>MwfpT|31ky(XI z>?GzcXsh;Mn6s1AOl^L2b}`goI}P$y)q1xzhL3cTrD#{HVbiK40r9o(4sskH`xTlY zS2Qg6^{oM~7E;MT^*E4#6XY#ZGHOsIA;Io|i{c7O=^Rn<_na{*R?*1BBY-auUaW$$ z4aqo&FtBS<6Ao1r`ebIaUMRnJzeo;_U5OCKS2{QWF+38TfQKu-eg|m_*o1S59O^o(w;<98^5i#=oINgq$wrke*XW&b3H&dnrSFI8;afDCjDeK{)F`0DB$ zM2jZh)A*fVo4StmFRTXbWoqc!r;EJCdxw_ z;@9F61LE4Q+0k{S{Ur;7GC%0GMiyFvwqj#gqm8W4$`J5#-+_!^-7JlR!QZSF#x0?b zvb|e_r9X&1uoaojAzK_nKYBl`a3lJ>=%)_3udBnD%(%z*H?C+D4 z(bdDR6YgIk^gS-U*Lg#0=HtP$Df3nQhE0xtxd4|JPwK6@nz=$#uZu7EGhzfgeN!FG zmUf<5*FYL#{xivB9a;~O{Jk*Y+TC$&WKWbdx{(|3=Z)B-o(IOW8-@RElG*z|Gs(<;Z#(yQjVRE+Fz))JqvG#+ zxLf~==d(Y$`~QB9xzzvigX_<}rN3X29`!H(oc($4_usE1fdLlGZF^X9my_)_@J95} z_5<_X4eF(Vcl+IbO$O|4mOdJIZ~W-j?77`pXe>s=#|M^h86TGmu>xIe@ zPC}skCa6lQEWT7Zh!33`LSt9asCo`08f*W7H9J z8Ox)9OHX71l-kLTEW`|xM*|BRA;3IYkb@wUfG>r?^5hmIwj&T}ENqBqWUiVf3q(rL zj7D$*mfQ*iVB{Esco?E_+}Fqj%fn3*mkAI7925pdCC6m=ZDSauw3>Z_mmzUp=@%8| zz(ad6qyrpG47W&O@u_kP8GsS&mQDg4%m`Q7w;da{?RpGvud>JeSIBuWl>lMXI^LQP~s zs{zOZtPEH}8Xva{VDPlDu3BJW5IH2B300-@L;>K5VuIdu#dB;tga)l7WCn<%Jn0q~ z4)C%!zYDi7qXK1_&?AE;A2DK{}8Oobv@@iEj_E${f z+mZzZN~wG|bCj(!jTaN2I$dOmSH0OYtztj311G`Sn3QE2a{MtxZiO!jM;acjJRpiX z?FW#g0?`C;8-ag4yP6bItRj}9NCRH}RbYP?ae;VonGSBRMIK>6V5PjOIG$n-g4_QE zv3T8*((z|6a=SC+zPx@cYMEw~!$Fwhc(|}QRvPd)AkXnbS`>~)2X{^VW12ZBr;lD+ z#X_*=0r>a?ZgD0;1>$H>lS!H<4fqp;vL2x<6Ty6}d^>d{l>pO6XAV*-0;#}1zg+1= zkR*{ug$NQrLxw^Ujy%jixsxwDQQgL(u8D!YeT(te_7R)aW$rwWTwF29)W zEa1Wf+8#>?+G9dGh}SGRG}#_7Y5^J*lS^emF8MR=IO32h9>lx><12hku{b^`>I zq{1s>s(1Xr79UHjPLOk$&@?8cpN3p!B5natw>U^>IGMzNb(v<{UAveV-ukY$b^1l? ztpB+OgscDVOKsosHE=G<0Slh?Rd(#ezvF%{KJmGN1)Uc(eu@LtiXY-2V0Hoy zOrSqgqnt@K(E}y1c*Xp<-BJ3adP4gmDmobvVU|5QNz37)!x!2t#;Uct9`(#c#^#sFkBKS!GTt*Cn)oxp7=H?!4dNE70ZCz+={l6UitbLUCFvY zvFPH~uh#T{p3HMS)DL{e_z&O8pL z1@&(r+@>gs12p?pLygFT8rZ3@K*tG9BEGfqX0;9141tF#eD zm0BN}VbWvy;p*}oAl+ZRuD|RMlTz7VX3m6}L?o=zXe2@@q7KPmjy5xqx2RPOwKNL7 z(rEoIV6ok-iTZ!HdHnO9Zw46rtC^_zUTaVP@6E&lU9=MfN#U!XXs;XRzUN)nL$%*B zE_V|CtC{%6<`I8mrrac&+f2->I23T-^Z%>O26&N z8a`MRIMp3B-+7vA^Ju|nzv@pKe=#$4H~Q(I4RWIS+1hjU5$i;!0K@&^2E_Z|zn{LF zbP$KL1R9_C%8AlXlwEAlWKDa&4Z6k`!LPpUw=zQEW$zefVYMb|4RdE_Qesx-D`EOo z2a}CrXt{~Tvxoe9--3z{V<4y!AI*GO-j_6+yu14OA#wA2{**Tp%_V`n**Q_5V`Sk& z^%3>T5xKvGV-1$RrUo6pCZw7=w3OPeSz`^9tS2zk=aSrU`$ls-aOlp+4qG4?VecaS zMVJ8AdOY`L8LClIQ=~0crurmNvgZUo`<*a{j1rst0O4n1_6sHAxNC-Rh$b1sMH{@4 z$>s@89}>CTu4@B~CwAIU4TZ2EVMx+37qpf`@M|7-v2NMS!6wDyz)-0Vhk# zDI@Y_eG?ueRCA;UgJ14bPZ$pb9}ID@K-bO+koe7b9O9d}uhD~`RX*)SVRYuc|3Th+ zMK$4X-@Zv8l+Z$vjs_42JrwC`=twgZr3(nsn}BpAgx*8%7<%u$Nw3nSH>pY&8-k*o z{PsToyZ0IQ-uFAkea{OcVa)ZNYtHpiodYTPvpI+uvE4=*(IqfnkrWFpS+=dvJ$`<^ zgH&<5S!HA4LS8`%%LMz&av2|eBo|`rZhHfrv-Bh&GH>HB7aq3wK4O_0n8>A~yy?{3RBpCaLLbNK^t^j;=$|{Ql5xY0&9mR8=!erL$qXBmnu}HU?N))s2OdDr1Kyr zp)2psP>+;cikit47>19s)5PV&L$D?jeME&|A3$9v7~p3|Z0vNQF^pO@P^ty9w#he~ zVj#tK*|Qv_jSKUc{S*ZU?TSKQXA5GWc0y}0LM;|4mcpOuaoV@AUl%p2jrBS2sF;(` z5JIkG#%t}E6y++66|SU;TZlhmnwW@h^HoIhN_{OFV)Wm-H}`|m^4z9--ozdFEaS#) zkoEU-b)wd9FRqn)6?{Ej(tY~qUdp$6c24~A`z>S$Ou?TZibw$#{=HDKYpqtrgN8z03YAgy-bAhEPa80x?U@ecqh_f?+Z?Tdi*&sM7)xGrbfAqL zgKD-ufht)Eiu+V9LTB%*Ms9*?{N9Z65@U+MNcL&XW_&};&!NHTB{G(L6?>ox-8!~J z<;T>0y1o)V zhZcjB_6NYi6OXndIvAmBpWnhGwS7pXw*Jq z%*yKh)Ex zm;!=1Ci<8(Mv)5azkonr0=+v(yE+xiP;yUCbKc7VBpMBZQr{)!ULN3+vKH!ENQO`T zVi`e)mt;^k0bI_Z({F(SxIYT6$Ycd3Q8B2rnU=hZ+H-6Rj47JPK4?LNi@^m2VCdzK zvJpf=qG2QoC|XWA**g`>hqGv9MTS|$V6u2byKg%Wi2_uCy68tP%iShYkBk9H{q5c_ z`3glnk$Gh$oa#8Vt_&{4TwZ&QtpEG-dsS?a@$iUN^P3ZH_)m8S6kIiBgS?EnqdMMG zfzD*3e**q}J<`#O|6W>7O4Fl9g1Wja>&2{-Z3|k_99AZ`x?cR`{qV=!{*Qag`2%H( zSuR(z;mT))YOUQ)?2G~4vgTc*t#2=jYfa9wKm7IE?%J|FVOUQE zg%V2@%6DA ziaRuVZBVhP`gre&-P^w}NA8ylJ%Av#IX+w6X<9CZ+tu%Ji(QRr$BU+v3heXgU5!5_ zYDjCHcwvXM8U^F(Bp`seCbz2zJNz~xm^I!l!zyT0S!gWlljbLxr7KpS2gEt26Q3UZ zUKu$d5trTEz74p(nu*l@9{oYyE*51ti;Wk5)5rReQ_pxVV@e!L;k>Ki`0G9H^%q%g zRvSuxnfWs9S3t(o1J%l33;8xpRgX684A+?7H%#5Dbe%j_JN8@Zrt~U!C3y0jie-5? z{w4Ci(gOeOv8T@Rp^$Wa7-9+<{YW><{s>A=iJZ|o4y9-YLG}5_msZ0Gw-vou?cFTe zLg0G;K!5kggN6R%v41RjrCa(qwTTEKh-iY(7OEt3m{m0KzAx1-RLJFP=3A)L4RW~8 z*i^anuUf)Cn*1-?U!_;2NsHUR30tPECZ|Um@9?#Rnwj&z*Bba*!hji=N@b$0ez!R~ z@IjttyZg+jjG*JDDdRWoDV*Z_AF+B>0=C^kwH&KIJc066#7D-t9la-@Ic&|djeF@e zb_CwE3s2CJf@Wpy!w=2`4l2wsulM=>9ybVOR9HZMM9VdQ!OhjYzrl1zFMfX#lt$&G z?fAqqf2xKd=+1oW?|F+yAIMDr2IKIBdTug#bMhx>Qt-9Tn*1y1cX^+bLuIC-Gf@}e@a&fONM;?b>{Au70*Y78H8Rum?G#r8cIDn%2zr6`{n zjKf?X8YCMMf7wz}muJG)15C?7N+fJ_C=*g*Ul<{k@{HRID;S%UM9S%c7d0hcj~RwK zu0@=NmOhULFJZj`j{#qec!Y?`=-w0cr*w#Z`3faNPIWcrN3=_Z?)Rx5OM(>G@cr(M zNWV93EZkHg4w<=Mup>_gWQcMfzb-fHg&L!7;*zq!C$enn(BHO>}Sy5W}_8C&j~Y9{rW+Vs6n&%@1CG#I#2MlX>b+1KAT?tN_QmuGZ( zDZ~J$ILIHyv{Y87+8E>Kufoc^GV(#DT}=jhjPW!?;FM<~{pH~SE7g;E>r(Pha_)<# zSyZS=%3FrYV~@c&(Xx|Ib5lhdV5wbV`O24xeex`*I+te5)VWT$(HYG{L)^3-2q{OMTDK_vC543D#1_?(TuY(}` zrwqw!xn>A3{M?4nxAzcJ5YGo4G#pGMDZj9(7S@k=Eq>SJwGFJseCs)3IEY&PwJP?n zjy$xR4{%4XE<)h85{Yk782g&_sPKF>KejE39fB-13*=#VM%Pa!fd>;vS%R*Qk*rS@ zp>$=H0COJ#3OQ5=$a>lsYpgc+Ob^|jDy;f4=Z+AUk5FW;lQ~IZ*bn9m)#pqHFk!fY zAF83&U;3SbS$m3P5jNybfi*GMO&-In22~8$mrR`JmH@Mp*!n02!r6-%^mgL3+P}im zvlOVguQc^@NME;CZ5W+P-$0q_KQe6|J&mC|oT#}(DI2hA4BDv8yxUVy5sRhZjY#8M zFcKFb5?wUVZN#|*3coqmGn+rd6gB7zJ#;fFLq77GokfV7!YIn^)W;bzr}Xnh*fzAh z$KRV_no5xr4%)An=L^DZ$|UYp=(2>&7t1^m(+aH6zeBrFZu|o=v#g?hfBbz>O|b-E zIl>?&dcOYID}in(KcL^?DbAsgM`Q^8^rJ&+$6RVnIW@ohBHz=_Uq5PsHn0-ot2DBM zeUxA+r{~m_%fq4<^)Yc(R$OE&W5z8F8F5vXKm4F?={YFD2q!yv{?)mpi>5-YYWpWK zs|y`1%{Zjjy<+rL4e8RyUmLN$=2LSLEANr4@U*w zZ;#Ae1AoeH{Pudm5t5G%WhNSd~J#N{n zF;sj*3jWk5pUKs@;nY8x{15c^Uul66&5xql|JLNCiH{PUSNK{&d}Gc(n!I*3)06YvA0b%*LeSb&|?o+-M@jWA_TsGMF}~%tWb}n(TUN*MV5>Ms3=Jb z%P`&(EKF8%fN{biTsVN8vD5Go3(7qlG`h2|D>OnU3I&po1CJIOnPkOY07;a9pDw>5 zi6rWRsj2sfso_XMQ2@U9`kcYgHM@sWfdGF-WV{cc!cc;WprT_x?1PW=T)KHhDe$6>WFqt|9&evzzkGobAJqTW-m)UO+!h(KGa8C(@&~^oDOw%mIdWuwMhX z5t;`$aL)U}UrP++t)+qDwjlaCpcl{U1_tu`9;Cf)&`x5q&sJc&{|U^0A%21PeanBk zH`xZJs#0x>5rfqHDQ0{uO8q+kq*xSKzL2tXaGoMASZD5mUs{22fRk} z1mUCd$^g#`hQPE>B5$xkfXG0CGXHpn2i8dFK92M+i2TtAO`n@c0~TLPBTY{x(f=5r z3V79lBtUMFK3XDZP4-~-3G6fgyu*?ALdo$Nc@U$@9|OSMOMre|Fzb$5?uO!b&Ytwn1yhFw9R2&Rm$wBeeG*AbQ>>=`1 z{&RwMhJW06UD#`a3>vF8vLRKDu%FgxrDWMlWF1?ORYSl(Ie8cfWH~^~#}B*(k!kY> z8B%Uq5WDx1LZ!&pf07pQ#P9-1@rGG1jEpJL<_qzw)K4_h=^?RgG;I+c&@nrVk2_;# zB6E8p`$vj0gy%o`Y$&ai0cFP)i7kxudxq_R1v&Rt4Aaab@D|~352&3&V$)44kf|<# zLE3f_L7<3lHekIy3;}s)|6G9g07@+TF7f9`+lNdkC@Jz4G|fH|>W%c(J|{?R6ZgMJ zhMxoR`Rs!-ytAp576D;If=%&3cPx?rQ?dUEXD9I1yTVce(}KWgq+13}9~Q!mC6KKnm~8{8o}>N3{bN+Y9Vp6l zf?!J!;X?}o2_yj*45WHs`wBsD2SKbeFT0N*e~0!+EGK$wZ)?)#MOg0{|0#y}WlC%5 zL+340zm}u|I4Kx~-BW{hTd3*cs|R&SKH;zKXVQRf#uE38@;>_J?T05||FuGbl#$if zWreqdG9f_Ls%hXE7#DyG3Qfc;^5d62n^<1!Ifm&{ zc!NaQ=sXMNlIJod(?nzns-DnY>_sG*4I;^JI6(uD%vP5#D4$q9LqP9F=s!$~x9C4E zh59ekEHeba5uk`R+wNA7AGGN2gcP}=4|MfFDAAXYvdorXwE&JHJR|YuXD?=RBdo&- zD)1J$F8a%&2xYNAHa8DKY99(+LT^c&1cG=HC+G(&^yH4!Fd~LR0}p<}B_+wrEI{}j zL%tv3z*y3cbpInMiK?jlH>8A(E3exeZ0k^fTsm?(g2yJL*$+`5wqAnA>9&cUP=o>) z-+z%p64*6(7QxW1k`jK#xeLs;PAXYa!hegaHHt!v2S?Y-n)@9oS9s-)!YC`SJi_+NbOPa%1U5 zqLs?1i}0Lxt!H#m)RyD;bd|(ObM42zkb4^A>tnRmwQq<*{?4s5md!>sL1xr_-tW(r zqL}8g)cNg(%M9x;jMeqF`l>7vR--BAs!bFEo zu*Z&qzPCN$X-!Y$pa0~jh9UNbDn+Z4$-^TVr@O&rHr9foeIeRx-nTuCLq-P%X4?J(ecAncjwQ~ zTLUpScOJj(y83qTzS4a9ZTIh=|7I({{qy_s+wq6#o}Pa=@9-@&A-&yJFbQ|r7KU8n zAI`f9d^?oxsoi!MqfOa%IIGt`ocD0}PUPJ*yPYU_N!d=cK+C~S3}P6*8~ZP|ved`2 z-FUf+gWUuq5$_&WiQaxMQH}dwY~{nfWRwc;ev1B6`~6hIf3cOl4)@b7!ttDU>ooh1 znRfrMm7Q7+KW4iP^M1Sm%w2I%5G!$XP>5CG zJ1k21hpn7pQ*l_5<8^dciVOdTt(@j?R9;q6aa2*&a&%N#H+-YMiD+7siB)(iKo~1v zre+zzUjwDnM6}IY4%b@+u#Y144|F5wtNaPfL#g*ubO)^vPpuB5aLU|D^BHs=o}<5FS?P{L}&oEDHyHZX*YsPH z#FA<>pP{y*t9is= z)#dEAJP^1)^ZI+n%JO&ahA zJmlFYWUzQ40fSgS^gAGiDIgy(qd3)fV|R;OxJjPA+-`~G>(dB{01$ntKNA9f<=^Op z%#GV(3owZwS`f4(&>`7DR@8w;p2!mt=n(J}i79bt_Yr_2dx?cgB!jKD2%OIcKcFo@ zu(@Lbc^~%bnx8d3Mt!st<@9WF+r8}b=Tgph3wHknoandg{5rrE2~;W%ehljXgd;@l zx^1r5sqbhoDC!1}1_B4DBCQh$*oJFWA7E{uS2;w2)*41vU(jG^P^BBKrcsJ%9pbC>S?$ zU(j`eqZFB@gMJ2?&((OZ_+vaDDrWkQ1p+kKyxxt*!xa+VUuR3^pa4EEkT6g5CLQ5d znVS?BD@;zBq%n}Z;ID!i!C3gt-^Qs(xw*o=*b4p9iZ>Q11dP)S3e2WD9j_!RDaLmg zgqSg8!kWR5$^+|wgRl?}m)_?K{xG3mjJ4w8LIj-n^|cH{O3KB8fZ1-~W>qoaP=}qd zV>Fob?rd-HXg{fwVHy3!D}JSQb$T!(kj+#iOhTWEp3AV0b&pnbzI~pQyG>DGgQq+3 zUK4Q6SCrG+h})(!0IF34nDzwyW@Ufn`{? zr$E%@EzY6-xZ~xIY6cf$giwkFNtaqqz`;u$V@qL3-#F0;1YmkW$;oohG;6o5E|@)_ z;N@r1aD{tFuvyU#F}IK6!;nOXp}==i=jBiWOZkvs#tdR}J4Kdjz{0m8c1F)jdG>o- z_k>Ou5+9M)ytM!>Ck;p<7r&7^Blwe>c8VP6u>PcWOi?b03cn}2V3KhG;OvPS zk1;j*6GF10!BMsvy`N#?(YinIFF!GKjR8Oi5=y>VR}o^G7)`S*4uT%QLK&~NXI|z5 zXY?6t$j%$C8osrvWH2^v3P7d2k|S{oD-pyTCWO8ooz`1?>zKZK?1bO({f*Ny@2Bzl zBueIF9k-Jm$L?WLI*`Q+3e^sRSn;xj`GGnWsgc7u{mTjYplk)wuZ*o>n!S*bZt>^R zvkRb5cUU(f46{X^g#Itf)*CO}8UT9y8g&XlMk0W$gjENV(Ee}XCZk{uRjbFxqG`mQ zt&dV$sYJ0UMk`(F?2ab0YG^Bsxm)!Gg8gneJ^J>%HV|+zRyFpGy*e8}G|u{~@jsTW zUIA!#xz7k@n-9{hU!5JlSGiPe-icx3Z#h}2BT()phrsNnTS@cB!lV&AV!<= zKnuCcdi-p1M=^RL5`Qcwo%Bh~T~hq9oOn^&P5f-~Ts!xE2t@Fl_F$&)UJSGH`1ieO z4A@>Gw<9s_Nh*WL-z4?sN~OxDWTxU7sl`i;)b>AgS)QC|HoGnTr^6N(^VEV>_T}Hz zdOft;io#0>57EDp-!YuBY2?1{`)>)9XXhr`(ePGA`~6kTERVzY_yhRQsypsggK9+> z&?=o0&Y0g#B6`D`7OpFS1EhDf*G+-={Wg`{NLRbZ{tQ`Nws!Zg?+4=_>_1Gg`FowM zcB|fec!uk|+}nPa{4ild?)T@z4?*dVd;WhkoA4c1H7zVSm0Z99`R`*~!2#8IK|VC(|`PB)+vNs|VGL@Tk6@q&34$n=JUe4+__4kd4* zcnvy5d>7C`)1Ok(#nN(jS-Re$!q&eV2D{DnG6;yZy+ll=^oH>BN0=hnxYTB&xW%h_ z$A$-d@bvLhG7&oIGa3t9}PlVo^zVqyqX zJ=qAgninCM!=vA|s5xi0A5D-c+?Z&yF{^Fg8}0)nD^lewzZ)XZr$cBWiZY;~JkrM# z79)&yFYBlJ4ipF|mgn?T33RG7r+4%LicKK{{~C(Q@}LN9Yl|VCNyab0!M>SYw>j&d z_chs=e75hsclQ6L*v{kxRlYORud6_9rASgO*>SQ18QzBlAn;S)+%QX?PeWkSimZ$D zF)4e(`K|`%^cmtWz2nWF%UZbL-Gv%VqvAe1LLlSGebN4o_mME@@kh_ujP!5izUhgyic?2NkB8=tAfKgm9 zZ$Rl9Fm$8O?O9p2$8X^CU@E0;S~f=j6-__*(_#P1ZkGHd^0F@SE;JGMWiJhrd;O+h zK7rpd>n%LY2}ajP#w>+Fj?adLI!)NA(e8#ycy-{fC_Yz)BikYu>nZ6_3JnLCyVhUC zZ%@dxTR}&6b%Ub|6Z0wFU_XR($=6hUfl%;Q*eBj}#UM3Jh=DhS*j06)yKbr}vVVVBEID95#R^ps27&m>~w_1S5dr zo=Fqxg0vNSU$U)+-l=INq`(5*V@Z~1H9nH^`s9bw6>uIA(FpAY_A73ltFYLeW6b!J ztWL&Jh%}2EV0F1=`g>M2=Jm42Mo0x0QC1ROpDU@#`&*GDq$+HLJG~SXoGdd1!~)DX zm0wqrWOu$QFj)6N^sjrfi&?1|TOtbpi56<= zBB5Pd)z0?QG$p#}VhK@40x>WQox&u4FKuF#72oIg(oWTn!J<7J=nB-XZ z8C((>Uam9BSi4qCgsm9mq3<Jd=^`z0U=n)3Mh~n z(`G?%$0zvi+X%AYqI@%^)2gEfow%sxd=exsgzV}0lzS0~JvIB3*n-7`q}-*BN(%Gj z&69SSx0Y^1Ckh;%z!;`csHK$JDEF!|#1Iz?aW<^Ay5(7mvgrkTW*90SIhvD*2P@1a z4PCmm#5C|J8F$pZ0P;EXh9M?vJ)N_!LH|`q0svkECHk?saxYqNyaPy)`9A_obnJr0zaiI}D^35YRzJzpDF*#e|DR=P z_BVUOdi|C0T#Z)z4L6@;442eB{0%oW0oiT2W#_)Pp|t$Z{#ll0`BNnXYPL7*zsnG0 zk%*LP{4|YIjM-#1f}w+xRV$xOb~HOCg$G6dx%IR8bPdlrrYG@on4jtlA)9uX-jwwp zNd7EmgyS*IoAFnEBh)SP<9M;rs;8!_(>u5s8Fi!ZxBFU2_9bNbs=F2yEakO15+U64 z;Lq=G-`18A%wGq60}!Q8pqt6N-bWFfEi)>&u5d!1Pf4hmSK#~$}GcKT@EZG z7$rV!Mb>gzy+iYGdyqwwV02>y+apzPM}3g@NRpU<4`>2sPSo&EX6>RKG=HAYPBam{ z)Ljf=RvQlUxr?^QVLL-_KgH1I3LC{&61kVi8$QO7ND{59At-_oElm68$!xbOFt(pV z++eteVdT{vdL^$|Wm9?Dl1=Y_+PalCa@w{hLFO!kC}2A4I5~TI)_I&}|4_Vh<5}w#6edLm?0zK_zmFI(WJo^(vjJ8!@ zhA6#Hz628+2z(vobawhW26w#vGQOf9ATov+>Czb&Uvlyo7Wg#bG%EV@?-&jTL8Z!?;br%htY#}kcn`a!?HFBn>}-FvHQaC)!JC_=Dh*@Q~&$C6#E^u?-E zqnXz`>OvOpRnMN4iw&RMKP`QQi#MmO-oC^_K3o2st3N(Ol1X0f#F9O`Y_R1Ky0VHh zaJkw_Sn|Ex%hB_?`h*kCyDClecJVXLFRhW;%^YEK9(*JW-#-kkcKLl;mGI2=aO>kv z=jYX#2aIQf3~zp~)x6U>?cmLBiaQTx68`gjB;kQWNQrvkpNn-_TJ7_h8|6Qjdol5H zJp~ib_;_!!qzm6%XB@xot`~2a4iwrApbC2SoeT#!Zf)LM;RrOE`*5KNdV8~> z9Q=y~N62#^zQMKodLtMo-nE1zUQ`Z&k>_8))%t1DCSQ=~QxfL(J*3)E4n@S~6TSS@ z$uQsRJ$7kE%463@_KVcNFf;$=#`IF2iTO*U2x|_x`xb_IbSp}u2q@{Lrd*bba5+@B zgx(tMe+iuxQX?;992#w6UfcqUN)^)PW~eYNyTN+iTi)VYR=o3oG%}j{IdM;0n#iv& z3F!4@T1Pi13v&ZZ+VDAt2R2q(_oXYi|M_53hN@5tHo*f}#4YJN7?VjD7b;G|zHkY` zjN$;!a{CmJx^d9ptap5o1=}fH_PSU(AtQy1$9wGEErl-}($G;p6C*S$mF5OD+~blSwFO1`B*m=@S^`_ej(MMBCw1sTE)XcTR1}UD{86n5@ zE_`)iqRS=PD8CRkq-TM&VY&P;sh-SpPw$8NJZj>M6wW6)rDliaPbH;v!^CH?MdZgU z${aeuMf&W5FL*Vwe~rpac_!WC8q@mi{iMp_MJ4&4atV!&rD8Sxa>5lL6jL_`%efVQ z>qRBt&1!X-O=!h#S*2Mc#vt6QIi;A+0Tt_K7*!-*ED!IcR4_r$PcYz`{ z5^v>fbIkQ@*H=Z?+URfVpoxoajVNK5Jr;y9H4t25QwzE^hqtyL_Yy~2`%}ek6~PT- z)$oz57T*ueo=dHLr%txK7VBNcK7Nd^g(75Q>717F%hI=BBGyJMh<@)^;Zohah!ueD zJ3ofz1`fjQV^dlGy)2FMjuOY%wFrg(ICC|UvE<+h>4K<;ei0y9VG?VH>*51UORO&_ z=wUbD2b7v#)9QwyO_y!5XL%W}t*u;d+WDORDI_^tVQ>~OgJDs5Zp~Fvx}qUp%I!So zQZc5R6~0jXvh+<3R&iRnu0U`!hg$TRoGNp8@-wrMReyV=>#v2Z+nVVMt5`i^(S>pr z!{EvFqnzGfOCf1uP?=-1V7eASyjM+iZIt6opT_t!)}}TcbmCBJvr3B4DSnwti2$_3cZ641oyaVo0!OSF?<( zUy#E((XjX1pWUB(lrnm**_;%k<<1cdT`$8LTKkjx-NJu!^%x6DK$Fkc$?)vj_5nI!xvrtXZ`K!ir?ZDmTvF1HWrblkt@V%IVzXHSL#3(K#(lNv-jvFI z{3UpbWpn>t;VOKny(axWV#m|-1J?oWKL0EehN3e2&yiuz%3SO1lp2#YAyML*PEOE% zWA^=1p7%0quXZjR_>E!t6rw(C3c+@2A(LJYWj2LdF1mM%KKGVrtP=>oilX~_o~eC3 znOx&N@`3PcPYK!R043g|db^rcd)dYE`6>&2d(k8FdY;|=D!z1cE%_|q*#7G;gK4gV z&m|;a#OI5(UDn>J58ax6J%^n|`aAS}D&iUDUc0Ks^&JLp-<3bMn{~SxTbvfVK_=J! zNe_6qoG%@eHE^>ntsuL-|0e1e0R=NXZO~s`o1g#p)5! zGT0VQZ6C?xI2sN<2wzNjrE@_(b1#BJCnEi2gil+rpP`n#M<|*xQoStv{f$ASm`~&_ z6)_!nM9cy7;U)P!k|;}f)I^JjsZW%hPe|4QQw~W~-er^xJenafD%&SICnGwWE~09g zy2dWLE+a;dJI0bOy19(HRVp%}EN0L!u!}@7`Z9)vIyOx{a_BO4ghU~=EVfrII{q?t zIm2pp`N3PYxLMmcFR9oSsdyRsxXOb#XkToqeEf-_cez^3!DXD7VRZUz{KY}M%W~Wo zIQ9BW!r#jT023A@jU_a~f*vKLy-a{aB}iw){#K(VVoIcu#v_uk$8A_f(%0-#aa7XO zbXSQm=|uWNMuD_M?lJ6eX#(3Jlzk;hh!o4Y!l>+(Bp#LIpIA z>4a4F9HK`#3eqa}5){*QDfPY~V~>~|KIRaR<}&&!y*J7ozwymlUP;p#&IKLj@*^d21oA-Gv{pL~9_b3+v zW8CiOeUjBTe~t3Uf4NgZ^6wqy(aB_r!QVtb0ctbb#fC@O#zzcdY8#ZY83TMA7|=$^?&GCTA7KqvOO$?<1l`OQa~qX~|8jgCU7+ERZNgma zGM1Idhl`XcDd7!mY0t(pa#XX*<=V@0R&!xTMPX75rbijr=n8G_lAxn}A9#i1%aXc| z(uQBwKQpb;i~#e}RnsU6>xvkA_JVl7>@2>@o@lE+^{U~l;`ULB1vJHbb$aI2s&2@O zS>vjz=r~i6GWGH54d$w5_4uW%>ZkQpTn;tezsM_(N`5ZWaUE6(^HzQ}u0&U0k1Oap zI?65D%YSFpi2KrQ995R87lVJ7-t(=tORJM6sufbFc#o(Z;Y(qZrQPGJ|I}W`>`>40 zF4HKgQewO2c8nF>aW2PkohvVGaaKccOGErhL&{B7`39mwh`Ld<(?)zPLxQCSQ%+O6 z+L$F#m%-HZeKq6c7d6naseCo5wY(|DFB=AIJ`8ViebhYfmwi(aZ0P80e4J*QU4I!x z&BoI5OQJ==sO1eL-~2eyVeO?8ONxs|gSxsuhfJ%BK`WVW>k?@ZRQ4tRcxzx*ZKz*8 zCrg_}N1MN6Tlc5dl~Ic5;|33h2Es2**fsB@n79=G`m~q|f^FbDx*>b5HS%5jo6ffL zmC8N-nW_E7hBnnkgNZ$(JHjw zArdff$G`8lSHE!Vzyl{M0Rh~-D%?ZU!A9f$U$TSV4uhKHgKF2k>Q!l4azmn31F9@T z&mIjKYZg8Z$TO5nHDMh#bs7@;J*2`rY{EJyIXob7-DMv=jB4pYIt@#Yb-R*}sII?t z(i{ws#nm$pgStjE)<<3oj3~2?dUhqL+?b5U#+GT3Cv{|wvbB%KnU38^4Pj4)aBE#4 z$FaPC%!jO5SrZ)rv9)gk#^X;03Rp*yuCZm&<8>!}k~w*Wv7PBG@7l=68(Fc5U1Rex zh3%{pX5_tpm){l1jau+cjOUCYOedNr#@0F}=A1@Z1V(jDYu@KfT6euGUYlIsn%ugc z++m&ClbiZzI&}~*b(Ax8(lvFqK6QRQ^_6w{yWI4J>GWm5^sk)h>#pe%jhy$mNs!hg zvD^$%;0#IbOxj5SWMgJJY6QwQYyWYEPAicnaF*I^mif;NIOp9x%< z3S6F@Tz?<8x?r}kw6U_nwy}1TyRxyd@nK_mJ9lIE{_?)r=BJINL$=N1xTVvL&ClJ7 zUvf9UIWPVY{P44S;mY~L@B0gXHa^@0&I9v45D3kKg|>)Y-jlj)kv)4)QL{yrH%EQ8 zMSC`TYjca?^(<4~7K_jzZtrNE;lrDIkF_Usg!c4qzkhPJ zXCTyLRI_jL_N|%FzWM9-mM;5NF5NFScWj?^+vn{#o(((S-gTwydMWhDBd_z-vt94k z9lkD~{2$B*o_z|s-4ZNx5Rx|^cH?po@pnF|=3|WZSlrn`!dZP{%|WuucRdSO9P3nOX~B6Az}U;!igo|MgfYC$w7S- zxTv%0!<{)4fc@Nt^JWGF`T~BAJO|H!C{O@q1c(uzOo4)AAD=VA2%4%X$Id^mpF)&07igX&xuh9 zK$G)?Ip`04x3Rf8-J{+gFB1r~kR)#17jY{WFMeLUz>*uy02pCJeXlQX-kwSeLv?2e zwNOOB$ES?QGXqz`*v|=z2m%GzFTmJ$`W}*qw9CQx3m`9a3SWK~CVb|)R1~yW{)`eK z{7podF!9FqQmXE9W10fA{rTr6;Jxrv_Wct^Ea=bZcQ({j{0Gnr>_wjtMJ*a6Ku_rR zIYHAL0FaMdLt=()Vi{+ZG^2%Emm}FnDb|#tZwWpd%+T3YiD$e2nvh9%Pc4Z{D^Dp? zcV9hC(9AuSQSYN>);;IV!A!kR+Icj^kNBY=1t8UJ8K-R(XPgWt7_wea;`ua^2#lgr zn=ShEw8pI4J@8fmI+j{HQAjJ1qhKz$c0AhmiN(;HNNv}R0$&3*3Z7a-(F_W9*qa_k zaYrS`@XPbzIJSq}S5LlLkEgzTPQZ6THcR|?MN|;I{aD{cp2dz$ZRxASVpXmYKWy&_ z7F2k%_8d9s1w*k;|1FE*_rXa2GGnYZsB{p`!Yo=RLupa2OL#&JM%;b;4wvm+~_Kf{gv3zeu7rHoHbixQ9?o zQ)FbqPE~CBu3Z7ELN6dLI0skJ$Ml7HwCNWKE4kKvfA<3L4+J_AXCOzCf&-=Pa^Em< zN}wKx{BrqXNwRkq5XM2U0s@@%V8ms%b{^v#e}Q6`oj3Ix$z0(aS`~L?~AxoZCTgupPL8HEn`!w zu411Xv)4Kt8`@3=Uq4@G8o3h@u<(Svbe(B9Xh+s#l9u-R^VC{%HV=+glA-<`e~_vB z0+;H>mv@p8_r01QPG8KkkTE8);QZP|J##SoVNGOVa0xlRNjNNaHbthHjMs>0CIi%Q zxtp;uZ&U=}|9cRw{wn9?-x$N+-} zE~70YJ0VBLt;4py@P<)R1-=vYs~k}b#UKeXgIV6f4#b0>>B)64iA1_}B>hHKL@cBE z9uT^8*2OwQ^*$BUcmt3bSO%aY*?vEHdOkbn+FwBH|Q&M)77T|p#FD{NUSm92MRw(lz%)IJ?VF>EU z%{S&2{gh9X;*pGdpjlGU(2Uh>+e>9gTH`yhXCimD1%`w%kBBH~l;S{lLz(M>p;ef$ zyIrFZkRJPS*9Np~rrI{SvyOsLx-R>tsxXT0)HbnGrF@l0F2%kZ`81Hx*Wvkc?f6$+ zU^ZuVZOCTgE37};?t^~hyHgSD=g?)?PjPCi*j|FaOrwJ9y%e_OC>`E5YDgCHHU)`i zkZCXQNu4gBq^MVV7%LCVfrU1BvMX|`$>+z`hq9L7$c7q8^-xk+SP>EfC&6IyB=ZF# zOSHkuPoQa>n(3SU1#{RuH^ku^gG(G~=;$q?(8frs;XQ?JU1F9{zGTp4FNL-rIOKef zoJTH9O$8d9h+8U7aeL2HNn0vtst@pP3#qbsrCKv+KjqO8ADr<%(%?s#w$I`{^RGFj ze=WM*EmlsUyc!>kt_|7mnb*7}b1V2CP$Jr=Ev^gik}`1 zd>zY`v4({_k?tcE9m5dQEYsg%m9HeQ3^6RYSs4$W*b$FOOXLeC@8QI~_mZ==48d_Jv*j*RJ4zmL3*uNX1I^Nfm3(9r&jQiz^$?JHE*k z=ga<;QYN1s{p_la0^CL{#}*B7B_HdL-M|HuNprtQ;vt^uTJMSJw1X3w2)^l2j(mLB z+%?33z&f!|jYdm&YA{{^W{TwwB52j`>3tN1^TCH&K@m@Gee|%_gm5>tA1Od{@N?13 z;Vn8h(7h(V`Cj?#yK`^9N;R6GU1Oy0Y`*rJ@A>n>t*E)fSFUxR^+1bsv!32wqE+_8 z{R`@$-7 z9zZs$Oq1>v&GhE97>_Zku_10cx30Ejt8PxM5&Y5<;Zq#Iw-`B;-#;ghblHjO>7Xj2+7! z@ydoREsVh&%K~@Mz>ae=5uaPnI>H{TfGl>p09X0eB$yPwIC@5mFs$OEC}v?UPN)|s z($-bF6;9kvb88I^YXkF*N@xw)w3{ zA;qbuNhwxkuRZUWtb+z)<0Sb2q5TNjfZ z9Xl@hJ1T*CS-GnX{DO|1TuQn%vjK}$;5SLF?F8??7ZQr?SYsb?_k@Vh;!gnaxQj}< zoT$h>q}A{CZp5og$P`5u&k;Un>S)cg4%jQ#;wEi7lrZUGc4#*)9x zu!UXUdbL$*1%%$8(4 zEJ9Na`}~%JT93)W=(Csf_Sdli#`MWuq|Tm=_PG!5HRO>@&S@SODz_T% z>|zsgA{OuDZ1ID+c7=Iu)wmEyx(9T)9oGchZ54AWt@oT5hHE43mVe5$(x-~pg?4hkEAcaj;{2XW$Am-)|3qhij329{bdK2i-qgyh zR=Rz5wiN3@RQCU(?!CX7{`)T7BqRY6f&oHD4ZT-Uil_mlw}A8_y%#CciwV6GddJXv z?@a?Dy^B&+P*gxfP>~|a*8B}w>-|~Tuf4CU0Lfk^n2WV%Q&49; zJWpx2V8g}hHsi(KPsNp5WbK+oT{qDAgwn2!oOrpXr2ymK80+-5pIJiP-9B$?-kYJk z9{)`tW3z3l^d{SL)&jh&ZkPIO0}C6?G}B<#+Cp;}VURTz6l4 zV>w^k&qXhwsP7Y5_1xQ2saoO%5PHMZ28de=W_k(YxAX-Y<`gYwOMm3@L0-bIFGROc z&77xsuQIxS(75iPv%-@L&)lnSst@anmOHV*8%l;RG=ux2z00@{ zU{$k^v_nZoUU00hPo0VKl2o4IpY1upSJW&+3ypKH;!d=W6^wqNa)T?VRg#%81B)yZ zi=I+1_e>4lUrdI3Me%ZUJtTjNqV=$lu2B2A5v`?*go-%7idQ1htbq-)s(zDA>I*_| zmQzF*HwulTdJ2?^lC-YRJbd$7;+n~qy;x=9ic`;RwrN@Mej`I(W9i@Xhi%IyFH9y$ zGzMzL5;#H7dzeOIH3fT4JSOjGkmv1bYR)NJHa_Qrdhy3JDnHCB%OJaj{_5e_l@q%B zL6%FO$BRIMPkyLh-IvQh^t#%16yHtu^$_8y>gH!S*n=_k&pm6puxv3xgg{`73Fk_o zY?C0za(&WDU;TNDV%On^nCS>_w?(#)cYr;G8lB)o2a+fWR*sfhjFNRgA$M9&OXwX1` z54$)#h#LhM+N|c~EPYTmB=kz4CZkoM)J`xb9V&)Z&2!DtQ%W$WikzDibnQ(qR*HC6 zO(+o(5_s7(-IhkTv5H^0m0MT4Vc5|&w?La0H@2x+B;EEi>%G)XtK%1@5mQ&Z)n0ms zLB%J8C468POc40N6?IUru4&yc0lMRzpx&Rk#3mx~9RSCr zp)ewC09u24rBe|-yG6i-U_rOBVyL8pksHi-5~KBq7wwOP_6!J^_Rz7|zuOgkE0jY` zC&u^^AUMaEem~zH8+%PH@glPyVgL|uHidDhwNF{RH{Iuxk9g+=|77v>@~<$f2mV%r zNw!$aDDSl_UwOw8?N2P}F+K-Y$95{Nxe5Fs6%@Z4jZMKlb$4D}@1VA!0Q5ymjUijm zQO4aLBxHB5$y3b8g1#>U=3ahqOQPn1wt$c=i>+G&_EHOC$n#wvgsgX)}p&B5HBmzY`LOAMw+Ty1YB=E0f~` zkeB7}liYSTOk6H9*PZY?xic^GDtD$>5=vzg$`9VLM$lQql91_%Z_O<;H5HTyP%Yct zQ@d)7zN*S!&78|k7bJiH3@5E0S$W^hrP)(3KlD|lj;c8xVlu?$)i)yxb`kMTL!|R0a9eaP=W7ERj190zz9w<$OLByULd3CE! zh;~7b_GY19qsNm#%QTm^lODYP^sON|Y88h<+bY3HOO98D%P!%qVZ40=o*=qDJL$K- zfK(W+eMIuz#s`UY8FX`5$=s4J-j`;m%ktoW^FLRcIpUXL0Ez54rU=E5iq z?n38epl~DJ`{K=bH@Gq;IKN$^48Uz?x&LCod>aTqZVpd`N3&z9HaxglU^`yWiv5n) z?_-o3`^!lR<*WTOzx(HIqSjBqb8{M}Dg=t|d_=k%z*%gF#-RA$HD`Qh=5k%9S;XuxIh+#lUKgPTi>tID? zz)L4jUfj$)1t`dfyLx-4X*1NCp8$EU#VE47hMY-gefVn10*jT;6dKBZ^D@B{CpoJb z$2mnp4C83eF^uK|#X^dV6q&{@KN)}Gnd}po-D_A12jyE7IrhfDlc0~iD1%CYMUL;|~in- zHCSfX-;%CIkxubLkzE{y6SmM$Iy{i{gRANMoNnC1D#-{+4`7d*>3#4x_XIVWkMB6yfStz;41nNo-ISN_uFFkDFjH^z{Au~*f%)t{yG z|G5aY0LO+ZWELVVIlomnk7p%O{W8^&Bk-|#=8ax~u(p_Yl8*LL4I+M+j|M|S-=Xns2 zirh+}7jZs74@JS4eHa7?8=^7v{QC9IX`9azAuZlp0^0f4oW@mFdpowbN{zcVSPE1~=r0fZEKELe6nwPn=MMAUv!LJ%EZ{_}h@pv5XmQQ5fR@MKrd?@s~-mJ^# z>+X^8a>ui?9?u5 z6@81<$LXzZ=chZAn%RHfnlaz?=pJLHR{_s~Us)S2wkFbiM`k@)qcKsLVQ>r(6Kg%5)`myr*mvl(2~ZG0#F0B8ldeGF6bCZ;Ei%--}@VFGpbvJc&B1i5^@^&=$VA`6GS~-4MG+af2i@s0l z&LB1tL!EhrEVqdQS#K~ckfHd}5`#BI?E`KJ;E=e{WKjDCutLcq!@{s<`aBV2d!>6lDYk-% zn~0v0r<^s7o;SA@u^^y%mlxdnFB=S}nyW$#{Q zK}INU$wl5d-((aef)47v4X+_usry;fW+X5WHJuBmC$~gcvGNpRYK*QWU=J%Q&V1un zhkl_SG`CKuBIb}f?aeV2D+YPad}2mC*=_3}R!)p63~a+IK98aDH`3Ia)1yGmVHgUL zpweJcDy|iG^*TC6B#H>=C{(66$W@hRBC*{L9CwFHL^XCARia1$Hu{^)e*GYd6Ye6Dcn(5E%(u7TDt(_0gdz~^bRK-osjnTE1d)T zhUs36=KV?8ceC3KRGH9NfMn(-ldXVge-h^?=Z0~sKwJci{0OUyh%FRig1@$?4rJ}d z7q?LjQdASJ!5)$5gjY;ic`R^Z)r6Fb$JQROzvyK9IL_|F=tTKS0hM-r?}ifBLC^R) ze1;>Kk(;!8cbQeW17StE08L3QGpfBL{H-)jCl%EL!byC#gDE+&4A;3WU$EKBX+ z1snXP^s`oaCWygnSw&bOFn}V8mJzI<%3AFVv5Uf6iM4CPkd)k#q}KeE!ibdYKahxI zuJiytmG~fX|6ZQ(98O0lvyFCYnfeL_Pot6r%JjKQ65eR%YI5u8jN#3^t#B#bhX39# zxl`dR*Xm%!oiyQ>y{|899$D0mm?R9RCp1ml0@L%XVD1(%s4a|J2JC5DoiYe_h~vX|X_Q@2MJYDb4tR*^=9 zHx8FfdKFO}33r|LIvpOkl~?$teq5Z8 zS7_z@9(_v!?8-vHx0Ln~=I`Q6b05DZSY6Q41=t3~m9GeIja-9{e~uHrm#4&nXIc13 zkL4!g_dD!h>(+ecO4nTb_~J~V;k)e(y0J7>i0UhiM-882K0kCp!&_|LnLP!ivXO8M z!++KoWjP@?_XA7ciKt4fT7chMoOhu0zdj zku_bn1xf^|_FC`;9)*oWh!Va+^%Y!w>mmuQAKRp7TnKXE{x9hSLpTlt$0%m9I{|l$ z%+xLqHKgp$CEx8}`^rlM?Zd1w0U>d5U5_9)rs`14sY z&ZTV*D#d$5miS>x^+@$VO~`Fa;Tj4x=MAdY(~du1IF3>Jxai;89;S4#zVsTsdzkOe zgW6-=0KR_(61(7Jkg}$b-(WBU+tH;iF-{juG1Ik12UBMNhgPjQtr=oUSQ?d4;g@Fz zt-Y;nSR0?nxFB9f&+Qd1)F*RZe$DAoZ!>!iD+G^Njll;*kXOW*EH@^FE3Sm&N-p!2 zaz!YkKW%=nh;Ko?Kd7JQ(co$X((vhUWoM4Rs@}{H;Sz{>|5lpo9U$=vt>)k(t_2#K zrv$FWe%ojDr5GfaxkHJ-TP`uScwu=i5hL0`S?t`oZS$T6-+P-M+nVg!)0mSI{#9GC z+uYK-BVymV=6F7AU^fQ=Nqk~64E|itX}D34WLc>X%J<6TitRkKKJ;3vZ8>wlM%%sa z{(y`ql7xlW9%85OX2xGFEs-uMyYrX(VYS^xHJ1?6miPG+j8e%n18Z@W*^dC8dn)$R zJUrJY-pd?vD_7ba*q0UnO8wP&)MB;_?aO;P5RHpm>hkf|XA;#qdDJSm`rWA{hIq8u zqBP&~U|w&@@ABwEIduNoOaHQ0hwkyRrzp}?NB{GYe@%#&3`Cs-} zkYa_rwyN1D{{fV~7V!PvM0?H4Dr^}UD1B79P-NKV`fs4LwfX}~w*PC7_1j0p=)c1& z#f-b`|2w?$8QbAgh}J*w%D7jsnF8`2Ym~sfW-(>*&mQZVo4-KdzxG%%4@CZ@x_p^0 zf|=afU2L|SEcTGr;lOu!tj$}ZQ;Oa`3!}Iy)*pEAVK|MwYMML~UM+Q2W;Vo~{rIxn z=GH~kK;C1`b^e1e`FnaB@Ovs+n2az9S^NwnIvqbH&x8pdCRHzJ|3R3%u6P%|4fzLQ z65cTzv0c(-9YIEzl-&PpDEkk>WchwH#PuJ9N#*e7ZO(rXCQQk3{~%192?=6kgh?zs zd5`sWv@BJT$%QBAj4o&^T`Pad=6@%`ik09V~q%Z>;L)M?c2b~ zr@C)X&wqU(@3AOF4oF~T_k%$y{`!L<8kxO==SWqN!(o)M`{BR#SR)+dJ=Q2Xmb}N} z$@yoGRaO6eLZoZ&`=rFE$d4)V9_z=n?C1I)GYaHA)+~9C)sE>2eIC!R%AfpmK|?0_ zr&u9I)Nj#1*Te6XiB*H&Ym0|p{g$jBi~29yr+WCWI6rCdUv+Q#>c8gFwQeR{l&gRI z#{YBj@tfkG7hjLx;V8vUHlmn4Pc~GqHFUpB65kK}K)53ow3Vsr8T2vNsxjzO;lq8o zk3PprT|7mPlzMk6o`eVQ)OYQleQ6#Q`@PrxEd1na_vgmn`~AoJzrT?v#n0cBJXY%6 zt>L%&{e4R2Tj-ZC{@dq27mXkOIa+qQ6uA9JxT%+aHdZ|RWHsmE->(Z#n*N@}G8-oM z`Id=YocvsR7W#AVbJNA&^Bk-5!?3m|07{eIzpTi>ots3^tI+`+Fad|GzxtO+Z4hSG z{J12M2z?PSNDCFiU!f^E*!q=>$Zrl}K$XCZ$A;D&4x%L5E#cx+L#(TFUgAk5w3oZv z+0PDQh3#2yT$r^zX8@%|TvsTik5(Jz@|=69ZcvJ<8oSN+Ybc(s{5`O&`UR^QT_RG; zhIv$NWG{>^>8EfRu%~(iSxlGAfwE)&tTy^~fG$O#p8I0CS{3q^F7^0}%~eWuwV^+B zgl6F_Hb$4hQtL9yyZu~TPNQSDjM5{NH%GXa7{}E|_S4nC6@O`W)UUwwGpoz(Xf<6X z42%e=jqTi%`C}UQhorK*f7%${I2APumdd%)?;vI@r!D~ck!#7rcO`9HOG=0#WyHNw z8h@fCLbmkj*H#ZP;-VhiMdR?0r4nql$rE!^(6mebCi@vrqN(tT8=@JdcoJ;J;A zWZ3>zN#4b5xUJWd*FUQ;$CR@Yv_FYogav?f6WAYuk8p@&fnQgIF!5%Y!KjXR$}(&U z^qv`I=p##&QRap8ea~`l=^71h*-3gP?+S_QJeUBMm-(I#D>vI~bZ)WD-QPu(3-Ipf z+OREV(!MHJ__M8-mTmSfjt_mhFHCK4pIo;}89;kes9O)o> z)2eQgEJ(W17;{s^Lw9vy?Y4hcczeUcSopy69sjl}UNLR_&Hh(H$2}Ij>)v+x7Tc}a zJ>hkYeqFy!e@gl}w0j8#j3$mWy5{t6Uw8Ig3wryrx2u81Z$ISo%?IBiS_ghkKXfQq zX>|@QV+Qhd5gMk4a6)+Uv4;1JV{M2w8cCau--b2g}C z>>aK5$eh683&Rn-Vc~nmzU~(i`;bJ3b6d92z!BL-@09!fte&J@R=$#?|3`SGkAuOd z4<+LX?Ejze${GW?3rF|=3a|X&{_+1Pcx77@!q56Sot3~{#q#;+2cd!1 zmZ%MVLIfs!5aGfTiJ-f9F4^i%xQ5!e1Ud`^O7}b*wvL2fxgY|-2^gf`1`d6DBt}w8 zB7)8xL$w&#hDp)`Ttf1EuFl0%Vw-`8d%#JsO(ceF%DKuP38haB8b?GTZfI>Xvam#8 znmG~t&P2eh00s^&rR9D^LabXqUxH(j@$TQ@6gwE;Vj6_TeUNn=qX>h(w{zOUeQY}k z1a>zc*W4LlVzHJR*F%CkyDX^hqKDUSqNDKQn;${r5$ls;5qG?vvnpZ+MWI{>zjDm` zrft&I2YNVhoCR85=GlaZ@Ln$tQ4WjxR;YBXTjfZG%EWA|RLG z*93T+WgJS04+7zVIwbu0XJ&Ha_60GgjWfsL-31c6|o zyX5*PAXHldwDUO-v`IrIE2?0S+RXv_G7+JNk2_V7NixCXSb(rZfChjfsyR#$9mbs# zkj#(7t3q}$c+zJuHx}Ad<@>;xZf z05H0WR&m4k63GYT4VRh&u{Q%Za%coG6t`~#qnd#b9MJY4L6+cy+DL5v9O$tG5!eWe zW=;s(d}ufpD?=5sD-nEZjC7I+{;BFeriv^+PDsQh%UAiHjv@?YeW0UB-kcHKCGnv$ zKD#E!y||Pax{z1T%X@=xVI!AZ9SPip;Tn3mfgLV|58ibUlPGzY{-#0SO*3yZW$2rR8kuHLvu58H%!Ep2a?~L8`{dzjAE(#Qp51P+u)@Etkuxk}0v63BqyD9F`o7DD(k zApQyfh*0xamj$sk1C=p|n4nze!x-2mg}re=%yxh*G8r8N*ExXsbwSje;5umNXVp-- zQRtO9@FFI_KOnnyoGB5FfVO}Os)C#ZqN>LOgtx(?F6m0>U?*7$pMSd50CQ~8_ysGo zqIHxM5t*)p_tyA22g22y5Vs}3p)8SaWQ%=mqNpYPl}})71fM(3 zNJwshzbRk_`{bn{qKN?doX_(MHd2MZvL zhj1goRuXX8xgf@%5*9P2bz-Eb6SyeW!BPTbbwFrlezMe)O4}PRy8%r%){AB#ArpzE zBQ9|{vLG1&Z?D+UeQba(DVEy_-h>9HPz9)NhjbBXH4gxw*mU;`HYOCA3!6)`r00IMmrGKH66%M0D;f3brxKXB1=AolS#?B%gQDwW1R|}{UerrVO^`v6*b1}UQRBI>vkTQMKU4PKR3y<)yVqRU(eV7)j3`$eGyb1!oi_*R%%{sW$D%eR(oLR1i~` zZVZ?*1vp{>Qr&*zL|Pjhh;p^d(7T?)C5jLI*r6vv7712Hm&mI6gEoDab7*c^6Z2); zawkz7Ldb*Bbm6fovXqCMg^bH0LuKLD&}HnWy{2@jTpM9-u?-?FQK=e5Z>fui3YZ>r zSFETZ>tn%`gNfC74%3tQ*UtL&B;lMFNFVQfWYj5)&l=ezK@seR^uz)zy^?1LPx*ES zOg95I6Op$+#~GgChSY$9&5yw?c@&(9pu=Y(UwVIZ`EC4|dbLo$bHXUi#k^+Qs0EpD(@s@=>x#)NM* z?V<4Ja(XQ({LS07xf}&)mkOR^PBSkio?}Ytlg=C^Lxu%thJ>kGAl40P>m3?}43~w| zRoojTVw;%YZFdSA*iVN{wdm0z#c;PI_N4)G2o2XbzLm1zaq^Z0M6DL$a@IMzhccA_EwMn`m#20K5pel%1BoIr zeu_}%qQu~)wRO}u0m6oU+(jAsAql8PbN~%PZ|_djI@icz!@r3zB5Hx;UbN{P$S*Nu ztDo3}1T}v463YP@9KbX&@vaJU_cpyfoDgi}4DM6m8>+DAZsHC zd9J~En*4}g7cPZO0kc^vQ$st!+>}%1==jdS=)bU+%91^T5}{q>B?_*BI~LZr4h~NU zO$1D7H&+iFN3P?jFClTOT8m2aA>U&Yc0Pm4Ykjgt5jsdvp9vrp=Hp!50cnnX5Qd5p zEM8K3j5zleiVw&>X{0C_(W(hBc+&4?)mkMR4$iE_LgLS!2Lnv;WThMVUN z)gGB*4ZgLaEnSvvRPrMyuC0ps&si_8-)qTk{gY+0*32xNHPWztqorjxcX&}K&Bf)# zV#5n-3_C}dz@udy{a?$kC5nj!evb(k%?C4m$m;`$5z|^v5skWd5YT@ z{wpMUsPPZ9M+_c74vAvn+z+Nqn%<8PxSPVJeiYQZ4umt#g&O9xgM7a;0V+?IFbj~U zjMYZghCBW5e1IXHJ^tda8f(oQwFzy8le1ENOyy@w98+c2jlULkeg8N$9nb`uzP9SP zYYbQW;KFg{;Y87Aev$l3d#=gQOprOQBONCCZiXshQwyo=W+q6TUt?vh>{bUE8%lQr z=QS&d)p2A-ggrehUx2cskjlXMz%(U>%8#m(d_p#cn9I`D2K09+56d;))x#)AcrTR+PKe`5rcJmA9a$+RRn();0?8yGk)nC8ZIaCyB`6eon~jm-16q1G zxrw;5QOYme-QSW zvB650qc2PWob5l=$>dpNIfUrkm~Kr56VTaKOqGyTAimOLF2!IuQw)r&|Fgb0|AZIT z8Dioh(n@=!-I1~{W>lY!kD!NPW|O5W5q`>RhV23?AF5ursq~5zaQM_(D5iwMj`%Dp z#oGccnioBR3eI|n-~m}l>(cf|@x$3NQhgxKYF7!en;z6rO*0Hfh0LG#zON*%=qMj|*e#@=iKTwTnALF7xMDRFg$q?3S^c(MW zegP)5qx$tDLS7rGQfniJ+>0$4h9m1H=nQBT%~4*Z8W$6$m>ku(iGC}7`Z{$VK zv8l+{QGHa;IsGS%n{z`4YgCrJnyFqjQ4YXOd4aCTfoAVL&1`O)53SdKk(DmG<=R+g zE~bqk#Xs4^ub*4cL zr?|myYFL<%y2aaKV}PC^Gn$qpAHD=#AWTujIL;lOudecNB)j;Qiy|}q zd4v*6j7$V_@-~rE?aka)J#7t-jIbmzuU1N~M8eZU$fi&XYY5mnjJj6|j48Va$IFwh zC!$%ZEk+-;=Rb&Z;ez07fIoBS?{0}I2g%bPB}q~kGCK0UmZyT;z=;@)x%h$U6#3$m z30!m3ye^Z7M^vqS*MMboGJ5DtgI8!LR0}}a3kWvZO5#0FL9?BZm=}HlrI|>`G6^N< z11ydslZvao+5U{AGEk3&YR~*$npnpm!@|e}UJlgT?Xq-~8a`9Vh23f4Mr_^U1gpi| zVuykLH2|zM8iFBwaCdl;&nwKK&l&Ux$GXMFyz$3hDpXYK6@21pV7;_0M6T`CyeV7nE===xN_Cu#=^0?;hKW~09 ztf6T$Cz1?m6ZzF_m#xmKS*&&1;*gmp==PT8r1j%e;oU^fFQ<~*^VRnQM8BT2FS@U^ zyWAZ~^mknD4|K8P^Ih*+*AM$Fh77skVc%vo8spEw>a*UT`EYF{G1qVzl=>s$sd-+j z2k6j{r4)T zWgz7T(FRg-HcAZhl6ERU?*o0zC4mZb6yvZ-jukVXI~Idh))glbX z-w#tkoY8lI!}h*5sJ`U3B>corda&h3y^3VkJI=TTx`BgAEe$rRG!^|7FU|-~A)OaQ zYDg&QuJ|w&4<}ym9_N(gl(R2XgYnmAD=R?oeG&{Ji`PeOeRWKtzJ%J~kiHu{hi8&{ zrKbe!C+Pz&1@&Ta)aEFxj+_#a2O7_Y-Q-{v^mwi%XG*-MQdnk|u}~?eqDLzP!Cv4$ z5^nyKO2QBE2pY;kz^=+H0*FCPITbL>JrQCtBn&m%>#UO$be4x`_@Yo?gm8lmy$~-} zk;=$-!G%$Jmv~R@hCh>+R^F7CxXHaZ&aJ*4NnsonU6JpHrb%KC7*SpSt^)DY9;gsM4YIiN0Ob$ zycD!tg=qI8=%O2iVtxrV+^%Z^_l6Gx+{xL>Ka&@U(#U!^ML%!Obsv>3azEqrL4 zn?@2G#AQ%KEeZY@fh?)X?bBG#8Al2l4Nh0zshR7{r20=D+2*)T5aa8v80qsN_^kt1 z@2MM_sx2{XhKjdx+_r9O_%%VCi<8R?kRhEn?k^zWxl!u{Gac`P+z`g>2>R=gK&M_j#%d@+eRWLUU zd$bJhXpYlZV{snsv8*52hS>JA6F_?;q(GVyaBf4oM#~25fFAyFaRXPzNzlD@w|DS8 z8-J<$`Y!ZKsRk@02lZKQm#Y3b>$ch_pwLfGA>Nk+N-PL}`FxW;|C$PO-!BYRJ|v)2 zIFcC~A;5AQ#%sAvq9c0WW(~Z{6mV~xH~Y2pmO>Li8~J8$If~}XW(%N3A~M4nDip_C zBXQ*G5#ov zK1*suk;Y~VKp9m{du>8}=5-h+!;195D!Lm1OANiEe6UAWmxnj;oAhLcn(?_CYnXWrh{gJh2JvHN-H zH^MeRuNYHQr^a4H6F7zBDi#I(@&}PVj`ExwLv?xT%$!kk#`dAy)({iZSbcO2w0;8z z(o?U5ZN&V-O(1$*7$hHcQyK`~tzlJLclI68e0sq~rRqC2k{Mw=ca8$6=G6{DqmGih zi>V%56H;ZACPX+RUNK@0Ftj>gpaPu`Rn`$L(pjPhx{x9i8Q7 zDDp>b>zjUMoohA2iD@tew{zUh;fdq)&|*RsF$XfZ-GtKh0+lPDtruAZ))D~P-@jmSbxoH z{&C#u#(01OMe#!XDbY}bp$|MH_BJr@g7w1=y+#lRL;aM`gvGo{-XjRHeLGOf=dT8! zuGC3l_Uo*Eo`cc$ROanih@7@cyK8eghm!7UbCPF#nfUb1y!{z(!G3%7^&c+PNo1>) zU`M6iwChYYn^Z%}k^O@KdegOF$#$dhh5%6(XOh^`yN?~s!VTGPw&ZzBm^xb_MVWTO zjR~gVtz_lcR~PfX)#az1oo&-!Jwp1{HvV>YKYzn#Gqt?39g}}qqJ3Ys{r8)_l&-#y zh;Kn_eQ!@HyPkf#{O!^2HUCngGTAb45W#T10o9cqVs1Q$xpuyJk#bU~#ebM!e*S86 z>_orNgDffg@E-l-rJRb+cS6DWmiL8C?1XWnPiEiwN710zDTk-2VPhPhWMfaKTxfBi ze(ukhfYYgCAONt(y{&fXbS}~JXZcOb_nJ;;^G|gAoK!7$4QJ2lno|54LT>fnd`vl? z_x7l%;Elh{6Zw_I+edAEZ|>Z@BfsMI;78Y5(RID6A#2}ejwjdqcY?q5ZHV7L27$v5 z;`kNT7-mnNb38pHz+=S|NWjj+y6;s_H-uX?+@aofo)aYvxS1cKdW^Ic8zDx zUibYyYEB*4bJG32y7u>1_w2xa!0hk0zyBVSE1>u|9&sHIN#QNcD6M8_gCM=pM%tA=bv>i z&eksep3FY`dpvvb_cys9z=8wG;=m?2XdsR%7YFOc(JbR=PjE;UJiRO)WrAl4B!lmQ0o8(5Dbw^t)M?W}; zwq}X3m5s4CiE#{!an6l#?T&F@j`2K+@nVVfk&S(166+rr8<-m#+#MUb920#pT8&bjKwv$E94H#1UBH(`Dl`P2#fy<8yQ4^Sk2< zoQPd4+>v~3zyj8Zv?EApvoqB805XF?)OFL7zQYAts08Q`>%>qZOM)OCCYw$_gQM>x zaSF76o>kMY6BSSd&|?zf&Bj0Q5OVHKJ|wV^j}>wBO4kLIniFOS6v5wV>T^Q}PvQki zXvgO)cD5kN(Ma8elx-@@bkV5IiH1-X#%sZ6yT(O1Zs3c=j>fDw6v# zDWQ%f^XhoolM~o&FR*wG{m6k>91k?FLU6h(MPNRQlPqnL04?ha-o}C7nIyfd&JqTs z4{n3myx^LqX(D)011>NwK2&==Va6Jvg9bNw@jNEbSe>RT;wZ?KVr4;4@M-)wx%5Rs zu&ZZcOabmV5dm+gYd%1E;f`FIdyntOJVrzDr$E(gDaO&>Z*hRmf4OH$ZM zB%hjug2q#9nyJRU;3|N70(k1LaRq{$V7U#NC*4$k1wfu&aOD+X@OZ%w6To94ZSDo; z+DUFc==8cM23TyD?H0s?zySG15;As@?Mwl7_sG9h*19$PnncRpNrsy#pfZoX3zILU zo;kFg(l1Z|Atk<5<ywJsU$j_DUq@q>I=a(Wl9Y8+qg`eY!hyMlFRhH!OW$8p*4bV5cBkZ? ze4z^~QRFcB)>(#pZMlJ2Ipa<#!$c@gIMqYI4^Bh(2Ab;gBZ*fJJ}lQqX{#WqWhGlASh zAW8zvZu&&z@D2(Cx1#NjxQ z00CrcooEOPJ6NT+%cK`6EtX24*F=I)NN^XfXBeO zKZD_IIEwX}7K~}8EJfu~Z|EY{SmF@IPAb0An@@)8uw0N@gn=z3vhbtrax%O@8`&U4 zcT1u~NBe-N=z_RJ%5W0|L(lT2%>Y@g^ulW)AL#`k$VSmaJ~7G0$6hjli;&fLn5^H;ZlNFq>sE=d-fB(w?MF$EwApjDUF z8U6yxReDAt&$E(sWWx-Bre7^13048vE(tKL0Z^5tnsvNY?X`Bzi_-|_&#%Ze zD=+<>am}r_f3)<*Y8fV>G_1BYeYLU`9@-8k76(;H%ax?}rd9v0*mVsn`;w#&%kBPM zIS8*-NvLct=(XtWHTYds?^gYMZD6G!_1Z;3<-BJ7R6yUNb8lDOfL2=Bo3*|k)oKH` z0jb`K@imnBYWFy09rYUXBBr)Vh-ig{RtmKL`rR|j|LoUfg8K%Lm6#kumWxR~ot3FS znru*?NVu$?dU8g8!=+}YYmntU{x$h*jLg1rPJiuY*tdyiL;-|2FZ4lv6J&01t*V3g z8zpcSzigcxS3rMbhjf0Ne4YK)#c7FvBxt6Co*T#iHkNdyp7v)qM7glznX~qvD%xuj znW6dgMy7qY*~2X6Kz(B!!e{aBbD-^s6n8YV%li2usRhker{kWhf^GI5L@Xe|0;GDu zmad9;dQ-sgkC3o&0?lGxw`@}GlZ)*lu8D&2c>2NB0ckT_l>F#PY@bzquT5{Cu44a8 zU4P+kdhg)pjP5ms_5D3JyQY3u6}neC<)^IuChRO%{S=;PnV_H1>^G6?uPUsL?VWtx zS5;zB)1o<GV`jN9d5v?$ei} z1vYavP8h^X`wWy;4f#q{{PPr1y{rYQAzYyLT)gQHwmI4 zjH_jrio)EHpes1gpj->&oK!sE0*0o8P!e-LlEP=a;7!e7nL2v-`qRtt)IFyI`=bbE zviAEFX2;VsXwnvUuU@pFzoD8|$D`Rcv~|z9O^f|;*G5fF0R#aUd{#m4gzlV;qhKLO z-tq{a73gNi<%sScgO^7F_!U9AY@9g z2WCrOA>TG^hBYxFUhNVhs% ziuhU}vtJ8phwUCEGIK6>xCoE_QTg(%u&q~0I6IoP)wC!4bFL^G!b_2aj7NR6Qsb(*OXz-XnRc{H#x%xmgYh%JRs5~ zd8`v*zw(W!u1C((v-qhX#dt+dm=z%=xIrenmNc{v^C5QF9fH-v$+UvK^-vZloFeM6 zHl9v#mtc%xWuo6g2(c*ZVQ5c+?vwR@JL#H0nQDCv;7x_4L>Y)Q7KbvjmX4KYVXU$M z`g)xL5+Fg5n&~Vaib$lB?Y%J}>)Eq;o008szZi1_U5ICtknCS#f zFGDyK8|}MQB$-8f$2RIhgr^J%Vu%l{rsAzUzG-Mj)0=icH=P@+D-Q359;nmET&jQ?BQ%Cn|J_=1_|BIh}oSqu|s>5gq}( zEw(-|-@d5_+J|7)xf<25ZPj9*=Y1TSEr0Aja@sg5o$P#T)>?NJv>b64%#s z9aKiGTYvMa&O}DHeDo*H=0iC$ zfJ%t##tysw7zV}U-=H_;Nafr8W;ocUmy`G~0Ub6(6j}*K4(+aN)?bm))SWPPb)L$?Q(;jk*LK0cs1t1B9manN{|8`%}}o`bt1!T zigCw{_OS>40^-7mHP=X9QK-=k=hL?q zV+neP8`ro8(=Wp$z>)p#v^VIPssxZ1Wut*4$aP@=7-mhSz!+_FqxW@b=slix#17uk zWw`voK{4$Sm+BxjDEu!GZarO#o^r2*x`VM-&WBhbxg=#AE^Sm6cxOVu<@nbXqUR8o8Lo>}r|P$XQ*%a#?^&3pB02|yWb0Hoyslfmm$R!Whs`u~l( zw|;8^eE5II*oZM;ba#yu1eFpPT`Hl{Qc4N}DlLp2J-TJ|=uJ!QU0k7(?z0yV!8DXHTSs|C&hM!XxOJAjftzf-yJ&3 zspr0*w~-%Kywo;Z#c!LZQA*r-`}yX@b{{?-uNLXQc)a#|ySei_IjPSD%lePUuC2Nf zZvvQ{^4@PpiH%e5V|n=<60iHihFk9O_IGVoiA;u6rbaES<>_3|s>51hZ$fBJ z693oCIlfR;qmoXjkCcdRov=};&lv5nlZsz1oOF6DnKfvR()Is;X3hgm>;nE%?tgTk z%yK=AdfbrDFnOTfA{tM$A6jMeg`s`kqU0HkfXtsJy3oqRn{DplEH+C8L#6TllfgboFAb z(ci-gmX_ZkQ;8Qi;ChC4(DZ%5gY`v16XE&O4-6R;3!kbIRF@{s5(&S&Z%OcKo>qr|h4wTE z7A|g#B!&CqAx{1XYS#0xRABKDJhCT*27b?-4KWlmo$pZwpi(9Vk33Z(74+c@)#jlU z*B~gwN~sZ0)}Q2{-Lo=l+a$2ff$@f;%p${I? z>V5A8Ys&Izzfaz*sR2tF0x8q%!nFzHVZn(ExNn^M_@65VlG zdJk|5fZq3GQGO6i10omN`rGFE5Wz_1G6FYasZ5;J)Y)|;XwNTH`(kI1Jv&reN_%${ zJP@V2eupobIsv}SNt9f}L)P@*1-x}O$7hT)1huqHoGQ|Ea%rD&vht#5Ipp~n0QK5; z)6LFeWMy{9Cb8mhCc}B^?{33M3^fB>RDq+W6slw0Keu3lyaz^|KEMd^;i@MkIHbae zr+t&6Xf2dz^4OL5O%Ed9EIMVxl%*83E>pY~bYykLK5g#6Q1Drks3hd8lI^(<2dzg( zbv0~46;I0m<|BZ8Q`I0~Apsv8OQF;D=Uy`77$Z%2x_y*X#GPd>@@KY@4mf@kwR-|L z-JMym(8posHv>RzAIKM&ejR~BXAFJOTNS&f!IGrG@!o=Y*;t}y;;g$Teq6j`dl0}7 zJt;SF|MGSq1W=tU4{=~e_5Cq05KHa>h_q_v21+MU3yKh!S_&c8-t8$YOq38RpKb)V zg;G1})yZ_Y1GGmtGtDZ4{YR9;@~ZDSd_U>s7#31Vwm z%Ot_D2;$!?QggIdK@Yg;Hm!VbG!3CCvJbn~d-cJF%;36#=fK}OQ(Ms>cZs!evH2^c0 z&kaIb@<52YC|ITTgHIIy_FqH$*A&e5leoU9noIhqhr9!(MqmB9*O51R=3!IUVIITT zIimK3b2zam0R0Hvf28~Jt}4d0QAT&Yl-b>2zWn)M#fL45p{Lt(ZJ5tlHm@RIlGHzM zQs%FEo#AYG-s8P8GdRbtu3?Szk4h;c&;m2j>~OZ?hE#ng}H zF@h?$5S_Ix=H`}>hgBX)<7@f+?^~x`s@?_ZkPV(c=kr8`ut6{u-(8#AH~&_7cj|mO zP4(*7dvpiyp1eqY*$ns*`{vFr*~ZmSUfRW^SU{tn<@a;1?(5%gkUv)~fjepKz$O*0 zs_{*ttc5m;xSCJ_-7SdOWgp{IP56U}EegNOeol&7l!op$b=Kto{BdoR(Zn`=`{kf` zTy2cK?hf4Q}Em^x}!wZ)PyB?ISD~1Sknn`jgY**BpzmDW#yip7EZ&S{F}aTfP~GB z@BwG_?_{?f`cZiMz2q98GM4bS+2)Y&-q&lOG!HRHrrJs?Ktz5ONXX$N$0oe%l>)bR zj|t{o&HCZ%y7mGTSQAbeu0(Q7%mr@NjKoRJCjiI0^9ci&{xUR$P!IQ;uq~jOSD$1g ziYOh@@n8%Ix;FkLTd6RQT9H{`@DJOdt9T_MjgZHU>?DmEfuS%!0?ASK_{RE38g;vd zz!4hkU;q$R0-rE|y!O53tvr{k$a!Gi20cjpt<%ylIUGv>#Zp(hd9l)PZ5aWaAK05Q z1Y(E-4GcY5(mk(A?u*X{&U=wHqrsv*A4++=A0z^KPTz@HhrsdLh|&l5Vu~TRpc?AX zg)}g2NZ_Msf4npDYCqt${fEa$0@Gw@^Ck!}4OT`1C0nS|w?H(6Ts=0y?)>CuC4u7% z0i)s~@H~*Xm7l1-XMjK`E3O6n&HlqzBW^JQ#iuCh|M(&3_Zf?Jqe#d{0g$#aDuMey zatH^C+GfO)74JHrp;J~q_?y6baiDMwTXhXdjXj7FcGn3-t!M}^(c?B?u>X%3!s!)a zCB1T0DdqiCR15BaDSh*yQ+$GkUKoQzgHj`0+7V(+;&?Qh}s_|ogK zN7K77Y-r%L{{lmRObfNcMf9sQXmkyUsgWn#ovdwyoMtItvLy5%T^7_zos({7%4l?O ziB_FKXQ#%cG0@R2+ffTL_$($wFQFsN}_KI(W{fq4_T3)e(uW)q~+%iNad} zQa*{KhtzzyC311DB##AumP79cOv%6C2@gyFvNE*dCibS@$@3*izm@{Utnm;gk?YV~ z!zcNvkB|ISqL6#aUwn^9!;^tDS@_UbLFNP8J=wx1L4DMor8L$0D*82PiV9Pj^Rk~K zo{#Y-=#ZwUk){~>r1~sV%bFycUDzP7{^bX?%^@Cl8-`S%> zB1r8`4!wD%0r1Uuk5Ov;1N$A#yOW{1-u53xP~17B_S5<4f?I^*`uLbXp$ZZi(?V@p zA3i!wXwVW6+(a_lL#+egQ}!A#Zf9dp19YVM zSc-5$A;B{B)*><^W2vOyJP7AMXW-E$x3OscB;ggZMm#DQI7zA+)!7--@%B1m; zB>G)Z%U`9%dY1}OmCo5GB$nlQg<}~?OM^tK?a%ao{48r~|KI^Np!Jfzr##-1n|bgA`mt; zddaiBnLtN2&66my!I8EbfS$+i2TX%b(tO3aLZ!sB(;ifZ?WO-^5QLR|^gO3N(a2%J zL^=r8zDWi83(@hVgLyWI0+F?9vMEQ)(L}zHtEToIkeao!_ar#8@HI4;oD+_xE3{U* z%>tmn)4YY!FistZBzq7GC!w@BFgJ~Q>jFZV|9*PZ)4&b$`6&PVh;AVbYEhGG!+Gy4 ziu%fnOh5>P;3O1r!fKc~95{Ty3q-?Q|Rqg>2#lr3*(8?rfr@E#~MW| zXUW17pw$48t%xE8Ga~SElgl5!z+<{mWG1bfwC$=g99cZIT%3mT`mhH*I`ypG%s zv7yDZyhygRG}9}Bsb2c3W5l%F(8T_!V>`Y@0jy}e@JYRKc0A?DaHP&-x{6;yk`GxC zB|D-CZyd_Gy})STs(ZGf3I3a(Od4I2@9fy@6+Lz67u_1p0uNI`r!UDl@~wS{JH}p? zh+k0ECh-$d+IX5^2;fNI2P3oy-oX|JRc{hbW^^X0lQ%Pf9Gr`V&x9rg$W1W4M^+DW zQo{|}>#9$KP9g%i>PbYAcRsZ{#>@uAUu5ZEay{h=RnQ?V(T-1Uyd@639&gIYSb;=2 zf%($q8O44b(#Nm2L!FR+N-=DM~-_+Cc>Z5UoB9XR)%nEJY%9?EZ zb<_5~veLDlZlj zK+TV6&PW&)5R)GMTpdMAr3}BjZ#x3C`Nx`^g8y3-LuB^7A2suJBA)Zj_RFPH+fTr5 z-{0ryZg%}>RjQ)_6D#a+7){!2rYWc3Tu6hj1gq~e?B{q(G7t#Bbp--L0APSfHL!(1 z2VnN!q{EFxvj&L>IjUfl$BJe2iUr2Gn;8SLr0nqyDy_rmvmo(6tbT#FxNeXo5d%}q z{RDh$o{%A*xpvxQn2HH%16MI%E@NVsih*%WGg3f!?iXJ6pJ9f9{Gl=LQv0=n>>mmC z#h75Mqi9(_unyEVAZvljb)Gp~+n;*O?vq)GJLsycBoNh-k{a|BWC81CTUgD}nQcJk zD6A-wr*e`O;reQKyCB9a_{dJ$lOHsw9IaGgy6V$HnisM})E%Ssh*^v0ZR@L<8n_7q z^ihkcd9X4BLi<>`%n(SJmqah$E(+R?AtxFwv*>$i40vtH5u8){HovzY#h(VY!M*(x zQcT08Le5NOzPT`Shntc)%ep2q9cT&t65sWCv&V?bpR=Dtinb<9)@1Wf6iv%vcr4Y1 zem^-sqaK3l(WS&a;~?VY&(zl7tNoaJ`<;D@91EA?q2Z1QqXa2Lj2oFD`@LE;%)reE z@Ph2o01*XQ4q{G|;}2tgphONIC`y#Im&!L$OL|s>J(jrE%#w zI81+46n6dO(Mh1`(S^kh%XC zDIl1(kdx^FV$*G0$s%Txz~<&*V-Qg*+rZ98#-<3B(uk@B0~H}U$7xZaRvi3Dr~11w zQqtW*R!A+{O)^oX8C0GUI78=GUh7ULH(NC%h9_pziK;If2DCN4HHuNSR#Z>7$%-`H zKD!ZZp7dR{HQZAeuc!yc9v!P5*O|S>Cm5p_JBdGNR+}31IZwCI6#2P!eg5Mt+(jE( zR*C&F<>cHBS`|9&`5XYx3!D?vN$fuLoY)=4g-`4Zgqqxlw+@_RJq#IinChCDl62h% zwry7H1}P$L-6kjV8|oW;_-=+d#;%+vgzeMc4KX-8<;{^gddH80xb_}tCHoHO}NT- zbcDiEG4XqApaHFp^cPC05g|5&iNA(skNh19xEfYqVp^DywU=%>@a>tB>-9pVE8Soh zwP%;NQ$5v|c+9(DfMt%visY^=_+!eDuQAM3jx!gy}(rJnaY5U%jt_ zsUTv%xtJTQ2#H&tz)S&xnm*rNemZ~N`Lv%W3pUCGUQYXgD@=fzH%2f=g)D8Sjtub2 zx{JRj!%$Zb4W#@PF{i-~BgDQM6zkHp6_8w_d&VQ4xE^ihaJ$qst0`apH`@Crw=Lth zFv;W@-AHOP&GEK-qK%jn8%36kb|H0frSl2f(B*|@_50!~+v4#DzB{dj*p5_9EXz}W z#y;5dj(h6RxGfLfq5MHDr=ZzqhqKJId9SDwTHN_`$l_(4^hNZf5)!S-<34(N(o$Mk zQ5LI!*AnXVY4#e!fu&f$_XJj&aP1hu1cI3QF z`=k1P>Wg|%`FS((P;G+C{H6@+2F@dr;KC>=>h}|U#b2Y+pq>ylPlHf@LC2@+pWMhm zk0=eD3igDle}SxP^N`U8hsuvLa|Jy5Ng4`9gz1Y2^yo+xX2pR}E^t}cYY5@1P8f+| zxK1K(0cu{v;I6`fhVs+_63DcUNZgW34XA$@zx%|JXMDopitGbpY#i-mWA$jJuALi* zhf;Vv;h`8+?1V=Kn_O{rBGs(zM?S{k;*<$}-1GC;b^~KgN1c^ea%bzP`TRE~+G4VC zb&Z9pyRA+v)zRO|8%*7KIR&CeG$=$0jem;5--oY%nL4UFqUNhbHLsr)PqZih7M|6$ zLErI*Q_%K?%l3(f@rOQP{QT(6yO=yd$X5_Bj%h-8M13M>@J~r#e@WQO61})k1SBwI za_`rw=!E>^S{9vCLXmg+5S2HaSiJ;OI@2c;(!b)^i$`7&ZHH1BJ8}`ez?Qwx@8XSm zFi5Mf0eSAG5H_^`2HOLOANAW5E!&~9x1B`rVx=wd`!T}CweQ`tclcO;`DH*1d(I1RjX8+73b&5K=v1v499s*2tp zJ!mCRCI1aGp0|p6#4E|;@|k`@VUXUNE63t>2uq=S{hM_vv}oEB+_+fD+OG z2>|#oyJ9G-^!AFt)%Xv6XB9S0}hHSPa9c;&a?ym-eoL*f0{ ze|s%Q>(TeBHo9N+MD5~f2tIg4Bh24IUb9mjx36rW+xlO@s|f#z*0%;V?n6%OkNy+9 z@_$(VqVwtb%l`^qJ(A-)UTsODr?zNs{;|;$vd{ilzSQ|kZ<4U(l)1~<{+7{_sC`RSWtw{KFvlWwT z&4Ep{co%#pMzqbrHkN$bcqdNl%%Q+cA+y;!N|nBKElL3|0UJoTE*2&}5WCt*GT2_C zOE!95x*PwIsV1o-Rk$&(-h7eC)%ffAtwR^1eT91$$qkEmFNdG=9=6^t zL#!?8{>@??F;DAp%w8u;^`O*Ft3(%WPxo{RXSepVQ_=S1Za2_SORAx+j>tVVwD{Pg zPOna_e^Em5(9sbN6f@ITO~VlhcM< zOW!OO{V#BxXA7*hw{JfYJdtS_pR!@R*p{qgt8#j|p z>iE4aCdJsMe%G!{$7RhoSAUM`g9~h z;k;6O|Ic0>rQ|2+lX#6EU%m=_d96v1aiL&wx*1XZ`&*&Fr}qaJU1QQ!okQR4w~=jk z6qg#5y(+l!5_}|?ef)5pmjLMIWt4`}&fgfdA~L$4&v%86v?e5v%{FgkX=E0xJ}Cr_ z=ivSc^icTLyxnD4`q407tsOKT1h1gI^_S`>v}w*yj;Qn|GF2A|XaygAV3d znF58YY73r4E<{@;aUL=_rf5WAM={^MBQ!Qo&XTr;k_JeH6CbKh|$x=yOVL1~vvDe6-` zHC-W5Z4gvB`>lmEIF39;t7lb-45Dr7l&IDm=gTncsV!`i?|H{7>EVSFy1cGeYx0(uTbE zT7t;cozNv!R>TjC5%&YzOge(=vjZE8NcpaKD%B^SeCNb4uYJ>HlC%iKz1=78 zvO>O4za&m0?}G$SFW0ADe2BSCb+9a%p3Y1~U?o3=^>NQ&U^KO#MJL~b;btm@R@kP` zq;?WnA)yCk*W$QFcB z)+q)?iIx#C3=|~zgA*Mj^26rSMHjJ#NH+AD>vA!}-hLTHoN|<_TJg9RcbXlJ^1o?_ zy$qSr0M6n(k!p#$f3S*aWAY4u&tC40Da1gK5shkS!@sqdv#=K|KNxGslU55^%Ib6o z{lrP!39(m3uWf~I)=%RuvW3%t3?f&{mtD;kRu)LXi+OL5h)Fec@gm?P zn-TE@8;V#S=GyMMD@9;>vF5_7m5Chslb(Eq)|)* zDbPXDPktfNs6(k)w5_Rtb++KyYPr>u?l#K(@5USQ*7Bcjq;U^V!-L+Bfa}Zx$O;e2 zHqM*se{fN7iM!U# z?}ApSSM$H$wHsICw;iV!4^VBR)xO(bR%SkF7|v*z&ZV&!rTLwwG5p&1N#*i1`13OS z!Ry;J|Gfxt#QeMBFdgZ{pj~wy1M0VQDM(Z;^0x-l?cU3xW*ALNa9_cljcxC54}1jP z>KPI<62pT{HG=&#m`WHt9@7&*dV`fwlB>`4Rt&5K?WIKokX?oRoTv~PY>1hCur0$Y zNRamtk-bVw*vf#*UmJ6Y&>;Q&`{_;2^m}v`VB64uGV%X`O}sM||;q8ztdQd5MG~BF5|@Xb!Z=anH@;Qk`x1Kg1=42aPa+^7C~x;*w}MB#!Vv^YJ&K8^l{rG4!LR}4b6OccCjvdah}%k zXU`djB2ciiNRUtbCDs?cueQM(ZaqZX4R;4dGLT)lh7tr&rK5XO5=Iu#5<}i`Qd$WS z%D53j1{pMG~jKCz0e^cqY~{`&qn&lDO00>jq#S~4DYQ<4ZS1?ZS!^nK{et{lVkeTOb$ z?MJ;VNX=q~lgYx=1C3*aOi~?ZQs3>d_(pzsqvdQ_YUF!2)w`7bgP^^?PdeFUTGV}8 ztwPZ!Oz1EZ`Y2NSM#Q_6(wG?1wD@$0%o41DHtvKd@UA~ zQ6|VIGx}LVB~xaK2}`YD7N=Gg6J18LRz@pnR!3_}7pZnGQ?}_@X1#uPgip3HD0{3m zyMH-*DkEch8PP4BQ)QA<=bkf|k+X$MN?dEDo4Cr^B>lL(EYoE2(fEw`lqvUICimAB zaiuZKVMeZL%SRKQobM)dznL&VSqw-U;~>b=UYZM$4Ygwhq^=9z|4I86S)gBApe~f>r^MoCm9Ml?_|`6oO}kLVz3{0JCVUg1a8zh&T99{% zF%Y7C#$5a}qtK+S$nLt(ld;GWLTj^9oXW()=v(YDR&?8(@2pMhvQlgWDJhgG34l1g zcS`dzrS%aiehFbg4HpKsVc+30T~uVTuT8N}uZvMDB{9CGx%b_iAf<9#rO(<*Y6x=E zW%10w=EYcP&QYm`FBV%{s3VkH$XqT6G0Tc7lgukq*Dl3Mp!6;G1dnZCMde z%HEba7{EdU6wW`=W_I(ep(@9c$`x!$VwhD^DRrnB$nrs1Ok8FdrkjFpNsOPH1_xO! zUvwc)G}9fOJb~!^Y+QeB+gzQPTs=s(HiN73daRzvw4OQhp3rfU>?*agGp6LM64Bn! zq1^y!laM~H(JH6bW5KjVRr5L3ny@q)WaVCYG#KerTk7OWm@!@XHvM64vWc$uHfnOcd=sl%LeOSsBnov{(CsjR{z z+0&4ZR*)P_Yj%6<$JN$iJ^GJ5q|!?*!R?F*?bS&v$v|1Ns%g?hKs%VTy+N3?-nl*6 znX34vrBtq>JS!pPm^8<&eZZ{!Bf6cTw!L_!o#du{V5!Zq22y9%(X>k1AKk&2*I|C# zI1ybwH6C7xb0(=0hs;NJa^-b`R~w(Kc1~S)k{P!y3bzkCcX0%DW%O2^+|+$P_L**n z3_ExJ5~ltW&19O(pZz-NP_kOSaZSVct^W%(x-c>#fuK zW1$-w)603*6LQ>JO4gTO+{2^W$86n)jqaN$?|VPgCuZKq?B8u6+<&6ePgmYJv)cC{ zyF*5|M{c73s=V*M{6L`D0PJ;*X3PNogXroGAlrL=XL|Kn2d9Mlo@IAF)@3r2AFAeCj5*A>bJ1np&xdUh`LNQ?Yapz1vE#uKBxmWT;B?@(C67t3m=B*4$;;DnmgQaC zQ!J)3|1M)(-sb$B!dR?iPA-LW=ZxirN#I%Bb(@pq)GbAF+7-7j{%3^%#H z>9Y8xa(>I=i|xZN&s@G7k$*l||9t%Si|qOrd-9E6oipc^i@$R=z#le3D>wdiPTj6A z;T~=-vTmk6+9Xk!Ao{*c`en1aW3%wvCUw9ljD3|RU~BGn?l5+X_3;p0z$zR2w*Ku_ zr|33+TpzE(nn2g~Ro3?CELQq_YQW^nu1(vn%E_)xK%rGYziq(Y zVcFLA*uB>;@W%%@lQ zGT|%AcT^R3m_5G9U@#w$r zQxxCM#lHQFJNf_@%7)OV#q1df+e3++W(=zjQZ#J;wdg3GFb64)bcVs@Di1K8P$CmvvG-6tkE1-iHcXrmRG5PSLwM| zncY{}8&@B3R~U}#e8uZR%j@F6Yi#ayS@(6t#&s3$x`yMXPVuI}@}?>9rX}~Lt^1~9 zz%JCb`l)_ps%aXW>(o#yyEtN3@`^6x_6-=*BYE8TzBa2tQW z;QnrM{M%Oi_to;>Uf{oj+ zGEl#Zb}3Q#F@Z3MjUIFUa;7KvIaco~Nq=nt%xA~Xt1LPL zz%0*CmP-Agqi_I1G?ZAy$z)jxQMpD6gRr_QbGfV#v5ou#uklre6M?gX6A7$Ch)B4N zUDs%ML(Cf)Kdxybtlf76*xFyW1O*X~KNO4tsOOmec3P;k=niKy^L(x1hYRqAPv;@S zfXre}(|UjhAZYIyJ^U2lO+Zzj6GHn;QH!p-^W=c^|{rUom%Yd=c>LNvk+EeTg8 zsoLylayr=EQnGN-=3>;rtvN2>-`~GDVsRychh^U)zBbkHp*oG*z_iSe9!zOWcF#AI z8PU7Pv=R_TZXPpVI3ViuE^rq*qa@TL%Ud%y0@ITw_zC)1bYfDjb2J zyP8}PymuRc54|_Z%(68p3Swe<^J+xd-*V$ox!xg(K=iFJ4Qqtk7$dXn$PaprZTL0; zuY!kr7{%BU7GS0u+8YbJ58;mZ4imBhi{U_0dI(~^U#&nUGkZFhl7Ftaie`lr2 zlZkihMS$of%Zk?c|Dl@;1oeznNfZlEr&dW%)Ma)#Hnp$k-)!1Zy+g7Ik;bxDZ9u(;x|cki9~Pq8j^BfFghCyB&Q;LE9}1=xSmU zCi+xJ&Sg}fq~p9gF%eNc9E{lvD#rCxh&SLyj>X31n4gQHvSn2W$D~ewQa*Tz`5ymp zyNB~xtSf>bnCPo7(jmU@vS;*;IFeyyF3rBnXP@ha=Rj1xb2qh)g*8W2gWH}xS#3aC z{?Kd;z%j*M*}RU9b0Pr8nyo3>{)nHFmM=K^ba3hO_hP?05Qku%!GWZefb`SIYtl^u zx)vp(`_n;`p;jP1X$0i?bTGq!716yG1cm1`E`$SQO`;~POr1I%Dxhi&dDfy#-vqno zw`2x=MWQG*4-Ot32=FvLKBMXyOPu^ zPIdQr$2L`Ciy9~WO!Pl8HF(8z761GMOzB|m^G6^=-|fWMbq6uilSpgUqsk`&3}bwy zEEKnf1-u$4fcNQvg8g}EQ}jsb*lkG|w6;jLj!~jOeL%*@hzRBYsMoSct%vGOaGM44 zywyiVzgDHqm+rU7PVAQ9e-*CpZ$p!V>Ss}x2zVy46w`32BKC(m+7eX!vrin@j@@;2 z5C@UF^=l_;S`#u#GbBTJhR2zJU?v>NRQJCc5?YaB!>edrBHyHfQzSPD>{2QJ{uQxg z3_zOFA^uw*XL$oO&-TL{)S5Ff;m&|IAPq2~F%#NR&k1?@&`!1fhzOT`Prs4$xeb-s1E*lO8%aM!dq& zo)PivL7(P>dtu7LbzlmZL3GhSH+;So!qNu;n~89l87B7<%i85|IrP%Y8~}8tX~R5P zw`n`5+~98u&|0)`EpLDx6bPX; z3a5RCB!(RKP(kxJ*Ueq>_#IM7p4XsQ5AMqeY6kU5O$YHOZxQuBOylaR3E6zd37I${ z87ymyFso>Sa-bF?1|T(j=uuC#=^lnAG$F07Ad}9>496HO>~6Y{VW1mmq6xXgqqId| zDmB55wW5t1=u`TQcoPtXsbB(cy&(2(1vga~-B8 z(#Kp4N8UsK+%gkUwnz)xrjWUwiR}9{*u1uCuOerg%#;tc{`QmxN;b!C>_`@!PJj?h zVj(eBx-)dGA{K?SA|Rt3vQ$!kEPB5%jfjy+nKm8ZQT&vcQVK)Bvq{dO5)8?$#R6EQ z`_tq@)p>We5h6Ar#ArPtMjw=QT7ohm+KQ~=<2XI#3b20xq{#TW2H<;KO?!yyJBs(^zva;ToZ)czCFRh8SYm81D?KTZW8%LM z(T#-AfS957{&~HvPzfA z7Y-29QKBM(!mEWDiu1xHOp!(tw(S2-H54Fj@j3hb`_jb3ld%%bX8Wh%ZR*>$j+#0G zLr(_Dre2AKJpAp$)CUnnk-hoS5XQc#&dmpp;p(#ZEQZWkVck+rd-w{f7Twe7JEOeJ z0wB~N30IkOc7W)e612BGlrNYDK}RsQaR;4%U{u$fptTgS8*y z%=bqSaf-o~0C(i&fLb-y{ta%))UE;FVDx1uRrp|;q2_3Ruuho28J@^pX#Zg)gbDq# zUXt_hghfkkzE6tqYl~4Awuc;g$=bxl`tpwTaqNZ)_djnO!uqS<9a{kKb_u0O2I++t zD7Z(NrU(C;Md{QxE53!Mz{)Q+< zI_9b;V_c%KXzrojCD02WI9G|w9Vgz}L2MFs1t`UZC@H|tMfS|NGgKrd%JK?@8A}Vg z1faAka8Q_5l(7;I6a##45cKjm?E&;?}g-=c!cWy zLU1OJ!s?0IdPU5g9@@Rs=E}%t?NMwzK-!M84jY5|PLm7;D0Xvb%C4w9l2V_7-OI!hT*e%Ko#=1fE z(fb$uv=#x$G}-P|Fhx)4g>ne(QV%OSx+WCavqFep!0VJ|=dED@6lwXd7RSt3Y_Ux+mkqz!-=XQ|tlJ}y3*&(e!gbLZ6N$OeC{ z=h`L9FHWAqX+|Ag0VSsI>j>2fmVO+@hMi@6{64|)Q5_VThZwG?vrUj_%45a3DwCp8RE z6Ug>!6d$UZ66FNNI!vDV<+HoBtK zJ;G>Oi}e>V{UpL%1WDo7_3~ZcA+N#FJYN!=*-04_uV)Zts8{7MJ5`?(k9r)hX^?=L zEl+>6BgG2i(PsZJBknR|1e>~pmdVJfFzE@!`EIuQ0}MIlW!$k58p5)ShC|$gbMm_> zWaAI>cf@ZE^d;!#O)DaNjX~E;%FzZ4UfzuXJu(kI%xv&z7fQ8VF7rJcod1h8NLrdF zJDPv4-KNlql{zN=$TDyE7a?5pNi|HZi9ll0Z;k6q^;AUQT@U!lu0ngn=qihjl z6}&hNppVtJ6lpWt5r2v$HYR_b?LTd{nrAuo*|BH=;G<=-(rL7gPZ2+t;G46Nnj_y4 zZ$DmO9SHTT5s_n?b$YdU*ztL}<@vgtzWdUo2i^RJBK*2Xa+;GX}UaiTg5TCg}lZgbjt}YBEv^> z>o>sr>kBBlxd8F!Zj(l-Y;z`cPaXM|vj$BnQARdW*{>>%GCs`sinF>%E{tW0J^^WgsGuO3%pmcOUuPYDKkYJ~_;@7@V*Yjcw z5<1FQ5)t$9t#(PzSgxmUiT6r~&kEGO;{4J84q#|&GclVm+qBG(Ptz6D1|TYHx;KD)=4DGYjX@U4PvGF z>X%S@m(cXHG3^e)cDT?3t5SW(C+THjGMXeA!E4YaGqhgWYeymNV2-d1q2YR=K*MU4 zW1%^M@^4OSbsi!0=jBn$kxjud%~9p8cZqm7OLnx(n@E#bVQB{$Acme)k*~0pYeJZ< zNY1XMd*cXzV$K(kyZp)mcjISaP1m*N(nb_u)kvO7tb~3W%$%x3N$ZB~OaVFv!EB>H zQt(^Gx&<4LlCKMe%zLmdcvN~I;_kZ9?a!hl#kKY>v)@?DA9>Kc>=TQd5i7qt&_h~% zCUl3CO#HXaor_hKtNc4RebwOA>bTQ8q4++LT)Y_!h)`t}V;nqi2hwUL-P)N}YPNrXxcuUp;mr{R_NZ(&2d9Yd~ zomDSO)*`1O{cuMTXOPsR6vDiW2vJrEQAsK=u6d&4zEa&e1?&OY#~NSh8gc#JYk0+^HdCjV9&Fdk+gBqHpOWu+ zl$^q%=+hfU)IoM8M94awtp+D(H)gCZ4xU8-H82E_OMoOfkk?u*7TG+^C?D*N@Hgxb zC`}J&k3Kx34GPf+DFBA@+_N>7-g0X(MYe=NCKl?Y*|mrW4`c3%2gSDw{47GUxwR~l z0)zYjs1-tPq8;(#b<+mNubhTepAY?WBKb#%?Zk|9F~(a1TzTwHSn||9PI_WhiuN9{ z+g0FgFaYOnL!ryu-7|-}9|~a4;AS=EuM&$%$%3+L?q5oV*C@wz5_Tc~Fl_}K55CK2 ztx|n-t1G)hMVm<;icYwfD2n%sF%Zf%86-cbWO-zVFX5m2?Ck5LqlCoHQorOI5wA0_ivnTf98oy1-r6G)M^-s~V%fIi zSz3lIv;A~5L3FWyne``M(D-Dcj@qbMP-9y*r9N@z35Q)5&_E4*rbZ`QY}}PDHjl_~$}C zo7Tz}_NdQBFZu|zZ1VKg(W=?Io5WQ2tkD1=md8eBH4Q3K@CVfU4%VBF%=x>8?qeh* z&V+y6SDm*dJ7gZ;OhwO1Z!O4F#shYDlp76ogu{>x3;Z%@#X~PR*uHU z6M_V`g3qe?P)svX_mc%x!@&=>jZ?O*??BPKGHvJ$Tw{qcnQF^)MgDJ#!OKm}D`}c9 zy@R8LM8zK$ut)4TaNk@eW9UlPgN(yRn;LjO9V(0^@X69c=AUu!qP)Q-kI^RKW1k|- zhWA*kNa^G1vBPmS!>&BwqYjZ7&*8~~u`-N?vlS6)PZGJfG~W~Ayq3tvXE}%u@sFgnj#9ZA{7Az|Y_27sO8oc)wq#9sm9*1<5G@}e(cx{?J2&foXfTzf} zDq_b5wln&DL7RSN%Otbs3aCq!W20kcl{G0c46^|Lbq+c_fOAf6 zN#H-FFd{a%HhmdM(F_E%0K$idL1UF&M%rbmpE&zpL^|2k?u!-&Sy3DZMQbpe#+0#T%J8t^!cSQ*X;eK@y7ZuMI(ye`1rB) z$@QzrcePyJbxqeB)r3J(UR3i*&mSg>>wg{d;`Z*!*gcr6QF!Hky5iK)jE%sA^H~+3 z%lv4tpY>SqPkNqG?XKI!ht}@|FZ%9le4X#Szx8!<{}gkvKZeI6_=?}_p;HAKvU3w^ zcZx6GJpbD3?D6yotMIbK5AT8n%ViBO<(*fP6rO8IXuA3B@7aT$ZbQCK?BQAGy4`PE zr-JWZGLhW8V~KZRN(oxTu&$IOp8M}71% zx#~Op{G@H-3H!ifkL_AL;FqM%I2SxV{CY*`ddPjCASUwol^t%MG+nmw3-yW5oYRaS zPx6?ai;A{x0SFN9Fv?5&0&AeP6+=CFjdi-vrLs8hp}S9HI=~;a8yCLs83ogSa1~21WtMAptAI)!>ll6@KdH#&*Q%`5U3rCa< z?Ny&iWyjSwj)s00BJ=*0U+`H5Rw?!#vcJ(rx1YXon!9&}droy+>s42bgn9sRuv;6c zDBkF~cKQlF$0*%<#KU)b(d6xi(?7>7x*S_NZf8}lGp+`2`pC#h6y_LTx9y6O=#Vz3 z3G)*9@vQsuBA(83>XkeKE5{)*#D5#(mLO%$Ye9E(SavayuoV3cofmrzLeTjo((Zjo z82Dp735?#bYafe;ZS`7QKh33!2@j|g;lA3&%zN{?=A`w#u(PK(t>bUO_`1F;fT4HZ zOGd#2m+SZ^u%5JV{V+{u;Je29^`PQOHP*3m(8nKW9zs=gKFcIm3xgMHNq%4ai(=Jsc9g zuegQd>6&=nC7>}eLc)?kRyzRlNwENL{Ho!6p1R?yB4g<6#YirUvr_||3~$Bs86T6m zy~V?5b>h#SprbA|f4DY<({DNiuE=#D2>m8%C*__hkx|`JVzZy(!ivdhxxTqP6`2Sgd_iUcFn7+s)P62cOvdz_0qnpe;gVvaKrjU0}U z6ukw%t!lt?4)^@<2XU*kI^n6)TxD5J03cDG$0(`eE)}VnvOemy7H6iYi#+#{(>a@rg z*5)rP@2Iaij#XN{>QlsS)h01r#RS;Ya81_bc*OIBmA5EcP(@Mao>^A1TP8VBM!7KId!1(aNj zq)RB?ik2!eM+jnl^=5FuY)QBHYkOdJOqJhdq`+py`A1h zp8syvTvB^oOuWV1=;dIX=Lm3(1l<6&`%;Iu)E@tAm=A&R+uJ7_Qh=}Hwq(J*LEL4ICxGwC? zEhMraW@Q-}zFxHQhaU+K8a-zdxnZ+jcQ7C@JO@Cj%#Mj3!q>)*;YuZ8 zZRm@Ek#;vqr zgz`wS?O&BoCC^=|8@~PLe2fik`7a>VJl*dH_q6FLtE_1(DGl$UOPJ%Z~Mf7{>m zlXK}&{ei%yx)RCbm(6%fwcw#K><$Z$Gr|m+fvV~&c(NuUchW#;>Js*Q8qax}s$W|({7lRt2qQ)^C z(^QTH%#k%C9N_;y?EOC;1wnus04DI|e;)-=fZ-4}9+V)3DglC^;OBEq8j7AK2%hl% z58L#A9tCM}1A$R00&0<_0O08VK%_b{{BVts`qp zS%|cH0t=Cr^TT<%$yh)JgZl@OM*KK(H4v{j*X1xf{%*9b{{0inxbeXYwz7-=90fVm zOu8>U1GlT?vyOt?8x6(9-zn@iewm=^zc;I}Yg&0#ak;wHvt|2pQ=ZLezPUrg$2aZY z{aWn)ISRVTg}IwFjlH=z{7C-(-b=r)U&h}kv5tcF%vV&A7420_KezS8frP_v!#zYG z7MlC<=tOT%@CNc&W|xt4&)$o#TkGXc=i2B#HWcDDYxWJ+QBY6caSL8mF3h8dRMp7E zNZ$PE_jX`jK#YN!BE&i7!WHa?*u;|=4hFp@gSs&aM%I`(m7x`zs~x5|G&eMthBFg8 z7m%BXgPA^d?Yw)+G2*BmcKM-M=v@(KL7A-O6mx4Y7Ad>WV>#w5H}y?AA^JH_QmMa} zOu9>1Wtr)v{@<8{hFaM#x#C=h4_3$&*2=<+nT4D}x>dt;$wZ)Oo$qWv`8*I9CoGdatIGk9e=w zwtuc#uj~G`wq8$%$#2jG`F%DThGnWZ8pkx&Sr@-X@|(?5tfQcond{Y?t@HPCMAduX z2BWx-@fW^!d@ggqb*vY?t?S$vVtom7+~;P`PH(kx&;G*Oo4p^SeUjVQqD6d^!8|qB zl$SIdNdssd1^+?bOTPY31+Ufk4~gE~@PCF0Q@HgEp*+TXjxDeGF{046@nclwnZnkX z`kOPipUb?h*&09ddt+-t`(v&+!$9E1_M}OHLLy`H*yi>tyzv9ISLPRP{CsWu#_VLU z-Tlp&*y#IVOLOHXy!cZiohFy*qMR{@9A@vHMDE`Q zzURf81FHcG_m$r-gT_wWGae5B)@>jCy##vq;MV*EBd;A3b*T1i9*SDH|2g4Ah}OHx zYrTl~C}Y=C8(0Ah$3Rijc>9T^&!M-}-@|{5%E@VwUb!L0~sfzL<70@rA|GjFUk&JR?=XMrUKv2nmmoDu5bke*2li}nv0#u-;4+pmZ zIG8}#IAiB=6-<@8s1j5&Qb10HJ8EsUKNyOK{yl_Q>a3ebqStnGjpDJXD!f$4G6-Y{ z%FtoINYv)bCFAa-cHg~HFK`*l(&(9-u@@v`o)Ex>f^D(nfSX`*$`WqmI9dXI33Dp* z;}qlv8(IA;^4g3z*KMG|m9!$jX_KqUPQa&HiSoiFD$YQ-E>a2Mc4Pq^%irrccqQ#- z%mFyQQ3iW{x;V-bA%*b|M8SS3Nct7-P2j8Fcya4ZkCY~ z+W?@K^ToKdO9`pf`s~>_xXr=|EjwvAr>I>UIZYqqfTaW2K^L+7gcxIN6&L%4hg z7UR>b+b+XtGb786lpz1glaR0vFSwbOwELnaCz@m4#5I#KkpUh;lEW%WZUo7rSey)- zY=RHBK`F@B3y9)+DR-zn#V(mvanUaJG#Rgpo)C$^EgYv9?!1nV`IF@QgbRNAu5LN# zIc^^8sp83@HfWUpE<6sHu0vQGHk3VvjzxB{YI!@ddrf<;>@;WO+`N-As_ zQ$|dsDGawvr(+tgL1)r2$EKf3AOUZQ&u>HIG5U+7NmhORxJI5A4%=TeBg= zNb1ZjmYYoNFsO%UB%p@xk5gD`22Il0dKYIneFIzn%f<&mUu{-VzZ)~+kS=T2F?<)R zS-J`%`)-M}V_c4Q2%ilv!Lg3%Osu|rp3$P#JRD!t6T5ASPHeP6izoqh|H>hiw4KSp z`-bZ0YgR!OsgmP6Kdacw5wdV{oxz|O2j79`Y_md14_3VSaIP-;r;FdDUsX%+{l>1z z@VX}$uRXPA&(k)4*S~8OF&(hx==9sKooua@Z0XtT?Rn!2T@f7#?HgY!Jks&v-n~&V zjm->mht$i#Ldh?Zn3+*c3oX@{&f^PA>gvr!U^&Oz=IiQLE;_nHl^uq%SU_Sk_m3Kf zNUce^zy2*rj@W$w>3MPZt*pvXQEDqTHob8WDX|3~G1$(pqQV*2V|Vg>Tu`WayG3|Z}7TDj7fYdl7p zj5?l{`gg~*>$Mgg7j8Aa>iNpLyIKV6+-_}q@DWn8`yQyX^DrYI^)xkK-d z%qQKSO_F&HANC-yJd~d1p+^^F5Kbyb*eqZ>1 zvYY?C>}Dn|e2W+_K@DQKZoZmm>ayHx(bRKcuN;f_?%*;KLJRE*F=Nv(&{ zb`NC&A7Zl}%5^+cn0=_U`%p#bk($;cb-PCzfsZr~vmR-8JUa7Su!sPUMzdKlA>3RD zYZC553tKb*Vab4eD~9rLA)PT$_%iH48j^~Eft;bi`dl6-(a|`l|D9`(u?RyN5X}JS zqrIUtIF@lvmG??8noXPn6r=**N^ylPLU?FEVFo}D2Mr^@bpb$ds=b>Q+EN9yaS{?n zO*_hfcv9lb@epeg&_~N58UqmqxPYCJMs(XY4BCI&c~KfIg#js8!`zA2oJqhyS#&fW zAc=>xs6bbLUbKjcdn=8&M#@TWWs710^%h}W9X1{+AQdXK4b65Gox{t8)S+fW>5st@ zPM=Reo~PMAH-+LW~PT0y+aI$Pmo`D1=}kvOvzrFQz~f8Z?Z_rpp8lnWCeaP+=Sp*a?lq zd%4hnyi`^&lnZKLb5;SdcwgoW$WcO378da#E30r3%1MIocq6~1nTeqbdE_8iKru@Z zLt2K20l;0Wuxl8YYe^pWQo(C>MEfs$Htpi{>&W`m%rFAVvKi{aDCS;+$ujeKmkN&T z0SunIgyE4bG|*8z42HPgE)8B-F4B{WQ`625Cc&_z3lAc}RUPn=4(RXQ+!?Kskmk~h zOaS+xc40(EmLM^k$KU!n6K79NzeKEfXbW>CX6fOe?j%?n9wJOCHj0;Oqd`1_kgf*$ zb4?&m8k;^7>PdoKrer%T!kX4tyYMPKVtE4vdVC!Fi zi+gPD6c8_i6=_1cw923)7~?$fMQ4sUpf0)t#C@L2oMjj$BJEAHGq8vb0=x}hUHBQ+ zMnSq`V9#caf7|8%-K}qQsk zJhJ$PLBfZo{2JlP`WCh}YB47Os-+F}^iIDDFt*2lvBc7EX=U};3X}5}FHvamv>Vt!8VG$O%)g3_V1yAwcY?;@V_?TOjNS{P8YkE4kkgwzFX#er3M z6T;9?VJc9T1jJH-3i9pk_;xLCNPczuh$-BI*7@a?uI7jMgHE;tJVcKHS%4I0UFZs9 z$xbNkVMLf1wYE*AN)Hd&d+tKp$>a$_CNJh&%R1o?ciEb{I((`M!gtvc;-r%2j4zOY z$ej3K49t8HmVkzEG9WyA_SYEDs0&a(OabkAHp@F?aqO`l31%b=ZVW)0lO97!KyysV z#9T9)SRBk`8*$4dYZZE6iuiJ~nz68Jgj}KEYn}wSC!joC#>s_3OVZA^pRH)kY~b;~ zc2wSpDdeqg)_Apj;K|BB?8v}1_}~kZLA{VclN$L)i%<(R%z|~cj!X(i0GF#SPPVs? zcJzWR*k826PXNH;RZoHTfRy0GU|Rc85^(Ew?sGeUITKJ9l$byQ>tP_W48Y#tV=4yy zBqveJ`$^C~L`hoD=wP5%hD)AwVdhYqiy)d9BWz^CtO1ijoGb^?`Jq|wL_bpg>fH*o z8CnIW@86v;V~9pGfW?l0B3vm%^(tMH9ZYV5sAltWRm~t1f4dJx`6F* zJd`sN0PdOmu=~RA720;(2Pu6cy%o?F?a(PngIX>E*8-6jX~Qk;8N3XjEDb2W*xf>- z?sdQN?F5h^U zv9_+bSEszwH{yYYxQ07Dy)t>t&6)9A3!V&PK#1}A zQ(g&rfU9w%F5d=gIH4h=T@Z}>~`4+vw+gHiKO&U2x)#;(`_ zc;@WrzjK~e^U=HS5gh?rYpk5-rb#D2)N$+I@RwQ8=b$9x56>u47xG1K`!DvTo$y&0 z>o}oDe^a;n<5LF<{=ynHzYDqnXXgf6vT~lTdzO$heMH+N3=s5|9)T41yY>Fu5k6}X z%y@Ul))yXA{D<>#knN@?Txe`2Mwh$^4ZC(Ie#xoi&f4^7$}tM5C-~df*P{jXsocl* zY%&f*S_^1^woJtZueKYuTVarr%S3Wmqt zUy7A}9AFv3=~q!0_9yUo5i94xel&oDXDlUgY0OAOg2q=qrr?C{NJVP%&q}5)a0#+< z9_#jkRDe;|$F$9pUZ2vpg%%}J6>h~!r2$=7@Rt{x&ptgyeZ{&*FQ%@3&S~b5{gUMf z8kWor_&hrs=Gz$iIrTxWF)k;F-@C&3$(4>z*`amAgn}3&xmBl#dtR#rP!*DN-j$1M ztK~No*F1}%DwFRDETY-hs%l&e-Sfn~4?8E=r9#jFt1K{~RfZSs+_5PIjwcd?OgG#-xW+kA1$H%mvPVYJ4kf)z=o% z`1?c0_VlPlM6nF(RN)fF0>E}uFQK{zB49Sjg1QEmgVKjaJ<4Im3aa`&Efq2;JE1#; zbe@YF-=Begd8-yP=hh^Lv6pH-SIge2QRo5*q5t?_NikgXO2Z&YoV z%9d|)bDaHNX&9$5)@9PzxOTljF1zM?x24C8nhMEsd%(1P%!@S=ckdpt9G_6DQE}2G z*Hzc8Uh(&IeCUn)bGN^|_@x`Lez^JjJ&8?eXE9R1Z)Yj?c-_v2#8Y2)K2nU8c9+v^ z{B}QOderTH&b|M2_X{;fX>X;(VdsK!MS0!cT20&6y>;3%rTvZOH-7t@4TqMU)14o` z?ti1RDIYM~54p#`8jD}UDUY6-IM^CD=KQn$(&o~ipVJ;Ge}2u~pZN28A!efI$MDv{ z=%3!B*r^pAq!Zd*6jcZ}uIS|)NsPprIm6C+>ZMdNqf`_K$jj5c zppasL&iyErmmUK*c}W6jh2c|&y$uMbMPjUBnvoVmz(8z)CeV*DI&#<80JC;Pupcf7 z$s6uI%I(UhaUgLdSTzv@FHSI@{{X(ZgLLto#JtxOSB5m`OWXU$zh@YpMBq?PB#Zmb zzEaAb^cb1Zl)L;alR9~Pq!#YFnB}OUT19+YR$r2tc9#ZMocCbeuM^EvAPkIACQ&EYB zoh`IZ*QH&OE>Z}Y3-S-onX_Vfh~5zrW3>GV3=b@~6GBhbPj zWfFN>B=={*7kPL2yv+D;QK=Z1R=9TA;_I!JpGiFgeO(QEfUf9Zsc*~rDe;_l;ikU^ z#@5$;fg|0)GLTrwze;)pfSHW20Rl>bqVJI?wSKBukuS<^a%=$L;=6gov$rIXi%GEe z>2WlZ*ihtR{l)lcFl@GuzuA_ACACK$)0m0lX#8}oVh3Zq62*BLZ7D|6J?tqy8}5bt zaEZ^yIi}U!U2css8jjyV(%g%Je$GPW1xsqDFgKM#f*1K9Tk)BSbn)92NJoqiAX;Ry->#Z*($qM z(Z8VMo&>bD-)m~;z>goH7OR|0677pTn=C>PdDTj@&DFhF_b;9_C$?Pq!kk!Fd}9+N z`XRO2HtLks`gq>GnFi^LCwrv3q8;5L3jJ-P9^{F<1GQr^;XujsF9e4O6q)j#WS|R? zAf9dyN8+#%9uH8?PwwS(6Pxc?{MqF=<~oD9E$AwjO?ld!KOubVu>ArMi<)73>H11H zL`KiE0pYnmj>@wVull4|E6ja&7S^C2#o6y1c^e3VqJ8v)i4kXWm9i8*-4gN)?mWvc z&G;f>bc{c|GXm8F2wMq|{~mHKOJEr)vPc%m!;vF0tpqQb0}-h3Xmu8F$?)8;ij3As zUBo*+)3aYxZ;WjPy1uCueEPky_}zJL0jj7r-;VCQO3YCwQNDrgO>vwf;CM)1tl+VM zr=trAx9%)$K(P^gqm$DDCQF>SM0JU*6@9PHc1$l zhI#}~HfhRdy_@;PyFi6`V2)S&o_EQk=xZaq$Nb^Tj`CN^hprder)6*dJeZx3Sfh*n z-Lktg_*OZrE%nCy&)R~x-*3(x+&}W?YR^PFGv?|?tI*~02hdnE2pk9WB>k{)h=q`T zf^TlU3Y)x-TRE)jyGL0vgmgFeWd5Kk|*r!`@8h7t~jg4oB#PAB*LY6C|rv zgi8#EGnT@YJ$X*FM~DyWYItH;f@Af*2!kCxtZjtOjHoU)Qq3arVuczQDq26UrXI~_a0Xt@&9TYA)|rKoGe+_tu1E?B+m6=JN>n#^SMonc*vo#;NU z81vY0<^Zk*dNF?LM!8HZDf3*YVC=;2n8Vw#(I&AQ0|T+cusETB*!Ko;%n1ECQp`u) zsFSI29kjdm(C|WAK#^^HiC}y&Hr^kPE*g%%M~g2Pgg0RCRAUpMr1(}_K#MK9-4o4% z2~^G`&^_a;Y|;LJ#LkuY#@IyKOnmuFqTZ>5(Vh6AfP^yJr2g3WDB9iZfM{u3fTju0 z5`g1{6r!1syb_SSmYKZKp8RztnYokvLoj7qGi4pi-&exnK9h86CwwV@XACW{Je-2v zN`VAYjyY4{9TbW0Nvb^P|50qJ0x*C9(8_=Jmo%y_Idgln`r*X;zW?*P_CHWVOIJPQ zFZ+@Ide{C(@g&8g4WKcuoumHquKiDcdCnXT0GL(UHhI4r`B#6bY*~B0IewDn`KszF z>s{;6qW9eC!G(VmPpo%st>$9|K(OP1*8G2{&TrDDOt$U;4{on}yTy@nY zQ5Mv&_`);qx0;6jd)cn_2wUbh3u>5fc+>9Bou>;cPdA&qzkT2N&HOl;AxQ20vnTRf zi%7iD%X(GB-=~uxN7^S5ZycozNGOdJsxQcZ1vL~>WG+StUdPUYSWv^lXx7=3i#s^Y z^Fy3eS;dF=fMbgv5>#a99}?B4hxve-pDU!2HGZ+)wI&jnWr{w?YdO_q!HxdVOeTv5 zbmm7a>5_N}aik>}IlzXew zqpaky-2CH5(Idwz0)w?f?cC6~qEJ_?<|E%! z-|F+NN87*SOJMXuMjvrbHy zR4deHN^>q>7-GAWyFDew=HU4Xa@GO|yp=~> zVRPi;p6oOKgLddJJ@0vEC1P^vbp)^=Zr`FpI`I$zy0~W7^D1mXF22M-~W2o z)<0Hxg5^0p`0?h_;h$e$QV##_u}txYe~}mf8^|a_H#Sog-}!T8j*!4=XTb+Hn9-pVKN{*$Bfn-D?Gx2 z8j8)SgfeD~5QkD<1|)^Q$C{WGaX)}_2pma`y^vVMTW(?~t1%gc4f(J{vwf-*^gV%) zD52i$*{+iPJ<-!ZQi$VCzk28QBx2-}@Zt23=G^z>Yhxco-&h-;+54ViI`8^!4?e6X ztQHf*yZi>eItapog$HA$RhMl6PG%3I?3N9I(pdC`(2pW1ywTF1GCABs^dF`AmK@8= zOmY>KN>}BL1xtB72f4YXD>z2WA6+>wJi;y9eus*4v@^YEed|#Jq*P6P7wH0T0+4^jIfjObK=fjxx!rQ0fFaxqkrZ?Ni|NtwNIuWapQ2VHL{lNqJj+iQlaTUd+3jNREX{) zvG%&lZ2d1s8X0kv^l;qE5u|*{U2rsE4QV64Ab2hvF+XOc+Yyg<>m&-jCx#ow^}UdR zO;t->k#~q9PYA_YrML^4oEe=XgUq=3mX1L4KbXTrudBHfg?_nmSO^$w^ zyPV&uQZwY~1%#X)B8#S1q?fGmYS`Pu1eW6!t&Fs+6J9&>-eJ4S0kV#2NPN*r;L9F# zQE?%YB@gsy&Wgr-23~deMF5|p1Vq?(S{SVB$4;Rqe7cu;=#e<)0!HA-Ae8eF z^KB!31jEJdx+{iN*NZ?t%q+{Or@qJpa!%71jgB~DDsA9eg#?gZ4I{fUhEo+JWaerT>>EJxq4vN}U$@4c#~TUYUltk4JXw_Qtbcwyp<67k|V zK72};>xu=p8yI8?JdVIXcn^xoK&t);seq00bGk>34gp)_)0IxA+xr=j@a@t{FVC94 z9biNB@Rf;Oj+=LI@E-IUB0I>C>WS#=ONUul20%v~sME$}67wiG>8ampU-{h{Wwk_Fd z@}-pr^OS)F2{lFEY}_y!LQ>tx3dK)OK9D$^t$zDFoo5gYk%7NQQee6Yx;r4%Ua2PA z%e@sI*T^v#pj-GuWX3HW#k z%U}d~^OShJC2UaR-jOL!>@u$Du9MO>@*Uj}1>@kpgBl}79yLDV%U2ZIr*%Il`}+Sq*C#L$@NwnI1%k5((Wp*VG+2jWIJ9x48cs1zAC&)nfP_?gw{->W?Pl8fP`)nL${2CO*MRvW}>xv z0v)cDVv;yAY+!po@fXMd{K>tLHwmSYGz|}$u}yl}o^);~X-d;*As}f^Gx`IBJs z%1qK)K=SfV*v3xsw4lzorb-co9g1eVhh}3hPuXo}@e5Oa$EJW%Q$T$wV0OwuCNb?X z@%Ky$xPby)rGNudfU6Yt)fE2Slt=d{sE$-Yb_&mPiZFXBM;t}!c`9GrLjf(XC<=1_ zWXh(bL3XKK5e|7W@R0_qztrq_q&@rS%%eqdmg1))-ElVEX*Zo9^w>q~v76oF>w%9wvmSeQJocS^?6>=vD3oza zE8~t`#=XFdfUJz5j*O7mjL_W-l2B&2R%WDKW^`a?Y*uD`M`q$|X7X+(MJVf`R#uu_ z*5kme%&e^Jj;!3-EY|%rRVceiE4#!lyDTufA}hP9BfDlcyKXm|CX~~tmD6mO(;Ar5 zo|V(tk<&e!)4Q8P7s~C|${n=J9SY1H&iV&rIK~1Q?&dOt@?L7?P1)s52j~ zGC@Vy>>|0&B89nspoS{K#cJBc>h{GNLB*Qc#oC?4XXc8}?G@vMOZ2o$4D3scf=W!X zOU`$en9Y@3+$+Hgms)CrzolJ%$G-fZBh2jbpw9A;x$@Axa*}XGxOPRPeMNLoMQnCOd}l@C;ao-X zUIj(C@}YKRntkQtpvuhb%Iwa{+_}p9y-KQZRgrd8iG5XBP*p{CRaIwI&0JO8UKLHa zx>1`&@~>_Us&3D&?(D4Yo~!QNtET^pVmN4DGZa)aoLw{0Su-|QGrm{D5UzcxT{~r8 zI~`OzlU+O4Svx;hJF~~OC|n0sWjCif8QTD&aS!fYhkmg~FUlc`a8MUkCrqjPr&7m3 z7lY6qcr>e0d!ykQDO?9RjlQY^LgN9qWoXtkpa>NxLIPf*lOf;hEGe|N&1{zc>eJ;h zb&yG@2;t@#TzxPFWXNQTIZxY{LquUfM=>-A8JzywR`3u5QIki9(by6QAX!X<+*^nt z8miM)5AGwg%CAQZsLd4sx$IWa(q2!9fA@Hax_C!~#tG^GBk2glW?zHL%rvU%75 zw&Ux35}H!wJFXKzM@~bmNI-aO#bsn2t9;7u0^Yle#F2pd7+6?B3plk-j{@>r?3ALn zgO=L)_ijY2PzUE1!7yPASe^#L(tz^B z8;!wDlQ}I=Rj5Q%$Mn;#d-8Qq2S75lm+={BOoaw7wsp(Xf|*d3YL7P;#ESv#thea2 zJ>i_Jhtk?;!AO@fD0sASNf>$!5A&yhUv)X9N5L%6Pr_)>3Hc7lI^?>12dkuZApzxa ztj~0@HUYYnj)yX6DP~WYcfZj(gckrrlYl1F#y0f8Q#N4wCs;5M%s13n>HstLXt`TP zQw>HtGl4rl*>LV2Q6q!eNJIh#raRxtyAL(^1T$u}PctD7n10%6 zv>LRIwF4di5i zzg7>NLp9dO_1`=5tisIG$9EtY{jx@`C2gaQ+CBBao-v^P-0bLU%d@Yojuuv#q3g$n zq5iNn!~)-18lF(uh&PDK)f`d9&xlHp210KVKwG0gfZ~< zQ6ku%et6iv0;v8$mEiFX)?u_PV5nt(Ht;n1?lgdeoGI*VBK;A4Ic<(U<2yj}o|<)d zy^^=EcD5Mbv+(uL0`mrys={uKX}(69weK2nMnmi7=PMD2v|6Ar>FLfps1N|yIS&{c zt)d^WQ85hT#YN7BCZDSSPW-}=P}uO>1t_f-lGCd~dS7afOh&Wm;l{WuUi4jfQ789` zmjsfInf!WwLW>0Q=&EwwAGKB)God-KNsO~*DA#GTpO04Eyj!d05s=b`3+G1kr?=K=E5fzQ_wSpVjy^0`qL=KS@uEN^(9 z2ytoHcf4V}ilp#tnS*P)`&r}2QfO#(xF6U5Y$63usdO1Q0Q=fgiuFKf|%q1vR>Ck6TMMgN#>(YfF|QI=QUwEs)i}d#F|E6z!k|(?_IE%FU z^K-O|QgCIO3B@jwGG5q_LO@rXFF7MP(k}UMo-<)B`mI-3yXVO-6Vd!E%|}e|^EVh) z)9YDeIaWF|AE(f|Qgl)7AI*n)Rf$XD$;R?{06$NnYvPGi*d zynxTUR{$X}>X!nN%UwE^4dT60Xu?ifDN1A|V#O3z(_4~e?Y&x>dA(}2Ecc!#9S4t; zTf-IH^Ij_~Dyv$ntXcCSRne*r?Y*m;t9HF>+M`*pw{Gu1pE|lE&8L1)ZP$x7e8gd+ z5huA`LmM+1{a8QoxvHjlrqSd^%k=eime=Uq{${(hpNLZ3n}^kPq%YcCU%SBBZ~bak z`+aWS`7tiP-g6Lca|3uBzU=n|Vr;Wnj#r_4tAd_F<+h_xgSvym+PyEdf=K2ehHz*M4`|Cemr1y!+8T3sjY)ym$FEsWe1aTzV zS#a$g7j5zC+g0b36+}4 zLI(=dNboaM5E6TO?{%yY`d>|NAHtp)F8EK=JKT39h#7J84kig_($AgEWHr5o?1q|B ze4YPJ#H5DxgkJnR5%aRu7tnQ$!J&%KhdS*&VvQ>?`m97O!`4758y@#hBIZA1aQq=W z{_<5q z=)|C%VYe`>ELu&2F&S#2E8cKC6697a0L6x%I6h2~VuTAZh8J*=B$y6jne$cT z;wc1elyh4(ql?#scPQ{Mn%sUXy{3jD-?KzH-|G(prONz*sj*$?)x%^24D&-Qll>5p zS**VTCpK1wEUp8=f*5^ZwAKhH1OT>-)dP}L&{k(ih%FH#;5|HvfQl64<{bt@xTB-e zA|y0PE0R#>_jR-vHS{iR9he5w! zrT1&)Lu-6B@9Q!ZzAm&J+)W5dB=Zv4xhPSl>}3JEcTZd&aonkwqk)ir$0e2A^}LU z=Uonz-w-bM?S#x2xzrNtO1PwDamL9S(;GD;<6}?agS%#?Dw0s4eTyD*O^qwks+MeO zW>5h@)%2shTTnIY@8>$wUX_9*{_ZYXTdGvEyc^)excL(=ixHq*mKmS|CE~a$sOPMLj(lSb#IMvJ;OCqC_C5a(K%F@XxOAJ|N zsEln8Cu3g@k{G*?L<=f)q>XIpltzmf;kljXd9MGto;Uxu&x_~%{o;OeU)T5keZHUH z?9s6PrSu6+Pjne6jF>Bf0t|4gytJ^!YB0umc}9VCBY+P5c=omZtz%XCMW=Qwym+$Bo7U1& zyLFugezFqJQe?WABHT~$kZ0X+@mKU!S;x3pzLcux60=6T7f$|p$kJEg8w@VxI%9P= zC~i>dmKQ&`t`8Rz9%XysACb->k58cg9arS(~YOL23Y?xZ2f!#h)y$aXos35vf~i89OQbX zo|L(3%ito7MTd~N2T^hRWFiTWo!@Fj-{Hx%r3L1BokXQBVmCcl!DA2FZvRmK2_Wv^ z><)$|)^v*n>wOp~nyVDS5HCk@nZF_7p04>d`D& z^=CKHd}(8rM-MYhNvz`*hgbtK2xP1qe8pq#g7>?a)1KNGpUISn^OzN@?uL&qG-GpTVC8CZ~LKCUc9#26&jzZ$RB3#GfGT^*malSiC8y- zT+e^?h@ayauMEGv_S$>YJ%oXH9Q-dzN~oeGR68ahYT`?^*ZzJ&GY<%EAg!gG(;Q&~ ze~+0~aLg=1{`e<&RjkJ(<}kvM|8Jr2ub6p?c3op{^nb?8KK|EA;p{ zp$q2?GYGjT|E6~(W?EJ}&)>AIk$$e_VaFTznq0(hUwHXWh?nnH+nj%=?=c(!gV*7U zt7Yxzc5fD+$eloMDL4`Wt;Edf_Rhq8$XEHQC-C}O{a#s-?_lr>Z%VPl%qxvvrcIDu zFpO5fD;=#fCSa{u0k2x6aG}s}YAl6q2FJ|9_Hd!l(W`V^==>`jGdZzvq0mFlo*bg0bQ^-diEK7P44_eDJ+i8PQft~t@}&o+=55Rn;vmDe`$=mRI!tWJY=QGF*&v?o!pOsCV)Cy}V&ob-c1p zs{0|iZOG`u4f8c>o2wrnOUrLOH2Zz@=6y@wj|l^xLq3YvA+!1`U&bzw>p?07s(D-V zLZjxL_Th>~iTH$`4D#dcXgsP}?NjSut{$X>RTOQxh0-hbM<}Q}OFC*R;<+WM)EeE} ziW<8DnB)Lz;2rfRUgaf1zn3%JH>}mGZ)p~*JBf?SKEU>QZWiwT z?ws*(FUFd5pQ*ejquOlKmW(>fU9y8csrV0H2h4vN(tQeFll%6}c|{!M#BG^{#nIEV z&%KLbar9K($JrMFcei|hdG?Rf-(Q`dtk5>-pfBeW--OF7oqKZ;bFhAxr%?&VOy%kG zZ!eoH&Am-AKiDvq;ab@+p1oXAm&sKIF25^C^b46P$*Bx^Uw(Z$Tv!)@S1bn5cIxC+%}nb4VoX{WYEhT4ZEGd zoY?R)uzli5#PVYIuq&|8w7T0+JR>;eJsSQl%avIp-*#G^ts*KxOMr#yz+F(Dly_m( z2xA*B_wq)(X6VNa?y?RvEqC=tD7irm1EDP-r${H{|8An-mXx%l6V1iVzf}j_Wr>O+ zto~;1dZlXPy?7522t`q?=H&6Z9?3Xc4OvwtL$_bw>bWGAex=#F{oG^^ z^1*d=d`})Qb?#EM=u@hbLJ_@nrYn{_q7V+>u2VR}H*!p&WRDTBnYPQ8%(HHk<;`tq zo(i4wnjLfBs#~`62%zDvPl?dhkg;>TeRw50w$ur>Xzyi5iwdDv)Pb)z!Tq@Ol&Em`*Cbz z0C8CUpGAA`$Jrh}&&5YeG{e4sJ`DRe!B7| zGPhl2jD9fk!_EkToA&9nfoIWS`HH3+yMFvAffVc4r`S64khWQmW2h!7W51tbE@iRq zY=0Jg!BmGuE4_5W$e@r{MTc0s%Y2kQXj0&1&}D0>O!NXKr9 zLANi$>Ii4Y4xe)eygN32bw)W32`CN~L5RJ2f~{lUc*xx_$*n>$x&;|z^}CA4IIp_A z6u{(zUv|X;4+#WKrvHi{wLQwW1H>&mi8$|m(n;$c)#nOwhYI-HIc*Euk@VCh}S3dB_HZ_t1 zx~XZnv|lu)rjCymcg**g8BRCB;PG%ybL8UmrkFoouNv7AW*X(3JU30*T-=R#rTs;) zt!iSyH|Ty-^esZ~OI`C@Q~l|^UyFR*lX#8?=>-WYdi_^dM8NdEs`Mq`Y80qt#reTcDT!-3{ zglE(IR=IDk%Xn!m%fPPTHcx4NFQe{eJ!zRdGF9C zeb%(}ttzqQ!wH*(p%+WD^?fbV=lT|2FD!j;lWUd4+5C8`wmjEu)A~8R@5hAk@_c_{ z>(^qN#rH>-rGtH~vvqxo)1k`?!~YXU|J%gTq2t(4Xl1+)&w1_P3A_Xo!GUM5C{sFk zv<=Dw@a|;LT9625{!k9Vr5}YU1!KIiD-&xru)-(E$oVd@3JCQJ2s-?@UhmSNgK%p?FXQzpWQF0RaF`4xeRD@uKD|teKC{h}%Nx{?N zf>}(7#QP@+th%B6f*oT8NF7n4xPL{K?BXExM4(g~EC!SORnl@{H?tolJ&)eVMXY6` zbR+;x2MU#>>p>|ORg&vq98{HbY#3oNoWY*Qba8~)iI#mSwm6>Kb5G=Kxp301^LPn~jC-YG~R2kLM#DgrbT!$B0h3Q+y z38MIE*d7Q!#j+8BZhV9X4)tOl<2!}6+0BcEl}ji?O+^?ppUR-;AQ?Hgdt{DMv#D&L zt_^L>M_c!&#%bg2q2xoQi2|=A+z48)$`O`74*@Ht?D20HKejLIk?I9pi>3**%hIs% z4!A&qO)w!efZ*OQ3|6u=a02{rsR?r@Ao**4ZTTQOXSzOyX%uhnRN((E-|{c;D%^#0 zp(oDrgh+Y3tiB+IjDD??mQ;`303eich@T|CB^N+$fa%O`es^j1&S1218RW`F9phYc z!SfS<>}aS!>PT26Z%fFOSr35c-t$5O(qYR^CqMu$1FFP85z>ulM$g(`#$)NAU`!_~ z$mlPGgr$%e_8EftQ7WiuAL4Gnd6j z7Vl7iAn(sC%(!aOc1_K&JZCWNa04h7iJFb#4@lDN_h(>2u3ysz72DFq07|w^=8Ken zg^N@ZAho&4f_Map5MR5@CLH3H+QOK!>U2Konn6#F$NqTFew61h+L?;nB*hHa0^#@g z@ika2sPbMJBm&~=I9OQeRaC2T@r_)+Q0sn_`@=}=6)N^VYUo8T{61KVqu^^fSm(y1 z)Ot74ktBHpKFv^Qu$wQI$nZ-O8PXFv0p(wvP>0CE8@u^+FCuPEua#$1p?d}t3ajT;k6%B1HB@jFr02S9nH zau5KKu&yjYCC@eDM?~>YT}8T3hcUn6B*BY|pbj_SaK#dQQ*KjpatY`vfV`-dcX}LG z?XyK6BMU9);3p~1Mv|(u9}%RLj2yZ7Qks{CM!db3nL$dq-Pp42edWiH8X;CBD=+@d WQS3vAiO_1p%m2O1{GVHzjQ;^WbNtu< literal 0 HcmV?d00001 diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md new file mode 100644 index 0000000000..1a9de801a7 --- /dev/null +++ b/tutorials/rendering_plugins.md @@ -0,0 +1,138 @@ +\page rendering_plugins Rendering plugins + +This tutorial will go over how to write Ignition Gazebo plugins that alter the +3D scene's visual appearance using Ignition Rendering APIs. + +This is not to be confused with integrating a new rendering engine. See +[How to write your own rendering engine plugin](https://ignitionrobotics.org/api/rendering/4.2/renderingplugin.html) +for that. + +This tutorial will go over a couple of example plugins that are located at +https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/rendering_plugins. + +## Scenes + +During simulation, there are up to two 3D scenes being rendered by +Ignition Gazebo, one on the server process and one on the client process. + +The server-side scene will only be created when using the +`ignition::gazebo::systems::Sensors` system plugin on the server. This is the +scene that shows what the sensors see. + +The client-side scene will only be created when using the +`ignition::gazebo::Scene3D` GUI system plugin on the client. This is the +scene that shows what the user sees. + +For the user to see what the sensors see, they need to use other GUI plugins +that display sensor data, such as `ignition::gui::plugins::ImageDisplay` for +camera images or `ignition::gazebo::VisualizeLidar` for lidar point clouds. + +Ignition Gazebo keeps these scenes in sync by sending periodic state messages +from the server to the client that contain entity and component data with +the `ignition::gazebo::systems::SceneBroadcaster` plugin. Any +changes done to these scenes using Ignition Rendering APIs directly, as +described in this tutorial, will only affect one of the scenes and will not be +synchronized. The examples below will show how to change the ambient light for +each scene separately. + +## Plugin types + +Depending on the scene that you want to affect, you'll need to write a +different plugin. + +To interact with the server-side scene, you'll need to write an +`ignition::gazebo::System`. +See [Create System Plugins](createsystemplugins.html). + +To interact with the client-side scene, you'll need to write an +[ignition::gui::Plugin](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), +or a more specialized `ignition::gazebo::GuiSystem` +if you need to access entities and components. +See the [GUI system plugin example](https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/gui_system_plugin). + +## Getting the scene + +When writing either plugin type, the `ignition::rendering::Scene` pointer can +be conveniently found using the rendering engine's singleton. Both example +plugins use the exact same logic to get the scene: + +\snippet examples/plugin/rendering_plugins/RenderingServerPlugin.cc findScene + +The function above works for most cases, but you're welcome to customize it +for your use case. + +## Render thread + +Rendering operations aren't thread-safe. To make sure there are no race +conditions, all rendering operations should happen in the same thread, the +"render thread". In order to access that thread from a custom plugin, it's +necessary to listen to events that the 3D scene is emitting. These are +different for each plugin type. + +### Render events on the GUI + +The GUI plugin will need to listen to +[ignition::gui::events::Render](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) +events. Here's how to do it: + +1. Include the GUI events header: + + \snippet examples/plugin/rendering_plugins/RenderingGuiPlugin.cc includeGuiEvents + +2. The 3D scene sends render events periodically to the `ignition::gui::MainWindow`, + not directly to every plugin. Therefore, your plugin will need to install a filter + so that it receives all events coming from the `MainWindow`. In your plugin's + `LoadConfig` call, install the filter as follows: + + \snippet examples/plugin/rendering_plugins/RenderingGuiPlugin.cc connectToGuiEvent + +3. The filter will direct all of `MainWindow`'s events to the `eventFilter` callback. Add + that function to your plugin as follows. Be sure to check for the event that you want, + and end the `eventFilter` function by forwarding the event to the base class. + + \snippet examples/plugin/rendering_plugins/RenderingGuiPlugin.cc eventFilter + +4. All your rendering operations should happen right there where + `PerformRenderingOperations` is located. In this example plugin, it checks if the + `dirty` flag is set, and if it is, it changes the scene's ambient light color randomly. + + \snippet examples/plugin/rendering_plugins/RenderingGuiPlugin.cc performRenderingOperations + +### Render events on the server + +The server plugin will need to listen to `ignition::gazebo::events::PreRender` or +`ignition::gazebo::events::PostRender` events. + +Here's how to do it: + +1. Include the rendering events header: + + \snippet examples/plugin/rendering_plugins/RenderingServerPlugin.cc includeRenderingEvents + +2. To receive `PreRender` events, connect to it as follows, and the + `PerformRenderingOperations` function will be called periodically: + + \snippet examples/plugin/rendering_plugins/RenderingServerPlugin.cc connectToServerEvent + +3. All your rendering operations should happen at `PerformRenderingOperations` is located. + In this example plugin, it checks if enough time has elapsed since the last color update, + and updates the color if it's time: + + \snippet examples/plugin/rendering_plugins/RenderingServerPlugin.cc performRenderingOperations + +## Running examples + +Follow the build instructions on the rendering plugins +[README](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/plugin/rendering_plugins) +and you'll generate both plugins: + +* `RenderingGuiPlugin`: GUI plugin that updates the GUI scene's ambient light with a random color at each click. +* `RenderingServerPlugin`: Server plugin that updates the server scene's ambient light every 2 simulation seconds. + +Run the example world that uses both plugins and observe how the scene seen by +the camera sensor, displayed on the top-left camera image, is different from +the one on the GUI. Try pausing simulation and pressing the +`RANDOM GUI COLOR` button to see which scene gets updated. + +@image html files/rendering_plugins.gif + From c093937fb9a104cc6492f1558c3b158765781b40 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 19 Mar 2021 09:31:53 -0700 Subject: [PATCH 08/18] Setting the intiial velocity for a model or joint (#693) Signed-off-by: Louise Poubel --- examples/worlds/joint_controller.sdf | 1 + examples/worlds/velocity_control.sdf | 2 ++ .../joint_controller/JointController.cc | 7 +++++++ .../joint_controller/JointController.hh | 5 +++++ .../velocity_control/VelocityControl.cc | 19 +++++++++++++++++++ .../velocity_control/VelocityControl.hh | 9 +++++++++ test/integration/joint_controller_system.cc | 15 ++++++++++++--- test/worlds/joint_controller.sdf | 1 + test/worlds/velocity_control.sdf | 2 ++ 9 files changed, 58 insertions(+), 3 deletions(-) diff --git a/examples/worlds/joint_controller.sdf b/examples/worlds/joint_controller.sdf index b4db4b5cfe..86e54350a7 100644 --- a/examples/worlds/joint_controller.sdf +++ b/examples/worlds/joint_controller.sdf @@ -158,6 +158,7 @@ filename="ignition-gazebo-joint-controller-system" name="ignition::gazebo::systems::JointController"> j1 + 5.0 diff --git a/examples/worlds/velocity_control.sdf b/examples/worlds/velocity_control.sdf index 2e104e5f08..71c30486f9 100644 --- a/examples/worlds/velocity_control.sdf +++ b/examples/worlds/velocity_control.sdf @@ -485,6 +485,8 @@ + 0.3 0 0 + 0 0 -0.1 diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 695ee62d6d..a8880ec6c6 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -98,6 +98,13 @@ void JointController::Configure(const Entity &_entity, return; } + if (_sdf->HasElement("initial_velocity")) + { + this->dataPtr->jointVelCmd = _sdf->Get("initial_velocity"); + ignmsg << "Joint velocity initialized to [" + << this->dataPtr->jointVelCmd << "]" << std::endl; + } + if (_sdf->HasElement("use_force_commands") && _sdf->Get("use_force_commands")) { diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index 815a53c772..d3a1fb6587 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -42,6 +42,11 @@ namespace systems /// using force commands. If this parameter is not set or is false, the /// controller will use velocity commands internally. /// + /// `` Topic to receive commands in. Defaults to + /// `/model//joint//cmd_vel`. + /// + /// `` Velocity to start with. + /// /// ### Velocity mode: No additional parameters are required. /// /// ### Force mode: The controller accepts the next optional parameters: diff --git a/src/systems/velocity_control/VelocityControl.cc b/src/systems/velocity_control/VelocityControl.cc index 7ed361c627..2e8941cce4 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -116,6 +116,25 @@ void VelocityControl::Configure(const Entity &_entity, return; } + if (_sdf->HasElement("initial_linear")) + { + this->dataPtr->linearVelocity = _sdf->Get("initial_linear"); + msgs::Set(this->dataPtr->targetVel.mutable_linear(), + this->dataPtr->linearVelocity); + ignmsg << "Linear velocity initialized to [" + << this->dataPtr->linearVelocity << "]" << std::endl; + } + + if (_sdf->HasElement("initial_angular")) + { + this->dataPtr->angularVelocity = + _sdf->Get("initial_angular"); + msgs::Set(this->dataPtr->targetVel.mutable_angular(), + this->dataPtr->angularVelocity); + ignmsg << "Angular velocity initialized to [" + << this->dataPtr->angularVelocity << "]" << std::endl; + } + // Subscribe to model commands std::string modelTopic{ "/model/" + this->dataPtr->model.Name(_ecm) + "/cmd_vel"}; diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index 0b546525a1..08ac7cd569 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -35,6 +35,15 @@ namespace systems /// \brief Linear and angular velocity controller /// which is directly set on a model. + /// + /// ## System Parameters + /// + /// `` Topic to receive commands in. Defaults to + /// `/model//cmd_vel`. + /// + /// `` Linear velocity to start with. + /// + /// `` Linear velocity to start with. class VelocityControl : public System, public ISystemConfigure, diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index faf510ec5c..a773c404b2 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -103,12 +103,21 @@ TEST_F(JointControllerTestFixture, JointVelocityCommand) server.AddSystem(testSystem.systemPtr); - const std::size_t initIters = 10; + const std::size_t initIters = 1000; server.Run(true, initIters, false); EXPECT_EQ(initIters, angularVelocities.size()); - for (const auto &angVel : angularVelocities) + for (auto i = 0u; i < angularVelocities.size(); ++i) { - EXPECT_NEAR(0, angVel.Length(), TOL); + if (i == 0) + { + EXPECT_NEAR(0.0, angularVelocities[i].Length(), TOL) + << "Iteration [" << i << "]"; + } + else + { + EXPECT_NEAR(5.0, angularVelocities[i].Length(), TOL) + << "Iteration [" << i << "]"; + } } angularVelocities.clear(); diff --git a/test/worlds/joint_controller.sdf b/test/worlds/joint_controller.sdf index 06b9dd566b..0f3678be24 100644 --- a/test/worlds/joint_controller.sdf +++ b/test/worlds/joint_controller.sdf @@ -151,6 +151,7 @@ filename="ignition-gazebo-joint-controller-system" name="ignition::gazebo::systems::JointController"> j1 + 5.0 diff --git a/test/worlds/velocity_control.sdf b/test/worlds/velocity_control.sdf index bae5e14df4..d3659d4884 100644 --- a/test/worlds/velocity_control.sdf +++ b/test/worlds/velocity_control.sdf @@ -486,6 +486,8 @@ + 0.3 0 0 + 0 0 -0.1 From 17aa8f5bd6125c2b6426e2c22bf8970a98661431 Mon Sep 17 00:00:00 2001 From: Ammaar Solkar Date: Mon, 29 Mar 2021 23:20:09 +0530 Subject: [PATCH 09/18] Add UserCommands Plugin. (#719) Signed-off-by: Ammaar Solkar --- examples/worlds/fuel.sdf | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/examples/worlds/fuel.sdf b/examples/worlds/fuel.sdf index 9331c70837..2831408576 100644 --- a/examples/worlds/fuel.sdf +++ b/examples/worlds/fuel.sdf @@ -8,6 +8,10 @@ filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"> + + From 0f4936106a6864d028e5cbed88235ffbf1f927c2 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 5 Apr 2021 15:34:03 -0700 Subject: [PATCH 10/18] Fix component inspector shutdown crash (#724) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel Co-authored-by: Alejandro Hernández Cordero --- .../component_inspector/ComponentInspector.cc | 27 +++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 730277d1cc..2d926c4fed 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -101,6 +101,9 @@ using namespace gazebo; template<> void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Pose3d"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QList({ @@ -118,6 +121,9 @@ template<> void ignition::gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Vector3d"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QList({ @@ -131,6 +137,9 @@ void ignition::gazebo::setData(QStandardItem *_item, template<> void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) { + if (nullptr == _item) + return; + _item->setData(QString("String"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QString::fromStdString(_data), @@ -142,6 +151,9 @@ template<> void ignition::gazebo::setData(QStandardItem *_item, const std::ostringstream &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Raw"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QString::fromStdString(_data.str()), @@ -152,6 +164,9 @@ void ignition::gazebo::setData(QStandardItem *_item, template<> void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Boolean"), ComponentsModel::RoleNames().key("dataType")); _item->setData(_data, ComponentsModel::RoleNames().key("data")); @@ -161,6 +176,9 @@ void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) template<> void ignition::gazebo::setData(QStandardItem *_item, const int &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Integer"), ComponentsModel::RoleNames().key("dataType")); _item->setData(_data, ComponentsModel::RoleNames().key("data")); @@ -170,6 +188,9 @@ void ignition::gazebo::setData(QStandardItem *_item, const int &_data) template<> void ignition::gazebo::setData(QStandardItem *_item, const double &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Float"), ComponentsModel::RoleNames().key("dataType")); _item->setData(_data, ComponentsModel::RoleNames().key("data")); @@ -179,6 +200,9 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) template<> void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) { + if (nullptr == _item) + return; + _item->setData(QString("Physics"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QList({ @@ -190,6 +214,9 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) ////////////////////////////////////////////////// void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) { + if (nullptr == _item) + return; + _item->setData(QString::fromStdString(_unit), ComponentsModel::RoleNames().key("unit")); } From a83f56fdf11c1f3bccb9e06670c31a7d1a26f4b6 Mon Sep 17 00:00:00 2001 From: "G.Doisy" Date: Wed, 21 Apr 2021 09:14:37 +0200 Subject: [PATCH 11/18] [DiffDrive] add enable/disable (#772) * add enable/disable diffdrive Signed-off-by: Guillaume Doisy * remove debug Signed-off-by: Guillaume Doisy * do not subscribe to enable if topic is empty Signed-off-by: Guillaume Doisy * add test Signed-off-by: Guillaume Doisy * lint and style Signed-off-by: Guillaume Doisy * change enable type to bool and renamed to enabled Signed-off-by: Guillaume Doisy --- src/systems/diff_drive/DiffDrive.cc | 33 ++++++- test/integration/diff_drive_system.cc | 124 ++++++++++++++++++++++++++ 2 files changed, 156 insertions(+), 1 deletion(-) diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index ffd16ecb0b..11828b72a0 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -59,6 +59,10 @@ class ignition::gazebo::systems::DiffDrivePrivate /// \param[in] _msg Velocity message public: void OnCmdVel(const ignition::msgs::Twist &_msg); + /// \brief Callback for enable/disable subscription + /// \param[in] _msg Boolean message + public: void OnEnable(const ignition::msgs::Boolean &_msg); + /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation @@ -136,6 +140,9 @@ class ignition::gazebo::systems::DiffDrivePrivate /// \brief Last target velocity requested. public: msgs::Twist targetVel; + /// \brief Enable/disable state of the controller. + public: bool enabled; + /// \brief A mutex to protect the target velocity command. public: std::mutex mutex; @@ -257,6 +264,14 @@ void DiffDrive::Configure(const Entity &_entity, this->dataPtr->node.Subscribe(topic, &DiffDrivePrivate::OnCmdVel, this->dataPtr.get()); + // Subscribe to enable/disable + std::string enableTopic{"/model/" + this->dataPtr->model.Name(_ecm) + + "/enable"}; + + this->dataPtr->node.Subscribe(enableTopic, &DiffDrivePrivate::OnEnable, + this->dataPtr.get()); + this->dataPtr->enabled = true; + std::string odomTopic{"/model/" + this->dataPtr->model.Name(_ecm) + "/odometry"}; if (_sdf->HasElement("odom_topic")) @@ -521,7 +536,23 @@ void DiffDrivePrivate::UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, void DiffDrivePrivate::OnCmdVel(const msgs::Twist &_msg) { std::lock_guard lock(this->mutex); - this->targetVel = _msg; + if (this->enabled) + { + this->targetVel = _msg; + } +} + +////////////////////////////////////////////////// +void DiffDrivePrivate::OnEnable(const msgs::Boolean &_msg) +{ + std::lock_guard lock(this->mutex); + this->enabled = _msg.data(); + if (!this->enabled) + { + math::Vector3d zeroVector{0, 0, 0}; + msgs::Set(this->targetVel.mutable_linear(), zeroVector); + msgs::Set(this->targetVel.mutable_angular(), zeroVector); + } } IGNITION_ADD_PLUGIN(DiffDrive, diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 027648c0e8..d1b444ff10 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -335,6 +335,130 @@ TEST_P(DiffDriveTest, SkidPublishCmd) #endif } +///////////////////////////////////////////////// +TEST_P(DiffDriveTest, EnableDisableCmd) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/diff_drive_skid.sdf"); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + // Create a system that records the vehicle poses + test::Relay testSystem; + + std::vector poses; + testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + auto id = _ecm.EntityByComponents( + components::Model(), + components::Name("vehicle")); + EXPECT_NE(kNullEntity, id); + + auto poseComp = _ecm.Component(id); + ASSERT_NE(nullptr, poseComp); + + poses.push_back(poseComp->Data()); + }); + server.AddSystem(testSystem.systemPtr); + + // Run server and check that vehicle didn't move + server.Run(true, 1000, false); + + EXPECT_EQ(1000u, poses.size()); + + for (const auto &pose : poses) + { + EXPECT_EQ(poses[0], pose); + } + + // Publish command and check that vehicle moved + double period{1.0}; + double lastMsgTime{1.0}; + std::vector odomPoses; + std::function odomCb = + [&](const msgs::Odometry &_msg) + { + ASSERT_TRUE(_msg.has_header()); + ASSERT_TRUE(_msg.header().has_stamp()); + + double msgTime = + static_cast(_msg.header().stamp().sec()) + + static_cast(_msg.header().stamp().nsec()) * 1e-9; + + EXPECT_DOUBLE_EQ(msgTime, lastMsgTime + period); + lastMsgTime = msgTime; + + odomPoses.push_back(msgs::Convert(_msg.pose())); + }; + + transport::Node node; + auto pub = node.Advertise("/model/vehicle/cmd_vel"); + node.Subscribe("/model/vehicle/odometry", odomCb); + + msgs::Twist msg; + msgs::Set(msg.mutable_linear(), math::Vector3d(0.5, 0, 0)); + msgs::Set(msg.mutable_angular(), math::Vector3d(0.0, 0, 0.0)); + + pub.Publish(msg); + + server.Run(true, 3000, false); + + // Poses for 4s + EXPECT_EQ(4000u, poses.size()); + + // Disable controller + auto pub_enable = node.Advertise("/model/vehicle/enable"); + + msgs::Boolean msg_enable; + msg_enable.set_data(false); + + pub_enable.Publish(msg_enable); + + // Run for 2s and expect no movement + server.Run(true, 2000, false); + + EXPECT_EQ(6000u, poses.size()); + + // Re-enable controller + msg_enable.set_data(true); + + pub_enable.Publish(msg_enable); + + pub.Publish(msg); + + // Run for 2s and expect movement again + server.Run(true, 2000, false); + + EXPECT_EQ(8000u, poses.size()); + + int sleep = 0; + int maxSleep = 70; + for (; odomPoses.size() < 7 && sleep < maxSleep; ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + EXPECT_NE(maxSleep, sleep); + + // Odom for 7s + ASSERT_FALSE(odomPoses.empty()); + EXPECT_EQ(7u, odomPoses.size()); + + EXPECT_LT(poses[0].Pos().X(), poses[3999].Pos().X()); + + // Should no be moving from 5s to 6s (stopped at 3s and time to slow down) + EXPECT_NEAR(poses[4999].Pos().X(), poses[5999].Pos().X(), tol); + + // Should be moving from 6s to 8s + EXPECT_LT(poses[5999].Pos().X(), poses[7999].Pos().X()); +} + ///////////////////////////////////////////////// TEST_P(DiffDriveTest, OdomFrameId) { From c57b3c902e7a7aaf5ce68952597b86ff0034bc69 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Thu, 5 Aug 2021 23:47:04 +0200 Subject: [PATCH 12/18] Set protobuf_MODULE_COMPATIBLE before any find_package call (#957) Signed-off-by: Silvio Traversaro --- CMakeLists.txt | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4e99b0b1a9..1b8ef5601f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,6 +38,12 @@ endif() # Search for project-specific dependencies #============================================================================ +# This option is needed to use the PROTOBUF_GENERATE_CPP +# in case protobuf is found with the CMake config files +# It needs to be set before any find_package(...) call +# as protobuf could be find transitively by any dependency +set(protobuf_MODULE_COMPATIBLE TRUE) + ign_find_package(sdformat9 REQUIRED VERSION 9.3.0) set(SDF_VER ${sdformat9_VERSION_MAJOR}) From 582bc5de1a7dff4cdec2ad6e1a9f6f46b1530730 Mon Sep 17 00:00:00 2001 From: Carl Saldanha Date: Mon, 9 Aug 2021 12:01:28 -0700 Subject: [PATCH 13/18] Complaint if Joint doesn't exists before adding joint controller (#786) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: cjds Signed-off-by: root Signed-off-by: Louise Poubel Co-authored-by: Alejandro Hernández Cordero Co-authored-by: Louise Poubel --- .../joint_controller/JointController.cc | 37 +++++++++---------- test/integration/joint_controller_system.cc | 19 ++++++++++ test/worlds/joint_controller_invalid.sdf | 14 +++++++ 3 files changed, 51 insertions(+), 19 deletions(-) create mode 100644 test/worlds/joint_controller_invalid.sdf diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 7de50652d1..3f5a1cdfd1 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -47,9 +47,6 @@ class ignition::gazebo::systems::JointControllerPrivate /// \brief Joint Entity public: Entity jointEntity; - /// \brief Joint name - public: std::string jointName; - /// \brief Commanded joint velocity public: double jointVelCmd; @@ -89,15 +86,23 @@ void JointController::Configure(const Entity &_entity, } // Get params from SDF - this->dataPtr->jointName = _sdf->Get("joint_name"); - - if (this->dataPtr->jointName == "") + auto jointName = _sdf->Get("joint_name"); + if (jointName.empty()) { ignerr << "JointController found an empty jointName parameter. " << "Failed to initialize."; return; } + this->dataPtr->jointEntity = this->dataPtr->model.JointByName(_ecm, + jointName); + if (this->dataPtr->jointEntity == kNullEntity) + { + ignerr << "Joint with name[" << jointName << "] not found. " + << "The JointController may not control this joint.\n"; + return; + } + if (_sdf->HasElement("initial_velocity")) { this->dataPtr->jointVelCmd = _sdf->Get("initial_velocity"); @@ -139,11 +144,11 @@ void JointController::Configure(const Entity &_entity, // Subscribe to commands std::string topic = transport::TopicUtils::AsValidTopic("/model/" + - this->dataPtr->model.Name(_ecm) + "/joint/" + this->dataPtr->jointName + + this->dataPtr->model.Name(_ecm) + "/joint/" + jointName + "/cmd_vel"); if (topic.empty()) { - ignerr << "Failed to create topic for joint [" << this->dataPtr->jointName + ignerr << "Failed to create topic for joint [" << jointName << "]" << std::endl; return; } @@ -155,7 +160,7 @@ void JointController::Configure(const Entity &_entity, if (topic.empty()) { ignerr << "Failed to create topic [" << _sdf->Get("topic") - << "]" << " for joint [" << this->dataPtr->jointName + << "]" << " for joint [" << jointName << "]" << std::endl; return; } @@ -173,6 +178,10 @@ void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, { IGN_PROFILE("JointController::PreUpdate"); + // If the joint hasn't been identified yet, the plugin is disabled + if (this->dataPtr->jointEntity == kNullEntity) + return; + // \TODO(anyone) Support rewind if (_info.dt < std::chrono::steady_clock::duration::zero()) { @@ -181,16 +190,6 @@ void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, << "s]. System may not work properly." << std::endl; } - // If the joint hasn't been identified yet, look for it - if (this->dataPtr->jointEntity == kNullEntity) - { - this->dataPtr->jointEntity = - this->dataPtr->model.JointByName(_ecm, this->dataPtr->jointName); - } - - if (this->dataPtr->jointEntity == kNullEntity) - return; - // Nothing left to do if paused. if (_info.paused) return; diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index a773c404b2..8f280f9696 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -224,3 +224,22 @@ TEST_F(JointControllerTestFixture, JointVelocityCommandWithForce) EXPECT_NEAR(0, angularVelocity.Y(), 1e-2); EXPECT_NEAR(testAngVel, angularVelocity.Z(), 1e-2); } + +///////////////////////////////////////////////// +TEST_F(JointControllerTestFixture, InexistentJoint) +{ + using namespace std::chrono_literals; + + // Start server + ServerConfig serverConfig; + const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "joint_controller_invalid.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Run some iterations to make sure nothing explodes + server.Run(true, 100, false); +} diff --git a/test/worlds/joint_controller_invalid.sdf b/test/worlds/joint_controller_invalid.sdf new file mode 100644 index 0000000000..4621474f99 --- /dev/null +++ b/test/worlds/joint_controller_invalid.sdf @@ -0,0 +1,14 @@ + + + + + + + + invalid + + + + From 5eff5f8e282f9df54a288a67b31e2c52e6ae4a31 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Tue, 10 Aug 2021 12:25:10 -0500 Subject: [PATCH 14/18] Allow referencing links in nested models in LiftDrag (#955) This updates the LiftDrag system so that links in nested models can be referenced in the link_name parameter. This is an example of using the entitiesFromScopedName function in Util.hh Signed-off-by: Addisu Z. Taddese --- examples/worlds/lift_drag_nested.sdf | 293 ++++++++++++++++++ src/systems/lift_drag/LiftDrag.cc | 47 ++- src/systems/lift_drag/LiftDrag.hh | 6 +- test/integration/lift_drag_system.cc | 86 +++-- test/worlds/lift_drag_nested_model.sdf | 149 +++++++++ .../worlds/models/lift_drag_wing/model.config | 7 + test/worlds/models/lift_drag_wing/model.sdf | 36 +++ 7 files changed, 586 insertions(+), 38 deletions(-) create mode 100644 examples/worlds/lift_drag_nested.sdf create mode 100644 test/worlds/lift_drag_nested_model.sdf create mode 100644 test/worlds/models/lift_drag_wing/model.config create mode 100644 test/worlds/models/lift_drag_wing/model.sdf diff --git a/examples/worlds/lift_drag_nested.sdf b/examples/worlds/lift_drag_nested.sdf new file mode 100644 index 0000000000..1587410928 --- /dev/null +++ b/examples/worlds/lift_drag_nested.sdf @@ -0,0 +1,293 @@ + + + + + + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0 0 0 0 + + 0.0 0 0.5 0 0 0 + + 0.0 0.0 0.0 0.0 0.0 0.0 + + 1.8 + 0.0 + 0.0 + 1.8 + 0.0 + 1.8 + + 10.0 + + + + + 1 1 1 + + + + + + 0.1 + 0.1 + + + + + + + + 1 1 1 + + + + 0.2 0.2 0.2 1.0 + .421 0.225 0.0 1.0 + + + + + 0 0 1.25 0 0 0 + + 0.0 0.0 0 0.0 0.0 0.0 + + 0.012 + 0.0 + 0.0 + 0.012 + 0.0 + 0.0012 + + 1.0 + + + + + 0.02 0.02 0.5 + + + + + + + 0.02 0.02 0.5 + + + + 0.3 0.3 0.3 1.0 + .421 0.225 0.0 1.0 + + + + + + 0 0 1.5 0.0 0 0 + + 0.0 0.5 0 0.0 0.0 0.0 + + 0.0000465 + 0.0 + 0.0 + 0.0000006 + 0.0 + 0.0000470 + + 0.01 + + + 0.0 0.5 0 0.0 0.0 0.0 + + + 0.2 1.0 0.01 + + + + + 0.0 0.5 0 0.0 0.0 0.0 + + + 0.2 1.0 0.01 + + + + 0.5 0.2 0.2 1.0 + .421 0.225 0.0 1.0 + + + + + + + 0 0 1.5 0.0 0 3.141593 + + 0.0 0.5 0 0.0 0.0 0.0 + + 0.0000465 + 0.0 + 0.0 + 0.0000006 + 0.0 + 0.0000470 + + 0.01 + + + 0.0 0.5 0 0.0 0.0 0.0 + + + 0.2 1.0 0.01 + + + + + 0.0 0.5 0 0.0 0.0 0 + + + 0.2 1.0 0.01 + + + + 0.2 0.5 0.2 1.0 + .421 0.225 0.0 1.0 + + + + + + body + rod_1 + 0.0 0.0 0.0 0.0 0.0 0.0 + + + -1e16 + 1e16 + + 0.0 0.0 -1.0 + + 0.0001 + + + + + 1 + + + + + rod_1 + blade_1 + 0.0 0.0 0.0 0.0 0.0 0.0 + + + rod_1 + blade_2 + 0.0 0.0 0.0 0.0 0.0 0.0 + + + + + + 0.1 + 0.1 + 0.001 + 0.0 + 0.0 0.5 0 + 0.2 + 1.2041 + 1 0 0 + 0 0 1 + blade_1::link + + + 0.1 + 0.1 + 0.001 + 0.0 + 0.0 0.5 0 + 0.2 + 1.2041 + 1 0 0 + 0 0 1 + blade_2::link + + + rod_1_joint + + + + diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index a9e63d1764..841858cc55 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -33,6 +33,7 @@ #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/Inertial.hh" +#include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/JointPosition.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/Link.hh" @@ -172,33 +173,67 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, { sdf::ElementPtr elem = _sdf->GetElement("link_name"); auto linkName = elem->Get(); - this->linkEntity = this->model.LinkByName(_ecm, linkName); + auto entities = + entitiesFromScopedName(linkName, _ecm, this->model.Entity()); - if (this->linkEntity == kNullEntity) + if (entities.empty()) { ignerr << "Link with name[" << linkName << "] not found. " << "The LiftDrag will not generate forces\n"; this->validConfig = false; return; } + else if (entities.size() > 1) + { + ignwarn << "Multiple link entities with name[" << linkName << "] found. " + << "Using the first one.\n"; + } + + this->linkEntity = *entities.begin(); + if (!_ecm.EntityHasComponentType(this->linkEntity, + components::Link::typeId)) + { + this->linkEntity = kNullEntity; + ignerr << "Entity with name[" << linkName << "] is not a link\n"; + this->validConfig = false; + return; + } } else { + ignerr << "The LiftDrag system requires the 'link_name' parameter\n"; this->validConfig = false; + return; } if (_sdf->HasElement("control_joint_name")) { auto controlJointName = _sdf->Get("control_joint_name"); - this->controlJointEntity = this->model.JointByName(_ecm, controlJointName); - if (this->controlJointEntity == kNullEntity) + auto entities = + entitiesFromScopedName(controlJointName, _ecm, this->model.Entity()); + + if (entities.empty()) + { + ignerr << "Joint with name[" << controlJointName << "] not found. " + << "The LiftDrag will not generate forces\n"; + this->validConfig = false; + return; + } + else if (entities.size() > 1) { - ignerr << "Joint with name[" << controlJointName << "] does not exist.\n"; + ignwarn << "Multiple joint entities with name[" << controlJointName + << "] found. Using the first one.\n"; } - else + + this->controlJointEntity = *entities.begin(); + if (!_ecm.EntityHasComponentType(this->controlJointEntity, + components::Joint::typeId)) { + this->controlJointEntity = kNullEntity; + ignerr << "Entity with name[" << controlJointName << "] is not a joint\n"; this->validConfig = false; + return; } } diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index c03eab6f15..b79e55616d 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -38,7 +38,9 @@ namespace systems /// The following parameters are used by the system: /// /// link_name : Name of the link affected by the group of lift/drag - /// properties. + /// properties. This can be a scoped name to reference links in + /// nested models. \sa entitiesFromScopedName to learn more + /// about scoped names. /// air_density : Density of the fluid this model is suspended in. /// area : Surface area of the link. /// a0 : The initial "alpha" or initial angle of attack. a0 is also @@ -59,6 +61,8 @@ namespace systems /// coefficient curve. /// cda_stall : The ratio of coefficient of drag and alpha slope after /// stall. + /// control_joint_name: Name of joint that actuates a control surface for this + /// lifting body (Optional) class LiftDrag : public System, public ISystemConfigure, diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 72ecf28d98..4b1e3181ea 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -36,6 +37,7 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" +#include "ignition/gazebo/Util.hh" #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" @@ -45,28 +47,45 @@ using namespace ignition; using namespace gazebo; +struct VerticalForceTestParam +{ + const std::string fileName; + const std::string bladeName; +}; + +std::ostream &operator<<(std::ostream &_out, const VerticalForceTestParam &_val) +{ + _out << "[" << _val.fileName << ", " << _val.bladeName << "]"; + return _out; +} + + /// \brief Test fixture for LiftDrag system -class LiftDragTestFixture : public ::testing::Test +class VerticalForceParamFixture: + public ::testing::TestWithParam { - // Documentation inherited protected: void SetUp() override { ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); + ignition::common::setenv( + "IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + common::joinPaths(PROJECT_BINARY_PATH, "lib").c_str()); } }; ///////////////////////////////////////////////// /// Measure / verify force torques against analytical answers. -TEST_F(LiftDragTestFixture, VerifyVerticalForce) +TEST_P(VerticalForceParamFixture, VerifyVerticalForce) { using namespace std::chrono_literals; + ignition::common::setenv( + "IGN_GAZEBO_RESOURCE_PATH", + common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "models")); // Start server ServerConfig serverConfig; const auto sdfFile = - std::string(PROJECT_SOURCE_PATH) + "/test/worlds/lift_drag.sdf"; + common::joinPaths(PROJECT_SOURCE_PATH, GetParam().fileName); serverConfig.SetSdfFile(sdfFile); Server server(serverConfig); @@ -76,10 +95,20 @@ TEST_F(LiftDragTestFixture, VerifyVerticalForce) server.SetUpdatePeriod(0ns); const std::string bodyName = "body"; - const std::string bladeName = "wing_1"; + const std::string bladeName = GetParam().bladeName; const std::string jointName = "body_joint"; const double desiredVel = -0.2; + auto firstEntityFromScopedName = [](const std::string &_scopedName, + const EntityComponentManager &_ecm) -> Entity + { + auto entities = entitiesFromScopedName(_scopedName, _ecm); + if (entities.size() > 0) + return *entities.begin(); + else + return kNullEntity; + }; + test::Relay testSystem; std::vector linearVelocities; std::vector forces; @@ -88,27 +117,14 @@ TEST_F(LiftDragTestFixture, VerifyVerticalForce) { // Create velocity and acceleration components if they dont't exist. // This signals physics system to populate the component - auto bladeLink = _ecm.EntityByComponents(components::Link(), - components::Name(bladeName)); + auto bladeLink = firstEntityFromScopedName(bladeName, _ecm); - if (nullptr == _ecm.Component(bladeLink)) - { - _ecm.CreateComponent(bladeLink, components::AngularVelocity()); - } + enableComponent(_ecm, bladeLink); - auto bodyLink = _ecm.EntityByComponents(components::Link(), - components::Name(bodyName)); + auto bodyLink = firstEntityFromScopedName(bodyName, _ecm); - if (nullptr == - _ecm.Component(bodyLink)) - { - _ecm.CreateComponent(bodyLink, components::WorldLinearVelocity()); - } - if (nullptr == - _ecm.Component(bodyLink)) - { - _ecm.CreateComponent(bodyLink, components::WorldLinearAcceleration()); - } + enableComponent(_ecm, bodyLink); + enableComponent(_ecm, bodyLink); }); server.AddSystem(testSystem.systemPtr); @@ -122,8 +138,8 @@ TEST_F(LiftDragTestFixture, VerifyVerticalForce) auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); - auto bodyLink = _ecm.EntityByComponents(components::Link(), - components::Name(bodyName)); + auto bodyLink = firstEntityFromScopedName(bodyName, _ecm); + auto linVelComp = _ecm.Component(bodyLink); @@ -151,10 +167,9 @@ TEST_F(LiftDragTestFixture, VerifyVerticalForce) wrenchRecorder.OnPreUpdate([&](const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) { - auto bladeLink = _ecm.EntityByComponents(components::Link(), - components::Name(bladeName)); - auto bodyLink = _ecm.EntityByComponents(components::Link(), - components::Name(bodyName)); + auto bladeLink = firstEntityFromScopedName(bladeName, _ecm); + auto bodyLink = firstEntityFromScopedName(bodyName, _ecm); + auto linVelComp = _ecm.Component(bodyLink); auto wrenchComp = @@ -213,3 +228,12 @@ TEST_F(LiftDragTestFixture, VerifyVerticalForce) EXPECT_GT(vertForce, 0); } } + +INSTANTIATE_TEST_SUITE_P( + LiftDragTests, VerticalForceParamFixture, + ::testing::Values( + VerticalForceTestParam{ + common::joinPaths("test", "worlds", "lift_drag.sdf"), "wing_1"}, + VerticalForceTestParam{ + common::joinPaths("test", "worlds", "lift_drag_nested_model.sdf"), + "wing_1::base_link"})); diff --git a/test/worlds/lift_drag_nested_model.sdf b/test/worlds/lift_drag_nested_model.sdf new file mode 100644 index 0000000000..1838aabc7a --- /dev/null +++ b/test/worlds/lift_drag_nested_model.sdf @@ -0,0 +1,149 @@ + + + + + + + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.5 0 0 0 + + + 0.0 0 0 0.0 0.0 0.0 + + 0.465 + 0.0 + 0.0 + 0.006 + 0.0 + 0.470 + + 1.0 + + + 0.0 0 0 0.0 0.0 0.0 + + + 0.2 + + + + + 0.0 0 0 0.0 0.0 0.0 + + + 0.2 + + + + 0.5 0.2 0.2 1.0 + .421 0.225 0.0 1.0 + + + + + + + file://lift_drag_wing + wing_1 + 0 5.5 0.5 0.1 0 0 + + + + file://lift_drag_wing + wing_2 + 0 -5.5 0.5 -0.1 0 0 + + + + + world + body + 0.0 0.0 0.0 0.0 0.0 0.0 + + 1.0 0.0 0.0 + + 0.000000 + + + + + + body + wing_1::base_link + + + body + wing_2::base_link + + + + 0.1 + 4.000 + 20.0 + 0.00 + 10.0 + -0.2 + 1.0 + 0.0 + 0.0 5.0 0 + 10 + 1.2041 + -1 0 0 + 0 0 1 + wing_1::base_link + + + 0.1 + 4.000 + 20.0 + 0.00 + 10.0 + -0.2 + 1.0 + 0.0 + 0.0 -5.0 0 + 10 + 1.2041 + -1 0 0 + 0 0 1 + wing_2::base_link + + + + diff --git a/test/worlds/models/lift_drag_wing/model.config b/test/worlds/models/lift_drag_wing/model.config new file mode 100644 index 0000000000..5cb5ee1ec5 --- /dev/null +++ b/test/worlds/models/lift_drag_wing/model.config @@ -0,0 +1,7 @@ + + + lift_drag_wing + 1.0 + model.sdf + + diff --git a/test/worlds/models/lift_drag_wing/model.sdf b/test/worlds/models/lift_drag_wing/model.sdf new file mode 100644 index 0000000000..9e2d6e83c0 --- /dev/null +++ b/test/worlds/models/lift_drag_wing/model.sdf @@ -0,0 +1,36 @@ + + + + + + + 0.465 + 0.0 + 0.0 + 0.006 + 0.0 + 0.470 + + 1.0 + + + + + 1.0 10.0 0.01 + + + + + + + 1.0 10.0 0.01 + + + + 0.5 0.2 0.2 1.0 + .421 0.225 0.0 1.0 + + + + + From b7346a4ba494bd03db9196f266c334a853aae52a Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Tue, 10 Aug 2021 12:40:48 -0700 Subject: [PATCH 15/18] Drag and drop meshes into scene (#939) Signed-off-by: Jenn Nguyen Co-authored-by: Michael Carroll --- src/gui/plugins/scene3d/GzScene3D.qml | 24 ++++++++- src/gui/plugins/scene3d/Scene3D.cc | 71 ++++++++++++++++++++++++++- src/gui/plugins/scene3d/Scene3D.hh | 24 +++++++++ 3 files changed, 116 insertions(+), 3 deletions(-) diff --git a/src/gui/plugins/scene3d/GzScene3D.qml b/src/gui/plugins/scene3d/GzScene3D.qml index 1f8289465f..4411fb5d7e 100644 --- a/src/gui/plugins/scene3d/GzScene3D.qml +++ b/src/gui/plugins/scene3d/GzScene3D.qml @@ -15,7 +15,8 @@ * */ import QtQuick 2.9 -import QtQuick.Controls 2.0 +import QtQuick.Controls 2.2 +import QtQuick.Dialogs 1.0 import RenderWindow 1.0 import QtGraphicalEffects 1.0 import IgnGazebo 1.0 as IgnGazebo @@ -98,4 +99,25 @@ Rectangle { GzScene3D.OnDropped(drop.text, drag.x, drag.y) } } + + // pop error + Connections { + target: GzScene3D + onPopupError: errorPopup.open() + } + + Dialog { + id: errorPopup + parent: ApplicationWindow.overlay + modal: true + focus: true + x: (parent.width - width) / 2 + y: (parent.height - height) / 2 + title: "Error" + Text { + text: GzScene3D.errorPopupText + } + standardButtons: Dialog.Ok + } + } diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 9de8888404..09ae8c5919 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -38,6 +38,7 @@ #include #include #include +#include #include #include @@ -373,6 +374,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief View collisions service public: std::string viewCollisionsService; + + /// \brief Text for popup error message + public: QString errorPopupText; }; } } @@ -2793,7 +2797,7 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) { if (_drop.toStdString().empty()) { - ignwarn << "Dropped empty entity URI." << std::endl; + this->SetErrorPopupText("Dropped empty entity URI."); return; } @@ -2808,7 +2812,56 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) math::Vector3d pos = renderWindow->ScreenToScene({_mouseX, _mouseY}); msgs::EntityFactory req; - req.set_sdf_filename(_drop.toStdString()); + std::string dropStr = _drop.toStdString(); + if (QUrl(_drop).isLocalFile()) + { + // mesh to sdf model + common::rtrim(dropStr); + + if (!common::MeshManager::Instance()->IsValidFilename(dropStr)) + { + QString errTxt = QString::fromStdString("Invalid URI: " + dropStr + + "\nOnly Fuel URLs or mesh file types DAE, OBJ, and STL are supported."); + this->SetErrorPopupText(errTxt); + return; + } + + // Fixes whitespace + dropStr = common::replaceAll(dropStr, "%20", " "); + + std::string filename = common::basename(dropStr); + std::vector splitName = common::split(filename, "."); + + std::string sdf = "" + "" + "" + "" + "" + "" + "" + "" + dropStr + "" + "" + "" + "" + "" + "" + "" + "" + dropStr + "" + "" + "" + "" + "" + "" + ""; + + req.set_sdf(sdf); + } + else + { + // model from fuel + req.set_sdf_filename(dropStr); + } + req.set_allow_renaming(true); msgs::Set(req.mutable_pose(), math::Pose3d(pos.X(), pos.Y(), pos.Z(), 1, 0, 0, 0)); @@ -2817,6 +2870,20 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) req, cb); } +///////////////////////////////////////////////// +QString Scene3D::ErrorPopupText() const +{ + return this->dataPtr->errorPopupText; +} + +///////////////////////////////////////////////// +void Scene3D::SetErrorPopupText(const QString &_errorTxt) +{ + this->dataPtr->errorPopupText = _errorTxt; + this->ErrorPopupTextChanged(); + this->popupError(); +} + ///////////////////////////////////////////////// void Scene3D::OnFocusWindow() { diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 97289bd412..89a5dbef26 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -80,6 +80,14 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { { Q_OBJECT + /// \brief Text for popup error + Q_PROPERTY( + QString errorPopupText + READ ErrorPopupText + WRITE SetErrorPopupText + NOTIFY ErrorPopupTextChanged + ) + /// \brief Constructor public: Scene3D(); @@ -161,6 +169,22 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { private: bool OnViewCollisions(const msgs::StringMsg &_msg, msgs::Boolean &_res); + /// \brief Get the text for the popup error message + /// \return The error text + public: Q_INVOKABLE QString ErrorPopupText() const; + + /// \brief Set the text for the popup error message + /// \param[in] _errorTxt The error text + public: Q_INVOKABLE void SetErrorPopupText(const QString &_errorTxt); + + /// \brief Notify the popup error text has changed + signals: void ErrorPopupTextChanged(); + + /// \brief Notify that an error has occurred (opens popup) + /// Note that the function name needs to start with lowercase in order for + /// the connection to work on the QML side + signals: void popupError(); + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; From 0f586706bca88ac88d92ff308e0aded912c3317f Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 10 Aug 2021 17:11:34 -0700 Subject: [PATCH 16/18] Be more specific when looking for physics plugins (#965) Signed-off-by: Louise Poubel --- src/systems/physics/Physics.cc | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 72ccc67339..6e675264b2 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -498,10 +498,13 @@ void Physics::Configure(const Entity &_entity, return; } - auto classNames = pluginLoader.AllPlugins(); + auto classNames = pluginLoader.PluginsImplementing< + physics::ForwardStep::Implementation< + physics::FeaturePolicy3d>>(); if (classNames.empty()) { - ignerr << "No plugins found in library [" << pathToLib << "]." << std::endl; + ignerr << "No physics plugins found in library [" << pathToLib << "]." + << std::endl; return; } @@ -511,7 +514,11 @@ void Physics::Configure(const Entity &_entity, auto plugin = pluginLoader.Instantiate(className); if (!plugin) + { + ignwarn << "Failed to instantiate [" << className << "] from [" + << pathToLib << "]" << std::endl; continue; + } this->dataPtr->engine = ignition::physics::RequestEngine< ignition::physics::FeaturePolicy3d, From e95f17cb784ee42d45a0fd9c8438cb5c8bd1c6e0 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 11 Aug 2021 07:30:14 -0700 Subject: [PATCH 17/18] 3 -> 4 fixes (#964) Signed-off-by: Louise Poubel --- examples/plugin/rendering_plugins/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/plugin/rendering_plugins/CMakeLists.txt b/examples/plugin/rendering_plugins/CMakeLists.txt index 5010daf7f1..b6a2365e22 100644 --- a/examples/plugin/rendering_plugins/CMakeLists.txt +++ b/examples/plugin/rendering_plugins/CMakeLists.txt @@ -32,7 +32,7 @@ target_link_libraries(${GUI_PLUGIN} set(SERVER_PLUGIN RenderingServerPlugin) find_package(ignition-plugin1 REQUIRED COMPONENTS register) -find_package(ignition-gazebo3 REQUIRED) +find_package(ignition-gazebo4 REQUIRED) add_library(${SERVER_PLUGIN} SHARED ${SERVER_PLUGIN}.cc) set_property(TARGET ${SERVER_PLUGIN} PROPERTY CXX_STANDARD 17) From fbe137e5dd957a9ac1e78e6ff1c524484025553f Mon Sep 17 00:00:00 2001 From: Luca Della Vedova Date: Wed, 11 Aug 2021 22:06:36 -0700 Subject: [PATCH 18/18] Fix crash in the follow_actor example (#958) Signed-off-by: Luca Della Vedova Signed-off-by: Ian Chen Co-authored-by: Ian Chen --- src/rendering/RenderUtil.cc | 26 +++++++++++----- test/integration/follow_actor_system.cc | 3 +- test/worlds/follow_actor.sdf | 40 +++++++++++++++++++++++++ 3 files changed, 60 insertions(+), 9 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index eff16149ea..7af78219a5 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -356,9 +356,14 @@ class ignition::gazebo::RenderUtilPrivate /// RenderUtil::Update. /// \param[in] _actorAnimationData A map of entities to their animation update /// data. + /// \param[in] _entityPoses A map of entity ids and pose updates. + /// \param[in] _trajectoryPoses A map of entity ids and trajectory + /// pose updates. /// \sa actorManualSkeletonUpdate public: void UpdateAnimation(const std::unordered_map &_actorAnimationData); + AnimationUpdateData> &_actorAnimationData, + const std::unordered_map &_entityPoses, + const std::unordered_map &_trajectoryPoses); }; ////////////////////////////////////////////////// @@ -804,7 +809,8 @@ void RenderUtil::Update() } else { - this->dataPtr->UpdateAnimation(actorAnimationData); + this->dataPtr->UpdateAnimation(actorAnimationData, entityPoses, + trajectoryPoses); } } @@ -2028,8 +2034,10 @@ void RenderUtilPrivate::UpdateThermalCamera(const std::unordered_map &_actorAnimationData) +void RenderUtilPrivate::UpdateAnimation(const std::unordered_map &_actorAnimationData, + const std::unordered_map &_entityPoses, + const std::unordered_map &_trajectoryPoses) { for (auto &it : _actorAnimationData) { @@ -2098,16 +2106,18 @@ void RenderUtilPrivate::UpdateAnimation( // update actor trajectory animation math::Pose3d globalPose; - if (entityPoses.find(it.first) != entityPoses.end()) + auto entityPosesIt = _entityPoses.find(it.first); + if (entityPosesIt != _entityPoses.end()) { - globalPose = entityPoses[it.first]; + globalPose = entityPosesIt->second; } math::Pose3d trajPose; // Trajectory from the ECS - if (trajectoryPoses.find(it.first) != trajectoryPoses.end()) + auto trajectoryPosesIt = _trajectoryPoses.find(it.first); + if (trajectoryPosesIt != _trajectoryPoses.end()) { - trajPose = trajectoryPoses[it.first]; + trajPose = trajectoryPosesIt->second; } else { diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index 654e578c85..566384f1bf 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -18,6 +18,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Actor.hh" #include "ignition/gazebo/components/Name.hh" @@ -88,7 +89,7 @@ class Relay ///////////////////////////////////////////////// -TEST_P(FollowActorTest, PublishCmd) +TEST_P(FollowActorTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PublishCmd)) { // Start server ServerConfig serverConfig; diff --git a/test/worlds/follow_actor.sdf b/test/worlds/follow_actor.sdf index 1bc7015a70..a02a444fc6 100644 --- a/test/worlds/follow_actor.sdf +++ b/test/worlds/follow_actor.sdf @@ -1,6 +1,46 @@ + + + + ogre2 + + + true + 0 0 0 0 0 0 + + + + + 0.1 0.1 0.1 + + + + + 1 0 1.3 0 0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + camera + + + + true 1 -2 0.5 0 0 0