From 4a9aca88aa8401274eb576661d7442afe2fccfba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 23 Dec 2020 22:18:13 +0100 Subject: [PATCH 01/55] New ParticleEmitter component. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- .../gazebo/components/ParticleEmitter.hh | 186 ++++++++++++++++++ test/integration/components.cc | 59 ++++++ 2 files changed, 245 insertions(+) create mode 100644 include/ignition/gazebo/components/ParticleEmitter.hh diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh new file mode 100644 index 0000000000..00430439ef --- /dev/null +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -0,0 +1,186 @@ +/* + * Copyright (C) 2020 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_COMPONENTS_PARTICLEEMITTER_HH_ +#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace particles +{ + /// \brief All possible emitter type. + enum class EmitterType {POINT, BOX, CYLINDER, ELLIPSOID}; + + /// \brief Properties of a particle emitter. + /// A particle emitter also has: + /// * a pose, which can be stored as a component of + /// an emitter entity via ignition::gazebo::components::Pose + /// * a material, which can be stored as a component of + /// an emitter entity via ignition::gazebo::components::Material + struct Emitter + { + /// \brief The particle emitter's id. + unsigned int id; + + /// \brief The emitter's name. + std::string name; + + /// \brief The emitter's type. + particles::EmitterType type; + + /// The size of the emitter where the particles are sampled. + ignition::math::Vector3d size; + + /// \brief How many particles per second should be emitted. + double rate; + + /// \brief The number of seconds the emitter is active. + double duration; + + /// \brief Whether particle emitter is enabled or not. + bool emitting; + + /// \brief The particle dimensions (width, height, depth). + ignition::math::Vector3d particleSize; + + /// \brief The number of seconds each particle will ’live’ for before + /// being destroyed. + double lifetime; + + /// \brief The minimum velocity each particle is emitted (m/s). + double minVelocity; + + /// \brief The maximum velocity each particle is emitted (m/s). + double maxVelocity; + + /// \brief The starting color of the particles. + ignition::math::Color colorStart; + + /// \brief The end color of the particles. + ignition::math::Color colorEnd; + + /// \brief The amount by which to scale the particles in both x and y + /// direction per second. + double scaleRate; + + /// \brief The path to the color image used as an affector. + std::string colorRangeImage; + + public: bool operator==(const Emitter &_emitter) const + { + return this->id == _emitter.id; + } + + public: bool operator!=(const Emitter &_emitter) const + { + return !(*this == _emitter); + } + }; +} + +namespace serializers +{ + /// \brief Output stream overload for particles::EmitterType + inline std::ostream &operator<<(std::ostream &_out, + const particles::EmitterType &_type) + { + auto temp = static_cast(_type); + _out << temp; + return _out; + } + + /// \brief Input stream overload for particles::EmitterType + inline std::istream &operator>>(std::istream &_in, + particles::EmitterType &_type) + { + unsigned int temp = 0u; + if (_in >> temp) + _type = static_cast(temp); + return _in; + } + + /// \brief Serializer for components::ParticleEmitter object + class ParticleEmitterSerializer + { + /// \brief Serialization for particles::Emitter + /// \param[out] _out Output stream + /// \param[in] _emitter Object for the stream + /// \return The stream + public: static std::ostream &Serialize(std::ostream &_out, + const particles::Emitter &_emitter) + { + _out << _emitter.id << " " << _emitter.name << " " << _emitter.type + << " " << _emitter.size << " " << _emitter.rate + << " " << _emitter.duration << " " << _emitter.emitting + << " " << _emitter.particleSize << " " << _emitter.lifetime + << " " << _emitter.minVelocity << " " << _emitter.maxVelocity + << " " << _emitter.colorStart << " " << _emitter.colorEnd + << " " << _emitter.scaleRate << " " << _emitter.colorRangeImage; + return _out; + } + + /// \brief Deserialization for particles::Emitter + /// \param[in] _in Input stream + /// \param[out] _emitter The object to populate + /// \return The stream + public: static std::istream &Deserialize(std::istream &_in, + particles::Emitter &_emitter) + { + _in >> _emitter.id >> _emitter.name >> _emitter.type + >> _emitter.size >> _emitter.rate >> _emitter.duration + >> _emitter.emitting >> _emitter.particleSize >> _emitter.lifetime + >> _emitter.minVelocity >> _emitter.maxVelocity >> _emitter.colorStart + >> _emitter.colorEnd >> _emitter.scaleRate + >> _emitter.colorRangeImage; + return _in; + } + }; +} + +// using separate namespace blocks so all components appear in Doxygen +// (appears as if Doxygen can't parse multiple components in a single +// namespace block since IGN_GAZEBO_REGISTER_COMPONENT doesn't have a +// trailing semicolon) +namespace components +{ + /// \brief A component that contains a particle emitter, which is + /// represented by particles::Emitter + using ParticleEmitter = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", + ParticleEmitter) +} +} +} +} + +#endif diff --git a/test/integration/components.cc b/test/integration/components.cc index 00649aa031..69a806ff88 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -59,6 +59,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/components/ParentLinkName.hh" +#include "ignition/gazebo/components/ParticleEmitter.hh" #include "ignition/gazebo/components/Performer.hh" #include "ignition/gazebo/components/PerformerAffinity.hh" #include "ignition/gazebo/components/PerformerLevels.hh" @@ -1357,3 +1358,61 @@ TEST_F(ComponentsTest, Scene) EXPECT_FALSE(comp3.Data().Grid()); EXPECT_TRUE(comp3.Data().OriginVisual()); } + +////////////////////////////////////////////////// +TEST_F(ComponentsTest, ParticleEmitter) +{ + particles::Emitter emitter1; + emitter1.id = 0; + emitter1.name = "emitter_1"; + emitter1.type = particles::EmitterType::BOX; + emitter1.size = ignition::math::Vector3d(1, 2, 3); + emitter1.rate = 4.0; + emitter1.duration = 5.0; + emitter1.emitting = false; + emitter1.particleSize = ignition::math::Vector3d(0.1, 0.2, 0.3); + emitter1.lifetime = 6.0; + emitter1.minVelocity = 7.0; + emitter1.maxVelocity = 8.0; + emitter1.colorStart = ignition::math::Color::Red; + emitter1.colorEnd = ignition::math::Color::White; + emitter1.scaleRate = 9.0; + emitter1.colorRangeImage = "path_to_texture"; + + particles::Emitter emitter2; + emitter2.id = 1; + emitter2.name = emitter1.name; + emitter2.type = emitter1.type; + emitter2.size = emitter1.size; + emitter2.rate = emitter1.rate; + emitter2.duration = emitter1.duration; + emitter2.emitting = emitter1.emitting; + emitter2.particleSize = emitter1.particleSize; + emitter2.lifetime = emitter1.lifetime; + emitter2.minVelocity = emitter1.minVelocity; + emitter2.maxVelocity = emitter1.maxVelocity; + emitter2.colorStart = emitter1.colorStart; + emitter2.colorEnd = emitter1.colorEnd; + emitter2.scaleRate = emitter1.scaleRate; + emitter2.colorRangeImage = emitter1.colorRangeImage; + + // Create components. + auto comp1 = components::ParticleEmitter(emitter1); + auto comp2 = components::ParticleEmitter(emitter2); + + // Equality operators. + EXPECT_NE(comp1, comp2); + EXPECT_FALSE(comp1 == comp2); + EXPECT_TRUE(comp1 != comp2); + + // Stream operators. + std::ostringstream ostr; + comp1.Serialize(ostr); + EXPECT_EQ("0 emitter_1 1 1 2 3 4 5 0 0.1 0.2 0.3 6 7 8 1 0 0 1 1 1 1 1 9 " + "path_to_texture", ostr.str()); + + std::istringstream istr(ostr.str()); + components::ParticleEmitter comp3; + comp3.Deserialize(istr); + EXPECT_EQ(comp1, comp3); +} From 272d39b6ce21afcdf2d0b9367c58ae20f619a1ec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 23 Dec 2020 22:25:55 +0100 Subject: [PATCH 02/55] Remove attribute name. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- .../gazebo/components/ParticleEmitter.hh | 30 +++++++++---------- test/integration/components.cc | 4 +-- 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index 00430439ef..d092911e83 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -43,6 +43,8 @@ namespace particles /// A particle emitter also has: /// * a pose, which can be stored as a component of /// an emitter entity via ignition::gazebo::components::Pose + /// * a name, which can be stored as a component of + /// an emitter entity via ignition::gazebo::components::Name /// * a material, which can be stored as a component of /// an emitter entity via ignition::gazebo::components::Material struct Emitter @@ -50,9 +52,6 @@ namespace particles /// \brief The particle emitter's id. unsigned int id; - /// \brief The emitter's name. - std::string name; - /// \brief The emitter's type. particles::EmitterType type; @@ -137,13 +136,13 @@ namespace serializers public: static std::ostream &Serialize(std::ostream &_out, const particles::Emitter &_emitter) { - _out << _emitter.id << " " << _emitter.name << " " << _emitter.type - << " " << _emitter.size << " " << _emitter.rate - << " " << _emitter.duration << " " << _emitter.emitting + _out << _emitter.id << " " << _emitter.type + << " " << _emitter.size << " " << _emitter.rate + << " " << _emitter.duration << " " << _emitter.emitting << " " << _emitter.particleSize << " " << _emitter.lifetime - << " " << _emitter.minVelocity << " " << _emitter.maxVelocity - << " " << _emitter.colorStart << " " << _emitter.colorEnd - << " " << _emitter.scaleRate << " " << _emitter.colorRangeImage; + << " " << _emitter.minVelocity << " " << _emitter.maxVelocity + << " " << _emitter.colorStart << " " << _emitter.colorEnd + << " " << _emitter.scaleRate << " " << _emitter.colorRangeImage; return _out; } @@ -154,12 +153,13 @@ namespace serializers public: static std::istream &Deserialize(std::istream &_in, particles::Emitter &_emitter) { - _in >> _emitter.id >> _emitter.name >> _emitter.type - >> _emitter.size >> _emitter.rate >> _emitter.duration - >> _emitter.emitting >> _emitter.particleSize >> _emitter.lifetime - >> _emitter.minVelocity >> _emitter.maxVelocity >> _emitter.colorStart - >> _emitter.colorEnd >> _emitter.scaleRate - >> _emitter.colorRangeImage; + _in >> _emitter.id >> _emitter.type + >> _emitter.size >> _emitter.rate + >> _emitter.duration >> _emitter.emitting + >> _emitter.particleSize >> _emitter.lifetime + >> _emitter.minVelocity >> _emitter.maxVelocity + >> _emitter.colorStart >> _emitter.colorEnd + >> _emitter.scaleRate >> _emitter.colorRangeImage; return _in; } }; diff --git a/test/integration/components.cc b/test/integration/components.cc index 69a806ff88..d27200c558 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -1364,7 +1364,6 @@ TEST_F(ComponentsTest, ParticleEmitter) { particles::Emitter emitter1; emitter1.id = 0; - emitter1.name = "emitter_1"; emitter1.type = particles::EmitterType::BOX; emitter1.size = ignition::math::Vector3d(1, 2, 3); emitter1.rate = 4.0; @@ -1381,7 +1380,6 @@ TEST_F(ComponentsTest, ParticleEmitter) particles::Emitter emitter2; emitter2.id = 1; - emitter2.name = emitter1.name; emitter2.type = emitter1.type; emitter2.size = emitter1.size; emitter2.rate = emitter1.rate; @@ -1408,7 +1406,7 @@ TEST_F(ComponentsTest, ParticleEmitter) // Stream operators. std::ostringstream ostr; comp1.Serialize(ostr); - EXPECT_EQ("0 emitter_1 1 1 2 3 4 5 0 0.1 0.2 0.3 6 7 8 1 0 0 1 1 1 1 1 9 " + EXPECT_EQ("0 1 1 2 3 4 5 0 0.1 0.2 0.3 6 7 8 1 0 0 1 1 1 1 1 9 " "path_to_texture", ostr.str()); std::istringstream istr(ostr.str()); From 698bb1eb05276075fd0ed36bf0af68b4cfda1f7c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 7 Jan 2021 17:37:55 +0100 Subject: [PATCH 03/55] Update particle emitter component to use ignition::msgs::ParticleEmitter. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- .../gazebo/components/ParticleEmitter.hh | 122 ++++-------------- test/integration/components.cc | 82 +++++++----- 2 files changed, 80 insertions(+), 124 deletions(-) diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index d092911e83..6385171838 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * 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. @@ -17,13 +17,11 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ -#include +#include + #include #include -#include -#include -#include #include #include #include @@ -36,96 +34,34 @@ namespace gazebo inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace particles { - /// \brief All possible emitter type. - enum class EmitterType {POINT, BOX, CYLINDER, ELLIPSOID}; - /// \brief Properties of a particle emitter. - /// A particle emitter also has: - /// * a pose, which can be stored as a component of - /// an emitter entity via ignition::gazebo::components::Pose - /// * a name, which can be stored as a component of - /// an emitter entity via ignition::gazebo::components::Name - /// * a material, which can be stored as a component of - /// an emitter entity via ignition::gazebo::components::Material - struct Emitter + class Emitter { - /// \brief The particle emitter's id. - unsigned int id; - - /// \brief The emitter's type. - particles::EmitterType type; - - /// The size of the emitter where the particles are sampled. - ignition::math::Vector3d size; - - /// \brief How many particles per second should be emitted. - double rate; - - /// \brief The number of seconds the emitter is active. - double duration; - - /// \brief Whether particle emitter is enabled or not. - bool emitting; - - /// \brief The particle dimensions (width, height, depth). - ignition::math::Vector3d particleSize; - - /// \brief The number of seconds each particle will ’live’ for before - /// being destroyed. - double lifetime; - - /// \brief The minimum velocity each particle is emitted (m/s). - double minVelocity; - - /// \brief The maximum velocity each particle is emitted (m/s). - double maxVelocity; - - /// \brief The starting color of the particles. - ignition::math::Color colorStart; - - /// \brief The end color of the particles. - ignition::math::Color colorEnd; - - /// \brief The amount by which to scale the particles in both x and y - /// direction per second. - double scaleRate; - - /// \brief The path to the color image used as an affector. - std::string colorRangeImage; - + /// \brief Equality operator. This function checks if the given + /// emitter has identical id than this object. + /// \param[in] _emitter The emitter to compare against. + /// \return True if this object matches the provided object. public: bool operator==(const Emitter &_emitter) const { - return this->id == _emitter.id; + return this->data.id() == _emitter.data.id(); } + /// \brief Inequality operator. This function checks if the given + /// emitter has identical id than this object. + /// \param[in] _emitter The emitter to compare against. + /// \return True if this object doesn't match the provided object. public: bool operator!=(const Emitter &_emitter) const { return !(*this == _emitter); } + + /// \brief The particle emitter internal data. + public: ignition::msgs::ParticleEmitter data; }; } namespace serializers { - /// \brief Output stream overload for particles::EmitterType - inline std::ostream &operator<<(std::ostream &_out, - const particles::EmitterType &_type) - { - auto temp = static_cast(_type); - _out << temp; - return _out; - } - - /// \brief Input stream overload for particles::EmitterType - inline std::istream &operator>>(std::istream &_in, - particles::EmitterType &_type) - { - unsigned int temp = 0u; - if (_in >> temp) - _type = static_cast(temp); - return _in; - } - /// \brief Serializer for components::ParticleEmitter object class ParticleEmitterSerializer { @@ -136,13 +72,12 @@ namespace serializers public: static std::ostream &Serialize(std::ostream &_out, const particles::Emitter &_emitter) { - _out << _emitter.id << " " << _emitter.type - << " " << _emitter.size << " " << _emitter.rate - << " " << _emitter.duration << " " << _emitter.emitting - << " " << _emitter.particleSize << " " << _emitter.lifetime - << " " << _emitter.minVelocity << " " << _emitter.maxVelocity - << " " << _emitter.colorStart << " " << _emitter.colorEnd - << " " << _emitter.scaleRate << " " << _emitter.colorRangeImage; + if (!_emitter.data.SerializeToOstream(&_out)) + { + ignerr << "Error serializing particle emitter: " << std::endl; + ignerr << _emitter.data.DebugString() << std::endl; + } + return _out; } @@ -153,13 +88,12 @@ namespace serializers public: static std::istream &Deserialize(std::istream &_in, particles::Emitter &_emitter) { - _in >> _emitter.id >> _emitter.type - >> _emitter.size >> _emitter.rate - >> _emitter.duration >> _emitter.emitting - >> _emitter.particleSize >> _emitter.lifetime - >> _emitter.minVelocity >> _emitter.maxVelocity - >> _emitter.colorStart >> _emitter.colorEnd - >> _emitter.scaleRate >> _emitter.colorRangeImage; + if (!_emitter.data.ParseFromIstream(&_in)) + { + ignerr << "Error deserializing particle emitter: " << std::endl; + ignerr << _emitter.data.DebugString() << std::endl; + } + return _in; } }; diff --git a/test/integration/components.cc b/test/integration/components.cc index d27200c558..45d662128d 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -17,6 +17,8 @@ #include +#include + #include #include #include @@ -1363,36 +1365,58 @@ TEST_F(ComponentsTest, Scene) TEST_F(ComponentsTest, ParticleEmitter) { particles::Emitter emitter1; - emitter1.id = 0; - emitter1.type = particles::EmitterType::BOX; - emitter1.size = ignition::math::Vector3d(1, 2, 3); - emitter1.rate = 4.0; - emitter1.duration = 5.0; - emitter1.emitting = false; - emitter1.particleSize = ignition::math::Vector3d(0.1, 0.2, 0.3); - emitter1.lifetime = 6.0; - emitter1.minVelocity = 7.0; - emitter1.maxVelocity = 8.0; - emitter1.colorStart = ignition::math::Color::Red; - emitter1.colorEnd = ignition::math::Color::White; - emitter1.scaleRate = 9.0; - emitter1.colorRangeImage = "path_to_texture"; + emitter1.data.set_name("emitter1"); + emitter1.data.set_id(0); + emitter1.data.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); + emitter1.data.mutable_size()->set_x(1); + emitter1.data.mutable_size()->set_y(2); + emitter1.data.mutable_size()->set_z(3); + emitter1.data.set_rate(4.0); + emitter1.data.set_duration(5.0); + emitter1.data.set_emitting(false); + emitter1.data.mutable_particle_size()->set_x(0.1); + emitter1.data.mutable_particle_size()->set_y(0.2); + emitter1.data.mutable_particle_size()->set_z(0.3); + emitter1.data.set_lifetime(6.0); + emitter1.data.set_min_velocity(7.0); + emitter1.data.set_max_velocity(8.0); + emitter1.data.mutable_color_start()->set_r(1.0); + emitter1.data.mutable_color_start()->set_g(0); + emitter1.data.mutable_color_start()->set_b(0); + emitter1.data.mutable_color_start()->set_a(0); + emitter1.data.mutable_color_end()->set_r(1.0); + emitter1.data.mutable_color_end()->set_g(1.0); + emitter1.data.mutable_color_end()->set_b(1.0); + emitter1.data.mutable_color_end()->set_a(0); + emitter1.data.set_scale_rate(9.0); + emitter1.data.set_color_range_image("path_to_texture"); particles::Emitter emitter2; - emitter2.id = 1; - emitter2.type = emitter1.type; - emitter2.size = emitter1.size; - emitter2.rate = emitter1.rate; - emitter2.duration = emitter1.duration; - emitter2.emitting = emitter1.emitting; - emitter2.particleSize = emitter1.particleSize; - emitter2.lifetime = emitter1.lifetime; - emitter2.minVelocity = emitter1.minVelocity; - emitter2.maxVelocity = emitter1.maxVelocity; - emitter2.colorStart = emitter1.colorStart; - emitter2.colorEnd = emitter1.colorEnd; - emitter2.scaleRate = emitter1.scaleRate; - emitter2.colorRangeImage = emitter1.colorRangeImage; + emitter2.data.set_name("emitter2"); + emitter2.data.set_id(1); + emitter2.data.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); + emitter2.data.mutable_size()->set_x(1); + emitter2.data.mutable_size()->set_y(2); + emitter2.data.mutable_size()->set_z(3); + emitter2.data.set_rate(4.0); + emitter2.data.set_duration(5.0); + emitter2.data.set_emitting(false); + emitter2.data.mutable_particle_size()->set_x(0.1); + emitter2.data.mutable_particle_size()->set_y(0.2); + emitter2.data.mutable_particle_size()->set_z(0.3); + emitter2.data.set_lifetime(6.0); + emitter2.data.set_min_velocity(7.0); + emitter2.data.set_max_velocity(8.0); + emitter2.data.mutable_color_start()->set_r(1.0); + emitter2.data.mutable_color_start()->set_g(0); + emitter2.data.mutable_color_start()->set_b(0); + emitter2.data.mutable_color_start()->set_a(0); + emitter2.data.mutable_color_end()->set_r(1.0); + emitter2.data.mutable_color_end()->set_g(1.0); + emitter2.data.mutable_color_end()->set_b(1.0); + emitter2.data.mutable_color_end()->set_a(0); + emitter2.data.set_scale_rate(9.0); + emitter2.data.set_color_range_image("path_to_texture"); // Create components. auto comp1 = components::ParticleEmitter(emitter1); @@ -1406,8 +1430,6 @@ TEST_F(ComponentsTest, ParticleEmitter) // Stream operators. std::ostringstream ostr; comp1.Serialize(ostr); - EXPECT_EQ("0 1 1 2 3 4 5 0 0.1 0.2 0.3 6 7 8 1 0 0 1 1 1 1 1 9 " - "path_to_texture", ostr.str()); std::istringstream istr(ostr.str()); components::ParticleEmitter comp3; From 6b6f76f52a2cdc1b6cc50b037e40c8a15a84404e Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 8 Jan 2021 08:28:23 -0600 Subject: [PATCH 04/55] Automatically load a subset of world plugins (#281) Feature to allow loading of a default set of system plugins from a file. This behavior will trigger when a world sdf file is loaded with no plugins defined. In this case, the simulator will load the plugins from a series of locations including environment variable, the users home folder, and finally in the installation directory. This should allow users to not have to specify the same set of plugins in every world sdf file. Signed-off-by: Michael Carroll Co-authored-by: Louise Poubel --- examples/worlds/default.sdf | 12 - examples/worlds/shapes.sdf | 17 - include/ignition/gazebo/CMakeLists.txt | 2 + include/ignition/gazebo/ServerConfig.hh | 57 +++ include/ignition/gazebo/Util.hh | 3 + include/ignition/gazebo/config.hh.in | 1 + .../ignition/gazebo/playback_server.config | 14 + include/ignition/gazebo/server.config | 19 + src/CMakeLists.txt | 1 + src/Server.cc | 45 +-- src/ServerConfig.cc | 335 +++++++++++++++++- src/ServerConfig_TEST.cc | 230 ++++++++++++ src/ServerPrivate.cc | 310 +++++++--------- src/Server_TEST.cc | 10 +- src/SimulationRunner.cc | 153 +++++--- src/SimulationRunner.hh | 20 ++ src/SimulationRunner_TEST.cc | 187 ++++++++-- src/cmd/cmdgazebo.rb.in | 1 + src/systems/log/LogRecord.cc | 39 +- test/worlds/plugins_empty.sdf | 13 + test/worlds/server_invalid.config | 13 + test/worlds/server_valid.config | 28 ++ test/worlds/server_valid2.config | 21 ++ test/worlds/shapes.sdf | 12 - tutorials.md.in | 1 + tutorials/files/server_config/camera_env.gif | Bin 0 -> 267416 bytes .../files/server_config/camera_no_env.gif | Bin 0 -> 214013 bytes .../files/server_config/default_server.gif | Bin 0 -> 134365 bytes tutorials/files/server_config/from_sdf.png | Bin 0 -> 50007 bytes .../server_config/from_sdf_no_plugins.gif | Bin 0 -> 78768 bytes .../server_config/modified_default_config.gif | Bin 0 -> 145290 bytes tutorials/server_config.md | 265 ++++++++++++++ 32 files changed, 1462 insertions(+), 347 deletions(-) create mode 100644 include/ignition/gazebo/playback_server.config create mode 100644 include/ignition/gazebo/server.config create mode 100644 src/ServerConfig_TEST.cc create mode 100644 test/worlds/plugins_empty.sdf create mode 100644 test/worlds/server_invalid.config create mode 100644 test/worlds/server_valid.config create mode 100644 test/worlds/server_valid2.config create mode 100644 tutorials/files/server_config/camera_env.gif create mode 100644 tutorials/files/server_config/camera_no_env.gif create mode 100644 tutorials/files/server_config/default_server.gif create mode 100644 tutorials/files/server_config/from_sdf.png create mode 100644 tutorials/files/server_config/from_sdf_no_plugins.gif create mode 100644 tutorials/files/server_config/modified_default_config.gif create mode 100644 tutorials/server_config.md diff --git a/examples/worlds/default.sdf b/examples/worlds/default.sdf index 934f985c81..f359666e1f 100644 --- a/examples/worlds/default.sdf +++ b/examples/worlds/default.sdf @@ -17,18 +17,6 @@ 0.001 1.0 - - - - - - true diff --git a/examples/worlds/shapes.sdf b/examples/worlds/shapes.sdf index 4715d18c7d..5dec565b81 100644 --- a/examples/worlds/shapes.sdf +++ b/examples/worlds/shapes.sdf @@ -8,23 +8,6 @@ Try moving a model: --> - - 0.001 - 1.0 - - - - - - - - 1.0 1.0 1.0 0.8 0.8 0.8 diff --git a/include/ignition/gazebo/CMakeLists.txt b/include/ignition/gazebo/CMakeLists.txt index f6a29455ec..65544b91eb 100644 --- a/include/ignition/gazebo/CMakeLists.txt +++ b/include/ignition/gazebo/CMakeLists.txt @@ -1,3 +1,5 @@ ign_install_all_headers() add_subdirectory(components) + +install (FILES server.config playback_server.config DESTINATION ${IGN_DATA_INSTALL_DIR}) diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index 6a1de2c4dd..abb0283cde 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -351,6 +351,24 @@ namespace ignition /// \param[in] _info Information about the plugin to load. public: void AddPlugin(const PluginInfo &_info); + /// \brief Add multiple plugins to the simulation + /// \param[in] _info List of Information about the plugin to load. + public: void AddPlugins(const std::list &_plugins); + + /// \brief Generate PluginInfo for Log recording based on the + /// internal state of this ServerConfig object: + /// \sa UseLogRecord + /// \sa LogRecordPath + /// \sa LogRecordResources + /// \sa LogRecordCompressPath + /// \sa LogRecordTopics + public: PluginInfo LogRecordPlugin() const; + + /// \brief Generate PluginInfo for Log playback based on the + /// internal state of this ServerConfig object: + /// \sa LogPlaybackPath + public: PluginInfo LogPlaybackPlugin() const; + /// \brief Get all the plugins that should be loaded. /// \return A list of all the plugins specified via /// AddPlugin(const PluginInfo &). @@ -372,6 +390,45 @@ namespace ignition /// \brief Private data pointer private: std::unique_ptr dataPtr; }; + + /// \brief Parse plugins from XML configuration file. + /// \param[in] _fname Absolute path to the configuration file to parse. + /// \return A list of all of the plugins found in the configuration file + std::list + IGNITION_GAZEBO_VISIBLE + parsePluginsFromFile(const std::string &_fname); + + /// \brief Parse plugins from XML configuration string. + /// \param[in] _str XML configuration content to parse + /// \return A list of all of the plugins found in the configuration string. + std::list + IGNITION_GAZEBO_VISIBLE + parsePluginsFromString(const std::string &_str); + + /// \brief Load plugin information, following ordering. + /// + /// This method is used when no plugins are found in an SDF + /// file to load either a default or custom set of plugins. + /// + /// The following order is used to resolve: + /// 1. Config file located at IGN_GAZEBO_SERVER_CONFIG_PATH environment + /// variable. + /// * If IGN_GAZEBO_SERVER_CONFIG_PATH is set but empty, no plugins + /// are loaded. + /// 2. File at ${IGN_HOMEDIR}/.ignition/gazebo/server.config + /// 3. File at ${IGN_DATA_INSTALL_DIR}/server.config + /// + /// If any of the above files exist but are empty, resolution + /// stops and the plugin list will be empty. + /// + // + /// \param[in] _isPlayback Is the server in playback mode. If so, fallback + /// to playback_server.config. + // + /// \return A list of plugins to load, based on above ordering + std::list + IGNITION_GAZEBO_VISIBLE + loadPluginInfo(bool _isPlayback = false); } } } diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index 39d790f7f9..ca058f3a08 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -146,6 +146,9 @@ namespace ignition /// `` const std::string kSdfPathEnv{"SDF_PATH"}; + /// \breif Environment variable holding server config paths. + const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"}; + /// \brief Environment variable holding paths to custom rendering engine /// plugins. const std::string kRenderPluginPathEnv{"IGN_GAZEBO_RENDER_ENGINE_PATH"}; diff --git a/include/ignition/gazebo/config.hh.in b/include/ignition/gazebo/config.hh.in index fb16fddef7..050a0304a4 100644 --- a/include/ignition/gazebo/config.hh.in +++ b/include/ignition/gazebo/config.hh.in @@ -15,6 +15,7 @@ #define IGNITION_GAZEBO_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/gui" #define IGNITION_GAZEBO_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/systems" +#define IGNITION_GAZEBO_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}" #define IGN_GAZEBO_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" #define IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" #define IGN_GAZEBO_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${IGN_DATA_INSTALL_DIR}/worlds" diff --git a/include/ignition/gazebo/playback_server.config b/include/ignition/gazebo/playback_server.config new file mode 100644 index 0000000000..2551fda3ea --- /dev/null +++ b/include/ignition/gazebo/playback_server.config @@ -0,0 +1,14 @@ + + + + + + + + diff --git a/include/ignition/gazebo/server.config b/include/ignition/gazebo/server.config new file mode 100644 index 0000000000..5de18a66fc --- /dev/null +++ b/include/ignition/gazebo/server.config @@ -0,0 +1,19 @@ + + + + + + + + + + diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 1c029e2900..078c1b4bcf 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -75,6 +75,7 @@ set (gtest_sources SdfEntityCreator_TEST.cc SdfGenerator_TEST.cc Server_TEST.cc + ServerConfig_TEST.cc SimulationRunner_TEST.cc System_TEST.cc SystemLoader_TEST.cc diff --git a/src/Server.cc b/src/Server.cc index 9fb9492de8..bb188ef993 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -59,53 +59,14 @@ std::string findFuelResourceSdf(const std::string &_path) /// \brief This struct provides access to the default world. struct DefaultWorld { - /// \brief Get the default plugins as a string. - /// \return An SDF string that contains the default plugins. - public: static std::string &DefaultPlugins(const ServerConfig &_config) - { - std::vector pluginsV = { - { - std::string("" - }, - { - std::string("" - } - }; - - // The set of default gazebo plugins. - if (_config.LogPlaybackPath().empty()) - { - pluginsV.push_back(std::string(""); - } - - // Playback plugin - else - { - pluginsV.push_back(std::string("" + - _config.LogPlaybackPath() + ""); - } - - static std::string plugins = std::accumulate(pluginsV.begin(), - pluginsV.end(), std::string("")); - return plugins; - } - /// \brief Get the default world as a string. + /// Plugins will be loaded from the server.config file. /// \return An SDF string that contains the default world. - public: static std::string &World(const ServerConfig &_config) + public: static std::string &World() { static std::string world = std::string("" "" "") + - DefaultPlugins(_config) + "" ""; @@ -211,7 +172,7 @@ Server::Server(const ServerConfig &_config) ignmsg << "Loading default world.\n"; // Load an empty world. /// \todo(nkoenig) Add a "AddWorld" function to sdf::Root. - errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World(_config)); + errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World()); } if (!errors.empty()) diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index fbb61135ca..97b738c4ea 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -14,13 +14,18 @@ * limitations under the License. * */ +#include "ignition/gazebo/ServerConfig.hh" + +#include + #include #include #include #include #include #include -#include "ignition/gazebo/ServerConfig.hh" + +#include "ignition/gazebo/Util.hh" using namespace ignition; using namespace gazebo; @@ -230,7 +235,8 @@ class ignition::gazebo::ServerConfigPrivate plugins(_cfg->plugins), networkRole(_cfg->networkRole), networkSecondaries(_cfg->networkSecondaries), - seed(_cfg->seed) { } + seed(_cfg->seed), + logRecordTopics(_cfg->logRecordTopics) { } // \brief The SDF file that the server should load public: std::string sdfFile = ""; @@ -550,6 +556,104 @@ void ServerConfig::AddPlugin(const ServerConfig::PluginInfo &_info) this->dataPtr->plugins.push_back(_info); } +///////////////////////////////////////////////// +ServerConfig::PluginInfo +ServerConfig::LogPlaybackPlugin() const +{ + auto entityName = "*"; + auto entityType = "world"; + auto pluginName = "ignition::gazebo::systems::LogPlayback"; + auto pluginFilename = "ignition-gazebo-log-system"; + + sdf::ElementPtr playbackElem; + playbackElem = std::make_shared(); + playbackElem->SetName("plugin"); + + if (!this->LogPlaybackPath().empty()) + { + sdf::ElementPtr pathElem = std::make_shared(); + pathElem->SetName("path"); + playbackElem->AddElementDescription(pathElem); + pathElem = playbackElem->GetElement("path"); + pathElem->AddValue("string", "", false, ""); + pathElem->Set(this->LogPlaybackPath()); + } + + return ServerConfig::PluginInfo(entityName, + entityType, + pluginFilename, + pluginName, + playbackElem); +} + +///////////////////////////////////////////////// +ServerConfig::PluginInfo +ServerConfig::LogRecordPlugin() const +{ + auto entityName = "*"; + auto entityType = "world"; + auto pluginName = "ignition::gazebo::systems::LogRecord"; + auto pluginFilename = std::string("ignition-gazebo") + + IGNITION_GAZEBO_MAJOR_VERSION_STR + "-log-system"; + + sdf::ElementPtr recordElem; + + recordElem = std::make_shared(); + recordElem->SetName("plugin"); + + if (!this->LogRecordPath().empty()) + { + sdf::ElementPtr pathElem = std::make_shared(); + pathElem->SetName("path"); + recordElem->AddElementDescription(pathElem); + pathElem = recordElem->GetElement("path"); + pathElem->AddValue("string", "", false, ""); + pathElem->Set(this->LogRecordPath()); + } + + // Set whether to record resources + sdf::ElementPtr resourceElem = std::make_shared(); + resourceElem->SetName("record_resources"); + recordElem->AddElementDescription(resourceElem); + resourceElem = recordElem->GetElement("record_resources"); + resourceElem->AddValue("bool", "false", false, ""); + resourceElem->Set(this->LogRecordResources() ? true : false); + + // Set whether to compress + sdf::ElementPtr compressElem = std::make_shared(); + compressElem->SetName("compress"); + recordElem->AddElementDescription(compressElem); + compressElem = recordElem->GetElement("compress"); + compressElem->AddValue("bool", "false", false, ""); + compressElem->Set(this->LogRecordCompressPath().empty() ? false : + true); + + // Set compress path + sdf::ElementPtr cPathElem = std::make_shared(); + cPathElem->SetName("compress_path"); + recordElem->AddElementDescription(cPathElem); + cPathElem = recordElem->GetElement("compress_path"); + cPathElem->AddValue("string", "", false, ""); + cPathElem->Set(this->LogRecordCompressPath()); + + // If record topics specified, add in SDF + for (const std::string &topic : this->LogRecordTopics()) + { + sdf::ElementPtr topicElem = std::make_shared(); + topicElem->SetName("record_topic"); + recordElem->AddElementDescription(topicElem); + topicElem = recordElem->AddElement("record_topic"); + topicElem->AddValue("string", "false", false, ""); + topicElem->Set(topic); + } + + return ServerConfig::PluginInfo(entityName, + entityType, + pluginFilename, + pluginName, + recordElem); +} + ///////////////////////////////////////////////// const std::list &ServerConfig::Plugins() const { @@ -587,3 +691,230 @@ const std::vector &ServerConfig::LogRecordTopics() const { return this->dataPtr->logRecordTopics; } + +///////////////////////////////////////////////// +void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml) +{ + _sdf->SetName(_xml->Value()); + if (_xml->GetText() != nullptr) + _sdf->AddValue("string", _xml->GetText(), "1"); + + for (const tinyxml2::XMLAttribute *attribute = _xml->FirstAttribute(); + attribute; attribute = attribute->Next()) + { + _sdf->AddAttribute(attribute->Name(), "string", "", 1, ""); + _sdf->GetAttribute(attribute->Name())->SetFromString( + attribute->Value()); + } + + // Iterate over all the child elements + const tinyxml2::XMLElement *elemXml = nullptr; + for (elemXml = _xml->FirstChildElement(); elemXml; + elemXml = elemXml->NextSiblingElement()) + { + sdf::ElementPtr element(new sdf::Element); + element->SetParent(_sdf); + + copyElement(element, elemXml); + _sdf->InsertElement(element); + } +} + +///////////////////////////////////////////////// +std::list +parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) +{ + auto ret = std::list(); + auto root = _doc.RootElement(); + if (root == nullptr) + { + ignerr << "No element found when parsing plugins\n"; + return ret; + } + + auto plugins = root->FirstChildElement("plugins"); + if (plugins == nullptr) + { + ignerr << "No element found when parsing plugins\n"; + return ret; + } + + const tinyxml2::XMLElement *elem{nullptr}; + + // Note, this was taken from ign-launch, where this type of parsing happens. + // Process all the plugins. + for (elem = plugins->FirstChildElement("plugin"); elem; + elem = elem->NextSiblingElement("plugin")) + { + // Get the plugin's name + const char *nameStr = elem->Attribute("name"); + std::string name = nameStr == nullptr ? "" : nameStr; + if (name.empty()) + { + ignerr << "Plugin is missing the name attribute. " + << "Skipping this plugin.\n"; + continue; + } + + // Get the plugin's filename + const char *fileStr = elem->Attribute("filename"); + std::string file = fileStr == nullptr ? "" : fileStr; + if (file.empty()) + { + ignerr << "A Plugin with name[" << name << "] is " + << "missing the filename attribute. Skipping this plugin.\n"; + continue; + } + + // Get the plugin's entity name attachment information. + const char *entityNameStr = elem->Attribute("entity_name"); + std::string entityName = entityNameStr == nullptr ? "" : entityNameStr; + if (entityName.empty()) + { + ignerr << "A Plugin with name[" << name << "] and " + << "filename[" << file << "] is missing the entity_name attribute. " + << "Skipping this plugin.\n"; + continue; + } + + // Get the plugin's entity type attachment information. + const char *entityTypeStr = elem->Attribute("entity_type"); + std::string entityType = entityTypeStr == nullptr ? "" : entityTypeStr; + if (entityType.empty()) + { + ignerr << "A Plugin with name[" << name << "] and " + << "filename[" << file << "] is missing the entity_type attribute. " + << "Skipping this plugin.\n"; + continue; + } + + // Create an SDF element of the plugin + sdf::ElementPtr sdf(new sdf::Element); + copyElement(sdf, elem); + + // Add the plugin to the server config + ret.push_back({entityName, entityType, file, name, sdf}); + } + return ret; +} + +///////////////////////////////////////////////// +std::list +ignition::gazebo::parsePluginsFromFile(const std::string &_fname) +{ + tinyxml2::XMLDocument doc; + doc.LoadFile(_fname.c_str()); + return parsePluginsFromDoc(doc); +} + +///////////////////////////////////////////////// +std::list +ignition::gazebo::parsePluginsFromString(const std::string &_str) +{ + tinyxml2::XMLDocument doc; + doc.Parse(_str.c_str()); + return parsePluginsFromDoc(doc); +} + + +///////////////////////////////////////////////// +std::list +ignition::gazebo::loadPluginInfo(bool _isPlayback) +{ + std::list ret; + + // 1. Check contents of environment variable + std::string envConfig; + bool configSet = ignition::common::env(gazebo::kServerConfigPathEnv, + envConfig); + + if (configSet) + { + if (ignition::common::exists(envConfig)) + { + // Parse configuration stored in environment variable + ret = ignition::gazebo::parsePluginsFromFile(envConfig); + if (ret.empty()) + { + // This may be desired behavior, but warn just in case. + // Some users may want to defer all loading until later + // during runtime. + ignwarn << gazebo::kServerConfigPathEnv + << " set but no plugins found\n"; + } + igndbg << "Loaded (" << ret.size() << ") plugins from file " << + "[" << envConfig << "]\n"; + + return ret; + } + else + { + // This may be desired behavior, but warn just in case. + // Some users may want to defer all loading until late + // during runtime. + ignwarn << gazebo::kServerConfigPathEnv + << " set but no file found," + << " no plugins loaded\n"; + return ret; + } + } + + std::string configFilename; + if (_isPlayback) + { + configFilename = "playback_server.config"; + } + else + { + configFilename = "server.config"; + } + + std::string defaultConfig; + ignition::common::env(IGN_HOMEDIR, defaultConfig); + defaultConfig = ignition::common::joinPaths(defaultConfig, ".ignition", + "gazebo", configFilename); + + if (!ignition::common::exists(defaultConfig)) + { + auto installedConfig = ignition::common::joinPaths( + IGNITION_GAZEBO_SERVER_CONFIG_PATH, + configFilename); + + if (!ignition::common::exists(installedConfig)) + { + ignerr << "Failed to copy installed config [" << installedConfig + << "] to default config [" << defaultConfig << "]." + << "(file " << installedConfig << " doesn't exist)" + << std::endl; + return ret; + } + else if (!ignition::common::copyFile(installedConfig, defaultConfig)) + { + ignerr << "Failed to copy installed config [" << installedConfig + << "] to default config [" << defaultConfig << "]." + << std::endl; + return ret; + } + else + { + ignmsg << "Copied installed config [" << installedConfig + << "] to default config [" << defaultConfig << "]." + << std::endl; + } + } + + ret = ignition::gazebo::parsePluginsFromFile(defaultConfig); + + if (ret.empty()) + { + // This may be desired behavior, but warn just in case. + ignwarn << "Loaded config: [" << defaultConfig + << "], but no plugins found\n"; + } + + igndbg << "Loaded (" << ret.size() << ") plugins from file " << + "[" << defaultConfig << "]\n"; + + return ret; +} + diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc new file mode 100644 index 0000000000..733a55ef37 --- /dev/null +++ b/src/ServerConfig_TEST.cc @@ -0,0 +1,230 @@ +/* + * Copyright (C) 2020 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 + +using namespace ignition; +using namespace gazebo; + +////////////////////////////////////////////////// +TEST(ParsePluginsFromString, Valid) +{ + std::string config = R"( + + + + 0.123 + + + 987 + + + 456 + + + )"; + + auto plugins = parsePluginsFromString(config); + ASSERT_EQ(3u, plugins.size()); + + auto plugin = plugins.begin(); + + EXPECT_EQ("default", plugin->EntityName()); + EXPECT_EQ("world", plugin->EntityType()); + EXPECT_EQ("TestWorldSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + + plugin = std::next(plugin, 1); + + EXPECT_EQ("box", plugin->EntityName()); + EXPECT_EQ("model", plugin->EntityType()); + EXPECT_EQ("TestModelSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + + plugin = std::next(plugin, 1); + + EXPECT_EQ("default::box::link_1::camera", plugin->EntityName()); + EXPECT_EQ("sensor", plugin->EntityType()); + EXPECT_EQ("TestSensorSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestSensorSystem", plugin->Name()); +} + +////////////////////////////////////////////////// +TEST(ParsePluginsFromString, Invalid) +{ + std::string config = R"( + + + 0.123 + + )"; + + auto plugins = parsePluginsFromString(config); + ASSERT_EQ(0u, plugins.size()); + + auto plugins2 = parsePluginsFromString(""); + ASSERT_EQ(0u, plugins2.size()); +} + +////////////////////////////////////////////////// +TEST(ParsePluginsFromFile, Valid) +{ + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "server_valid.config"); + + auto plugins = parsePluginsFromFile(config); + ASSERT_EQ(3u, plugins.size()); + + auto plugin = plugins.begin(); + + EXPECT_EQ("default", plugin->EntityName()); + EXPECT_EQ("world", plugin->EntityType()); + EXPECT_EQ("TestWorldSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + + plugin = std::next(plugin, 1); + + EXPECT_EQ("box", plugin->EntityName()); + EXPECT_EQ("model", plugin->EntityType()); + EXPECT_EQ("TestModelSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + + plugin = std::next(plugin, 1); + + EXPECT_EQ("default::box::link_1::camera", plugin->EntityName()); + EXPECT_EQ("sensor", plugin->EntityType()); + EXPECT_EQ("TestSensorSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestSensorSystem", plugin->Name()); +} + +////////////////////////////////////////////////// +TEST(ParsePluginsFromFile, Invalid) +{ + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "server_invalid.config"); + + // Valid file without valid content + auto plugins = parsePluginsFromFile(config); + ASSERT_EQ(0u, plugins.size()); + + // Invalid file + auto plugins2 = parsePluginsFromFile("/foo/bar/baz"); + ASSERT_EQ(0u, plugins2.size()); +} + +////////////////////////////////////////////////// +TEST(ParsePluginsFromFile, DefaultConfig) +{ + // Note: This test validates that that the default + // configuration always parses. + // If more systems are added, then the number needs + // to be adjusted below. + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "include", "ignition", "gazebo", "server.config"); + + auto plugins = parsePluginsFromFile(config); + ASSERT_EQ(3u, plugins.size()); +} + +////////////////////////////////////////////////// +TEST(ParsePluginsFromFile, PlaybackConfig) +{ + // Note: This test validates that that the default + // configuration always parses. + // If more systems are added, then the number needs + // to be adjusted below. + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "include", "ignition", "gazebo", "playback_server.config"); + + auto plugins = parsePluginsFromFile(config); + ASSERT_EQ(2u, plugins.size()); +} + +////////////////////////////////////////////////// +TEST(LoadPluginInfo, FromEmptyEnv) +{ + // Set environment to something that doesn't exist + ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, "foo")); + auto plugins = loadPluginInfo(); + + EXPECT_EQ(0u, plugins.size()); + EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); +} + +////////////////////////////////////////////////// +TEST(LoadPluginInfo, FromValidEnv) +{ + auto validPath = common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "server_valid2.config"); + + ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, validPath)); + + auto plugins = loadPluginInfo(); + ASSERT_EQ(2u, plugins.size()); + + auto plugin = plugins.begin(); + + EXPECT_EQ("*", plugin->EntityName()); + EXPECT_EQ("world", plugin->EntityType()); + EXPECT_EQ("TestWorldSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestWorldSystem", plugin->Name()); + + plugin = std::next(plugin, 1); + + EXPECT_EQ("box", plugin->EntityName()); + EXPECT_EQ("model", plugin->EntityType()); + EXPECT_EQ("TestModelSystem", plugin->Filename()); + EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); + + EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); +} + +////////////////////////////////////////////////// +TEST(ServerConfig, GenerateRecordPlugin) +{ + ServerConfig config; + config.SetUseLogRecord(true); + config.SetLogRecordPath("foo/bar"); + config.SetLogRecordResources(true); + + auto plugin = config.LogRecordPlugin(); + EXPECT_EQ(plugin.EntityName(), "*"); + EXPECT_EQ(plugin.EntityType(), "world"); + EXPECT_EQ(plugin.Name(), "ignition::gazebo::systems::LogRecord"); +} + diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 4b15c260fa..7792222754 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -183,204 +183,168 @@ bool ServerPrivate::Run(const uint64_t _iterations, } ////////////////////////////////////////////////// -void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) +sdf::ElementPtr GetRecordPluginElem(sdf::Root &_sdfRoot) { - const sdf::World *sdfWorld = this->sdfRoot.WorldByIndex(0); - sdf::ElementPtr worldElem = sdfWorld->Element(); + sdf::ElementPtr rootElem = _sdfRoot.Element(); - // Check if there is already a record plugin specified - if (worldElem->HasElement("plugin")) + if (rootElem->HasElement("world")) { - sdf::ElementPtr pluginElem = worldElem->GetElement("plugin"); - while (pluginElem != nullptr) + sdf::ElementPtr worldElem = rootElem->GetElement("world"); + + if (worldElem->HasElement("plugin")) { - sdf::ParamPtr pluginName = pluginElem->GetAttribute("name"); - sdf::ParamPtr pluginFileName = pluginElem->GetAttribute("filename"); + sdf::ElementPtr pluginElem = worldElem->GetElement("plugin"); - if (pluginName != nullptr && pluginFileName != nullptr) + while (pluginElem != nullptr) { - // Found a logging plugin - if (pluginFileName->GetAsString().find( - LoggingPlugin::LoggingPluginSuffix()) != std::string::npos) + sdf::ParamPtr pluginName = pluginElem->GetAttribute("name"); + sdf::ParamPtr pluginFileName = pluginElem->GetAttribute("filename"); + + if (pluginName != nullptr && pluginFileName != nullptr) { - // If record plugin already specified in SDF, and record flags are - // specified on command line, replace SDF parameters with those on - // command line. (If none specified on command line, use those in - // SDF.) - if (pluginName->GetAsString() == LoggingPlugin::RecordPluginName()) + // Found a logging plugin + if (pluginFileName->GetAsString().find( + LoggingPlugin::LoggingPluginSuffix()) != std::string::npos) { - std::string recordPath = _config.LogRecordPath(); - std::string cmpPath = _config.LogRecordCompressPath(); - - // Set record path - if (!_config.LogRecordPath().empty()) + if (pluginName->GetAsString() == LoggingPlugin::RecordPluginName()) { - bool overwriteSdf = false; - // If is specified in SDF, check whether to replace it - if (pluginElem->HasElement("path") && - !pluginElem->Get("path").empty()) - { - // If record path came from command line, overwrite SDF - if (_config.LogIgnoreSdfPath()) - { - overwriteSdf = true; - } - // TODO(anyone) In Ignition-D, remove this. will be - // permanently ignored in favor of common::ignLogDirectory(). - // Always overwrite SDF. - // Otherwise, record path is same as the default timestamp log - // path. Take the path in SDF . - // Deprecated. - else - { - ignwarn << "--record-path is not specified on command line. " - << " is specified in SDF. Will record to . " - << "Console will be logged to [" << ignLogDirectory() - << "]. Note: In Ignition-D, will be ignored, and " - << "all recordings will be written to default console log " - << "path if no path is specified on command line.\n"; - overwriteSdf = false; - - // Take in SDF - recordPath = pluginElem->Get("path"); - - // Update path for compressed file to match record path - cmpPath = std::string(recordPath); - if (!std::string(1, cmpPath.back()).compare( - ignition::common::separator(""))) - { - // Remove the separator at end of path - cmpPath = cmpPath.substr(0, cmpPath.length() - 1); - } - cmpPath += ".zip"; - } - } - else - { - overwriteSdf = true; - } - - if (overwriteSdf) - { - sdf::ElementPtr pathElem = std::make_shared(); - pathElem->SetName("path"); - pluginElem->AddElementDescription(pathElem); - pathElem = pluginElem->GetElement("path"); - pathElem->AddValue("string", "", false, ""); - pathElem->Set(recordPath); - } + return pluginElem; } + } + } - // If resource flag specified on command line, replace in SDF - if (_config.LogRecordResources()) - { - sdf::ElementPtr resourceElem = std::make_shared(); - resourceElem->SetName("record_resources"); - pluginElem->AddElementDescription(resourceElem); - resourceElem = pluginElem->GetElement("record_resources"); - resourceElem->AddValue("bool", "false", false, ""); - resourceElem->Set(_config.LogRecordResources() - ? true : false); - } + pluginElem = pluginElem->GetNextElement(); + } + } + } + return nullptr; +} - // If compress flag specified on command line, replace in SDF - if (!_config.LogRecordCompressPath().empty()) - { - sdf::ElementPtr compressElem = std::make_shared(); - compressElem->SetName("compress"); - pluginElem->AddElementDescription(compressElem); - compressElem = pluginElem->GetElement("compress"); - compressElem->AddValue("bool", "false", false, ""); - compressElem->Set(true); - - sdf::ElementPtr cPathElem = std::make_shared(); - cPathElem->SetName("compress_path"); - pluginElem->AddElementDescription(cPathElem); - cPathElem = pluginElem->GetElement("compress_path"); - cPathElem->AddValue("string", "", false, ""); - cPathElem->Set(cmpPath); - } +////////////////////////////////////////////////// +void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) +{ + auto recordPluginElem = GetRecordPluginElem(this->sdfRoot); + bool sdfUseLogRecord = (recordPluginElem != nullptr); + + bool hasRecordPath {false}; + bool hasCompressPath {false}; + bool hasRecordResources {false}; + bool hasCompress {false}; + bool hasRecordTopics {false}; + + std::string sdfRecordPath; + std::string sdfCompressPath; + bool sdfRecordResources; + bool sdfCompress; + std::vector sdfRecordTopics; + + if (sdfUseLogRecord) + { + std::tie(sdfRecordPath, hasRecordPath) = + recordPluginElem->Get("path", ""); + std::tie(sdfCompressPath, hasCompressPath) = + recordPluginElem->Get("compress_path", ""); + std::tie(sdfRecordResources, hasRecordResources) = + recordPluginElem->Get("record_resources", false); + std::tie(sdfCompress, hasCompress) = + recordPluginElem->Get("compress", false); + + hasRecordTopics = recordPluginElem->HasElement("record_topic"); + if (hasRecordTopics) + { + sdf::ElementPtr recordTopicElem = + recordPluginElem->GetElement("record_topic"); + while (recordTopicElem) + { + auto topic = recordTopicElem->Get(); + sdfRecordTopics.push_back(topic); + } - // If record topics specified, add in SDF - for (const std::string &topic : _config.LogRecordTopics()) - { - sdf::ElementPtr topicElem = std::make_shared(); - topicElem->SetName("record_topic"); - pluginElem->AddElementDescription(topicElem); - topicElem = pluginElem->AddElement("record_topic"); - topicElem->AddValue("string", "false", false, ""); - topicElem->Set(topic); - } + recordTopicElem = recordTopicElem->GetNextElement(); + } - return; - } + // Remove from SDF + recordPluginElem->RemoveFromParent(); + recordPluginElem->Reset(); + } - // If playback plugin also specified, do not add a record plugin - if (pluginName->GetAsString() == LoggingPlugin::PlaybackPluginName()) + // Set the config based on what is in the SDF: + if (hasRecordPath) + this->config.SetLogRecordPath(sdfRecordPath); + if (hasCompressPath) + this->config.SetLogRecordCompressPath(sdfCompressPath); + if (hasRecordResources) + this->config.SetLogRecordResources(sdfRecordResources); + + if (hasRecordTopics) + { + this->config.ClearLogRecordTopics(); + for (auto topic : sdfRecordTopics) + { + this->config.AddLogRecordTopic(topic); + } + } + + if (!_config.LogRecordPath().empty() && hasRecordPath) + { + if (hasRecordPath) + { + // If record path came from command line, overwrite SDF + if (_config.LogIgnoreSdfPath()) + { + this->config.SetLogRecordPath(_config.LogRecordPath()); + } + // TODO(anyone) In Ignition-D, remove this. will be + // permanently ignored in favor of common::ignLogDirectory(). + // Always overwrite SDF. + // Otherwise, record path is same as the default timestamp log + // path. Take the path in SDF . + // Deprecated. + else + { + ignwarn << "--record-path is not specified on command line. " + << " is specified in SDF. Will record to . " + << "Console will be logged to [" << ignLogDirectory() + << "]. Note: In Ignition-D, will be ignored, and " + << "all recordings will be written to default console log " + << "path if no path is specified on command line.\n"; + + // In the case that the --compress flag is set, then + // this field will be populated with just the file extension + if(_config.LogRecordCompressPath() == ".zip") + { + sdfCompressPath = std::string(sdfRecordPath); + if (!std::string(1, sdfCompressPath.back()).compare( + ignition::common::separator(""))) { - ignwarn << "Both record and playback are specified. " - << "Ignoring record.\n"; - return; + // Remove the separator at end of path + sdfCompressPath = sdfCompressPath.substr(0, + sdfCompressPath.length() - 1); } + sdfCompressPath += ".zip"; + this->config.SetLogRecordCompressPath(sdfCompressPath); } } - - pluginElem = pluginElem->GetNextElement(); + } + else + { + this->config.SetLogRecordPath(_config.LogRecordPath()); } } - // A record plugin is not already specified in SDF. Add one. - sdf::ElementPtr recordElem = worldElem->AddElement("plugin"); - sdf::ParamPtr recordName = recordElem->GetAttribute("name"); - recordName->SetFromString(LoggingPlugin::RecordPluginName()); - sdf::ParamPtr recordFileName = recordElem->GetAttribute("filename"); - recordFileName->SetFromString(LoggingPlugin::LoggingPluginFileName()); + if (_config.LogRecordResources()) + this->config.SetLogRecordResources(true); - // Add custom record path - if (!_config.LogRecordPath().empty()) - { - sdf::ElementPtr pathElem = std::make_shared(); - pathElem->SetName("path"); - recordElem->AddElementDescription(pathElem); - pathElem = recordElem->GetElement("path"); - pathElem->AddValue("string", "", false, ""); - pathElem->Set(_config.LogRecordPath()); - } + if (_config.LogRecordCompressPath() != ".zip") + this->config.SetLogRecordCompressPath(_config.LogRecordCompressPath()); - // Set whether to record resources - sdf::ElementPtr resourceElem = std::make_shared(); - resourceElem->SetName("record_resources"); - recordElem->AddElementDescription(resourceElem); - resourceElem = recordElem->GetElement("record_resources"); - resourceElem->AddValue("bool", "false", false, ""); - resourceElem->Set(_config.LogRecordResources() ? true : false); - - // Set whether to compress - sdf::ElementPtr compressElem = std::make_shared(); - compressElem->SetName("compress"); - recordElem->AddElementDescription(compressElem); - compressElem = recordElem->GetElement("compress"); - compressElem->AddValue("bool", "false", false, ""); - compressElem->Set(_config.LogRecordCompressPath().empty() ? false : - true); - - // Set compress path - sdf::ElementPtr cPathElem = std::make_shared(); - cPathElem->SetName("compress_path"); - recordElem->AddElementDescription(cPathElem); - cPathElem = recordElem->GetElement("compress_path"); - cPathElem->AddValue("string", "", false, ""); - cPathElem->Set(_config.LogRecordCompressPath()); - - // If record topics specified, add in SDF - for (const std::string &topic : _config.LogRecordTopics()) + if (_config.LogRecordTopics().size()) { - sdf::ElementPtr topicElem = std::make_shared(); - topicElem->SetName("record_topic"); - recordElem->AddElementDescription(topicElem); - topicElem = recordElem->AddElement("record_topic"); - topicElem->AddValue("string", "false", false, ""); - topicElem->Set(topic); + this->config.ClearLogRecordTopics(); + for (auto topic : _config.LogRecordTopics()) + { + this->config.AddLogRecordTopic(topic); + } } } diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index b057678e28..d5d9c37f45 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -34,6 +34,7 @@ #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/Types.hh" +#include "ignition/gazebo/Util.hh" #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" @@ -220,8 +221,8 @@ TEST_P(ServerFixture, ServerConfigSensorPlugin) { // Start server ServerConfig serverConfig; - serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/air_pressure.sdf"); + serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "air_pressure.sdf")); sdf::ElementPtr sdf(new sdf::Element); sdf->SetName("plugin"); @@ -229,7 +230,8 @@ TEST_P(ServerFixture, ServerConfigSensorPlugin) "ignition::gazebo::TestSensorSystem", true); sdf->AddAttribute("filename", "string", "libTestSensorSystem.so", true); - serverConfig.AddPlugin({"air_pressure_model::link::air_pressure_sensor", + serverConfig.AddPlugin({ + "air_pressure_sensor::air_pressure_model::link::air_pressure_sensor", "sensor", "libTestSensorSystem.so", "ignition::gazebo::TestSensorSystem", sdf}); @@ -238,6 +240,7 @@ TEST_P(ServerFixture, ServerConfigSensorPlugin) // The simulation runner should not be running. EXPECT_FALSE(*server.Running(0)); + EXPECT_EQ(2u, *server.SystemCount()); // Run the server igndbg << "Run server" << std::endl; @@ -316,6 +319,7 @@ TEST_P(ServerFixture, ServerConfigLogRecord) serverConfig.SetLogRecordPath(logPath); gazebo::Server server(serverConfig); + EXPECT_EQ(0u, *server.IterationCount()); EXPECT_EQ(3u, *server.EntityCount()); EXPECT_EQ(4u, *server.SystemCount()); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index 1984408f12..79e4a1f34e 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -19,8 +19,9 @@ #include -#include "ignition/common/Profiler.hh" +#include +#include "ignition/common/Profiler.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Sensor.hh" @@ -29,6 +30,7 @@ #include "ignition/gazebo/Events.hh" #include "ignition/gazebo/SdfEntityCreator.hh" #include "ignition/gazebo/Util.hh" + #include "network/NetworkManagerPrimary.hh" #include "SdfGenerator.hh" @@ -155,6 +157,21 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, // Load the active levels this->levelMgr->UpdateLevelsState(); + // Load any additional plugins from the Server Configuration + this->LoadServerPlugins(this->serverConfig.Plugins()); + + // If we have reached this point and no systems have been loaded, then load + // a default set of systems. + if (this->systems.empty() && this->pendingSystems.empty()) + { + ignmsg << "No systems loaded from SDF, loading defaults" << std::endl; + bool isPlayback = !this->serverConfig.LogPlaybackPath().empty(); + auto plugins = ignition::gazebo::loadPluginInfo(isPlayback); + this->LoadServerPlugins(plugins); + } + + this->LoadLoggingPlugins(this->serverConfig); + // World control transport::NodeOptions opts; if (this->networkMgr) @@ -732,50 +749,46 @@ void SimulationRunner::Step(const UpdateInfo &_info) } ////////////////////////////////////////////////// -void SimulationRunner::LoadPlugins(const Entity _entity, - const sdf::ElementPtr &_sdf) +void SimulationRunner::LoadPlugin(const Entity _entity, + const std::string &_fname, + const std::string &_name, + const sdf::ElementPtr &_sdf) { - sdf::ElementPtr pluginElem = _sdf->GetElement("plugin"); - while (pluginElem) + std::optional system; { - // No error message for the 'else' case of the following 'if' statement - // because SDF create a default element even if it's not - // specified. An error message would result in spamming - // the console. \todo(nkoenig) Fix SDF should so that elements are not - // automatically added. - if (pluginElem->Get("filename") != "__default__" && - pluginElem->Get("name") != "__default__") + std::lock_guard lock(this->systemLoaderMutex); + system = this->systemLoader->LoadPlugin(_fname, _name, _sdf); + } + + // System correctly loaded from library, try to configure + if (system) + { + auto systemConfig = system.value()->QueryInterface(); + if (systemConfig != nullptr) { - std::optional system; - { - std::lock_guard lock(this->systemLoaderMutex); - system = this->systemLoader->LoadPlugin(pluginElem); - } - if (system) - { - auto systemConfig = system.value()->QueryInterface(); - if (systemConfig != nullptr) - { - systemConfig->Configure(_entity, pluginElem, - this->entityCompMgr, - this->eventMgr); - } - this->AddSystem(system.value()); - igndbg << "Loaded system [" << pluginElem->Get("name") - << "] for entity [" << _entity << "]" << std::endl; - } + systemConfig->Configure(_entity, _sdf, + this->entityCompMgr, + this->eventMgr); } - pluginElem = pluginElem->GetNextElement("plugin"); + this->AddSystem(system.value()); + igndbg << "Loaded system [" << _name + << "] for entity [" << _entity << "]" << std::endl; } +} +////////////////////////////////////////////////// +void SimulationRunner::LoadServerPlugins( + const std::list &_plugins) +{ // \todo(nkoenig) Remove plugins from the server config after they have // been added. We might not want to do this if we want to support adding // the same plugin to multiple entities, for example via a regex // expression. // // Check plugins from the ServerConfig for matching entities. - for (const ServerConfig::PluginInfo &plugin : this->serverConfig.Plugins()) + + for (const ServerConfig::PluginInfo &plugin : _plugins) { // \todo(anyone) Type + name is not enough to uniquely identify an entity // \todo(louise) The runner shouldn't care about specific components, this @@ -789,8 +802,16 @@ void SimulationRunner::LoadPlugins(const Entity _entity, } else if ("world" == plugin.EntityType()) { - entity = this->entityCompMgr.EntityByComponents( - components::Name(plugin.EntityName()), components::World()); + // Allow wildcard for world name + if (plugin.EntityName() == "*") + { + entity = this->entityCompMgr.EntityByComponents(components::World()); + } + else + { + entity = this->entityCompMgr.EntityByComponents( + components::Name(plugin.EntityName()), components::World()); + } } else if ("sensor" == plugin.EntityType()) { @@ -830,29 +851,59 @@ void SimulationRunner::LoadPlugins(const Entity _entity, << plugin.EntityType() << "]" << std::endl; } - // Skip plugins that do not match the provided entity - if (entity != _entity) - continue; - std::optional system; + if (kNullEntity != entity) { - std::lock_guard lock(this->systemLoaderMutex); - system = this->systemLoader->LoadPlugin(plugin.Filename(), plugin.Name(), - nullptr); + this->LoadPlugin(entity, plugin.Filename(), plugin.Name(), plugin.Sdf()); } + } +} + +////////////////////////////////////////////////// +void SimulationRunner::LoadLoggingPlugins(const ServerConfig &_config) +{ + std::list plugins; + + if(_config.UseLogRecord() && !_config.LogPlaybackPath().empty()) + { + ignwarn << + "Both recording and playback are specified, defaulting to playback\n"; + } + + if(!_config.LogPlaybackPath().empty()) + { + auto playbackPlugin = _config.LogPlaybackPlugin(); + plugins.push_back(playbackPlugin); + } + else if(_config.UseLogRecord()) + { + auto recordPlugin = _config.LogRecordPlugin(); + plugins.push_back(recordPlugin); + } + + this->LoadServerPlugins(plugins); +} - if (system) +////////////////////////////////////////////////// +void SimulationRunner::LoadPlugins(const Entity _entity, + const sdf::ElementPtr &_sdf) +{ + sdf::ElementPtr pluginElem = _sdf->GetElement("plugin"); + while (pluginElem) + { + auto filename = pluginElem->Get("filename"); + auto name = pluginElem->Get("name"); + // No error message for the 'else' case of the following 'if' statement + // because SDF create a default element even if it's not + // specified. An error message would result in spamming + // the console. \todo(nkoenig) Fix SDF should so that elements are not + // automatically added. + if (filename != "__default__" && name != "__default__") { - auto systemConfig = system.value()->QueryInterface(); - if (systemConfig != nullptr) - { - systemConfig->Configure(_entity, plugin.Sdf(), this->entityCompMgr, - this->eventMgr); - } - this->AddSystem(system.value()); - igndbg << "Loaded system [" << plugin.Name() - << "] for entity [" << _entity << "]" << std::endl; + this->LoadPlugin(_entity, filename, name, pluginElem); } + + pluginElem = pluginElem->GetNextElement("plugin"); } } diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh index 775487f4fa..faf8e3518b 100644 --- a/src/SimulationRunner.hh +++ b/src/SimulationRunner.hh @@ -170,12 +170,32 @@ namespace ignition /// \brief Publish current world statistics. public: void PublishStats(); + /// \brief Load system plugin for a given entity. + /// \param[in] _entity Entity + /// \param[in] _fname Filename of the plugin library + /// \param[in] _name Name of the plugin + /// \param[in] _sdf SDF element (content of plugin tag) + public: void LoadPlugin(const Entity _entity, + const std::string &_fname, + const std::string &_name, + const sdf::ElementPtr &_sdf); + /// \brief Load system plugins for a given entity. /// \param[in] _entity Entity /// \param[in] _sdf SDF element public: void LoadPlugins(const Entity _entity, const sdf::ElementPtr &_sdf); + /// \brief Load server plugins for a given entity. + /// \param[in] _config Configuration to load plugins from. + /// plugins based on the _config contents + public: void LoadServerPlugins( + const std::list &_plugins); + + /// \brief Load logging/playback plugins + /// \param[in] _config Configuration to load plugins from. + public: void LoadLoggingPlugins(const ServerConfig &_config); + /// \brief Get whether this is running. When running is true, /// then simulation is stepping forward. /// \return True if the server is running. diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 52795298b0..64b75f6c1f 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -16,6 +16,8 @@ */ #include +#include + #include #include #include @@ -26,6 +28,7 @@ #include #include + #include "ignition/gazebo/test_config.hh" #include "ignition/gazebo/components/CanonicalLink.hh" #include "ignition/gazebo/components/ChildLinkName.hh" @@ -48,6 +51,7 @@ #include "ignition/gazebo/components/Wind.hh" #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/Events.hh" +#include "ignition/gazebo/Util.hh" #include "ignition/gazebo/config.hh" #include "SimulationRunner.hh" @@ -81,8 +85,8 @@ class SimulationRunnerTest : public ::testing::TestWithParam { common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + common::joinPaths(PROJECT_BINARY_PATH, "lib")); } }; @@ -107,8 +111,8 @@ TEST_P(SimulationRunnerTest, CreateEntities) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/shapes.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "shapes.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -520,8 +524,8 @@ TEST_P(SimulationRunnerTest, CreateLights) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/lights.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "lights.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -790,8 +794,8 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/demo_joint_types.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "demo_joint_types.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -931,8 +935,8 @@ TEST_P(SimulationRunnerTest, Time) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/shapes.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "shapes.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -1053,8 +1057,8 @@ TEST_P(SimulationRunnerTest, LoadPlugins) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/plugins.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "plugins.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -1135,13 +1139,156 @@ TEST_P(SimulationRunnerTest, LoadPlugins) #endif } +///////////////////////////////////////////////// +TEST_P(SimulationRunnerTest, LoadServerNoPlugins) +{ + sdf::Root rootWithout; + rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "plugins_empty.sdf")); + ASSERT_EQ(1u, rootWithout.WorldCount()); + + // ServerConfig will fall back to environment variable + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "server_valid2.config"); + ASSERT_EQ(true, common::setenv(gazebo::kServerConfigPathEnv, config)); + ServerConfig serverConfig; + + // Create simulation runner + auto systemLoader = std::make_shared(); + SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader, + serverConfig); + + ASSERT_EQ(2u, runner.SystemCount()); +} + +///////////////////////////////////////////////// +TEST_P(SimulationRunnerTest, LoadServerConfigPlugins) +{ + sdf::Root rootWithout; + rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "plugins_empty.sdf")); + ASSERT_EQ(1u, rootWithout.WorldCount()); + + // Create a server configuration with plugins + // No fallback expected + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "server_valid.config"); + + auto plugins = parsePluginsFromFile(config); + ASSERT_EQ(3u, plugins.size()); + + ServerConfig serverConfig; + for (auto plugin : plugins) + { + serverConfig.AddPlugin(plugin); + } + + // Create simulation runner + auto systemLoader = std::make_shared(); + SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader, + serverConfig); + + // Get world entity + Entity worldId{kNullEntity}; + runner.EntityCompMgr().Each([&]( + const ignition::gazebo::Entity &_entity, + const ignition::gazebo::components::World *_world)->bool + { + EXPECT_NE(nullptr, _world); + worldId = _entity; + return true; + }); + EXPECT_NE(kNullEntity, worldId); + + // Get model entity + Entity modelId{kNullEntity}; + runner.EntityCompMgr().Each([&]( + const ignition::gazebo::Entity &_entity, + const ignition::gazebo::components::Model *_model)->bool + { + EXPECT_NE(nullptr, _model); + modelId = _entity; + return true; + }); + EXPECT_NE(kNullEntity, modelId); + + // Get sensor entity + Entity sensorId{kNullEntity}; + runner.EntityCompMgr().Each([&]( + const ignition::gazebo::Entity &_entity, + const ignition::gazebo::components::Sensor *_sensor)->bool + { + EXPECT_NE(nullptr, _sensor); + sensorId = _entity; + return true; + }); + EXPECT_NE(kNullEntity, sensorId); + + // Check component registered by world plugin + std::string worldComponentName{"WorldPluginComponent"}; + auto worldComponentId = ignition::common::hash64(worldComponentName); + + EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); + EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, + worldComponentId)); + + // Check component registered by model plugin + std::string modelComponentName{"ModelPluginComponent"}; + auto modelComponentId = ignition::common::hash64(modelComponentName); + + EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); + EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, + modelComponentId)); + + // Check component registered by sensor plugin + std::string sensorComponentName{"SensorPluginComponent"}; + auto sensorComponentId = ignition::common::hash64(sensorComponentName); + + EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); + EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, + sensorComponentId)); + + // Clang re-registers components between tests. If we don't unregister them + // beforehand, the new plugin tries to create a storage type from a previous + // plugin, causing a crash. + // Is this only a problem with GTest, or also during simulation? How to + // reproduce? Maybe we need to test unloading plugins, but we have no API for + // it yet. + #if defined (__clang__) + components::Factory::Instance()->Unregister(worldComponentId); + components::Factory::Instance()->Unregister(modelComponentId); + components::Factory::Instance()->Unregister(sensorComponentId); + #endif +} + +///////////////////////////////////////////////// +TEST_P(SimulationRunnerTest, LoadPluginsDefault) +{ + sdf::Root rootWithout; + rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "plugins_empty.sdf")); + ASSERT_EQ(1u, rootWithout.WorldCount()); + + // Load the default config, but not through the default code path. + // The user may have modified their local config. + auto config = common::joinPaths(PROJECT_SOURCE_PATH, + "include", "ignition", "gazebo", "server.config"); + ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, config)); + + // Create simulation runner + auto systemLoader = std::make_shared(); + SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader); + ASSERT_EQ(3u, runner.SystemCount()); + common::unsetenv(gazebo::kServerConfigPathEnv); +} + ///////////////////////////////////////////////// TEST_P(SimulationRunnerTest, LoadPluginsEvent) { // Load SDF file without plugins sdf::Root rootWithout; - rootWithout.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/shapes.sdf"); + rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "shapes.sdf")); ASSERT_EQ(1u, rootWithout.WorldCount()); // Create simulation runner @@ -1175,8 +1322,8 @@ TEST_P(SimulationRunnerTest, LoadPluginsEvent) // Load SDF file with plugins sdf::Root rootWith; - rootWith.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/plugins.sdf"); + rootWith.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "plugins.sdf")); ASSERT_EQ(1u, rootWith.WorldCount()); // Emit plugin loading event @@ -1233,8 +1380,8 @@ TEST_P(SimulationRunnerTest, GuiInfo) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/shapes.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "shapes.sdf")); ASSERT_EQ(1u, root.WorldCount()); @@ -1270,8 +1417,8 @@ TEST_P(SimulationRunnerTest, GenerateWorldSdf) { // Load SDF file sdf::Root root; - root.Load(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/shapes.sdf"); + root.Load(common::joinPaths(PROJECT_SOURCE_PATH, + "test", "worlds", "shapes.sdf")); ASSERT_EQ(1u, root.WorldCount()); diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index 594e360763..0baa713665 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -156,6 +156,7 @@ COMMANDS = { 'gazebo' => " resources such as worlds and models. \n\n"\ " IGN_GAZEBO_SYSTEM_PLUGIN_PATH Colon separated paths used to \n"\ " locate system plugins. \n\n"\ + " IGN_GAZEBO_SERVER_CONFIG_PATH Path to server configuration file. \n\n"\ " IGN_GUI_PLUGIN_PATH Colon separated paths used to locate GUI \n"\ " plugins. \n\n"\ " IGN_GAZEBO_NETWORK_ROLE Participant role used in a distributed \n"\ diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index ccdcf7b8ce..9cc417088f 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -57,6 +57,8 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Visual.hh" +#include "ignition/gazebo/components/World.hh" + #include "ignition/gazebo/Util.hh" using namespace ignition; @@ -279,16 +281,6 @@ bool LogRecordPrivate::Start(const std::string &_logPath, common::createDirectories(this->logPath); } - // Go up to root of SDF, to record entire SDF file - sdf::ElementPtr sdfRoot = this->sdf->GetParent(); - while (sdfRoot->GetParent() != nullptr) - { - sdfRoot = sdfRoot->GetParent(); - } - - // Construct message with SDF string - this->sdfMsg.set_data(sdfRoot->ToString("")); - // Use directory basename as topic name, to be able to retrieve at playback std::string sdfTopic = "/" + common::basename(this->logPath) + "/sdf"; this->sdfPub = this->node.Advertise(sdfTopic, this->sdfMsg.GetTypeName()); @@ -306,9 +298,6 @@ bool LogRecordPrivate::Start(const std::string &_logPath, } ignmsg << "Recording to log file [" << dbPath << "]" << std::endl; - // Use ign-transport directly - sdf::ElementPtr sdfWorld = sdfRoot->GetElement("world"); - // Add default topics if no topics were specified. std::string dynPoseTopic = "/world/" + this->worldName + "/dynamic_pose/info"; @@ -665,8 +654,28 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, // Publish only once if (!this->dataPtr->sdfPublished) { - this->dataPtr->sdfPub.Publish(this->dataPtr->sdfMsg); - this->dataPtr->sdfPublished = true; + // Construct message with SDF string + auto worldEntity = _ecm.EntityByComponents(components::World()); + if (worldEntity == kNullEntity) + { + ignerr << "Could not find the world entity\n"; + } + else + { + auto worldSdfComp = _ecm.Component(worldEntity); + if (worldSdfComp == nullptr || worldSdfComp->Data().Element() == nullptr) + { + ignerr << "Could not load world SDF data\n"; + } + else + { + this->dataPtr->sdfMsg.set_data( + worldSdfComp->Data().Element()->ToString("")); + + this->dataPtr->sdfPub.Publish(this->dataPtr->sdfMsg); + this->dataPtr->sdfPublished = true; + } + } } // TODO(louise) Use the SceneBroadcaster's topic once that publishes diff --git a/test/worlds/plugins_empty.sdf b/test/worlds/plugins_empty.sdf new file mode 100644 index 0000000000..ac6128380c --- /dev/null +++ b/test/worlds/plugins_empty.sdf @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/test/worlds/server_invalid.config b/test/worlds/server_invalid.config new file mode 100644 index 0000000000..d0371fc23f --- /dev/null +++ b/test/worlds/server_invalid.config @@ -0,0 +1,13 @@ + + + + 0.123 + + + diff --git a/test/worlds/server_valid.config b/test/worlds/server_valid.config new file mode 100644 index 0000000000..7c55928937 --- /dev/null +++ b/test/worlds/server_valid.config @@ -0,0 +1,28 @@ + + + + + 0.123 + + + 987 + + + 456 + + + diff --git a/test/worlds/server_valid2.config b/test/worlds/server_valid2.config new file mode 100644 index 0000000000..e52be4382b --- /dev/null +++ b/test/worlds/server_valid2.config @@ -0,0 +1,21 @@ + + + + + 0.123 + + + 987 + + + diff --git a/test/worlds/shapes.sdf b/test/worlds/shapes.sdf index 7c4ebffeb3..ac254fa80b 100644 --- a/test/worlds/shapes.sdf +++ b/test/worlds/shapes.sdf @@ -5,18 +5,6 @@ 0.001 1.0 - - - - - - diff --git a/tutorials.md.in b/tutorials.md.in index a7f1c5be81..6930c6c746 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -16,6 +16,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage physics "Physics engines": Loading different physics engines. * \subpage battery "Battery": Keep track of battery charge on robot models. * \subpage gui_config "GUI configuration": Customizing your layout. +* \subpage server_config "Server configuration": Customizing what system plugins are loaded. * \subpage debugging "Debugging": Information about debugging Gazebo. * \subpage pointcloud "Converting a Point Cloud to a 3D Model": Turn point cloud data into 3D models for use in simulations. * \subpage meshtofuel "Importing a Mesh to Fuel": Build a model directory around a mesh so it can be added to the Ignition Fuel app. diff --git a/tutorials/files/server_config/camera_env.gif b/tutorials/files/server_config/camera_env.gif new file mode 100644 index 0000000000000000000000000000000000000000..409b0c2b5c422661cb1c17d3de945e8ea347afaa GIT binary patch literal 267416 zcmV)3K+C^JNk%w1VZ8$b0`~$j0F~DOsPh2-00E@z0;uu@r|$}(<`90b5di=klEoaN z;3EwMB|=sx9vdhuGAk7aE11$ODJv{8J}oOQF&GIkE-f)JF)@FkGL^wIg{U_!EH^nt zI50Lj7X&&S2|h+J1xjCmN~_dMB@j#`7ECA?O=NpeDHKs85m6@;Q7IWwG%!*u zAW}3lQkJt*H6&AJbW~McRcwh?Wo%iW&sx>~TO2&fHX&n0L}PW5WO$ira(-++DQsk9ZHTdMH63n2Hg!8Pc0Vn4jjMM)J9sxJcsU<xnl(vAEyMy2RghfAuNJNB`u7*-jhG=4kPD+SEC5TE#h@{Pks@922K#EK( ziloSkqQ{MsrH)Wbj#yKUqQs9=Pmr9ulBC0wR#KFqyOgfimaNd1wB49rSeUx#nq54c zP%NC2lANNjp62?Wx#FREb)vrMqqo+i!S1D?q@}UKr@-W=z~`sN^{BABsKf23%>Jm- z{;F|es?Pta&;F~0jH`u=tIGMS&i|{>{;bUVtj_+d&i}03@U6}MtxLXuduVPv9qtg*{{Oju)y4~$Lz4p__49Cv9YnS%=WUetg^!1vdr|e zw8FE@@3YMDv&{0e%kH$x@U@$lwXUqS%<#6$?YGP7y2|FebV9xR{=UfRzKuE#=zFf;q%MC&CGj4($mt`+1uG}UE7RX-PX|H_5R^tHsXkU3IG`1kes{{H<}ApQOP{r&y^ zRU7{P{Qmy_A^!_bMO0HmK~P09E-(WD0000X`2+ zoJq5$&6_xL>fFh*r_Y~2g9;r=w5ZXeNRujE%CxD|r%fOt?uiw9b0}CEZxUk{Fh!ZPb%($`R z$B-jSo=my2<;$2eYu?PcvqKdcPDFs=xwPris4xFe5uvpSk3W7im`%I3ZQ8L%#$Mec zcgNjQe5W2xy!h$W4q7+(@mocM2n`%WpDw-n^av_+$CfgL`)-c0RSf?TZoItt^N?3t zNDhN}a~1G8sMr91K79K1wR4vuMa6#i8g17ffan!y;DLeFM;=t+bqC*S;zcVtMMmLi2Q-r+YkMv=pS?8mAIRD{<%0Ji34hAZ4{d%po_|HgnWvBNmAK`ffCdWFYOQ$*n{&`vrzmyL{dlN|Bc{0K zK&#C;VvKRl38I5A0_h-k9#%S~prn>+>Y>R&7p9o?sURPI_Qn4SpGcx+C**&tp=hO_ zRQC7b4@2^|E2bv`o8k~N;(6+_%r*bE;C}iZ+hKoK z)(f+}BKPdGfuM;-T651ax~O&7=_Y4)NzVEqcTVOho|8^OICadGPVFGJO>X`3*I*Av zsB0ft?W(N!!Rly8xq-;rr5^sa4f!`s=XAF8l1X z*KYgmxaY3>?!5Qz`|rR9FZ}TCwrc$G$S1G-^2|5y{PWO9Fa7k?S8x6G^17)#gxo*q z{r2B?5B~V#mmmK5x<@rX!Fq7s+L#3n*d0t}GA z2B0X#C~m-tSgfKJueil5a`B5^3}Y9^2u3oBv5aUuqZ-Y~#x%BZjc$x19OwAPI+jt2 z8~A_`N>jB(v+D*r6*6x%2c*;m9C5>EN9utT8dJYwj|{%bBW7a?$VdC%w#gNm(4_`G^0sPXj*fa*9;~Dw#m(Idh?s$45v89NzQVb^PK2R zr#jck&UU&}oqqJAAm<54deW1S_QdBsSCIcte(tlM0R5*x=c!ME`qQ8RMd&~ic~FKX z)S(N7j!bfqqhDNJYD zQI*#8r8kvnPHFm4oc2_wKjo=OfjU&77WAD+O{!9t%G9Ph^{MCFfIRPM&#GGWs#wjc zR=3L4u6p&WU=6ES$4b_+n)R$`O{-eh%GS2J^{sG?t6b+wS9?PBu6WI>UiZq^abB^W zbq%aw2TRz(8uqY=O{`)U%h<*`R;_)FtYjxk*~)rTih!-^2tEJ;L2mW~pAD^NM+@50 znpU)>MXhR2OIp#cmbI^SZEI&6+tL5lHnp>bZEj`DTHW@Rx3#_PW`+A(+V0l2$Hi@N zl^fjT4%fNM1@3W)OI_$zH@etm?sTooUF=@Bx!&zAc*ncl@S2yr#rWTUb2&OY-Axb`N>jdv68C{QbBf)TmCis#neE zOS}5jus$bd4Ow5#y4lUF&b6+0&FfzK`q#h?wy=jC>tY+**ng#UYWX|tW;^@Y(2lmW zr%ml@1Nzw5&NihpUDf~M+S=d_x46em?sA*E+}cjJy4{;;Wh?mH@Q$~<=S}Z=+xyS! z&bPkzO5bJY_uc>(HGv6Cq=6fJ-~ms#!WRzjeLMW&Oyzd14b1S0D;mLxl&Z!zuJL(( z+u|S(xyW-3@sgW-o&EoQ_sCbi=lrgqf>XR;1tnksn%kU$5^#V7F#B^rAcc=uc02)R#W>rbGSeQpY;gwQlvSdwuI)?>gAWF7~ol{p?&v zd)U9(?uj!y=x~2?em7u24OsB*c+YzUIADPZ z?~srD1nypQ2LPV&n9uyr5zqO~OWfm&*L=w5?yAU}9`BRqz~rSU`qsN%;l^e`Qc=)( zh%27ruV1+1S8)2?B z&nJ7bmwekqfKF$AM7MkfNOk1bbj!zn1Nd~!$4x8%0^g)`W0!$umv$Vub{$A|Y6pTJ zD0U1WfE4(DC^&VWXIsE|`Nl7;58pf+i?{ED(Se7=+yf z0jnhkJ53ZTysXWq5zt2YjiweXMthqBx3t)`JWniE5^Y+f)Q> zhlmx(O_IonSEOcq*iEw6i20>v%SVN?$W4K`O~2@bowtR36(va}eeg$$&1QXOXoJ4D zhWY0Jf~1VpSdGFMPK>yU-NcHpSc^rFheM!;*T?|eI08jrj#09HwOE3U$c?9%hvY|o zu?T%EPz38JS$SxVNVS6g_J-D|Ynz34WO#;Y=#2QceRn4T)A)}J8HeKZirRRHOxTCI z7?Iq>ikx+igb0Xy_=~;>kwf53%Qpn~xPe-ifn}D5_83_J*pcjqff&e5$mov^iE7Mf zkR1Q8chIPY_&0fz$A$_?lQlV%#b=7-2u0fzlD^o4cc_Q@NP$-bkq>E$+hmBR*iD@E zgpJ4mxu}SD1(PZ0fnq6wwg>{@_>C7BmSnk>R9TBpnRE`&es$<>p+}UgHg`C=cYDVH zcE^{d*LSK1n5&nJc3GH38J4?9e(uPQt5}DewR{=*gqx+6iD-*XnTLHyg>|Tzl4yi_ zNRkvOk?K}~=Lnid7njJUY%EBahG}YHcz1T!m#3!zfJu42HvvAWdK{p0dDNP|`Fi8z zj*BUk*?5ZPh+j(ij^{W6g*XH(V4B}_jz!>KNePQ8S&JljoV9p`N*J2?)?OZ2Y)bz( zlfUVj0m+HZh?}`tcRZZzMJSDx~Td6QLIdPR&-6_b>upZP|f^BHQ6_W^ikcd3Vy zooGStIeEPKp9~sweD!>&h*!y(R3xZ$L3p7UN`!{TpX#Ka{OE-Z3TZcKpd`wDxCx&- zH+&(wq89g{Mktkeg`eki0H}FR`KXfj1&`qbmQ&ZG?8KvK>7z5Mmf_@|Eb3_UN1{p! zpSqcwI;WyX8m0GUcp8~bH0n;h$N*V-l0&LgS2|7{T24TUa$Q)LQmSY$D3FkMHcNVU zbXTDFr=Y!grgS=QL5hV%SECOXrk7@sN(;3W_-$2 zFsY~F^r(_Grb{QOU+GkQq-Jz!iHs^}nOLYL+N6MqkTr*cpPH)FCZ-`sf-@?qV@jz) zicYfXrLb13SgM-+sH%WAqS|+m7El4gIswC40mOQ&#+t0iimVmTcM0007!-=UI<3tH zrkMJb*Sb`=I&|3zsg~ucVb`tZWRhB1rk+ZzdA3==*R0N}p391x#_F!}>aOuRul8E6 z5ul#=IsrB3U+DU;y%t|zN})vhqvE=)8Yr#{h_E|4uI{9t16xj%xSEOzupq!s_Ij_% zy0Py{uM?mF#|pB>Dzd~{ul6d97MrsEx1UZGv0f^!;Ix2u`cyJ2vtR$0R~LY(E-SHs zrC$W5vUf%#`wFkiy0OJtwC`F0`^vG&%Czt501mJMtO>MK%Yy}rRN(5c`8lf(t5=k2 zvrV;tV2h=W`F<4(umKtYCTp*S(zX-Owyp8Da*LaB3%7O)x47v57LZ3$TeW^WYU>oM zdD^v;N}(`2PGh@NiOWrkn^cY4SCnX9E%>+iMI~Pbi3)~y#@bhPBtr};d`}gH%YiP zVALCD!OO4isgsU-Gz%h%xC!ALd z8?&{$zzLjG=IXou8=#z}Rjmx~ZGJ?_|Ka>$=^;RU=j?py9d9*dck(beZ$Jb zTkOZlyR=9vje2azo;;3I8Ok<#i1BDnrR<%8_=niohpJ4zqAZ%C?8>Oj%Cihk=qJlm zDNc#RyEG=m0a^jHsR6O+mwIQkm+Z%2T&$729trlz&OB$Ed6gD8&9Hct;K`M~h|Pg` z&DVUD*}R9<%+1=2&E8DT);!Kdn9br0h~89-7AVf*T!-BZ&g2KrYG%&mY|pYc&sVw6 z<3!E&oXzW~hmLvA0S(UateTMIPVBJ}dHP$el zR!?o#X~mUdb=GFJ(4CCML}GVnSbuZPeYBaAPTRp1y|L@T$zjdWnnhYKtD%1Po!q}Y+(hlO$$iuZC)II1sB-^p0ic0~#Jt*mT;As0yym^kQ7hZeJYc>bwpZQTs+-|!9L4Zh+m-r_F);xHcLGCt!p z{^Eu_)#0rHIX>4q4t%nS$?1*BT^;27D&iwf;w&EFD1PEK-sDdH1$*d**09;wt~{;3Xcx1WxC0US}-sZBZ^~jy}|s{$XTa|3njY7{%$J_->3kXF%KWh-`{Ab^w+a_UhP4AU;avQ&b`}jrrjxy@Bd2L zv03oQUhwd~?CWlK?QVAw@aavfwh|w=mnZNXt-hU=@fqLmrqx-S2JpQM>9#iV_(k%Y zcJd~l@+H6WD9`dL-|{g3@-qML@-!dwH9zwz403_NXVl{p*{6Posn_}T1ry*hJW~opZJQu_>AB9 zj{o?OANi6$`G-HbN4|T02?G|S`D%~wZ-4M#KFJI(uNYkSc5lWX_S;jhN6*95dVlf< zN0OzfBp@*RNmBb!Li@Ha`?-JnyN~;Y5B$2{`@A3gzkmG1FZ{lr{K#+o%>Vq(AN|8G z{mZW;%PHZx0O9lJ&yzn_ zr~v%qM-Re<4HpIsc*TdGD1n~ri?VS^%9Sl&#++I6X3m{GfA&10AWFNXO`k@sv*+Rs z5;(NxAYnu7*t7p#%ced1XwuzBee?FM^taRC#W`3wo}BjW+smCZm%U-^inFP$U&o$Z z`*!Z#Rp<4|SiIlBhs~ewp?JLbyx<*wSV(aN!uj$`)~A18zkUAs`xnFy!2SFqP{98P z3J}2o4J=T>k{t6cLJ24A=>y%2!_X+BIM~oP4KV~UL=KPYFvJo?L{T=N@S3ni7hi-i zMj7G4E4;nL`%4AE(BqM?AJkinF9>ghkFo?09O6hN7j&?}B$<2?$t9(Pa!MzyWRNn_ zX5_L<)ka|Ls0&dfvrIG3L^DL>a$Au_FW-bSPC4gHtHug%ByYza_e@WP#n_XKG@y<& z5;Q{(MKu3WMHembF*+aZvcfUb^l-!tPoy+c4AXINLy_E?IHMCAVCeP+bqG@>=Ed#}EG83*91lZ4f^~8O1kWefOo8AY;u1 zn8u%;9kJj_Nkmv%Znw>_+lIH@kYR^|i>|$ZFUB}yFVQ73M^@Q&)!kV85^`QfZ|yf_ zlvn;$SeJ8Exn<1$)wpJwmTi{O5-;V}+KH>}8R4IelR(9AZALn2rR(BYyrA?1nNPqX zBiaAy%24JvYpu8LEW!F{UV3RshgObkvxPpJ=&{0PyKT2^YPzw%ppLpn_0}udAeal? z6=s%)-SzL61DBcbS}grHW+fFBu=~XpTB)qam_amJMMQ^t-D=VV4PK%!I zSn~Jhe`EJL*3rkz^MeyKAOa0IfdE4`I_lBtY7abI>m)cq&Ag5xX3itxQ0R_`93V(SiiJsEt4d8!gL z_Jm-{g1J&&wiK8y#Tr3|$G_hzlYI<>^!U5_tuSKR% zju1Kc+kj7QI#ncUv?%S0;|$*zQVvM%j`QqVN>R$7vEmb-(izabY)VzP2vldm!%$E~ z#Lc*-&6{93(@z~%&`VZS0xM!`VE1QLRjIL+8ZbcwPEf!%F7T@+WnKSFeObgIPBwy{ zNzhsayA#G;Q8<;8YhBCME&9<9I21M02&1{prJ@Oc)Dh!mWh=H+Hs*7NHB1gQ&_=*G zPh_!rkLfUrOemSvxF;>HW@igGMusS~W}+)xrD-iEHuAIARVsFe_9;>>*Sj_&th#j6 zsvil4qdvMD>4HMf&7jnWDP`$P<@-y?hP5)v{q9RT3nGY8D`-3eo-~aULMwJ^sKKG+ zQH-j|HL=z=4E3hN2nI%R=GVfrt1TMSc;3*xk%4&2W9!QL-s2wEz5c53h0oR81EVN? z1=9`gh9^A!9*3HqysLnX)1jV;T!Nm!snNb8q3s|6-TE;V} z!uu}VcG$yrY;vMToXZjyx^D}@Z;@9}fht-c$Og48q~|y3;6z2cl_qTy7gjJax4Cu& zJ8DDuTBa_7B`gyVOP*EzD8l|JfPNmJ9ZO0iv!3|S^Q|&Wi#y!RBwEE_+5nKhSwco% zvcP5AU8EsRW->)m$7Ji!Q884-<5)l|jy83+v+V#ok0rLN26qxOjO16t8i%8s-VQ@7 zXtHu<(6=_UqHLYaZ-aXUT&@6EO6XaICa2ETE-*L!%j5rS_Vw8Zk0=MaGJ&oveB0VK zwOFEB?{HU~Lf|Rgpzdv6bLS9NkBy9zdEL)GhHsa+wygH9-0LiZ8%+29XyTM6D3tA z5jlIIJaRtXn#w6JxqUe!_OY*q%h)z`z8Q^pePjRLE7tDR+)23fm}eX9cs+W|m4EcF z6rcInhW=Onp6%k>9h8o?``ic5e3_?R=@7?##8EAQdmpXy=f61B$%z4H42l9G++#%EJ3BAT z!YHIX%}YeRz_>Id#8fn+JIpv4OpL&Q#l-jvK&!*?FvJzX578hH5+gCp(8ZGYMZE#W zj3AbWFvj>G#$-gsWjw~v7)E8ZjF&@2{xd{GEWZsvy90{EE!4to^v1|5K;4Ug|eaj7qdL zJy|)$9Ry2$1TM+c%+2J?&h*T(n8thT32YQf2T;m40dQ?lt1Wy0DfXsC1%pI!6%FIE2Yz#L{mF28O(1T9Q%uMKzvGz(oW~x$LfsE?2MHl`Aw&+5U$8c)J)9OJWSR^%t69D#2iWkx=nACPok7h-GtAX z{K=n$ONN`z-Au}uG|k>zf#5VyWvR?2)6B*ond3A?sMHH%iBKD@#y%P}KP?bDTmnhEwO*+V9&GdxH7IjZg>_+vxJfUn&_N399gvkN*MjACf znRCt9RMGZ~#MGPs2?)&-RnqUcMK?Ul=ETrKlqz%bP>iEe62;Oi)zU5H(k|7|CDpH= zFi#?V$sT=C)pX5mOwIoog*?b>&;HEDHPz8HHBL43CA=(=vV32C&f_CDp{-y&)m2Gt z*nFMDb=6IAEK>ha)yW&h&o`x0^EAyJUDi8A)op}4|8!3PmDKrkPkuevm7R%#t=8_$ z)-Pq*RICu$aJ0%BQ{5cU!{pJ5{n(C;S7k+3HkDU)tyo?S*O2vApvBKIqb*X!oH>bON~`78Vj|trHQm!i-PBdx)n(n*b=}v6-Po1g*`?juB__aS7C5U> z%+-MJ`-M{oVvt;00#j243Ltv^bz}rc>*}rE|DV>^@>r(~Q+Zj&0vdCDy2w zSfsp78Z}mU{a@aFS^y4Uh^tYv+uH6j;6`=e8n)pZ#$g+a@kzDoJuUP; z|8+~m%UnW&$2HB^(w$t=Rbs`2;&CL$BA!I;6Td8W;Q?-w89q@2&fzc?<1r><*4<$( zYmEONHoD!VU{vEm3?AZ6Jlx(jObs^Nn}poD%tmhvJly--E@Wdj-r^WOV=s0=FfQXn zR^&x?;6l!?gq034fi!19u<$d$K>pDJRN;@s<16gV3;xM{Izdf#N8iJ}-Nj^i<>Jsa z>V$qV8Wth{AzV?hq&cYZh* z)?#0lX8|rIa)v84(~ZM>VV_)PR2JlVj%WXO zwmeX5=ytB)h}LLS+b8MJXF{}Qe-`PHu3>-%s2;}U3qhz#Dd^V#3=Vl|`H^IwvgCBG zXtVn}oR&UzwrQrL=Zv;#Dc;)rG3k$Sq?eG5qOEM!J$+R)37TGHS^#dn@+w6#wG1gP9mF zOy#Zy>WThp0d{6P!{|+Z-W3)la8i+cR_o1T>$isN$Ufb;9;0P}>fjg?>Z+V@COAo( z4d^pFBktV__Unyy=J$k6AZ_O++-XnVCnb(oom@cU5ZkqB>{WYg$=2=2rfmNd>a5G& zF=@)89>Z%8;S_UTI8lCRNu)``RpH{@ts9St5nTZ28vjPx|E=B_s<@y9A6tO@pzD zdW{YE?jj5C@n&$5E^qRAIqojHZV90PTj_4R)F!%FB7W2*d3E+O1m98$hnsdOY>SiM zuFq<)11m78$fQe~t2aY9454vQ8Ff!*n?4WqVz=R7?;K!D6V0A8T_*CN>Gg@Z@G_D0 zyo&Y|*>YibYGdbiSVnfGc{vexBxOVL++iZhk*)_b^PdUlAV(2r)2?ctwgJEPJJ0hj z)^<}O_HO5Q@BMb9`Ej$UF5VfQH)o=3dGklo^-8ii5J@Ua^C|yVe=|?&tK;sCQLFd& z5hah#cYW{oj~C;A*O>Dr^x(GZb(a<*XY%wZk@l`?88fhMnRIhUC{BU+7@zPKqxN*S z98PHs0%q)vCv}h~`WqJcj8S$?>Ff(%^&ShJm+v$USszS)D+}K=8XNZyhv`XM@(mvv ztp6Eo;x3`Ds-idh20r?L$*D|B_jYILO(Sq7m+zDhajh44BxiQIe{v01pEuu~mv?DY zk9djKcqzIKJtuqfKKsQ_;Is!AE*t1&L-a;!ADCZyNuK&0`|u^7_GKscxX)`j_xhem z@ty&E(VC)z;|(y9;lv+v#)o~T2JfUd`4f3A-QjtvKlA?rH}uo59EOQ}&wqA;^Zl;R zd`p^`nQ!=Rp|GHLeYKDM=*M2i7njvocj2#{rk5YAH}q$d_YXR@%9r_ZPxBN3_U9LL z=~sVRCZkd(bmd1A4@YysSMLCOdj!KY%hCRZk$ZOs2o3@V5-g~K!@+|E7cy+#*jk}PTRB+8U3SF&vB@+HieGH24PY4aw|ks}=N?CJ9- z(4azx5-n=!~!F7+)(v0=FFNm zbMEZ<=FX?0N0TmX`ZVg)KBIna&H3sF4ie}R?uwS+Vht8BuDu)fuWhnwe-p<`&^Ybd z#}k(ID-e0_hR~Dq6|5C9#fcTROMWOBd&R^OC(D+=5v1$%>esVx?;d7o)$-@luWz3| z>-YL$u83W5E_Ds1wb*~+IV2ol6n)i}b-)Q&*MWPb1srn_CfFQ?eEk+tZ(hw+VS*3^ zNZte-l=#?qBNn8cKqU$!fdl)=I3tZU+PG4D_vyGJk3H&`-;FhXgcU;*O$4BdxM2id zgnChkR^-CdNOLy{rJlVw4=`6irkUY4Ve zb=r9+o<#vEXM01=w&IFr+IE|g0--qKf`m@VC81Q(b){V)J_I0`BI0%yq>N6WL5ZD; zDd>n6O)x+FNT z5>z5%d--K-qrWv*A+uUJ7;kkNPDq?yRTfOJbMOL+Z$qAnxz(ekO7H=<=~{d-##6a! zF2@~v%oDm9Ys_s&(;~~zmH-!on2Y~R4y&Gj4aqK+o~TwTVkrNW1i+U2Fr!|m%c zb(PX)5yJ=(o9)Eht`M@wQA<7b#vfaKb)Ha9ZPSn>Z-DK?UJ`n+R@5f9vvRk&l`@uN z+w9zNaVtAF&IM_iufUE9OZJ)V8XA$=8up~(uwQ_~f1y*T4hSB*8~k>96v<1%&a zbjcGy%JX1+tGKy^Y4^xn4qLdUpkOsv5!aKS%GUM0n-$7OL^tJ`~K$R zk_$h)X}td)(^XD?u)(N66Bqhd^)kx#%++VNo8O8_Ml7b{LCO{QCzA)IUSQTsZ<2}r zH)`VO9sfT3ZU#?0{q-wleEk0{UCwP=7C4|7k{A>)&$&%>C_`AY2E!Gk3C?;263>zR zRwmdr(1B;6o>DumZ-ADWMH4uA|F4fkrDxD zZ3t7C`e24O)xFJvVk;brTGltx`3rReAtJN5cPzyqZi!aBBOa>~#VPWUcvZ~f6_b}m z?a2{AK2rhAtOuAx(vT|?B-0Oh6D8LT%!Xx5&Y=imqzmGPRNC6z9|0-KQR<|Rrkr9Z zNl6kcV#R+Z3Seac)jERY5t1{tG$?sXM>AjB%*u)zTeQ`!0?C{?Mj%^ryP70jFIa5S>KKb77en@M7cbtm>?6r28J(!;-g@a09QD8 zE-7NA+CaCWDb0PRaF5UYr@8dWPY|$jES~CFmJn#EGun)iMG~9_+&ME(ZE92%wcRa$ zrLbILbSoAp6*56M(2g zOEoNJ*n*nAx`qEpS`GthVwi?c#W}UEfP|`4^U5Qtu5?|b!fIBz2vb?wtE}+Urdq{D zOHGCcu81Pv>b#?-HBz=k64RYX?W$QP;#IGntq))Ox`M1mpaEF@YgS(=$C)`av92AK zTnrRGd_}~Ewu>NOc>>DNZnn1<>+ENPn;PDZ^eP;10AK;z0OVSEaZfjm@nJzw%cc)x*0<&jA#jDO-gBMzC0Aiya^tI92RL`Nj9jN;bR!-V zO%O4)eP>3|R>Z|Fc4oV*?x*6K+mI5sy$)todejDN&hd!E=2ujzt*Z3G)~!73OF1mS<7qYM98$ zZQeo0xx=z?$w_(h8H*K_Ho+JY%0p!om{1GSWahZb@7r;Y!#tE916hzR)N*Nyd{wME zV0^kV8ZU{d!@KEAZC^Yj+`3snVJT2V0Ge?_q&E;P51F7|KJ@XxEapY82GN0ZT63Fg zWMQyZ79N;}~NN_kEA3V8t%~*emi`&s0w*BkhU@Ior zqr(4IbA<_RZ2m9YvktZ}BaP|i4*Rt0Hr1(eEpMsqn%83Xb#bxc?PFtDzNU3IzoS)w z2$;!{>5jBT56~QKYA&`So^W#`yy6Hat;I9mTuoaX+!g2eE4NCmWNW-cmF723 z$UEZRiwEe`11;-@V+(64GyiF+K|L^rz8i@xzTw|VE^ zMmof?E%m2g9N{OYFOkvw*EO&E$myO~%vmmW&$#^M6An8+`$KSK+uY{v&N)_dj^v6j z4czOVc+u~UVGdt4>!YG?v2%-NxaT(Rlb$c(i)?JT_gn7jKDNLA+JLQJ{O8B)*4Y0u z@2#?%eZ6Skr`m&E^O{Hc@Noxt;@AD}e#bZUhIjpPVQ>1^A3pY`N3QHs?|^^befROD zx#5*d?8KL716{ZLCpEA9RdK%a!u>omVUtzhbN%k8J$UPDKj{qzmhnd}mF?rZ``Lqk z{PHz_*TbJ&@ok>zR4f? zxt<8J8T?HePt0GxS>SeLSpG?&wqTZDv74mDTMUk&kkFtR{)7!G(|he(t@+%*jmliL zMY^%s7M9=IO#l&|pY3Vc6pCLTB4Gy-9PmY<63$)*BA)5(Asc4k1fJgnNPry?6jtb6 zp^>2_&d3a&Axfp8Dy^Zgksc4i;qG`1xPf49S)rv}-{Q^Q__1OK#-9}e-yznYA&ws( z&SEPD)+bULU|m}ymdYbK&C}?_3UD0Xu@5I+qB53}CZ1t3j?zbbP4!Wt#Yq5bT#i9q zq1^G}{pn#8#-2AW;q=km9|l(NdE?CyqWO8-U$tMP5#HY|6|ERo-ZlT%tt}%yrbi|= z<3By4DBVf~U<>s{n!-hzN3_cRNTVkuA`^NWIpX3g-eNg|Um%L!Ia(f@rJn5(-Ykw_ zDE_jWde5P z0S@LJg(d49o4ZU4&3T)tpk>$i-(NkZ+btMgW@av8X8hS9Y5D(zv4J4_0UT&9oD`RjknRbc9uET(Oy=9~zl> zbs!b8WoZ5!U+$fJO&s0*4^If)uz8q6vZK(2;YcPA82%k3&L(+M1y|Ol6y4?%t)Xsa z3&m&yTFFu_|$2SxLITpOn5Y1xGYydnDlPJdP(>#^Oo?4)JR;p4I69sd8F%1xyfIiN6|2Zu%}O`NBP zLK6&zp0FLG18|E)JZ6fvNqu(2eTwOl4vF!N-jQD4x5d@t1za2IPBF5XM{vs>4r!8_ zTfjXg%2mb+45ZKLVr6RQmZD{hmYx_&DWbXrl~!r}fT$DwWrW6~iAuyr393ifCwZ|b znRZQ$WoMhJ=>&|01MDKd9i0EDz>vY|M+Ia@Yyb-?sngskrU~Sq{v4Y;sP(nm@%d)9 zXy_VZTDm!aqb91CEh?k>(N^{cl9t|18VRpHqN|?D3bjhN45zCy&ucE+Ws2o7y`coA zn^*u_sbuO3tSY=^g@>8S(|kZdQeddADs}2+yEXsd&*ka;rK?8}sxii=R1&MdHq){8 zTC%P{+d*dkjfVzs>!8Y`P6XKo^hBDvTS#)Jv8h|Aw(5gc=xDJSN8INdcA>|v+rcf5 ztvcpn8YQs0spSpa!Tly{wr0`s=*#{q&8}#`3hV%aXSRCM!8&UgF6k=WXKFqm|)D)QYY$pEgnhH7QxmeZ!FaNZ%yrYOOl)+d4D1QsmpRxXBJ?o@7o!hI~z zb}r3+F6ds3=<3)Ad`-(1C_a5a>KaLN>COhg$aRJ%--)U&)@#3c>$hI4gASa=3a$b+ zEyb`a+16+2#wYtYFY&ezyoT!7w&BqxZ-Fjv^tPt+Rxa7bru0s4^}-ws0;JNN*0$7( z1{~b@`cHzsCckxr^;KRGhFceQ#E3@bee&+Q09LDFt9!O;>0+8e5w8dLFRCJ~`O>8R z8t|ba@COU)^)_%_QSSqL%n!%Ukg)%tO*SnBMO4vAT*jg5&us)>w&3y7pSoU!3drdP za6}dtZdf+JZ=T8trzpk5n|(!uXR0AFCH2Hx7$-EXA-3_VHb_ zB5ZFGDEl~OsWfu&+1)6!vIH(1yooEkeKOCca3^oEC~s*;>?nq%s0E;}@bd4M@~_3x zU)NPFJ7(yR+)5oQq!l0VEldBY5a)8a?DFE&r!R|XG5Tl&;*&%eNkpk;3zuZ6w8gP~ zGXP4i-Xht!4yTEPap3aoiyoV+_QwVPW=LQKhR$#}f2;+>2HWYUWeS};C+IgH>I&6o zY~*p_#D*RTu}`F z#;+%>aKd8Mi=LTfkPKg@aVckuMh7NUHexw%+-RXQn*d2lTlFIQuuBswOviLe;Tk@> zYE)cfS@X=pf#F=i00;DdL?~PqZyiVQr?&Xtu@$wu9WBj~DnG}}Qt=Odm+>X5Ysi8O|5N}N<0Mt0aWvp@ zY-oTAT=crV>TO4Dbn~{M3%MnD13Fj&bZbjCkOMiO12J@jHnc-K)B`(^10Njji#GKN zJMJ;GLpK@}9i6*RgOu#2k>`fomv$!4-Hz!g~@3w7v$I00ou`1FZd&v%VCVfbeH|#R>J@Yju|oFmVIxci$8pGybeBQ*4iEwo7*8$M*V@>54{0o|7w)=tdTDM??*} z>Lw^aIM}dZLWKws1a7D>;oyW13=c-w;Glv72ONlb(qLf-I7AhOBm+mzlL`$QCOG)u zjZXxFDJ7^#=4sv)4G|zZ7?KSfxMwC0I$&Vzln4hCLiQ|q)8&MM1#vn}sX_(BiYrtY zY$#R#>cXuHCu~q*fvZ=iQMso4u!3z`s1qc7_%KlJ2)lPdJM* zZQFb8u9&+)uHxN;@3Q^<*Y|I>D>hb8UU1<_4ko$cTqyP|!Vgs;PFR7n;lQ&FiX3vP^=T<%l?4xd3HkbSz4};TpS($qzW-;5-5&KpmdC{xg?+qGG;f3Rst)RBd`MJ!jvjZ zu-tSBCzZykZUu;N!ZSOIVuI!w<$~g9QVC+3$Ib>FkYI>;hOoq#8`2DTh)Hk%5(=7A z8X#+2r0T2`U6;Vxu%QSke5+JU2a?d#>KNpJpt8nojL8%IifrT!2t!ucm051t<(H#0 zR_2*$uDNEFVb(F_lj~Y+XA?`TE5=rLjuyBNlFODM=TLgeOtqSFinmoGpif|8&YO)B^x89oxUpbD_BP>)lDBzXJ0_lgMH7-;ZAi{hxE zii%>83ok1yPc`N)t%ySmYg%Xr!mY5xq%@J_lymOf^Up!Q4Op8=FWvOhQNua(9Y+w3 zF5-Su9fa0}Gup7AfzvD2W@k@zA#JnN0PCi%bjpEpz5PJCgEH2XO$QAB;hK-EEU>^3 z@zAj(D|+1kJiC;t$VP>H-8h>*L$VQ6`{nXYMw4`-S3fK1BtATGHYd*XeoM9U)PKey zmz@pFE=szI3t(QimZ2@HFTBxNxakDgSwP0<#5YN9LSQ_=%YNTxMxjTsZw?vM=EViXj=uN$ax57sSZ^@ zQ4wnp5?$h+gWLpNMLb9V2Nw|yNeC@w(TZDim==v~3_}`wi9m!V!pxxvFc3T;Umi58 z+qqGMAhhEh@u;&7?vamu{Lu&V=q%dRiZMYOQSBV~7(>cMg^I!d3I{B3DT8Q$OFgJk za=Mg~2_R2uI@F3+oR=waVG1e%WZYNKcEyM&DnhAjPy<3K#w?DJlrQ-rS2!R60Lqd( zpJb3)h9kk?RPHb-de!SBC@UucO@WsS--~(SGqr@H-z%v@tjkPnG8%rh`Iub^j9rfrou^Cd4_EDSB%*~1fLmWZ6E?O)U zXKsc=7iS*kk&%?4NpPC9OitxvmVzX@Hl)N(IqzcsW8DA$`gBlnO%h__N+Lo3C(!y0 zlq+P)kUlxqAc@XNcMsH@1SIGzuU0F9GsPTCa;ov1+VToJ*|{9y8IL-mjOY!!bj5s1_Irx+)bD<`pU3eJvqQWR zmX7Mb-wiH9WvrM}6lT==;SY<}8BD8YmqJ)^^sIKN+(z|!7h;Yqjkj{^Z-J{UxXzWh z#T`;zL3mQ$jc~8UglPgx=$8fVu91n6DI8Z+C7a&xJi-&6a>%j~sg&uo8=9o>s>C5E zf~C9*>eGT&rCL&I7II7d)IffqLOnKd)q4X>HarRlKeXlKB{F2<0$88cwS8PhpOX@o{Q=?03| z-AhK6J2a-6J)7g*OPX?uJ!UWcHVb7*V~VN?m1t1$*C|l>S5t+WbSwkx0AaRH!OME! zm{C+`lkB_5;- zaVMP5R^T}tu%xw}Q$0{AmRsJP??1DB5<`!hY6dkZR5zy8sFi!&_0uo58{);B|8ljF z=86RVjk12zc_4xrIs?IpOb7oujuH;*z@d)jf*+jfa!t6dculgw*7jMwjxE3$_$+Dd z#lS+--8aYHD%^3&rbXlum(csuE>1xI(1@ktFIBm%8hSUOMs=mjHNENmB(+9#zg zThA$f#c<2ZloKnav>l?%fL$JXa8k<5fD^5ODrF?VY0K{ssJM-_s$>AahE&iFa&B+JE$IOvl=I;a85amlZ(+APYq zv*ZS7E8iV4_;S1DjCOoH`-hH}RjN=6#!b z{X=v0t@l4kbLOt@Y=zzk{&tV-c0=?`ETy6(;}+2Vyh-CeOXZlRyl`UBiYnbcDMM6l z?`jCjGK=Lz3*F#F<~pUcHcR{eHcRpJ=SzGkLO2V+q$b}S?EKUS{(KEL?v2dsZT(&i z%Z91pRt^91Z~u(2g8J|OlyHMyuSRxf09Oow2IG*rNn~CG)h1&~4zS*k<4QcRO7JO& zPQst)M{sUp`5?`^n5Ks6i`-65(nbrZWG5ecGK_>~9uo6qB32P%|?5w(e&EAqujsz)l=miw{427(v zXF?JFz%cH(1)r+pB^qa+Sn-meq65_sTikHu-cT2LX~>jlvg}8+kZe`(u*fiN4`T_G zqDCbI>B=Gq5u-#AAt0j~xkYMOb9?T&jTN@j4<&czVDB_RbZp;tl(0OJINleqhm_Z|`;t-O9)xNA9Wq zY0}uOzvj!8>Who~>&F7Dmjt3Sq)~JDZJKn8oZN3(TxVpuk%3mE^yUv9zp*8ABpk;v zCXZ!TxCv+?t`kksf#|WhxXu%8#}mQM*nE=2rZCa**wXI)az_Cl@Go+3ul#B@ z_^LN#$HWG!>qrrE1Z%?1F)!F6hSZ6MXh~caYmAzsJEs&vcRsMk=85S^r=esfx)^hG$-L(R09 zLNrZhl6A(30R_n~4zUWk(1g;n6j^Kwd-C(tve?!$A3YE{j&zD501UyxIo3&dwkzcj za;N5wLjF?@r)@_mOK<{j1Sv!rxz9y?X&n7NI!wy49#xj>>Jq1k- zFXf5E2pknD1mOW-o#EPrI0SsF8*St%rLY|IFk+C zFxv=}zR>GXk?1LG@fMHI$YAhMVROj}hXr9U(oWV|n=~v#E6HR@EhZ>)c=aS3@Ga5t zwpg_j6X`)!_3TJ*5l=5)n-f;~wP>?RNk|mmt}_%{R1xdZ9vKM~rK=Nbr#x}5#HzMe zrEqCmXW7mJM|VnMN>H*wFiWVClK2j@Y_W!Z>PvzVBS%)UNbA2=F!0K4$ev8TK<$kG zmNxA0?YaoIYX|K78Vry!=lmMRK^Cg@o=q-XD{b*&&pnT(6$um{0eY# zC9!fXcV83kFn4crYcEELu5U3@k;=*UnieuF^WyLnI9m**ZdB25v1DmC?ljB0-p+qx zY;Bq5EK+G?8Cb}g)Pb>$DKcc-K<#&}4=%#&tg>`U9Jg!NLP8^G>7MI!i!+4(r*!m4 z_((pHL{Amg)|GtE%zV!`R*@@nXGM1Iw`hP>{zUKm#MC&lQ$~{wcS6Vjjiw7HVDFwS zDyu`47H!&`bxW!e3@v4CnNop=>OdP9%7|AI&WP_KBB~4_H6z7uYs#Gb;fXaUo;$EqA zhoiTdT1`xyaV^l*5l!SHh1fVjGA}0CUHO>c{`i>P3}F-2MG+Qv8re?&XPFbH^8p8} zhR2EGIJ9U`MEH)?NwFV0GHzxyLfo3@!?m%Hk@{;q0x~Vr?2jv=QH;;Q) zXpgVjqq177V=_h5w>NgV_UbpS5&Agl^lB|m&X{>&M|W2bIRUwvM01-hsKN_R)2@Su ziS3D#%h`W527yfufcYnLN~IzJs^@_EC`*QLrzydFt#RS9Yr(8~ zQB7WP=DAGGd(~Pm(=~FZ6gjsM4a4cM^nW3Z^7Lo7(T`+}mVU5`1xajj2$s?KpzE z+*9eh$?fXNk@=Y&bWcO~X_x7Qf}(D;1un`=8cL@*3~^UfGoYL@kb;YmG(dmOGKR;AnAwIGCDF z*ZNs{9qt;x_o#n7pf!EhIQ^Kld@rV)wpU$#b=k@xJgp-6xuOL#{!D3wt#x`}xGmr` zUwT4T8l8x7OLXjqI8FmB$+_p;-Fk_3-PsKd57FpL#v~~s5=8qj`Ot*S$GXT(UR#gd zPyH@qN}&Cs=pxarn(PdWOTF``aq!WXdT@Wd+&%2v|2SYvM6%O8vJFtw#af}MQCF!m ztOHqfJCgPya0T|AuE93ItmKN2%pllyNc9eFndTNP<&%@D+Ai6?Oq@1@eTbAs=2Gy* zZPT&xsVpp@LY2JNwod3f7u53@=?40Z#=GhNmYm!zr{T2s@@%WT#h1xxo>%zW=KU{l zh1Jzvexwy2qr(Y>=Uzn=S$C$k%paUDJsL5D8`k^%;5`szXl{$lmYw|f46mLunU(G= z{wTUwD95Scewc+{;$$9}pPD$_8u@FB zC{ zG5n;vWyK|UoX=3NYsmG#7AyVTh5({Mg$NNeXyAab2SODHHK;h)u)>511S?jQC~@Kh zj2k-&^f(ctK#UPYj{G>#qQ;IBOGa4#N%3XOjultR)L6m7h7}`vg7^tEsL-E1M|{}u z;V9A%MSTu^+Vkj#pGh|?ZR+$Xh@wlkjsQ{hDpsvUB?$EyHYwJxLAg#Pn^tX8pi$py z1sYcD*t>lD`uz(yu;9Uj3mYCf!hzz&j2k&W zul@}!T0+;LQnQj>A=)bGr&aAjh5bSGY^}9F6Gbf>aBrVQSEx9C+yVy;0+%~K2yL*+<4v@|e)>grlv`sI|Vauv5~moQFQoCH-07vrv|0*P$0$}Y=eVoE*> zZM4!(D=k~aN!S;Zq;`n^tzTC%85){3o*M3yX|~2KmxYzO6q^(FkQ{i;5&F?e^}3{| zfrKuXV0M9WFj9Ag@~ND>0BeBYqKf{f5u-Ons*=6^^>-je1O11oOpI1+scK~|cK!!F-FJHjC!A?pe9=qr9eCeM0n(@6eRbMLada`&SyQG9+llW*<1P5Hv009aE4!e6 zeeTK~hTS=cQ+hc6EU~hY>+@g5GPPIMs=jWk(6-->`)Nt<&U^2^Uxu5y4weaf@E1;f znpCloK3I!Z%`7&zWJjHPg`?a)i@5~9nna>G__Kzk~9pZ(y6D2WkHI)dYldN|;cI|QlgF|45}Pl-y-4ANy>^Wct9 z!?fJ&%t7U%5xSZeyxp`2c1K*^)H!zza*yKQfgF~SIMqiZ-9sEsERx1MszhV>$%zCskhmZ`DY2st!bdopVw7VJgHX;HeF?uAZ#Jp_m>iI|**dSR8E`NiH&zQnShi0|T3=v1VnxRBMDr^IQ&D_pH1B zic*Q_3bGN+l`JVdom>-HBNEybuj~z)Ui%8)_$tk?9wkkV3cIbkB=Ia;!LL`w)>yg> zr=yeXoKn2<-!)yWOPGzRbO-(lu*SZ zkb)4-PSgAko%XcOIF%TcvAm18aM~e7pC`cg$o)QV1d2uDjgwHn52-U)KDa$`;gH zM!eR7(?qV+%vme2!7QB0$DES%32*lD-ggwYRJr*{a6`SKcG?$IjZm|Gfs<|ja||fs z7CWvz$CQ(IB3F<`gRx%5Y}o!dbyci-N&*`E4TNY@vLv@fkW`Dc&)nj=5baE6Z(Zx@ zHdGe~_6#?@mMm2o%C*0$`E_7!wtLGA?Pwb*N47$&>n>!ij6%;ZtXmVXvPL{g>RHxw zR*{&X+u-*-N6>3KkW*^{H%NPD(aMD4_tqm3&q7+nROENS4#d9AM(3%ap6O7#BRTF2 z)jhy1=i^MhF`4KXxt^+k0}PqN7d1I{|J^pJ;<6Vg(~PZH4&9cQJeasVP1y@I-SZN> zUKSm@*v_uG*QAZ}oM+~|huv>r1dHZ93n#pK7COzGE3Q{ETQCi7;=C9Ctv=fxv#Jtz z>J=%rS@6uQPd9By9A_LS`e^YaQg6wNiwP6Cd35iDYY*+ zD$+eVxk$7D2EfzrDuS%oTpmaZb{TstU$#}E7PH1D*2*hdSF3D}c_4{d=bZ2SMuSds zvV_;lhhZ*thxiq;DIWEsQSM*O=BE1T%^`uZ&W%f35vw1^Zu}Bl`mz(h_T8-@>??8q zUhE#5yckZKGNVa01*rPLBzH+Hgfs(0UG-Y3$>uQ7#|ARn9LJ!+;{#oX~o z`R4`eDdoe&#>${{koucj*CR?T^Zb8h=l>6Yit#0_WOP|$BOZtUOG0Z4{AH#?g2fOWxYew2pZ)?Bk>JuCGVa28T4)fQ^P zU`$jVs6~4{ur>ig5>ADJ9H0<@)_WTPC|4vM%OPQc!f!AbVkkjc%ST)LaUBTbMfTEm zY!`#TbrOk^MS!C)G;w!$S8*!=c_8IgVPO_+MN1aqW$PmUNaZJmCuB=Xab%JAg*Ss1 zBzH(6_eU61S5;CMp(lpNxD{onjM4UZ#>h#&)FSIAD!xP|(TGvLGr32H`(9$Ty`05nEScuhlkVS9}JigT2)pW@Kt4_=0BF zi6)T~_hAzSl3S(7XaM7I4)7^t^MpDAfddGK)ny`SQHxQcR$lmpU`P~cQF*>nfL@qZ z#inwD$0AgQj4O#4%jlA0#uPfka@DqXx6+XhvVaUVewKujBT0t@#x%KxUriwz>v0gr z0Wae?kA+eo<3W6!r2!zA9fi0Y%tS^2xjqmEf>J5}VsyfZk;qgF_gb}OMhJ61Z1-So zvv7E`RCmHL2zg_r_#SF!9S(3c?WZ|jbu+QpOA6(S)?-00({0|kZN;cb9M^F)7loBn zjH(k?K;(=pnR%P{l9hQ%ZV_|E5m?CcEmKI1Z>Ct@HGhifUv^f2w2@Ll=XDOD0`Nk6 zgQkvjBZyG>5K_5^1M?hcnU3BeeCPpo*^zq(a~)v`cKgwS!%1UcBrs6L9i5mba;HYa zrI4L6VQCjN$Aeu~m~qo37O&`Wx;9Y22x~ASYtln36a+$|vU*kaYny|BAJQrZC7zN= zpUG&M_eoKo5t^w|U#qlBx0X@+msW)(B?0#TA!{ZjY9Tw51z=kP1>%AMGe%m(n{G26ekt_T`3DRa7lm>;*E1{GIB`ks(^BeBCRr#WS`12y1=c;bdaI+8P7 z6PfktY?O(gVahw!LZqT;ZGSP8wKNsl$e?s#JW|RVpn@`Rnk^tBF0cWW%K<0I0WW?C zkcy^(<#D0Qq@n&1b-cL|w3&j4l5Y$V5t!(1GqxS{@mt85G5>N-63S^gAwU(Aqn2Zj z+oT&wnn|Z(SnqjkA5@V@sFJ*~gd4>FYk2lSEYl%<2SMf)rBE0m-zAX@U(K^}BGskF>SSZptV$Y_KU#V@WLdD$L>OogOmwKR8I|f-9x$+n53zOM zGdHB>OnoAc8Yqv0VvgIIHu=aBMmZ=BHxSEFmRKYbru81)(`W?AscbY;rHG;*Arn4I zszAnMNg+ip6 zU4t{H!dP@#rxQ{eJ~ELoYe|lTH62Hr(buQDSB}1Eq2X$w7g~a4_bU_lXF}N9~t#&Lv*gV{$42D-8>pvpPD_ zx*-{ouqGE?R!A2v=e82*kt2(YC3~`eYi4Irx2{sHv-6pHOGGEthCyVroa8)fYN|4G z9?{2|t+{(QxOGwqf`NLp`ih9{=%Ir4HXepy{4ul~);p(Y>12YejSobn6-KcsTUs<%p{8};W^4aL0Vcagq0lY7gzV(7Pk zi@ig#TxD{&h}$ALS-62^p!SE2swg(tsFUFG0Yn=pe2Re;b`a${H-4xB;`*9}A|SAf zo91{YKPYd17Mq+!f>XQy5@8f#qKL0%IXLRWa4sq+z*Q0sw_>>qZ}g*DGQmd&rlqz< zy}~vnY&$NlM@nzIu(ZTA8q2XCXB!bDJHcDMlbO9SjIuCSB9^td&jZ4a%UnM(z9OVx ziZ@_KWQRz4Wo-tIRoNZofgE0UMO$Yco9htmC}}$ty2A;59Cnlq!5t^6TlE-e_bOw~ zN2!Ifg38G^Vf00XmQA_a94K)UeKb$6)MRtZK`{bzdON3R#ZMbGvC~UyFGE&k)k#do zk-yl%FAT#ntjJ~-bl8Ttn>lmU+P&e{cygv@`^jK)TBo1qKpy~(H>e!$Yd#Uy5Oc$h z_B)Q|L3hNYt}ns=J_|`y750fUhDX<-b|#h)+)@6uJ>J)!I)PvZ{!Lg}$n`Ev!(0jAY@tCdP(;*(|YijL6M)y^D;_lF^g1 zfyr_BxCnM^)vQvF%bEVAQe&lYKS^Ld2bxaSXB!~Ew8vqh{B!~xo91D^<(Rc4cyAX& zO~X0BiB?on7azlEs9I#v$(MED;}Pk&sjL-Tak*m!dBNc4L4Ws3qbY$xI%HNta?vw0 zeOw{2GNi>KWF?6_z4(|M(xgE2nBYRr<@{ymoX$nv7~L|w^2}yu+7@M!nYq+!o%td! zdvrU=X8c_LZrR2y_scz%Yq_2E9P1ds-ip83(OIYkqat>RdWv=!A+?$&RAotHwgst? z))F`skX9rwyrpS8O3ZCsI2r-R7%7cINvo`Vp%mc*6eG}L{ zdYy8C+AQr|&=cM%jBBj&mm-9KKK-!U60xwBozG=6v~;Dma!Gbu$e#_`Lp|F4T^TWJ zSd&cuCZ(yS&ggACC*b44OShfF{mc{dXB43fk6#^ozS)SQ3_gT9xgKgC+4o}e(r=+P38+)u6AmOFS{NBiwpw zfg8#(q1^$F;^?y)de+ySt_>{`#<|gj<1ZgUTiM~3=TlRYE7yO%nuy}!gC219k%?c+ zk5Tl44vCi>k~!ktae_x#-Uccf8Ptw-WhwdI#ihO2HeHM(>;FE_HMb|8?fxbi=&sv(C>+jk zldCpZG`UjSiRaN`W;yNDeoe$KTUZ>+^*A4Lq#wU0T8p!Ww#t6ZOe(XeY__IdwXU)1 z3Ad$sWl`R-D#EKjqUu_O>X*#w{O9Vg9>W}kZ9rthEsJDqlENY+6$hV&#nSJ{dSKlc zE)tHLdbls)epEO zhfTB61G!fHfST-B+16$aVLmcS;jcM}?lZ+}-Y1C?eR?x{e@61fbapBTmhllV|2EM@ zg>N*Nd_br^#%}KKBrG1x?{ZbVEqnOqt*a%|X35feOOHtYq_z>?aTZ(Hpi%fuUvp0n z^?!S2;^*+J$JE|y6j!6queift&U!Ng<|_-og`&hsSVwCIg9Jg#Sq_*NXm6W6P#usP4Sr+s^mb}=N_)4hsK%(@S zPbx*E#~8ILGA%os&-tPK`A{GFZFcoL^s;6C$mce55Fa-GeE0yu;K73e zH-H#1!r+J%BQ|j0prN8g4Hh)0;HaVpM~oFkimXs!f`$koF>1hAfu+coELW=32-Bhk z4iz}yq_~qJPM|(@RBpgbgbs6hv6o z>{){ZHw=vUK>}L1anmYXE7vaChHlq3ba>Y;-?t$2eu&u6?^(VJ5h^6e_wd1nV$Z4_ zNci!?5fb`d=G@uyXV9U|j&M-g^l8+oRj+2<+VyMLv1QMuUEB8U+nX`-9l=;2+0VRt zuO-NEIPk~9dykzw(6C?Ozmb`{rNufhTiENv|3lFTbZ%ZyBsAjUuxaX9LT6VgWih|YYdLl##c6Cy1qqiaVs z5t8vu-*lC$A{o8arH!u0-JPo?xsGEhO2GNp9ErUE7~rGpDZNnwN=z6#-oS%UZ~ zmtx}YDvHRvs3P(@+Ao4b9k5_6S!aE*p~@KJF*sNgl5XYXP)5!$-%jkY<+5n5+2ovS z{q|N|ONLokoXg#LR%Ewrc4?-WC5>9Bqn3JVsd;PDU13*LnrJqqBbLi!yC(Orb=Pe3 z=Qm63*-W(SO!FZ&d6Ez#jrimUUqCm)h&-$;`ZqxTh%u!~VwnmzeB*p&%6st%Ewag_ z2sq96qY6I`Im3lij{dZ%2+Oud zn=4m2TW|Vz;7z4^c;bsUUN#urjO(~#$E^&yvWZR}Yqwj3jIY;oKlbHowf}2HF54w+ z0~LDW*Y1uacQ5bwPEzWnj2#beqm1L%n4xpT3y`c<^&Q-J#vdTn5yPXKVL_*E+ zNM@j+OqzJ(yWr(ehnzcJ4}JK>H3UXHnT+LYzR(9?3IzE zbEdq+PjTj1pvESo9z9uPQ{jODc|7H*^>j=F>k%LU3+P7v5%5oLN^c{H zBjPA$p$1xjRKAPhuFUi!g|Ki)B&wq8V5hXsU8azT;UJkvH$k`&QC+z*49ZaCGEQo8 zhodCrl7M(hRHm{?jr?A?c9T3-zRQN#^VZh3r!5jHZ$mfAo^_7YEwJQ_O?jFde9(uU znBb2-h@+RM%GWV1(oufOq>llm$u|QIFi`(vrZnrdkqYgEK}ji%=v+6;o1sun;4@(g zamcNs73oHvk)X{06B-~X=bc`4p$kn7K*I#K5mm>E zX%ZVjp(h<(s)|>zLlX8_q_*45Ykn}PTNgD}6Z7Q_nt~eO0P`hBWoqD#6q#uq&VNB*r`V^IamBy{KGpd?+B}z(yZ?9JJEg>Kc&glsG zHsgpiZxu7?O&F)Rx<%HQ*^TVs9E-Tb!Sqkhq+iEO+9!?(%p`)G5ohWt&o=!wR^hwT z1}rGWM2^U|?q!h+l~gPx@$!T6?Hz6ne9+z|Si#kzpz|6t+#3z#pSuJmj-uCK7*X%S zFKpM4xEI|Il&_d9p>7wudt&WY7Q7=>BS_9uAsFB7yfdb8`l=#S2bgnL@9m_|2+W}j z4(G=`6D@3qOk}l;g|?#EXgrxLx8--_pme&-ucp$+}<^Zxm~ zeCoJ(On&XGblY(M`eDgYRPOR_8%5^(ad}aqa^nZ;7~SbsR$V*WRxy1}*a1b|Ylpr; z9NHVLkwj$4XytE!M;$r@r#jV7NXsM=&6Tu*WyaGA-R5}|(!sX)TB*wGE&+4gkSUwI z@>D*Rm=`@Je+hRXYj?@ET;(kHsZmOj5x+}TDuNe0%S&>h!4swBHTkwlL2`6|e{lBP0)a>FPA~EPL(Ga)FNlgt>QVrT+RCRbBS4_Uw1qikGd6 ztI3Cn{35@)Nw1HlqHAAK@Zm=67ZpEV5E)K1Wl|LJ*t{tCxsUV_kEu{)3j5pVe&YX5 z*h_UEQ(}DoK28sxbD^0k)SCO{rG-9apZUt^4ZbvY9vSOWmy461_K_snKP0GwJps&_ z*(*RTQzBYAqUF&!N>aPb+Y&bG8L?YCvb!Ga$tce-y$I8&UyCp-;fWU0JHU%M66`j^ zGr^bBJD;i;P3g9rAiVKwK^7!2?$bMC5{dk!2&s}2|MC*0yAIGBKrQ?W1MI>CBdsQ*Dh6De(;+@Iv%Q2{Gb{|l zO0yv~`>&K4vtgQ>j={E?aKXT$Ec;-e$#SgnATdC^n7osT8O*ziS&6z)DWG^D5SX1J z6GBS=s>0=pKne;q*ZDA7fx@(rw9G?2b*UX-TMkQ_Eh;2FP^t`L!HhKA!q>wxFMLIX zQjST29{=|va-8wl3CyXuA{;fY8^a6>lF^gIp5d{rNv-BNEqTjA{}Vl7GRK=CofDxl z)ru!vWJOkVMOf^|Q!10+;~Wr(JTx@Ldc&d=S;e9Pfnice=-4-dR5-feykmR2l(P@I zNw#e4!7#TN{za6Q>F*G$wY@U~tzup@{ddjb~i$5Cw z`k*2TKw@D(cl@MF(nNhM%7^erq&%x$+9eGXh$x~kwfaTL`wfRor{yRvy3#8MWV0pe zxNAGCkvJg5S|+lj54kbRpYREu2#TW+q@(Z&32@7}oJ&FCfVt#=luSuDNy4AI8L{x5 zaRf&RT*V1&C+U$#ad||?@Tgi7A98fPClf8}csFIKp@=lf+v3Nh+|1$e8dd3z<64$Z zt4iH_9Y<8Z8Ih>=E5pU83oAJt3pqKlJgk?>$hz|h+_Xz>+)cWa0J{{VaDzOO8O{=^ zjFe#&R;fqkp*Z76`o^eewojuvu4<&ecR49wMGx*ZELt@BB~^gIm3FYUN0>7=2-P^#{{zX!BJ_Y_Zq zB2V*tQE2J8)4{;uVw>FCCFf$hb32(gj1~J#v+#_#97)iDLeBoOj?(EdiQq(QL9H^8 zm$NC1fclLKS{_U63}cg%%_31xTR!WQPkLm`|7sP|%tcS@x#IvuxEfIw1vnRlQ8p?KRlPn2BNF+CHxx!jo&o*__IBnHvnbU@hk?_1v8*R-% z%|xm6QHQG)s8dae%hjqnx1mYMwcAUio7CoL$s%G?&axgcb*)yp((b%HG!+cUBS+)n zPNOSTPAxrUJsIv?RV{o|S1s4tfWN{7ms;esJMEoYbyQzP42Gylczw!SqE}m-RVsAN z+FMRiQ!87!{K~M+!qo$y~C~nGT&nQM^(|aUD-{ z{n#h@yn=kFceS`OY#THSn;v~LhY~YOO4%XZ)HB4->-0LeTTxK|@}=yAL*vY?)e_7y zi$i<`*9e+LPJ1V#KMKpoL?$MqK47;mDqFY6mszf_q+tf*P zksC5t50f(M^eW;wq-GfoCF54jGtNp)Pdxpqd+WDzR6BJSt{&S_323 zs6E^&iJ6VsFIZ_=+f!9tJu2~OszCjc%k<15nz)+nF@42SDrHUZoXEC4oB5+F7fRZr z{TAtvQlbr3CZ#{f-4YYkywm)eMzzw|C0yJxT*U2NTavZh#Wk%>QwkDN2`t!%yfEk4 zxuz7@Cj(7?H5KuxUFlVb)ni?V?G7H}Kpgo-8eva!v{1kQ-3`$4-n+dXqBPYhM7o>Q zSOgqg-4!d|?cKvoN6Q^In5B`EO+Mq@4bW9B=+ZB<4b~QME}S)s>bO*=amtbvksztgGCW$?!?QJpNZE?Z9EgW2d>m`~_cO%+fG3C-K!|CF70^R$Ti^MNXYtqNA1V z9U*$tU=7_@mg&65ydDwW71A-G^u^Sl{VYso)lH7(a(beNi(@y0;{a0&&23n>_|8-Q zwf;@d=~!i@MOxQn88*3K*Og)1edIa;WQ#lIs;Xt-gI`)MUGyDb1O`Pz{bbJSEPakN zdw%9o(qw6d(@-|xo|{({8fEsJ(E~o-CC%C}V;+xcV5`(QCa&O%UO;&E%g+7O?=8(q zy~WnE#|-UD=@Hu|9IbH~Q==NDh+Yie@aAFvEFpp(ifiNb%pAB{TZ`^+m3!Szy86j(hy<0X!$DQ z4eDI2ilOS1XW0s}Q@QEYB|Q$Li%|Ad%QVb2^=G#Z9)pJK^3;pAz2AHr;y)#4Ts7yy zmO!UY)?LNsdDiP?t;%?9Y_YZ5HKFaDoZVWPRySLu>b?m5zS zVL2XR;^Mq;X4fTE-Q&i(wn6HQmTGzbWo-+LZFh2LOAY9c9?})fAoNvdRZ&co{_M5w zYGgi|RF+$p&R&LHUzVZo=f1M&reEQ$QPbAX3bw#){yKwHbllj_Ko8Ujz;Df;B?6UhZIqN-(?P^VL1-X=yCJ zPv>s&UwU!G^&mUe(;QvEI@P_iA*kp@^9>(clGf+?v>pAzSyT33$!?-jc~-S$3k7x> zYei3m%^Z9lE)!;McOxQuTeqeE{lC5Sa`^@G`ZbO-AKri@;L*cRs2*@ZWsY2fS+#p! zf<*F(ddxKkMlNC7w%s=;XQTl`Q(GzG6HjgH09in$zlLJ=#G#D!P(!+NEw|XSb@WGv z^cVi(F;6FjmZf2DXVS!M);aE8OuGjM#t3w~E`RE>Z5pZsZ9U~}PrXv{ZgiTqZ7bZT z+Ibab)e%=wTK+m@ck=bH8f{>I#pRoHiLUg1V`pC+vlnUh2DI^f-?~qaW3?*vj;fAj z{^k-f@21Y2^nTuCF%DP{vn)3|gtyZDlGxDUP>ToU6MooUXZIF;caXJ`b(Kh99irUv zvi0sgRX*Ug8j~Pz7Ah6^Y(Dr1|321%ROIA(^>|air0aHH9#QDzv^#g15IuH^Kf5rs zUu>T*K<{FYFDTM*v{5k)ss9S9zxt`qdaKv^s_%NN-+Hk3danO^u@8H)Kl`yyd$ZU2 zwQu{XcYCx4d$?!&vakE8|GKi9TombF;58KuMBYFT5+B!Z@|Irb0(U1S<^%6->Sb>w z25j-U@{T`Pep693pJK^J!UpTxP~6l6G`$d-_NO2Hs2kt{_gssTd0B$|YThNSAuTo@ zb*pLf;^lME_r1BkvXkZUC*z?p zT)rpLzy1{-c~D+@VGp~(|9{!mq1sG1 zp+XP{3w})b(IUZuBv*`(pmHY7nl^9Z%&BuH&z?Si0_`~hqDq7-S{n2zaKp+GM@4oF zYLaP5lPgw0l}eGRNvB!0f-LwIti*&ZQIaitRb*F!8Nr%G+wkH+sSo8+q>E4~)~G6x zR<)TBZ%x2~oA%{-aRW)jgm*61Sk|lGpe-ABm2g-p(hpZ-rVTB6H0jc&Pv0EMbt1{d zm4B}88uu|!)v{I7|F%2Oi`S{b&Ge4|BHBWVg5B*BjXGTEe)PeLi=2q=>DP;lQhcOFMd zmgXZ;N4BOUjLngxo^3O_nA}7nk{O+eL$!$BiZr=}V@+lSmzta9S!Y|CbajmtgKDmTX5JB~z4_Vw$O@T6wtOmm4xx>6lu9h^TuQa%Cz{2|cCU zZfGVdVM_4*gy*OO#hK=mOa4V`YOO+6=bc8{nALQTawcL`jFM&8Z>2>B8fvcD`Qd<@ zVw8E8Q@u}UdddgTOzV1bu(F*8pxEq%QlL`|?2=hsyxZHvqvd98rl%Z*!ZlGDm z$gPFZZUN6H;cMQuD>F#@xhE@~`jVI!PPyL6uTDU(1T0X>Ze(<_@RbB2k;cJ9Y-vz| z>)u(?|84j&kMSn@@W@|-9kz>5kvpHcdX+mKLj!XCFLB!mEhnIY)+?TxHr4I+ygzG+ z=G{W&UC~f7wfz^;YY%SimoHJQI8rOlM17|Y4kUY8dx=t+@_9lGdZe+*{J z2ohy&tM9Vg+*RYMR5fA;-o$gz9Oi`c?JWTwIBQA^)!nfM>sI&Pp&2`6e>=JLas9Tv`}uvm zVzw8&tN72A=WpT@UUJmeuR6KxWa^TR0dH5FLaoedv7ry;GMA&yR8UW)`yK~77_#z_ z|A|4bSxU96x4N0g&tB^47gb`Vqo1WvMLJtmclz|g9mTLll z9?^8j7Pvsrjc8;T(?HlLx8!g*qJm!ZR&&Ifkq=HBqfi#-0zoOd4MCoZ*rYVbJu5;o zk_vpJo@ zQv^xMe4$T&Y^>ue+odd4Iu4Zzd>+=)<+9~uuvWetPdnw=pv`ftfgEvL#Nz2WMe41e z{zRPem}$_1BF9_$^dX73DVW#gX;lvG<|dW$s@X-9R9%!3@9;yw6`sZ|Gc2NnDA}g= z_zOS2RATkSQ>hpg>QpAxUYdM{w?76=h~45PG);=op8{2s6V)601a`Y>md!;Qoy-Dj zxi+H3FR4$gQrzYv(yF>MqwB;70JE0F>patL6U!GLl@cEFC~Kjzyr7xFinz5dl5=jm zPfs9XO@a+3sCwP2O@?Zn(^+q+NfT8n`6nd6!ZDBx9ZuieG_8$&Q-y9(|Cv+&g%t*@ zAbX)~lTCNJS?g`kBQYK4O%3ZdtPIVG!_uiC2R0)gEzPibyXqzbAitDYyXne zK2DWwe37+IV~g4)sG-wZgG13epW{36i7T_7E#WxP7sn_5Gp%0qXdwG^^+q>6k(ny4MfvcxXmQaVHY`Ayoo6Yzm7Vg%jRiEu8a5_X?*ClXm z!eg0M^CGMOb2p_uW37bc1>ldEsZWIrR)$vz(AZ*4JMJAZP_G3YJh8SZie;Zv$wVdN z9v4E%HQO00tG6#b_oV7H$>Au3&K0_qxReBPkS8O{JTnB_)afd8$`pLomasGc184xeVYr}BI~NNIW{X+S=vigwb4bL z-B~?HPu zB|(a%(UM;F6%~3|!k#ROVCD~smF>yrnD&1OR^^9UMlZpF_Q;x@a(2ebw`>dQveG5d zoPTHQ(!yGBoQ@Hp-)e2qj#k&Aam`x(<6C9}yn}3`r;VYB|HpYJ3fb{)7mGEUYKB*} zjL@Ais#|R(oS@s_LR`*)PfRmlm$lHprenz8ig31)r_v)g>*ZEDY@`sb;3~pZz-#`! zP-%0`CB3)22wQ6L^;byXHs8eF#BJA!o5zCY=#J@>^a52Xlem27yXU95ZZ2K4BU$Cj zshrO%o2E!vPwl{{4R)KO9c;MScDmHHbuh7yI9ZGMnI=y0y3@I%i5#%TNy%#Jv?`O{ zEasEJ(xT1i+iJlM?Y<8=_Mk;7ig4a_vKMa7lczoN{yC%Bs{!NUtiH-)NXdO zeIsL*Q_;oq^M9r|Jsq#eC+o`h5-Gauzr(!YXqEWJ|I3*73>#NwWu9(`(DXu=);#ky ze1jc{A>6RG)L|8o@YpYChe_d}nI-MS1#i+UU9P{7?;#<7#a)ZS;v; zobh{lmh*zjFZ7>0lb7H8|38VBU5I@B()5{C(0Rn@u}ad(9-XybcD!EEj1**yADLaB z(@hBaSybR$9JH{>Sv?j+2p_}H694InAGKBVY{zAoAnXC)3uemp)t{zWh?G>|QO!-S zJY1(aR?vK(#tB-+)mqlM61vUC<&}^I3X`v_ADBQ5e6im}njd29e!QdDc%M7+f4Jz2j1sJq}$Lg&L|6;Mw?14n><<1RSMfuId&z+JOJ{8X> zA&_(mdGW`MjNnbQOv$;E^dVx#$P!KwQi>!W%M~ISQli}$AP;6Ac>EwyZCa3#5d7GR zPuSsXSX)pf$^JRoq5h^?4m-uxjC$woAi23>fg=`c?*_LPB< zTbmS;Bc960siR~?*l4-qG0Nle>|nxWA`5xZ7)93h;UF5?%?}=7?uC>8d?OQ%Q8UTN z1%^=QnO!YX$tz~z;0@zHY8gJ!Pr-$u|C8Yw6^7yN91=y6<2;IFA36^LQb(9AATz#C z&(RJbb{y{Q8!yIUv(ynDR#!NBRkCfKxsBUIs?b;+MumkCq5u;Zf?#<0q=%7GB<|fv zI%T<-S(VtNy+uxIsF_&}*!bW_9tEWGUF0?zo|g1QNEX_r0SH6&m^&$lM4DkoBH2ay zm`{BqXrbg>>IrLw#8>8zLOx|*76oujo^zyL9ZHjP%pz9S|MCf8&cu*V-lm7arCo?-Yn^6b0obf1CDR3#U6!Nb z<&*ifrfbe4L=+|+Zc}1v(qbOXM0Mqn93C4EA|8=tx=~Ggu1|uUUTqXuU^L(izF)Vz z5g580z1bmj9EJb&9%$~KvK3|i@Fa*y(eH6*gBFIU1tZ7J$52_NaB5v|ktgyT1Viea zZ8npH&Zh(^(%+R!EPA0XGF8)Afm{g%y|W7!4RQZR*jaDcn0I+0ZRUGs#Me)?OAAR`61&yOvkFd)ZC+DFV0tweKc)>q-b``sOMS8?f!a`<)?rkx_sifT|xrU$@=>j)hk67m_r-eH!4Yth(i z_Ec-q=xW3sR%@mu|Bph8vCzoF4vnz}>x1Ity{hT<`POuX%RTC;H!YZ(r4YQH3Wu7U zmv)+wt^~!}5aB=|tIEby#;i}eEXnyIdfgGi6v)Ra*p0q~(b9{V03&c>lgL7?e*UJO z?vczwS4H6+rA#eJ>d~UQ56_xMj4o}%&LP-JT)Ba50UD~172}-!EDq&RLf9&!e&O7@ zWS#;D$42cj?ui*j=(uF6sePIaT5Y(6?1M;ZaJDM0cI(FJ?9Sq>JCd!hiJ>X7YZL;| zVPLCoAgwC}E|3%okxpxqZJyrltubz5w|z?1>d^!W$x33G*pehhCfdKap-{Lki=?j5 z1_ig~ClLLW|I+s4yPB@<)=`4?2RQcYtC6OX`t9jz-ZTnsZ?MhWZEZ!Es=U~#iWM&S zIqvR4qkdIfz{;PX%3JpykZgUfQskQ;(js!vDl1No$qJJaS>Aj!E%dHwulmO8bm2uI z(cxAvBg$?XxsGJ+SN0kOl&%W?P@QnT>NUDAe&pHpB=6Q4Nc`rWP6mh%En>PTQc#69?P`drb8a-W1cIsp{>$FfQF}97u77ssOU%q-46Mu4F-UYzA=~9YoK1MOd zsp{dvP#|}owym0k_7RSVSVOu*nys;U{36S7asGbLg)d~ ztYF}6tVr{}kkRi_pk>W+mgEMEgbc)j=v1V3I zq&DjRXs|iIp$4z(j;c^gWAv6yiQu7%dr0rbcJu}|^YIC9axK=$bP?_VNbvbIEhjW^ z^5o+-Ft4Bu7UrSG^70Qk3W7zJYFXk%54CMcS?4q(QU`J$qi+I}+j;uNM%gt)?yOL2 z-8_@?S3B*os%#w>489N^ z7U!RR>adc6>e+5y$%uB$Ht(HofUH7nRul2Il5Nj)UBh^c>=0ZnITOgWbI{zjV2Iv# z3)OCOXJXG`k|q{K-7{l4n+5W9A0C9aF^ND-3=A{pmFSLEt6_A{wd8V#U+2vAfmIFD z_Tc{H*gf=@77vvQ)pDD6iNOgXg-LZcl*j$HijWh`(jsF#GpLOtOgFB0IdDVE5{Xuh z_Vukf)hNL!-Zy#EV(01=E6OmsrH&3#c}KWkss@FJDxLaa6}$0XL%1@=_m>sNYnLQo z@+h>rENhc5ycyr~Q6QTBWGm+(t15Es6z7dMi-U*sj`KK>Mk~si@ong_|A6$kwjT6- z|95)z@|%NJUl2Ex1FEUuPyKBYpIa=j3aV0MOS+ok~c$kYhGE-<&QyYr- zFNBZVk&_=vQ2Jr%NCP%B@;b!9vJ3+*xKc%~@mhF_Hd;ryHI)M*{p1u`qI#}Q3ky1C zk1l#f6GeqywMKczhaVduAGF?qFPy&%atCm5bG7F%a9Ef6iQ(m*;4U9$E*&WvPfrGI z+ivHk=!fRwq11Y1Yfgz2`N27fU}iY#xk`VZj2J&{PF_-!Cg-g3r|E9*uXrt(YBze@ z`~8Zk2f7yRS-WC1S*~|`=A8s7ig@E*I)<(Wt^X}ycs9e`U9jJI|5bujcEh+$qaJ;x z_Gv+Ifv2liF58;$lLwuMWJ3%cS z3&%9iv38)7I<7iLvzj^LBs;%jDkM`N2d6yWE?1EoJf**lUpz6~Ju|$3Ft}7aoZpX< zr|8L{_;7xCm*cwxNq49Id-^J|m%lH31n9Uk($mYMEwhZ$lyrywFS-{yc!0h33K4$C z=gA3vBNxkD8~%{KDaHnLA|H85>Gpa;NW!y*z|(!rvF@Gbrs$WMN;lbVhy<2lKR2{^cuE|59JAh2VVFkhXq4ufFnG zFQNR{a`!kkB22YohTEf-IAA^ zTILGU?BlUr8!wbVIx$zh0yQH3+gdWk)`eNORNI+0-xWp4t_D0io( z%O{V(9d_quy3bP*mEN2>Nr^?BUXRNCWmb={+lsGP*Kgag>B$$~IK1U)-oKi_E88ZmIC+7+gGS_Ik|7|(5rjnAx7zvs&!yze42){OwqzTA6 z?Ywiq!~Cmoy^@&RY{C3C+YvPS+}zT`EQcCR#0_;s6hY@0Sb@bTS1?Yww{o1%xG2#y zP(Hp|M9{zkHDpsxKncZ@)mB~oQi4xMifJYlY`3$H|0DtjLzOD9K3%&0d^k88Kv-z1VRTo?(3ZPViD<+7@Rp-wkeH5O%AD8;a0Ox+N|ZTVFOYg-op%BCY#ePx zyOX&#fwkPT`2MoJvR}|GJ$r6|4}LSa)D`}@MBufM|4CWGjz!Ntv0Gi5VkEb0X)Q$AidKeZ^d+W9O?n&} z!ROp!J?#(;C2`u``rOw+53VFAsR|SHhN88ALF{Oeo7eZ8LKfjEa03yt5A_&jy7)Lw zEi4>d_gthy4Ml4_BqX56BB-!v=B=F%h)|WG(|Hr2-u#`s_%|{AY%ykx4CN7}wVNtcQjE7O zNIc7^PnN`Ph|SUDCvo(cWFEzUYHVgl@L8yHlC+2&b7)vvD!!E_6sNrVonl(V%Japg zp`&|GArJT&;IL?<&WzZXs)!|ydW&fDtEs-;IJn^~#iO3NCjBVK&*@0CLEh8LQFB_> zD8er~FNF?7G`h>%|11?nO|2tXo3w#R!4a6yX&OvJTAGuBCZ*?#S_aj*#KA7Au>6{- zR+OeIduAq{WHsw#I~c;a(Y29>9G!SDO2D?>GqItB7gj=RxMzZCqH2XFT+eq?9?Hgu zkKLy1*5yxhQWQ-GRoGoDCRxh03XIVp`8fEo7$21IdVTwGg zDtApKoi28h7T77RQ9YpaYyajFr`1r2a{%)#aM_EsNMbg#ajOb^0VQ9ZbheBy6eZuJ zTbusAE2)4jEi_e&x~F!GyNc~xyw-cSGs((En0saM61>42KCrzRMw}S~q{}+`bZcd! z2!5fq*NYT*|1$p_8BwphSZT6$Wv*>Z?5sOmp2g9y73S-w_8S<0s!zvIde1^8s9_^p z?VXvlFKY%Y+BV)OuTcB1ibHJTu+~_xGDa3Bn*+oWiuZMUQA?tN49nIzuFQlin6`Gw z+aezs&gfbwaUUly5+_EkNn>#dIh^7&i^`%{#)_6LN9gYEnO%P#2$*kW=uvj=yC{w= zTqjc1!4y=|o!p3}w^_YN54j7^(ST;0A*;}S=jCZ%^r0=CDvyR^Kou{PTAx)KR znQkMtDqi#3OxEa>Q#t=u(_c_Pl+Es{@LfU!=ASzPooZRX4iH>>`>R z9l1ey>+7`t{_=tSdvJo{*pLo?Uk)$zZmq^DpqvUfy*bXKX}c4-<}MX;2W@e3gLT9e zCW^!#4PzUp#*_dQj5<%`9!Lj|-B6m!UuOu=zDm&K9T$3aFkT$Z0=$d?4&p%LOY*2t znQTyp$+#7a>PAvsDt8skR2#hY1=oB&0$iM9&OE)t4jt|D(TssYKArM(`^BlI?w|^c zuN%V->@fG+SA>lfkdAfZ&-%5jX&RZIyGd|AHha+1-gv+kJJkxm7vZDsbU(-1)>;*` z|Ar)Q7^+h^=QHNDX^3mIt}ibsfiIIqx9V0prJS~X_fWYVU;C1G)bgaw`O4u-5r!Mq z%7_Ip|KP>Xalx5{e)jo~pmG;?csB1=noZMW>-^M1lGJZt zYDWQ&V{DK{T6!jJe24X7YKE+g(JTp$7|*e;um3(UZ{{z=#?S3o$nI_}{0vFzP>R$J zFikLOJBaTj{)Yt7Zv~kON4D)~;E%T=1xDTsuOZ=AbMy)sl z`Y5Bej_x<~>oC;NCL#utmV?;z5Hu`G2bU+NP>Z;Hr7v1fM<7pBp2pt*aShS#Ky(NI zMZ=zW&sg-0DLkN%86_5@&Ir7?EAx z(4`86oIs?o6eIU;OMlFQ6I%|R#_nzMMSuppqlQd8l}jf)@?p=2^aSw^*HcCcw=$0YRsmG3&RkGc1C%`|4?((s`}~+ z61Q>QmQAG6ktCFeYxDzePViuiY8R2?`GyhUXzUAD1#GafwTS1!+=-hqFq8~XV@M^l z`q3Ye4IqO^2@@lWywM=D10kJn!K4u8Kyo~G#3j@4&>XTc%!iFo@#^f!3*DrTN`j(N zZ5%^V8~eg;zK=v0a3Rr8d<61%oRV+c5gGN#6{qJQvjQK%jpgcQ5s!k#C{lcWQs-jt zLX?gu&vM0t248G4->hpTfd)5RuuSeE_$ulYVe%%Q1NOkuh#cP4G8gk7C$alDGg5fvvNCfpW#l!fDd3W_k6^7#uxBZmDSU*YG$~W0j*}(e zryEP>>Q+-%MkUK8Q0PICJXU z$+M@=pFo2O9ZIyQ(W6L{DqYI7sne%Wqe`7hwW`&tShH%~%C)Q4uVBN99ZR;X*|TWV zs$I*rt=qS7(BTJr4xw7TU zm@{kM%(-(zb>{paL6R%uygC)4I7C%dn4_sb7#(+ zJ9QrI*&BDx9dOprqf1}y?i7UvDP*7C2zmj6@8H9W|3|RE9P*IL$IZKUZ{9fN9PPn7 zcW>PE`}p%yb}hw2_SxHIWScqLY*WoC1|oQ1f(C9=+;bnvw@!QOth3%c?r;RpeD&$) z;fEj+W?O;q=o4UaCIZ)wiYy8QVTACEa}PS-6t~TK_SME=jv@BwLVnOXr`&=Q^FDV8&&X# zGtWH6ou&>v#yJNMdwkyGjyv@A$=;uP_PI`%f-botpn|SL1FJKLm?!VB7EN>O*?MGIbe=XoURq3MmIEunvs>W-3!uBZ=(bbj03aH7)5s&nSh zcc_jrSmLPXIrQ+!@H!jwDxW*P&iRdt<_rpR%2;Q8FK7mvcJ)ykt_Sj;x=IbtoU?9& z&CsS!xXy3#x$EHE=Gf|Vj2_=JwR}}$|ETrffSW8FXuo}Z)SdLrD^Q$LTWp)Ve~v@X zJnB%~vCaZv$)Tf&p3}6W^2w-p;G~yctl<)E>Zzx`(JLUHw`zONg~Y`^;ixj+bB?y! z!sAZtWNK;ml3)64+j?6j4zlUYH~%AOqLJn`cjkB}ZM4+hOy)gFC%ukw=EzA;(mBub z4btOt&t8<OZG@rqbH z3F@-Q#V&gBi(m|+7{^G)GMe#>XiTFT*T}{;y77&0jH4XqNXI(b@s4=RqaOFj$3FV; zkAMuMAO|VN0vYmb9n$1El? zm#NHVCi9uhgr+m2=^!aw;R{!=CN{O1&1-gZo8IK6IKxR!aGLX*=p5%c)tSz6wsW2C zWT!miNl$p%^PTvd=RNhA|Id2%)0}%a1vUmcP*sQn8wN$_#x!vbg{q>V=U}KqAu3UW zJ`@`fZKy>ls!?%VG@}#6Xhl8B(U5|4qay9-M@PC+m6jBxCnaf0P0G@j$~2}erKwA2 z3e%eM^rk+=sZDd*)13ptY8OA*uon2 zuz|e*3oM}u#u`Eus_;Z)CF=>wQuY~=y~JcOi&<4@wz8bf>}EaD+0T;pw4NPpX;mv) z(4y9~p-ru8S3BF*|DKk%x3z6-Vf$Lv$~L#Z-K}qVi(BE=Hn_b#E^&36T;MJjxy5a+ zah*Hd>MGZ|)V;2Dv&-G-dRMyOjjni^J6`CL_q^s!?{n9S-S3u{z1wv!dg0sM@Xoir z_Ej%_X$t@V9H77d^)G-2EZ_nM_`n24uz?fI-~~Ha!4Ph6gdZ&73RC#P6V9-OHH_g6 zd$_|Lz5o{15C=QNp%8#bF^VAph(`nh5`lQcBU&uu8QYk~E{3sBOF79{Hgc1v++`qtnafKy z^Om2SWh;|8|IJ#ya+%}&<|>aF%yV`#p5d%#G~4;iY!)-1!|dfX6I#u3=JTEX+~!3G zy3mRKv!V0s=tI+a&ytRGqX$iCPAl5enXdDuC;e$shZ@tP*0i8aooX^eqQ9_?wXA1N z>ss6T*0|2Ku6NDrUi0r2)b94Tz3uIAYa83+-uAiIo$hUmo7~wpx47FaZ+64m-Rr)0xw&occ=H?G z_pUd<{hjZ2@4MjoR`KY{pv^0`qH)jbgoa`>sALl*0)afu9qFw7#MLKPRwj*XX5Rd z*hJhnLHD}b{qA_ryWaQC_rCl6?|=`y;0I6m!W;hZh)=xY7ti>{JO1&IkG$k3Px;DQ zp793AyyiD=0040Q^Pd0w=0h*~%#*(Krx$(dL0@{!ub%U-AARdhKl{$tKK8D^z3yj^ zd)o7U_nc3=7S>RRLNMFfnV7^TImu{OC`=`q$6?_PhW6@JIgu24H~s*Z=C$b&Zsgg+>RI~asL7=$_agGq>k zKB$9BNQ6$PxypKc!f$Rg;rRESQv#!D1}`(g<-gbO!$RH$c1R=g<&{`V3>wt z=!RrCg>hJgZCHkD2#0kjhj~bcXK06R$cBBWhk?k4Lr92OXoiKTg?p%ogUE=9|A>f( zD1-$t0F#)1`8SD`Xo;6diJEAMnAnM%n2DYEiJ-`dqNs_a2#TpVikw)AtB8uNsEV=3 zil^v_vj~f|7>cE6io5uVwwR0aM~a_Ff+lDOEoN<#z+kP?}W5&4i4d6D** zk?V+&7TJ*-`H}Uwk0SYx5DAhb>5dfXkt(T?DT$9LNsucUk}VmNCpnTb|LKxBX_Fj@ zlQ(ISJqeU0$&f=?ku~X)K}nQHsgSS03I*_#P#Kj{Ih9mdl~#F`Secbtxs_bmm0tOk zU>TNT*_Fgt2F93z%~ylb$O^B}mTmcrZkY>i`Id4?jc*y3aygf9X_v2%mwoA%blI0| z*_U`ZmwzdkcNv&^S(k(9mvFh5h)I}=S(tq3n1Fehm06gOnVFLrn4Ec-o7tF}NtvSA znV4Ccph=pEnVO!7nvbcPlF6Eyso3UA& zvw57m8JWZxoXT08%sHC2`JB$#oWm)d$!VR_sh!!0oxe$)*J+yH|H++u8Jh%fp6HpL z>baim*`DtCp70r;@;RUMS)cZKpZJ-d`dOb4paoQLf`ovUEGUD~=$5r`pa`0v3c8>S z+Mo{lpb#3N5;~z2TA>ztp%|K>8oHqz+Myo$p&%NfB08cZTB0U;q9~f89lD<^+M+J{ zqA(hxGCHI3S(bJXppig#16rW3FblJA3qTsALOP^GTBJsLq)3{iO1h*>+N4hUq)-~A zQaYtnTBTNcrC6G!TDqlN+NEClrC=JSVrr!{TBc@trf8a`YU-X400dxQmN*)BJ35#? zI;M7dr+AvDdb+24+NXZ{r+^x$f;y;Nx~7JDsEC@VikhAz|M;di>TEjN2{=fnKT4>U zda0P2shYZ}oZ6|L`l+9~sG>Tmq*|)>*`NRUsMeO21lpE$3aYRgt5!M-yO52=fDF-) ztGc?Y#ZU~wunW6j3$i+_#9FMzdaQVAs>-^o%qprjildP_sjgb7$Xcz%>Z78N36H=C zi=YQ=Fa=dG1ykS#;yML-00wLD2$Mjq*4nP_`mXRwtj#*F^jfbn+NNv(rvfUet=gmP z8m|C5sM&Z7S1<%aP_R-k1X8fDQm_IH+ptpb0TR0cM34!u8n76fu^PLvg=()J`>`M! zpAet~U7)Wy%Bnniu^hXyb}9_fUEP8+iQ>8Qsjr~I0-N4vCGJEgUH4Q#LnbnpjsptEM61~+@N zYH+q(z_UEN1yCRbLQ4e2V6<5~w{%;#p!&1~Pyl$lx5{dx#~7{ss7S^x@g z2S=a)3Q)R~Sf2`j2}kghe0#h3`K^X@f|9}ZGU;w3R0JD1s5D){HV7jO)p8=o% z)({2?5CFJazx)XV`FfToJEzmyy@X4v+0eX-Fu;4z2Y-+UXZr%bAbynFBk63hjc+ptxT37o6JRvgE2tg+ua07qaAM)10& zO9HH`x+HJ}O$?QPd@C9ak z#uWSoX$u7uTeNTt%gCI}$NIq}fXAVl<$wt=|4jq++{`q90W>fP*1*ozKm$O40n?nvcWeYO4b2L0 zo_gENVUW{CU=4Sm(>cu27yty-3;{NM2SIJqnBcng8~~tv&*}M;M{oxyY^Wv-0kU8X zY#jp-u+L9i(5ec!R-4iodkv$IxDk!K2TTVGtOh%~1z$kMXIt1@Ak4!I1!=q36pOuf z{n(I=sde1UMvwqS4FNhGzYu`c^=trDtS?~1Alml4rcc?X)=&;%pu=!oqxfsk zyBoO29NDqzvdJI?zFfct|D4eoy$22q!N!}>Vl2iP?aO%}%!)nCZo2|?Kno>}-Sl1G zdb-j-{kr*m!|Qvx@N3qGeB5k}+)zEjlx@=k-rS%kzNM4x%q(rbLp<81EWhD<1el%SS*-x{ci_=%1TjDZ zG@!$e{Ms~-d8m!P5e@+fpw7{J!=${z**w}`-Qg(=0nIHBk9!$ZNijo)tKPmi)_29+vLVw+cs^wfULR+P|aRW zyZ(*T!9CC&PS)ih4|d+wsa&SBE83;K)}>6)QT(?EZRn%kslvbvszA18P_t(6=#Bmd zeGs#1z_vfjwmqA+WBa%fjOjmn0-OE=Dp0W|-R=C|@3+9rOrGC*-sVwm+VM*RLyX+4 zjlSxO#|Cfa(j1io0Kek9=TRNuckJuXoY|Q0<Yl9MR4&alaL4+b@+Th%VL%9B5C)^|@@3k?s2js44xjis=qsMkS3jt` zAPk-m!9Y*53+&gMukJq&1xx_?K&$lQ&IMwy*z67kC*T7>`vVmF#*-iW^*y>Xf5LD5 z;47Tg4z2*3{pA>-!>;@LInCNF&HGr*`zxHD=IiQO5Bxj4!fF2HJB-6&pwpY}-@L!X z4z9Yq|IfmW|DJwq@-Z;};t%C%y2LPz+0d=rPE5o13B@Km#nvtRfEv8lkPSod2QtgH zOrZ1t(T2{zJOkUbQA6homn~2lZrLKnj2Sft4}SRqMI#g&CzwF_@#DjqVzg%6LYY$K zN|r5MzJwW5=1iJ3ZQjJ0Q|C^eJ$?QJ8dPXd0!57)El{ASQUXeo9zB{=YEc6ujucR! z023w}2BI>B+7ztVu}cdKP(TCI5d~$LzJ2;M?A*Bqj#$H+w_ILKa_RmBJa<6Zz=aJT zMr;&<7BFS(0D2T@)22?HM2TX>>eZ`RCx?Cp9a{8gn6q|e+p}k&nTTTA;K}nxc0q({ z|I~b$$i<8p-V-Mtq;t@A!;L;Rf?QF^q-WC2oj->jUHWwD)k!Bl>~yJuJ6o+`ilM+O z(!hkFf;A8W6N$Fwu^XkC9lNt%KrYdgOJE3tL(DO zHtQ@$GtUI-8ddgCBem2N*#pi#=2S!xMCP1xk3RHt)6G3q%Mj1hq~Lm=1J6G4pok*d)G*@<+vs@qS%C`5V?r(%N>mCn zxcEYhLRXj~l;wCuH(hntWtXK_-wiAPc#jG|UbvdVcV2zV?ux8ZQbc}N^_9~wWQqrXk)$cGb7fMSC{&b_;H&p$`gZP7<3U2V9#qbm^z39?Mu~ zomuVz=`I+0(67nngx;4JehD6!0Df`weOMv~9^6Mf@f&hqym0jI{~i6_IpAbu*1ZQ{ z00jt>>J`v{2Q*B-{*}7zt!{vw^VKCzaJ3s$@CG&rK@Cz6f)I$n{{tTA00?Vv0}*tP zgC;y-2sT(k4`h&qA}B!zIv|1)mLLT+uz?9q@Pi^G;~FsP-UEd=!~i1Dh(|o*ug8B;07=VfeEN6#xP#-1|A@z32V^84t~%B9t`6U zF7ZQJFz<ba9J1{t}qq1Sh&| zIZkrEs$XSTLma$hs{&zWGj$86$!1Z^6ChKX&UEGtGI)bz^56#k^k)uk06!jV(w`v^ z=nbYB1QoD>6|jhBL?ue8a#qx$M1lYoy0C^q075`DE2I-AdN6ugFq0Lm!3b+m&>C>? zeaeKX1#>V{Os>>|BOItgIZ%dej?||=wb4a|I#gI`l%pQa#I0<`8KAa{p2Xv)LTQ=< zAGCC(ybD5173xoZ&a?z2C@4&`3Ih%pq7+RqWo8bR5QHeaZ-jsSr&a^{J{h!NrZLR{|5?kB3%yp>vYL)kAi0gXU&-;Bu zpaUHUK@<8BgboBG5FH3cH`>vUhIFJG{Rqe)deDb1G^Q_YXiRh3(wok-r#0Q_P?s9i zrzSP3Kb>k;uiDk4ezmA&ZR%FT+Saqaw5A1A*X_Miq<^;2HM{`@L7chR1y1uI)co5v z%elBTb+a|=eCKAqFR(q}z$eZMY;IdN65kdOxCIm$aeq4#<_`C{)tzp3uiM?=K6kj$ zJqdWzwchle_r3L1o+Hxnxl0xH^({7 zF}?|m56I^{2l~&29(14=edjqxdeW7?bf!1m=}(7x)TKUks#ksL?bLXeYrY_1Tj9)J z2m6_o&1^C>8?a}8wly<(cDAd)0-Wgc*5w}2LDt>wcgK6)^}ct$_ucP*2YlcKKX}3y z-tdR-r8|Ay8U4=vIn?mR$0;#+%9EV(R+t0W+dNHYVwkvpjV5tnz5z~9*72tYCT3L6 zip00x^{}4-oG1Xr6w`V=>ZJ&GI@BiNSx(9ymga3Qs7oYgYAAa(UuYBY$-}$v? zee_qaamF_u_08$}&gJ|}%RX$TXGc)DIg>cM|aeek5($}vjWc=el{oBvJ z^}UyW{tKB4R`9?7neo2>1i%6OzXB9M10=u$RKNseKm>Ha1$@8;gun@uzzU4O3#32? z)C`TwIt1~i_Ja;vfV?kIw#u`-%gek$AVI<+EDUo&7W_PgVnGaJCJa*n4)_HS)WIQo zzaE4?{hL4Gi@hMsKOZ#0BSgX^RKg`>!X|XWCxpT%ltLt|KE~U@>ac~b<35s8wy|S2 zue-1yctOu&!DbQxILiSV%rFU9zyB+AL+`1DIFv&_Ih91boED%Oa1TZuZ zMqzw{WK2f!OGCEH0U6*#8j?mDk^vErfd&u&YT(6fw3}RLc*$b12ls$5c$N!7O$c)s;jpWFTY{-rqwmCopKNv}T^n)=w$&*CJW6Xjm zcmkIk#(tDZmn_Aav`HB-0U?lvM*PU0e3V=S$3lv|z7vIZay|Kbrz)JnrDV#cbjqiM z$|KZ8pL`BqclrUjPPB2!*=S z%ln%x_=CSZH!=w9a1$ zhTj~MsVvQ*@I^Hk1jr;$^6W|h!$*pg0nqXHW%kI0bRo26GSxbJzwcg;G^`hHUVK+Z?0^wMAMC1`5rG zGBwjPMbk7@)BiPP(>8U}H-*zUmD4$;(>g6vc_;_P8&cBjj9u{4KLylX$b~^A)LamT zYajQ)madxB1Ki9 zIMTW7&&wc%)dU4zcv5(P2Yu)Veb5Jcu+>}D2U^{R1OJ@1yR_HT1eHGn1##8ge)u9NjTR`2((BLv_Sg= zXb=NAz)C-mgOtR|dz}MHJw|-A#~ckyO7#LC&;j}3Dz4%HDrnbr{kfc*gv;2|aD`Zv zSXKU%zW>V@q$N#;C*1~kPzPPb)sF>Pdw>Tj{nc#XgjaP?J0t~PKvr#a*_Vacn3dU? zb=iE_1U-#dTbKo3@dY-xf*}}!pB37mCEB1J+AENPJ@^7V@B=u&gF#3GIA~fpkOMfd zTB}WitR;h}-P+)S12VYUs~v-H*_N{17K{j5DFE8FW!tuG+bWm>Hedu$b<2pgTXF3S zR!vQdt&B|wg^U#kbpYAH9o$>JRe1Q-WJszny}!!{1x_eanw8wirQFK3TxFGqOt=g( ziCEL{1vgL)*$~~)72QKP1Yr@DL->P&_=D3`gho&VJir4wklosam_87MKgeA{h>g{? zkpDiYli)psJ{aEFr2|1A-a}9X)6D~k;0-ar1L%cbGr$At72V+Y0x9@eDgXpgaFn|R z-;|hzT7XE^?1WA51!z!(k@Z-@b>EK_*j8KCi*n=UMf<*`hVW`{iwcGL4TmS6aO-P1w*jQeD-yqgidk}|n_yi^z z*2}=($o=0YcH$@2)&RB)&Mi{UJ>cG57&L#l-a0u1J!u0I1`ZCfi2pW# z1K)sy;Gp2(&=}vS2oZi0JV_R0X@f1`0u!DHF@T7O&<)?X7&`ca)Ck%pumkUXSR4LG zzvNHVWX+7-*!B(LO11}eDA~nL;!ap%{e|LB2IWx3+@$hWroztxzJ|}e0yp^sMIc?- z9bMIx zW?^=giE)!vo&h(ogZ`m~Q)Of#b!4IJr9nd9XAp;4t>knDS;U0~UtprT>|{}v=Xv&D zDK6zjc0?=YgN2FZ)-7ELZe0mh1W6!hg0AI*e%)h17STl()g|3LNQmAg;r|9UT{~9MBW5R~ z?1W5!TzdBDpPt;zonljlOH}?`7yg1jAY?+84Tt{XeqLSR6_#AyXyrYYht?2dMizo# z>Vnmk7VF@>6JS1wi71g^78kUJmT#E|pLt=RodQlk23m-_l_t#`cInCRg=g3X zd!S^R7GlJGhD->Bnz7gb^<`xMWow zK3`7AhV>0>!LDR;Pz7(`ga&oho$hJJrta#7R-wLUsx)dhSmi8k>hA_8 zVC6l8JWykczyk`N2nufRfiPZd(GU)v=wFVQY5oxWmS{og0~OwlXttJ+<`9WlYD3;$ zNQj1Az~|s*zv15NP2dD`MrY-wX?A{Yfw2tf&If<6?hglX$R_GW-i6N%UD9=BfL>no z9`Ey3USWA%7~kj&>D>($h_5DLI~L(O*@H1AZylHF=}pK4uJgxApE`o42t&T-<6?K$yr*#>e&2i~x@lVX9B zV*&8ru!!KOmTKu^hX5HCS%E58gkms_Drd;K)ZxjPgqWUb_qB&NKmsIqfj8)KOTOs^ zMdHff={0ZjU8iReZ*aM@;wvx+KaL22kX=I7>|z#O3-Mys=#AGFVc%76_^#ayHeLm` zkky@yL09%|_ubYuVT|eE*$!!HMqxc(Yuttwit*#)fCw>Q5h(|5Qg=mD&%GVy;VMn; zkL`zaNQYN{gLJrLf8Tdp6}5c$$h zhURwn7${&77+wTq$c100_dk2&z0R^^5C_1nWOZaZud4YEYh= zZigrPY_)_2z(%xBdp7X!Y4!DO40czpbEO9Q>g8ev{%$^xUNJZWKkj?pSYx}F=+)&A zHDCyhXbqJQ4huf^Kw0Pvo{eP*=0AoAFL(&c$9Xdb;o2~KG2nSIFdA{;;}dT8szH2+ zh<8Bfgn3_j5N!IQ>|1nA26NzYOMZjf5BOZY{r`R__*~tFgy*%FX85uverwH#vrl`p zXZvb}c%}C;qppIaP3p_m;sB>!iLiT!$pZ%Fe%3exi1>Rkuv(IDgS_`_JQ-eK{*7o> zdG{9iJLmRd*5WOwd6}2_)_C4D2=M);eiH$RHfF?ZDM;|(mVsutm>F1b3zUcwe@I!e zV#=am!f4I9Pv^jPr7vQq`r9r4=K~7;*t>+3N&aYPWk?kEo=5H+O%rdvTf`3E!?P-td{vRcMM^_6bm;t6|A| zXFLMM5cC3tG-)_uRCDg^y7M8}p7X#l1Bdl$GkC<t-HuPsmV>8Z+7*Mr0z9bj2xlI&nno{yqHo^5@g9Zy%&io<2nZ z6*{S?I9O$+ls#3!V@^8uz*Chz0y1TfJ>o#~pI7~5^2u0pX}BSW9eViTTX*d>mpp$3 z_R3)QskkCyw#~&TyjNvQP3Hg=_Xnm!F|?8 zkdtAC8kGvwhKG1?v@w~MO=dS5Y5x#GWS(+RbXSl<;^&fx`4oF}nNJIr;Rq3eX;8GB7 zMbso;2^Cg`Aga15tF3;>h9#-OGE zA$|05*%k!NnOSR`(IMuv1JUVaa9~E;(3aT!;Vh7!f#zBs&rT+1dF`4P5ozL4XBiz_ z@F^xk4ZWGKcmnwwnHXkb8?O{YtPn>g?d7^K!woz9@Jx{UL`r`{0eID=Nh$aS5><7& z>819VvlWG#n0leCuByB;%m1$Ovtfy~q6jg~^0|o2H8K|L(6pHehox$fZFcT!eNfj> zc&Oo6ov}kU)Sc45;bHEubZiM+lhjQ;E|ftQ?d%?VNJ(Xw-`**jWmD6khMd?I#P36L zx*4y&ku^kb*k9~11m9o)Q%o+0);u`jg&QuP#FCyGNiydg1u9eh*i(tel}rUWf##gU zNhFz6c&b<}i#|H(rPF$%;D@XJl46WOMw)igCiKU-%mPW7YuVulCU0UmC*G2qc}<-_ zzV$Y=W^~kM+t9;;hHSGydd+nnU#LMgYTv>knr6Q>No?_QL)|9%W_+>G7gwucnb={6 zO-IQe65#xuC$Ig?ok zL#4YQ1~b^9n4yk;9u&#Va@MOqiKjAF8%P_b$EsmYeKV5Hq>UOy5~wxYjqBJ*a_;d)QL@ zw5WzJd|?Pz7{U}d;f%n2u#Ikf!P4r`}CzNw1M!vSir8MsQLQoNR<7Kq-k)hBB0&RKy=r*sM7{ zgiq#qB^1oVL;uP+tCqD~8!c_w8KXUE4~huevRvp(Un&9-hzOf7_t1y%(4m%Mk_bf3 zbEj#7hYnw$jut0F#youimsV2)-ZDPHAxL2lkdaJ~f|VoL@Mvp&NLD97>B&-(@{^(*B`RUq2s)6h zi9RfwnW7^kqPeD)&8p5rnN`bSA`^ziYy=`;I!aK+6cH{orc95C(nBayS^{&^6nS_j z@R-khc><61$mlCF+Di&QP=N#_APRB<}UTeKW0T#(2(FH zC}^QW^8d4~Ze3L)XNJ|m&4L?0;L`~RBAy!+F<3uJ)d>47CwR|JpzN*Iy)Mj5 z^iSe8Y!=tJf)uu3FFv^vnh?QJy83|3UpA|jl}XnwEsI%=wh&rSlT4F}2Sxk}%Usi= z*JV-aEUpchz{>Px*PwJ+qp9mhG~B~>?!~5jP0@-_=)r|A>;n^oAh#S2L5D+df(`Fh z0{=7M1V>WG-4(N#aK?>PR|7~CJL0jq@YLK{BSE3*QkSjR{V|Z!5?2+sm{H#4hAK{A z10UERme^VdyT(gi^TsP&(V+}PUDyXL{}qOZP!mXbI3-HvhI`yAj=2C#wdzo(&GfR& zuhg8bd9k_8gngE_7GlK-N5lsk1~G^|+}qs>+6K7Q?G+Yr4dC9d$c}z=!(PnQ7?HdF8PI_aw1;(@Tihyn#3tZDZzrJWMW>j^sQx#==_Bch&5=@# zDPmN##GZ~`8ffXOA7wGVC}caZD03dfKJ zEg0QsjPt$k?-@A30Z5ccZ~_|V5XVsx-k_1ulhYLf%uhh!k-y#KrWd{FYaIkAJcf*}XA_@rUUffPJ-4*KJ??Yw=cg-~_E0zh({EpN ztJ6OCKTtc#rw(+UV>k%R@4D23j&q!!0MNO$z6s=B@*AvO+PGe?LvMx)T`3nA4eH+&XHU@IbC38Ia&~T2T;Jk%Hu1814fgku)U=GY(tw{vzLBU<|3A^zeyOH2TOqmq0o(tMq z398`CncxaW#M9kX*V!P3d0h|$-4E>G)@j|JeVB-W+~{rK=wToRa{u2IT!AGR!YCv| zF*IQNEua-%p-RY~enbkz01%}_0wfI3;hDpy7?3?Y7sEjVFK`0q(9z=!U;!E+0?y&+ zl*p%T7Zz&XEU4NwTmv^`LpCIXC-8zLuz?#~0Sv%E40EYo%tc_mj!JQ8zA_tt&6Y@eba055=VILyH6jos#R--k3gcj<@ew+-Y z++X26!#Ti%I~b4xox?Lg11CH}=TM4Tag|R>rHUwfa@Ieq@pbsp859B~Ye&F26okUJ#FoGDY*+31*fDY(D4(vb;Y~)4` zUDl;t-X&h zU-Fe+4lKbDzTMj?q)D3IYg!;ms^YBezzysGM#^0c1ZNF|fC!W(X@=%!rU1w>nQm_8 zWr{!tAV3G4fCh}hP!^>yLeVxd#=1pS#xCv@ZeMM5Mz0wi1lG(5vP zfFpc*!YF(~IzF6^xnWQMg*)~HDUia2Fv2A)!hjYifgY%VCMbd~sDd^qgFdK(Mks_% zsDxH1g2#7!kcmM)WW(U-0 zjg~+NsHSRirUr6(tRLNbhkC)m*_)F&iB0_SwjItoQQ?gx4LXDEb4qe8+bG%6!# zDyMoXBy{SghAOCv>ZgvXsgf$HmMW{Rs;izVtg33PrYfzr>a5zTtmbO1zN)U`s;RPJ zCVUz`o*JLBh%hjNC%~ErOy&cKzz3SZWZGzrvZ-{|=mR`J2Q=%8wt)8CUh)M2Lw?`L zon{UsWDxLx^D!OMEy1~h>$$pOLq6hZ#{Xn7LLzEbUYbj~AO?0R0T#%97;4r*FK99LDUHj;u+fP&+h zY*(PH=cw!^u&m3TEX<~C%&zRrwrtJ5tjy*t&FZYp@+{8oEYS9B(EhB@7A?wF$UWjC z<~3}52tzR>>x(jL3pgaSQYLg-=44i@wa%#4Qb3D#Kn-}H1yhMiw01xV zuKM%?M9W$Jz!#i(xUvM%br z?&{92?AC7V-mdH7F6`zm@9wVe(ys0TZ|@54@7nJ0QtGfSZRENK=Uu`QylCGpz?mK+ zv-W7z&ZuR+DVt(zjfz0uwy6zR;0vha4G1n}a&L{MK(k&yo4&vcRILa!fCNm#<1ViQ2i)XlW5k}W<$9Ixun3PZ374=5pD+riunMm*3%BqH%b)T-uwf)-GVDO&M&|;gz-z+5 z{#vi#R;COjZopz|5PR>8KL3E+t>(wwfC+fO`*uJI1Sb;{EZ3rM-PUj1dM($^ZwCnR z`-VV7)&Tek?gNk<-wN!D&Zq}qsRvZ12h@NGuxSfuKoK|tHOep^uUG_2F#Y{c#rOy2 zaxMT)kjYGH2M?=LYE>>QG9x##BR?`EN3tYOG9_2CC0{ZoXR;<+aw5lY9^(WJ+wlKV zW(w@U2f`@=_~`Wlu?%!(i~6V#AF)I#;R~py2skm>VsVfD==C14 zWwrp?-tzl;KyzZ?zV5HA1;PF{X&WQJ8rJ}vc7O)}<7CP}1b{&_e6lzfnV}?drB-ei z{xKo_2Rpl=THRBBj{mMxdM7>CvpwH4KIgMO?=wI5vp@ecKnJuy-}5-vM`C(IMvih0 zqnr=4=$QU+2ed#6yy*7!XyS&z5rgsE~vAkI~(#LBeGSGHf%S_ERez?2!JW0 z^x-aX^hPw+V((lRvyajwMh`Aa%K#5Rb`gJcW!k_JnDT~^H1-a&Do1B7uXHOL@eyyU zmGbTTB6CMiZDbd)DpE0-Mz5C&ZubK91U!OK$F_UBQE5X8Q&%pJ)pzJpwFf6MvA#Ed z$Hy+@LNpwMBUHf#aDbBK07^&e8;8Jd!)?|^bS?idX^wYXBQDy?t77M}tfAx$yzkv^ zYcLbGcSm?H2R4@C?MF9jN24uAUUm*sxQo^(oVG76%Q&{qv;<^Ad-pew<4=6c_h~ov zbh)GGR{wP;_c)R>FDW>}73_fu>{iHKq6c^_1$ga)+xQWyGA=IwX#yh^BfxieDt;;1>2=w{>*;s1&ET2&{Mu-1RLFt{9gujn*jqX6v;AtVa95224UO zBsroV&chZ114uxlKf0qwI;1;zSb*HmJ>A#6-QPXl z=e^$VJ>U1e-~T<}2fpABKH&?#1RVOnbDlID!zJ*|9yIwL{J|a^+Pr07*iIzc{{N^6 ztmtquF>t=P>{HAA;g9Y8yZ~jK!k`AHD27vaU(>>jxuDtsBwb_50*i;1n~hQ zgbAA_PT;(Gg6D|{0wlNyMC(>jqeqb@Rl1aEQ>Ra%MwL31YE`ROv1Zk}mH%s3uTYms zurQWvS+i%+rd7L^ZCkf*;l`Camu}s;5^{ajyO(d@sIzuOyLQab5Ghya?Ab#n&mTH; ze$?zaxhD)0G);u4sk!D2AD=(p5FLW#O3^o9)TohT^=Z{68;GFb!Gj179dLJ`UAuNi z-XS~yH#wYh@8Ov>Xb^EaN6Q?~S)XhXl1C6IP+;7+yff#{o7_)Km;iJ}9Zte#+48%d zeS7!s;m4Oh-)UI8_wnb~zn_19|77u^Prw2D+JzKG3|s7vKNh3ok3JHEf{rh~kOGPy zc!D8Ap1?anLk)Av2{ju`;K2u%PCJc6g%)gF!U~x*vuVQ*DU(vCoEqServ@gFAgD)ZnT5bH$t=^%Gtr#S zzW>;4)6F;GY%{<#=|r=bXpUKgjUo2nGqDCAeC$s|_-KR=#SoRk!XA9UX+sYo-S8&P zzJmcY&{`TYg_4G=VYnqhRmlb;NiEe>BeM&_v(H*Q&4<%W(C)j+JcNNtEgQfogzjo; zVAlpB_(_5p79k~J+@p=h`hc)O zK^b&xLJA*4R52-Pg`tNJLDcX&@GQ#?1{+TF0lF1~cupjjM*qrjBp*oR;WF*?<-yWR zJ=0gaA{U0i#F;`n?F1jXv#9|PIdn8$TOZZZ&xhDZQ7tkv{C82r` z3N5TP z3}J1`Am>1Gpomzc7-48pFX+uV@7!~#aPC?3(Mf;v=g&VE=8?koP-8);A8Xp_JP=XD z_N#HfS`tMh>HU=6!`|bNJ`|zac;m zv;{GyfeXar9}Ypras{eF91|IpNCrdkL5^NDy#H1CqNg(H^-w3|i%ro~x~iD-i{#0sP^1gH)3 zbr53AAfGl!$Kb(%c=%u&@GwH)SxuP>N+uu!`Jg{|&(j`RYGmBs>Vg*A`gM&btz;KO|4qW(X8p*gIJmN8qc%*|FK1$9zqA`wf z%;xQ|_8{9Sf{b)%;}+bAhd6poYKpF)=H$GnhbgY^Is6RP#f`S5d3ouQT3RVe-SV=?`wUrxf?Z%l?GPMJ=J%QYMTU*;wszZo8fd&=_$*1m$ zxktR)b*>|ZFQ`Ecim9$*2(<@qeV}r|Ko4F28eZ`-E3bSt?|I?k*YSE~7QbMFVcXCc zHJBlS2`rcJ{_s(jda#YBWuqC~=>JWj{z0gu4J{e7$u$1@mzmh4AO)?4J4A$5Yl)F* zIlsUKvQ@~ih`NGe4i(~ZN`VU`rqGF#ci6-JX)%W_;frBBwh@O7aR z{_%AV>?Rw`~Z*MHG`T0Bhf!ML+pglo4u67IokjX2()5yb~V_l^&eDDZot$IO?$)_hR8UP@m)kok3P2Bb>cOuXUs zF^*{@FdRULZ8)5Hvtk$*AU}KO(O$5EiYQkgcWS(y+DlHS=4P8IdPYI4yO@HMYcjv|a7GZn+>tT?(0@4P5)e z5LP*fx%!&qCC5sxcb#&*_S)o25e74k!G>~bxtsF7CfAY;!j_Kl*(nVzxy#LFp7NBy zLj5lsoSF1(Z@b%L0IC?^(3k_Ou@8tScez&jv@z#VP)_?A)xuUafJ5BO-R8JsAG<(0 ztoe4uD>v2re09gfbpJv@rqBt$UMqc+9)5Kd zAW@85fVbt9w|r4hu5!)alI52-3Nw5$gb5}4F;qYH9>_hs;b}dDLY4Zn0ZG9&(|MW| z%x|}${y{O|0qRK4_D|i|-~W!Qo5b$sX@Lq|pmG8CXNIZb6Hjw)AOEzZCMa9kx>=6L zE_Q98?wO5`X11y}$Y}Te_cMHV z$mVPC;;%u9?}Qd_LSU+a?r1TLX{D4f8LLbhLa&^}rSz!ov9_)gXHU%VP|d^)o7hZ^7z5oz3u{QL%o;-i7X-iv zY79)V4cAa z4*y+B7GdhX1hZV)Z`e-g`OKjF_(%#L4gS=?fTrMO{tqT8GbX8sCNWcgY|_?pApzOo z3J%L78)IDbsM*wL**Z|D;HU$;iP_rBc0e$~DhNXKZFuZ$9nGz3erGrB$aq!{k4)|C zw(a=1E%?oO&Ef~ z4bH_e8feSlXp98G+7gWCwC0bb^N-vO1aW70a4KtVlia2zqc>*lnlquw2~E>XI^S{LFUt3_?~^7%}d!KJ?v4NJin!j>3{8U(xyA(~pSC+zx@y zhAjtM#|1IY8z=OHR4cWLPmF?T2#5g5{Ig5(>M{j1Oml`nmF!MFfltC{F`80%9)pdL zt}&_&4-rgG*X?N>C=Wg`HXFelb7yy!^4Q9yNAJvcc=LB&aWU2I+o&!@=MYBK&A`$q zN&7T+tnSaGCXg_WoVG?#XS8^x>32jF5&TO9HH(d~ul#0^f$odXs8BwcbnP-#P^K#} zpKli_uAB@*OBV`rytG$?20+C$Snq>OlPnqx0WlWHnx;;T?6I4$&9gvj_Ww3CkVY`b zh=+nKXihf}D*H|Dv}|kG?1DgbgEZ(5ya}2paXh&&AHz(g*lyjj$(hz}=%6#`c1nWa z^}w=5n&7QQk&@6vR1wfp3{;C?yNUVq^8R9{7`N{+vdmnxhDi&Px=d;pR}@jdubVz@ z2&kYCCev3z7F&Q-SV`7@s-y;1KJ*kesDlJ-*_f$8_o!X-ky#yN-)!>}8`h6_kdIz*4nxc8if3vh z0lUBs?ht`^IMvXA=R1iowLG#4z0cbgs6>B?;!+gZn$#-Ws{Q&1B>$=F2P5t{3wFnqzV?k_&?@Y#yC5moaQ-^eMAvJqx)v|N<5TnZ2!>}u$Y za~H%#_lTSR+rEjJ{BWgYXY0073C+*>;uAZyFjk2zQ*%_y4wYQ+Z}GhEA@FEf}}1hDHIwD2&$Vr@V>h=m3P!^>qgfn|`w15^T+Y?!m%lo8ZV1dG@mq>}FHS znm(`*?D40t5-dRo%`Dgy8O)pTZ#X%Q?JCt?*$wN~?%ryrMgNtQoFpiP4`FW^bumd3 z^?>I_x$l8el~!vm>(oxm?k;;zw6QR8IE#^BwU2vYQSrcV1*%{r(<6PEctF;-eW7?P z-WQ_`lnthf%S6gtOYx0DsJ~8YW-$=<07;J?1L@9eYU@l8*Hg?4v48cAbB(gu>Zo?g zHX|R9YqF;MmC6Cd)Yy3L@t>&VWxiD8*No;ZrzcZwZ~Xdc(F z=If*staZ`oX(G7WkgnPw6p(wbwF|^LiErM{?D2-C+h|WPU)#rW^k1n)#_H3qTn2ksc2U8W28KZcK zkS@IdFWah*Q0wW!5}Z&O_=0Z>4(iofiEv{%qWfZ&X<2b?d6%Lg*gk5$tW(ZD$c+hX ze~oTwO>;qbZwt<#A%id#(TL2#Eh!rT7-MiXClJB#l#YHU?yAPzyg6zCx%B3=f$dO^ z1o?uj?!nHv=hRu96*(ZKE}NiQr5dQ}d~`wK%=+>+2^mNj%hN=YnJ%FKE3przfR7{_ z>mO|prhxD*8F~X4pct4@qUHK4D7vCc_M*2aW&c+;G?UF#jj(?)kSm*wjKa9+oaqd( z5-U@Bvz&=7IWAp?3OC=e?RY8=*m9U(_gd-M&*)eLC2^%ndWE$TYJF17R5eE9PALO2 zzZ$k_w|Wb?k|$RR>1sNqV$g#$Qp*M|Jg3hU)lL|BvG_0-x|krK@A5i;>Y!PXB7f>V zyLbqb4?_e13*dU>=K8v|qOR>)Sn*nl9QRv3in%K?tOE?QcP|4cFcO_9`4ZbWu}v)D zK&n})v7#wkCCHo&*-kf^CtsEEin`-YTOQ%n1fiE4><*gS|9Y3{%iGh@#z zxf@He@Q)&iGZ#OKLQ=~iVbOh%x3<8=i!FnzY`jm?_F~gIHxhc5|ZcFT- z7+B$zu{*~>2TZrS$JL^{qiARr0dg&vn0@N$EZ4PdD#3!pJ951f_7F%kF-mPlcdzp!sEeXOmHx8THl3T3L2sni5O zeG#026%d{oT@uw99x1eY)iV>wp=cL!;TpKX5HtZppsU*k48RYp!epD6qb(2Apdshd z3xeII{1>Hymd&&VzLiklf^>I~Ek03`b~Eb*d%C1Eb*a59Q@u8{q9&2|O>7wCnM>H1 zUQ@w!_Nf1D5UB=_qUOw2@n8uy`!M*-5*;lwQl+u4`tlay<{X8`216zw)JL5aY+T_R zzU`ah;US(TB_4`sLG4GK8~;3k5A=Nt;*{9OSOa;=PCp2wD3S#o?!QKQ5gYNT!_{8v z7YZh_5B^mW$jEkDFShlOc7573Q#ifdEJ9WIkRxzIi;{S-4)7P5>WF@Lm?@CpuBho5 zBqJEQlTXr%kou6B`RZ{7OFjr8U%#SM4Rm+lq#y(e{^0AL7Lr^w3QJ;wt^F%ZQGGa%H z0yk3B*e9jRjdaX#5&xrx&c>B0JxYuyW($-pTtKSHxkZf7heEd)h4QdX#5PPtMpWYv z3Q{$F_Uut)O4GH?Q8keEa(S z3plXg!EBdFuz)zR;>C;`JAMo~vgFB>D_g#dIkRTW5^@p#3_7&iS!Y?9HeKu*H&1Su z_+TQ2&cK0+8riZfAr;g^W~k8y zR1Jy21y4C~0smox`wa+%8R%7{n{FYoC(%!0i~*ER`&p=zM@*fl22?#En1@w}>_N~~ zDMj?f4<>{))>&w&wU%f;{s?4{LJmn}k$@StS&~XF$z+pGJ_%)Fof%1`kZI|7Rxznv z!{usj{BVMO5FMn5Bxcrjo0)1Vk_Uizn1M%}$IXe*9~Er}M^VigM_VJ&Q8$oG7v*+a zA4MISQ%(+n1d@Sp{AUJ$|1pI}L)g*L(4_x~lxT=scwwIx`TaJ=7D|bShkPFOM~9s$ z9Vd`=RiQK!MYe84Rff8zq~3ZrIiwR4`)$GKiB2WxQcn=2WYr-rT1SUhFn~3LBiBSD zOfIzWxc^I)-hK;ixZ;j07?M$*i*CB=u8Z!JbmWN!WZM^xYLA6EK$Z@#Yrkg=E9jk_bukH7co0!Il>O_5HRM2}G ztJIQFTci=xr=W^T6o4O!(S|`2rTX5CN+~oO&jCF;zd7WiApI4`^~ORZX7=RpgRNf30?S?5tn#nbx7iKmJ* zwS|~6I+RO5_2eE&y{+`c7f_tgzyw2>jqNV9sLgl!>aWj!k#pk>fBf>#51HQWzb)^T z^a7q5H@xU8EMaXyHf3s@z#7M@npMruHY==9Cqyab&$-~5Wr?W_vj6Cnrjsu1EK!kAQSmL4J ziCiKgr1VEQMM)MHzHlJd&14UVc-j|w5P}9Yzzx69l8)APzc7k%jAW$C`{;+pH27x)Ce0=2V)3n2}F7*yo4~tPQ^pc^l+9! z`B+Y2(78^eAcY4pq)vALg42I=_8yyvCv*6b3Jiafr{5&bP7~A=^*m^^B}Sx^HZxFn z7_}&&yrffBTaFl{!UO@13YXPO(M_JWl4yC)1X^4KFs|W6^MTQg)U2j8-*(0|YIB?1 zyi6OfIW9Q<{P3S0ATgrlz<-8I_t^aG~d6gL` zG%QaQg+JKwPg6|NJuEg87-sq6`M`Jb5+~rIQAgEy;tD8D zTtzMh)!gji4*_i;&=RQ~=;)?+6%#C3ou}21Ps9? zvuJA;(f56d8Q zaHEl^pmabPC6-K5Rvt@HimjC!-d|xwkjL#|RHaPfLn2Z_@Q{pWU;mBWZo%`_g^|aQ zDpQ&4HbSP`pafH#(kMf1u+C$iY9ij#;t()f(`|7!wfya`f7>!z(+YUN>q6~+RVxf< zB*O+KpnwN_fKsX;qF}Z4lklpeofW=JC@GwcZ3LE^+2}hZw z#b!Hu;4Ev|ngJ%Tm%q#;18@0TX%R*?Y!CtpEFc9TumKFDa<~DO2{-)=;w&R2lraS7 zowmWDN3`ah?f|EOJYJy=OW5KbW>p{xqf=G(&>&UTc(-xdF8`1jrn5@#_F?9QPkC9q zGw`7G$FYJDLKq?-3gM@hE=x*FV30+zKvNhy+V7ZejcYM>8O*%yb!EhyYa@{+8zC@( z2N2MK7lfb#3xF>ae$X#sEe)U`VQ!n~&>RsqWH{5=s;g+S74Sf6punLgci*&}OIpf8 zDPGT}h={3%M7qRcwOWl2if?;gcZl&$_Y!k?6j71YW!M?wx~qE>qcjCr_8A)mA|L>= zXjZ>i4z|TF&bD3qdgB}ys%J1BE?QjU3nzHM0y@xv7IXmFZ8pIPAWU33l&KH&!5O5o zoozT-4GtbjVR)GGDCz|zm8qOzch2gjgR1hRJn>0WkpC4R#X7|dtM-&}pN1j`Nu?)D zi3xi}5+DXyZ=zcJSw7ofAR4CK>JviBN->HvkZi#R9tgn$8gPOs9HXXbsW{004)`i* zyyJxTHLwHkqg_zL4Gu>+%8}gx8>qS2KIp-c8^nc*v-_^}ewbNj&zZeH=XsKT zh)xmQw_6OjrTTto*}~bk22@JOPa6!3l^@;~BGd!gzSdKzJkQ%LxK*g)i}ahqtTqN{cA;QEV+g|6z)SJ z7U+mF7WCs;ur%sA#tI1Q3RPqRBSJx)^I#2qY1@&2%CFZoc5IH!O*1!bO7JNX-`IN< zJj~^h??-gJCv+Ypdi0J^1{C1J1-!x+uu;6%KU4nQ<0-KP)&L_Y9fa6P& zsBAqJ*n|b-M1o4oBARrFL6|hTuNvS(aqVIa!)?1zl;8G<_S*vdGEn2brga2f64fNm z|J_Qk$!}Fe!;Qu+g2#yNr1w*h#6)Mu(97Dz3bE2=Djwl24bJ)TE=$571%I$!7w}er zUejd$pF^QKgDl{HW#dkMQa9%)3b6p-4k`k7B!Tr&sd)<7Xl9o3A`p!PnfPCFiOt^o zdj01}UaJgLL%R@P0G-oR7@iE66$~EXmkN%{)%4^Y)K?a&6Yu?DkbgJ*c?quuwa8P` z?GmF%yr1%1P6qo^I`bQw7MkDo3IAAQgan)|0>Jhqy+FYqq(@J=%s9?`!+wnoUU~yY z2icU~`W74TQ}iwgah47;A%Im0;EpA_i#3pkRPZ@5P7ztA90qz8dKDo@!UP+}j%H|Y zXZ%fPUoTJyAC4B5mz;N&ytl}HiRvucdusYQsu5Dc^_K8^6MXx#n1g(Yi|3`rpK&)b zD^Gy~?3t;3JKz&0`)+aNY5)A7l!BlO`JRS)hC4t6Aqvd^_a%WO0MM$JiNwrmoIz>G zRCS^meac3-_e3L10+}%4)CnL&1-KJdAc+FW`4>nc%h2Sgs8^v}f|ZR${QR3@_QT+V zknA5j;2+jE^pMqhWXO#vunDrV^K-@DpEsJPZrn9w^cWuBIPDKIp_gzqm2icEc#QNs zf5v&)RH=v6v0ttfu1x7stiJIR-2Aidc6g;%_|>DpdJ@#T84gBqRI1-g)%#NGK?EON z0*N2M->}yh8eN-Nt~T}Z4{N!3t**3`&d^1HRhgjGfg3y(;I18@068w+s+NZdih3ON z?J(+gMd(ag!9-e#;4VqLG9}2i>7HklT6z=lGRSYRUIQS1ibMVl_*TrX%8S3izRgxa z9AH!bTbCQG8Y^za4c>~WbPUcaF(k^Um8FEQ_}^2kgLy>>uo~q_1tL>X!Zz6=;U%4! zq3W!b-&0^+4z6E<4UHU0Cc8IV#N?iZx5mUG(g?>jmK?RlT@B76WroZKX;i8-Jrw3& z=H``JGVM>Gm)scmAIQ~|6^Hh3hej~62b;dZ>Ja`_-G8uP4xZkSF^|FT`B><_z1u1lQ?i;W5Q0PcqXz2VT2mZ$-1;BjTy;b2tR zN~3xr_&-sQF6sKw6j-7Q_`FNC!?s%}y|p!~I{?}sctyC2gqS*rGem(U=^!Ik7MgTj z*B{KiOy@Dw<2mTePfYdb2WVHNaDrCYCCRZR1gfENXO1*!6oQbc<&9SB|s_9(5~_z|z^N zN=KkKHU%oHAa!OIjs%uxwB?1R%G%w%G!?458v372ALied-&uE}ggRC34T=o({z$(g zGS&HT7kJuuaPt=+x~~DzbbmdwVbHdAa~CL0Zcs&LhwK4$4?vU3pwC9xk_3?SaHoR) z&HpZe1+aaSX$@KoupzlYIc!K8oBezyYI_%`zyO~0hpqU-eSgu>2Q}O?z(^KXig*9d z)pO}p{eO-k#oHdm1z3ssAA_Zh?|lAIQ(o0&a!?cL4OYF9ePC6#t#nsW;Q{|Z!{<*E_ys<_w6sXK#RGWMfA9({8D zV9Uy(5akCij)n&JfS;zo#-y0kvC+bb&91fA<(wMGv6D3y_U zPINeE-}Cq0qcER;0QQe#(1Jy@SyVAusV9_~|)1SKEP!~l_J4wKgQ zYD9dVJoye#Xa`&Ej;MFV{rWX5)!z2m7WjB?c;Wu2LVKIlUR%c`xSyjhbM1j_a#Wu( zNXmZH>Pnp4L8+D3@%WAG)TiRNh2M7>lBXVejj5B{jB@~6M+2C%`4S|yvSGOsuJ6P! zf@g4mXJF|1eINxJ8L2X76!MrDH7BJ%7dyhW$bynoz%Tav1zH%sgEuY@fxTLQF$_e? z82i1$tOezJ&Pv$=tf_&1Kxx#l)Ea2Oqfc>d2xs4DWHP{1o>rKh`sy=tTV>kFzSrJ+ ztn>Heq&p}(XGkL|RgpAQ)P7%d3T%H+`b4P5`qyx_{XY8`y#}3Zjoyt+phcV!rW=pok{O0o`C_8_fy6U@V{Jkmvh@-)B~q+~T->;q;*%mQ8PgBT!Czlsqv!CiTSv)Uwf-PW#Jp73tlD1JrQfw(@{o2CCwoO!!Zth^2|@p*>66Uzn%PH`ekI9!qYLL>Fr__5Vz>{G~ZXY zV%NVYfMVZgIT!&St89>XUuck6TqeB;I9S3T)`)uiXYOtCe{TTmk3fE{>=j&`T;o4> zr<|D!>i%~)lmHDYLVf<6gD9>=0OBkI9G5wyl=!gVUIS;$Jg4tGb}#A7{Y@47ht3hb z^2{t}gT?2OwGTKp6YjrGs7iIWdv9JfiDvb_%j(qlm^C!r7T>;bSp{hPL1+;5f<5MV z=6U2>iD8)2`rErw`scXcWhlSH*={T|vn+k**OyE05!sxvZP7;{Efqjb*W1{KoUQ$? z0?Q4ZT(v`cr7!I6)6{yDXO~RX#&=ua4;l69d-phdB_=wI{Abj;`mkq}`>sah`<_EU z;ou!x$+D08^v`?HZVlo43783a~$an3mIu{){tUE33>+QS)fhLv`)j>g|q zfS*UR1$W)BW{udigZb%jQ_$N1g5xrS1D-Xl+O}W_sCCJ>{h_w=%i70c?z@~!fQx;0 zyyz$OQ;qMvhJLIx#^0J6wC(j(9#V{IiiKalO?)zVdGuG#Q0&x>#=~L8N4f^%80bHo zIY2_JGr{?G54qcbN(Y?Hc?TgpY8;OaT2>BlMsXTl5Z3Czddu^(42}!_Y;5}v`d2jaTXWq{P(#}s>B=LO$Wal4sxyy)k};2C~pH+0}$6Vpf}n-=idkO zBH71y-ZlVW{#dq50DOKJ@oadf{uHQZWslK1aR2Ht+>X(C`{*V> zOepeVGkO!6FQy*%yC*=Jdeiq_v6}DTo|w9bq07+W&jK^i@SgIRw<|CA&UOV%t1d*?8TNiO)BJQm5Qnk6r&3wqoegl>ztU2JI|lX}dDKMYS7mX^)O`wvgEP4YJ= zX^bFHQ*ZI7irf-BL#yInnTuQ~PVkCo>rGgZyz#PcIkM0Yh?Y*>3P^DrqTHNPf$9+0 z5ltsxHkD$4Y|(0Yrn~^Ym|iBZ+DQrJ`C`t@X9o##Eu{!MirJ(iRpuLH#9fdh538*C z-a|xOnKWy09sljh$l(I2Ga{p$iXh6rWo?BIwTz^mPm zHo^%x$OwuZ1506W5GvcKIy0!2NR)GEl4{2g-wJ1vGME1$Z7Vj;n6lMw- zuW>_ym?y7@%@5pqo;Fb8)u^~MGY2Z9nX5HVW0xS) zWR^4_c()LCEss%z0qG=m>;#TENSlpejfxLxm6lgHa%dG60K4HBlL7*Pu3rgf$QRjH zSbR$E;(eMr?0g$FkNR``(}|oHoqt`Hh(p+xW1$Oq^ZjY!LN1TRG*r(%o=ubQXXtAM z*RhEjQlJubsaN4CqKgJ;Xjv3+3O>aih4-?`1Iua1=PI~-rldTcx;s~mWviV`(?3K~ zeefXBNk%1y9TaNWPboL0L9}TFh}R+bSSEIzo1|M1;$p_Jy9p3y#-<1tGn6FX+o*_^ zoN~PMnHU}63j@gWZi`^b^8GFTxmU;;N{E+{`?)6VS4S9zx_6m~?cfksJjUfOcI_*t z=}3q{JYF;873POI*8H6x%#Co`i)1}3MCYE9t%oOgKx_m2srktnjd!#tFP~R1X6F`g zdXfrMqfyFn(9=z^e`@y5wdj@byVk+nM5tUk{1lsQX<bqj$S-QW?* zr=FTu|4WHIy}e;W(9-ss70Cy?0mfu{M$-SaKp{u_+4LX!gG7l8t|texLf)iGdjlC! zBchrjwIBm6GKsbB5>>tJpLzBg$2}&o68`gq$|{gvF3A8~(!KM_$j}#pcNcDyfmlFxFJ`E6*NxtnVrCN0q`4`Da1sknOvZ6vHZv1y zT{h8&;nW^ zl&l|`>%7PSFp4xPAhEJ$WIw`tv9pM9=RydhZ@4n5pE_$!0&$yc*-LjT8NmC|+#j08*DcOfk0xTYszwE%xu43;1gTMv+ox zBgh|uv0IQyPGI%;UQ?(t%>7Y?(|4w6F)|9^XUiNNk`fv5wN4RNvhFC(n@#f{*JoY% z*ZAoBhx5biQgzwyuiWi&g-P_I*$7J+O~FViN79(M@VAsx7`4iI724f5f+3s|vZ)?v zCXlm)i8!T1aGNp=vjDWM&<#>HpJsqk4NCQjFYhUJVR@$dsW5;+W^GuC(ZIgBCf@l? zDhXg;(Pci%CSNp)d5|yh9bEKMU**|s^u5%t=2PBt1;x_@QU>^Yb0m(Tpk%}%DnkXGXn1o7o zfhdRca1IKL3_VY$W!&shp|?ADf-F*ipEZDmND7Qjt=-9-=PVSbmuGNrysXM|%4}rM z&~#R!_$blprqh%$6z?Ef5E-I(0DQA*_?GYVZU))D%TOOVBF6%_SVJ@jlq+JHILgE5 zI}jcNROBYa?m%9)8)8Q!)9+JWNy{5~>WD(5mh8BjJTq=-L)8|!m^;|EGp&zi0`JzJy&o#ps5=O z+wvn8R)IfInb3ZSN*kP4gAzuU6w(3ed*mq_>0Y`}vL6mSB_hY+Uwgn0d_}3lV;~Bo zlv6{!R@M^d`x^yd1vW{o&W3js{UHe6k(=4ZDBet@w7`BpsF7M2@{7%mz#sJ=t#yiL zR)d0M09dg5XFm^xVLNgsGf*r5x*YP=nd6l|l(|W>LskxM0hR8O?HMvwCe}1sj=7I{ z+ShxQ_LFzIQhoffc$OI!l}hXq4u`QBlfY^$kn++{{6L@biSPtTvu&o~nstg+$B&3W z*o>t3B#^5IavG(;O9na}!-RG*K#wWG_W=)TcPwU+Ct*rHkZ;AFP5ET|%e8^NL#uC&VS z(|j>dr(?Pqnvohvf~G6Ye9C(0e5J9M3#xy}f8{Gw{{Y}2rY57MW1*q_x$M)j zS{rF$02_G^kUYImjBat=*`~yY`kWy^?4Ns21n66fGMa7d7=X4*K>kBBL*SqmpRvBp z(@m1;91*DqD=nN)xxXwYAFSC}#2}_2@+kIQWC(7mE4IC+0OWW!)b5K(Yoen$BvZ{WEl0 zX^fisMl;3^<30W)yl0)LTC_V?JwEAN#;4A zaaZtb9rb;~+}Op9r5W-&hV!3o;ox2Z2#Ivq15y-Ov_R{$PqqeE1HltN*{lI6@XCVaKU67S^vwh^IZ)om{F4C>no>y4HxWF$UyN{t|QC|5B(oV}2{m^Z;C9 zU)Ezpsey2aYETd)utUStM>rqk5``aDSVdOcy(Cj703_WcLq({;fb@TSnk+ER+Q3#A zQOV`dY$pRiAhpKk=EGQ4u|1T164-?VL9@tTGS70Opws=_e>EToCdEiKB}SV5?}6Uu z!IGvHDcseGFGuhLXg$k9#KN8Xed(1)yWUQ}IL)7Ma?Kdug6wZe=Y%pIw$q0?GSRi>{>oV?BkV z17!`K^0QJu^xu`ENENH3tcj_ zqD8_Rx0cfk#{~EsZ>O+_kZ9pd4^s?C(Ldk&a}@^w+KF?Mu!c+kRjr$S z*Z(ZNd>xP+`FiosMlX7ZqvO_NBdAq#iYUu>a>2?O0|_yP`jcp~P}=A~D!!1)>~|CH zaNA*9v1OdlQysGnD0T+2h7^;F1V6(Tph$*`cgmCPE0zu!xK&Ty{?d~1hdiUsV&n~i6aiY{drE>i zg5D{jbC*gk$siTq&*cIFR<)#}f@r?|e4z$u-@axTx7`b6`pT8l8W^`6lX6?zQ=I5Z z0nLF@r$hgK2|)RUhG)J$uJXlpfh7Q7tNzz#-*Wh3HD&~bYq7uDuy`k6+N%! zXk&W-VlBY5p4Pk{#uCd@SvV5ClNLT4Ctc?G;7uqYu~DO7XH!|+13g-70uI)qEw2@!jiT+Qp+uSl*Y zG=wmd%6lA*aA8tqlW2Tb8O4%H!AS@?A_$LS3rIo*_@9?ia!$JpHSpi_?s(~C0b;Oi z)zRsiQoVAQhhPLY2W-ce6AF_aMViDMTMuIesD~GJZox?c{C8g#a##1~SHT33i|0T; z8Cism48>x8R!SHX*IfvRT{wpd{?KY2UQCQa08+yIl^qptzUxv=c&r*Wnfu1C90jJB zV<7Yu*KY|7pPjef9=UaXP&|=pKWS#nT(A;RGETm~RU4zuUbXu$M)Oq8{&)2jKMAGn z*Vcz^9mq7R=IN1G)NMzI!eoHLVuO4wHKPONG}*lU`h46q@X5k)>1lOP6woKISst6= zoS3u@P7Z#N)K6Oy{0xwO7v<^W{rUn?Aw9YrjOui}zcrvxUbm2k$*{PRLGy^G(W^3& zzWx0im7Ns+R2%qoIgA?ywc8=r3IIh3@*f${5#1g3@XRpUs88E=3aHMcCHlTNzSAFid<)^!G-g|?D z0bu-786H#9%y%1X4uC=DZi}=s}KnU9=uk# zG5PH&t@lh^ZZXu61jG{KE>~KYq$1>&TqiuC^6Wn@-nbIt`6J=c(NI$2u=M6cth{Xw zO)l@QFE%Z_UlNU^8YR`Jy~(=T0Cn_F34aJOWV{r9xh$6vX^Tp6-85Hb!uSb5iLEwR zQd<4huzdEP^G87MTik1Tf@g&C^k#r_{ySyD0#5T$b3(=5`k8a3C7;9)$DS^him}nZ z83wi@?c+T4bl70*RViYIbcY`GC+z0@<8HI1{rEOztR^hL;Q07{s;382{{|@H`xAL= zL^twyrGt7W2DR06k;UO_cFIXe&fEPo(m;oh)M!N^B}GiC?uSFPDy597(ww2S4`y&dFCLs=XhKZ=zRp<@9ns z<$Ij7a$C)z2b1|9hW~ErL{_9p=T+k$AJ-qH@Tgxi`T6DDvzt!0ubCcwnvwO$P``fq z&#&*Fww~R-{?GB>zsDyTdomb`!Kr;fm-}Cu(&V30&m_-7P(>HbZH3Q}sJ_v61^9Dy z9%)chXm?SF zZ+=xu#=HiN&T1ig?O;N03SHK2-SfE#7j{nm`P|NW$axBtlG9yS;EY->@{=DvND+7b zh)RK-wRQ%3+1D6)1*#J#UIrUwrhci?FQ?1Tbo^w+ao77=+$Cyz8{K_c8mQ|PTvGW~ z$V(dIUN(2D!=32h_ny8}j{Cg1TpsiQCC{UJ999u}Ha&FZB8=Cy`>{NSZ@TZmgif#( z-$s`AY)8TnXJ`DTP`bTNT|dBD?f%fN^Zk76t<<&A%qr)EMd{l9&1~)U{woI#;se`7 zXZ!}XUm86%Na2>(N~HDyU5$Ob-7N89!XCe{mUrOGTw@Yf3!{Jz3eTWtQ4TEKSu zD^#uoqmpjxWFBBK&SWHjxX#L67!A?tA)JA$H_%^(>;7JA^oYNdddJVG0`Rw?DIl5} zepZt00aJC7`S9q&-Djr*Bpa}gW+MF5MSh0}K3@42q~>5N`vT5YEt`tTozhi3oDI9P z4V*s=pF3@adMu?q{KIVy~@^kQ3=M$SVHYF4cX9jAeI5cZ^eH4tpnVDbc z47-4;1aW_*!&PIfYHKclM5>43f-gTBNNxD!42Q5QXy8S+KreL}b;f1=G`^Syh{X0J z&1f9}l{gp|^m=zk-2)9dSbZLTkpY%f8BtZA^f)>!7L~l{RB+2vRz=&aQu6C(o$|Uy z$AsN8H@@p=mj_IhpL|n3H^R@<^#ljRk*1rb80wDqy8T-r>8?2 z??>H$%A!szAvB@-D>SJr0^8-ko0V^zl@$%@*wHKocXdV@HUg#;{U?y)%%p#-`%9%H zX}#_&RRyEf_e)RkeQ}?Bj#ZNKV0_r5Y-BYd5WU%J5$l%jO*?qSdRn3uD@v1@hO46Y zhsQTFvIUsvaXj?7{ThZQ&aLZ$^!q|nIHd5UAZe&}=Bk|kSBL_E?bPWCc_|tLf`&yR z9J8LQ&^O@cr$)H_H_J-Il$x?C#V(bx!2jJDAKHEi=YM?B@6-X~!6ys#|i9j_FH3wRT7MSMIDEoviT>S0df?&j-G3Y6YM) z(cW(7V;R6;Qep=+y2r-4ys`Jb#ldKSVOSL2r89E7OF$Ly%07hkM4{R-OXnZEBKQ6$ zvf>&3cG<}kwJR$+9Jfc#OfIu&H95oNf~h|Dq@ya2E>{z-5~1YDgSHsAbkY4R{?Yjf zT(u`xI2p((en$|c27y|Ws0Q~B_6k-%d`vvWK51U7|6nhgG9@LdzZxMN`m@9$#TAC+ z`mMxAK^}1N|nbCIMHK?6hanVyr|Eq3_K6eom;PplG9chQT){v z*K{L#rKxOS7MmnWE`oGI8gqF}YeVzM@KeECv@Vz*n=_FS&r_g|io}A}oJg(CohlWA! z#XsS-;gux-xmf^NYp~V=M`E+kJGK-)U7Y0pw8h0q-F{qx;TwKT&L|g^X*zPujlv~s zQtXz^6Gt}kli!TOKw|B#w<#8$lUVy;pqRm%=OVA2h?$PzmQ9-VzT5UsCDPPz(~#F| zbd;~tYg*{OKynDw1DNGmJ@LDHW$7h)E=sV;o_Vf1->YG^GRK13x(vXW@k5`{jYey~ z7gxkq3soZ($T;DHm-x45vT1nv6KSVw0l$jbNGgBx&Z_!hV6G{iBV=uGgQXi7v`O>h zi3`#{J;O7~zgxrY_a3N--AGLKESD>S>Tbj*r<>Gqqv%vVIqG06qt70kv9K;fw<`@N zXq3|whH+xtRC6HDS46!aCRkuR=Xt}T#M_P0$<*Hz3ru%D7h~jDJeXq1A!#ovS=p2J zWayc7VS{bBi%bpF!`kf#2?sRteD|#JU_ARJU>nR;cr-NOF2I$pYKL}2Kp)}&z4#c_2JDsq-Ag~i8Lm$*h`rwZV?@Kkl3v4Hq=RgE!q z%!vF&Q0I=VCNKB>kRYGwkUKjJ{gt=Ad@utcXQUSGJ_d-U;ic&i_Ll_VnCyuH^DL4b zzXuKbduAh5XuP2G_AF>Mhz|BoL ziX>oXjVMKV8j^mQm=q=Bm$j3zlJ2)lH)vfi6f`eNMQcl-vxzeTEzP)$yi&PQt%F<~ zD=kF>U(&lCoAI=Qjr|Q{r`J=IJqy2g(mWepJ6|_aB($wK3ltS`@>m+4T>_X>-;8=t zs{tLxEW1fO>M~1X|5_$9n&G=V5X~_ml=NHjk?!%Zi6C+Udmu{?{&zqX?g_rj-JgH(!pWM&CO6J#~7GXUSKZMdT{xsyglher}k7Zob7?vttX;f0%M zpjcG!*QpVSS)9-$?>Ue6_Po2tzH1ZCgQpT>%N$A4b@Wv4ivUL<==bn;hi>5~akp$* zo)>B`U-?`9a1Aa8SioJM&2@(n}%Dn@jaRaHbU^5)35FFwXMBRLidj zEmz_^G(BEr{57(6dl~vx6~nJOu9Y;|ei#v*v>NhZ=DN!hEpB30>j$5-=I+60ed)bT zl6iWtze$9IUI<=TfcpOT=-F%B|4Oo#_CDP^K_TXdqK4%L3aK)#6e$rZ|KWO)EKPqF z_+JR{a1QtNCs1M=`|yOp;rfjGK-9}bl8Z+ENh8~cu850xN!+2K9^$^v0W0f)qFuE4 z9oI`Z-#-?Nl}>Q#=(-vo|^hAlQ59KNa@7cAQTns98HIyW4s={TWdXV>z zXk;iC4)t3qTcrxxC>piw&~GC*{_RXVRf02m^v9r*VlW7ee5F7zlQgeQa`onN0J=M- zn09_R_6u5l_yJJlwm3%@vF8=m>X!m_1g#m0?#%9Sd?1u9xc zpPyD6fAx|7tLwCf7q<$~cZY2ub`kZO)-6%#UH#WZJ!v9(u z=00QL3*;)FiQ|&E*l)>BzF4>U6HILIsIu%w=DO`wJpMElCrPY>b9TI{tlDVuUWrTh zdhd<7D8WsiUU1*qHJ?u(hlM++vSKlSAgz432JnK`1JSPTp2=TE)X(n`s9QqaHF;7V zXc23(JSuy7wIdBVDic+qk@oZ+#Tu76I%YT`&;Vmev#X6|@cB@Och*o49xnBfIj{Gt zZwsq?9?L8PMkRv9e~w6K;EsZ~i=KXzn8bYrMx5vmn`}yC@sdvqv_q?H;z72DT~ohX zrnrYB8Ea8rD$CSHHjc<;wwniMxx@m8u)BYGlM<;C;462L88}_wls|`TG|GqvI52F4C{w zp`tX*+LhNZxV?ofycK#=)BJZH1Z@Du5GX<(tast*A)1lY$3mgJ)WL0!d!HNc`!_#w z%@~*tYHfY>Aj5sV0j5tJ6=u$p5cqe}UIIHS(!idk4-4T@BNf8|;=S{F82j)nP2NQ9 z@z6y>?@FZ>zVFSlnA~mp&^d=SuE73!k}WiGJ|`U0{mLRDSmP7A7aF_M9XoANe+4EwF*{nXyLe{I@udLu&@S}_Ip9uEPE+*VN4%JPKP*Hps<0L;?l{?o&#KzIQh1KL4?n@3?a}BxORO+osVK5&XzzZfX40Z+I#%PMss2?H})M zN$)%Hs6Ne6P3+s(P44Nzc>ZGlvY&ku*({mbyD?r>(a(hVa>F7YY;F zh$8t7{FQs@&aT*BYVvnAVK!S*2PouTZLLEYO^r4y=zWS_8G9-(YO?s8OYX=5_;01F z-S>sGvv}R+CQ`^*?r~bhM_q%}?FCZV&2Xr1a3vSSmP5lLNZ|b4Ej~4%1;>(#`_j9c zxl;k>Hl3;4{P&=3nX&d1i&>MiI@)OuE&WeLpOVJ&rM{Ow&-0YbM~ko^u1A}zQTHa? zw60w{kZE@)Hsxn=@speMh#L+Yz;J0ZpLwOVzH%CiU>IlLtoOd>IQP6CJq6JG!;|hqyC)lOJ`DT`)<~da^k!UCqFAaQ7z7RVVi& zNWm2-o=ly!`WRb2C=o(IVfXi;pNajKgNG+3-G%ue3KH`6;x+;n7C2-^_m9~Bbi-o8 zg>(|7YfzfEFV@MH`Aj6TJwB^zd2vOa3NNv-&`g|mwUwtwj>jI!GMlfu=v;ZZ99{S- zSFDx;t3bZ}TiO-obyIu7R+!Z~m7=U~b7rU?_9(Iy?j_FA~K5L{J_y5pUP<2%~pZ zTn4p(EHsaWd`R3`)v^Zbh7hDZP_IfuvQ^AAd{(&(DD5#i)GJ_X^x5anKEBJcRLFyZ zl&+v2l7+wGu4sy6Wy%;P=N0f#U%4lU`=h{!*RUV@^rKIN9RQ8XLJt zJq%xu$IZu_IfgL=E=sqBwWz8d5^_8JuNmxTd-L9D-!{=7vAxd%V9WV0NYnQ2BMG?_Bt!uPlsye=}w0cKme*rZ|;f~1msNwGeaGr3MbhES+(iY7o ztHet~$tQVG*=2t>H}DzOdIV;sp}au3`b;K?+wfhvOjfzO5=>e&LZro7=3HP_y?l*? zZM{6M2YpirH9b-N*Pl~Z7noa z>+6e1VHb{{&kBN0#|9Rz{kqJVqqH=Pt9%-F*P@&t!3#<^LS@ST0}ESCtq89~HE=4Z z{FxZ}9GW6f;U7A@TR>>Brt!1KPvyPxihdxt=o8-|*uR_nM{vnMRkCy`F#Ud~dmjy# zwtR1}9L@XE=*30#wx>bRihDgIP>y0lEPdrcoTsXHe=$b3$ozCPLa(n}RbMSC`;s{v zt0zNJ_w9^$<%9jQI-%qOosrc%GoSTN?6lI*iTr7!e@ad%v40~~;T_ftDofWO!cUcZ zj9Q53SC3`MSw6?5D_k@m<3UW7AE$6B(~?`D${oqTupB>Y>zlR7+}(28a~GedNpP)v zsS}D|{A4S%_NqjsB>^skY0V7*>ttX0OwZ}7N>?((Tu6N5m1Y_K1zt@nGo?QCpQ%Mg zr1BB&OUA3(eV+6J%Sxl>9Z;{m*4C`{a@2gPX!!7sbg@+r_CrA;zw(-gxKq)CDv8LwxO7tViMZetFH9yv`9@iuWhxfLY z6R+89-^WXZOY;UFq(!e0^8y;Qu+kM1P6~KMd7s`;#cP%QVW{oPkGm4uR$lr)fGDcM6md7hiRaaEvp30h5rTprScCGEBHPQ@9w>3w+FUI#^Cdm^Ef zcWfvVHkfW~b(*iRV7BBV`K*ndA79Zh|N700Ct~e@z<6?!xi<}$72o2d9u)xXqvK#t z1Gv?1msb1}Sn#nI-(fZ+(v>gVU9D&IB_!VE~Pr3rK5$%-Vuairp$r^}@Tdptg)?F<| zIb5-3?=0=Dmfem-*^Zb;X*em_C^{QbF*`yKF}^pkdG z;}??|*p^z}a%sECQ*Nqugxc3LCG)CIB4>Pr6tx1_BQ4`~vo7Vjm5;!MGXnFI%_Sw$ zcLx%W+1#`pCLzSofp$W0NPG*r+*$C2was6_F3KNeIc-mmF)5+$>1Ej%E}F@~kd^xR zC{SRnm3stf^eXFpZLs1@SsUvaoK;ZoMZ>`qWCKO*|M=-N0pXAj=k=DfRb|R~AAFo; z!1McaqiRm@frK$$xBgLyTC5`?H;PNArMV=FMoVEcV4+Hl=spw(lmS&$I&0!cx40Ev$M(Jb@QIQ8UbdZS@C~nTR`wrG{15Xi zbAJCl5f2FtWJu3KCOTefAfccw0roOyL>hq~A1UuS(ONqAXguN&nzC`%x=k(eQ20l5 zy2K|cY6;)jJ}$>UyWl!}&9?t)fU>e$*IVZ{H(O(3KuMd*S&U7r{&JMI>!S=yodnO@ zeZd#>&cZG3u|m_GdJQ}7RJ>ikwn0<;{VzZBV2u5(1`MG{;C5$@*!<<>mE{UVep{nt zsbtXfqjoHQHb6ul`m?2>&U)@7^a(LNq5Ko}7>Q%7@pYmo;ag zn%!CXzcpaClkLz@{HTO`Q$%^iie)Fa@s*=U7UZ5U(Gkw;l!VtY%%u&e((6L`8M72&lBaJS>_ zp#^$ikY)R&?WQeV-T=T?O{p4|Q4z4>6bSlcuZs0KhA|)b=UU7^lg`+Oj7Cp zQFI>uRDXXQ=ickO*SxMhyO(>p_THoGTGyUgQP&Jbc9e7%u6^w-n?z)jifd$5Mhc~@ zBpS%KH2wVkhtK1EKIeU2ujkW2Xoa;m7tu^;Y;y_|G*98}V$DZ<@b>iUn)MaDK9#0L zX^jhRYp-w1dd~HAKPR{C=XW|c&)(0aeYv`IAu%7ea;B}Y5$x`!5gw^cW9=&bpaQyM zkmh3qU*G%%Iw33dU=HGp?x|9dyu~TU1i$Xxjm;z6DZG+55kvwZ*|CbuGRX)UtzSc$ z{gDztH^@W|#);wtUL<~ESTC+I1#*N8g-Zuxr>a-1WfKUMRxt30-K#aKl@fW#NzyjC z6_lxJ$)N5Ze);Sm$?Ay(0Ww~NQ~}4OYeFVYt#~l4D}tszYA=8sM_6Lr2|YBDWJD!^ zrMWYO*bP-0|8(pKCdeAWS=pu6GnuN@0&Pz8lp^xi3=zPr-J!pPu{B>4!AE$>$y$3r zEjtqkj(?9lm_^yoyB@W3yXB&9S;RFfl;l@I!x20+>k@6;_d3kvjnLlZh|*{-jc1t` zakA6xHPBDQ@PQ|u#Yw_=Qq)$B`mP+WN@JErl42qA3}l$4YCfySQXXak{RuheE;ZAI znAYL)sUpF*hM4At=Cu4_(OB7eyIrs`%qVa`fnlmc6Pjb_(TZA(9NZy zs{*%CkHlFPK z-yk;cK3$z)+2FDeDn#GKJUWHIlRBtgv&%!XC9H+HfP!Er<%Ng=+_H|p(g0_ zPDUTp-Ki;YatE8z)j~K`;^=;7)(8EyOM*uMi8#`o!-hCH9@c@i>w{11O9?l$(zS(| zSvhzxa~qlWFnp*3ffh-TCK68rw(BsNuN{N?8N?xf|AOZg<$J@TmDTWV0<>k1pCtqu zN2U$fu?p-9vu{8NATG~w<#nb8ho{OO+ZHw$>7EnQU?sq-jp^EZ4d6wP)s8%iFw7Rd zk%Vcr4%suBa`M2@oc?sMq0$>y6)5uS-P`oj?!dSW7oN20P%=aw5(r0ZRukGNg6i2n=U3+7doOwuc| zmTa+pk}B+S)q8wF7W+(>KTUGm_yZ@ggwXa~oWm6n<>U~&wM$g8SEpJ;=*zWH*0
f>=(AWb!dhQq@vqRZH0StX4Kn+sgQ95`o87d$o?qYt1h0;=)&-kHhp#cuT%i&H z$YG+25lQ6KV#Qa?XTqP3FZjOYnk1VQ_Vs1b<#T}Wz2EInjU%&SxKvSb$1}+A#L8HS zbb3K?lKXpra-9mnF8wO*gjwky$HwT_Pz9dOz@cZ6>p0Cwk3yf!rm8cys%b2?LW4eH z?IgGwr-fe7;x>X^NWhj}#SKHUxz`~KJ`W5$vzUTj{-btV&e-CaJ3$zL(f@0253hhHZ>9tIDc*m&S34aE~wMZVMjTPRQ2)rX!7^PC^=e-|iS(5;<&T zmjIo4z7Rp>=I}+!*0=v~Hw$}vsV!W`;A5s;ZyU6$Ds*8#Y(FAtx+K=~IBCJd2wlY+ zW+KGK++^N(GyH_fU`n&cDxarsb8BMxM%ua{d7392p&7erbc>ne-w5`u&huX*&)Jwy zijfoF+k|GTMdV7WIA+;Fa+%%$85EsMsK!DS&vgOBeA5)>v~8w^soGxS0Lw|k(pCsh zWi^r;9@L@TC3DPXt@Rcjvt9kVl|G;s2qhEDOR#2v`*mvZn0BS4oy)BF8W4?JS5 z3$htZmQGw_%Oxq;wAuT9a%!yJzt%TTIMdC=78nKG(y*!8`%`FOcpR3BYtQz7*r>||E;&j$8rO|Yxu zg4Rf-{7GY|tH~H!4%<*ir~C)c>3V3_v6Dlp)=_}RT0jSm^t&dt+i!EaxVrRHi{i`w zeyhPX<_|^pgJExV*w@zhEgFEYu32v*kOQOS3pE7MR`@;m33b;RdoCNj8}c z>uN1{F0+KPbdQV0KE-@rBH9rl>B!gt)`&V|sOdWYv&_5C9NKzXQ^n6uTxF?1zn&;M z$?kaiE%7@KE8Dtr#7OggUc3-$LO)B38)Wc3g-+PcGv+9~BOKfxm`)ptNA12P+^Y{!DQkpl5vxcyah0Rzl?lbx0gG?f~EV81x zB&1m@hvqfRugO%@#r)tzcq3gGzGzh}#5jmgM*He8g0`$f*uJX8;K1IyQb%?+<2lth zg5NvTk`q>{@@bV5!S^cSG*i zvpVMSSXp7AMnG~TKl#pK6S<`ic|qP2Mo4~^`lByxP8uZX=g>en+koJxsWfN}a0!J~ z5k4s;2W0U*S02wwm-q8uGrM=0VrqV^ZF;VfFdrQ#9mr^W|2in6!SB}f<%9wAgwj)V z=N`Mg%>pRluJ#HQvxN7(0@|?kuL0$oi`-DWLRN$%4sqVAzI1uB6Pn5a3lLu}p(E{=PCma|(JC#> zGrVdn2!T#;eSA~uq;g$1J6w3Q&%?^@42DA&!2P!z4X1C__D@7?fbp#i`skp^g-{}cSDrD z3(~{ngUyLN`HRm6`@emdt+l>w_i*69y`@%brgB%I&aZV4pVPmqy!H{Nq@0jk=(0j* zPm5&P*K^SLz_G~HtlgEYif;{O{I^vmR46uaN*V_f&R;9)1rWA$rwo-Ij-WMCEXEij z%h>6-?a|+K?Hv`AXhFM4H0VwbL+1Kgz+>jjt&r*l6kE+j2Q|ovaFoIUNH}O_J>^W) z%yn^!uiKK3t6V zVibr+o!F%*QZm2CR*8&>c>K|VW8!sxXLe;8Y=QkO&-Et!8BMu)JSh2aURWZHhx&YqMf#^(u{A<<*4RCaDjxU;Q)|4QGO z=|W*xFu%ze#OBz+#II#8`=d(pcsJm&6t3)pC}?Iau`)3VRtP`B}lg;^*ZjPki% zIT(8q`lLW*PHdAVp`IXWeW{bKmK5LRVz#E5@&71q%?tAR$)sr2bw5|tZ|qXegBh)1 z4F7pk$v@kJoxDcBd(tsUHV4z^^q685bh4f1yDf-Cj=cf1g+Nfa zr3^2=qt4$d%uN?FT0=Hh}6+|8_m9lPFrd_?IR6gmoEVJbmORboN99tO`NiK@<*&C zqY*eKxt0TKqzf(3?Xjy_Z3-N94ZZADXILM35>o#DB|kC}?Nk)nQ~uk}bi5gc=-#LSAfN;Dv+KHG?IyCM$VYD ztajlw7HD8H6S7+5Fc~|y<{=4Rr*iUdQXU8k!gP(3gmsKXUiE=B7_OP({IYC#B2a{^ zQK#PiG*ll_`#K+mmM@8b;)QZWSciKbRe$7+#PN!~>;g)lQOMvaDdCnO9r@#fY!5;n zS7Ky;(V!`-$np!T@Jo2%L4Q`Ill#NFFta9e&$=jm$nbkPHQ6k8XjsFB3wua=Ze;K5eC(o0`f zMUHP?D{R>}1My`+coTMa2yC!MRu~<$&hxl9Sz>o6!yBQZ-MJ<$Q0l;{f+A~;=n1LT zPC^YekgnPESJzyd%6vT+&c-^tQhMwx60fyi1+i^nNVpCs>m60YLYqKM_q*#3q>Zw} zMM!l#-9^IrnqzqCLZY#0HrpkE37uq#W)&70%wFBw95AZEfhuh9xwgV%TP@KiMfwV@ zVtIdDoiU!GQ!mS|j|H9xcU0Buni^+VU1vsZ2BKx}`?KP)l(N3jdaXxH&*VK#hE=)Z=Dq#^;6qPW+^=kkp05fN zv6?XT!T_NcHGqbLb7Q_D3;b=-BqBZTObq|j+wTKK+8mip2_LNA{W7uusLwhW+*ptg z)?oz890qeooahz6m?K08)i_DKF%Dooh678QNd}(gcQeLPv_A2xdoF?SR7oCXDfS4D z+H`nm-+5UzX+-mWhI59L1!V%4(?J9w9x~fT#_h_)0L~4l8pj0w33=OP3Kky3#so{{ zm21(we0qank33-K!?I6R&rxU6N_$_nGei-aM{^1^$&52Myf8W%l z&)MmdM1cQO5_P=!hB|iw5q0}Y$hF2l-XB8fWXDuuWO;O54ri!)X5SRg1UCI#0t@8o zs+e|%%I8)r#UitBQ zjZ2#aeQLlGFcFd91#rQQHP>bs`g2Rd;d`^7SApl{bZe8PuCUW00({w$n7)R+6~AiU z#}vrv^nCVM+ZU#0(qIUrdIYU!Iuka{Z|Lxrw-Bj{oRfC0?l=d+;bfnWWthU`F8$4@ zxzw%HJLgfkCEH9Xm_8JntB{}2w>LiKCcUkN(5t|Fm34f!QMLF~y3wfV1k#;KW3-fd8{Et&J3MJ-26)>8L4o9_c0AP7YiX1SeZkeF; zHzM_hT;dj7%mA#$?I=eTFgoR2>|&Im43V!I=;#n_{sE2Dk<()e)SHE$g!2M!Ei&u- zpo=^4j**cDbaJkgr5+K4-zT{<;Fui!3Q67pDPXf2=H|SNl8S+KsJW;r&ppFe$H|gAbm)24<`VSF+w{*7+s1HRiN*Ymsk4I z>>DHA0EB{gY>#|{K@4l5mnm27i#X@lF>PML^l76=GfWRR%k8w8UP0 z(3{%-A$0ghYL!shxN5>*(AC3jr)%pXp6zGv6$%~>J7%Z=-4#QWBZz$;cO>*hpy&hKo1pI2#OWy zW`%Pk8XSZ3+d1b9~xSA`|WR=&FgVz9}cfHP5TXiJnY}6+DtEDBCUM_1})Z zbyXK~-l`#wif=_}cxA3MA4I+7qvLj5@#W9Gqm0lzRmKi_H;dI2Q&0uvMGE2mQ zwNFp+c64Nwv>XqgdlHD^0L@20&h~%00eoSu>){1XyAJaU~%*T|}3TKhWg66{I4{>as1lE3-EtTlIu6CW< z9I;nz6gMX>v|;-*I`p=%4D`Et;DwGx&sCytg#vzZF4(HY?=A2Mhm zDWyTKymC#*9Zo?}Xs_oL-}#5CEfxX=ZA+LSo^;SVhP9Yyk^An2Yj=vgR_ggji&EFc zM}q8$RW&Z_BDM~YKY8gdkJzgm8{B32oADZuqcr`f@VOq*ZoEb|kEEWu&)|e88hA6B zO%p8G)S}9{w$HIifwX_zaJa(MeI-B?`X;V4(c?e5Lyt3)l)R5ybm zt?~{0gFLqrSxjJ|%~U=oYUCEEmb6Ekth<*R)gfM4wpQ8qb4wdbEgWb z>}ux7B;%z9Is200<$`jG1x5&8Mv`T!9SrZ0Y4Ph~EXTFT!=&lmb+XS#%-%^x}-!f)9 z_EE`ZzC2UK60y(5>TI(+`~YXw>5Y;2p=X~;t5x0=FCnr>ytdaay~5&a>$fc0UB$k9 znU#*^v};dv+EWIb2YZH}jfHW}6sFcD7f-KA!dW}M->rY>*757X<7FgswaVE%fvf1n zs}D&HQ-OBAyAUOyy4t2_kSAmgHjLs|>)#U{z_P^*fk$W>%1J7nRqFC)EV8+wJwu$Q zEQ^yxJTws`69ycCep|h6Pxco}Gw* zT_wP8O-Dsj&b56cWlZz-u+fc*qC)d{9g z1Y_|=R~$J|tx0*XAVYF;XIqJF-LSa#fH`6f`T3At-Qkp&D3#fJA?@H^o=lUsBg76N zve3)^Ns6<47WBou{l2OQxFdd-S1kV8h3os!nEf-*ylVuy7hT0$S6`ihxO|<-D=EAn zYT0m%2?9!Z+?U}XIsJI>&Ga;qnGlYAt}S5z>gvl$bPgBR`mOeXRqX8nyAQMPiPGJS zQgE+6#@LD8RN!94FUI>>veXcim zh37FS1%#}4KeK!%S!)DJRc2PyqBmlX)uXDy{7F>H0LXDB>Pibr{s4e#lG*uL@lz+~ z^2S|faKFe0mdvs{sJL;%;vW0)OJ%_5BU$~@7j6dk^(!`HYSW)cR6SYU9WbT?MPU#u zADa>#8j*JGf%QxY@eEAV<^%h~3A(ivktLh1OfH9RcNir$vDgklVz71@lfg_tC;>aX z4(QzRS6EnEWR6L}$Tyurwgtf0TgQsi=JGmb(>;F%`x9QVcTPVVe0B1WVciS^4F0Jc9Ia2@Mp`UbN@e=JIid z0*s@L=gS^hLJRh9ndV02)Va$t!3}7jhMTV&*<^Bf(YQnKW%*wJ*-BP#DCBdLM39_w z4G=3i=IRisJrVUJghf!CY|%U3avi7#>koEv1JG8B9#q6V7`GQ-v40XHKbI{r$4st| zxyJ{GTpx)~0N&tuV2l9VpC;s&8!_f46j`9eo08it8eQ5f*VpVUG>UM4+1nIE<|u1U zBoX?oz35$bfq9Tv2hrru%BM(&Y=;uX4d)iHvTi3we=ev}m;I}> z?V9%DO(<6>QHtQq2~cGX0?ITzT`BNHU1Ew>jXS4911ax=M{mAv_`H&+qQwuLwG=>I zW|uj=0%(S7NBjm;s&Z65k&K1VZNhYiSd_&e=v{>jQGl1nJs^Pc#+TjIzn+LLI(J?2 zxlFJ0WjF}SDknRqE4!piJ_o!hss|B?xtP39gXi&RM4cB2bH;^cKM((Z4f&hHTPIENBKY5jZ+d7=QB z3oRR$p9?z!tgjt=Rw!_9W0&jV&%KQ=j~>Ir&+5Q97<9E^9}S=vN75{4>R8l#1R^#l zd5@GahnO5~RA+hzO1eoCdc*QJaR!ea#9j-?-%L&-Lt3?Ma+sYUN=Jg9#jXt=_G>(f_06X*GwWB;q=DI#zz+(kW^0|dW zMY`kKKqxCvZU}rug#{O$KB|<+%?dqnVG>Af=h%Dy)nXa6OUl4`JR4h-$KMfT0*M^g za{P>UHofPsNRSv7f1t zfH4TSbrCC#EGPQcKe`2P-%rxK0d*s=0Ot-|{8!ALn1x9;2etEDT#PW>*~Y%xwoI74 zUowlGi}33(vo;4Cob)g`S`yG_6KDP7bIp(xp=e*;Y;DEdA$0zrv~t*V^helh|LJFYl)6U-Aia{~PW8idPS4+Dw3R8a33rEh+Wij%uL=Bkj&&z;xuA zcZualMZt7*kiJqrOma-&^U7k_d5iRKc$M|#nouC_!Fjh2&xuS=2NL9C4_2(`jprV? z7OTv4*W6+~bKy_i;rpkzuRS=;q<;Ur`Z(px#eWIE{`>sy$?c0LiU0oo{Z@okb?U-^ zN}dgs-8~Hs`uHbHGkt7r^*F&>j&i+yR8}t(EEK&l40#Vvrpw}%S@ec?Jlhpcsgd_n zacMti)qUtc(K*6QJOPD3<<5X2n*jt>*vGXjy(CzuD6YQiEQnT z;#$O6a4-~_^A?LkSb-&-r^#~hCR~b9&DCIu=csKsY1gA-BnrCM^~k2Ek>ql@@FSg>6SlV^V6U0Ld>|4Q`2CBg zM_BH%AIyG_dRTU~Ise-NxzBVXQ+t$Jo~tS^TxYM|`ogJ3?8sDddX)b*kjpr7X+72G z?vV){ePr3td^wHn^InxySG za-&OY-#SZ8*go>5h=yE9%6Zig<5%97C)S%=6b6hzLK+SvHal|c`5s@fP9?roq3>?@ z#&C0zype`^?-ubu?Kn*ZmCgy9`F|e@Kk`xdh(nCfS+dBYO{jTwF|%wO-%$Q%GqouX z+wNjV)^&~2_hI&b0)fU833TE4;_<*(kc6))9ddwl@u!MpFpW@RnbS`q zlY&f5^61GzTL_h0){C}HK=lScA^!LF2FOU9WJAQbEQ+Mw+jmOzRDqb!%UUn0Jjrj) zXVIWnqdg^g^W}_FL$5^I6nvwUn%~cHPdY9t2e{;S%=Mgt5vRb z56<0-eb0Poh-CXvUH~z5XyLRW@mi|X^gvu8Vnm;dCTUzgda?JWcQ6{>#engBVL@@r z&7127mynhGihm~GCwpRx;zCGmF(2hcj-~80)Pf`!bX>IyW)#*t!hs(>@$r0r(Ac~3 zA2h_F7Ft7-v0@KQxf(OfrRwc#7c;Q%RU;zpEK7((lHQoyTVGXTyNRlZx#l=A8D`a< zMVFh9tm47l=_tu@_TD#B+>TPphLnb#A|)H@#|_R}Q+X44G6zx2umfCn$kx(5S)Ef4 zNw zR3pXLX_syzq|YKiaoCbc6SAz0{3l|x?R@|)=m$udu2iZOky|=}1xuU8LiLNc8|5OO zqW9NiknNRs2m1R(bOM}&tJCzN2zJpI>cD%>#@Nojkzs{oz7skPfq2v-o@uKnSTctb zqYj%7+k6PN@8){rt|N5WM?Sfui%wtAvpPQ8T@d)WI zv^T2Egj9m(1HsNi0&g(*^%|rUA9WTW7O&?EFIs9eF^fn$H|YC|@0^}5YI8iWs~XJg z%iE^&oI0*E&$75~4EI~6!nHCl9t*+V7-p-~tkdLdeAwh8J+kSloOU|P_pD;l$qGn_ z)p1OC6w!$gafdGLbJz~}h}zo6(iuIb@#-a43XK*~di`pwitc1FkPl@;$(VKEuFK}= zs5_ohyPLZNVo^f}imQ~mc(kJ}{O2#p(}%gk!%rsFZ>~`)^4Xjgk1Y9O*LX2qvgm34 zsUKDPcEUD4%Fo}w=e82es<8G#v9Nl~;5FK*Zw4(wm}Q)ntl6G?`c*T#JZ2*0DdFyL zt~SsP^~r0j<&P=SDxHOT4z|=LF^%w1hf>o;R3;dZBxNNV7EqHo~zFG>HF>VEGwV~zD>hFt!s##bRFAbqY3 zCn#5UC|#mDGhxb`yH6Vr8g7Pbg{TsTlMRoC+hXOepgCkLhk0JMUwZ2=ZSt{Sw|uxK zqQ^N8eCd+G^Xk62E#~^@C-f(r1BGfOsSPK^2%DrJYMiozi&-IJu=e-QxRBj`{^B)C zkYP^T5XG%tuYC7SL0e?_v)w7|O_3!calx=_*C8N{(zqc!hG;C z?O`VwL(~-RQ}XknC=CHdej6s-r^K#v7lA?MpGQIq}0JnQHGXb$807{TJ`=VS-(K49LW)+lCk4%y&$?QMp%EVNqCYfOensU z%K)flrwo(vn4~X<7#ViKxI31DAuN4;TDh{?%A+Rm0gkjgKsmg9J}*bzC%~@%$rK1} z)R-{^j+wokOAMfiwjgy`4@*fR-1cwEEM@_{cTaIPTHDyDzF=pK|&p*$9H~}Ud%>4V3uY^;KcJ4AVhKyn3vch>&IP-}a zl&%A>QVB&{I8}SXMt1_OAS~{YO5UlisMyCQ?eJCXlY*v5;Wo6lrO--<1k7Ne30PS{ zgEn1GQ-=-cVi>lf1)C9d$^j4FsZEGZkktQUHk`}9#c|u)@fleGmkuLUyWbx2V-|~} z{*ExopW?79X2#RYI_VFmgeLD;A{2$>xfE4?dQN^l&ip5v!$d}Sd7U70K-@&#jNcqn zjS(4}vz#w5W<*)puS50~Ga~1nx)37(oFQ#oHxR485d~hE=QxrSoMuB5O~E&3uPnYS z&tWp(p-bIJm!GOR_gMyAR;#RMkiKpzq2?w^nogWbuak6xs=EEWk+px^YpOyI>73RW zcy&+=lfi)Qkds{FMC`+L|FREYih-klk|U~g?H%);M9-wPf*j=_YD=k#2Wn4h8jN?0 zVdaV%O9OK=WJxi7I}=+hbAB4Wbz^>@)dV7;v+y>pHJ3P`zDTmW(;_*;Tr=BZ|I-mjQd`9 z`bQ}t9w-WVU-KnGRzU|r{`qWw=0zWqkRc5ymj1e=6mVmzc!x`%hBP34rl(nmmZ+1!;y?;HUBP~ZF zxUh~fdtM%XH=YAKboXnYsI%tO0!!vH`nAMOM4NDtMDAFBiQB_Jt8H_lfjVHVKC<$T zygu`ISUFs}l{#GF4nPg1hqh$Yi)RI(c4EYpZUSm{)Q#z&tL3y#%5aH;hc_FaerQ@Q zo`wlhYQ&Pg2i~FMNG9>js3GU-a}W5IE-tO->j6((UTb)kU|np63*hcA27ebcu8Lhe zU~507D$#(h#hJ@bIbXDE4M39aaX9`6x!XD9qTEtA11a@EKYv1_@WU6^RZ69oK;Oxk z!qu7iZ@9j6uyp%?1%uuUO=yl<3!@=fW4sR~8rTK3?rjr8kdvw3iSp58%mR^0UJ0FwH|;!W`h{dnNTq>Q!%Rjl#44 z<>kn3f^I$C9O310a%evH={{@q=-EgC;}yDTc#dBmb%+^VY>h@&==$=BDZ{WD2YJ)M zsTJ)lij#`EJQr)2q$TzX>fH6z+5w_Xq`zY)dQ^v}n5J;D>1Kw+bM%A*?}g{^)fLn9T?N za>WDNkK*QIVj$z;x=*%weK=m#&wt~WeYC=kwYiU`}%a>Q+}rdsfR9@i@%`yZ==`DA@y=>kr4W9w%wC9C%@F@#{3`jtoxTn;rCw3*$*z>fmZ?@g+ zF2ZZjQM>N3FGRuP+=e_c`L(pC%!86bEHlZ-;VPDxkK}8G0uril#UR|1|C;pPlor0h z=(A;N&QR}jS_STqhwB9rEJ4(g>9_ZAef*D~JQT7Ex-$yoxyP!+qYpR5g<@3s}ULX&ZI{>;{dBuiP zd511^3AzJ>Pu{xDi_7cmNh5(j>d_LfVkLeIsh(R{UH)!$zz2H)71jxmcvIeZ9Dvp3 z9T`q`o=E#ZB~4ub{bo~vZ=VW}nkB*pJw+{_X?-4Z&U^1;7L|9dM&W@+XT0jBHnLT`rg$0AVqwDgUf}{4py&>fsmL{VZt2 zR$LEDZ}mx%n@+Oi-wWAeHrD@QrmA^m#fQ4JVqcIUGV9^RRVd@x)ZhOBlxgDCtBQh0 zdrOx2s+`xd`rs0c^^Y5AqROd-Hvw2({WUKD(n4|jdfKEO?a9GeTL>8+bI6Gy`-hW6 zq_f?NVK_qXHC4oU2UvSr5JNm@HXE<`D>G%`HdRq(ObG0TaB z1BKNqa5lrHYUEk1W#L@Xm?F5~v}s0&FS?evMfqvOB@`4vPyY6|b*{0fi$|;&_vY4d zi{3}vF^j^0e7<0YAj?><6|B8x)i%XoU};r6CjI=(7_KrYXe}9E=>Oa?p8%qTynA%+ z?uk~=vvTdot>Xjd)b$c|$HGroNvUbEvr*v5$&DPFd>QLmgo4K*hlsp{TgS}d)_dL} zr1yMAa9&^`#$)i)*2m5Odo|aV(_s$w5s-E)R>&ct*tjM5FY1{68uzIuEgl>2L~MdN z_~p`$OLL%wt>;5tb%fr1>8j*Y2hp@Vga}{opHtIB7Q9p>3_aL**7_U2qJj6OvV?KO zxq9_e%WasQ8;ezZ`o*FyuzM7DT_luhAWhSR1HEtQvnGpj&PX{C+cC`fvTg0&cRlVd zcH5M~9V5~w8$xBARsD;jK7Zj5u~2A$1n)qFEU2e4AcJ<$F4Z`XT$sqg=2nJEGTY^ zj`ehmgo&`LzMzW*nUX+o`-%N=jKFv*tU_LS&%qxBin~g*WLCRWtDt zQz;I`-d*@p4JG>21cx*B@b0Zw%f9b8=APn0kai9^5SfV`$=&D?0a5nz3sWzXcw@rJ z!o4kqf~&2c2YxFJR)n&idHCPT4dq8acOSG}JG>vjo;Hb;DuY|W;8ucEzPvBdOzad6 z^%(;vK}0{)nFDcC)j~XtoBN7IXzAZ1Nm);f!VH<@o$<;GdG$}TmvElb%rtTN@XF{M zYy&seGhn9XEwdMCtu!IFImv$$66ug_6lQ8kXZg7F9>-}|ItI7*djBL#H0H=$0H?^p zx=f)Tn3b8N8oJ=^CrbX~O*?F-a_cVL`~i=9*E+&=^GE2lcUns)RVJLuFB~YG`uH&l zmma}#+?w~?3;$X?c5CxoL7kL?X8sle$3++(Viuj$$eDb4qHE(N?xLdxl$ohYkoTIg ziJIY4Upm06PSc2X3ZJD~^qC34;AgI;CEuQ7k_<4douwHp6?*WQ5DhvnoR3AO;f65U znastXC6`zni)osWXdIH!SSSn~5!7imeKnAuBzLX`fzvygutNlNqa!(yA|95-xNx8> z`MrGEFE(!6B{K>418{XZn@|+fxN6q@t9lb8j!{g3nAkHgjaN*JrI9ks!Uh#8p;Sxz z=AiwVp6H8Z-Yt1%$}>~HXU-`phaBZ#y;VV<|o6{>R-MB`c(Gj7@MZ=)sw z!*tFC(_bm91-G+jL(GwEv1K!Tk$Mx%Q83`4)@%gE1hAgVKg%tG;OVjS_q77^=kW{_?x(`m1``Jza$D*KFDJf_s2wg_AU-u_b)(0uW3weMFThY@m|1BYU+ z;@2!GE6WQC6g!Ika#?k>#0xChmxTZ;Yfn!AjTX z00KRN!cKom_$H*T_yGAh6*W2(ZHld;aa}uKQEb#Lh|aoLoYi& zI(!Sh)_1ZKdN)E;zVyUzTXFE>y`03yQA87~m*U+aAfHjMts$_$eXwE%jO6poXEB~q z^J-Q?{9$G&QU@BbzghGJ6Op5#nsN+ay%U-NdF7ptUpc^=Q$4* z_Bh@ByZ54|u<^tb-Fb!il1E_U@9f#^f?GVC!5phQ-yc8r^qoHX`|a_`Y7Wx@-$-=~ zIL*eUZk0T;HD+9r%oJGRNu}w<*nCw$$oA1YtDJaEfh{>W5bH9TofA2~8Fgy84-;6Qdw#jZv#$`DBcsKRSwHlc48|7)sx zmcP!<1J+Y57g@=;xt}B~{ceQMK2%6-;FEdQ@@x5e?uk0Fus0mv>16gdKBbDT!(!Zl z{$O>~hSbSZF~V}e=NYDzzZTDpv)O6*zw2i(^QVgRGqQy>p?~dTASRL+!6=>CX1<~n z;u?fUWKr`K@tE=-mkNMCk{OPE<1tSJ);ULZu4OC&J^zpW&x z2-6I(Unu|f@VY1Vb)( zr6@hjFW5nZs1OUqNK-n-Q%(aXP=OZghJ&_{sKmmAT*4RR!FvhOQ1Dtc=p{A|LY%xw zQKW=Wpn(^70U3CKi@vCg_5@F`1P}tnO87{Z5S~e7#2{rvMs(xo5h)N!8zm%Z=PYSK zG^r7hCL5jRKyCmh9HiSNWF5?mD^1I)%m7AW2$mwpeAvQd0UUx#D5oPGFH6O@Y+gaR@MOF1o?3ur+F76V;qsVv@1IkimB+(P*Y16^1M zZ@SgR#F`RNU0cLzLrIeiUV{(OWf1M?d>!66Xo3&Agw|-yQh`lnK5K(TYlIEbgOwW- zeWSHaTarQzw^joea-oxkD@l#iuhkbe_?lj(D-Ze_Nu5Fv$iPkrERnsx?IPh+NPqWY`m=JqqeNeibte&MtwNf6f{8{09S-2C^P?1!*fN# zE6C~;*rco2hcvtn7LdYp0?Z>!0oCQK!v)ARBm&0LM*?-7(>|bp^kUuJP+6KGWE_Ks z@*0tRi52kLDeUF18N}9fTM|-AI#7zYdh0i2MYuNUNCnAA<*nZCt=`txK-3ox@}Rn6 z1L2k^;r1Zn67HqQKoE#g5U79zKmr)V!7Jb-2hyZFRpdopZSuhictXN7TpY@}i<*H! z72tp|6)O4Jhb^h;x#Zrcd{!;UMIAT+^KEAXC5JEZ)r7DR3I2kcWhz^otjZRzyRhub zCa=rJY+wwBQg$Nm5ZY!9Aax{Q#O#cv)q)JlY7WS_ATcS zgaaE9=hSVtZYu>3i3K+s2J1-KZZL{cf)rQ*9K#XEY^32Ma;{=A1EO|JsZ=6z%pq?`Ry2I1Vm(a6 zxxgNtR?ZTy@n&(IDK8gyG4r~`%+eLEiEt1IfFj`lBvj?C-0&}0>I6L&1Gx&$WP%f%nhS`hRab8= z*v>`ff*^L>WBsShF~jbhp&m{gdD3C_)GHV>Vj8v&^+wkGxj@W~5E7r<&+)YfVX-?W zHfzAMJU6!geeqlItP?<;2NgqdZFFNah!}TuW|z!}G^GYr=;=(Sc5xlj4jSb^-Y_?F z=M8a-giufSbPsn=E9-D)cTwv^PG4q8G@FREo(2C1fiFlBBiJMlJDgtF0TvWPtXLmr z+nwfuq~|IbGkEg_MniH5_T?%|^EFIdv?*qPSt3-~nB{DM^wRddp)f(y^@WnfnGbKc zpPEJ!XAkc>E4GGn24g$6hc6v`b_~m4?`HM$2Tjn0G+8`-Ol=snic`qR2*$0>Z(UGb zUo$j}V~_)BUiLK&Z*WwrKoyilCWJz6-o-@n zu=5Z?z-0z;5a)Pacpw%-hNs2Dkydf;aKrydu_TTVJ|%G#_aTlMx*Z_ajlo4Rn4A(D zc4J5uW&Psn=pk93_ATgwGG*##_*Es^ocNg8f^WF2uSJJ{xUJ(EeBzUXNG&1Qr_63$ zC=mKX=|z4R7lV}V!nj3fPj;;H9HHGY))wsyY*Ju1&^27Twkjh8n3Oq>dWm<-bO3wiOnau7+$Brg1WPz8v#PmL3DS;wSeSe_ueII=ut6k+ z3S7iWw*2@D)nOAT;)I0Rh{X5xG}mm57fUK6%_OrlU_m65g7ayl@UidDptY}~sdrMr z_kB{K4hxr6$CnYpphiPmNfso47MTCeWXOvOtXKQ2Yj~~SI?&ISd?XrPWCC$whVTjl zg1{imC>mdMNL?Rvh=?h`Gzg8`#iao#!710uK%7FGx^1i%Q-((F zFoMdLvC&+@5bVJPgEzW=Nqo&aMqK8+^Ju;6s7LHO;13bJb4lTQcaQ$)kB+jATmdB% zfdvpe3g{}Urf;q)hg&baq4NbF0}x^88(W=-eU#F)&_`yp%yDq_TSEdC%mOkA=Q8hg z$qw{c*SxBCPsB;j61z`oxg5;7yk0N5@4)&>&Kwr#zQ9C7T=zWl|9sFte>cfTYEQO@ zn5-}yWpK6cWIb22i`vvF2s!`Z2eWfK2X?_^=`lOEOI&b573@d))6Pk%h|Ov!0PTWY zegOrS?MjyfmoyDP%n>+npp`jj5TePFkRii^4+#$RBXH21iWe5z9i$x|^wQj|Xxr@{zDs?ysqa~AP&z`oBN#isllTV(pW|1O9B@r`WvyA$* zB@9_8qEUO!qWQ?l6i807#>^#*S(Bn+eQG6D=O!m)!i?I=#f(a(SZJfd%0&uL7bl5G zA=AZES2QqZ@nTh*$&QmcUxn?`#jMVw#Fy3fbqGC~|g3KK(2F-0l9kitb5ReMVL4H zo23|`sL-MlQVQ|)+Wxlvr4S`1*(Ii=z~~~BVtR_^6F2y%=88cm>BzziMH+}CfeZq8 z4l4+@f{Ymvc5w)W8D6+y8&{~JiYclf0*s5>z}YLktJnW zSpEcvOk_a?Tc2oJs*ZQ@nhF_G>I$u9rmP)Rs$7;y1PjupGW4%^cfod-Xnt{_71Pvu zqzk5gDW?DF!luz8l2SHJ%IYZ?`6U`O<1nt&%(|Fj+GcW5_f#`O>B2Hp@y=WC&{Un( z@4o>LT=2gocu(#Ags~5dUkGu55aKi~?@DB#o&twN-kKS^`J8LKkY>W=Qc%;9q>q#? zl*k0G|DqGUG(X8=W<(tInQ<`*g~9OWEy3ZSx^^Ua=HKh zT68f*8CjG8i6msg6fi-{d2XjAE>*`UyT}FQ#5B6ZTuCWR3QRHF1SdIVq6v>0jRO;C zhf4pwB}rtlTX{HDsKzCVK0530c3NZz*I0aBxu%cxGv!x`W3z`l7zes3bFkt-${olhd&KB15O`9HW|JpWVaB0$k<-hBHA{eC69eS}K`abW zG!%@E2$>Ne=X3!OG|lK(YN94WNP`+?`Ksi2ScfUh01|J_AU<;;jZZjE32Xm)t6yKo zoJWMTP?N&zWlbYcBpQ^orR7^{8k$~Oi0vkH6_ve&lN7m7D^|({h9-CuFG(WAFCSINw8W&C zhuVbDfSZ-1B%&_JaD{Z`qz5IGrjX$30wainQCnEb4p>NUX!g>Wrobgh(a^)uN(D}F za>j`MMU`3<%Z55U=~;4Wk2v*1*8ZU95or?!V>ZK_h?LTCYlBaR9JeaunX9d38vDMbH~L!(mXENRKW z1*#GfG_J(#lo^eq-7@2nVxeO8CsSd@G6wWpBZpNBLOrKeqtUB4_%yilc?6c<5;vLb z^mJOdXJ|M@W#>F4c3m*%e?bF6Lt(i-(jY_`O+`USbOjPraEeq-g`Q~)r3rWyVuC5B z1X9RO$(3>vnd>^2itbWUSV+Q_7{%m7(>B5o*u^%s z1zandC`lt(vc=Y3wD4QxP{mxkRSYTeW5&-UZW?qvu};CG$1=%@6Wv}s z(!!HbJ=HIE*#$E-a@B#TWtz?BI~-Nrb*+@NwA7t#QO7V@58VMtbsPQkk5&?Aj56k<|2B;n1EJQq$Vp>%;=6R$y! zVyb9C-V~hFmYfvywNhoXR>YH%9)SfckCp2}UxqZ4aBlyja0>To5}|W4hnArio%sYk zy3(N^eZeukyVUk!7xo=UNOVx}Yfn$O073DjOhI+aRcSQJZ5Ct2Q90s1Zcw}pcg(D% z3&7+_cDL(tW-7%As#90uGJy(4D_fF+5dLBsrr}%=<5cz{5!j%TkRflhLMU(me#j4l zB5f{=W|wjy6V@sD$^%+@#ypfnz?dfWz-m4+!JLK`B>>VHs-efEsWLY)FTM zE*hr61@59uXreF3CTqGcJD8!vkg!}W{;3; zXWFXwE<=zqp%~N(ft~|A#DmTf&8DylPGE|Ih~@wC*spamhb+*{aWo84J}lazp${J| z@l56Re&ONjzzL9H$F3+^+66(F;nYe+XRKljYogP}3JWJ_gE|PTN>5GP>hq9BP6&Yo zsSdCn&C~L*yC??>?q>J^>-F?X?ZRR*fKT|W;M_Aqq&|dx_0G2FlR2{%`AX%ZAd{6rXU#%P5#x&Cq1y>ylz1)46qLJD+ITxo4!gd1PuQKmF*(2ktfnAoW`l;K%+3CX7-c@C$C{M*1qp>KBvNfi0m$bvj+R90C z(kH|a7Ln{bybKIO19lE1F#JSksFFaea@zP}9p9pJyb{dHLpwr&Y?!K!V3FjgqBC&7 z3Ht64cR^09;&Hg@)KD-j5(hl&C>Q>NgM39V(J6Ms1gzEtu-YmxY%*v5gBkb=)oyRm zIxk~GNf^E>8k$DatdS7* zGOI)(oTdS4oIs6gb2J=;4T@k2vd>hcsXbTjc(E?h}5m7xC+*yK#tDo)~T238bX0xe5!3PsV)tPE`y;3!Wm%QDLm z8Ai_%1r^qQR3^Y==Nxoh@+3=+&rGF)ENX91gi%t*P>7Dh7K+nR{;E^5L<>AmFo?#T z;se(jM?9E;+2X(~X*5>x!bWklR+CNw{BL(!l@mY(IU&l)oWhTu6K|$V59;weOGSpVR0s-RR(9&h-@4-9YyX(H|01 zTY*9v`pX|@?l1f^^yuR%g3ARd5(BdeOS^!+T<|braH?7rU5>PB{9?eGW-3-HZO&*b z+9nZlB5|BxL+55I3bFr@v_Mul_A_YJRza57BmfNZ$~n4B3DS@uOJgk3k`sOb5FE!z zj?^f)tlVaxDcW=JU`jc(AQZkaFmiUw4(}20FmAjq%j6W@%nUlp)I5@g4xfTF9y3h+ zEGqD%g03oP{Uj)cq9{fRPtZiB7HC3cg6$xI^m;AOlq|2VC5Fxeg2qJeLTIdH?MkPF zYFd#qQLh&vK?^VqZ#xAxM+jK#AQIpag@p0ZqK+DHKpLJDaXSSPzyQHIwsNuJV?#D` zS!-lDK^nSk2FxOF3d|9vKnS)7TS22-!le+p!2Kl8kEVmwzAF?+l3apCyRt7SUU1}+ z^WFLpE82)&pEdt9%B7CBjFh?*-6Cr!Hi0#}ODSmbnQ|s5I7nsdv$x`B>x7>Q)v=`X$s7ePNm^Q5)!C^8j|26NhO^gL9vR!Evz@Au!wRk_kVc; zb2WE>moAGKVOWTR8hq-iKnrxOX2 zR3>8u0l5E-WkP@nIF6-A0+tmFG6ip-g&KTli?9t6$gxzk152j>3yMW7oU9mTHX?;# zxW1Eq$M0IBQ(8rBq}r$nAmMS*f+|2W|DeQ|sN+$KDO@H2&JLE@TsWl1S~ zrGjgxghes6M5n+lXllQvAqkKbU~8f)GU1sXs0&sZT2pKa^nerUAQG%gZ}8+7^brQT zcu+Je4qh|FqWLolgA@GMjV%|B<@lSYuMk3k3Y0;C>k6irp%BV0zXXX(X0{8(O54y* zbxc@-A9G2l1MZZ>w=igo{ljE6Sox0DNp=D+@Ps~kC8TopYUi##4HFC05Hpw~LVviQ z%Z&et)o(AUilv$)o1!EXrlg*EnD(H~q80@*oh6ZFVlvajl9{Rtt~u3|L~>`~$$0IZ zipVQmF+j}uDod=dS}h44rxA@Yv}9+Sxw&J#8JwAVRwO_dkRdcgkb3;+23-b{&1_#D4iJnFe+QkXrG_Cm;=B}j# zr$8lxR)T2_tj&ZJd}!t7k~Fdzsgqh(m%6ECI|>17IkIyq$&Oga5G1F<4nnG@r;z_h zYq+R=LOWOra?ovO#gr7bWfL|8N>v#Wm+kkpbjRBIP^wm9B&G+EcWDk@QPEYmLwOMgR75> z_UynoN~nUOt}`+DGIDO`dVzGdhcDJ-`zy z_JSBe4_c<-fC<4tD|xJ$$sE5CtmiM=l(D&{l@w6WyPV*YyEiS_Fu9l}ET=!-wdT5@4CU116iGjl}G7MTR)nVtg4k~4;vughaYY-&& zqD158UH;oBxF+}tdT8!ioCcDsd+`^3k;5z3!$Ew|rBT7HPR(HlpiA@Z!lLRb_QCJX z?pBD#h3=!8;1HMVOvsLQ=qg+N(xUI}@B(^)2b#{f>i zGEoA_B3UZwndbZ|$F~bQMu9#p(&U6xnWF^PggLgGnL>@b0xeBUvrR~+U_Vk-g+oy| zHOhX^2QkzZH;Ynq5xBEM!vS5XQH#*c-EUk=7)B4#HElgO`7(-O`!Jj*&?t-EJ&uNq zvlV%`w2OX&%TVkNQhZZLL9Bvm zuW-creCNkKRt5dsjovj}>pzHn#1j2ESZX7|+RXn_FU0~L>!>OkDu{Me ze$Rqxs5H?It1|4vIx9Kn?q~;Zt`>fN;TL>8*-c|CDu*amn=a*K`@Ha0EKjAE`0h5; zuJA0_3)4A5cNEDK_HJ0&ObEx#Lpuru5D?{pI$im=S2XKW7zOt~ST;xq}JiZD{cX)|4aW00oC{o{B6#b~+-1hkb>3*%2VH&n8uoZG3L$Fl| zA#LC;#egPi>xwz7LWV;U2e4_h3qwRdBjs>#&jI3=z<~q>>S6{d&a8qA8{V>&i_{}9 zP8j_Xmdl~8WxtffatJb{$dM#VnmmazB|%{f1Tc`$@?}hzE@{fFIWs5Doi}^h{HfDt zP@p`C3N1P`Dbk`6U^c6=+G;rtjJ=EF1`q3j55whV~sZ6h+~c~veJnX$gq+lE5d}5h=!8@spBk!*l{B* zxrE{#AV}g!)*R^OYz}B2ygm3m966LMDp0=oZZu(Ht|wBn*vOSQCkOxTi_BMB3kh^fA`O6p(nR5=6^@VPQ!T5kf^B zr`|@=F3e1W-bW`v^hg&@%&Mh;f<3aGVz3tC1Q@>xLrX&k)lqC|uukMe9h}&vo-oo- zFkNIx%fPv~)nRbqk%E!J3k|76 z#{W)SOvMZWQcNxycPC7>X$~~;TXH4wh%o=P)QTXfT{wmj#hECf1u5K}$SWk#L?c?s zG?&JumyAp?Ln6g&TH;V3{wMp-k}!ZG`6Q zcc4=^QJ36ACcIA%F~th#lYux?n{L z3z29A)Q&?cicIc;A(7hm>@||MJYot{s0-gl;w)(>VGt%*Z$;pJ9%6K~Hh$n6+kyg|%*dZ2h1ZLi# zb2y`6<~rQ!q3NDEm;W45JsW{U68iVd)U~oh(U^fXje|e_RK^j#K{STaAlc++ECyV}g+w6IQ23k7__8FtIU*6AenSQz8id5K zX#taU?OUfP6Nh5tQXuW&i*6O;9A;3>ZmR4pZFg&$@VVd-$Zd%1_HxUkYGyEYz=B{= z;+^0$VK~Ml2-oPw9B<|AwSbsT-0BkzRMr+jQtQtcDR&oVaY6|XDG?Ysr@GEc1Ah2A zU98$w2M=ksf5MnXJ0=uT}>;0ma2!RFZDvmK=C?QV2xQuCN!Bx1)VM|wgC}zyJiMgoO zQnlnPbm0pYqym>7I6;jW7%*RWBLyT#m7rEesaQ z3pc!6XBq!F-dgO&YdZn6`e9An+#Nd`4Fi=gZ%e}g7?#00eC1*pCLJCz0W@IO6#CGN zF1W!Dj*>Y2$q|R)FrOv!3vl7U8O==<#Osi!iK$G>-Vz2!wnrv21(@R}Y1_w9x={z# zVWg$;cmnVDn!WT`ZqWz@74#HGnKLntvEiv=w%7%yRVgG-UJl818K*+X$~If_(tM-r znjB(F++LE)v`ts%Yk7zn(!lc3aY!n-Isz?-HJhEfto2+Qs?cH;CPlFI^^*+T;Rvt0 z-S2*jVvrD%Y6oY?JUudIfFVnx77TC@QG7UC1@zQcBq*ArR-VfVhS(<}Je{d|q7N89|#%GLy7D4$)l~ zjMO^Xn_#`V@@9u5aQBFIl4;x%j(p`$gI=VdbxBV53q801lli{aMyA0R{FWC&UlusO zgP04D;a741dVWaej%d8gfBp$}nD5(7zd&WYEs(H7{9`8>M3Mx_vl5)p1c~Ds^70Fe za2Nrn7g&O32L)tqa&!@~bT-yLO`u~ZaV!DWOk4tDIp%%@Q45x0Q{_hxkuoVz2VD6x zCz`Tjb43L#=o-}01!v_rb5l1SHVfxN1)QmX&v zebL}e*i&aQ)MUo-L-oQobw)yvzzn)jb|V3Q^hbtes8@Yr2NicA$g~V`p#;j87*~Qz zNhlB?103YlU7Imm5r|!j)M}2=cN3B_O@Iu67($%&YnkAHC?htn)_SZadWNVU$D#yi zg;Wz07Y#Uq15pbTLp6ZdLR%vlyzw=3h(C=ednkzdm(Bh;c>s<1X}P?`r|Vk)G2r}R_a0uRFEmG=Rd~)KqQrPSh8m@ z1s$6ZD)+(|?Gg%|)dfAJZ=~P|Re%Fbr8~9YCEqg#buDVL~XW4DSS9BfuVGLu_-NsY+BG=9mhGo zftRJ_Nsk~)aB@VM@NIBGdmZzCio_U&Kn0HQDSK8vIyD0rr%h*BgEjvI30by^O+YE} z5lGmvA;*Dk(!q>1c#P)sD(crcj8&KUh&jK+9ugr=9TFjO_mrDZlvHV)$H{5M&^(fe zU2C#{Gf)WqL{tCdE%~Qm^te2v&^&xuT*&YXCq#S%K$jem34KHB~b}$+tMu{L1#eKE;1yV@5c-k0z$eJc5%g&zUV_wxu3{M zqcz$r!T<=E)QVu_c-x0D&jtyEnG#}IG`Sf%Wd)D)frwE;mT~`-YTOxInRk06MIdareVC4x7cv0a@dTzt`$q~$D20|saUqe!z0$x#PjFe%)1q8H*8 zNxj|Vy6EcKRq?;y3j@UpH z109bgu(o1>F;jUDfryo%h|TCjWLh$j!B}9L3za!Uuh;~I02-5o7&03Y5H|%lpa(T3 zv>-8x9t93Qo;8kFGi#GrPMleC6Vo0pP$A<1t6k!-#3`|b8?p8mpdhg(+LI?c zx(k`$1Qi>r_0uNU*=xcuTS1O|W*wvUi3H&ug@@d#hj zEHH$FW`rI6s$@dhWnTEEAcCmTXs|$)ER&PCUqr9no0Jkk8*q0_gYmG23%@lgJcNLc zepqS^LbBFT3=dOV71daVk!iS#Lb|XQ_t;@l101OnGwLdLgJ>Im2(akb;*Hc<$H=zf;cFs zA6=qCo@=(~CLVa{LI;r$I_py{!;PQAal-$?UmXV=?(scJ>`YrEq@%g1?3cQ05vRxy zsqyQ@$0-b#g^w^LVFdLE%_s~{cXxD zXcAm_X2Alycx)YvVF#h5uVE{MG&n81!cs8l%JmA$5@A+|6IJG$GOU{_T$r%22YOxn z#l=jHa@bH(6B=8YB`uqP1?)I}xC{WSY28B^!8aJ5MM-rmH#Wx!((riPyrq(XsD{LJ z<>NP`&;^W47~Az2hzv~MbyXYa*Dmt7x!Ee`OI#XQ*Hm8rY@v| zu$+|NfhFOF& zYkkfL5-F$@EGd&L52`p`LP4dlNnGYDsESn2($~fT3l22P=hP+3K+GjFqD3@0@iiEY zjUtEb$>Jgnqw@$tP1BuycV_>hqkth8o<_}W**~Px1c);jt=2Q9J=CQF2?l5x@T{a+ ziFU?XX{23?S5g;SosS%m`C$mjZ~NjX~Mqz zh!(@O2t62ufCY_-AR0|x#7IL3@!i%}I4~<u!wFocVL`n+fgufw0zb69!;!)W#MXJG ztBv%@HsiU*K(kPTvMEGXh{r1#`WbUUr?;6r3#&2%k+91sG-Wq6f(beeCv3{hi>@$w zE7D+fw;WV+t*SPp(0TtMLL>x9-GQj}$!6yYm}yqT^QOL2zzEa;ME2cZ!VnBa64M1P z<_EV@pdm8&i@|0DQ%tzwT>x1g{zZO67~rCH7!Is1NX^;^b5UDmaUqDVV-N<-ec93cH2bdgEG zM8k0agJdO4?_sxhF(3t^Rcywmec>f|tgQXrGH8V5dX}->(^(}A=VMOn`63KpzzNep zNR2z}vquevAOsga;gofq5%Gg|zGEjhR&o@&4n?~-@YTS?tTsj4$RQ0%w+S-s5OHm# z8Js{2xvo=23M2m>kY6$bgbU-P;sgikWJIF`03AXl>7Y7{yl;Kqk6@CDy(;M8+dfri zmu6L5!z}>6RpMI*{t1-5(>4njS9+~4ZNV9UP`1TR@>kR+w1MW$eki+frcOXrlB;jP zeHb3nHj4G@mRC`55zc=h7=X|PBXg+LT zlbWs4Ai?;u3(N3Suf={9jguii@+EKhzf%md5eZBmHQ2E|{R&tl6 zOCa{H>QMhvtAvo|xSCHf`)*CDBFcR4$))TTj6?B6el5U=1;0}Z#SjYFst1v+@;-z)T(!NetTjC^ z@`n%pXZQ;TD9+8vYH|UACS!jdoEM#zh_!zxND9weBQ@_owAVc7Dsg##&i-5i5Tpv( z5thr=ErbabE=;Ja7&2ysnq#s!s?b)h zmRkQNB8w(X$s~(i)gqjwQQ(v*nXL9)+jSRNJB1`_$;7OfF1mGn>SAW+QCpFZv?zh; z(V$?AHj4oQlne4@%$YTB=G@uy=g+yA@#P5`VJ@_N&gz(ie+? zdF1r+N@UU!y$l?AS0*QYRIK<Kip`euv;ZW)g>1sFj$;_ng29Wh zf<%ZZ5{ZdC&*Y0n2~lz(1(GS85HB~-2&>}}uS6`wi8_KQ2F1)Iqij72bJTH19((`v zQ80(FcqFzCgMuiNCXyKPv4ljNXgtk~WQLTX04avakdVBR!=E%dQi(XW^rGG@mp}i6?a_0 zzIvn!WPFQKm}OLJ;t}#T1;maSHOp=qM`i$oS%z4$qbk|blxDk$yoE|cEvo+u_@`Nl zac%}eE^DcY>acA%8bX@by^E7<<9K$ zKpj=7Xv8H2~pxe27~&O5L2Vkf?JarlnR+&V)dFx9fAMjM2TVq&%`KD zbGbU}sQME;SzlSrWf>a>Brlb%Z=% ziN+^faG1|bOhbWb86#lEAQw%66uW4d9+c3do=t%hVCX{ga>SBofB_6s&<_Yf^A%)t zVN<Q7D|anXfQo2Be7ABbIog|4mLb^8*RbNHH~!gt30@yP`tOSO+R3LOCQ%3IE_$ zivi|Qk9*XkFu-6E$b%b!}Dw7pu92_pXloXDXWLcWQ3fyeB5UFI(4vdLOMZ(ys zM=+0J;u}h}ltsO#gvy(Iq-QqGk!4~6jE~+kJ#HZ zZx@_IKrEDQJYylQ*f4280y++@i!ffMoYpKO6jZPSDku~dJ0Jrqp#Z~#c*GK)If95k z`bsoNG#o49je|1~g{q42B85#9CA(P0)9Qniw=}Us%$Wa15{}9c$`OJJbx@8G*K(I- z#DPT&8;~8Gpr5r-Q(MvLiWwn6g|zJlD)O}EJ>B|NxNb%mzi2`R#{`y#?8-`Z6&-js z`4cEk$#Hw)>soD5j0f`RB3@z!lC+SbVmWP-!IOClKRfUeWdW)~0J1T1dR5*Q(F#86F;&RUcSCg#*W z{mFz9*vpolbwQ5s45asX6HgIIH4!?li+qHI$FlY;X>%lKsjx5!@dCCbUX|mFxD+Zj z!dJ{=ey?cwg5LeTGH~N0>_igdS`d z>l|H}8f{{P4vDp+%7OuWFP4bPoY%BtxFFVF$;8KMjYW}UVvCc5F&L;kJDYX^DrWSm z*B~PwY1qNWT%jCLnUU)fMk6klF=HX7Y7&P!>uIsTqKIIXRvtoCz0|&T&wXw;hF>~y zkjiV78o3$N@P)n(QI=l)3>uFTq#}$n-DD{gCnx;EvQO$!WjpvwJKy%OrRxH0kRg$x zw0d@Rl2coO(mM-7eN7Lflvga3>68E0oGcUZFG7sBYVMUwB+&rSQ?lEHOf?!#%#el) zl-;&jzi-qPDm58dE zg4?zcg5X3jM(vpy<&}cNhyeQt86=9Z>~*B>888A27M(C=RuYY4=u0{*DbN9%pQh~P z%*Fh1Nga?ei%GA=7R;cAg0g(r7bSuj;jiyaz%cTZn9-k@Z8B5s5C``6i$HN?vf@mQ z|KDhdI$)x_tE2u%rypC3mV=SL__4c4r~DJP0fD0-OAFIOIn~QR4dgv3vJ*%dB<*Um zCo&vn;2}9{oXy$2wR?mqkcR)pqBD@BK#7UTLx}HU2CeFhVaq0KAu=ZeK+wppcDlnlX*dkrKtUYD0V@PT2pA|j zsBb$d-Y5vNAQ3Deh3(@JW?%!EDmNZ6k70dSu4??y8tAG0W`+G zdz8c&7FKDAC4vMrNge;j0};@p!vXQ4wDJx4FpO<94KupA=^-$oAw+dtN5K%4E-;9s z5Uf7)LU5ykXqXbjBc&Om2|2r(E(AZf@K2C4;JV5kzL5Qm6{Ra}^rz_C#H zL|EL8?ufsNdPV=uaF`I=xK>mu$jA))V*a} zTv4>8TNG7DAt~IUaCZq1AcZ@@9fG?<@FYkT?(V_e9YP515ZocSlb`_-5}I?m`*inx z`pdoF?qAq@t@-XT_nc!SH8Mq!r9j5Jh_Tg)=?Vm^ z_(;0+O=3tE+E!>PYG3weXxvr+uR>4$QxJ$bd}i#_m*EtE6FyUJu>QupTw)SC(hk}; zC8E+xh~38_7LO?yV-NhnuCQyQjlLLnY81d)I1HgQtu=t zVjy%HIhElMekG-EK`?UJS6q}F!&wk+my^`9D1XcrqQ5vw_F1g~HSd^!O(f@L0E0U* z#pCu>!AOeCDq-VA%1f%YYX&56J?Vhi!Lpx{aE#~KlV5BIgli1EFDNj+pj$Fx%*h9iWDX>_X%$*$kf>^e zi4>LIuOLQnL-2-vCM1(NP#}`KN4wO6Wh2RTLR5M58z(eSX=#bsmZw#|a&3I_&J0#u zCJU-TWtW25!w_EYRUHTmQ!Ta9QBWDH=IH$+L^wo9F~j1Kq77sQyq1miL1f5MYwa&h&?2tGOU=@u>(K%{cFOk>njRH9d> zkQm#e;KDtoG&sJtPI{{T!ukGOTQWhlI0j2jVd=b)lv!6SA+pjW8ix*#(s#6zvE}Cq zpQ*X&94yAJo$m>_(PELT_D!J%bI_EGsi^~>TtYV1&P`c>AWW3S7!{3&=2zrj^6%pS zJQ)cQa_>omPZ9Wo!ncQ1bcnz z74x;7$@&QMIlFu`y0I4oQ+T#B1?4N6l?BRWD0qf;c)@0HvZ77WJaZ}Ux@@;(Jc42) zE#RGOWTg9c=f#`~VE+CVGd?7C+pD-MYh>i%Q`aaNAgnU&IOWBv*#d8*rFC^=%D0K> zh$rj1sm9R6y#-sTZ<#QHn9;t?N6HKZ9LD-LP{#TX*(hcw7SpiGk{*HP!SBp$Ee{r0 ziKL%QGk2co0X$!iTeC=bgQUx=`D{vnX>j-GWblj-1LbA%NGY9@KXCPrAn_kqL#P3b}{zh`Pl|h zV=UAuE7X)7k=8KTO5Hc0Fh+YgK1*25KTRQ+#hac@lxMTM{sGxyMIy|AQuN|5@{V2(2x|4v#NCM^>mwY zW$d}_utI`9@9ym7w2$=a;hc#2zq)1aVoo+L>DL>_Ut+|tzozm~@Z^Ua+Y=ARIbBZC zn`Z>$w+PzkhxPI?wAAN|j#zo;F(`|F{}{Gvc!^&UwilR}9CQ%>utACL9bs?&GdJ%i z)x$iTj3Fn}nua&;!<^H6cMZ}D7;`N7w>nSfeCohsbp9OL2*B%N=)W&^Y{E$^AS`;a zSv$2G#OUL}wrZv^HFtW8_4Bg!^0UawZg=Um*|TLRQ1fVa;1PTar;3RxhjsItD~uQY z_#S`;l5m!#^VYCWh=>)Dh=fk~v^diw7TDi|1-k8W?$0swn6THJgKB0sA649T28%m3 zEWI-c;$wDXt?N6;nbA2&9xDHZViR@D#1h~Mbjr?@x>Im_d5k^}0bI_RQ8FAyBn&ZR zd`S);p(b6owIY0b|0_q7wz$N`Ic`f;fi>lY;ibY9gMaUKNeyz##uk_j+^<44>von6 zfW`6r(5X|3NT5UE{bqmZK$&A^V6<{%`0k&1SW8J{-u$UKNhODes+eo*D!J!V6XQ)I zK8+B28PsKRSjfxeDb3;tCVMCla_O1&Do#dPaa}7!!PiS(my5Y?d)(XX0~*Nt9Fu`f z!keU(zmViG2p9HN9JepQ8cK3yL~Vf?R>y|XH7YCPHGDF1H;RdCqXa+sQ;GYcr)$%c zlMxi%=H)U+H-a!dM4PKO(DKQJM?FLz%>8n4eOSXqKCFtDYT2;kN&o8clEvSetN=^k zU@44YK%GKf(77j3K-D+xtrT8t`1w6s`(ms`8nqdhtALujhNy%45(VCvh>p^CMxJ&I zs!Nx?j@I`xHUENKfKpfHFx>GarBQ1W%ep2ExV=h>?ke^YGitSdozi*6S~E>O7Ms}^9}9DY%qW%Q-o;|M+m2GF^QZ@TCtHQval9o9a5C=C zN>Ddh1VRr6{rM-6bMdO&?nO?P{j?j_M;+}?ygy!FQ;WmwQLW0SIJBQPxG=3MZdlQ# zz#^~Uf8qFWAoc*(dJH&)-k$-xmpSnCWvo+EQb98QaKpPfxID?w&ls|#LD%elC64+C zn}RY|>KP3D6`4}lmaBPnkvSdvKySkzaPC$ngBCEzjLB)SCIsyTol3czd9QI_0+D8t z<5I6dUlg7Luw0)jjQTZsb4!)J0B5EsSMz>?Ho>dnsAC{2|6c!-3KwFsnNfw56|RIq zL_q9mGiE$-0-%d>Bl#A?6{@N2??}>Q$0gI76s5kWrfK+rjz9>nSj{|s2YY^On(ob~ zAO+;4wPOL7jR{}HWR(y1_wEl*KwJ*r`eB35eD5TM1PZv!$Av{^q@vvVj0c;=@QH61 zt1V{nCt=N*jZ)?XS;jKNoEpiBMT%wXjFZos^Th{!|5#L3>$u!K60?#pZGRx>O5C#= zBF!XA5v2*MgJNwwHks=Ddn*hYyt8bXjI(reJQXns5l<~h6>{Pw&CypC1d#WeKlzzX zbynsSX@d=YXi*g@=Wa^~Sj|*W6xFRvKo~F(P|lS0GO_T9%*19AV(&t?IY{Ul$$~dpMiE6gM(Ce0 z>X1BM->T?Va8y~qGXqa@lB5#{nsD_)m^9PI-k&^Cdd(&tWTx>gXl@c-%Nl*>8*bmq z)BIdM&h=JBmR~yT_HrKVMXV&dAfPy61bd@}QMRknDT8VfaU&%KCe@Zx))6>&$71^u zIgpOYUsTZfvx+|1xN#H)(ZZnRhv zLB~{?d&6GcWR`_iX(-=R29lxVi>))#khA{Od0N+>m(G)8H)B!r2|3gn{_I&hz-_iX z zL>7aY72}hi5`UXbq%Uz9bS9*}-D{BB-~tY}n>&KXm{z+n-&-&ZTIhL4o=1FAO2pb?#SCG9Xl3+b zGM)j$vCX3n3fpDl1%{rJim;7pQJ?*9VoIC^6EO~SEy5YZ=r}r2)dfUL3MM*AqzEL} zxl?!~A>JjLzE)uZC-p;6DZZp6kVZ{sPo$+vuVLj0_Ky=DWIX4n@+?4$$xtJ~B4`^= z>IPRQPUDLRk<2S1k7qfSo}p`}~w zlHqQFAiHOasD5}QFd_PY9Dk+iq*PE?s+@4?1@)s$_WShJ%D-#Ed{d=~!-E6n@Pek2 zRL6Ms@i06P^vuWKJ^}@JrZS&bbe9X5Rz}!c4Tc5=Sf+Df(qZlycrMM?%{!#Wii7hy zmeex{ihr{jxU}<2Hrq1(PxdG*w%S;Fg_mV6WAV&}%h@QN7FbCfs$Bk}sby)%kPfvEJ`S@CsZ3@Q zY992kI{#PAK{}f^(Coj;icUYk=~oe?2tP z(`7{DQRFfopLEQ^$^v2*q}*-QMH@|7grTJXQqa>$mjYOHaG44eDWmPCzAM+|9v^w< z!+=jwXuz8M6m>L(un@@9937`UwusUgHq9(nk+a-XPR>gq`!eDq%zhj3UYTyMTLII} z0*{_qq(F#K6g>h>c4Ym8=>)0b+Y_C%@s;(cnT3NBpQM1Ja*OD&Tc4|0 z0M^#T&3t1~8q-~2uDYY_m^SeQe|Exv#N>|AI4zDJ6zh9Um#e#MB}q@|RYI7L0`ot$ z0p)VAp{~ImNnB4bHOudF`$-r_0$ji1UOA%^YO(QyT6D(GiyZj^t>9&&_KT(>=GRzb zy>F5-pT4Pj&2h=hj3;Mht?G(%tEU^YYkn@u_&ckyhJlPGF%KgK%3rny3Y=488Vb(j zLOEO*&Y14#NKv?0!hOB+IQ?l1u|J%r-ZVq!6!xn;@NgU^;8^SsNO#$30x9Oc+ybAX zx=pUvI}-7m!Z)S@6WZ^-oE?x<^9m`bSZ2>1g5Z_%4=Tpo2W)zWKB`cY?mGT)o7GDH z4|*f%(`qTvAnDB4Oe(zjtd>R{euJM^GcI3PkU2!fgxmm8iI$0Qd@n!fgz*wnxCO=N zp(wy@?9EtwlHkdU7HyZ9L&Kh^UIpd9BOY` z1aJP+FelnnoqVmf` zCJ1b8duj04p}fR2Kdo6>T-Mu3na3iR(F!E_lrYNO4rg#057Q5m*TD3jh`p^Y)Se%u z&_U+3D_K4Q=_i65tS#Tq%hHiTz;H`u$|*2A2{if`}NGxx_*Ud@0Bi5!7P3 zVt87AbMalPQ@8iC<=uh)zG#p2kPOvcUiJRWFHxK_{mfpHB;|{33sKHJz$by=kU)&q zl@(3GetLCDDs>BYo(Tbj)!N8+wSUGt*dwnE8HxIq-EL$pFJh%MiVek{C})EQ7FQ5t z&xweEDWuLOayc?0VF)!sAP!#sVg5)!LGiNqN{ka)=6#m#hY_U-lJ5+0_&f}6_)wpb zMiCKa)R;04&p6=G|DzE_b*4ixnSiv%pz+($^+FmYr0Tbl=qN%BV0m)O&(R_luTA$I zqVjkcLhSU-1RjAI^_#pR@l>#UZ4R=Fi|n`gnike`E^6yDdyJDDnQ{}mh9LAmPGKF| zbCoyBbTX(OERqp5QJkPc>St@uAe*rod7{jb^owwgJRJHKdFza+-#Mgm9my;#uOd0E;own`T=R1?Hfaf~{fjE=za*OO`l6Z;#WEqd(y^y4Raf{5)6ZF$blo)5G| z9HXR}%N9O)ll^{Mz3=pv7;U|CzI}*IsdEPULD0xlQRq*wEGxmWzKPvkINIe=3b1|> z1CuPu?Z8En@9v|z>KV=vTj82WhrX>@)x33Z7?-+|&XDP`f@w#u4E_~;GMZf~Ulxxr zeOR0Z$p`cKb)z$Jh6|a!NC}wBZ*1lo^Ki3R{G(iQpnPmA+mFIa<93E0uAyhK0O4F<&d@9%J ziYXenGWXu#U0|Oqozo}ioD74GYs9+yIgmjcg+5|w1Qtu}4|ch-5)keiADoq|%?txu zbipWY|I*s4BL$WvdlPMle-Rt<_P6~r@mES~9+N@SaBxbL8kq0B-;*`5>icrwINO=3 zG%$h_yD!U;n`w9a<;cOsgNdI5HROb}mKs$4@T6IlluDJaR-rVWB7;ipFfi{hauI}r z`#jVa0$Rn;v0atazhONQk9-F#Z6zLUo)4zVz-YvoS`(WT>ps)jg6iEM>~W1g^i-{} zZYvE~?mDc78`$!{8~h{&-Y-;4gVoH2{CJI|?baD~*jk`rwFr$f%$Us!GhY2VnB>%o z_-9-ur-mZPFg)}n%2r#MPDN6_GHQU<;g|57I$wX!4U^k43h8v(=^|(yZZ2z9w#(K*n3dNSdaLou9$*Vc3s9-OK5}^Z=$TEB^Kk zn|+J43q;BDup>P#%aBc3fLX`iB)T>e9KZFK)b_V zpW^mS;P@3YzHu;cBNlg9petPA{DEPL^bYgOL}ug|UWpybH#V8!8UiXBncssbY<3fX z(K4)UoCC~hL^&bkScw>%61|3x9SmM=D!^uSN1p@i467VKjC&UEY{}uW__ft8sr&EARFVCLazvsDIg3 zq+eik9#WyJW-??+oDBY=(ksxe9nuP!MF2z0wq)A$!l~nvPO`{C_raFCns&o-ASeDr znYU;zP8rBduPZFUDq_MX)31FS$`gE<8c2Q#3gwc~*%Ta`iUB^-rR{x-Z4P#W_UBc| zi^iJ9Qenk1mRsKM5zE~gSTnnPU0x~#zmz5N<8+2?_aJHnVE&+Bdcd3eFKcatA$nqc zOO0bU41H1BGHznPj=+%{Y`O%$LBB_hA*z1tn}ZEn1KM@Lymba*(oNOi(NXF=az8D9 z8>(uZVeA;<-;gVz-9wFkXiipz{)B)_~~SaZS9FvTN{iJNt3 z>Zm8+C{*dVm+IZ?*zTt2Z zLHOQC`_WI8;A$ryr#)6u3}23gV7s&1fIa)$iIN=q7vL3$UK6nLfm-9^z>QrnW$Cxn zhBq;mhXQuJ4m6+WyeT+)A~jh>rW?Z)Uyb=Q1Y5;7Pq`FwQT=@NcgE$NB#VubRvc4- z#pLu&PBDge_($Jt5_Gl&$yM+APlXsuoJs}y&acWe49E$PE_e7E$rBNi3R^xQq5I?7 z8V2c08mrGsTIbXwRbk}WJAKK5I7V#xcRUbJAtY0%C*=bo-`j% zXx?2HI*BBUJuzgr?Z)~NR^(&2vIJ+J`n%*OF(j*;$hPvASZFiDngrZwUYoV?3N<>e zABj=gc&^7_iD=xI8$TiKj2uld{`?je)u@&)x%c(lQ<90a8-RVIR|!@`$_=nAoeu61#SnB0>By<(T1vN+EC&{JqOn!6U^v zOZAZmI%*y{gCRb`zNKPOOEY#N4zG{}K0$G*;g29l;ZTm=kaT+^+1R|C*Q=TtQq@v) zvXYb-|BLm`YCJjqhxrw%(==?oUB^K5&M19Vf#6cdFq-Rtul>2yJ>xyf;?)s+0pIj9 zl+duhJ>h2WTwf);;k~#H<5^6hWuPJ#i}qJ`kbjUD_*7uE+uY7j8;P-{|4JifzMwHt zP1#z_R|Eesk@DwzJQ~-8ezIl*he>M0d&_PV~$hedy*5JuVS8 z>73}}--?@Peh&S_imEyCaelHM3eVC5eNIr($=7{lyI_`f^@GjNpj@W9Fy$tN+GNJZ z<`0n8(@Kt;k0Vq%RCJ;TtPM(3g)GexLd-POm_4HZM@}HBBlWmx1*$cIzAq2wv$po6(9jk;wv02gj zCZlPB0mROREsiU#s-KlfVXsEKJ90;~Nt>(@#sGZXblSNhuX8$tQOpWGNxTP&cVtss z?vS%5t!3J%Y-x!x(%PZ$d6LXXSaxcpncd5vN)>~MLRCl4RELkT~_hv{IWl8hXw47C-Oqo@jai;5`UEbKzy|7ZVTj0}`HQn6-F(6edLSGaD8- zhDqjflwDI|d{Cm9Qd5zxaSI5-wvsB2s+eVRKjVlgg@I%$5t3nq+Yoj+`VxmmB$-3A zZ=(3KT}Grd(#Zgd4F@5r63AYD2A2)&1i8Qyc)aKc?WrT_`%pgOACSncY#bBfHuqP`B!WaI)scH3LH2YDx91U92FEc*=2ynjj?G;e zGr;JtGHb{bu7owuawYDfon~o~Yo6r1FwOc5bvlR9K8q18h;kUdbt%>phpA;}6yM0hiT?rA)j$u*Or-T==&cf6w{|Jl&_ZEc1H8a`Xz zm)I0mHLVOfg-rWK69qapIVpQF_Fob#W$KWj^x|HN9e^Yqa^Nd$2)Mzh=w6JGc7N;I z$(@XahRv)w*#6q%yIA^0ajI#SeKJB30S#e|)iq>%Tos{hr#=S0YPqmrBIRtpPvtNd z`+;+Mu@%LXOa`dHt68RA!T3?QrNmKavNm?ipYUdNUyO5yB|`5>N-I`R(kd%k=A`f9 zs#;Jr9iflKwmVS6&w&xil;z{7rkzFhZ0ky9wF8DS8=#YI)63U zuz=C|)eIa@rt}ouXrDf-m)g%&%gw%4v$cyt-7>Ad&Gg>cKWvI4dCo0P5?Q5I9$a`j zVV(60)6Ih1-^c{zd7#Zs`A7*V@|FeZF7+VUXm7GBf<3qzbYP#}Jy0Bw?s zU!>fJODIV>JHvcNFX4g3z>|P1`IJ3!vT#pA510A%oG$?~QIezpIW`4((LU&WI6 zT4v19svK9VrHU3p=AMJE=Yq_%t+f`+CmXAgDgd7#Jy-&jwPfRna2iwz#8ea`iyZ{X z!>#%-@7Y%!6l}98z|8)hoip?~Js3PWr8Z8L(odQ^zU?A{V0`zBQPP&_m(O$IWDS(h z-SS;gLu>T(NsAS}_!W)#OT>9|l&Fi7KrM zDPw&{nlDwWAMw0Bm@{gbfX^hFn4U?bdgK+&#Sw~B4ZJP#Td3;fnFZOTG&8)vBJSdG zAnwJ$sh68nULMk2ZlUxx)BjAwz(>Dy?p}!%1W_qWbDwHfYSbEYz;ww#5g&$>3vU|B z2|$9827zguDh6R}r_*h7kaDFzs2X*YPlj`?Dr)Rs5QMB~YlDTfyUGItl-cNIr%~Stp2()RW^{e@{AZZ}bv%)?B=I66 z@(6J~PO#{-ZhMW!e#;2Cx?eyY%4=?R7q(Vwa_ZdA# zaa(%yr$vK^oRHJhfI~u*RzWdccOa>HnB1$a-|}Fw{6D_pDMza<^TBDqn#&rqAd7n; zN-&NijEt;rROtoNw+z*_ck3=|9 zcD--9BE4(A@2*b662mDKo0b~SfPUV~Y}Q@B+{{?ha%0_JCVIB1UJKWf=0UcK zPi-AOQSNJ1#B|F{C7k0wk&A)HTx7$R!KZG2)XrMIZP3|VJ&ha%^hLf z146%_dEq6hqc9|ktqk$!kQ5joKB!{IHU<1mDfg9GVwSE~`Cc?#;6*B}eKC_$5{#PhJ0)z32bWtR2CU9pg_yZQ*RaKso% z3=@za{Jc9r#=j*hdzX0_T`Fkk{q4_H=9_Dih?L^aw@~JCH%3M*^7t3Assg0jpieXn z7W_-Hv@asL6c!|3JPq^U9Du1}J9wq(w;PkS3Mz9=yx#D8zH}0Z+omie8~m72YqiCV zTinNBDi_%55?r`#MOhkDSZqFzt=a8-zpk`2RS7)CB}=J$5S>On9!HR)bL%T3RO%Sm zEQf>kqmK6ZZO&d#RAD~1>2&L{%H;!aqf{yZ=yXt{EFfJ<-w*_;mH{Ngm&E#|`YHw_ z;ufvw!A%=gWV*>Ld33@*HN^%AhHT0`vC)0tQ-6g&$PWo7v`Nq;c6FP!=Mo+*e3tnTwD+z{?Hd8mm@{m{JtrCE=r$73&k1LJ3tsS%z4Wc$t4}$9mPtX0PO<^3;_TE9AE$l00*c6 z02ogIFb1W9dj6LW$FsEB8MXQS;ZS-d#0XFB7X%3>)0wSn;cz?wKhuDMhm{lxm1HHT zLZe6_iG;t@Sn;}GB%ORAlVhd6^jk2O;)#HtyWQv~LDwI9B8^8H#cW0gDt2Dw8im9K zA5uEB?DZ;Dn;cRjZYve4-m1pMk|tLM;j(LCD7?JcSq(Rzbgt^aIW-B_4A4zxfX{CA zB3}@oDf#TZ4G~TkN)a>gm>32kOL11cj~DXd-A`_m$j(M)@}C@BF!V~+hg5ls)+^Gv z7w3I4Au>+wJ{I3&Vpp^M(oYYQQw|L!B1Js(GbF_cQftJDR%V&%;+RYyZ$=kkZ{I$Z zNCa3pXT3L1`pJ>u=DHb$>22a_(s)&J_r=q-JB8hL^xgUJC#^OjjBL3*$zS-voI1$V zpi}U{hNq^a!dqo*E{tR(CazwVH!)6nzD&R0GO-??yKrGhZb|u06f~7(H=1YBZZ}r= zpnNw@?AOt5JRFU6FF}UbelJmhsbVilMd)}hSzV5GKLwA~ELIRgst!*=fve*J^<5&1 zQAh(<0BLAetU)MpW1&6S`VcpCOdzF3PzK!MYCqf7kRHI~b5B-`Ct$X9knNgg$$$m~ zxU&>uq=ZV6qN1#_pe17D1M+}miSVKzDcD+3f+2x)2?(O4EjIM>Nr3U<$s-3i2&eD z$!Yq9S?_Gf5X>ej1urYOOX1 zwnQ2dRVLVISK024?N_KX&16Z=Med2-)@*hJp*B(4dmd?5ytv)LW^ZrUjkf%L(6Xjy zV}gjLaoohdTfmqb@}@$5E0iL*ZPPQ4sKvzmP_o=y zCjIi(L=UOzogqn)HbQGnSwfPkcav$iqkZWvlWNPgsJ{XKJ?fnu_k`kG6wBBuw;K|T zGo0`93xQS~i#rO^P%uLt8H!PtE5>ptacThknIlTJZUZcVH!D`k{l?Ctw?# zD6U%Bu_p=Fcref0WMnBzH5WZz^k+VQD3L(mF6idcQ)!pvds<+oNYiqTm1iO343CO4 zY$}gSbG%QE%ksn6PRfhZ98N0AODj(*t6NV_s-Ay2v7J^oFFKsov>#NS)^`0mIj!qK zV?V2>z%x5*7;x}DYaEp*4MIU9R1azZlja8jzycJcn6sMfJ$UjMa3ChCUBDt$24w*p zh1V=35^&V*=<;lj2JdHBWXbQLTAb#oGlpZprD2N$`Onu1o(}+RLlCt9QUG2UfHy@M z3WdU*Ch}Hcxr{wTH_##w04n9+ubJ=oXbH=M=zNg$j0>L)Bf?o}7)lHyM zB{l-krrprL;e3lp1e%*k0YN{~RHVk>VjMw(%McL%I8e}Oa#YEZ5OoA?DaY-z^b1h% zSFpM2^bD|=!dosM5feO3j;Ef$;py`PLP3L^V)=d{Iu=g=lCr?1f$v=z&YM9Qfift+ z$CMMc@!mx{EyijIaPFlHulX6Quu-F}p<2BX)ki+#cYy0`{&&4qJ)8oyO>(k%+!@8$`k9R+xo&ebS0Ca^OAo)cQhDtt=WTXd8 z^dcAfaaPaO^_phj4`fI`Yd11(ibl^pOE3(aT8nm_oubg+VsM%P9Sc z=P=%pK`#HxXfy00(qRQThJU*>-~XTkueQGg!pvefJa;Kp+Qmht8sc0h=&2fP<;894 z;y-jz!%z*x;bZhP5AdSfJ(l=a|L{<*ph1*(?FzDLjj?e9^pv{_!$E-mvm|{+G5oKR z40CLQh|uZg3)vy%ds5Arqao5VRt%} ziZ@%mUf6Rj#+gm!Ge!SVlEwsz#0zi&*eD}3S*DTC)Z7?rsah(P)VsMvcso~V zGTwT=`W$dYO=#B2rQT$XtcyGG6K{>*!ouKYx6o-sII?@EV5D(>J3pT@Tk3C33o%YH+D^;GY&f z%q5=Rf9|hID4jn!d5*FSF1*nhKDONo9z`OFjfWC%wXD)EWe7tEb&tqHrTiGu0|*R{ zw!>r0<+Rbs#eEEeVWs7CMyNKz+uj@RNi2O^WRW{j!Uq_{0R$5JoAIDgc_QP|jq=?@ z1!Bf+HHz7mJbRQr#@Xi8`W%~AVsL9Jdc`R4$zFZY;HcQ)S8;}WXe_#Q zkgT`DahbP}Pep!%b@?~5*NNySl@3WlnGwa_PnokpNsSJtiJ-o)gL2!Ald6ogldRPc z%6|?{C2c0?+4;jl6im|i9vNAcQ@YVr`BHiN6)o$)wez;EF!mqqdufh8I*v-KesrF- zp8oiJF~t6}>t@mM=a>6~s-NADzfOOC1)y_W^ngg5E_yMTt1tSnU!Gm`L*+Rx2MG0? zE(b|%t1pKrea%}%)&W;EnB5K|5~vt ztNFF+)OP-B&25+=}4|g zf*vTd0o)<}?_~;e?>+kU#HH5-@s( zab(O!0%2Q;x8=duXUt$3349ujd=Mj>B<6#GBy~JCqXbAJL8;vps_SOO!mT(K;?$U2 z>QqAW2n!OyX225JqGp75j42<`($y0JSoh7wgS!#~%C@Yz@!;_hZb`6ED1aQa6>blK zrLWE*Ui-7Y2%Ij;MCE0a88}84nV${F>KSIFWd-xeXu(_or2rOMbVEo_&MVTm+eh^$ z6^Zg|>a6l%#wK+Y6z#qj=tQ={U`@4;zeLC{+^K{ooNpP{HjNH@V0^~y_dQJWMdh+Su~Sqlxx1g>Nb!$D}?0| zMF@iV;(n=01N7Wj8B0aAQH`W`| z$7VP7Cyxe`7|{RYTbCX{|6jT+A-_8m_~L|pq@Gq92_&RL9MxM4g#MzlnQxof96%Cd zsm+h@nhzvD6Xxbf1O7UITcrCez215xlEig0G*7};Y;DZT2S(Yuf ze&+=>X95iU`XDXTg~p$HwkdC*a87k@Cj4LD@R(TeJp;W>vu$hdwHX+l> zZ`E>zf`Tu**`Y2g3$V;tt_;0{voehZJPt8^z-51AuE+Ujbq=dx8P@);b?$4$CS4Mt zJnSsbvF3WurVkS*9b#@ZWF=EWV?L?-X(f81+0a^<$~hQC7l-(CqC01eQIqW@p4SN{YL1wz>v zM(PXxQ!4*oSkF3}KZ;;^L&q@MSTg=US+5$wMsTubpLD2}@-h@crPTZ%tmpo6~0#_`C z+TB8^RoX9*PpvT>0r%HOFGGnr;qOlF$_?&R-+YxYU$yo*{e~mF|K<+>?LPD4w4yxB z9mrI^r8jK7pKc82WZ6b2@><6OR&|<}ku4g}te4dBCX>sQ#n_2t>1)=qE9yNo4MbH< z--!|M)?PIDb3F7tRPfi4rKhO4{$eoIKfAre7o6H8#!__8QW;%bFW>k{(w;G?e|u@e zSkL=`-Wh#rKR4ZKQFt#FBdvldb_Rv%Aj^&V!6wIR@tO6$2Nj2TfxnIqKLw$&9pxj4 z9gYejm@1D7V}wqQiW215j*C-t9ga)>zsipRV#l+F5vHoM#tEU*v!-b|_Vea>UB~m5 zWt*z=)^+dG|JSS!EM}=oS&IW)VbAmQ1I0Pq2MDE|E(b{TVlIcseR3{`DMQcPM;PLr z8b?^(JYIA>T*x#WU3$2ZcENSvr^xmSuZjE^w)VU5S`0+@^Df5ZYu)o$6Z@E^N;%t zo!49)o6!Ml_j?(isQeCcp2XBq@i0K0@IPC|er@SKwW5;`^Zjy1IKuF0iIVTez9&_O zxJ|GB>C<(d{hQ9aK3)UX{<-8oyskgH2fh7#en1}gc*FaLpcycU^;&Fg-sj2VV&yvU z^WDbJ{($f6$#oyT?biM5K0f}+{d)5Jo9ol~fNS)hzo&X%UO(-Pzill>hyU5H3A!eL zwZ??^+)>pB{|F#u*WVVz=zL*9>;>yQF|Wtg5{`jUDE5TVz@iDkh>*-N=k?N%p;yC*RHU>ZcwQgF9HEcY zC@w^Bn4wTvxQ7|0B#?ad{lWvWi{YP;m-uHs1UkNm!eFta_=X`zHRc}o%b*B;7BP%@ z*$@x;O%L1f9hM}&N{CP?rXv|0krTa2Oo%CFU{)MeGQ3L4m?&m?IXbH5f0dk%UBV)- zIHs9(l~S%!!lpMmrrUXyS|3xwVXHW9xO$b=K2gHuGdgbi`zpN$yObwfal(T9I%7no zlrMdB!bbEub2_F}piFVn!SFh3d7@OPZFJJb|2lgMyG(dkampj>I_F5GOmt~<%DeMA z_adfD>`?KW|LS$#{Y06>-RRS|55KQJ0dUIU=t|QeZ)NIF?A_i}6|&i|$ehEt&+uQZ#KbyJLa)lUi90#jpHq2H#2(md9G<1hEZwRJld z|IULhGGSgqR#--3C5kSv2S>ZhIfeyBfyms#^E}lnDHATjUTPQOr<5baX5eU_rsiMh zSz|D+AEOIcq2Sp4Wz(k!(W!}h2L&2b0_@nJ?DNktZlp5AjTduuVYjp{L;&i8D6|kO z$+FdIInzToU4e2UIs--wRlVPH=`Pn4-^+(!kM(+)Q`(IQL=l!?7`m%2YSTjg0F3lh zzjKO+&ah@c9o(o%^|Zc_70OZ#U~xB`$E9ntW2u4nC>e)2NyGRU6>#enmzr=3$-k&N zGe(I*R}AlH`%F$Kp+=M6)r27I;^)GA*?N0Y11+9JwL)M?=oo~dDKqxW@2wH0NSArL z73rbpSKfq%M(r=a_PTfWC#$L6b3M&S_Ky@E-#c*it8jjmGR{v!n;`Hi(98*Cms=R% zZF@Ul=ztTXjvZ`F`{GQ8Rdy4G{)cZ5$7}MZkn?>4hYUkI_GPH*XOU6fj%?Nb28DcNrUMS;=y|);5T3?V3UqyL^upkJB^N_Z9v~-BK1;U1z%1IK$i5%6&XYG>_yylbpKA8D#g5ut^d9 zox*q!2I%fF4IB!Y`LjOA#e)z1U-}sWZ~+_vME~nEr+y3mb|r~%f@xZ>TovvAXz4xc z=iosJ+<69df>GH|u&6Vp{M`Ry>a%|S?=8J=9$erv$mr#Kt1~c;&P0@ltUmtSa4dS& zU)P=CSoAkjfgPTE-%_QS$=6eZ+@-}`@Hzt9r)+w=jpd^AG<$3K8ed2y~_6Do6*Xmv@!Gv zT}j3bMO1i_Dw4%An|V#DGH-;Dc|>f7lY2iKkW+{08#ynk7Dt7IO5SgIW4U-L31xcW z=SdQyEz<;v{V3aw7yof&nE=PNFHRUJv4ctjK};FZJQ5xG@X_^%A}9K+a_dNAn-#`L z(=bdMuRWcYcus36t+}Dc!pl_Ip(2@aB1vM`DZvE$5mt!-_{WEdfoQ*NKLzzIWhbEq z(*cBlxlCm_cpl6_Oe#_gN;1Sz9VMl2T|`UE^1ay{T+V3?)uS~bXl2Q6K&FfwV8s)@ zQmo&Y)=>@OfQ_a0^NFZk-Omm0?27M_ou!rTqK2f7Zwyvu%ZjANkDF(8DJs(w@J{uL zojWVfsoSe7 z>xlUmkOfHXN(ADQ{-NFWR?7;VX982CxMgA~ue;4C(A3-nDpfY)AYkD})8@c+&o}n} zjjs2MYAW!yeM3k>Xdwzn6+-WV2uLSX>AizUmo8PR7QKYxfI|M;G2uPQz zsGum9|2g;Fd)|2Ceczw<*n5mM*P8P;hpN-p*mt%h;G=VO{4dAsN~8rD2u0yxNOI`L z7rW)L5PE6CO@0jEg5R?#HwAVhGRnD0er)v-PU+#hN&dx7jSvRKzxXacR^zI4vlWjhqV>jzEVz&0!V3^e@>1{8DB}+re6C!huyvK zO~T1!D3VNzjY`MB~IUj#~`P36cvEtL~bCYJw%emJtDR*om{5A znLLDi0I3~mLrtSLsKV)?XlkfETbc3J)9jQp@B%sg+Blu6~ z{_BC^+q&oE{`@Vv{1GLdw^YrK>p$kzZfD-Fi*1*3smWmOC{0gN$i16(j$XRuM}S%5 zBV-ct2dK(rzw_Mi+I_r}b7zxYzL}u?Ic$jW6M|J1+Z*@9ZPt=7N8P@U=ZUBJ2e~h` zY`l|dsaBk9QU`pMt<`rZLM^u_fqIqLI#6ki7yjPTlXQ)Q0o zO5bqmTJ90fG10l?ctyq#P_|9w9L`F1&b6HXxjs+OTz9=@)p5FNuSfilDTf13)twyc zmcT0CRDHyQ9Cc$(zNImhpYJmUYaJeqFHHs+H)4<7oaFeHKc@ZsP@+}m{IoAEK7-E* z_G2G8^)Ti64U&y61r-Shx-unLguVseQRWsWh|}ZWx;y-d&^tSLb=OLvZ7T7^Cr4v# z`?f0z-&OBd_I35h+rRzuTK&sjDXUYfh0c%4f-i@^LNiE^RK)>N2FxUJ$)Q^%C8{dI zjOR1n4y<=6>PE`4OyQ~_z`JNTK%Fwgnt-+yffj1;pymfa*e-i1>l-5Jj;z7Y7P~-8 zLQw)o)^JkxK60jaF?y?;lnJzD?J`0Mr2KZ&k1u;c^5>B>owj5YO2Z5Xkw`T<;>>Si ztN>1jUUmOF(hfjY*H^sUABe^EACz122EMngl!gnuHR8~VexE%H-F;Z0_t0L&CzmkL8x1O4;QSS~^A+zby-le^iJbn}(x* z&jh>|spjZ%F>Pu8m>1ntFZXRZ<1Pp{Ms`-5J$d9P^=AnmD(0DU`HU#k6Y&7u+}twh z9=5%;^7*8>mE%2zg(fm8jH#u4!9CTi_0QT-Qj0Cw#bcjGX6u(zE%NJ=FJ3jSh{AK4 zdx+{!ENHJcAY83|G*f3zY}cDDPU0=D0_X8^3|r8a)}hB!UJzB>7sQSDaLF->7=67> zuaScsHL3rWRdT%}l-vS#)c&4(`!d9nUrzdagysLa-ecYjoDS2zD7K5-1va$JWKa2q zPgo+16$+Neo#$M$G_|2@7FIrcUQGELZ0WXJd+K5H&|aN@UGeO^+j4#@K+ra zC;ZrDuemh5;9&K%)Z*ro7FoVeL)(G7P==+LPyF6n;}|ja4vUbB`s~@0NCfGAalF*3L6ixtw}H_o;*{wa z8~KWL4ob;@Pfl7@c1aR17SofEhq&QPx&2DGwnTP7KZS2$Bq2f~JF+oZZrgNAMewow zLEPg)Cj|;-e$#Y|3=ej@QOFUJ11H1l#HNE9Xthxj1AP3B7W{#?BNlfz7cO}0;bNCt z5YWDqn82`4Pz@PMPBnD```Fz~}9HV>ngvHc*#}n^7g7#6 zcvW-+z03bT84!Z=RHnWQXUXOS+UI6+0F@C)LZIrZkcr6rhe;Vyd_<&V@yX(s%DXPq z2pK*&VKLX5Sp|^v*i8-8!fEa|()q@DjvvTnpa=vmvG|*~uH+fj2Q@Bm0X?-Z;Vxkf$xnK##`_7y!kdAr&oV;d-bb>l?(7>RJ7;VFNzM%U`P}6!A06 zUl#{nU>+SNNoi~AauzHq?P@lcxetz#WZ{P(eR?1rkQxKfGlEK*3ZZj>V%)Yy9-Wmi z`yvEG{*7jFl0om=86trCX9Mp}SioYmf1I(kBNU(@C@WVi z%mD$&i`!PQYFgf-I&p>1WBH`*z^5rO3}^do|3G1kn<)S;h)ON&zF=VCcO6;0QX;Pr zlzH1a0$lhU!RtvHO`U7wchXBlg*>GM9p;hTo-hSrIha4aSuSc9%nNm z8Uy|M)TW<5!z!o=Oci{LbDk+%Apq<`9%yP_HhM}{Tv+~C+;nSS=+qMmJ5UicX~Vc} zwSm(Kht&Gi)<bb;O5ivwOoC&W>kh49b zPrU=7rx#L^79T}<(~b~lYZj7`+i0U)5Eb6ufB{;nw|CG8#`Cjik~FVElA?YBhX5jp zdPJ0qFpB)*Oof8=EH0=aIXmzUr}D(RL>0zaFT&B!|Fk7jGODTgKFJRgLBPd_8(&D2 z@tc^R2KT+GSb*dWIPPs=$7|09#mg!M5GyuZ<|83v6Nxse(1w8MM#LJtj7yfKP?Od& z9tp(f^+6!dMH>SZ0GD(Mgsehg&tPuMx(u}5!7K#$dn^f;i_T60HenhggbBy9<4<^4 zRR)qiprOPYfSq(^jnE45c7hb-*1-VDAX_1(Pc2CNqtN!peyQCLpm57{*6WcHCRgur zV8ij#{@vX*REYHV*qz)s@EpvC#U%@FAw{kT;AOL1k< zTMx<;c?AT}Z5L@vv~*Tn`D!pQuQ(CSYsJ|YacsnYU7{mU5RTY2t3ew`3 zpRBXgzT{U#2m*8)B#-8kuQ_Xbj*s~MUVZBMck`3x&8wrB&g+%ep}(7YE>3EC{;G4y zUCx~TJ!`zV-io>TJ$d?XzyI^U&kL`vo`hb-ymr*{$w8rj=XNVYE-o2XcV~!;8@x;5 z_LSmqN~kBbcoaal#}}K%m#W66U`bn$@De210G_lSn(&r3;e&WW|3-X^X~O%~g!aXR`pX0yExJz} zJz$C+3P6uw&||IWiAD63D!TuSxUV4|c!#|161|8?Ty9NVT})iROkCtn1bZcJm?rH8 zB<*984o%TpBk^A^lg^-MyihV8p8T^l=~x`T9guu|nTWS0&cYHGZVck>Uv`&H(gS;`gzcWPzD(fhl+dm;y=Q zO9!-Z2HGAFG9d|`UjZ05h=!hya^018iF zmM#XOhRLN%9`XeHIA@Cih{Dgn5eR5F9F%ZCK#Bzx;&ZM?avIu_9?=1%aUeZZZn$S| z1{@@4oy`NvXuL{#FOk11PS$_Mor{77V)HT((CM7?a6HjnXJV9E=1^eLU{1k`cybnw zsQn|M+zl$j7yvfj0P7+l#zK(8Hn1)ZtPg*)(?{fCO@>Dmtj4AE2_;=!CF*}8q(^33 zsSyMp5P)5RpF(lRK(UPUZ8XQSA^sJIfw^rJ`w!W>lcd?d6GTHQZ4UnXI-aPxUCn2Zx z+n*$aTmZtWptsi~gc&@wq(b#`)x{o&^6{~Hs@!~i>zo;|DOvLLX5Xs(Tj zzUJNB5>Ytn-Tj((&j4T{K!Xf@brA`nKy`gjWy3LjHI*mu?g}AQ2iWok0kLQR+oeF9 z8ycm@8$ID4WTYVSHF=e4M5^QIx&W{ou0qeHv@*9kraFb6FS!r_-dQehKP-Q_)WieN zvg66pVP|Oq5k{r|;Rns!g0Up|DrXp#Ll1RA=DoY4%!&tQXTC|MsKzdzTzPAeVwhK6u5vrN&j~bo z{Fa+ou$X}r08>MUKWP`xwVE)nsJSN9Jg%G`(S=^A^dYX_xe2QGSt^=h$aN#B;%d)M z8O!F>tyAP}fZ{r489GchIKy%Z7V=UPc*}r)+6i52iw`UO+5vfEHO%H!4KJWWZ@H*}q?-MA)mk+M+JI~N-Nn3&Yi$P{ z{{aZ$vMKrB{&lVYxB{TzuZ8Lo+>P%sSV>)#NLEZ~si&{64{o>4se@WpEmt=O(U%=E zR8nBEev%cnZ7np{m8*OWjHp@$#sQ(FobQ*t`Qw#h6S;YO#gJ;uPJ6b;QRj3=_PEq= zf?0iPE;iMr9`vXEi+L}hYyBO-kj=!KD~V)!>(V>d&jv%89Z32`oCUEJL>?z?NdhnYY(1~TKp4xW7vZMgJtD8b3t1rk(&DxtzuA4}fD_A9~>)PA+ zgr=~3m_h#Z=Z7V}YQxLz?U>(9VrMlL7So?rE3htaPdalg)$2%Ive{Mv0g4@|u2Xy0 zt#8gC$(n5k|W`r0;xpWW7+U`;H=qdJzQ z`>0-J!L){3`Dc@t=fn$Y+^eTm65E+wu>LNkGJl)p1?KP#xo9a<<2zB7#XDOd>0T>b&Lg@y~McpUn?rJpMDx-TT3-OLm14#Xtz*K9c=Q71VzK#b4 z(z)Gj3e9Q5$VCL2Ulvw2-%O_YJtg$eCh$Dju0U-WXcPRNAPQhY|CFc^-5`)^0O_QF zZITwhSB~3C)Tq?&s)l}c@7~O~+W*GA=R1Xw#t~H`b_b#4)mY+Zx`dhsdnk{u_2P#( zfvlL5&8qH2Y1~(V<3ml}JKXeXEtZS5rwwef(|YbbV@bqj1qRv}m*qWDEyOp5-NlmiA!sb(0`G zJ>Q&!pt;!7-b!Lm+&3Tm*Jt(L1FaTxmeywOpGSopJ&?RGvj+bttkNY#kJ26JpAhis zKzz=?2F&NVLQo$eB75wQtNL@s7le6*yPL3Ye8_xhKfGe`Z&!612x0!UoLUNb#Jq`E93RP!`G&xs0 zl|MUhLhSf#5Cy#bmHiCu|Mp7s=HLx8NY?Wf=nU)>0N2oEJ+|KS5?HVoym;wld zPlH---Vn;C5N-$(n(1DfAqZ9Re~g8G%<7Q!r(6Zz01Iypbl|I^`0~s^?2!kS-t8z> zvK;V`Y&nfzBZXFpmCYuGgTt3!?VUX=m&@3<6ZI&DjM-@@_7#XuKRr`|-oQRE4eSt4 zB__Rkh79YAz&w-+fO>IkYZuDA`gfbJsGQd612M`-y6o$hYZXLOwQi4+vP+uptA=eW z$K01>8Vd+l(H=~Q*u~Avd10n)az`))KKdMEG_r1`8+wF$S|ltULE>KEWrMyba!S5< zkpr8d#0VH#zvOE|y_B2pMv+}iZ^QGEZbV7y^dp@ztv5eK-rHMd@V=Qdwf!=fM#FMr z8I5yhQ;MeynU{nxNx!o#>rH$dUEB8c?j%jNk4gk*LMDx%dfGcy<@osHwKgA$yY1Vg zd^-BFGrikI$ut6rN6ml3hsg_uk7<~aK3u-~r%B|vbW}8%wYUkM%-SFz&fKk3t-+7P z+9nHn2!$mxgm3f{lD$o_5f$E+)Zx8fh&_(#2vC*proo(rCI7QxE}h{TNl{I~ zO}2j|Am${~k7G?he(#TmzR}x+*wvzX@5%-R?9$zN&rM7Y*E0`qRCklho zwi~=Ry?AyfGzfz&@5D(5w)T}IJ`#&>Es~geKb+b{FEP&l<5k~osF_3H%}VxLl<_USmo?B!+uvPvokh2*7eGGFn{R=n&_ zgx%(S$&GbV!|XF8h+>HOSviLL4EdQ`$>faqLFs43pu=CZa^U;`REW?Hg+}P>8~%5Z zyoRX}Ba1j;mdkKX!y;l0-Eazu(gDPKnkeZg2<-MF`xb7uofVDbvRW)e;D5jV_H@U8(crbDvC&AF@Lu^AcB+bi>=%B zDE-4W%EzHao>7*z+z}$NP*`6^g^0uYwe>yYlZTnLmSucA1VvnoUc|DU4iEAM2|;(p zXdkWG>xj@zB$Iui(~sRcM1PpDuRkG;NC{UNIh#1@4I}fs32+o6I*)3Ro+Vkz+ZE}# z0;?b4VZfJ-GWGB~s~fd{3@i36 z`Mq_sDq7_^$S5r(}QQ+cgxngeAHt(12+vIBH z9Bb0`^OJYT4_E6Lh-vRVF|$ZfH`~WQj0eSjy2bjr-Pq4Kii{f18>BS3Ig&@1O}=dA z$^YTz6ah4!$;zrmi@Lj9#h8C;p64m`t8=npu$Z38YR+vsb{ELASX0kx>GC^z5msZm z30r6w6s@;T&9m%zklhyKcj9wQ|MXxiv;9*6pXC50pY$@U2PS2A_KKVa zKFqQDQJ&g$yjJsaGr{6&%D?4D)7uy4d7n2)8oW4$GuqNQk#(_Of!tRhgbuJ~Z zCw*|l{V~e`O6lK6QSa%aCQmx%7=VNQ^tAoVU~89%8ORkrkE0>ArRKs63OJr6*tnSx zj|U9RQzIz>VPwJUi|q_24ar|}ZCO6Yj3~=arKa9UOE3tUbxOnDrw;~GSr}@MN!EE~ zyw#lGw+I~n#W?sd_u4`8W!tcQ_g6t|h@(j3JMIp=cixLidx_V^y?&ub1?SSHGN*KQ zzCXV^{bAhihvnk4>$rqv&*St&mS>WqeM>oHoYhU1KV}d4mWv7;*t<#2cI|^prH&8O zB68=lnSO8;7tz{yZc)}p|EO`e?`l51Jl{0*qt36u)#`M4p$qc!?W?YRYZ{CBl6{eP zGy-mRk0j~Fl0-k`)P281vshw5NTCv1o7WON?J30AnALlB3u3|_>p{&iTgR%Wtq&pzpi)$X zXAC_ZLh&{)9pOMyH9+KNzZvgA&$Vya!y&ur{}R}tYY^30X>4l7N>BH}IA~&0N-s}bJh{}a*(Y)T)T~OfMm^z>5TR$oV zfIhQ5BdbWZq%Cy{7xF#78W1d`3nGdn{cr}g*$zMCq#0uSp!@GBy6Y&2EAk?>=+(vx z%gdqR*Z*SVULpZ~XZPPkS#m>)H6nTN4{v*p2nNERAR(pWU2Arc>x7a08c2OrSsR=b zFrPpnHqwl??ayovoJzj7G0JiTB!Gl`9|zlvNbUCno5v$tYI@T6dNrNGPo<>J41o99 zz;qLmz2lKQ7|4eN+2)dNbBug4VecLLK2EB(W!G>gr!E3%h)S#savwQP8U0`b6lxbK ziGQbch8$;*a<(RX(%SmbLMGip;fBk%|8XbS20*Bd>`-VRJZF=$!9=l(Nc>`uRK*iE zMRc|(D%4r@GO|Z0U4d9E7*MlU{^Ht1t^{Fbm+zcy?lJ%>Tt+>xMv_Rk4Jax#8H7tufRDx_pGdbE zxeeM+NSBSv$||+pwU2hbjFiL>ATeFH%NYiAbbCkpe6Wm)5H7Dq&IT3v!$7&lV91xf z`@KfDE_+*t)W9BT4?7~VXI#Q!vCsBsklIrE%!fdMTg9Jo=$sGoe7jZA9%64e9Mvfa zzL2w`YP-vbd!`EF8X34rW*dI681;~`Z6LTy$tgSm)YdT$;<}W;+x6xcs7Bk5rjg<( zl^`BuZ2^%zG@!_GpW(y~+44t2N#FY$gF#Z(Qu!jPiTzKc5FoNzxo07=MeHB~ZaD&{ z(W;5|WuI_|l+k2{!8MIYx`v1+`-(OV5ixUP?#D0wwGYX z+I=N#Jb|x#$A3liG_5?G=2IV70Uv27yD@fzu1bxhOUF`4^s-6!Q{o!g6lhx2m@U;h z1~e1LhYQJYar`(!%l?l1j`m>W`kyh=4apk*Axs|RNvwud=fuQ^ar9hN0bj?dhEyI} zzDY?=bw9jww)e)uz6W<7jB>{xQ z>>b}G+TUnO(O`g#DG;)2q;KRjqzg=N1eAe3(SzgbB2-)&`UuIR3aOMEsiq0}qa_<6 zEGzLz!8$}n!|&K4B}%*R`n8Q@4AZHGKZ%W&knXAdDjS&54Okm3=NqF`)^lK2<62bF zLQBMlXeIJNwD*B9<+hJ#+|Sk4c{XWBYt2N$j|i=y<-9Pb5isM<@ScGbazwF!9ZbWm z@>fLtCe%LKAy#hFcesNss?%5hkDabS=48mVel3HPJ@R9fhQcs^C*R*z*)r7+pz%~b zh^o_2%DBF?gK{QYWbLX>qFU;lnqWiO*wuj(od^Rxo*uBH1OHw{+VkKV_wK`YF(19frw=)XA{R0EsM+^S6V=QOCZp*k1NY~g$ z-%z8Y=QZ^wYr0Nr6&O9km7+|d?#pwdA&u$7e?B}J?~rl?5UQp`1Kp=2cMSFtAfEYQ z3XAyfq-Lqqy#hyl&Zx-qQvBa>u(N73kE$YwQT85tyCgO|SwNFt%e2rz)kZZ^5-?Oc zr#Qi;t6(~yl3`Yxpy|#Q$!;yx^=Ncw#jJX=hof$&=#wc0cr=e}>?Uu~7KK|6j?8L| zf;SP`Sz0vvDIaDilgem5T$}mU-<>`uS$?Epz#n})t7&V9w}4vqa>y>Y4x7C)T1!}T zol_G+$c05oI&VbsO^nV5gM=FNtI9Mc97d=IfI(n`!AFZ0nq~zb zYt@h_Ggz23UNm|VeGH5#Fq6{)C6k+=l_30x1um`8`VWMyMusYN-Q&vZ6A^t@G7_|( zIy8@a83g7o{#Z;k8S0PBUHRzgDo3C9BTxTYP4sJY`Hr&Hsiv|^#5aA)w$oa;_>9dn zsQvKy&!@gNQj6eY4J|Db^niI2nE^&%ww6*uYD65Y{iLReaP+=frPRU)!`ad=AdWNX zpFwA&-u~|KDJ(r-OEz(Mp9Png-Vm;s(W9@F_Y3;Mvq>XKKstleM7CO%Bvc= zu(PF>zi{>4vdC|9LNQv>8Wb;$yVRQeDzo)CRE3gV-{PVNdT%8Z4N*mE)a`t!t+7U8 zpAcYxLtuNgRnrhQ&~cZo&Bhpy5R&;pH#L(^HD7d9ojq5EqT%ZDL)ld#POxJ@9bj)9|sT7g5hj|s91{E2LZOW>(C^vT7b!{d2}#}|?f47S>@j33J^DnMjy z;4@T1dggAO5gc+Nux?AMU3mV~RIp<*pS&E{B!%I*+pfVvzb;{ZB;VgJp0eFcV)pZF z9qAmA`8$dPn%$LUz0U=71;n34BKqHMG_ud7k4z2{alVHjM|LR1ErkU}TCT{dXVV_VAYXlrfmyXb<`5+j&(TG) z6XY2mid1>9PK3)ikf`z?X4&%#JWoJZD$GNVRXOiS>C zBz+f@A6$OM8JyA%PRh+2{f8_4y0!;r&l|mmMeT`Ga36r;69E18Jn)AW;XEkJ?Od{pQ7ylXk-Ie? z?B;n6@l>F0t{+t>+#ph>3xGQjsKSunS9^s%B)3qt*PQCy`O&=e&r6cJiJeQ`6?k=I zuNDu=vELYfa|6F!u z3cu(^w>{dM;FEEk+WxYe128Hq3{*H&!_HRx@3i6n%b*y4U!%EpsnO}b(uQ>_O+*hG z;QFQiZBYC#vOo`tkn}cf*s$3jduqkQy{(=(n7}OMctq=+8J?UV-EB$NxXTmAL<|?8 z$2%dDb@T4shw5YJYIXXp1h79`=b9X9n4YeP9<4SSd~g0MmEy5k`|67rQ@+^w&Ts)= z@>1x-&n*>>b zd|6KSJTFN06IVWPr)@9CazIu>Z07j86+N#?q_Ykl=rZgokim?Upy-OvBj!o24_s_6u3 z9KG+p_qF!@J0?E&_s#SP2Tc>KD*`Pu3a)jnD`^aF1;DCS`(%CIr3W2q?F@pQ+G7@i zU8l>Ur^#0z7f%y!4ub`I{`~F`#AR_D?etkcs5R?PGLpY-o$Pk_|BwZ&sxG%iWs7UQ z$N1kKd5;VA@cT@NOuP9^ihr*4nUbE)cW{IYPMqQ8pG>HkmZsGHPqKisJgRTX^jEFl zyyc5yzXj{p0zW4yo-dvCD^=Y8;FuG;Ma2ii3H(~|G6Aj$cEVqKQDOnGRvh@Z4xrD}8f4ZR5B;V?3kku3xlDT@w)im573)>WfL^j_ z-Eg)K2#^+3o=RUgidlMt*r!*X_PuVT;Kc^{Q`J7|@P;T6%_7*%>)3v#A>9b+4=i`m z#g*uQ@1nJoY~enpeH_{|u~MDIcMD7h1k~@u8*Q^v_FpQqqLogq zvNEo553_x|lVGe_a{tZckj%?>i6OOi_kM_v$llXW2^6ts-5DXdVbKL_GQ43IWCPI{ zd52_8uyZ~(Q`35xmY#iG%B`rTu9I~)qg<1N*F-|ys5vdOBBYGpPEEsP{%%%wB$*?b zu*f9Yap?C1j1b2zX$1(*J1or!NUTCS!gLWpX)NG$s0Uz7nG4G=M^<0OyFM_;4f#_3 zxFm(~DuvC?*-KP?3?GNj0Y`rTtr}rhKTA z=KZ0V|9D@`BzGojYOefYl(UvY?rh45VFmBtfnwrS22kmnvXM9)hbUV~nPgLyZrQj& z8NE@t{*P+o$wR{?^G|g_O*PhohbDvc#`S4GY8|z{ntn2$XE^uP{KeoX6m?JJ+JQCP zaJ|&&)is6C^d8 z(Er(3Nbdgp$@tPokDnjnsrwuzn#WtGGV6UZzh=drC79npe>S&H)_M4kudE-6hVZeu zbBZ!7>Di{Wj`+EGW#_Hxi}|;Xy*lwK(RjLNOw&F;`QT-X)YGr^%@2qbSF#2eRu*6e z^+td}wpZipKihwGoh6* z42``rQ;+Ou2(IpS33*ei+;K#VzZlz^RTSiBDWPhVzjfCZ?3&=X z`K*xU^}*A(u|!(?3JkyTXB-b5Us%#`nMN>uOBt5J6*;_;$Yt8JZtOkbZ(#U}VN&#H ze2TIr_omvsy8{)?6eW!0_FsOWmI;K9q_fuGG`(fAkh@l5X4^uWDvu|esIbU; z7oHJM(RJiOhGFD8fZ_Kxk>Prs5tD^K!7}TNZUP2oP~^#vw>^ojXD4^vogTf#Kjg7i@lW%Y@S?801G5v6VA{O&qaJt;eM!b9m~G?RcPi{DgYTz=zVH$s z@dAsX`#y=PgmJ9jaZwLvnD1zYh~G@1FF5v&(|vorllf1y!JRD0{xcZ7 zZ2Xg3g#4S!Y{Z_LL&U?Z>TILeEjx(eA1*Xj@Tc*k8pqms?KI_^K^A`xO{d%E+lu%9 z+zX!Dgc6OqPPr>WuY{48O46O1alEu&?q;{PItIOSG)-2xxA?O4;Y4U$-f7;JTkAkx zjV{FQVr$Zw$geVe)!VN1^6mv7hAX3PnKL5jYzY1yy#WLDQ*=V3Tb26!LoPYe3s*!> zI`MKdUsz2Q&T_+~NMz4_UiZ*}Mg0}29~2!-eWzWW50y!_aEonDHlxVekNTol7^q`v zd!9?&1&@S*bV7VRR8o9#QrP>qhR^Kgm_94sORm@F2awc&J%3(uZ$ zBjlzy5|Z24a8(AtSX)P*%v0U4YH0BK<&ju7rf2vP}CSaP|&d~5J276nobBZR`LsZq&4 zeUx#KlzG@GoFZcva)h8bzd=!KV}myl6e%y={i3W+jbG=s#^o=@h5Nm($#T8#M0~I1 zwUMr8m(Z(JE>I9QEcXuV2*o0v)!gn&D2hQR;-3B2gHB`=6+~MB;J;2} zA!p{e44WRn>%tpMx@23rblby+x~Ba z`4f+x`BcuoNM->!LNhmzFuiEt%u6tH0C*V>d)Q1{tLjQ;;!*>K9SMPrgq+!lJUZ{e z+PPA4XUJ1klg93)u+hM}v&hbI?#)@KQJf?Df~T8vf`fH(HFcnglaCP+c7+MXJCd0Q zk$5e>6c8i%V+u|S%zP}K+M4ZFfl7Qtf8k!FB9?bqlOrQ z3jen^v@pLJ)M-jYuoH1DEsP5aQvw7kMki}LiRj}_)x9D<@z=#e|IZ(l>*)4yiIu|%$}bUh84EPI$__UJFQvG_ zB)t`I(2Itc(c9}LPY(6~g5M=K0ThoqCX9*Y_>H=DLjvE^WkSuv2QiV$8|1%`&YJ*i z7hRx1%A0c`*Nd|}Hvo(aI2IQ-2`aE$F0&#j_;}?V#FAxe0^+DHe1o9KEzjEG zc{5K(v4r%76cI(^^M()<(eS)n8*jb&Fncpt`g5pTL+KT!Xl~vugD9J@T5#)zGBPc| z+wcs_wUZ;%aD9j+GHYtp<$iJ)*MIkcg zaiIvpq0*nV*R3wsnLP&pQNUEMXW!Fp{lqd-FWsP~kP9TN&>FfaMA9&dRu%&P6Zc$3 zQ4HmfZQ>wH@PvQnuxMnhE^%$fHkJumc|Z#bZ?8|S2o~5a-Z-<>J~Dm(-3RW-LS2~35^E)AM?f1bZFOuaXGAUmEY&!5 z8PGJsN8w%Rp0JYeN2To)*;)dpI3&h!dsZp@vB!^R-Ws%DUkIgNrpL&V*n3r)_o)|W zSfmn|fYC-;R@2kf~I*hF#I4y^sjRt*+O6F&50! z0-3rKWAIK2xy>IR`@4RbGaj$+`T3C!RdQB4@U%>K-wK3g@6=5Gud8-D0Lo@Hd8h<>D0Y}WvFc|`Y6bBpyK zH5*zF+=YW3r8s-Jj*U6j{Zh18ULHHSo;pL{vz=(^zU8!QjthqjA-_L*R6GsKA3rD` zBD)^?EA8O4PKUFXJcaaCQ^X3Er1Ox&^|-YojCv>E0GrR(1J&e?Qtkop%%f z*tt!MPU8GEhdhoo?DJo|cN=o68(Kwsc-8i5X3ms}x~1fsr>zQaKU!q%oSP+Ec;fb4 z)!hv8^pnxrFmE}I!+0VgU+9L^qJm$)ZAsw%EwFLgG-$Bq2d+$DQi*GDm4E4u zPnk6Tq|e_OrAcAUJ$K%{;lWQ&Iig=Y;xv2uaR^c%tP;I~{_7rHCpdbv5dDgcWZ0bA zQI1w6-SqaH|8#A>pyk%HY}`1M%jo5ML*|{fw$@um(}kvSU>u3)^)<}&p3U+N{<~f{ zXB|}j9AslAOyo`S*YByLZT^sNF24Xf)0WE9`p%R2%+ulZ z)9H!RxyrK%@Y#gT>6-l6;QM;2=iXuF`C}hKupe6K`tc>{#hnSD3Ji0P0e26Ed91v6 zUB7tjym-sJ0AyXjkzE3RT*3-oBE(#x`Cg!RT>vnzFfK0ObuT~sxWX2^!t%W&$hsu> zaYedui609?K6!=Udxd9v{Q(oM@uM5~5;?0Ixf8;C(`AR&MUFZ|jyjutGc$D~0J#zR zfi6&mhHr#=?Q<(>YX+|exUB>rX9MIh?|zWo{Sv%W^u1GIx>JaO(ZIaZ$+}bCxKrD> z(}EmpklpKM-5ZkKo5kE~UfkJj+*@wkISAe>Ro(x{x-*ZtH^#ho@_q2refXt&ud4fq zFXRTyMhx#pO7BL_zI^NfJ@J#FjVe5iRio9~J*E0SLGQdrr=EuW(8RKC^L3xeQ~<@g zfWSY`6m;eVR~)4cp3ch+THcq zGx<6(`TRVA02D?tV?_?#;b;s-sftCZgfOGlk%KD90b3V1TadRx-}ggbv(gKkQl^*F zu9u%MP)fzS#=rN`jrV)V`?Ic+g5oQHBD-5C03Hs7D{P8f1bP_A`c2I)r`I11Q@VVS z*-$j{?RzBQhq;vx~nFhNMg)77pF2BS#?Lx|O{jfMl&3k%ZKZ%igK_~#aR50?3iTQSsn(<2_CPclBDzrli6oGcB9v77+39$$ zLiM8d`q|}tt-}|QEVJ^O$38VuB1`AZK`NtqlQC1@+nR!UMgt95b1*? zDKeZ4ea$SCL<+kErIWSoevoAv!MTxT8zXl7`)x_7PL6vgA6uSxqaRz2e{I!qg7@XN zRw{&2F}i^qQ|ue$-(9BREVl$v@U5bRtp!a#3+B); z@A)*4Yf%(@tYOu(*SK<`hDAjk)QzhOa3J7ug@RqQRo5J5*qheeHvZu0c%BR->3A=# zEol2d?l?EyVMx_BJx9J$GjlPq}9AA zD}=|Qq^PhJVo_E#$YWX2wBKr3)rG)oRWn50W>q&SPIPP)ufCFI1Og)bR+uhqvuP{) z1y7-T-5Hdib%DTV*CT;_fMXBGEJ5rD$MtF#RC{G?H$qdi%A$iGib(4H{7-_+ljA^( z3}#aw2_Gi2g3ozQHT1;JZT6|%amlnP)XBaPi=0Tl-nhec!6NvjFie}HvJ75F>ru?6aH=aPX^mkNK0eDKO{M!#g zCrhvpipgP7TC_0X4~duh?knVo1EC;WyKN`xAbqr^IYC^3Sf?qwEjTfM9=zx8A%bv} zG5EB8msmdn(frq7*C_lP?F@n{u)1jixWwpyv;=5MLyw?7h-GunMhZVf#zj`&P(fOx(k=dFkmhpoLfR%I_;K$eMB-w{1ku3c zRZl0J;f{6N*eY+49Mu1Vm%bTP(CyLMxc{fN=&tY+@1Hrx?mm)hA`+3>V`4e)((2-Y z3O?+%(p**r;!qha(>_Th>I&of7BL%P-@FpZZ%tB3!^ej3)fhjba$_c2ezW+_g!5A` zw5_f7+rxJwe*yPmBM}5Ur(tUZ%_ih-1XuAX!>ahnqtL`vj9Blq>HeZVQNA-$DuB}) zzjSB{con;3c(bIJ$oSTS2`Um56|qZFh2zg>M1jXW%p=bF?g63j(?{~d zmouqNfS*D&kZl=NYII1fY2W?qx-_PX;FvtXXTqAaG;RuI$;`Eza5OFbwGDAh-{Ujo zSy-BI9dyjRYc~~mSeo=jaLR_~Hxt2Io(dIr%Ej$46X*PY4-`AhP^S2}lC>O3qjbRoD@2lHDQ;H@kUiM!PP z>98{4Tv?h7aj7rhx3*ASSzZ`)X>9m^4-~~+Tjx4#T$)zaE<#+}_xNo+7FO0D23kM()#lH&iq)WA5rATzSR^TbX?+Qx zNH$J7I917Fwm`W?pdoec%Up#vFc*?YnReMHlI|I~`DNq&-}2vs|eB;9}~3NyVxQ~~^DlMq}Ee22g2;&>s$+7#N3K-sOuFg*Ob3|DIL`wS3maWZAZ z*H-*b(BO;KFq(e*(E!YOZ?+QywTbS;vLTp%j^p_lo*yGYcVrZ=z}k`@`x`e%A$a27 zUWmR8@%)~aE(&NrNfSeKGz^wXVLKYQx3~`$!y%vnJF==5xw_`Y(xf}w6HsOPls21Y z`%ORPX9pd-o8^QNJ{RSJIV?k5y3;nc ziYav!CLqS2%c}&woPg^+k}SbZA6rf;sqZ6psv3b(R^@}w8mHx>lw+sWW82H+*~(s~ zQx4=FEfh(l9z0XY1|dYbOy%tcm4N-kmr)@amB{Vz3KdN_lVEiNQOpCVre2qQ#D=oAeb)iyRm1Oz zr#8bxL*|S6>LEuA%^DVw#?6$u$VyQa6Kyq>>*#3Jll(H{H*Lt6@J#>e5z^~>+z3fn zrmyJMsAnX2<*McsZ_?Q3ljml4Qir95pcV>g z-$NK|!n*P!s9}Iw)pi54m8Xs)H`^s#Jz)?{R&B9g7%W{vzla;kiN<)Jb`mYoo+`)< zNm~vcLe?Kg$sSOz_R}n1-S^6QPh0mXnJN#32t!J(Q#2gH7yl9jf(Zwd9 z6Mf;k`v!?kN_Sc>la@Z}ZU?GQ?1zoX>V?9~BXi@1x`h)vMB!B_W*rn!-FpuFhQ)#( z9=LF61LAHyAdOfZ0#Q8#nxdZj0bAGhzSv@py*9#UCKE@jIC=~H?iyu~V|(404&-`( z(I3!*znn}I!AHvkQ{97~beP%>=0drs-Xgz58NI8#&#>r_{g^m4cSpS-Jj#A9_kGo% zE!PyEY<&!0*$JQ6-$4Kd9~KG89sfw@zWXA1!c+^50ypr9k1|&hb88W$Cl&$2U#*Wurk=R%xj~#y zpOQH5cEZ(f6OU3H!weWJMkm!Q?be_e28PweWxNcxtKPD}iyff#2Z29R-|!Af?t$Q$ zBOHRRL}f&^($GGQPYwJu3iDTYT&*UycOP|K4j@PYm_}&dGCSh6lX7`&Lr^``>LNW@ zDfy!mMO{g#v-fc%xsX!D0@PuNU7q^c>SzGp&1U?~h{N9QKS(pyPB>oF_S1TC%Nqt@ zn$yW>GdnJ^nNN%5mTH>d^ttDP!{xo!ullJXTzJ*_#~Be|6pQ(S(^+tp$=$AqE<`>9 zei383qr+|!mfcNFIDHUP?#}~+C}Pl}kVi;}D&pg}_A8z`k!Mcz(caoID~Qa7*>&Uz zl`clo3ZOwnlA^d}enUz+0q7pU01CJ%X&mj|@<)^%EkuWYWw1!4e{i0P=AA4b7#Kr~ zU#@cT$l8q3jWA~-q`c0C7#7FopPY(PI&p`Q9>L>R@6?0Dp*Fzt@Rbhc}3n`T9wtB?XtPdH8gveX2 z7%Y=NO*lto?N*Z}8X1z;x~Dhisxh+0tg}!BtVZDFQlD0^Vf`~}B;hioK4FI+fL_~e z_7?0)UYjiw2yYdBk_DzgZUvCw?!5wI zqAqB1dKUh=XyHdXj<+=)X5x;>4uxVz@HX5Lzuu$?UW(L1P-H3tSjx9T0)xI|dSnkV z!?BLCq2yPWor&xB#EEiL??|hig&3TvRbZ}M=xk0EGBYT`eRt}^S3W$%MH7zMq{f0z zl(g3kAprMMV@3XHG}P@aTgHYVq?jZ|K#?9$bvbqK5lgNUTCCaE*CKD8lx50-?_Tpa z3nWf|nQ+aMoVpCjn;6VS1g!$Vn-js%-=+EOYp|Eqzkr@7X}odof(O`##~F>zCs?8F z$!gyrNy(1{an&r#h-#1%fTK9z6%Z`l@^X8q?tc)vnvJ|Vrj(S|vwvkty1h>Xiw*m6 z)DsX~@8iw5v5toKrS(Sy8n%Yoi#SIrEdEeiVwQ)5*)bu!9HQbcWB)GMW(ys$hw&0w zM}0q~Ez^sp@)cPGBG&}NPmfcPekNcx{N6w*Cj(=)!+VNMUp(K`FL2QJbg)%_r)9_3JcNP#s^rpL9QEDFur`rTHOJ|bhwY4%>X z9qlowXr3#hmWRehB1!Kp>}c)vuxO?CJ>tM2+{UXpBC6O-v6MSj&oF&nIp~t#%Omyz zqp{cOUVe^+OxJMtC!od4grieF#x*R7Sdz>N@~0t9N!(*ZlUk>8!f%t+54wT)*YK2v z;-lc-?bR9oMS|(nG|BX%Ke`r`9kqy=zo;&*vW`NboE5u!tB9u%Hpb>3X?s(_`F*EN zVL4P7(x(O^;1s$%Gs>->yDpU)EQ>=C94W1z(}1bIl#?>MgeBjD?JG5CNe?|4QBAN$ zwbd2B{-Zb6A>Oc(cA&G$CIBOu1*C{akQW5pjP>Si(#te(!4<HdMdDe-S>c-3ngimbA!XscQM@T zM-U4Ijv&HGN+?J!*x}PyaenmVc69^-bkODk|EM~TnTmxTz*)h2%MVd1bAm>)HAG^) zpq%4c8bD^Yc9H^y%)A`j9qS;w4K+22bttu=8a%WgcDt43TaZ@Xgd4Fl6N{4qnjmcs zSiUAoTM0=e8->aTNu6$jp9T@IL)||jVAz1f>KY6#6Q$>J(chgs=3}KgHW}Lx1?WFI zD_k%yh5-LMiGd-pQhKVU$uy`xXh1)cbZ|{^Mq;JJ)YO)QFwe+A{eJG3 zA2CDY&@QGh_NJtL`lvYBqUX3M<@NBimAqtvDb0tXVMC+E>_A2>a&R?Y;(8FARp5Uq z;K3eN)Kee|AfEvh&}l&(Tki-x`9es8NOC1dU)m! z6sk;cjh)V&l9H6B84p@S`V@DSs6WCh9V+Xb<8(bQo)OREca-j}&pcVeYQI2m_rY83 zbB5?HQ^po$N^q1X3$r+c1@Eg!;=dN a3~O8QXsPcOBZ8&?X7PG&#NSTY{c@0#LN zK?J9OtTbkm;<7BmvM3JxA`VpEtVzL|af+R>*-%749blX3qs%GhnfN6_%fl3#=Wd-M zy4^^n+Aq|Yz@Ds+58;+pwR2JL)HJBc>TIT-o8tDgi$ zOhn?b5{Hfo4+43hY9eAU$KYxLzJUf}g;aU!K^J(VXq_Y9))tw7xGb-p=qPTy`$vA0 zmYjGNMO%?lk=tC(VY-wXi7q8+l6(%lKJIHrp#meGd01gbMHlQpKj}pUXe0QMJ{2lZ zmvi&56D{*T1yV^+@##_Wu_tiWwfq75Q>Af-czh5S%hqT@#>s!i-Yn&@4yTk3EyXNN zOQun}Yf7pZ6|f2VbwBc}LAr{{sQk$x*QfDIIFInrCrQFtuHUzO_6E!t$Kua)Oe8!h z61ZuRO4;r;`Eqn=wF)S8*=%^-X=|xjo>=12s#24piTct>U*HoH!X^I3dHP=Y_L#?D zj@nd}3T&})ze0ZIj?RkE1oP9-^Gw|kI}6J&!O7ALh#c&)!^;#+eJ@J8(F*>?7y6GO zte^8IZ^foT1riS>ayQ-2xx(LJ=`;p{%w?fjY!gG}iEzc^ z2yakG(dM>zg{!NH$T~^OQW)XW$*?3_mNt|&0p@(=ztw&kWAw|XLHbmE8HlfuCnIJD z<7FXCwb%4nnY+VNq~bd}bFShLh0-_d7PdV38#sNuv>LPAHbXW}vH`x8!Dv~}UqqtC zC7+t|kA!(47OZ7Tys|P$RWGfyaPk9iojOl!&5q*XFP%-OO|3kV$87Z%p+H_sr@*r!}~aIw1KvAiLUc5Y?|wJow#e(1>ry;;WR~X}`(%fQ{9V{*wBq_|!l&oJmon zT5_}!NNkA^766tUph*wHSEx*gg2^`?5z-qGWEshv8#$&Lal;t}rHQ2X!&{X@= z#|qHKf!!mpIf#mI$Qe#(v$21dHxpLd|E{n8T}7K%`HH&R&WMl?0Qye|=1d%?Pr&8? zG{+`{C?AVyzq2~MT8`EL z0iYs?0=O6eB344fbu+@_GlJ37B7C!@tRVQ!86oXiDeGA&?^!|rSuo7p4}MDdj#-t8 z8P$xra42c=4ZD~UF!T$xoE)t|0kxGJ%`9VnxZ0)e3+iw-S|K?~p1f@}1g zaQXtT_ks_@+>f_~?+lAUe;0VpW<<{xLZcTV-WFuf@ZqZI+$!jz8I}^Q7yY&8A{myH ztQUS)EO^Q-{$^Md`@7)%wg}HWGHHa!^9iN5+hzE>PzCc!ox(~3SzD8k z1Av$*6RKDCz1P*(R;AHr(@ECU{w^s-ud7DSp0CYZXfI^*ZwThBKcH{icdUGih0`YA zfYaGT@Y#Hd-bCr#L|fl9o1Q2?+x#G~g`>0e(Ps-Ib6Mz8*4}T6^nHt*ber;g6DY7v z?XyjrxlPx({dIkt@qPQC0v=jtG3)Gb`0Ox}ns9aQ@U8C%yzdB+?h241TIwN2EAFt6 zgII)Mr8;-zCU$|FyNVclKNs{B!c&C#FCqonhrGyzZs#&H(oan8h19{9L`5fuN9 z{SCb1uW;fIKyDJ4ZX!L@);?+OJkeqR#R}~-VIXU3lMLz{4*HyGX_E|0oQ}Mo!up?1 zbe_(vpN?jp_JYr*JJ0^voUQAeEt8&Z2%OJmo=q{HAA!#obk0xK&vq-%&(2Q+>}>VxkU z5OPVFbxE9cNo0FPesM)fc131;O%-!RQ+54?>>5?@8W(a63#qzf%0y19o_$}xNQ=FB z_ql=Hx)CA06~Wv#y~Y+}+Q_iGeHOTt-ME#9+$xaW9WrnQd;%#m-Kk~WkustHyYGNo zcRE#f27>oSy7wl&_hwo57G3vN8}~MldpoiR2f+s?-3J%n2e+&TkFE!=jRzmdgCE&r zfZ$`0?qi7WV_4Q>MAu`~#v>T=7)$mPFZlFZ_bJi$DLLyYwd*N;<0%vJluh=WEBFj8 zPz!yZi?g0fyZ);{g*;c2z0?Z6)a$-9`o1)0y|i|{v~Rq0LSDMbUV8;!`*mLjeP4&O zUPrrL$2VRlAg@zoZ_|Qrv$}8dzHf_JZ_8b8tB{Sib;#Q$+57kpw0`pUpFiIBY~O#x zydPD)%TB(ZUA#jL+gD5wA$iE1ErcHod8&c{D1M|TiI0B$r$ANa zzysnhYviF%Bfnd@!w3bG?g=r|K9@jLZ{RF?H!(2 z?NSd)cp(#qR+X^+s2@LvXf^mFdOaerg45MYk-d=a`R9pK%_BhQ_Y^`3KZIcaRYZmq zhw?O7E{i~j9uuOw9jwP5iI28YEn$3ue8NjG^bQqUchwOY$CV_ zJ2B)??!zVm_(ujIqJuvB91LF^=HVcr{#ePUDA8gB%*R79sk>w)NwF_gc^`5JtBe>U z{cFF`iZVt<29PtOdQ6Y9SknK>W<#u{=wuHcqYMkT@B@`_yL$%YZbU8p>VNk_t5^8$ zzVlt`@As}1hkv(jlGBP(Gz{bNFzflV4FYT(j1jb6o3lJj->Djue*F+*S5{UvZctX$ zrTPgg=b?zB()YDxRz=%&4;ev+y>GVle~VB5d!E$(Kl3C};s2MP{vQ`JB2#sBencLH zaw%Uh&QbX15mQR0XwmSWe@5fK{tCeX%@lP1kGSRk;-~*dd|F@fzvf9wFaWOXKPU5* zdR-BB(i~PxH6}B;+MbOS8ckLkqtP;Wm1`}oC);af4=3lLe<8(g^~M7DQQ*Ez zZ5D>H(pKrG2G7i9%-cPnCD|I&zj18}L*Yo|7 zBu)%%KF`yWqNW(%40rpd%Zmlbx^{=pH6-JJ)aRb6iOk~y7b(;47RD?)5cTBM+h74*Q&F29==|LY3iP8<7lvYP0&GB*8GiaHAN}c*D@S^I=*dLaJGM*!|K`PL%kld2t$}G*rbbqH&yG>LFcPR#XY`D9Hg^pjeh=4|>oS z<{hWfS2p+%mj3~o7YKz8IV7Kkj1fkj){TmcmDf**Tb|V~s6?JMF1w%#)ouJFvT59L z(5!6QETpe&-K|}rK=7LrUX127F|egh+iV;8Z}I870oDH_K9wQR0{}j#TGjO9=z7@? z5~_~d4`ByF^=tSE#H=G^uIaUd^tM(GV;}qYSVx%_WN-fB^_2|}2IDvw#-_;DO3{3G zHTWO#sgyJD>VJz*WsJK4TDBd|3$R`!_ltUwXY31xX>u;hW?9-UE0%44?^m2At(#We zhANttz4{<)u50cP?}v3CJPfWaTU&JD58CCzhT!{;*7dYd@hLZbuAYtiUb3Y;H$A5! zqu*g}kU;B?0#vwXxw0&q)?==Q%vPbgCPu$gt~t_|llr<&&x`gIu;*o08^-I|z@$z4 zWjj-r*LkOeZTrnMeU<0kR3DiCYK3g_^=j5q@a=9}lZpR&Ga=^v@c{GU?PfJ8>+Sg@ zjmhWj#&`1l?L0IFst)qheRy3Eyu+>b{>!EZh4To^8=w0FH#J}on1$=rV*~Kp$(O0s zgwYME0||Gt5vh`eF(d4PXujzqe{b$ZEsPB&chW~?coZQRj16I1)x(f-`%ZEn8!Duw zwF5cLP9~QNFiXM~V^O1s(&CE4l{FG$Og`+V5of`ZgUevfr}d*&xpL_R0X`Pti!r10 zhXa=k@N9=fSzK7~4AQp=Yla7zduzh&XLIrUki>X9Sz;V_4T&z0hG-CK!8ZMQ6lb)O zf^@e3s@Wp#*9$v65D4B*dmeTj8$$@ znxjnE0;T?1Y0RW8-WqcirASkEZd1cc{{NAo{cuI8K@$zq`p1PRrqaHhjp$4%;^;pW z#Of4*+<{DJA0W=%dKG1tZ$_btI24xo3vi%B`^@tk0Y>?pk4ExEQU+x@Vel%QSi3|@ zlWscMW43^uKTlRudgk}??*cNhFS5=aGnp83(PFrz(h1Mg1wh;)0jlF)(Z{nXbazE6 z)^sZF9?B&q>_w6p7OH*EbH(w0$~5liG#(!w#k%X2;HSTMZ|CXC@jx9}i+}CBJSC~o2 zEKjH2*QW;ieJtMO5^Lb}N(mW!SB=X-d~rA~v7bAw zfcOA9Z7=18?1jJQt`B3nx6cn<0E}usM83@j!pCkT`RV}V>gFeLPKnvG{)5X%?RSmE zHn@rE5YBPvJV{Lt6{99hLUwzyG_e5_V_L}2a|%WGaiHn3I?7abhj4|fj|yu3c8$_I zl;-TkwyE*ax7s2idK#9LuZ_oe z-u&D#wuaAK*z|e6d7_~*P6R01-wmMR5GuU@_~YvZ%w)b>0dVx9nQ6%ZmEcD60<jtY_Kj^1zDqJoC zJ2JT2&KdlQ@fo7$3M1(g6!WVZK+e=+Ji~qcX*F#T#mv1;Ro>x4d;1={D!@1e>i!`j z9?khEG%9QzZOFOWud&D$L?v$-VavPopLvq4ED)STh@ITrN0RCjS{?Ydkb~j5B%uv3 zEPFfcW%OLC5DxHF!dH6`n)`_}a0j}Gv!Ss^|jap5Y5 zE!}>RUp-dcXx-MWopID&Bx7AGh(s8zfh*2mdj27d3|gN4cW`v(_*Hm3;C2Gf6@lL$Db+5yA7`6{IL386317G&r7 zO~IuO5l;Wom&p`Bgb4Q-3Nvp9cP{}Pn768fp4CwMqX>CUaoXuC*v%!W_l6)tOx+L? z<*$s<_dp0w96rTk$BO{^c|rQ7aL_N-Z?U$#Lw;Eh z8Wwm-DE^vhj+u+({i8{zM&okw4KTiMSt#kH)NDV6U19LeS4N^Vu!YQ_U+${vqEZW_OYgpmipCLsut0y(5q~RAi{4Oxt39~s7RYwX9E}@Pi zZ+1+*bE@HX#Qq(;9BR|Clr~PAnz4*B!^rhk0aG6)HLyw-TP`J>gp-?ggtGaGcVaSPuwG)9U)(OG|Ph;z$%%4 z5tjdxr+}m}Uxm(EWH&#z2AS7hzA?pEiLlT>TJJX%K($oM#6#V@v{0qB@OTlPJC0U$ zADfw@(8Z$&7@}^YQ3wxY~+sp2}Tmb~QlJutw!^Yvt)E^T8-v*D~}5xat-KS1lXfIkxhywd!@b zO2i-DWwQ#%TP-LIjWnx~=mE%W)hH{~XfM?mL^UAZnh%;aIG!~h(`xYBY6w?qh+k?* ziE7E|@ssGj!FkrwreT-)Hag_+ILG zJ+b*w>qJiKxGd|XJnMvH>LtqR<>*0TWA$8ERbMKE$5^)U$d>;v#qAAt!k{T(XzDzwY_bON{p3y;kbFUt>P)5 zPQ#QrDKVd&7|lG;Aj)-iSbjccnz76Q|$PuIDs*}30_4HD%|#^yOG>#R%Y z%$w=Fdg;7I?Yh_OdX(vU9_xHL>3n_ZdME0>LG6b9+WoN71<%)&aU*o?*@;11UV_~- z6WG}@!!1T3RuR}!Zm8JQ*F#v&LrUCB@U@qSua{b@mlmy;ro8vdY7hNsFT-mO^LXz! zzCMof9)w_B#Jg@jzVhsZo`)OkQAcdDxju2Pe#!KH>GpnTR4)J8uRuKTlW#ytYe24O&SgI249Hm`$r#6u2zLrz*lE?z@!=|djv zLtd*xKCeT5#KQr6!$DfZAzs5_>BA9__Ti}2Vesp4Eb&M@-^g#RkwmYNvr9}mk{P>@$!mz;6fMIH*PHRhSIiE-NzRNJp$a1=29N;Btayhpzx9kn z$E>8vtnAw?`}~X``ka#XoQn6HTE?74$DG#MoX*>v9?84`|NMXEN#66&blsw3-fC^$ z=55}NWWj-d!AX0;#e2amW5J_i!E0^7=WW4{WHEq$F-Utc#CtI;V==D+wY<8&`o zz0DV&!Q^W%H)PC{k^?BZmr$z#nAt0B*7G&dE100w-VOjzcy-`yuGkuOm|?Y#WEI%G zI>|r(g&aVdy*dl2Se?jN(`?Uwqj(XOoLI?h%E0qD?l-K%?pvuA^v9N-1oRQoS}IuL+9XtxQavtMe%atJMf z&gY=)z0@fHY$i6~eM?ggjSge8nE}K{4#EU)tIMJB{@dgr2X)Bpu=>pLoMWRvGxm4v zX$Am4#;$_)F0Vc;g&jPN&8`F^&eZ0vQuHn#*3M6xSrt2MrAlm4pFQC>IIfyK?wVb> z^F6K%c#U^#c7<(|%o)XQI1&3DWxXxy^ZoDtRupv(G%|KP)(?CHMpa`Ed~N1b1P+zF zVMQry4kJ1b6HZ})6#G%6Gm4<29~tmJKybf1XA?4y)QLg=3+nTqo74ta_y0-FaJmDs z0mKMcAC=sgbNYfYiT>**wJ#Ej<>#y!OWsg48E*jbm)g%m2^5O)N?#Pih~#YG`e*Z{ zP2`lV;EE$kN@>#41U=7{jFF3`a>N4foxaZ&D-=q_h&Z>_m;B6Es?o`4ohwz!1zKVd z|6fp_CcB-{44J0?3+i)23Y{l+!}kF(=;f{OYYd>DK+HO?Y7ToNv0o$xt=w<+CNsZV zl4i6xnNAnUIqIMjvRnQu)f`$+7X~D+=-v9M!xn-w*)4AmuR4ms_FK*YpD=9>nl87- zGnf`;w78){(B6=Kg#k_pW?J^j*ODjea!cgFQFuP7|Tlaiw#nM}E;!q0858^P6q2;oU#a6Mi)ASD)8in?i?2UOLv&ofoo0fzrtX^2JdR|O=Y zFBckRjXbFw#uz)P9sK!nTDu^9VpY3lLiDwH;JuWgWigevvSE+IldUiojkGq0G#fsZ8rkF?A0Ku zVU*nvx}_KM&sx}A{u@pd~eljVK8V(IIBw_)h({jlk3%TEy-TbuZt&~)+s zayi5VdA(f_bU%DNsDiw|K3qT`0JLlXqGUIa@X`-RypBW1PW+=L8Z;jm1V_WwbD*pc z@G&S8fh}1W-D4_{WS1OX%uN^#TpdI$n}d?GK&lef8(a<&Li@-19VX1+D<_U5x-nNQ zF-m_ZZ+Q+T#F{IX{2ml4MjQ!>EB;PJdKJzmyN#KGKR_*y6(Qc9`>{?^^ec~Iq;|Oh zZYWYeQwU3x*5^E&3b#SlO2ud^;!n6UToP=(icvDR+e9bL68yDSV5i$WV)&FHhUK^z zU(sE1^d$*#>iAgxpeM8;*S0r$~&g*v=?&sjmSBOW2d)doA8XK{B_HnNxcm! z;=6i+OgKg)WNqA<^3JJGdb`wRou<=>oIOnjB7DmMXw!U0O#R_ccbkLVQ7npnEFb0Y zJNvo4=sPFfG&sIKhnm4mO4#CGSSe1y*Wg1*UFm*J+D>YkZj&zsSD9i?VPwP_ryKbUn5+s#89b< z*0$8aB2sUE#;tX6J~eZFE_R{=W}0QNn&mM3srLf zQrlSF=xuH3NUu3-^RcO5j=_$9Wo6M|zPWVo%>GZ>>gN5&a>J5c#Uh!tV~vGY6eB&7 z*d)$dvFg%IXliEs6jtUl=W{4m^?y<`*Dpf*7P+MXbP|C5?w)2w}5 z!5>bmV|%|P<`Fn(@%5R|%64t<65dhw4UzwrjrUhjj5GD0ZzYpo!rA$Ny`LR0E&{`+ORsoaUi%JaOPiha(fHPcTENu9Ua zEK$fLM}&AUQ@_OT6X4G*=~i5aT+Z!%GrX;gPnsP-*)Vk!&{%DidvwjGu_mRWOR6r% zANJfKNQ^-rKCN{P9)Z1`pWoJnXmPEi@}cd5#8&M_vo{VvU5O}v89?;98J)n`qPe<( z->RIyk3fs@jGNg!R#gW+%1My{(}-`v~| z4Fv41UHSI=|kGyIBK-Yv0V3WxLMWwP^?d>rCdgc@_ynbGY^4;9RLy_2|5u%zF)T&)QX| zV*+bSxN#%?ma-MCH_Pev*D$8z)bz&-#{%~@JqF#j`Kz7HOXf<)fm@^D`~AjE=E^(6 z)AA9<>-Nj~%4BHG#m2b-JoL@0x9dGBX>z;CGiy73(gm`Tp!>S(sQL0u{JkG)A^e=B z`?Sv~hyaRthx@wzz&s@Ib_IDk)LnUk7`rEt6OZ@lrR({1O?jXqpdcnAYYZWyJ=&(Y z_+cfRV;$OdcKacJL{5+OJ45hCJhZ@*v>m;;PN0xLe8hr&kC{lN^94^8Td^t zkYiE6xXCi*yFCZCBZjLB-a{YbWNBkfIE_=bS(3D^9LasLHo2XFcLnq`CHTKXyTL`@igf_E@`r#IJh8aEe z&_7i&yeHc)y*oTjGCUs%<-;y&&s6vWLd1-nZP{>mSG8WoaQMSL>MRItNC>@2GNNwL zzq8oyF43aaCGfwkgKjx?Zu_Qu!>;(uzWShOKFQ!&wNPpNXiu}~e`Z0eNN~3J(Gs-a z9jJs*EqYxIEPm-G5f&}J7$h_mt%46LuE%zx8p=T(O~CB6YZg4?7IWhkO;8;@=N5D$ z<^?+v$mJRheQ9xScDqoEJ#`Br5b~0vjrrFMzE=fHxal_7yN6^WLN$wE=wjRsEvs5@ zNKdcJFFXqnj`$ey#T|`)$v@dGJ{f{!(P@XqDU}d=8PD#H)+L!h@`%c&p3shj9OLFk z-=f#P=r1>dJnI+UHTApm@;CA$GEIpd1FZ>6QIsA*q5*dzFb5EOAb494i^EB?Bk8s4 z7EKf$ZBY^pv_r(#gA;F#(FcSfhR5tB1MtZK`g(BIPi}TnUWWJGK=!_K2 z@;xTLC9denE&ijU8<#cqC^#fMXC5ipq9l3QCB_Xuw(`j(Io#z|H3vn*J&A_+6E{a> za(wLN@0i7S<)?U3wTu~PCe)li3qUJR{7rL|FZ~qpQz}8mLN7)Vo!;G}O)|Wm>yIiF z@KX{$9Udv`VJqX2|4UW>>`Ru-bD^Dvr7I{V3obd^J&X?t>_Y&1^%!%2A9FUGiy0m* zM4k*sh~QWo`XXt#4oL8i z@bdKDTpeWIpBsg6gGlr>bdp|XVoL)2c9z67b**bTT?v^uLN;PO+^#m$q&MN9AbXB8 zx|E*Ew5K==7G*w>wZzfnLPdk1db-MyM3?K4L3|o;-gLy-{8by2PoKUilp4no@1+|M z>Wz!grEo?;7xV&1A}u<4b@L)El$?Lr|Cye0}~k>L?LsN93^#)x(0`8^jgN^PYGy!#aVf5WbtCqK2_0ciZGhhOMQO=?FdYPZXZtk|qZL zxAFjjlv4fl%J~f=uIN*CPL!8o70K3e{@P?{O(m3_d<#9DDr{h~dMc`4V!)9koY-KM z*dSJ$v{!((2}9!v#m?(d`rakmzJxJd%GgubbWmY{$WrX!~p@J;q+oH zEYx7~fp;_qWElnh$PNqPq0g6wN8gDDF|@RzTHdfjQj+1VEj=7aaQ;zftY|)qT{>kF zTv34fq0f_602Q5by!_a+kkuIX?ozBUrn@Lq&Fh(`XZ&yd2$$}-)z#Q%6E9-A;%^=1 zs~zSJ7h&Y8YfmaM8r|s;A9}J{>Wf~yV9|Z}m_$wi)|GeN$V3joEjTM0^OFbOXSc#S zEpE_euZ9;uDm4lcufS5Q43mrUU*&|-G}korz-Z2rD+UOiH|`{6CnP1a)AZzLU7UvF zZl^r98(@tXh*EDxm}M;Bpd46mFb_2r0A@o|w&HqQ36vZFa3X*TfuJC3H1x6TQ9RUK z+z=d&@+vo+!lxR}(;j>@;EsMSCJxY%?)^~+)~AP1h_**z!5lbBcCOUS^McdR>e~(Z z4Pgm)J`LG71f+2kIQyo#(iA#h=(l>e%RU-yNDNN71oI=g=Kk0fmihkVk7~BkVjJ2zqGgQCo%qj6)i$QBN6b05d@hrtwgF8c}H8 z#B%WTB97X?N${-6N$tMLF7Y0Ap7sE2XqZiP+S%w&%^3+OqQB@FCM0347#KpN`XN%Y z?mH9mA>h};*^X`Mb?Mqg`w$|u<&V6##+btvrAILe-%sfLvOI2Z;GS~vnp1(mc+!9` z$gUMgNu8efa@+B<5A`#ZIcA4B&~?B`5+%!>W}H<`f@Hf z@6C}<%^n+0K2(09;43?3REoY<%i=xUWe-)L0h3px{+>hnC@7|7a?Yr_fT@LxCSRv- z@@C|em{E5EC+=MeFaQOmxK<0c3i;9F`N!2a@NA}sEr6XkyN((>RPl>CeX!ekBUX9! z>C{T~XD2%qWvdp%-8P5Gat%fm^$Z$kX}$ZBUK^yojTXrL@_mDLrjzfsvc5 zw9Qe56jeM6g(Sc9q|^c$uGCo0)Qpze7P}hyo7i(riVB{E9c~C)%Syg?J_leews*}L z54Td8$?zx@Kl6Lc>PvbVU|td&0SS=9(UONW>-d(0U|$Icu_7`dqj#Wd8g5e(phcT+ zpzV#^b@1O@cGDqHtwxs#Z%+CV*o0E%BR5Kx!|d}m}YrfeR>qKTRUR7f~y@t56fy9%;8E`Rh?884diPKcJxYKKpS@2%7S{FjZjTR%zhi91LDYO%+ajfA*QW%n%k< z0<4jw&d0*j{^)CP_1-O5)1fg?lAt#2A7sBdFSNN5cF|_=bQc z5|ViN!@!D!E-@bRfaS}r#p3meQ~j&65O?A=jQGyeQ$q7f*!k)GiumQy{jjeP=U@BL zQj$^P<6r8SS8^P`o=OH&AafI`3`(+9RCiF-= z>5tWi&hVti-@kWyAM_hw(!7u9?p1nx7tmAx&~&)3wtM#U#NY`E5v2cJ7_ctV(wz3m z?6SB2#pXduu6O?}(am|s^tT>r55%t$AJVxwJAF1aK6Wwn&GJwgr#QT9wfyaij}zqU zH_5{?VUN#_C$68rQ2#ljU(Tr#es4%-Ql&hny+RpmUI&Fi^QEgRTo<)d56YNuw#Gl8 ze~)K=>Wk9$HmJ?#BdHi}9{4mLd(V14t~zyXKCVpv^|RdlQ0KeT<_1XhZ1K;1FTdXr zukK5{4UD?A(^I+;X8JXr%%nQGxa)3*cV7JIpHwamZE-ktOZWU9GFtTHocqp6A&exa#9`sa2 zsLvy;2Zn2e3rJh2M^SKHi5NdJ7jozX+y942eN3(n?&L429JPm;8BL4L=%lK1f@|J(T(&707O0gx8C7f-t2TLzA zg(VF~VUvSh(EHieo3GCWlymCe)*}ZpS$?y$AYX)1Qop;?b$@3huEzx>6HA*fAIvDo zr&Uvi$E2%BMSwZmJ?F7HkM@~4%X}6am~@VP3r{>T)FkzyTw}W*-s>5xJ9L-doPAg< z(f8!D{yA;jwwAjU^YvlIAfq`g#(T_=G3E?skI^fd;MP&T zM7OvRP6sUy4sLU+>v~MF1CoXkU3;yDQm??WM%U#|B3OwFWuoF4}@Nw|fAZ%rG7nX(Pac#>T@+t$t6*^s@o-5-5}aB zOlrT|HT@RkhFgYi6MI6azRnHz92<`w_dKUl5qQdeY>!9L{m~nqB_U5uwkHAGH^@>S zppA!* z_4zt_^Zv`T{TKINk;qb?7xk<>na1ElaJdcGvoB!m>cP(iU7-nZdHBazm4`Em2Nzqz zH=(M5bGj=s--e}xRmoBx&rQKayLi>$H9I!S?`!wRR6{mH4*p4fplYGp@xuL~yXm@W zVej((NqtJ=)xzIbSNDg1Y#vj4^ttPRj3d5+mIjJXc~@UPeyw;b@?^#4RpjYb$gRge z5At3;KL6Tv>&eC0%GSjLJ(kg(K}7_}q&@NX)7&J4Il z)vZn!mq?2EmH<^lhz!!F5io*Uyl`u>--FBB3=wS+ler}8VLqnjnh|lejAW-17xoe*9l@RQ z%bHrQoMo13?49Hj)d*Ln-Gt#Axz|&I1Np9OhK^kyMJ1v3T$zDux{RH!Or@5td@S&+ z;Ki7fyBGWd2O>IRI*ch6?E-@J`T80LnVHciZdcXy$7Lnwv#YJ(Tx5B=>i+YrK$;4{ zABSVg{SR^*D%{2I-Ix^0Wz2a67SdaH9+pVT%<7A%6w*wb&=*=L7{}~izrmsF1X(Ct zAu$8Ebi)j9e3&n4+NhEk;V^kH`Ji}TONhBX(Kz^N>*dWpH^Cx~nJ|O4r)L)xs^1e$ zT@@atef0H2EY-|7JX^p~Y9A`v^$_f%zvHO_rRv(2hO zuy}q=b~-XBm41TOQOGu!j-Kb|7Ny4vd>fz1m0`~N%Ux?cGN~S&WR5urg}~JEXLUz+ z`69YuhU%disBsF+2|b<)j3?_A0QK5`Y7M?ctt1~=l#8a;8m@(F6{amcUl-dUiMS>$#&4(Gq)t8w1*K81`jq0^;zsGOvG`#YZnCrbhbu z*W27y-_Znc0(2EsGH6Qfg1A59>v{1Em%`DS0Bh+{-ETgLZZJIU87k&(a(IR)Vu)7s zP{))Koz^XL#^+Cuc91$w4DMd$8l?wtjWeWwXa#a>2T4V&(bH{Z?o!0Tcpc}8XtL8X zS`G!TIa5kg;Wf&u>r<=!bQA10Z?lK9X;%w{Po^ceP}B*DNZjS1PYbox09deVc)gFJ zqi#S`Y_Oo^Bi;Z~F+;VN_m5a)EaGNNw)uo?fw#qY0GFwe6d)p4ZJY#*;i1NZXvX6J z_HQgHUBNBahU=LnTS3snfj%L61Oqn@I>f%B{1yu@m!!t7yc4FLr=lhHU0>h$UB>3C zhm?I;TWKwf-M z{R#`eYjB<4u8OAzS9+Jbz$a+$_V`vWXFVffR8D2kzvd=QuJ1c_PP z@=IaR;%ugceZze#^Ak?7p(y8R&k?S7?0-7p0;?PElV??nCH^*dC?WiU@> z%uio(@umQ-Q9cCR(NlyXn?)Zs!q{WSTrs9h05v2KC#F;(1EDpGLJ_465!Zl#=Q1xq z-fxuWhq`XMQhZ-mI39#CxyDovB|HKEf#Y!@s1|da5>uhLD;E7n`T18vNDMX96$|40 z-MvjM9$zT*t_^?P>hggdUro|2mxs3oUHeGUA0c6AHH8=8OD}qUzkt!3A+8T4T*{a6 z%NHGdcAe#jGL?Gp5x<-om-wV8C>Q}{uK~r}LyIDsR@yMj%AGHdRkv>P*}TBedZA%h znL<|zrx)_@BN?XT7fqrHFI>fC0<|{>5QChm*l_&z8&&JOLnHU%O${6Q9&|jw#)lvp z{ajzEa|!KhNObXCmC=+y`syfs66rVSai)?p6^TcQKs`@HUJQyY4vt!YMqu>1id>^3 zkE9ommFPh_HjfZ(y#lGvs%)~y)~*jRtg9xuUhBCjCaXLOC96opcsDJT$^8El0@nmN)qCrbm>cK>d!PKk8;u?GL+rt&^J9UkP1`YPS-2zi10!E@f(^7XU z+rZP46S2s@8nxlejj2|Q@MQb+k}nqx`LG8wWgJ~GEGIsL zF@Do9^CqHdHqg-8%6J)ULTa0?j4)h}Fn%jwJo?G76;o-PG_y8bZs9`t20r_- zxF~C(dVkpPy|36i@v67XQzI^wozoKwdqy(K=z~i0RUs;O>x-H7%q=mF7cQjg3S--rD!ds zSpZUkma>-@^RHT3|LK*3>Uz9bQu2F}4mHkB`8{yNoZnEJ-+iUW%Xx zu*h5Zdx1u?QnjzRO?sZ>%vTf>D=ak)LDD$IVzMR|08Qf~;49 z-B&__Rze+YZvR*g_j_8!2XSGKi+H!h83Et7@svHV(gZ0`TLHiMA4nJ$XJ z|8O%R6}W*I7}J0E(dhXNiuL}j&Da@O8SuJUT*eXL2xj8*y|GLo^D33F%)PNJG5NB< z+GD}V+-vUZZr8Gerc0C`?aS5r;O5Hp{;#!}ZJW>LWJmo~afk zeA9{gw>ArD+UyPe`e9}&q?F24|pP|)s%3tEEZlwb0`d%>wNVY z>UM%anipS!a8kZYqDW`Wvt;pp5!V#CCNKUJ#o2t znTBekdv2y`cXZs%)f5EXt(AiXvrX>myXW0ixTC{SES{q;Pyoa3BfNC@&_xs_1^b1d zj$c*g59++LOHfqV!X@{ghItlyeVC}iMb?pHSP?rthffofm4z$(h0cX5W6pmamgN}u zc$H)@DqpKE5G9AMN|MgKakW0-qV<)IB!jxjqGz1<8e8Vieah=(IP2=`kEt4(8w)u< zHIFhrBGWRHKJ`swtRH=wo{Ca8b}YGsH+BY4xgkIt5h7o@_j2!j={c;b|5t$3!l;rysWB7GO>7e2JtjgJ^HfKw#jIS=f zM&2+kYGLDVcox}|>mye}`T_?TZW(thf;1bS4_eqY>Rv8WTGF3(%kw*3^Qvw6hjuK1m8hAu?1_hZdTel3Gk9~piUuTc9d5#z2lDeXk(W>NNHuluB{2Q{ zxtn9E*1a7J=BE-fjFRjHJfi{kzNg4}s{ElL%Rl=As8|yFspW;*3-k6@Z^J*;pUpn{ z*fAve`)en)fXbJCwp-+(nN;b;H~h!Pk4|Rz@AsVyGhMy-GVOHh&)J(N&8nxfkM2MI zH6nID@|+N3`uBX>bL-{#V(BH)?;i_aAOHB(bxV!(yUmGYbk+l6Meqbnp+Q3ogBUv1Wko!BNZ=8eW*L$RK0pQ501lnox(3i(~Oa<|W(jfrN)R z*N@_4Hn{gZ$N{W%v-rGnGB*=j1HH+^AKa|>j4^9GNwA-ft%n{VY0FDPfbX(cWj_O8 z7_>$1nkNk=IIxzFYhN=7NJcWdvQMmz$TnS1X<*-Fee-j~9&euJe!|E3xkg7~e=gNK zWta27YgGAd0QQNT+toGOan&pH>4AZJeDK;aMH88fOlAQAE^mEfnbypxVON2h*9=VJ z7&FRM-U+Es=$cwEVjIN;#jgI+x1B%ENeUDc(oZz79Bs{O>vI!*(qmvpwUF1fQ7L+_ z!0^ssW>Pad49JWHKqZd~SEs8Kx+Z4)!@n01X{wdR^k*LwelI?>$H~v}wf9>$pt7cT z_hfWUCw^c9vZp-vQ3<5i;X9UbIw?C=xEgI)A#8z^+<$a7}&MmW9gDMd}u9=h+TGd$ms4__XU>TNV)o?eb#`;~I zNfFiU=A@ijONn~3Jkg~F$Dqc$v>(mK3YVMcv~W85Nag<>!$J-Tw&P;2dEe~gWr!SK zeWY;uToWUHi{CRoy7Tk@UYq5L0nO0ykpHiNgb zj8V@D(3h1oY8M9nTbrFq(~aZ(LJkbK&ezZS*Oxvjy)u0J_k5*TM_NOH;=-7R9SD1D zElGW~T>eb?=fLaArl4Pc4}ZxG9XhHcO3dj*vBa zCu;X=(pHB`-l1zaxH-vM!nj97t(5=a6!7fR0P%!8JbWkL78v@~S2gV*P%SN$yA!)$*FV!7Aggq z_8%!oJ9GF+0|35F3njM2Y`g}E7&bYVOk zG>ZBB%zqQjBLq3b2Yo1C;oetf-lB10uZAE&rO1~nV;?e`%4 zQi$5%9;!t0hYG|!M12fDEe-h6LHwb2?{sC0;>?q*S5@gNL+kcb&1G{l&d9b$L}=lB^E%oC-&4~~R_8NKdt z(8E@AqE~btDZs#fc`;d7Rs@k6gN?zpK)8Pfm9_+aV1~I51{Pz%Y-Z3_Gl<0@n2jE4 zzJk^_i(&K%La;;G02tkF1eZuuG0HCp5bDkjK?9=R+>UC3MtvWJgUC9xP~h=Cc)b(T ziUf<$!$NQ_uMjXcB3NDTk((Z+Iw@bn66fa61L()n@a$3((Wr84Vj7Ajw+1>90#Cuw z=7z%iiL`O_k>yBO9wI5q66@pHv&jSX+s5tPjd?FYG0D};5E5mTd5TNX;7Zw3KK8152 zp&>08=|(scu?Tv&c#X@KWptP)Hg_zZw=-~< z71EEo$M-Bcl;p{(JPH9}vz!isj)gL?SYSCmydMd*V0XEz7tL@dN<=^U`|T{M_VAy< z&`bG1tM>@6>)s$dWSu}w^Bvxw@NmLQ8j?pd*B!ZB0|f!-;#$a8DqsyuoBabm6AItJ zK8ZsJ7d zZ(|SMry*vKN^Rmo(6RKPP)l5K*hwBTfZX+mPHZ7S!7+y$5tkE?VGI~}YG);(T7Y@5oH)sWu<+YwHp z(M@I2ZD`D=3C2eB7pBa9NFJYrm73)*u=xN+3XIpAzMMDpxC3+nuwI^h zG#^#?z^5*s{;5%Dr6V*W7+a@X0|icDTcxW@QN}Y1w7P+>F!@D|G|PwlyxIWzt_bh}^#&5QGX~2u zD`Uz_NkJ#Fb>*kvQ`pA3-x#D)S0|}tCo5qph_L43H$6`uDG1O*EY0F*3htNELj&kx zwZ9)_5L(EttX6a|S9~bu2o932E=RrSm?{<1i3{hUR`sUcE+|sdAt(5x$2~eo@E;~NkNDw!pbRW?;|ejK3VQcN+y&oR71%v zp>@RLa74vU$TKbFp=7hN>8{7PT-&3Lp3+DE)@A|^!5H#NQJTt%NQUI85GX1A&Q=5p z?u$)`!^7YWw4*#DEM7F;Wl&@LsPIQwY^Z!+6uU2C#G3o52p)pLvRWfY6P2iVMZkAb zV%czGETOFCb?JOUe0P;zF^cfbGg|I0N&CFGw?$dDn_fQ8_6IMo-q*5^K<)=^c2=0`zR6g zLk=E59w75gpckE1Vj)dsv`ke5Q1#_}~U2DdrR5)T$~Dzc}8X2vVA#soWUoMGg4 zo=|VqH@*mm4rv%q^gaW`*n<;n4|W~tDk zJlJXbV$tmKlCCoVL<|c1z?<0ZN*4(Kbfd@_`(kinGW%lK&Ku>7q)9=H?7zWKSuH92 zd=0u2^%9STy*(8^gsJdypk#Bp+1KP)#w8niWV_{8Zc*de+y{>WC*^F|Jd)x%K?0yKd z?aR2BhR}rpM{y;o9xt@%UCvrZ`PbgioJ57AS*c4B*l!l8-KKQ(obuqt+NZ9*0Z-Pt z&*_d%mLpm{oL8$zln9Jj+!r!E1a9`MI3Yfdz8oc; z?LU1hq#rg20`(}8rW{c_>|Xbp3!6*-bTQR9-kiKFRQ&kvE&cx656W8@GnyvC%%9C& zwJT|jm$A%;yy;1<;oRHS#UqWzv!Gu!c_=AfIoFIZTeKZJ3Gpx`D@7ohJ z!Gymg8tT=-Sg}{rOd>*2Z)SE@9OBN|4>IjdenvaS3u=`?w9H0rOZ;}T+%+Y2HMK8x zF^-2|B>;%zyaf15nD~s4C;_gF2i&(GM<8~nH>qtSQ>n&s-${_Iw5SH#5r2m$-Ya>< zO@y2#l!ZU5TZ0R=aZCyk>`p)L-S4CpSJ(YzyCQaz(by!5b~kNKsd>rvgU|Y<{Ybff z$2>DAnVxG$9uls6t_()lI*{k20cZGNutJ= z+)_eeDcR@-Jm~h#xq4pk`d3l&uM*R9VzhDj{qtvA=Xs?-C>r?S;d$BCuf2Z6-s9hO zPQRaT{ca`w?!S70zjZNa`n$*JeC*YE^Q()dt@AO`MP>8F%vat6Z8?Jn(rH<`U`P7HRwSA3+g-^QB+suSofV zcL5pX6Kx=fNklq<-dQ~se#ym*2U#`{O>>Qr8CK@39nZq=AE=bEi%6zmL5hb-m+2&e zSR&-~W%$)$a(+)2ZJ7@6Me_Rd(;|%JdP$-;Otk74D<*JIc?H$lqxbr8h|CrSoGuz* zQXCO=&SHdaeLguonZ#w)A{mRPa0mWNv3kp^{a0BVHh`mi~GQ&TIBtf{&TsJV^~ip6>Od31v_nB)3p`uxaYZd z-uW+XX1*QUdG}uPh=QHpzZljU=!b%Rz?fi{{lnMVXPtLy1qB>Jwqg|>!wxFD93Ooh zQFMwtdlzEk^ZP&Cj8jL=5Hgm{;~zKUFF~hwWzCH#L26XVHC551i{>U39OIgyE7aqb zmDtFi7Hs-o+)NzD1i355!!&D~_>Y^}zj2@h#@)zLr{1JGc$)q%h6S&>k*O!@`2Q2b zy6N{nxtXoFoBsbVZe{=~+=m*vq^lAz!uDU>OuWjm&(t+t^rTdm%EM{JmA;3wx6V`o z3A$`A1LsW@Rf867Y$EIZd#?quPIy*tu0B|00EBElJctb0dIbF&vK=G*ICM8z_iyOC zEYHVb2Su;{9Q&s7?qAXW;byM1a4Wb{{$M9_GprM&$1GrH zn6{DzV^edCuoiEInym(FCm~kK-U(!>q{%tx5i33HOc!K}0BSw^7sK-L@7CmFolB5e zMAGNf4D)i%C7Sv=U&vqzn=jq5$WgeO#xroci7%XjY>mM zsdUpW;L25Pfa`?oWbM(K(fU~d)Au?riJ zSf0zIs&Klx^-UKDdk}rn9nYmhocKLAL~G|gCPaBeLm%k+3)kk^RRdb{sV#F8x0>jR1X>vr!f%>%J*{N)?rb*5e$ zxQgPQF{(PVo~oU+GBFrbIAE;cmSk>=oq9awkyi>#K(pZI?{eEY5da-}w=C!f2Hg65 zG3z}2iY)_zBJ%}H9|YU{I%q@cO?Qr`?`ir3ES`A-kKS4~U}E*!7kaKi7YM^M)T_GR zm^3t6@*k<|F4DDpuRpqE5+y4Tx#wxigFfClyXAJhuVmuY`~)Yy$6tv|bhNbwr*9qKltP0TszBy0H8wcIHu1p^9sb;;cO&{3my=^@1W!h3o_ee|;zJw9x$TZPXpZ z#zVY-YpWq*KjjaUzcN^ESfeY>+rc!12>@_IlPPs&?{Iz4B=mr@oVP#oc&!=*BUW0i|W-B;pp>)#vX6?v73DVF8Vip9BwU0sg&aYgdY% z?$v03Iq4@FljN>Qs6EG1ho##cFwgOO9cKLE(Ep_-lj*AE`Bat3SSDPfQ;h{}^4S}x z*`mqR9auKCl-4EXAA3nzQZSY@PKOMJw9U42TO`)HDLsl1E94ohE_ihI$)Owj{I;ND zKnTUfj(^Ds{?r2QNOwySd5~u-G4LbJtZy*uO05U))QZ}9N00K8ht=+XA@x65?*~4* zb1J+jta?diupp+I-$+BiYEZ~+P?+p>3DmfT8NAj$C^}tod2b*>q))73Q0iommszu< z>}uQ;m2Nj!6{#d|G(?iu(v&AVUs5!c+%%OVG!?Ull!rBMP7mEI9#RDl-(uEMO;FwCc;V8O$g$qe`hT1ZbcBJ^|ICbF2(IdT)Z z;u8fa`bB#w#eKt##EG-8i9)N1A|w4Qd;Po<{qpRI?23s>jDC^UMB~p`SJ-Hrl~x!m zHq&jQU|7FQfU?kjqDo7@CBmSDd7`ba!W|b^*FLE|jpcKWwO60&so-<7oqCOp?-Pfx zR7~}!+a{u4W~XB5Z; z@kogC&WE_;AkG4#HtdZ8dwKF}r6!d$1w2hnamJ_|aK{R`mzgC-pAST$;|#V$ zAAO~Qh$~5N<3lg8J$<$+y)%%`r0b#5bA4|l^Q#3g>m&n!FxE`I63Sa=MgBHj+>z5*>qwVqJOKcW-O+}-TXQw4!@|w3kE;L%Q z;VwTSM{i$xlAy0kB7T0}oXh$;TSdhss?YD9RI2~DVy@h<=6_hC^04V1q6 z4fHL)S zEZM=l!y!4f+8-e?EuQ?bp-W-RUUp_SH`zZQ)bq%naO+Y@cB)xPm^3xN=_k1{Q$^Yz zixxJt$4h*!o6ncc9~yV8T$TE5^C&|7z0B-_45vgK;cl|szJZ zR`>T#jr5D-$pwX%KV~dReW!B|pG5j^b+M{_M`uYzo-S*;6M|Os>t(;xtw{XtLDHqn-Le8Vo1=EseiEqUpf}6lW~z8OHR{uy*3mmGNd8 z1yl_432sTrcHojr3Wg6{G%P)isJF%jPJxUv6e>jgCQQv_?A9*q$J&;EwZtPnUF{%E z@&MjaN*k57=HSn*G3M^%Ad(v`eH~JXQWP6t-fq9&a>ynjG#4WxCuumGFjvmQs zjRvyQb34S-uFtQH z3cl8FHHqIWtg!r8tq|HYt?CZo5&v?HlUVjTrT)DqQz`NC$w`uLx#hK9Lj6rv*NbNw2p^4B@*62e(ero*JfX(*XAj1ulfy&c6k^cm34g5 zLP-&QotvwopHrh5L5Ncj2VU1O`p#%(e$V(t_p*}XVCuckeDvYpR?JCoJbQg3^yxTb zw2~PX1aMc9Agkz~0LM^E9>chE6Or7dv^(sQP- zYHYh7<|N6}e1qSyrQohfeGX`Mc46VdjQrVqE=!4YnWMsus`P(O?kIyYr)YF*Esr`- zwzyfx0l5cR8hN!0-1*B9-M0N;A+0w?KWN#eb}6CBjdRpbetaj*5V5riD(CwGHoPPE zJ$$X~H(p;>{8eZra4c+wr17(L9UE$l7GIx+`1ReMmag(hjVV4fITz&qWA#l$%ZK(3 z@-C}rqlQf1R2(Y5mup)@v~GxD+Z@Na^usSu={7ALf7I^Mb_=*ehk*`A2w$3zwvd{9 z{(9Qe+nB})l$8LWQ2+BO3?<9UPUCUFnWo6Y+y2~zv2?3dfTLhp=?N6g58a|(6J;G8lkr~A4~-C@p?U&9)NE@4Te zizw@PM=Sg2l}7Ubg=uSmk`9ndFHL1pLxmVHT5H93e(d)CMfPkC)eTht1K!0|DI!6W z;RHwP`o4@=Rz znb0gaXubuXQQ-c@f^L&Ax1u~d|3a+kQ1DSbxhuT;ZP7|PZH)+jzTyBlmxpXinXG=B z-)-0=bR4EWU(Cx;K~6s5R#D-% zS}a>@r514Lptf>K%?YSbgg!b;s_)T4TF6*T|2|3Ng#NHFjg8Xwc3^Rk^8C$WrH*ym z&{HGv9PheI+*41w5DAhSsWF>UHiBK5Wzq^~n(5lrWf3JcTaZGzA}#oY_mFkVB1-g`&O#2EY% z2dxc;mrK*kkNFDNXx_9kZDZp^;G}344WAE7Nhlb=Lfx&8!t)4*{nDP{ghwLS_#3eX zL(ETpTRe>1cZtKB1m@s3Kisx) z@zjU@A~<6N!RrnAhCVbEhWV5)Q14jz3?l`cJ>ixpc!HwiCV);$+g3{?Hfs#BX6Cz% zjtxGJu|mT3u(UdvG@D4+#1Y*#y&u8`;!B{eiu2PMjHzPvRbQnAVQF2)Vp&dow-Geq z1o9`{)M@Yuz;XY?YH!~8YH*z4b?u5!BT?(*|3TMVcr_jP|Ndicz=$zaLQq5mBn(1H zg-Lfef+I(F=SDXJ>6~msZ`F`%X=l;&Q_fOc)+54QmpRdQ`@k0%t zJI~wQIMO);m;``+>~v&7=`6pHBaswWurpI{ms1192Ek?FxEG;k^-ks*3k0rY@G+KTS_y2qZ8yoN$)e=?uum>l+>ZVVLcR`S z*>WtAjEc*T?5e;_Nk#P}ct~WC{!|X+VR@FYLYD&e7%_ESqkwu~qi@8Y5#a~e<|D{W zAxB$*(MZVIC@~#hE(5=W zIET8GC|l1lnch%A-Hl16u`=&9R2{^9I?ofI&MK}s2kT2~jm&*fj(m1~a9>6i-AZ#*#J206#DmUkBeAH{~+$0@Q)DrU(MMCaF#}I+&o+q(gM%B*fpH zo15o5b-ax=`fWso`Z|pu_19o?Ffn4;@Zk$}`3aI#azUo^7~$N5*)(K2)`^um3OQZU z^-PnkSdHAwN!w(QK|PSh26Wqskute+*riU$v^l?t&nSg*Br`FBAp3KWcT|C4Kg#VXkcc|C7OBP)%&ZH|#ZDuhB^NlU&aS^3z?RYFSu zY`1TZ@#(1Q@6=nTV)RK-HODzWF6QUhM1nP1FZnjBJ^)dbuP2JBA9R5XpTeUeo3y?O$*$l^-XOpwd%Sgm;ROIKId z?VhJbOcX=tBx_T@j}BnHVk(L{wR@D(JcLe5^np8KF?C&BO?ix}M|ER{kXaGyH+@p~ zDW#Qa4JurTol+k1vr{lHQ1vI#JoBvaHZW{$hgeJMsH|3ss@@&Si7l6b>OAWB} zm>*NBd)fr5F_|6a;_;-ZMlxqg+*hX=jzuI$JG3>^AUE<8+6%nGP&{D?0`KnTxaI*B zt^Qn9%Wfr~d8(@rcB*y4liy+xHU5W8T#Gr1k7~@We<@Ma)&*fLYb-iso%CQ6^2Iq~ zF}aq{KB=_D7O2$KePm!H|5X*c;5XJ2z5iYG^tqzXE>B&yo1{#)V9mF>Q;$Zw7`#u3 zX@hU%#hOQTn~l9}1xy%k?Y|JH+R4*?%(YJwm#w0hu94iOLT)IVK~OZ(RbSU7p3LzL z5zDxU@hMJr=HkX>e>%UccdC2i<;uI)60+7Bp9c5;#6fKA=dEMl=_Mh^)HDDR9Ws1o zBH9>q)}~z2%`@3{9X_D@p8L~Y+gzssjch)+ME227@y6Z8OtD^;(R}4eI{Z&Gc-?xu z?r>WxflOTkpn-r+y<}xb7hgyV{GG(e1KEa4PT98{ccR{I-TtWe0!^k6MoZ4mYVsuy zhsTWCP1v0V`e_1<-dni~(ByGdXAe}KD%c9BM;LRf$E#JUN|~K{&{4Jn?LcDR8w>ID z&#ih>`Nad7s%mJ5oF6f!N{f4?=;X!ZTgp{6rgnhqt4E7fr@Zh|ABk(FHob~__iFz~ z%ij4G#lH@&UPac89}ScLh;t zH|#&e9lBf-n~)~MNcn2yVl#e6zJPf1+g9a@9LZO&WOKQP6S#+0O8N!VslK z^Ph;n_YoS{5|l3IK3G@mD6H{kvc+7`Rv;!Yd?epnVZXA~1qhlL6(l6ZD_NDKc~akd zT2+B3niEfxCpw{MteRS4^Ca-C-sD1_>cUo@YM)9;Lgbr8EA}RNfk!WEN^@paCMC9d z#L6qBnQ?qv{*KCz=VZL%M0$xiUhPTzYJLA!x9#WgD*^v`^NF@7M&Un?2Q>_*-o}mW zzJ0Av(&LmOO=>+$_Vxon)quoFMZk5B@&9o5$nz;{F7Te#n3YGJvj-2k5BfErYcC5b6(wjNWr6G z1!0@{lD}(@h*zk$)fvUtmb_Y6e&qZ8t&-{b#p*1v?IPYwJC4IsYmQqTdQh*P(P2rt zVfQ0nD59UUl@nm{NTZ0MmmKd+aFDCPA9Arr?D;Q*cz(J3p@sj2Zv zbQ#Mf?!&T>8k1zyC=i3UwKnnN`39TMljR5EX?hYRZ~K})Ohl(~zAEV((Ua3^7Md6n z3;(c|p52%FdW|!xW&5vU*uCGcq9(ZY)^=a=zomU*@4vOVu9mepf3HSMM4!G_Jbhbn3WVR||8`1Ef5t0(CYE`|n+cHpb}Hw4CiC7u2d8YpKT)_AIUG$mO^0_|lTvAxyx%LyV19I<%xXO-18{b69G&zL@&$uxd%Y7AVxAlTo+$2?5W0)XjH z<40IimRZwmuYvTZT)1m|`qS(YR_vP_BE)r3`E@4lIv#gZ_Vl(0cZ2o4E>*lOi@q-X zc9WcWU7GnYKl--N_U60oZK3aVQRbh-k?Y3Ke}0tTR+Ig$TfY4feLMZ_Hf7|tKJ&I1 z_vSRSn4p^iGBg0e(i5BEhzDRK+roF5_J19t{{}`$2Iz?gup|>$lC1WB=f1c*6(4|H zPNTxS%154^Md?u|x(dedslg6gg$Ct|x47A7wTF|lS_~D)(SHmD6Vt@SpCrCCDRKC5 zAND^1JnJP!L^TQp{NVi$G_T5xPWu>1Cr%WH98VWA!q>YwEmX>nxet}mv)Ikt3t_q{OdL^oc1>GmDRcY zQmZ#EZ!T{0C{@IgXvX}p+tJ34^h=wtpO?e=vc<%?3ZIbnTl0ykBL^Selj5lwR#5AD%XzPE>TITaZ9lik-Q51g;h=Cl0>+B=&8jcMaIlFC{i|dKv?a5K7&(0+ z_|10?QBvOZ3Q;oQbxaWBKtreqOi_$eoI=yMvKvZ){ne5>>sTp4Yx|v3@(Fk-N-X(K z76KrW|5^FpqY1JnY38vCaRFR1tob=7d9N*qs$~90HbQ|07?Hl|WvrItCYUtLlj3qe zk>g#yqZ#OpJs1@P55IE{2!JZ?Vcs7{e9VIz(Ws$B$SC4)O5&t?PD+xrfpN;xPt)J3 z$h@h2J0Zi{9j7WU2tHR;{&4p?Hkm%OP@VyI#zm6+DN+=mY3Zk~q4Ck_9Y%9uUVSFX zVgKFiXZI)5n!1tTIxU0fTu7_#q8A8bmhZhzE|o)pRlqANoz}6cjf6}k)1%j8;6qF^ zpPU9i@M4@6yj}I27fm$v-F9yY52%A#c;{ZG}WZ1@pqb0 zR`O=5GyeQ$x^mv5&MYvWz&1gQzRq@1gpI&XesV@r0WyV0``!90?zsTV@@D*0%VocZ zx_6l%iRMQ7;1+i4`pp#Svii*gX`ASUJi)^h=A4+r^PQV!+jgUq)T0hC%j4s&2S_jb zUU2YxyMEH>w3B{{^2euxv?FP!O+xv~hp$C9Upci^|9eH1Xsoi>nWTgCKA$lu$GFTQ zU0W}H+Rl8qShW7n(S-L4y31dlyh85liJPt0E6%Q=E@Pt1=||h;y*}OlC-M2;zTp2J zFI3hC;-BG@F^idDzIFx?KNm^6s>tdJzyHegyHreePZX`F-{b4boZc@C@^_2P_}BIi zniqt#T?EVwc$zjnHQEpIM$$eQ5s5!MdolJw*qwo*=q>ALu0%LAem-tnHDA);gdEX7 z!CjuArgvYeu4Jy-Y@$eSu B|7J?RM_lF!2N3&--)Gk!YN-7G6Q4^%+Q;#JAmQ*f zhVO`NHf*`tqjV4Fk7N1TUo>6`UhGcSnlESU&(j|))_I=}>xmOm;9-Ce0OLvw3f}(| z&!Oy7lk@M%Y(?KCucpi2BeklyL!T$_&*0OIpA&8LTRaZ;sgyly2x_~F0S!unir79av22uRTfJQSM!96;?*@XYV2OM^k^ z^OMab-xpMLRgmWWatB>4 zSaXr(bJGhJHG0XpX2s5h3kfIzAOEw|m1ZyV~!tR{rL(&Q9b`tlI zX|B_(NNwi>?Su@+U()#*PSBnFuW06Zy2e03PFO}0YjJWJj;1KTj834q2%8{NoL9FK#$HrYQ|>riFCA5KHZI4z zfA*igU~M-(A>d;ZE3)*?TO`Xo--5pis!IR`mzEDUt%8o`#G3OiW?yDr^DH=|F4`?x zQeEZ&vM{)*%VnR_R*hv~rAopokUWD=JA{hvY7O|7j(^=xaF}l+Om?Z^SG=On^)HNN z)b(b9>r&$uHb1IqJNfCI%O|5+!DBD2UcqC(+EzbdKX(n_A^WVJYK@=t+==oQ;3Jc~w5h}0*^OZ<>wv&9RB9L!# zl@zC*B+^xR6cF=(fh_z=l=1gbi0Ix|a&(dy%j>aVNs=sz&=7Gpp~^sIV?)Yf!X9>o zu~3=yUyo|FB;N7FL<%~sQGcVBWNnLyaDJFgHDT7vf1(_1_S5j`C5sfilQTk(#F&<# zun>qV6Woz@QLV?gr)qpM=pRoTdT^H~A*a6-LmiX?w;wsB5RW!6KFOqPC$T_1dthQV(aJ= z+@)}%-I<>$yi*N@kAMZ;lNSRsZ8zuTDAE$dtzT^!O+s9U3P4*?7h^2azqymGiM$wf_pe5r-z;QaIw*fL75#L7r^p%*tiT~`~p zJTQqrGhk|$oTN@Y9~3lXFz(y{XD{OlWdAYN^dI80%qd@1FEW=s5wEM%#ddJ<=Urd0 zhNO51-mJ0WV%{=RQ}XEv_0N-mc=Y~x=_s>cpxJC^&D5PK{c>>mpG18H=%F7B=+XwL zHsA!2i%=+uA^^&{HV<5+r!gS`49yUy^RzTj_atHb;io0c{18^=u8 zYh|cnK@ce(yZ`%GybTC2h19dd!E9MuX7B+?<)HJ zijVsiv`6forsb_ZD#8B~i@b%18~YTYZt1o)J$ka4W=deO6o%0bzc=X>(=@@CPMbp)qUEh;%^kv z5FB2=o&fv!hDe{CFi`(`&`MwN%y23EUNzZZKVeex+-SHWwO+?d*Xysr!$CQ|oj)ES zmmgBEni>UAZv`neJtyfn(8mT5PAJGxyv94*BkF+l6AJvPcL~Zd}`Y{87Fg}nFvep&mMU>Cg5!5eVD5;*}*0t^}svmK|+OzrjmnU zHrnp@$K#`j6=s;#C~1fmxY-4~ss&n`CDt6ZDkgU;OF)VsAZGxmh#d*jmLnc3s0u}< z%?sYc-koZI#1N4=_7(xt#ClSo4SJL~hJ;8PY~upfM4A9AOsrOd?lJrCbP=A=^W0A+ z+13Cd+I=+vHak4ASJY5foGGDR2yhV=umXqLAkd3fVR-kT8wk&145|1E{uvA^1`9jw zja#=9N_qk7&!Z_Z^XNGWJ#-6KhxywaLD(T2XLe-j^a*^&VLj~xMQGsTWc!2)l+6nM zI@Yf|iB!Ek4%m+QNDaMQ!S~CvxqH`cwE{Uq5a!MXid==hFeg#qu+7>e1$LnMRw0K+ zB;0o)%?G4qSnr;zWbC69EX4jo)TcnhH*}SFTnie)0@~2@)r48@@C24qVt&;nace^} zD}yw8gv2=Rq}Hx`^lx&LNZO8|wikYUoZu69q&GfvQ41t?1Oc;x*4v?~M=`%7psO6< zPz_s{Ds&51VU>4bs_GU_M2VrkHWg{dKZBF3Uz+;;rqTM1f5_|D_Ektz(@g|pW@G28 zq6Mw*vzBp<=QH=zo6S4{K(#I&DHA%Jz)3U#&}kI52SYt04f^LE>zAnKN{DZy4IbOV z7eOTHhj`3!*m~KKoM0iu_{mJ0kRCh8864_`qEQ$nW}3~wGl#9TL*;_Wx;RKOloC|| z&~tj27DIxQOLoC3e#Q#%7@_+KM+T)p;Q9(Au_8VLOVGRp*>U-J|BP9bImOf?&urd~ zWz-k^hVNONV*NgBxhUYHq9c9qp6W!VH+l zDFur(V0*7k`&W?kFR+ikL$8q}HvK+-RUEX4ko#BZdlRMuJfNKinVL%YixM=SA<$iE znu9|Brx2*(h0wh`(j=A;mb}=&;CsFFAzwTUIYUEqLbCDatpVGCVxz=+D`Z5CF>l;6 zH0^vT=L=U?Kx2JHju)6D0uFT#FpZ3@7$S)-hx8llu9Or?<-|nX@gl1 zF?pLATPPZdN9ZdU*}wU?tVELIm6B1Vw|7Wbc`yDp0d(mo!(SBPtoj!SRO+$VS#$9tN`2OlQmXBvANIgO0Hi7vDUZ{}4qs&B z85Jl=fYgtmEj_Mh7;62nXc3meZ5Oawd&<5m!Uhpnb`koQ3#kf&@}y+U!^{eJihj9Q z-MfgH>(4kyCf$&>54$Kr&%Md6u%|PQzJk^4brtW4#=t6z}a6R3$VvU2%TTcnbE@HA2Gg;HH$y=ds#l>=N>D#H2s1(12X}AflXb7RUoI^lf zhCLW#F+2!P&RMON4^7I{1?luq7_t_|v6Y?ya;(~||89}02b0lDr32E;dfI_m0zPo+ zbRe_6r+K@Hokd=L>qGXAatlIIRfPAAT3vmnR zM?k7zO{+>@!*2c8=>Z5OpSe-%Gr?zuG4#-93@)1b%p72i(#DdUI5Ne(7##LHcI}V@Stw}&{YKFP|8-q9HOWTEh_fa zDezV0NSZ?sI+>D47MUg3eV0ol1Fqn=p~w!xxjU!c*y6G@e=Pi`FQ{x(HAZWA$L3Mh zCB3K%y2iv@VIjQK(dDdU8a#o(l8R4tp~o=aPa08dEH=+{9*fYU4@bYz%ylcwTCvR% zFKZP}_C*9;L4)W)lhV**NvI)D;c+6_uYHX0bfJNwD6%seUanare~O;zvEv* z$t{DDND9V?skO-9tTua&&g&~=cv5B}W+9SNk$mm}=h!&)_H@emjJ=AGJta5F0vi)0 zvhvHWut6aLHjs0w&pUxTFgE{~FRN}QCa!_(QD|f93fZ3{AD%GeErtv@%OnOT5%g#( zs_e=_LOiy}A|O4QSI}}=C{8JaPAu`w2U`K0RAM-vt-j_6E$JvRKGbVA?X*a{s4_W% zq+h~&Qc90g{hqEZSWdJQ(N>8FNH9yGx8d+-E>Pxnhak_nLf>V(Jc^srD@DA6aMSe+ zEB&ScPMdrSe?4iQUsj1^sIzK2wo&@+0{m)m>hNQ@N7u3ydFPX$yqL0QCkq0!u=(Gk z%;U1q^nRfWmN~&_cvrDiBid+%t^RVT(i@gq4Da2OQ&+Mj&ihZ!P;(_GYZJfSJmDEn zB1F0WHTS3d`Z$9oL`~^bJ*l^f_xv-SKJ|+DV-`@E9=Gw6Nen)7U+UyQ>(8N5s@TUf z=u&Ei={#Qc)9h#d%w?G#Bnn8>04?#we{1 z_o)wy)2Cdl27fP&YR(33)}F{)HRUcvv{Gj;&PE=)Y+&zdf}v0Asg?I>TQ+nx>tc1T z$iVDPqR&6}1Tcw4a+4V|k0z4rVMzS@!|6cGW)qb~tDu1uB9r-_9CUY0LCV-a9OI>? zD|-DVcAy=8b8BITD7t*quKtyzvBDxNEK9zwy)i_bU* z-jqaJhD4wK?V4L{z4gTn31vpKlUXs2Txm~T9aWzOEE^CA!!a9^#AKgOYPCJ0Y@M0p zC(18ilY5$eEnjhpH%qv`5*mO-n@1v17Zb!Qkl(w~WfmKXi~Gy}qMw=ECB3cc8>SF^jGz3fpv&-#^kDx6!`=hnK*2n%- zHiMD%{>A|2rFIb`|9JLb9JAW+LWneplRf0@!L0x^APyqPDn7iY_zn9A(j ztz`ONb$-R+1kwBsCXuv@&2N15|NX97UXwgqdh``B9Jh(Hl`7j;7%*p^^Ag4606n{; zJEB!|S@Z9Koqp8ZD+Y)@(zFUKyBjY+oMPmXjFn;!!1QoDlGkuNFrJPWTAccGK&3d1 zbqS~BBcmbv9vbtwV+k7D@0C(io^QFN8KXZr^gjvxS=rB$>{QjmnmS1?%}}^LCP|(B z(?PniC!m1n+0fo#Y5nla>K{Cdh7+&eZFmj7!dvLwdWm2Oo`84pYigZ2^;5lJjC#p~`cs`DWL`a@UEdm9@s^UpKA)3mSdo{(Pp_{%l zq4^=*jY05~DUCGgi^JfX-j)VD5DWGc$k!VJ_$v0Im1RWmg^bfzp5@2g zW0CV|fGHzM8RsngtDi38CcT8N(~`Ky-6O%0f6rz_gY^K*(YALat=^kOmW6n>bk{BA zh$ZJ0$CyDwHsS; zfG%G6&0;4-MUpr>XoU!$Ym~CK0{r)+w;fE>j=CCL{)2c10RKM3Q9hl_#NALmyoaBQ zCizK^Pvs_pztc(4#1Z%!RM9asH5$bGAL5fQZpU2FW5P0Q57qbZK%B{q`q7ex%VrlN zWw-mZZq{iOm)QEVu}~orLyB6KmN*EC)RJ0;Ie>vkqam82vG1v)&{aov$ynsy6e8MS zLt=qx`(W4aMs(*5l9I~DQIc}Q51udyofxc>182W0^|7EdkH%u61B@A&_@!ku?!SbM z0;!`qg=AgEzhr_;Sj72dd_&2e|K<+6m1>mHs2h(j4={OITM)=m742PuF?sFWD64-l zp7@XEsWMMY-)G8+q+T&ou6T0_o%<&D2Lnvs=JLy1G;u+6a0R08Y8&NkTqaU^zjrFp zaSqugOr&j!AqCPOC`5on(hmcW?>G2Ias#-b0a&EadE>~y7@XzbcS1OrUdittHrRp97hhsTQLH^dGhJ0hQEL66SZB3qx}izE%(i=1 z@0@1(w6M0^OMLfp2ivSD{&a=UhnEQQ=2_8!xA)f{0&uUDiPQ%)rmIxRjZDEU41#MjqNw=@1Q;k;g<9io0^td3CkL&em22g1Qj}b#>*frB=3rthKGzhTw8GMmc_;eU17wocwm@vhDB2q0jN{XS{oE?f=B>P>_}t&{M4r zQXabi;`avl!n2*wo(k{5hSl5gnXab_$l#c915(kAh%X;1l~laOKVciX*?c&|_1+s% zPiXbL>p6~eemqBgI@=>O%!zSrF?>dq+$VWpAEr%x9LDsmv!6c5Ax@LcFygJsfM$bF5uz&)`bZ{1iae`3nEHkOWYT}S z#&rB)B+_>ZgJ>4X47KDcV^KU!*fDuKk}NazE%MjTP?mf}p%1P*Bt?!}irFIO_y0D= zZ7Sy~q9v>?CL;mr!2eSZ`~S!)J1SSeL@?!mZ{GKaVI)`Oh)xhW8PAYbrBP4dUkM=+ ze*2B?*jLCNIrmeekwjrvx<$Sk^HFRuVS$R+JIfi(BErHffjSFxjb?e7;llaBQj_^T z*B_~MwyQnL1=j(?PIH<6%=fBJD{AKqQ@Yb>y=%Sa-@0@~V34Pm&T=65HzofrAYi9Wz z2>lgo;7??ev>M3ZSFnou59x$r`}e{ioTO^YAe4(}D=Uz@?8-2T*Tu{zLhxUoL5RRF zmi3VLKy$_bDY|6CSka6=JxxABgWPyeJ$I7?os%i1gwGz=Oo=*oV_}l1A3t-7RoS*_ zqInnund;c4&7AH!@1B=oF>P+5@qHD4!Mayj@{@gsdSZcnikH&S?R~6Gx*;fsVVYj+oK$^Z6$n~R^CE(NqgMz zDeEXPK|LkeK9SbwWq$mV&yTqJo)U9b^)qFbI1IeB{K?h(#&hpvh-2cV;}5>&lIoO} zT4omP6sP3YX!|=EbDQR=3zlrD7s#`(b&#T(ygt$o=VRmO6L$SiuKVXRh~QTjv;Wn@ zraGhJDT&d*1-s@amkSOv@|SmB0_*xEw?o{%>oV%})zz{;fx^{l&ug^hIoHr+enwZz9t-|aB_wC|LI?vsTV1-4EoSf3z zgO+q4#qQaln3ai0FErNE!1kk-SfGA6ez%uLts3Q!B zRJTM($1(mqR?nc~R~=7=m4dm9zmniI2}K{=D1}In7?P`Bb<(kog-ZWfg{Ah1GXJ&< z(~Mvs|9bb_nXU-q^~$1(ZutI2Mmb!K#OPs+nK%c~K9VRR8$d*lssD;4w0!`lQ^uxz z5Q&QR__Ox(mah*^b06a~`TQA$d!GpN{g|kSjL)AoN=eaG#m1!NFurQ+l`&NLl1ReD zL<^BoFs=HM^=HlEr3v{Y$cU94Z)3o)tO+LpCoPuX3cjnGI^26ozh|{ntcAt?&h_q?MhwW_!p7WL< zRgt0xvr`uALxI>~@>me`VK!iDOOl^PC0ai&horVZn3ZNMhO#D$P|sXa{bn?F{9z7j zq`ACf(^z8NS&k3|tCBXGTJpSFK3|}@VyJ~m_Q_51ns|2W zTea|^i87v=!i|@2=1?RWIHd=vI*t3*_O}YwM8>Jj`)oGo-3|wpi3Z>{n?0-9r)46| z#>Oo+$I9)W>%Uc-zU97l2&P^9Wsz7v+HGT7Jg9ffeqi6>sdpaB+d83l=(s?; zd^yhBd{TShaBR8!H;StD^6wkZzn)8YuJvsI<|Eh5;*~!MGp!II4&UciOWvkeD0Weq=-;x& z zMfGD#LQvqfW%zM)?7SN~wt8x}vAYICw+TDq$v>oRG!RA~^1#lX9-eFy&h%!(@fX5>FzJuLC0#)RG4 zMAFk`;@``+$*WC11bi-)Ltf0pp0FWbrWe+O_so(6r66pd1yFCc&5T-18CXRIkFbT~Ip zM`m5?kB_vXr5#DfJpj-K+zEQ)ZZ|lh8;6hzj+HU)eb}g~is}+c-`$(>U8qOd51B*n z3EDCNMUO&WYg;!my;UV7-$Y>4VfKR$r7}-%v{Iv-4K<5?^ybz5wVDx{gj%enK43Om zEOD8vT=cdH_FOPfg=-HPQob8$Ub-B=SMM{O!G52xA=I86g~Ajns`SP6 z2s}+cI8EP79q^ufOUGMoA^+Tao9MHbhS|PNJC)C-6eWtY6NPy)6QlY?vxU=X&EtFi zzbK>hnlBF+Y75SeajhmAb9eDP8Ay=EiFYZnu&q=94qYmG6aW}IgZ5RD6 zc#IPiCt(DBIG*+~$sw{O!|9dQeKb5;-&lYA!be!d>a*=cZ|Wi(NjkDBtj#lvyMRi% zsdM;vKeS7#_svYuxU++-9C@%*psMHr9x!OOk}nGf(R4e0ae(9s3`#@oDZ#4^gh5v; zOhd9{)0lJ}nFU$+Tr?~EdOjjec)gkeT=FQanKb?HiGiyy#5EP(aOwaNz5uZ;iu_CW z9cJRyBcIkFsj#<1G%SE=1cZ7JkONw#G?jUbU@ zAzr7_+IV49?1T$K460?!L{)9;L{jT8{**q@z^iSuk)d#JD>tBoR(H4S;U;N%rzZ z|1{&wR*Lj6Ch5{b^Gx5B+3>@XJa<@vHn$=}f`Nwxv~VTx3O#W`MYIbAI^+^f&>yv3 zAH8ySae@cBv(a{&Y3%dG+JT|#2#Qt&;bs!Wov3cJfM%1AePcfx9vk+>Niu74eW zmsM^xdcRNUn}mrK#|G>nNT*@Y1ORAtG+|l^%Euqrh9Es`hb|`ttx_kRVSI`@f~=&; zm>Qhn2+{y^(tFg2+cRkEeyF2X$OJ~Y#1P!>3^toeFG2s!?WTY%UD=1jfQKBy^Y#x@l3MYHYr(u9fJ{u*i4n`N@ zB}(xp`y@yD6j0D?Cmviv9HhxSk`r3{@RR09&y>*j%t#k;u*61p4U8GZ1`K+v1l@x{ z-RCkk`H1$mQ;NT$_mrU9j|AtBGAx+^`=Ob2+R#HdSrZ;~uP{+NCgY417P6fVG=Su7 zXH+^uPD8Ok1mR(O#vy`4V>M$HkU6j_T$$}qbwni0lE9LZ#nzN%XYUAflYE2?SJ8q! z@55T~`8DzfJDQPftl$$q19T~Y0;TSjEodtW#-s(xz($nj(>V3h%p<;%hrohD&_Dx1 zr@~=9!A4QLV227+>uyHZnTO?z1Kh^t`w1h0;aOUvf*S2@chP5 zw3rN8rcySLGcSlDKPV(yBqcJ$HRoGDz6?$W`mu;~zCEzIF&GF(q5C}Nv_gO%$@<~6 z>i{Ta7c>LFpLr7m3F3XpEwi7|N1p==4 z+`9@EN5K*~NcuO8JvSqjmIaCrRlOrs__nydVK%@j%tC_eY7ZPqw-jtAosVT>NGn>P&@+Quq3 zkaWd|SOQJP+cLgzN#C$?IT;XnANH&WjQ}J8>Fded%AZpQ2Hv0;btOqdBo*k1J={x4 z&2rTd6$b?T^Ki05r3l+We47X9OoFsuSpi16DDzp9ixij@B7}tloUL8Of~d$|0iAB8 zCKK@Y4c`5f(8M^)T$_6h4VIq57DgP!DPe_Z=Fp^kZSeFpl?f&&n5YhD2XO}#U0QIi z)w>5#2s-r>C}2p7xxopnunhnd^f>fM0s3MWzx4X+03kHdr~+v4?J-e#>J79*+mB|J zc#i{Xp#{!{rJcdsgW91SvLr=!3t#(J#BJ`9WlDhu?b%VTeZ76ggRO|S=oG-H%TW~)*0Qv^i0={u&9>QiZa3U+vl=cjvjI4iA+TlU`t z;*Iu#P!HPbXMsn=dAcnq>n)I`XORZlr-jWZ=&EH)2_(kh*SZ3N-6j)+0~ax=DMd5^ zN0C6>Gth%A6dyaF`nF7br(J?524!9$L|gc}L^2T;c&SsY;@17f@|y~Ap#p}4ZIh?K zB1304^RZ500b9P-&4AN;B9F$}12$NF3k|n2f1^y^T}G)DPL|Qmub~`KbX=5xAiM)g zJ?4nrJ!u8!NOdf~X^)|jCnDI~2TgmetPrm7$HTwg53lk7I9EU}S1~-Po+?SP`+E?1 zuUxqukbX#c-aYH}1D6YB||$g0DI;BtKbUCLG28wjoyVcKEzcybRgROF+LJ zq(z{;2uawwl0a4J;9uIMT}bm@ZaA!UHsZh!h1nRakeqPu# zd&hnrLD5D4Xgw%vrYT+&Au^hBc};aD=T~8EM9Kn+LM3i+5dCETxjrLF!XJH!yAH+-{hS{q zO(!ZWbzfAnAdPqoE!kgy>SHzB{7Ifa_-OnLjD(hgRpK?{2CXEHjDa^Hz?a zCx8+*&AQ!W5*v)mw@ta__hpgZYkV1N2&0OforrgWt7VmWHdyrBN&>u#CdMB&sspO7 z>~X!Iy1AEEUMV9?_t@|KhQ==q9@%Ul0P;a5d$?<(VaCJViB>uYrl|t6`qB#d_C12Y_}w7&_f0-c$_pWfj18eK{30XH(vHoShz^_4Is@E4mbRSw)X)ySA$! z;UaYAKWst|c7?<9u)P>lU0X`N?kr@L1?7+IeT))g@df5jRfZJBY7g$Wr>ub1kyu|a4=i3|y zQL824a{l9XPHT(c+#&+#F{UG8@G+Nyf4aWh+Xn6QQ#ox;q5`?QCoytl(%v$^;o|g1 zC(|w+?wEd=BH{(@Q?non?+d1ojG9mw{M_}0)j}1v_ zX`W+&spL;xztZ2{x)OFSaj4I~-!Jkm#@A|?1ZtMFo~E*EW6n>lD6C+b+PLr?{`$Zx znhwrgBUIJnxNI*f-33k^=N6)LV-=gGh4F1!VoWye2Q9-jCK zU-A14%L%de+ZaJZX}=BAB!1ZvuUPl6vFuiuRA>wF_0fK#c=4gl>F~8FvTwb}1ts>< zG%eq`?8Qx6kDYj4oMr*j$GoyIP1C?yUmnw4c$AG@Ll2iJ?2FM8oo#!cks~|bBR~90 zro?zw0@jX0m&JL3H(P&zoXt&k!~wp4XN8B~;78pNQ`xIq+$`{%8mh-K`o?dBJpu@P zj)iC`_h>NwCsV7w5l-4`nMMKm#ydWilG8R=7bAc&I1um<82<2~AH&xUG#Elxax%IK z=T&DTqHlnKzXyOm*rX9wu6_(v7odEp5=h#E2F?=lv#P91qk%;a8&#NINQA3<5!u~) zYp9q??k`cJ9kZp9Dw0YEo}VmG%T*56|Ksk&I$fkx%RJ@oyrYx|w75e=H1>7stQXq? zX*Cb-h=={9?o`b~{WkBv|GlmC1JAObUc3XpNUeX#^*eG+=Wnz^nRdy^!C&TqLk%N((^YGZhyd~4F<9Zr#E(M-on-lZz3l0HW z*n@;WEPao;vuqd_(o#e6(;m`}FywD>%aoin)r_>Bch-!s4_}U!29zFcd9I*Q3XCYOZF-?jj9!0Z-LFZ#pW}&KEjT7^z!+ zPFa`^5I6@S^Z#$Ha_hKdElmKgPtz#>STxr*9j7oBLJm)lgqecE-8a=XqBLz*{0F&t zvNUPx8jEK9T$p>SruE~}W(=W&m;HJOsXJ|Uv`?Dumq1C*<-c2a#7tkLJt+J721q_I z@c#{sPAGZym4p?t4*gfF{Iv!+3SQ-$78Q9Mp<-XWQ}H;do)qwrUZ1xkmmbh5nXFb| zY#&QpS=U@}msq;38GBCZKS?|FRR1o2_`sWBN%*#O$glYJfc1nl^Yx%S)=9@#<#2Dt z`z#!WPA+w$H5z#q##h~wn=g3SzlVemuCXj^gouB?yNm;$pSs>3J!`W(znKnveB6A- zhztQ@sRSZ(Z6Sd(x?fRXyAgYtJX6T@KpdP9p=d=W;5U3?Z=!1gamGzh-e&Y-r(H@W z_GT9I{1LmNKai~U&d1D`>LZy|iP-ZsjkV+JZ}{i*Ass1%x|a=8`#v^68E%GG%r}69 z2?L;ZLq1t?QF?y*5pzCjrq_HV$sYbD)?%IlxjXU=MyzU_5qy_$iAegxqH`=!z9`vo z_Y;nMgg`>tPxe^YD{6ziJ(+)n%9By-9Fhy>A`4t)p7Pcse@1LQ$o zG*BNfbyYM7@H@&R#Zl#Tly(UT2lgaCFsLOba}`0UKhg0r%o8 z(8gNC0JruOOjf2XcO?S^4Ng1$;Mh&W`GTnXeRMy=ZM42lGlJI}-x*Diwl=kvdkF{G z%<^m(no3fuCoR7@ZM&>B2WWqr!)NzQ&ssRl$tYvu`5pd6&Y-BaxqrmoIl4{Y64P@%3LmTgHaG5TqS*FzEtX_s3Fltt7&E7 zJMy0rQz2WuB|TC0Zb-E|bCBU()>7B4drh#Aohjj$+ZOh0G2a_OvG=8aPxjhI^Zg`%kO}9^S*6L$Y5IEV_tjnfs9tt(5`Dq z(QWf_6D9C|KqTNQee>U;bl}56SHNvx?${cukYR0?eVy^<^W7$&&q#dIsb>Lh(Pb9^ zuN#S~8_3oDN}?O2(G9kE!NYc=D8N*Qg`Wz$pT2aG_jO^+!^BBzJ9}ZBI2@`b;HNsy zTHLT>fgU_TQMJTw0*f9(w;m#R4{=HlNl_1JeGgfG&)fN)cY8hWuX~_HJp>v(xMZTW zq@v3qRS&D(G;Y1zls!+Mdt2_i>s5Lg@p>o}M4@|PjRwgXVscS_T7}U&CdB znBVO6E5d7Z0RwjPgM5Ere0X6dFiCp|iZj)aGuM!d+kmTvv~xSMyWNnBpR{YNw1?Y} z4_w+eMcS`u$ainZ?{vujdMF4q9E=g+%{1&TDD7N?OwcZ-)IMkrAC4re<1*+m#+F7n zbq~kR56A5d$6pU8fJPGWMv|yTlDS4cON_+MhvV7FpoFqT!ACOMYv>euncIs}`bWOb zk7VzS)Xw{ya zIfEDi9c(;}TtPKf%QaRvKkSSVrliu7?>ABnA8S7S`a>QaAJnY`04q7k)$fgUUdyM< zhbvr)RMrnRrHu7SjOXW%9h-|H%!NAsjSZ)akE{)M<0&+9_1bWa_wS8QUK7~QHJ-MO zo$tbxm*qz#CgzLeT&9tgGT@5c3S4{rdUSGA^%JYtpIOkm?OYWWeL*r16vP7FY!3IF_jU{6t8`2|hN( z7xp>^>?9U+N;Y;5pSr)6S+sy(#!gha$zIP-J>g;4$%L=$)+z-lE|Ln}rA)n&RB@UP z7xRKIkScJI4P5O_p%zcK2BE}mh2N2?oG?vGdQE}AGiUS2Qhbvrnv?%3r|~pZo4doU z%Ze5rJ2xIDBq5X74XO(k6B2w%zsJXW4QAeh)f$6lmd4?-k#HFk(CdyFYDq==>6r#! z6&t4U1B_V)MOCFEp$o=YO2ygNmb0v9^0ezSk8U!k4YQow%DyTw2&Rta8DBV6m1;`t z9G~LImcmdh#-#JwnBa|?AUJ}gcN$GJIY~wJSTAIgqYfVTISCcD z&v<~?e{j2_5$At!j{C4t5SZ-}9NVtpG^~+;5n&+{E{v~XuM^4#m?OJs8zWPew4B%H zR^DoB?xX~f*e{rW%vH2kgbq{1&4;rALhPU#_5dy2qhaTEIETr?=M*qyWauZbDlK?Q zHgdLdO~C-X)K`z<-W|#OM~L!FKx+Ec8ODe+6^N2v1`r}pHZA}NQPxzk_tLiB zA9fz6vU@wSl>#Qo3l`&^r!8K1w=nADuG7zj;vCdQan^yL^oJWs>Lku1zo>tV6T_6t zsI>oqe(Y&<^iyT}!rlH&%4Wd%62TS&Ang>eOk^kkwVIY-DT`>UInMsFodhS!=ha5>wZ9lz^`8kus7MPQy3)`5up$@(M za)jh+m4>?4GIHCh8n33d$HKBK8&E+^D-#S9N(^(l2SXvDPA}AtykMe_lt1Q?L&E?h z%OHz}C1W-qMkEr63IKyh6Fi`;Js%G14(b^I2*~J}4S;&y8jy4cu`L_SKEY#f412*L zGTl@pkXKds28$ER<3ffQP>^v-v;}s=z@ntm%iD2l<%C?Mt`5TgS8|mgP2_%BW%Cyfrewr;HA8JmYV!k@ZG)Uk! zwuP*p?Qihx7%Ai#=}vFH=zjzsHjJ-U|AB#XYcIP2|1$uxmFPfV4h_*y3Mlz?V^UYU(AN%Z#Sncw~bq0 zjoKUIY8j@d>gv{n^IaNKLP1K=YdRQkauzeP!60)w9g-ttm2QCV0`k+%+URNci-O}nqpr7Ov}w9N{(F*G=EmJ161ETrwsjs3y3k+h z_L0cU9xvB?(KPcb=*L1fK6y^84M)vgodB_2$#zP~B{##R*nOGoeNbR(SU2V?lIBpd z!KIkd?a?qJ=rTwl!xU_}Hr=pi4h|_x4a+iIWate2Qe~8Zxh}eBQLeZnaAd_YxP-^E z?2rM1@P(KX9C~TWzUWoW28Kx{Hi)|6rX|7DG-I30`i|V{y2wYE8WHGW0+jyd`_#Lm zry%c*CE5Vvrza~h2SbDshha2_&iFq3Pw|E>g#`vSJ=94Oyblr^HukeL{o}t!ffW(r zZ>02YhcrMJ<9@>-5sbkHJjL8p@i@*Hpc0Z<_j+MJ$;~o6Y(L1u z=8&)X=AgA-dF|2Pe=9o&$mTSpEL`oy9G zyIf*G22M2?IwONF!>p|Rcl;YjML}9|r!&%j-h`e@+ynUY!i0PaQLlKSh0z||F4-vSjD>z1ur=7#D4IZzVEniu@nZFt=>2W3HGZJ-c-5%C zkj?vaT~@G;((Igj9N z1rhHbgkFqIv-pP0#KkvZlMxJ*A7?TjhGbh84-<-9Q>kpGI&FAGWbbaR(S`qrUNm-p zS)Qx@wGi(5VPHfMB|;uE!r>l#n{)VvV4hcbEC+OrMsuxn*EnbOhv&7b2x3X$yFx+r zbtjd3ik&kD!df}vM&nyiL*a6?KU}O#gU!;&@cSS3zv^c;nC|J6u3#-a?HN@UYk z8SzBmwLKo;#d;qasJ6!?rbu-cc6ZO$CUE|$%g}wwKKH)1(kmwSuIt|<@`4xSW+oxs zTRgN2vuZg}{Pwf-SfC8Lx3PDph2o{#^xpMhCa;h1Zs*P3v^1OI=cT{p3f{4o-l2zM z7xl^otaF7+K78uR#ou*a1w72h`jmIwS46;>xMx%?CabJ{dH;xPoKDQxKGaB0{2&B) z4@dZ!c+}6oY?XDx#eE~;KMY^r>DWhwAdq6Q@2G;ecQ>TsV$9r0anC}u&hW8k$d9UU ztS#18>4o<%I8?y$%M#z;Mex@wuT5d6%$&Brfa23vcmG-ArzL6sp9xQMx&Eu~{Sj+T z>P}@|-T)NuX0OGFr*%hvSBZd^2WH`-hsz$a6wFt<>u$U>07G9C6>oY74p;toC(j1I z;05vA2mGc*T=F8Wq!E9#5!cp;8&AY-1mZ3oabJqKK}7grBm5FQy)zKcC=i}-5DwYL z=|pm&Z~{ZK>nQaS*)RO=IMmVj-?YD5Ipb~prW{VBkWOa$bVW6q!k}GicYH-Xp21-~ zTlwh^&E!{p&#TkpKeW?%Vv>4Ha&mYBikWF*A^k_k1^hnOGTAma42zX|O)h7@ZWxzq zjBpvas9qxhz0H>7s_H(zDJ)4$Q>uLVO2yZOU!9%Yv2JyTpy0CD-Lvf=`lE#i>=hWw zXBCntghD`(*!g14I6vv<|JEH&=Sjz~C_dC5&zEU`bC`H&un~y4%1>IIbUgp};reK{R6X#MYPV!zV!B$uHDuayd}ru0tK+la!}YJF zI>(E5t`yQSd#Fw+Wz&y0VVAG&SOj-yaEUz)To#DEpdqLX&CpOx{<6<>KohQf$pm*C zsOP$-6>&tj_cD3p`)DGHD9S7yifG!342l@W0GVNR=20&*rwz<>*&w{P?y6GWXE)G9 zQM31>7z z+Rs;BhC$IzqQ3Vd+rGf=8GKJ`M>rlU>t-kfnCs_wY|nlSZZN>;Tx~QCzimegu(a%F z>8n?UUG2!`H?=;pwErFzVC}eB@n!8iH%eyhibP}Rj>iqq-)aGq`myz*9%i0b*7?*r zcD<1oWFNrSSNP7JPP8k-hWoB5sh2!PkYj|Jla`S+uy(9^5E0ty=R5#xCJ&;H?)CfA zj=k&mv5I*Kt!8L5#ExS|lGLATmSZ5xWv~J37w5c?{L}TkqPl;>f^HL2H~#xG@;Yiw z>A0I^y%>Lrt3;FhstwylljS;^b;EkyFh zHB0-GiOEvNK`Dap2ASU7Y-i9`|J{#pJojGIuw8STFC1fTIM#jdpuh?QQC_e6jR^~! zHGFGzt1SN}?6VU_h~-n2cE{4b->AmY{m#2SI0EYL=lpM_|IfRB*K;VZ|6TMM=XzE3 z#lG{~-u%{i|7#7m;s;>3JHF!VtPLUj4~>KA+kW8~gK!n%=H$YEYoK&8@R@%|#Qahe zO;x4`T`VyK8)6d7irq~Zjne(^r(;kW`pZ)(yyxlDbRgMj?(^_a^<>zk=O(W4whwu` zk(GkZwuOXu8A-}A+=oRn6LDw$7M*!Wg4%^WO3r_M+tp3f=dBpP-#ChCB^+9O?_1p6QfZ;IrR}EDFZ;o*1RKa0tJLm zuv=C~wmX=6Pj?A~)BgXe07&XbD1Bxr2c~17uH|EfSG81?Zu_)% zka5jXj^r4-Y-u_b+1HRDRN*aAJieN45UQ$BFq0YXH=UxeEfD+mi5Vs1OGW$}QkGkk(ZsJL6f%vvb||u?IOEC; z$)^fB)E<3Bvw=|L`1)#pX1muGA*AECpscS|G8w44i6*s3ZE?&_p^R$>*ZHsG9#^Ev ztLd8+O&#a{ ztbV(Un}18-9oHSK0fsR_|E`+4sufQHz|%qV4^7?3Qg$|^*jukSn|l;*&P2)E06>A} zUV_d~HiT?j)eJ9F&d*NDC?f;S5K#L*)p^(=M3d2tM zec{;eU#cF?1q0DUtTyAr&V@tqP!XHGK5LVaUWNHN#f|yQ zx_zZwA$#OFUCt6(&77RKH+!+LJ z7=CMHUTt#N?WJavfZ?}!l{S~}490DA1-yFo?o>O-hzE#w?j!d zhRGw}sYz3~z6{?`kg7waHe*zg@`3{Braw~J@-9a1#`E81>?Q~TkIfS$us#(f$`EAk zCCTxO?7cto^^X}(q63Ff6!zpY&7R0jrDl16D`Ct(2fr^|TzMTJezr@1j z=f1hS$EVWB*B(DD%QJg3=}U4#q6;D&tq`MR9}8;KPO2JfDPUC$#|(*dtVVg8HE~i8 zAAbzL`&Rj5oM!d(ho*sZx}kHUTxs@VHL6WzZf{gU$!gZGUuljmQ5B{8@v8?-YgXt| zY~LjYJB>l5SYw)>7oKRoN^xUQ**^4qChqesZ6;j#1=U z`dDbvxTMAd-Q^JRbi3)CAjG@n9=h)N(;hdTcc)*;)}(>2uCjbg zs7}Fbe>>#CrQ-D9>)8QMXv}$|=xfF6W5_FVcujvrbs=u$Ng01!jrPp$DR-}uW?c1Q zK#w6`Yqjy209pd@H`fkJ&^ga-=f8^y^xqE`1M(t*HzP~?kLN%>W8dq!RhG7!A@ixM zt8o<8j*IR;O2WT)BLdrQ+eszpjrDBeS@w?ua;ln-(4gN&8$^_=?DQeAKaT_lMAX?M z&@5F3k7?*C(fLeGz99j70tjo8k@6u(b6aacF9e*%IQTmn4e;^Js4=36+_JVhg~fto1e7j_EybMiHtZwHP?}o22U|fE2K|LFpW3(bx&X=nka*$k zVEm$Ev1SZS032V#6sdG?A@7Y2CIzx9=A%Fr!AA22P3`A$%BiP=>vaBEe2D1>90dCSpabPkC!;L zCa>c0Y?Y4KkAYCUVaY%n0n+l%U!YY7y~!V?%ghQ0i%#G1StP093dfct;-|g4hO!ri zu+=mcjSf}Q#~2}|@zQGn5jDc>;w6T#is&l4I2KjW&~@wv4~0SPA9xHdslRj8nHZ@@ z&=~8Vm16~5)hn8p7qc+kh=I+LMyhorSTv`hNa9E|ozax`Bx#so_(9~o-8x7|qMfFY zAv%T?xnx7JPJ6sa-tYVd;lGd|k(u9@K$nV(PfK5-sdXiZeKmsp)ZxI(5?aBJ7)Yl} z1y_>anJi6XpF*a;qz&hhw_3-#jABD_GRoO8Y}H-|e$Hl^Wb-#(+df}kD%gUOlVg-m zkmv&Y3YULGSgImJ#M9s~KnV3IX*ixI9^@{r)=pIgZ10zfiMWwqW$6jWPw2(QAOox4 z-9^cJ^&*IJS|wP+lbBzB$sCtI8+i7aLFeMM9`Fyx&Ko&p5Y`Xj4?h~9dycVUvuqXv z&RDtiaWn9^U47n_RFqsgbkCtR!vXR6P~?2qMdTAWUJXJHztI^0V#wq6dXXSY%N ztWw&rIEWHK9pf~;Qc%Cxz%Ef0r%`Bv$4}i*eG!7H7rKkvYvWP%<`rDswsrK;ofaX5K-AjgG>h@mq3ws)mgrwP5w2dUrYu?hX{ zS*-}WCQc4NnSwr@_$Pmf?`cJ(K!`MNFA`Q1r2#ZI^1lC=3E-q4xUjXQ#zVF7TbvVn zdl3Oa>7|{-5~?#LqGv_+RYvt?b1Rxb|%H6rskZ59z>Q-_lnQpT(ckMH)<3ogh=ZZ zjRoKA9N1lgdV8)l_pC!P(*V*uqg$4@T?U=p%Gc?X8|Y`DuON)nP1HlOn~_nwDwcn!ZXtvs<7Wp$HH8KIjU6tqyH*b+v0 zLJfFNCq5DZObP=kHRu-=Q+8aU>Pce@M24(fqH>#I=H{VzIwQd^JsPc5(}pYy(|krK z(G8d6?|STED!zkF#tmQrC2Xt?C!|6xP)87|2f29kzE7Kn`|SW()L7$k~XyrIE@ zbH&tI)7ZJ2GD3TxLfk$mElkUK%fwFB03ZGHuEZ zKu84*HXR*0F|BvIxI=XW&=P7~gy#_#;n^rDUUXoyO6T()1lk!SiF9|n`|Z_^jHR^Y zqvGmFR};G195+!HI!UWX{1R&p7zu=F5PnpLO`|K&+I|y_qohXHbaIT|2iekk)#gzy zZlRmpC-ogV=tU$9g`>{X=>Hu=hTI8MOFP_HVH^!ucEVn`a7i`^&YulJ{KmJ@J4+16 z(=i8!sg0~qVIOSy@0g2@P&KflE+U9rhkPN@&X1)oCn#3N=C&CRAd5~R zRB+X+WfRGp5~p)qE;OGPl^!jF#Q?N_E1*Oe`-&S5WL5U6JPRr8+M)3wR?K?zPu(BecMv z<#Z(ceNbm&WKC(7*d^+sNj&>e5|X!9A-8nzEczazJCd%~H_b^jRvUReD0=M96$o%< z!ST1+L3TW*;MBH?O(%nuqx97TQ%;sYD zv*aYlx|QP~JAo{nf@@zc^i(Akg0F>I;P7eNaF`f5Z$>&)eohy3cVo=jDwx5BCK;sD z=Y+ca*SNh@$Ib-PBAiI`kNsGBB=sj$$g;aba}o>04!QJe9ttR7NTY8^KVb=Pkxm|( zqJPO9`ZmJkZ*k$LC0mq1w+D6`IwCBhD7$rWtQ85d0d0=E;%HN-gC<+X+wg4Si0nsh zv_%t-J}5dNG%~r^7O3(S<5tshy0FlRuoZET+#d!k^gvokcN~OzA88UArQ%=@k^OW^ zee26IF&7%coo8 zRd9@DUbG24b_W0%MKAA)8x6b3Y~2K7R1~I%BkJm%uVgAf1u~ZQu!wZFFu&8JN^uE$ z(DdU+`^e=hjAr${@hgnTBcA{(7n{7gM8`7ETdjoO4-M-ZfyG?1OD$XWJDPAO2%NwY zvys5J58JIhEF>Mgm}`mMA}Yb4RTyXa3pWA>e*S#YqdNonW{l?iOBUd_n$Zu|C?;cWOIscV6h0D&R2 z`eNPGDsU6fcK*gNNn>5}OQnab)r?yWd9Jqjo)lqx7wC&1SNK+z{vvKvRSHg)LCF0s%X`WCDcRWhf__p<_wP&2<(=73Mz%|F_ zEc2+v7sZ)@?6ijSA1oK0U*ZUgL|mz-y{2(?%PcdOqma({Mzg`hhMRuasX#t5T4?ooxyZE6+#IeQ1YY15rhp&CtM5^9~TvCoKtPwZAo>H2Rg+! z`>G3y$^D6L^A^`Enx{OY7M5~K-?%0?>S_GRl^=oYvv{5iic~>UASv)-txU9{c1z*D*e|QD6jHq z89)PWx^y)*MpB;KR}x?~GV?2rhyDP_5W3TX$U2T}JP78j$wJ3b$#0FC$@d`bdt1WZ8DptMk}8Wy78i-$F@8rf z@^^0ahkfZ>h>!_CdU-p5?tvX4d*%BLpNYm4_6m(Ye@*jcINLj}(3*KRC2@HMO9hI0 zTQ%gs=~(fVP$TeXBdtFg6jag;=z*y>*8CVslh<5cvQSV6hliQ6Mv9?wC8r9CdrhsZ zy2PhFee2l0#r0A0Hz{b8>k?{%mdc9~8!O|}tH!t73Gs~Bchr+r^{U7d0wVq<$j%15 zZ^ZE6vxQna>8=`ZqO>4@QifKjHbEJJ915ytdVn}`1ZSpi@HTBD9&+ADs0RKFi zEB{~#L%?!>+o2wfrK>bny`fkM4DSq|H-2rl@v4V<^`VW&aO112c%$M<<-A(z*G(f# z@za!G7gu$>7zJhn)%ef46?=Zud#W;u(x+VFdN;%KCn{t8mS2YqC<-W?6qSdC#y8|? zi(Ob&Z$!SN$dVbY;n^4-63vF_1JG(zdsF2Ti@D90RfkjFhckzI7)*tn4TozO=wbFu z#h892`+6%V_itVPUR1oVH%@7OVt!1tO#+{@U;8T=y9V_Z#^-q>p%n&D4mZs(8MT6b zygJJEXnqU@Bc=9O_L6e@VlowfhN~fV)l$bAOQst5bPU-9ivB%ud{GaepQfT?Xmo}v zQHAI?j&#FdDi3f|1Kgt(p^7HcB8%}YoZ|>+HWymnr(D{cD9Z&q;_yjPs67p zsUcjg*}N_qLbj3w{#mZ+F1#T{d&HNRHo3hhIc^uX zq-tPDj7jTYwB{4ftaf+m*22}?A!niLGm1 zwP*mdpFx%Ew@bY2%`wfO45u2N7WDZ5Y$1j71obe{ChLj?nE+6Okjy_LY2s?^NT_*< zV7n>bp-XA_b(tu=(O^)$Q`){Gbh@Lmyz>^h15ok>Cfv1j-bHNQ4;0_UBJP1d?&2K( zX6Bywu->OT{>{q$TjcmR;QM|26u&R){iV@;JnMZ1>wN;{nqd*l`aP^6;c-6Lq;>PL z^ZO(HJ6I3m(Vze&35s5?vhKio#7O~gVZECa!Jc~mH23;xh825J@0m=E|Y0CI{$?+M;j=zU^dKm{Lg1!3n{pq^v`6l=2Md!00h}aN$29U!5$iX07 z47^Be@}4kMR1OQBntbsvY-+ST)#6xyP$7;>@;+lxCH%#Gju&*LBWq7(`AOajV}Cq_ z*)*+R_D`{_E{puA#WBv&NSdg6iQkI>yGE}G=YMnIf{`o4m@m1$0g?3E)WU3Tz5&3x zBUuA-9!%Qx#w|2qDRz3}YnK^`1dZ+yt?&Fz4cXXAi zwtAzIgAr)n6Lg9(t| z_)!yr+{>vYw2ee1`>}0%E_-#cG2Reh8E0aPf+ZEOMKSGvo{NGEXH@#|+1)J5wT+Ne z2`TMU96NreX*kN#<_aoT0LP=T$DYfVA3M@CA1s2wE0q?h+Ey)=o|Gd+y6M&>EmmL3DfW`ScpkJ^ zr=IEbS?5R4WbMjgv1A>>KoIeuVzAH3F}%R26>(fqoWo#KmOo2!Qr?36SYADZ^=SKJ zY~#VMVZut_tg*vGz@hn&#`ml`pF#Uj;aS1w5SC^II_b&}-#hL?NBNgjO#X%p2L?4= zJBE=h*}1@g)5sTH)*mf@J`0`y^cj=6yV{t87O76=iVBI ztQ3P6WMcxN<`YHJnhqiCH$moZ7RBStZ-8d zOFnUu#sA^LHH*KyosJLznPG?VNl*~XL`qAT;iNW8(D2MeDZ?rF^7tgPoOdiV`U{57 z6G8Ses-)ZZk^}=~>`L8KWI#Ya(Spvqlp<+sPtpv}B06j+lVf~V=7ze(8?)!TwBE){OD;{w<+VL`XE$_-C9fO+Se&1k*f>#$Xg<|q)%l7kbhPsE(T0yNDE0xMqk3wXwqcy?boO>OoO5Xid~e-Gk{+) zsZsdy=z|1ma9$PQh7of$4uuql3 zMGL|#N|+#MD(>O+!Gmi@8dNKT;kTa)M&^;}J_ZFFgqy~n7g<5eh^3MGyCK$0r2w4| zbArYFS=lpI8bS1l62kkz&Sa7tFa4MVq6WvxH$gP341j;ZyELC9EHs446ANJbNs6IS zc!tDNrGOri-(+?OI$Q5#Hz_d0FXT0y?9LmZW$r+co5>HPS;I~rYjZSY8DvdnF~3l0 zKxI?q_i{c=(N>ft|Hf_|d%0?uHrTGa8mtqBw)EVuE+f-xYXSdh2Fz6<|#O|2kaz<8MP{ z|DJ-G8-R8PDf6h*jqk=krGbop4UXt23aJu{ck$@)T71y2TlhP70@zXvVchMeSf0y$ z?~$D&B@OxlW0(6i=zm9Pwwn=1Qx7l;|Bf*gG$Wqk>*sF#0SY}?nnjy$3A3wC@Fd%t z#nSCHPBBXg#*MKcXKfjdqP|M-wi|qZxGaQ(^nY_g2!I99@T&iRazYq6EV3sQg3Dkq zT$A4yflVp*Rpv**KnxKl1=EgH5UJvOA)8q$lf9t?sA3LRIY+TPFQf6G1nM74`7B=D zkgu8QB@@{qB6@1>$C1pgJZW>EAH1%&);SRlhJSq@4lZoJvj#jr z|9eg?-SEE0EXxhL^1jOrMryP+4*e}u1`WZfB{U7h<&Vq{`&Wfx906j(b@WZG3n{rvJJ7)gpaNh0~h zBqgzvk}H4Ha+o7`d`z1ML>)a;3r7p0%k^Q=`Pb*_hIohM`x5f~X%91jV zQKqT^;W69#Z%QY24gE#}Otqa1@@I`LBroaWP&lJ~V|Dx&hq@Cn`Rdk8AapvBXI8(k zgMa7CMaSLZDr?u@2U51~M*=&i4&eKL7d@yaCr*9Xxc_SU-*76h4}jPY!oS$1kO#ec zA5n=yN|~;3H9}Jwdo@ZObILKy*2Ppe%2j9QI?gxME~O`Uclu`vhQfS3EkS61JtJdl z2>=j-PXFtVx|!F|w!c}>`L939^Nf2T7L}`XC>&xULu_3dce`TKG;zD?Fob!x_Fp8N z$Eu+;U6Bl8p-DZPiuryEPUvvI9Z6e#KZQ(Jv$&Kf&GL6IMcd);K4G2;*gQ!SnRDfR zU6u4oVY<@8u}^G#<8gUmz{9WbvUdW%YU_+1Piy)D+RmHOt9{<8MfFD06+l$lF9+&s z=YNkfvL^l+Wc`kJ4TKrDt1W4FrQFPlbiGL5Y(<3b_hK$OU_Ye;pC68`UplM%UB;ac z2VXXy@9*c7yZ#+TOm#h3Rk_PxMTjT`VQzqK>rbd{V5_xcSX3pR~vddt%Ep<@;kV z89^GC#279r=-cvPvFG3Mew7yQS)*hWIb4!6;YHM>#Bv`Tl2bys_G#HO<-~GuQmSI9 zXzA%kwQH}EDpK~Ch04d27F|+1$M>1!kL65e)iTQZE!lm&$1Slq(+c6m9G001M#8RH zGi&>-nX(Eta&uV=YX{sy9|qacf&j=)+vvt#NbapQ*%xlKf=k3xJ}a&{*ZqfrH{}SW zfECW%t5a(jqGc+07B>$_{ZZ`VlS<&b`aE>^G6_<-84PR-SADZkaz7&e*&ByQJ*IWM z>YYb{(2lwcO1&S?XUp!C8xC zM(!2%XAD|D^)wqMHNRQ;GwPlET5Q8tD!cmn8}dbc6o?Jt2VRa)Jo*ra*xkqea8N&T57T;5?(g|HPRH_eYw67(T|(M zY%#{a?xIh4z|(Y5&n)1tzq*drl-LGj%6$EyAz zu&MDU^|?pS>iV%5Z~I2^OCv86L~)tO1%&FKH%F>{UYRVucK?K9%HPl2nBq>(O%eF2 zeUmarBgTVnaED-g3t8a42Rpt7KH?GtFCc8$siF=4(zcDR-_%OBQ57j(X^0uK+($Ke z8MP#^gB7^k{|@;_jC}hJ-jY`z!TMUJ8jo5UPIH$?wIkk(J)HvOZ}k1mk0fh3H33K; z0d9P4N~yv=gZ|%9!zgAa_HoMrB+UxK~boYr?7^x7MQ*1QqkQ@~||G?`s?YGMA_POJJK z_(rqlDEi9^O3g1$Ni|F9#~q@n=0RTJ`sHe$M$-&X?1^6l-=%JZCjuhTy8dBRc=zu< z3$25rKGvGrw+|Reus>N%b`CigxHzWMw|1<6C;=)Y$mcvoM^@|zflB@CV2Dq-|D-7r z-!|?D40pv3B5CwU7^ASagExl#JA(1|QZLI+|C9W!DP=nr!C~{-q0(LJYBv3X7H6(L z(G^vV`n)GW(3_Q6w}7GGO~03_Bqv)Go1MT!lqc_Ay6|7Vrn=wEj@HABh`Y40$KwR) z>WZ-rgFIT(KG+lhdk1#@bI=s$k4Mv+=ZynCWmCML0Cm5>vdwf7uNh9E`x;;S%~1KZ zlPH?ntM4C=+XN7QrxTu2UnP1AwXtD*1-KG{03h$BFOR_hF@*ggCP+*n7AhLxJ*E#mAr#Ty2=sDC+j!)^4%k3Z{=FE0MCTQPf@ZqK-f9W@jEyQV zr}Vc}DKvr<`6I|ONM9{N|8Ke%gfAF{E_h8E@)hdkoTrqF?N)K857qHHEe!-Zg{<+0 z?%au;Lx;w%102NOE|eZ zs`x$o56&%X(()n5 zix1T^FDQ@A(X%_^bI^-61(X2*1v{a1LeVP;k-HG&06z$t=N2s?wtHw<5O;{nivn1b z5E9CV3dD8^K5~;a0exPM@SG-q1x4pwl1g<)CDNgb5hB;Jq1M8p$WhSXWszV17gui? z)^s2K{f{wVBLpu=1w}wYX#q(cjkG}{j7A!ybHIR&91E-J&e|fw0>TrJQJEcKNz7z5VaRSy z6na#n9z&kU446ez%pS(vp2y5mNnCTHGpHo`n9(=%5^b4i%(6trVazxH4NM}>xfct( zz*~@F24LXmOmrKS#I0y7p%wgZAl3Zv5`sYW7GmqBzel4?z2Pb5~s2`T54*b62NIfo!R)Q{?j5d)A|0LUBW zY9|0`ze}7^iP8G#!d2+Kf(*+5Bq0vN))cWTo&=GA=q)h*D1CzRC(${%^-c@z36u6z z(sLHQX#?EBz`z*59cfQ;rjOwH4vJ8!*r`VJT`|%hMHD2sByn4+*p^I^pGg#Xt5U1rX-Gy`9wLdG>SIZ<|M zr{-c}S=9Pjv`+!_P%jtSaO6iMG&9VZnM|D--~l7)-Hu!Ha8+dpmqsNfu>z`{qFG22 z*hw^!@%wgE#Aq)9cZT2&Bv6fnF4~g-0f!(Cvp6*!tD!`8cOi3q$yJ!361p65>hO$A zgPpZpZzM|c5)!DHv}cYH--#1z!icl^r#g`^2LpXxq*i&PKsAZOIH{sVsepjExLxDahxdr}FQR$pw;<}z0 zgfr-|B9fWRGztg;*g>(AB<^+y87(4-0Nl~ zOV^PM5-12!r1Egexm0^%e#fgz>tPM2;G0-Veu6$v#m^Iijt|@FG#>%=`HSfM6zTqjL4#$e)@@ z_J&m})%#V=$dKw1l@`hR&Cq(|Iv`l5%4$sm6L>UY(9gfvzDlpkr#PoAFIcZHJqIcX z1l+Ou`9-=vW`-(uF*9@a5be#MxqDGs(1eD0))vW@6vg>?qsdneOK-3gO7yYU=OGzR zjgpeG-b>>P=Ks68!!Ir2)J1QB_L1;)$Mh7t+JQ1bZ6&nt9B4?Ox(zwKmf2q(MWG$U>;a$tsLKFPslmBX`N|J@l8=ArZkN$P$g`O$M zC~B$}&DJa?`9z9B;55Ia4^^5B&`PHyl=+Z+A@))!h_zP?nNpP!;?C zj%}Gm*Vu><6q6V=*Jn7@Pcf8POqWo4+l55H{%L9uljKc zjZY|b#R_SO8$ho2_1FbM+^NFnBx<@DT0Jy_v@Z*)ogf(gRCfTV6-EIB5LXw?J656_UXne`bcrLje3T=!F84r6VGVk}u}F&*G>Kzi|0z={*Z4cbLJ)6q9b zVQ$?QjYc>6k~i$eL^?sP^+H!hhnHcoBNvcJGzI)B71#lGOv&IFj_FeM6{6`Dp8vjo z{XLivT%iJXry_BNf{*P+&P(lYY{*%LVt#wqimD(0&6TT3IT6#yEl-Hp@7}mliZ#V* zZy0FHlOURzY;qZVJv|UacPEuTaT6KEcA4bvMe?vDyqYR8>j5U8t0I-L;z%TAdroNach&O;hPnlBaC#y@{*DxVv>oJ5L}n+B6Yzsk;=uq# z1l3#8-D11f=vn?Lj3#;>8gf4^7W@&Na}RyHMHX=r<3tuhp*L0ZeCF~stbfw?uw^E7 zVa8ejz*gxe+4O}I4z$CcN)>Ey*{qY8BW4+daH@qegN{TuN`xd-C4Qzy7Fn8pYY*3ZMDgg@FtE_?%_3Hs*@fRI$DfM2h-E$%LS<%xi?d z!3R>LHJr_TJXC5qvkejH#eHLI-wbAm41+fv4KEtZwU_7J4P+q z-^LIy@-@TX(aVlb0;I8I3t6Ibc7H0;eDl*%`P$25bD)kyZZ7-d1xOA}Gg?#jP|fU{ z58o_IYAwhKzvtk^4KMh)Xe4C@;=*AWKq!h zp5JjkQ-4c@%7~A4$1-JMw0A(php8X-Di(wUOO_ZaXJOxH3(91_E(_EOPg7_FdzQ0y zpq9v#u<4mg#o*L{rwLVIz(K$D)(BJC&44B%>w)z$k7>)-xZ{G3_AxX9rgN zl%^c)3F3DqCpa|hY!+a&PE90&_D9xOrWKmqN|f<-K6}d$SLh05o3D63=~zK|j3m>0l7W`;Cj1EfRcGTIe?i z<;NzNgVTrGpX;1-ADt*BUKYo^4Y^u1GQO%a&JtG7oK;wtH$H>e_h1f_<}tgz4~a3b zGbMHZ{22qvMoeg>pMs>L0;8*f9eBlOzS@A;q>{c5*BbQTnQOrPP1jJXHTw@d3g=&& zO%h`^RL_HRG{+)dxI{eCklp-ia=D>#>wKt+*Zi z8y2~6at;x5-TYPgXnHaIYtgaQ?%2CDE|Lsm(fkHL!!`uNyA9Q3Vf)3Nq<5R@=~8~T zp!@ItFMky3p#TdrAzDRU&=9}^=npCR3ODbEeT>ghfkr~0&RLOFDi*Ez7G~V!bEU9G zn^vJgd+i#7+WS}UX_XSljH0%g=4p7ez6dE~amsG(m>1#yruOwDm_NA2`}R%w67_v``)lRilP={ z+pnWF*yXOFuNdT)#+b9-Q5Z9yqkKNkn=&RigNP8QUoFN5Btg`s)oh_q;6c+~X-c&6 zURSq^GFNTQ-$9-S`dm`iU)gF@pO45rR}-ExKl=Jup0!ML9G4@QZjQ#ubSml>~Y_lUB^}7Z(cq&r&eHN3PEe^O4_TlM8wzhEu262`%TS9B3|&H z=TG)J#{}8lC@l-guQUV|b9OT$$X&_@qcg|FOWse`P}cS&^WF=JWVZ|M&0J)x{Rb!7|(@bw-WE6RO|e zt320w_uk6)s85c-(xc|#r!@hE`8%N=6Tjl$M~iK;vnNh*Hwq=T95j_wH}h8gq*1Y$ z$f+}r(@+qzNYMGpMZkJ=67@lbaNI_Q8Mil86QCv=C955{dsir6!Jcjd@J5MWJFkRa z%aZZ=T$!PV*#;%f3adqN$0R7jp{lxkN|^Wc#@9)#iquy^5uMNFKMPg>x*i6Mk>-e9{)6fAfwuJelJf;FSrOvnSVr)nWK-n^I!LKoYcS9$UU_YrHEYeSE+`~Bg z{6X@omWu<8SJ@X6n+^Ua6PSM7R{cvUD${#Sg+wdV4Nzi{(ZFZ#pgj^I8Vb4h|Jee*D!^ zPL{zcUS0^4Nv>D=d#mmE4@p8`?(FT=3XyUdeijd^N;uWkKMSGUM0UvoQ=;D;MrC+*m;*W zIiB}i>*HHT<@X6P%n+F804t~xrRFL_o$Um9X7m`YH@r$~Ok}G&!Kz)II8kaPZ>v9n zcW79SmpO*m8bbQUGZ%9UpE21G*oeQ)outWEB-&9C_I`_9OsEL-D}teBr+QaUDh2P_ z;Zy^Q8opqEYe!(Xk&#K|uO^7b|=DY{nji8<;--S-Vyw2F%- z>*{;$9o(7?7XQkTY1ReaJ3TD z;4caQXHJBQpo!tHYSZRTc}MSw=EeD!I(1#&de|a|j4mgq+Rl0_fVF^y<&CL!9FY^8 z$d{cNss(`4I|b3Sz=&Toa9sHvu-g2Fk?P=)aF%?uhW{9m|CbXAI96$rU{zUqI24@2 zXJiR6mD9aIPv=MzNi&8i?AI4{&e6^-W=v<;zE`Kt=s-#H|NK$3e^p3v0`nKe(*qiz zf8PNA#Bqg51KuS<5{*qQuufh>0)MJix_o*0F^xl(w||o+QY}Ry7`{0eJx`re-4Olh z_1*02^W-u^3oHOgg{FeCiO!jiD*TItJ5DhE2dwaH_K9xjan2(t3#cRu)!PuEoC3*p zMds-rB%vT?5gxdvu^3eVt#F=f>qn5v{fQi2;T+>Kn>WUd6XE`~*=Bw_TKF-31hHFL zLCbGFlB=n5quTPj+`o+;%uRNDKdHp<%qzc}`;kV=tC~xC?y(g2=1X zOsyba9R1ExmT-$69XC8qI5_3}GLfQaCykL~ z8r4+l2DwMi6W;wI%b=RWMMSS~x^uL_^%I5wk0yIl(|g9L4Yd2BE%Gnp{*rdg-3#*? z&Y3q)F*IyiiyH8C+y9(KhuM5}<~8c`(lztmhb?)<%drFpyymxcTgAhBT;k0{F>xBZ zNWFKxMVnjsr-hnvH^J%Vm+sXiXTO0|&8i)|q}r8!P1a#P8gkO%jZ?7{QsGR}Or zq+fZD`4|CmGktfoD34&*EYybAM4WA$SJNYlr?q`jdu{<&3!Av~v-UH;L!Vc^%lC}W zdlhg0Bslucw7;aUHugKtTXM6v&UpZ=e0f@t;kWO&bTvy7aMq3U`-922-h32r`K`kL zxMJyM?-fqC((%UDHRty42uNGtl^-4r*EtI&!6V@SO4EmM5W(UX>MPvsh z_JxvA1Hh?JNGX)`O9y#R2gNaz0@Qhjyc5jUNyaUGClW>IiUJHj#eM3eLv+%|cQWL5 z-v841pr?~@ypw6I^WkylBTyGJb=PCIE*7CKR=F-Vwk{w7lKifV10nO+yo)op>nXKN zk&Dc;@h%=;X{Y5bK9DSfDguv$6I7LQp@Ittb^nWmOFHTjL3E48cZ=nAi+|~s=;>}C zC2@jvy#SHEY=J)$u@@yK;FM41M`Vu@(@G?*0DE-|yVb8DSQ7b<(q@$n|qTy`Sg7uMlIAS4Z;NH2vzvYts01RD$2$c1!Gnyfb|%& zDL!Yb;;Vj+h09@=&Xs|LD4)XxWn$yAcT!R-hER6MG;1;tfR!@3+(~O#soG zfvZuc>+i{_YS=B6SKLtI_u4%$c}<%DWnUYiqIvu1 zc!W6*f+LqBfWA%V|A9G_dFS+_%oXC|+09%w@GRU586={u1pKl40)ik8mLddw%I_hP@xN_~dO7FO89zZCGjxZ%m7`P2P^%EmMLB4fQ7|Zhjso|}|{WLutrcB!8ppG|) zF-r?=%ifp6!~IqtCT-j%P4Xsb(z@(UWUOi@twT^!rP={XN_bS{k>Qv*lN>-YRD)gv z7NWD*L?erx^3I#`sh#reo${NQ@?W0{IGKVIO$Sa)dBZ7#VBpKt7Y0#Np~7YI^zomL z`A`X2n|5pQzvYF`p0VJe08u4c&5sk^zd>zT3&BLTyMb?6sb0Y>8*f*Ym?-K zlWS*^duLK6W>VK@(oSa5iDolsW;4Ix(eB}jy2@Cs+4^b?65H9l5dFx%Akrg{O5to_ zuYR~7qWA<+R;ypJr(aGqS4A^deWPDPF;}BC_r=1X`h!8ey}_4|xyA&8avFGjnL*3M zTuGWfmY-M=&{s-hNZ*2J(;~fY(ZC!c+9~Ec-3$fa6C3-@4+t~#?D2HlhpX_1_O2Ta zo)~rr%#Zp(#tA>?RofPB7~3 z)!69O*tuEU>|Mm57k7w^e={u{h8XRIEbU5>U7i?SoEQyj&6_|aOq3RJ3ACG0s2WW} zpr!H22?Eb!JMe?tN|6oU05O@tnCW0lC5Xt`xIJz5$ifIyXbe=JCvk^O>@9y=Hzvw5 z!fL|K5{w8J4awb&x@lI3ZWk%EsZRHZZa)wMHcYH8U}mB#r?n=lPhj^Sh8lSqk*CkH z<{L9dqo_Sssi@%3Jc&vCSGJgpsUDirzl>P_V8|YAMD30;DqJKXHWfTw#{IEadF*aN zX=Exyy9|05Y63OfmRe=rUy*dU_f0B-@$1OF^k0nbt44qoftM@13Z~!WO=V7DZ0-7K}wpf*4mDnJXI<*j52@zut6}w|8>%Jy|k5s4EiR;X@)i-qA*OI^lkET&p z+LlS8rWSWr)i#zsELs?ZLZm}C1pHCfyqmg{mg?zdF5fq7zb>0^n7cl-!gTyHuG_q1 z4)vYf^reOSifp>JnRyUff0{IRyR{-fuTm`&5G)henyDm zETi%_%|x~$+|46yx11fU;Q5gZGjCdHivDD?sigTAcmPx zdMjA*bk0?M!=Zc&lfP-Qyy^0N+em50-)KA4-Nwv+J?qxmZGX#;J=EILCK3>A}YR;B+bkBpUUQ3O=5GfYWxukp}i! zZV-hXf-#4Xf-u4+uH_Q0tUkl$&oy?-4-( zG?+g>1sylj|2!Be9FMmD8ST6s?aWBxLL##Via`-0ojdOQWz+flBtvwz&VHQNh#lk7 zRkcf`OK_R~mzyMYG1`Ua>~CD`-XCqMo!h^HF^M?Z7>G6hk+33zfYs59R}6w-M`9ZH zNJpJ9%fa6HM^aYzlxXc~k#5@~4R(Fh1?sL(gJ9)$5X0sCfitpq-C8?6mi8dvv{HCi8#w`O(pq+7IP>-Uj zB+%?TF&c3ra0*^OIWdVr-N&x_v!9w%+F9thbA=MWw>mYz99ip}bko8Y)7@>RPVF~O z9hN?Eo}TIj5MVq5IXw@Z=-fDsfCQdESIh|~5*X%w_I?BpDi88{bi#y2J@a(;)i}ZL zguibOvZFj#m?C%xI1i$8qhIz2IXh-L45XIyI9Im{;+jOD4qQ1cT_ewa!v7zjN*!Uq z{}v^w;Xy>vL85o=zsFKN?hd=d${RoJ^e<55G2WdU%hDI~P}YHZ#yNN3Gp97(ohz6P zRRg~79q&=df1)L*^|6}zo#i*Iuruj-(bK|_RE02>UN36ScX{d||EP(deAFsZsZyxr z`Wg3BW2D9VuTW*_OpW!=;txZ0WpnjTzXsD(>dP0JJ&$%4hUzPp+Tny`ZDi1nK(erV ztVX2`0>ApAS!L6?8wJ;g5}%tbmNq`$97&fAUi8JM!~BJvTX!q-BWf0aUu8$5+FpuEZv1i79I}Fol{#!JhOF{Ovcyc9lH;q@+hok8Ni7^S&j?MC?cxW`tfAZDpWny*YDY zM4C9WV_zz7=lT-wSTO?SS)go5nKU+fnch3w&?NZNj>5G3%a3|Rp}4`Fg7WmInx!S5 z^`Dg%f7jnBDLgGMDQX!M=f-cqON>_3l^5HU{0lj&ZdOitRy)Ry=bQD5H}jOuc>D0w ze_P$Lt(}b~bEw~VXs}=NyX}gnrngw7qINTMj<;^N%g3?l;#7jKX_c6}q7`(Y;?PR` ze7C&&`r-Ux8IS-CC4Oh>1O+lU`u>T3IIyuOE>a}E-J>IpT#Y$>i?iAUD4E@#K%I*vCd(^eHX zr}hu{;RK9flz;nHA05^&Zl#P=U2bQL++OYXwYOdGjW`C}oOcJb-(LJ2!QpPnmTy7R z?F9EL;ajYR#QFRoIoq8Ys?R_NiG5%tO{#xrTJZENtTeedI{4u{4E#z-=B_&xf>|hw z=rvY`w!AWg27%zz6~OBs&@_adS$95hlGZF&h7xYCkmHEpvVqiZ08-?pcZOVg*hqU& zifq~c6ma%Fd0EA+Y0g4}x8$-q;GNyBEOf2(3f%5h;btu?3{#v6{MBQTwsK|jY9&$)lV*)N12%7l)yuq+@IUp^I#LUHG?J`wAemH8YS(!<6K zX?(5neGDn0%5vV-_u`N9u5SVPqo+DWgWCCj6C#42JhRvy)SY!ntS^1S>rpgh^y4q4 z5yZ|HvONU5{|UP~1P9zlHp$iAapy%Kgz^|;(j*oa>RcY zk!lr-wc2Ra%#M|vekpmnUaZ=EIZ^djs1PRg>}{34c8iA2y89zn}2nJD#tlAkB@f*y+rr_4CG(1xsl z_AGfKW=3RI?{;#p^S!=xZJiH3=CgEptJD71jW>wUcllgUxAP9W zQ@}m)r9aA^9T!nfp?wl)-#Z8Z(4-WpsJi-3%6Si`y7Ll!Kk+2npeL5cO0=Ep7lTJl z>aQ;XQMF0GhW5{^3)j=pVXA8^4=(zZ)T@n2GgsLqE(SEC1>*&lb;ac;?~bH8$Jh?9 z^ZHy2!R{Ohm*uPprd$kLtJfq?MbZ)Oy5TAdW8eC)2)W$hW%ml73M&Ngj zg{6qdL>^rJk3089gq=g=yL;HW_T2ueb#Oaf4J+3&8^ z8SARR%zdQ?J2nOqqv=miitE4aIpE#7&OdEozf^f%t z2i?i$8F*A+V}_xF(wW4Uua9*WcJanE$UR z`Q5pu;r{m>UiYUXiY{8W-ZO+a4S2Q6LzTq7iv=NU?a+shyNNNWi8b+V{V}bdjPLub zzbFtc4^ICCi@1&_jA`V(@*8rixlTZThyKIp3=vsFxmDCy3cp%WE4Tgm`$Go%bSJO7 z(`TlCtQ393ettiFW!3!4DW-XT^ZSPOqr~l9ZTISlDSfriD*&6+gDv+#Z;yaiLl#7*iMYA@YpLyg!10#9J#GImru}+TL(2J#X7WG; zxO~Dy>_=y?BrqD#;|_|VgA35P9MHmV&ujr(0U>noAd*kFIu6$yj?{(l-b9CMI=l3~ z0PzC&##cB2)**<)>wuOxh{KVY{u87j5Z4!UT@R<84gk>wGtvj~a|8jIgMAW$?-x1> zkl0Cx20f(!3>ndHu%xTmm zQPNu|1{g@eLpggI1w9NqnQD1hmgn)NYHs`_&J%5C-Mpm>ElOtqQlToipf5|@ea3)4zwXh z$n1*{>rJvr4*X|8pJuGrR?Hv=(%U+=?GR1#(eJHjY*0T0*a5lW{A^L+{sZKGpo99a zD2a+=V|F}ZfB798nT3tuqmPmmb6V&R8gwNoD~uw*AW|D55y23X<#1p}bPYB*ki;&l z-{GsZYl^O2HrTEPi^vFb)k<=>^bjyc!Q1l#9=~t`cEqKJ5kN;>4idxVIROe6iQN5g zdU$jnz8H2M4X2BQpT&1h2UmCsyw7wB9sQh9369qEuOR$PlN)9~9c#b!nYbwFnV!E+ zzu#=7FKtoS_#wX6=@&E|iblD+fyqh5;);`EJNVLfx$wDmWY~9Qz+L30HoYA`YJJ)0f)8&7P@d3 zx)e2hGTBBIjDKpU3)-297*!H&q9-gvrWGS1_w^9J*%48gG@*_N$Hag%rHq@Rj857# zMXubks-7f zq3xNz+MeVBPu1R9hdzA@81F#;V9U9*juj7g|I~mMc$(v?o5KXLOkX9f<4;wc%~fx* z=^d~|uzo6}_8dG;kQa@ZYKTlP%#&nr>8B4L6oNouAgv1&%uCt3C|U@e*vLudj3$^< zvNOK0?Xz}x^)Wq-)7Ek@bX}X+pTj=CPO|3s+zIoGbVAQseMU2*(a>z0J}|5glGB(& z!Igd65c8!t+sFg`L$O3p*S`RgJNY7n+q;wq5<43fB7JGmev$h_ylmXYk`Uh;g%kby z=+Mtuco&;$f1lXnurQDVuzFb-^djPye$Zr5^rj8y?M%1_Aea+u$Cy)O?@ba1NHk$4 zLo9ni0Y&~7wmuX2L6DeE`XZM4g8bt+y~YBL^ML$9hluck$Cw~cv9jaqs^#;_1=6ZO zt4y(JR0};Z8V*_F0#w5xlhYXrg?4%ai1$#pQ&CbiTwE5SGK(0J;wFkV!1wfuLi(q& zpWaUv9|EUbKsp9LGhD>5J@l(V@ zi^1x_FZEtNB$p%=*wK1qv(8g8Qp#tQ5Z$0&dQY%*dKZ1B|DXW1r>i_YF)cDMq%rt! zzbi*!I`6rcUQtt8p@T039yA-x01hgdt1!X0>LjWtnjF)8(lT_!PrxDg29mN$nAl+0 z)5{h{y)WaLA+ztphCEV)F3DmvV}HWJf^oX7IQo*Mx$GyeDVU!EB=lR~PNNx1MOI+5siM6_2DL!Ah`naLv2Acjn$G|dPh0O^NJRd;4Gi>GAV zs15{kr^|f^jtrDR1(AL&`qY5rtqyTD3}3zmJ(&;3G6TSj5EHo5ZFt8A0O=@_pc+Q< zs3oCNG!NFOLj{X0iO;V*cgb(=j$rM1T%YiE&{mNoaj8H33uljPOQrg?tJ-eQyJP}} zLr66|7FwAg-cl*K8!mXItAhbYL-hrhKoMb>K5xAgtI=Nq873^G69Yd~~yB0U6_erDAF0aQ9G8$ZDo_Ag+ z+Ul#EMc?3H6W%Im+uJf+dn~}$*FV5a#?mq*PGYy9to(iy3UsnS@Joza_H~Ya7EI1| zW3-fV?=vJ0qlc6(jQ7DT+k+)XjtxgFSK3<&2kAdGc%lffnnOZV4b_>0fdJ5~=1_b7 zU{oZeoxi>WVF_o;?Il zaa+-MK&tskxg{K-I2b&8?!|k4>f%38)tZlbI%>bxVnmdk)7e8vlH4;-`%YWNRVn(d zuX=?lAvKF$KvYYPvmf{OXULD%y4H!m2N z@|^UCyEb&>?S61F=`sLF@qK@m)}g2F!s%i=W7;02ob&}`{-rM6{@U|NwJJyFF;2&ZwytqR~xHZWK?#A>RM=${2*4- zr< zEGuHSE02Q@@JV*Y*mb*WVmGE!@q3YVmO~?qwvMECX8A`I_^o!Z;oXI*O(H)=CRNqU zNFo8w0&+78A6Ac_SthD2K5bh)QUoGZ3C)!)rjrvHG?%snMl&@#ibOl_`FBPzk`VHc zrT-YhN{+@c5YuH=6DX$<-jK;gcSTaIvdbPtBtFXqs#*k> z_uj=xCSry+$GE8?%6oksW}|t3Ijd}e3!p3<`DpH5uNxQ1NT!BgaP|XD%cMDs8>9olWcw(Qc?`mM;s#n|ZmNt73zcMRrb+0=~ex!rRF5lm>By z^vn8usvP~8uBfQ zJG#wG^KZXKAe$kC3;4_OVC;^{SGM^B|6NK4WelyoZX%fFrG5i`HfN_!rqNCjGY%^_ z+?-!%^53To_+xDukXNqy0Wg&CHDW(nH~*yrCb9#(3wj&o^mG4!V=@j^_A_>3dId+m z|3cviRzg+}|0CXhWI1U=jDC?gB;Y7=EHfhDbu_dZ7cTC53s9I2VCa9x=hhH$;-GXZ@)}>bXh=o^(Eu-{nAAlNs3@K_ZN4I-o< zjg!~J^6J!pBoXv)R^`HJc#L|mZ+InT{)5GLq0b%vn2tc zko{z-*E@D~LLm9_@l2ehW{O1cWu)FGj*%?UxWz9F6Gf`U@)_d2`odcyWzQ2%L1bE6 z>S;PfrmYa_J^eJZnYLQxx{q_!N)*s7;D!kcGD{@(pC_bAoF-jHRsWz>{;YO&x$|h3 zs_5{VL_RkD8maf!aZkqf%?*x(A4)*-pF5YF{}ssool`BbBG6nK!jW4kL&n#` zFH7-at+Jb_nX_B=t|D8N+&v9B0eKpomP#^OV}yVLgH>*o!UM-10YxT{wJOC&0if!y zY=&Q0yO?9-1YbYFm{-5PTT7K0Daw48`Lmjcv!Du3{aUpOU;7tM2$E&k{2%`RElSql zt$23N)x|b*Yt$ulx>mDf04TP&n|-`HSDNHWyb33oyb$h(A(D>d0&3a z6{dpTs=QeL@=lI07CerW3qg*DsnP(nv}7&Z#o)2L%%2r^50(=b;5 z2Gel9bkScS!VaEhF%rajtHB&kPZxczYU?%P&ny}(FwVo~aX!Ke)NhlYbp72xMoXP0 zVE%RIQogu&2jD(?)^soX@muljyhk?4+XY0(`?#H=lKe}Xva}8To$|6<@!yqI>^`;? zBmPM1w5rgi?DUXO35P~XY9jvPxx|zNv(1fW$M%~V36>7xie{%S$`_K(J#;!P&R-vS zNV@cMU|L)T`CcVbhaYeFIuhvqxo{j)?o zN8qyb!DBJtOzM0wj3nK2B|`Dmb3MxH<;4cZXHB1FZ>s;*8AFTuMei$18#8|`0HUTih$P1Hx?SX*;EfD z=H+Lc^@M>c?n;Bzse)*7VWQleo#YNwxL~?*7>PVshB6e5U|m~=XyGTO{*@u@z9tYA zu*`kZWgk*I*d4cqZZ#rVmaJbUc%Vv;#K-9WfGRWQa!>vPs{HHDm4B)|7OvBijp#DT z<8~j5FlM9@Eq3MOPaKQ1a*YyUjzyX7?b%x+%ox}E@486l8jGixJv?bpe0e$+fkPSa`ZB$Ya`4Jm~FlT!r_F7rH`ppV|?uByD>qw`!fE7<9`xBsY9KI-- zC};81ES@6Xmqm_oAe8=zX}>v}YYW}BjZ0??5P7o{~#c0L?Y9$mcBmjYXGFiMnYmr;S2^7Il+T~p( zaUv>0^1_-phO9sUzj&C?uDnpqhH_z2r3nnDfhd5TjcZT?*Swujm|Q~JE$q#rr|xG+}U&YDY4$lj8T+_AQQFdCvCL)t;- z*-K;0CxaXa4Xl;l13yj_|EZyVRFzG%&n(|K0+N$UO~r0}e8loSjB4DQmIi*ei&@1Q zc&uepi?n0?=PhdZgry-w$xzWmg&>lpVbjh0bph&wiHQ!td6bQV*X5maaz*YmQIIeQ zfY31SX{8mG(RysU5c~f4@kU5LN8vKrVfIv~bLuX~#4~_E*LVTHU*^kpvRJ2nVDcz+ zhDa{gUGf(-m9$@#EFKHCMJXNCQ-)SC8gnavqyIi$sN8gHy;zNxk&FBlyb)=2Y4GO0 zbTikJbz~=wV^|HI*t;BDey%^aOt0e={hs}!A{1p2>C_l4{p1N(=Nm;*9Ym4U2ETm2 zo#nIo#zD;|Pm+4Cp(Zcg(+t@mRw_egFU}Y+-VY&aeyGjQ$k-8og)hMmxQF=Z3nKT1YjM3ns+X*VUFW{Wb${ zG)=XC#cv8R*_l$#O?MHybB3v{@DR@VGHke2cE(c1%Q;Pr_}7*5^$+TKNJNjjM?D5* zlE`ucS#FX+A6r}ZnYX3i?uRNdE!*#hmBucd?VCQ{&2%K-&VE>o2j~*rQN$6pgQ$QH zJ-gn$<_~$%@_8e)zWd3;*D9W-t8^LJk0swYM}6}BmA)m~|LUR3=a}nXz)FySK${DP ze#;YHI`~l33QB`NcKrn=XOM{h6B5L#CrToIpT{4fF+5K%ttfs5OaGkJX9(yK^5)}? z?#|U&aMZ*%xvJZa)2#e{|1;)2ZK6J$uh?_1+Y`)X6iZf8pXMm}LSi=NyBh)duPuQo zZ@FFGyM;q7bb53E!TFcx4bnG{g~W8W`K*o*)zg;$$yOM-I;no@tP1CU#L zcdnP|mi|yC`TZd}^j_KYKO0%1+s?!JL~1^|z*F^4e)IYv3m;xC9Z(DO{Es{L7X~cA zobA7^fw)=@!wpU2dy^V$%>PHo{4b5im7xFs51D~Pok1iNwC|BlCSCZDStPZ;62D$T z$D=%sbT<2n51HK=2ddbVK69vrk6XV^cuY_X(*4WU@o#QSF4gSysemITom;Bg>z&oN ztd~)%Y&);Heq@hC3%ZF5@BGNs&Jg*guZ0(DYm$UBku5|2Z)-=|vwGfzX7{7jg_3%{ zrFQ?Lhq}Re>ZzjeRcc@l);UWN4wUw%#=Ecv(R?I9#|?tNhT+UU#5|WZ>!Y!1vNBSa zt{=xsjN{ZPQfh7HDs^I>kY(bn9UZ}BkJMWl{`~5XduIH-rSWKUG>}87(o&5{B80Ro z^tjOHOeywZAdd2te~agzHC79mjP!S2r?K-XBz%t~uP^tOFnuxUIRBeJ1Pyb#q{rGY zAb=V_BLH$YFb9#+PQwrYs5Nu&orl=Rq15^fc$$kh=SnDx3;k*+^GhTP>Y4lWDvCP4 z&?J)k$5wU}zY(Wd$O9mpfYyROvEOXb!W7R`qi=luIf*}M?X#M~wmEy2QjvMQw!YYU zqLSssT7s$#WCLsF(zpf(G63KNc6Bow$qvN~1*y(m+xcmZ-%%VXK0mw)(&3W~TNy#L z%3E1p_merZeeX1Fq z7PbojJ>akGB%w^@?;?I-=+s5_YS*cUT4I>LhgPN3=_`%d?w=mUuJEYwZe^`+I#+m6_KEO<7n)h~J+ z;nH5r`w`y0ma`@A@O&tNr$=hu1sZza1q1v=C;r91hi&i~d4D zvlrRWF$S(%|Aox+##qH&8{lV?kVK-$U?R)e4t=?!Aql;(P zX9qYOfIJgGqSOJre+VZ|?d2JzZaWt{45W(81aT;JlCtwcK452V;;9?c^zH;QlV^by zm1J;S=s;T4EK;5RF4{UL|C5?-;u1REgM`CS(P0y?hG-^n(_t8tJRAR#buLMv%y)16 zH{$!t!ftl)KPbuhD9SLU-lzJ1!nfZUGVFTD-M4WF&>+vDSETQ)QoS2tt;$M8p;cx9ioCco&2UucXrm6xFZdsH# zI}+ltgyGwgj9}6@@y9_u>NHJD>vGdl3cG(If$M8xHy5IkL0mRL>xoaN$rX4j{)GDo zzk4?NO5sh5YOsDtXI}J0*J#9H?9D(I=eLjY23N$W#$%?PZ;uD{i5M_49(w0+W_5dNKIvn^_wnruYnmZTh1Y^Z<`vPAPo#I)xLvA4zkNx>nOGN-vsXDe zKT9>Z&J|yNrU1dkJgDeeiR49C9mex?ufpkwo)6gm@H$S zs4Do%^yXgYx9hz^Y(=FelL+~)8ZcVi`{$t1a5#NXROG|1ImgU&Phlu@^*noG!P;20 zaG+MO(m?Z^Wt>3H|aSNj2K2tEjqqayy|mq;DN^KF|(H#pxO2BxuTTbMrT z)bjq!V;)j1|K!`)fCgIrA>mc7(}9Z@{+#*H9>;nCNCM*LGb2n#sYhKE-~|8+)j0sx zQd9X^Egh*ub5@?wE)z-3-o6IzR@rZzAEH|4sI9%NmqqY&jTC!3xROb(pKY|c`P$=Z z<%zef08ozT!@qF(ZeJ=9$N-g^zQ+<|sx;O(k;A6^ZcLG)0Ddjo%2)O}1Z@np3 zW$t_V>zAoS!~B73GThbuKLMWHxDQw1ECS5P^gqEL7AEjU>f-wpP-QAq)#b{9=Hxdv z$RhHc2@fQa2Nmd`>A!4`<9;biUn2=EMiw}$)r zX`6*~@Sk6&)FdV-u?@wP4?KBXZNnZ>9l~|U}R+Ki(azf3mqdV>%I)iJ|gx|?b>NTaF z^U9`Ya=tWs@1yxWo>AgN#!c-DKK?7fSkLDzh*N~Gd&W177;PsW0MNzH(Df-Gi`j!e z&SN@PW9s-jc9}mfAkA_B1;)e_AD`&9LOVbp=07&}>Od=QrT z3SoKY_*b<#4n@?ZW%NZBAoY#NNs`l7b~NrgWxnCsH+MXgE8^exv!{UN8V4H(uRLs^ z?OS8CjC-lSlOVsl9FtR2p7*Zihri?&*es&ZzcNz2dY9V92OZ3^YOoCy{N&#FM~+6o zmSn(=*@x(-PTy+GKVaG7)``nkNf}r9W^PNZ@gXVmzw7jPt}{9!$gz15dNo>(xiz}q zEWqQhf_c-egR*TlV}j%2oX7p4FXZfAe=x+5IeC5uM@WO@d`({WN+6hh&|N+umR~o& z2Rw_`sO`3*K)BjP^PjD`8cv|Hbi!U`t3$Y*^PLQ_x&7SvjrXSATM)rLPG2jIKgw%5 zY2)awWqGk3OB<)pVnLla`T%pz0kPy!uN4hadaW}fqBV(47!Z{Kj9@JA9q zQ#h1MTsZUepLPF^2+-v9(dPBF{ph=%pHTBr;`>v8(w59*o|pGWaddY~(2kfBcK6TlzmRN*J@g@LX-e20T?<5Y(OP@Xg zcxw5^LE|Q!lcu4fgcHe|jxuLEqW^T`uAr}_|Ha=W$Xv?Hg)job7y)0hrKBsBrt8xQ z=F(wT=?KaUV!{8k@ld99W+vU%XHd^&&^Bazz06<`%%m$!1E*&&CT6nkrma+Fa$aR} zH)OsW&t%ri;-$=DU&diB%tjd9=Tq&j7zp$V)o+(`G(nSWtYsSSJ_IG zIf`?ViV8WJK{;x8IZ9SCD*ZXeb2(b9xerrgAfjAzynM;}~@P`kN2kE=WsWxkhSzK>qMpG$r~Vt!CVe#pHbl7jI8$U`KJo!Jh7CgCL|kP}&J{0R z6=Nt%Rs~De^-4BfO12YA0`zcp=SmK*O8l*GM(|3{^h*B*G1t44?pQgRwv}S7l!Aa| zS9nFBcV+HDQdo*5i}V1|T^fSxGD0>)R76>sU^xQ69G|K@ngxL4l#xkMCig%4wu8lQGjdhKU-BNa})Hd=yqD&cmrkTz=lHWvMMwwrd&kaiAq`}3wY9=GsL(Os78y+p#<_%5BY$(@7ubFT>m)niBqM$-wWk$rP&eT!m!F~WWE=)R=nzL-8a79H;E>k7Veu)9-3hvSR@#j-yfPI7>ZmV zoKPF)%Z{9$9gw~mXk|yRI%{`@a7GIgR@nTm)9?Fj^E)c!caG9f>frA=%Sr4oi)k9GT^M8I7*D%j7@HFte`PQ(*gP(b~Il_bEtIC+AZvA%`*7f&w&=CWw!{0ZmGX<%vYb4AT_g}2jagSk?Jxq{}o zD&=|f?Od+GT*cy?smOeG=v>|6eA&=^I^n{H(1qI2xm=E^P{Jv`v(Xsa+49|ngpL>4 ztYF5RSHZf=*)h91B?%+bS~^CB!G zT|f$NY=W@JHR(lm(Tns}=*h_9Mfl3!gVo2WEBnUFd&P5y%4+}>_-W|cD_S^V>KdQu z8qeVpdCS^s!=)9>nk4O#xZS#B$(p3yy8PXm^zgcb%DPU;l7h+qUK z>Xzqy%Q~uLTa9+jUvyjNZuKt>++Yc2Tq3YGIbf!;3i8}cNMAfhz%xr$WJS042)6=S zmLqA`K8r5!-F`fx{2)5wn=Ooo~3|FuWFOxOYgn;tSj6yIb41+mi`9 z{I#?V<=me=T+e~cQL5~Ou_(ru?8^-9=N7_15rl43tgoY3697=_rOof6hf+(&hYx>W zOPEEwwH1S9r;-Cj+AYPUZH(QXs>c$|kG<8qKNn#elxZ8sus?v3qwW^yt>`A;{&nFz zfUxB_3meXr)Cy&#-Bp17Ii@{)Wr+FCxldlYz3aYLBzh*cban=(`i1(w!G+h0E<)@+Z)Fk=>`Cj$CQ~Tp0f8N!gW9-PlR} zL#BFSn6?E<{iEHo^>^u?z}>%H*xtb*=8R+a8g?2bIUC^i*PIqFmjO>fgLUF?#_snY zrIw9)+8s#AiNWu~?UaL@PrEB6XW@2dB)``*hOc;N|2lj+k|{k%<2vLL{d;qFad&qV z$yIoTsm?aNj5j(ET|N_6+1)Lk;}_jiRatTxhJnHfvXqxWfVq|j3WEdi>;86bXYm-6 zPDo~So*#C&V=y%vPI%*f?)mz>f@_PJYo+*pkM-w9!_h?_=jyNJf;KJy02n%+tDGVj z_`L4fc;2`3)h^e6oYb8GM>EY?5Ne%c<91&{a%M}l@^;mexs~zV zFH9nzV$HgvcNFL461aulcf0ZC4A>n6IaJ6Dj*U8Oxbe6^E0Su4pWhQ2?CPt086C(i zG6Xv(&}d92@l;aj{>gfqkgSMJUZUZwv@KEmHD6o zqcUVKFDiSydW-1&-0v1kk)VKIT!SB-OLyje9jYv&Z2GBq}qHN>=8v zGzwDv7(&b!b=evBhVxPiU_?FYO=8p_uo;;mTE3V)Pj7W^;^I>9k6jxVhc6m=B zTM>h$aCt96)%eOM^i4kzhWKRz&^MfwfZhjBq>4V4Py{uCMJX&e`yZbb!Te)LR1$=_^Sw-{{NJtJCC_fcg1p$odkShM*Dd<$JBR6;xd(rLNm7H>Oqc28_!`$m3&S zOA%3@BWNAL!a6rC0uw^#FJjl8F*^}c$b=7bO>&RI|)TDR><`)bK-qT3;_8MlP9sPL_1Seih{@L9bT9 zgZJ{H3?*JKMGY=1Wu#E5Sz+kShz-PlO}3_Pj|KfbC{7%ztcBMVS| zkmX|_t52Jg{R@(Wcv7PGa<&wY%2mEqO{F|>QC3iTxMcpV{<2b@hX?#joAmuGk{6oJ zYX8EIW*@=--ihI{-*HUyL)bzo`iV!{eYiAfzG>c@g->A~Pts}e#NzIY-N0O5a)p>jHD@z?2X8T|w1emf_F=Uk_ zp4*R!+vKUW6DVp;>3qHj7Uq=rJw?9`*Wkv)UIY7kiHct5;rVVyUWb$jGHS|SkBux8j@^h6}nIu z@cA}M`mtJ863u}eRb0FTu-e2wm;;Ua@xFt`UhZe$j)kgg=CC}odTvw`M@;4VTva}f z?$uPBV#_0P@u`=&ogO)ruOj44JKD!-^K+!e%6rC^bSZ)rKSeSG^S2k9sCJ+bR7k?X zGm@L?*jX!jU*;81D^SPfp7>3O#Lw7}lv4McK`HmTHO?0Pq(@y$oR_`czqCD*o^G1w z=Cp$CB3K6!UbH{f$Xp-f5_ypwF2JSna(j@@YhK6;^eUeW*PWc+pENh#GiES!u$_x zjvkZ84QaOIRmaT-Dx2r@RqUnaoB5N-Iws%@>>5e(jh_$01yEiI?ZknC(|3b|=OSNT z;e3=Eiu~8{HNL-Big9hVM6o9)j6+43A&6c(DPAM!BYkSAQZN3%w6|Hd@;~iXQXE)6 zR_deNGF;2l7JE18qnDR4`E=Du@bwxv$_bCTVakqj= zGS5G74B1-M(tKA`c^hexdSp9J^Fq0=Cila^U;lfmliP!Th|j#2zhrffOJDu`cL+-B z+Skre4$I%&6S<<_y}$j)>R%_l&vClXa#xn}p`lZoGW(jq=)&kj-I4G1NtUW8+sJc< z=+}gUS#X2YKTW512M)Ql`X^79-Mz8*Zu*R6P7`XX!|^)5mp*;n zEGI9TffZaiBcj^@FR^Ss*lU4M6L63Kyu}_|-@+Q+xD79ebxvyHuK6mG_=be)D}$Rd zs9Kv(8?N^PYcB=RZv=d>#3sgT+)iH>x4sP23j#0jV|TW-qTp{ZZ7N9L;}x*U9B;$8 z*xGgL5689|tX7v(5hceqhK1Kj>eU(*ykt^ByB#sR0ph1G>USK4|2kH1&ayxT+n%on zx37u6xoA_ufbYMhi%qgMjw?1~MTG&_8?fAH|GvO?mTWtH^LqISaj$i3+8%T=t1*UK zKnqLifJNw6$Aj$L$NNG5foibg=}=UvRoeE!5f1Q{lYEN{QAzi+%lH4rO*oPtYETrq z#t+j}>PmO)8UegqvG3B5l8)yN)wX%?^GF-|NE>8#X)Q?W?MoXo${6xWf5XLA{(`Rn zZc_B=Zk*{cEWbFBB*7L=t z=et>t^A}m?WLc*#vR@y`x=Qu9XUkTYg5@Xzo_>~@4(?V=?zS?6)T&7$eZX?|J~VxP zDKmkARlWDY*}cKS*ue|EHZ#2`+j8OSa>3}{aK^qUbZ>}8U&NVQs99gMR9~x?d<1o0 z%%i>#x4u~6zC;`O`1Rg5&b^-Do!TsN&xPf%7o>n{y|r?Z9l_ws5dy1pY};@JNQOc| za(`iR|NHd*lJ$P{S%29=e+hV?lu@y0P@!x>p}eWTl2@@eK7itBNZpQ#LrzIXE~mIJ7=E zd^Y$SJT&rXXq53mk?MoG0ei0dwEBp7p`{e1l&Ce7-XKujHcEc`Z8y8be*%4$&W2I}%DS1#hK)v`)C(+x6@?(Wf`x?CTDosYmFqX^PbBBoJdzEKkC zQCKm1mrlQYh?;k@8n&4#ezV%&!IAbNH1*^t&BiG0`6wM^3`sgh&osusH)doyN>;5F zN>xh{Gm4k<<^=twXI=b4KZGNRfqim}ePfK{e2fz^&P6)T%{0!#H~w5&okP0gp6u&r zCa=O%(x%#cWlAQ6XDM$NYHZ%i7TPZ~m|j7YV(Tr{;bAF|@U`rN-e7&WmOA7mzeA40V(W2Q_n z5JL(-idD#a%Ul~$l+8K#6GZ#-!4w6hwj;;%C*^5J&1rjS?eDhQ4!+voa;CplPdhhj zJ5Nr3Uz~P&u<_h#S#L~P)A(85`j{GzjsGf}>oHZ<)`oyGT z!>3~+r!%8J196+lr11-gnaNVl%j(ieA)U!_*UPij%MGP3DAp_Voht~{Ls!qCo9Bul z?}|z1OKIMf^39h>zbi4HOPQRt?b5Oi)dB+Mrm5!?+2{NX-g$OSHS_tUD$h0F&bLAq z+HU7t_^>Te*zeW!ESVO%Nf&y)F7)~?JRH#V$LLfj&-vYg(|t!9zD_kl3|f`-vfby$ zhTe@cEskq029W}k<)ZA}=O?8XXJZ!Ulo#i73>K;v7dQ;kx~A@HICT7D=HHy_Q-c@R z+@~A#x-o(KE8jsK{F>4xI-e8Ekjew|!18>hqPM(j{OqyoA zTR2u8=bC_ECK)s)jm0aVCGKbZK;Sm2xy%!SYuYq}p^;f-lrg3rUa@qW0cfpeb}eI% z;M2C^)8TsJ)ZydR1+)BJrEFPY{;O}gZOUY^*mUf9&(ey|*Ak39V#;#2%D-vc#IMRj zyOKE+TsMjT{BZRIg#|=_fw(~6F#s6u^~v}BinL+V$eOT)SPsyP+m~BJH5OL6n~kj&9CjaUn75iN0i55kZWcEjySJcxo{02S_Lsosi>>#f z7S<}8@3l4^hPQmeh7kOoU;Vb4aV=ZxHt(@fTdrE$!QE{S9-4>mgE7GY!@(bh@qN0t zBRM-HTJYg4AEH%uKHUZ5q?<;?ex&C0q{`nRnb~fv^Q4=?x0V4!cH=(`cax;cJeoOTk(N36hE;k)^WByMGto?W%jDH z_I}B2Re#&7_1mk9-K)>tYpB_4?B1IJ?>24j{q*|ab-34hm;Z`+yP0giV=6Xn3O`6@ zzq>otzZ<{z+kRgzF&@IIrhAi=ds<5d+c_M^1cCi7egDvL>!l2ez79XQX8mI?4wwbU zWX5+C*5v)|eUqA}=ArqN3;=wwf3KepncWoaurOa-I+zZ##mLy5ArBW150+KzuCF#F zus=E)9S2J9pzphaD~09V}WLx&iDBbUs~AF_~|!ig$lljm6pA#I{oNyJEJ#VqL%8G+&JM zx7q&WY!BHAJMO9QY~=rB5r+LcEF7|BYlb+6{XiqcjvZyNtpczO0M1HG@gO`GTE7Vd9ZXUFiJeR9~s0O9vI&d*ft^V6Oa_8(|A zj2%bMAMry6uAj$NbT<^n!e8e;}HIE*`(tr)N?4Z z<+z@DjJQ8t&pj6ZWMfQ*q9gkv`Qc3F`CVFUu*hu>a1_r z>nX06YMKq-U*KDEo3bf<(GgvZPd1$2&%1L^b;xZPQJ!o%U-W9NY2&{dY+2LRo$LSm zS}%GoA{S-ydrv&p4$s@c?5FjsIhh?g`TMz&Uib4#=VLl#axZA^4apSoZ{^o^%YFYz^Cu0CITHd z6_Z{&Z#E^6Y`svG)zx#u#Q;#A%4v8Zc#{vF9MFS3pn)xK3n;I+|Xb? zrdX%eVzMUXI@V6V&hk%gGs;|&`4MKFu@H&a z8yz0gp@i3txo#H@rsE+(aoC|QUsfmM->G`g$N@}%)p5H^LyiB5Fk<}(%7GcrqmTw< zh>ymnN`nxIG){oa*RA0K)gPQG#*7D(^+xx0LI_CUYl;6IjxE|gY_U(woneAWp>vT_CuaUX4Cj`gxjI65w$*APKC?7$L^+aXnIo zcy>KPk##3KQdL5JBSuN#<3{W|mDy~2!pFu8;@AilwFF3Df`vFBU4GL8R41U8z}%k@ zo~%0iI4{99S0FdVmU2B;!)5G}S<>mRGmDn*U7tmUy@cLValJ=cBM*`m2C=8fc-aMc z;LohP;)$_%R{42$c)NK86;}lXSoQamdxiNmiMzRIh3GvgECM8|v>9}5UHS{gW>eP1 zfX`k&Ks$gg?-MOzuNsos+pnIocy~}U@lEKUcFZsM;Vdz1uefe5)pfrV!6=R}8!^8s zU;&N1J8A}%MIJT(9V;qr`B%XZ)CwB4E^ED-yZ-d+h9Tsr9r8-}xa0D<+i@qJcF2(! zE|q>+E3FYhnHX$dQLP7ylpEELMe_~?;KENr_wzhu8|mj?ws|r19RK?HfJn!~qqN`| zycm5wFMQfBwLDlkEV`v%^_#o&oz0jsl>z&h1Wu^qkjU%BvvGAJgX+;1=273UP`+1z zxtX2KpLo!?Q3H#YcpVCyUzhJgzc0GZ58+|l<`4d1T(%haSKR4TE>;6ydAwTnJRPcA ziF$44ydJ+5`F-Qc;qcWmXxrebB{1$#pby`~U}T__3M?dEna6&8P`;%iblA9O*LVb) zq!m8;_0P`jPcIyPGt$GhEPUE0`C5$}#D~q8=K$v%VOwzg@%>-@mm~L!R9Cpi#p(~E zJGSl0hm7DpzOm@dP88Sc>#g7;kDJpYt`hOuIvd;HW-hUyCI)j;HwY^=OE)o7ByqOd|a^24p%R@i_ z5Cwx{GinhYWEhe~y(QNps7Dk6709Cf*V`j{MHFbPw)(+~x0JL66!uLin}J+jR+ypl zXLv|9V+oJ_&=i6k_7Bf` z-cW*L>IQQtAZq=*6`r99XVc8^$BKHCr}5vbn8d&I4O$4QdxO-x#PtifRTxeaXEZjS zr}Zi0o>U~&QJWxbvA8seIumDzcvw$CHjHEdKDE3%oCTuYWp!EzOq3;)dEtU6Lwonc= z{4sz$C0+Pj3It*2%_1WJcz}rkc>R@`6vf%E==;_2H#IU}-#iodJXV}%EC}=_c_tqx zC>w=`#5Qv%7$LyC#c3Y~U^^v94@6HsC&ifSobO8e;&>)_@Tur1>uRrMYvy-DyrzBAoKjQ z?<>US>Q=fo_J^3!0fQh`vEiYv3dw7QRi*kr%@&8n>Y=T(FW!8w!Fhx7fa~#kKAI^u zKW9(0RAZ)GSb_0$OZ~+6qO;C-uCvQ2Nbh5N;}!iR!<83RfbRh2ousS;)g3tC_5GIX z`95||BUg&!;18yj8XC*88Dn(K-@@yhv>+7&dE7Kf{TB4b#P|zuQ|t2LfhQ^`3}bGs zniU)Wih>@GoUp&ZP!b)4*sy8I2ljvQ5%cjx%!;gOSI)K0ejSOs_(J>^@@_EXg=W$OXR+b(7wwzYg>~-N&qD_q z-bPu^&GyBTctqMZ7O)|^D<#zf+Bi_L4UI_JrsbY+a58E(ZFYm6<@aOdK* zlrfvzisMV@-xyB~kX9Y%kQjA8r%#Md|H()!z-sY}{Q8U%hXwKBso9OoQb6+_rw4J! z11|Zms9tp=AWqKZc^1XRozksOwQ{3#?8jUe>fU>$KG??gJ<;I4^5k+ko!d$Wug^2z z4;`9U9)Dh5eD#Yn%Xss6=p*s^Dps3^7mj{2y|Z!TkNz`f@C8*dlQC`ps_iq?wkH=p zBLWofjvwzyS?5U|AX_)-iKOsi;P+zG@gn5$WRCY@t@C1^@lyQb$w}e;oZp+b*Na8R zn?K%Lu+H0 z2LIv@Y1av9u?%T*3h9pz8LSH)s0$th(v&#SjK>ERYm3fqkj+ph~doC!O=2s@$pxv#_42nu_T%YD@=cs=&>di&?i#ZS=Va4<9+ zTOb@qHypP<9B(!pdKpdtjbL2k!cvc5@&5UiLJYJb;2Omhdm7=573oS6$tV!X{4A11 zH}aWtB`(-5C<0#H&QQQJiFZ&{~?k6I!qNA|rMP&jalzTY$s*kmq zjkUXswSOGvAQ1OOH||?~tfoe+wo{zjY@Eks9O`krmw>d3uCLmon1F=%p!)cb+4u*u zx9>Aw|2~m9l2@_L3GoRDiS-G|vk9q}3F(g$GX)Z}W1`lOcGq}I!%_Q%Pc0?FOF$-U0WzYql32m&@hv?fVwuGFV_y&n!E^%rO!py{ zmUfYlc2%EtGn;mInFgRt2MMNw71HR`J;yFn#_`rrS8d+=mRCe1Bs>aQD#dB zW=rX16BXK@F+>YBq@PPTh*@Q;QRciA%pppIkF2CVZO9g5!FxbqR26cJDRWKnGPMey zNhIXxHF#%^Kn<>P-e2X~Q|8^P(O5KyStjQ4%W>IUWnCiw17TFx%l$`^;&kPWo%PHR z?>`VmiF<`SZfFiLgCSI z5vg8b=W!PIToIKqZk0lAf?A$WP?579SDFL5I0!z%4el1qx1sIkghYVdx5U;+y>F2vwQWw;ZpSv!SLb~V^V5c)bDy^n-n z+Lvh?5hGx5zmvLY1$ zyTriP?V&4WaA9kx-3UI}KxHb1Ff|=|){4V!Oqi_zlSm?nEd!EX!!PXNtm%X&NOUI# zJ2sq9ND=-UgMTgtj|IRCtf4E%@Fh(3+(@29aE;+SAwy%S3krP!sJ06yL{epxDU=v0 z7U#^>*o70oci~GYcs6U!{ai6yus8U+f_e`gYY(|V!KKw8H)Zhc5dfuP2^A7>aZEtS z4c0~ik*zT2BA_G^C}|J31AsOVm6Yi~?PDO-F;G*eT-&%@(YjF*18^yWpZ8;*h{3qI z!EE*rvNE7uI;eIJ(1L;gO9#F!Ya%WK&T&`Jp^ER03Fz;+!O|Fj`f)|`6{JQ8L|le@ zje@%Yu(Z`6#A0CbB4|)!5vdiFa0Eb9_UmRIV1xQamRRusU9#0dOXArg8w+t7L7gac zY8kqt5X3$LQ&a@^Sc77b@CyWt4ukD%4b)VF72(?4;K3kx?YnY@Mo@QI<#sx7 zRtkC zMWESZ*jr;L0Rnbjh;w2Lr391*6`{}Wk)3IXnmrddHwL#-sGL;|7KcyBrUtt~!MBYc zBC2f{Wz}8pVE@#BX{~K%$3PoIjT;gyf(GUhRQ0n0Xl z_M1D6ToJyF0Jdt)x6*X`w zvT_auw?je@Z0OVxtaULM!ALJoW68F0f2&e?XAyLfy`ozUNQ8u>ayR}%J~S!%%R>6u z5Un@^RXzAvA;#qw7$~I}?5q_~gNDM8K$u!1(Z~?7OZ8g-cBNur+#bB|7)bh15JNVuKxgo{$WxEO2& z2}~YoDZ4JqaqD+cD!)WkPpDPlB-Pp&154NeZ^a-zt|Nr#k$n{6~WbzTX?iS?EIKO5@|<% zO^}%0aA8b9jO+#9_NN*5Nux&;2SDu)aAZ>Z6YEh^HlSHkJsn%gl?y}yGqq$7*~ZN8 ztHF8ht${5_c%c|PXg;G7FVmiSmigj|ph4LvYlS2RD(2Fq!vhLTH0~;JQ#s z00JRvV8&1!*WxEapeG2}9}FRDI03V3*)|4Xehgc;hrAVocees;#NbOKSVYIrbJWbB zP4)zOi8+8ag#i)Df!;m_ehEg?xI&}>qv``C?FumIkzZuoc;o}UT16%Bq!LX8kSHA_ zuMEeO0oB85e;WgBnn0QFnnY}VbJ;8u-}I}O0j&o+o*hEt6ycJszerkVuJ4UIUM{r6 z&Epe~{E`-1x;S1Y1ay(vLr=H|Weu};iq{$Wp}e=xglLL)6{d#pigFq%>Xg_(N%t$fLfZ1^!BC502L-H2^yRjNYkLU6&31 zQ7gYhPLUyiB;f}zz^3=o{=50|#RGV&A)K>#Mm%vnHPtJ#r7TKup9sImqo^)dVI%(z zp2u03Z&#Qfc0|)St>N)27jGs9uc{nx#*MJZMZYqg-5Gv7L4}idTH=|cLSaE+;oF}DKZ`4rexY8~ zWm>ZW4&BdrcTY`!WhnkSS2=%jzg3`O_}A_zPweMkKo@lF&yUX?xhD62UEsMNxc=2t zQB18^VviTtHvIF0=YBr=SJMf#Q)l}uiKj9*7GEAsce_9Cc7EL*9o-%LzB_(>|3~%y#OVGi?f&NHJpc$Lej=9!Cg$ZY!?gM0 zkuaEDl+jE16LDyD%Dq|Z^iAeBXJ87NWCK>(LB;;tlkjckjjmYgIRw7$BR_A#}%7{@z0J9E_Y-4 zqP{7o$)xC2e;mz}-Squ`JvqzWDewN-Ej7D$*ojrhcDPvif?Txei^G2)j6Y^wrvA^MU{9LS{oUWy+pPca|-hX&C!y>_BPk@MHt^FgLGvq%!T zFZ5w@eAB|A6wwQe%>V7lIqH0&D)Mi=QuX!ygC_^*MwG;NvtgF ze5z&i#FlSL&!1^(DteXRrLI|=Z>6qziaA-L24qGOAj(K&JpIwtz2==ov+qlN`<~kx z{m(;RD|Nn3OMiw-skLjNxLS;B4PB3v-w?U|+o&}<<-HU~k*ke~Gf}BgG8_CLx2Q8o zRMOeO#PaTRnFMpyTzCd(o}fU{v=}kKdv50Xbr)H(bYNV%&JH-r$nSEA3;UzIuh#o+ zfh|2q24jFHBwXS{hClN;LR@Y2NsdpTMZ*qBGs=q~rUrq!$4^h`7PJOFJ2qzeDRL-= zf(cJG*i>qtUI6iUwRV6t5T|RK`mHc)V8x0d#uK77cm2NM9=nOTdC~42s^v)K(k_Nh zEdkDt<*$E8!h)&;{**)jR!i_@KOWR+h6$flP@z1J>kRa+*IER~o4@8t+CR>LX#M;M z99WSl@NCh1=|?{O*+1c8ngH||1bAU^>F^D)mXF>?$<{>uYd62sLH!On3{|M5PmTbSvcq2 z3uDkfU)1_z*p~<0TsfjwY?hwei(Kl_{LM4~&vfM8J9dt0{>$_)cr4;g<@^#B5ugD# ze#G~&1{BYTUlQ*#oVm$#X@px!61}134_~G4W)FxY70&X|!GDV|vJgt5Aqsr_*7VV{ zPWorDgZ?U6rlcG-9F@*;!FTP+JS7*M>>i(u2<0djn=EDAOb+o_qUQZ)EK6(K{@7S2 zuQiYH*TObN4f*5}dM9RNUsouae%oiD$L}i<>3$OttT9c>5GN&9f*;}LW6H!=FR${g z!d?H&j73^N;ccvgL>#Xmo^s^#L3l$z)n$rAq}^DC$HqkUACEWX=nUlb{L@gk-uIM)xcOp@vY|ha zVzd)-`4UO8p>D|544lw>sdut(f(0LCQr^GNc7bz0#nSCEZm(RwTKICs2ZCoaT6&^xTJNLJvd@1WZf2oA}UpHTw(tdVeL}PDxR?knQWDvD{MRs2l3mjX%uOeq4 zj__4`vV3LkP!hl6?m}N>-tROqZ#)`>s{GL`xhPhH{;GoUJhd!^6ou--$s(P~!=|qD z*r`&QMi+=;Y^F|$`M9XCkXG@$kIiUH3RUfaezlDwl;qp=!K`k3y!7?tt71cwUhqBZ zgcKAB?85s&C>%ffh}z}(K_r_1+cPnRXvAt~9pZ&az0KF*IdFKsuD)Z$?sKLItK$4u zj*CqDm8hQD(g*y3%}J}K#tHu=r#?z&V?2z97~|tS-a3}cGw+K?`1hL=E!k);qiiT@ zwLn@!rl#+v{&C`jK3rBg5g>v4ruO^qi8pTG)AF`7%`gpmI@Fnb)&NSK^fS_Hn}xcz(L4^30PNVJ^5UjPCeviOk<*a6k7Z@nv7j6s}&c zV0xp+%orNA!S0m%wu@aoOt=?(nfslq6s_+RVUF8BXu zJ*^h|tBa;fjXQ#96l?zP#gCl1hOW3zOL>h~SGV(3@!Td|#N;G^fU+@((M ziwH;;P*D*9=}kbY0v2}WoNMp#t-Zc8&f4RgvH#_N-sgF)>%OnjBf|MAf*`rouH`aO zMrV|PPryc%<{eG&p-0JsdkF$kmAJ(IBHXenoFvm7eR+_tZ^H)bY>7-PZk4tLQ zmKG`ORy~4S&hTZG^$F}y&thb6H?)uAM~AK59)k5h_65A^j=4Sy)J-Z#yq1{IQGmCM zV+FV+m>k#K>!H< ztw8`n$iG}FiXd+g60rOGBP7JVHL1zPMnS0rY&#D>2$_K4;sxkyD-AaXh-eqgo627$ zQB=E7x=uKcB+*IAjG1|5YbWygewshS=+xwh8P7L!CmT`4%P|f2wmsRR1~Es4C(F0E zJ;F?6vN9)1(ABDjrfSomq%Fl=CgqItnzB5^-Cw|^)2*^GB94=}*8)K3+{Ol5-yKR? zvbWSi6%KYof}{-15rQ%MstK0t?_Z|mNTdoeNNn_qi+V0icC~Cxm#8JN>UX#9ysI&N zV*k3k?d!)z=ZPZyp7#CEoq=EfS*Lfe&Ry%d zPDebQi+lI**vryR^3`dFdH6=|R*6WP)bM1)=&!fS!EeN(=!9x2z$B8a3foCk;8se8 zTWsTM+0mK$fy-`k*lZZ4hd$E?^)JCpdLTkjJn-tDzXAH6RSi)*koaJ9Q`xH|dP!B% zYpQ?W?IL=P1CYK4JU(-XzwUxK9)mqKBZ^oot!UuxWQZCM7;>(sXWP|MW1M_lb@?aE zEE>wBn5t9QEryN{)r*L&@sFze_zZl1bE2+IaIQtm7n7?^%a+XK`eyttY>?Nw#CLFN zkwk(AZ(#{OWck&^^`ZWFd!?KgNxU*brH*cJUj3R2hN!aB0#!-UhI~NR7Vas_D)@3u!3%%Vc zQvEs39aCXH_ugTW1Fzf;+)~-*!9~#ZmEhjpV}h|xHy`_{0?C(KpY27A`odQ>Uq>uG zgwSG^BcMDr%aNq>o429@Z>u0Y{DuhGZGPGDePjX`@L(S>7PTz~ftBbuY*;t%aadsr zKCUE+4Wo@>L)jfQ?n~%M$H&NTp2o%zyi6aYR6eM1O4nkM$AzN%?&OCM!ZckT2{{t8 zWhq!+aHd#wSGeS8+QX`Hh{-r+bS$7UJemxy&^Q|DdMQma&qOok)Vs0Ki;qM4TzCo} zm_W8sQa0kZOK7r2N`Z+72{jsX>G313X--3qNs#>#wMx2DB5r0EA!CAS(pqgqLR6T_ zuGSy2?m9K6zAJ$zmMAz72RxpdN92Ge4N+Tq;Ty!=>W_w*@9iCpAmfCNN4avm zj>q__>yO8UI`)ny#72H?3rl@*@_8+jlO*|ieX3cqYhbQ9aB7*OWnyL(%#kdjMpf8A zn+Hib?Z}gg&=XNLRNfbU#pM(yrsb*ZEmDC|L5o|jP3{Y~;3PD7^pX~ZUJocawas?S zHBZcU>?w1QBJY;ypDcxa)z_iZA&Ht?4ST1rLzSm4`C3#TiiLM}Q4@?&zvEhs1iF$1 zQ`l8Y6xF&PS3FJ{nis;_>!qNH|y6w-n(*BkyY(% z@=pUTXI1VIQ%V(@uN9T|1gmi=Wgq7L)@(y943~38pI9S3-VarJ-pIA<-<jK2d6_S^LxX$6TZIJ6{#Y;w>*mn?UA9s=il>=FuMSJ_V=zB=nF%_scV*_ z5Sn}|K?7o(ucapUBpm%GjW`Xj&tf_qeONZ5uuAlaa%Gk<%GpvSXaW6dqDHzbf*Fi+ z%uQm&KenP$s_>L@(n}*G&;+PB@{`6_)!4{9I(xJdFGl(hL$~87WYKJCodEjQndE zHi^+h_sMzIqd6TD`O_p`&6#ZK1kUahs*axWxhDH&$nzR&*zl(*Z9vzyiWz?A5MW$t zxQwJiV=t=2o+3l3n3EW#xRW>3>n2OHZCsdCq81RhR7{!GFjA9f1?L*pv!#y+c7tC7 zbz<+(d->NZd&p~bwFO?{S zx@Hw&)KKxWp^N!O-SxY~TKQCQ>+4M0!Yi0zq`Z3(5aqzgI7++dV06!=A}K(3hw_(% z=C9XYE&d&3nTI2?mYy@}%DjwHXigIKVI(OKsAUqW zIj2v_77-xO_5b5-O)hDFNu(>T<{C*FFd#&wV>Y_Oaf?f##z!T%$6%LOHXascLk zcf}3HAqeLw+x4u5@SwqCVf3h^0W+I>_isWN-(I!xNLGJ-EJw^aU_s+G8#n}91C8hY zix5KY8n4AI^HgI{j|7zYGcm>?A~`yRiA`3o%M7b&%E#M02Qc%yjt>~k9Yh>Qd+Q3v zhd1XQ+YrLl6ryGt+JYaDU;N0fN4a7%U7B+{#3pqwE@_3gbWn6cT|U|}dU;&>)m9ts zu6tmd*v$+zOV+}sop;r5K?=-+fMd>h- z+Gx8F(s6aYsZ4O7g6l0rB3-=WO9TX_21gRW%O`xGntaycF;XgtVwW17#V%dcgGl~Y z)Z2xz`w5zkRHfAAObLuZ=V+=t>L~Uk#wCu)qymJdbF^D}8HAnvAil&!0e)fouPAO9 zbOYr6KfyGVOKp=Rk6RuhU_07aivL46b?{)CgPH#pWHZ?0Z-%ZC{xa^HE)K_MS_c`s z%@!HP1M#!fZrL1{53J}^$BI^=v@@FLn02Je*g!_d>{d3@Bg`OO$Q~b_p{o|^=B%y_ zxYWIWCbPx7zalF5?vca04+W2A>n-SIA%}D68a4AhET6kIj3|axrGg1`3r^O)ELEP; zhF+UIFI}oXM!&u9+|hJ9)+J}$8BQRqCW@)IrQNF*e$M(hgr`2;Zxb_NeE5cn3&n4E zjf2)TgyZtAgM{zQBm=ejph1{C5zMx?x8qxnZ~aVP1VvN-iW@}p+VZP$W(n}R%hkg_ z=JHg#rvM4H$nsBS!P2!y#3WnV)GSkU8R<7}_+{1@wtY0h{I=#MR$qnzaghvXnwsH+ zbu>AEY(b`44A?f;F;?~vQEDy|U1CHojj4zNc*BD&p{yq7MrH#4zcM;kwT_{Xq?~}M zPn87&)Ptls{_~N^QeZxIY@y{+S(4bK-|7HQ7bYZ0Y&2RzjmO^u=FX?@(yUu(B|)W6 zmo{t7pY1SboLm!NpPR&&!Wc(P&62uJxpjQAPAAmze;EPB>NL!49qiP(OQNe86XjL_ll-)@kbL6Ozf>4Cd z(O)aWkAh6={sK1>_>({W*C_Mx4uvw0Hm&BU z4>dJ&Cpci?zw9e|*NkH0Sk~ z2s&2dMR;MJ>>)nKmE_f8hpoJ)VUGa*rdQDWc$`o05>Sco|GGSAc|~WRn&|X`z9jM1 zbW!(q01BJjPE_jl^XK_(CL;Y0dxN+7!+FFdJ zca6_6G1{+Mi9^Qnt;Ta@V^$ORs{U_`4r;fG!oKfp6=R76wo9UEJ+@2ZdFr;yl4W+c z%W;}`RduF?$4+IgYu!#&LD23_bxEwiZcRnD$8K#+Ro!k~ef#e2lg8mIfv@$gA3X3% z=FPgVPkX=betp(YB)Hc&MC-ZtUvpeN_uJ-NpX|3U1bzL#MHhrlCZ#@loxGOYsy~@h z`hkydMG*_1&ZyIQpT0r!Hk`iIlifdkXQU;3Hfv_-efHkUt>Ns0?Y;f8j}CFd-{)L@ z$l#%AfBGOfyqJtwRmmm2ku9*F9ZgO$5%GNyEOh1H$QD|zj3$>BYSrg7get`Wm=cxY zMPVWKI6wy4Pw+D3Mv>Zjppbu8{~Z!s%vw}ZV-!s|osiaMjiU3A*?5p&bVc#j$zu<6$qH;z+V5c3iqE+8<;i0_? zdWjO%iIXpg2m|%7t|3$h$-d+4lhnpOOGAuah`NYHF{wNCt6~xK3n)MqIzSbI?ciNP zh5mxSq`GDj^<@X}^`f#OYd=?f#5KhQ!Y3|XKnURg7!Xnd0H7Pl`7ap4YGzR;6uRvl z=$2Oc*WdwrC#zT+K|_@S~^B~N8Y+Y`$|>&ib;7j5;{nU2>+%eB&WKXv$tvu1sy zVr%!_9395j4kHc2@*Unvx*6Dg8H{`XphxSQ+3d^MYr3hPX=3()pAYr#%66SBC4Q08 zTHotB{hULYlW(7r<>&am-dVP?)_}$G)Bl?P{5LV<)xXD#S_DMEG8?7@iH-by?UYRg zL@tGV_y?4Wj3D9QD~Y7wk?oHrB6TRXq@oqW#!}f}O7V3}h%yu_IrVBhIFoNRk)XDd zBT=Mi&MA?n8NC)KIu&1@EDyKrPec6)ri>vl!(&U@YbE$0q!Yv?4xmoBm8t0(&!wv8 zTFa$LZ6c4#G}-*fo@z;1QJGERZ?&H9kZ4_+>-^VDQeQy5G}oaWww39b5yD-FVXSa{ zd`qX+?XiOaUp0Uw(!s_0uF~yPq;rJ2b}-|AG5*bpOHQ8K82?h;BDgl zCl5aS6z-d&+!cU={qv8GacF=r!mIM%=Uc>{Ge$_YR+WO{Zd>61L4HW7@OrlQ36@*2`n#1Gu2z1|)M zAS0kgZKKzdKDEBXZ~SkCBZ8Av!1zp>?O0yk3jZdPL{g6rqg4&E81;5)|VL6NP_F^KL`lSM^AfuejL*D;fn!D6&=mnecr!UEMt>;{B9_*`>3@@ z^0d6?=Viglhe}@s-^nK(2kVaxzBBafF)P72kOzpd{*wqjK$(9S z&G#RP(0DtAz&cWKKK*4>YZQyvWGVT*(Lq+codPMO#dn1;>BlQD;?a6#lsR+cq|K2u zgk39?|JW&_wKzG*pZ#U0Xo}OHU8VcmP9c^ovrxwHaa2>pRXoKTZ>PwL*Nmd}PYs?d zC;x)ck`7O2J<4T=eQ{J51!u5?&z6&XMdJ+7;;}2pSOANrkgW&OIjPZd^B~nwbrT?l zlwCPCJw?3_$GVP)=Lj6tiu7Ae=X05m)HEVD9l)`Im!nX>;&nk@&5x!571={$RZtBI z$em=rX(B&n-iJ#k@aN(+oy!(%Q~}*1CrMTWi-w{}9+`9QDGTN8DB1a=RI|{*N-rp} zjw%0iu!|WW&~{t(e%Flfcgh;_m{08z?QpIjpW9b9)I5YEwou-}=^vwNj=-K7qL9 zgrMbS(DRZVRb>H_{%*&L<=lSwK*WS|GiR0$vc^AWd@|DJjAhUdD=PBU6ogR)FGIPs zUapWeo4ltoeLrMkj;8o95L730N5JVDX2AZbLvH6RN@Ckz4-{Np@cDDKjHZnPXn}y4 z+#&jI;8>&&6h#o)UxVsSH*yYhcyyYp1!?Uz=!5sez`!22=D1#%S>S#4#U{gNT^0iZ zmdLHiD#LH$(E_uS71{KBKRn=M^kHRny7~?9TR-h-r!0Ur7!$y0fiEBYCl{lQ{V}d>v=O_Lv`A^>=y;GGIFKSWA6mdi3^w~ObF^J zRHXKAS~>#cX$KZL;7&=oOW4Ha(s_l6z6d)Z0%V{hHBra1u9om~Ks2uFWp?9}29kzI z_PseKWxfIJ;!==Y%k37nY*drD7g>Z}XT z$j_t8i8IEbnatDan`#OE)^mRJY6N}tb=)%BJ~B#D&laA`OenigaX(@H3}zqk`9$(& zlw5}Cn-RVfbIJ|2F4dyesU^`(p2D_A`O@O_UXSn7S-<4&r^3X%1g%Zk-Q??(yJSsi zfv`yQqaY*;4a!pElkUg5e!6{!0GdB=GcC5DlclE~gmw5!U#fqsD0xeQ*kqoJ^7zLt z#E*bO4022>*Y%wS%R1+na39f9tL5t^T3GPfoZ@cb=;_hm;7fycYO%MS>ta_Tvhq&) z2vA|6OVS$2wrMCePPk3z(%n5Vm1!^c=TWr)x#8C_8#ovElokZk*cM5-(N~5`NxSjI z*j&V_C-Ocx>P{SiN9k9xc*C#NrrE#2*I-(2-lmN=O zMg%^PRJs*5XNss0OL)KsFGRvi zb8_FeJ8S5_1q`NeTLgt&A`Yxs_qTu{ndERqjkx*CYrKGA$rhEy))#`@e?|S5fFV)+ zLVM$4c7+pC-axrpF6=(zg}Eu8t2BbIME< zKsq~c)=58*eB0S^vw0SWU3Y&pr>?zr8mr>dYY3sah4XLg(~%tvRm4-K%DNQo{YPun z8Rj#M6LnPjQ#T19-?oL3EyAm7bNx+I_E;a4Xd<8Q?x8Dltn14&G32*O$|;Ko!HVY( zSfBrV{fPxVHXS??Up70r-$8J;V*c_J(d=H6Nz}W2q-b&b3F%b?{ogH%A^`^jvGLyH! zx7)g^lxwHftuT_j!nF+NDpi%ADs3Sdei!n=8ENtCZbdF!J4 zx?CUUroshP;+=E^i~2u|2{b%Au$if7;F;KI>M-!AS8;z^w^3Lq^L4W=Vb`O+wpQnJ zL**nmpF4M&(F{|PEs!M8R+n+}AiE{e^J&?~)m@*icj1b{-QYGG-;QmMp0CZnXrExp zV_cJ-J#${I>qq61u0LxdSoEy#&1}x=M{RUki#=b<{_NQ|XCh!U(gy#!ox@>i-OvX; zdeU4&%S7VQM#P8Eq>mO8Y#1Z4tmCbL;|=U6dagsi?kJ+)mBlY~E-^2RI|Rh~YDE(F z%kFzT@XRrYn|StO%2j#u{YHT9c9nih{@quObm~EckMgbg^Ds$Xwbi$Su70{bzZ+^D zxRBPTa9ZWh3*jjg?GXrEB@s^*T=b?z^)KUEl)e>3y4k;3bs)iZZNVelySFQFwKbJqI zude=(AOT`})Y|JbYC@GF1KR(LHUGo9OP8wzA&;gyuF)bOM5>12jCgsa9AT!T12o-; z7*R8JQa8Rq#&%q+Y^x(_;OHRBB_i&|EIZ=LJw7eSYXHeTt4*2HiQ*AxN-zp5qdrgYoP{2`=Jt-&c$ef0R2o5jHDdV#j$8ml4i&srvW7?n}lAmu%4US%8 zIm^`&;-N@z5-LZ�Y-18}i=F6?v(Xie7RWI?5P=nu5kb(`jl+=>dGpPgg6Q{o9c znOp=++T&UR&6(9wm7Jzy_UyAhfg@KK(|Y$e%IDXmn1Y5wZuZ4ovM z!k_|&E7fy^Mezgr*b?T?F3Tv@nk%Z%!_`6`u2|V{{z*YNmKE%dlpqP!yHkbB1D_AE z5=um`?NH@_{RW{z-TfYLEXy)AmRA#NXkBEC+?T7CGoI6oTRpDKsdrMk!8a|&Y6cI* z7K@LJnjoy4W7f@L;G43hkrFfI!;h;4)O6CwW?M^*Zu7CQ3m6-1&P1yqfN^y+g)Szl zU>%QP3Ez^0O=TiC;;R55cB~^Jx>A7#5dZEz;D(lB1|PQMmA9Et|ck=FPWMQDi_z4aLnv4T-ZN~G%b5j0M4fwmERUJr0B z&j+WzErBHT-_)X4tGnJ7>nt4$x}kHEb|?tR*a%Tvjj)Ws4T52n!YUtbBEn|W2+M;v zl{j$8x5(F9^KTC-Lcq7?pO(OnQN*N(NqZ3WO3CbE0xH~{^t?){f~OS{mc)niBemom zMgVe1rcZ>;=B?ms`x?*gn?!a}Wh$lIR{FwDC>w@iB7B27njNrM*P(9M9`*1xcKz&w zqhevF_tx1Uafq0a2{~ORAkn)C(gNB?2pzGW#7@vc8)Kx2pQT6q<&Nh$%NB%$6Z!R;SQPz`Z= z40;fyqUg?>Ll7f|dI}t~BlIy09T!JKV5IAUs%)Vk3 zR1j*4@Jr63$~zl>?ii*ir<2|+zQwYtE8fJs=i$ZRGs2(B&h~6UA;iZ4d>#ENUWP0Aj1iJp@dfo)$ zWK*6Wb`Fs}xW2ds!!lFS$ADg?Gz&=egA9~0GP@!{#F!rhpMn*b{!H0yr)E>A@)0Wt zd;#_qjf#^r>-(fn7gAdbQ|^3)p)VhmGo5i zJvBKg9}xVC{Ea%rpP7fRAvYi!;r^#V*)G;1-_4}7)S0LwmAE5$UwL;`s|ZM|(owtV zRHAXw;YhT)cSjJpRMfb-8qX^OHY+uR3+7>Vpfps4S1V8ws>N8Nn+`!Mo!d$nv+&zGa*eDW%`TXe&8cFP|Mydd)*9msHDy-2@jK2YX_xtU)!QMzah+AQjd_0C zli7xA&lBz7GP`pvDlg0Ieg+DD?vP&`C}esku-GG{m>-tV;XBrN-|&*9H$!k`@ZmK< z`^nCxwZGR`dR@&M6S;3x?hijHx*n+-?KR>U?7Kg)McPvHx zfuS8Vpgd3{mO!M&DC#TWXc2Isor{RszwPE2M5ta<8p@J=Uiy&1Bc4r#`K{JcCC905d)+hwR5;9AZULRg4PJc_8xIfRJM2p1>A6UP~< zU=Xr`8gdmd5*~~!k*i0x5 zpm7fKA7=L5YZ^x0V?G|?$iX)ea#njakMlj-3z!gV5ej@oox_QeEn{vKA6ELdhp!{N z61p>^PT_s$4Vtat&Radv{X6eao(rjfJRO&zGI%zs?Sr-N{@srbf%rN?=Q#cEpIoc$ zzRzP?8iGFiy%6sBe5d%iq4Mz^Rh;Pl`c>4~b?{yk#d0Ju>-lorM^3qwc)`^3Rcpzq z&J`R9Ue=d>V@Yl^CNOn+BaVPvVLdS}Ty7&jt*>jd?0%}kT3u3VhYDTN?~o5EB++ds ztXs;@FU8*udiFX#KI-|_`}NQL)q$(UyGJ7=Uw(e*xVhB3VxuP7eLVKlN9oX3&`{~@ zGpBFok5^2hhCJpZW{N9$BNQ(_RDMyG`*=v)ceXm^`TFYjpLc8k|47g8MT+}5l1qzV z%nL$FqlbAtOyH}I{!4zu!>vaSVBX*xfK6l6y`J3nlOGk|u=s`(4lSXY-3A)&QiLr3 zw7asX>EGCYdQVKRfYiLEhcTQYL~g;3^y-D|Agj#NU{UHa@`T{NPboA0e@KeX>bI1> zzIG3f(M3|X@hJ|xMkEEUmQjP|G@w2d$=8ydsOhXUVMW*OTd#ki-I&wd+9CJjz>ijR z?u|_A`-cD2T_PitSGw^Xk^1tabg#QZ`B4AaL$d|uIf?D(L&}utr;l9Db*!`}?3(W; zWO5w@TOgKSeY=zTwH)^4TmxdC9%9Pu0EyGmT`e_8u`%NoesbP>bILfo#IsV^@rN$4 z=0Ri#^XPlAb6rL9=7(DA&Wx6ru2E1^LZnoMz+=nTZ^;5eKV@zb{iGlD4R{u#vd$)* zWO@DE?&$v5o#J2h)@uDnoY*BLhu;I8SL*#MQH5Vls=qPbGX(mYBg4IHuS<_ky^Lwf z|6Xn{MkiqGIqYwM-zV+xc?@bCa26Hfy9fzYDeR%kMFj2@T8<$-CN_b{J;V~qDE~$n zihy~#{1(IOF2yk18bS79F{N?*giq)Zu3oA_JZaqEH({$k@_8+iaK0SQ)b;8x>o`u2%grqWYGCLj z9sG1pK$1p&ye7!I?7~z<4&s;Kb>%QiwJgT!O(@12V5JK5Vnz;>R>ly7*zA&L`!#(NIgB3kOJg5;mOJ%)9Ins zCRWybfjcYJ{f@W5dpV<{RcBT*+#^5+VGoi*!8H)00Tct^$1oHDxO0FA8o88o6oHII z*k2#@k7DN+QcV$uvWUgh`e$^2BO(C31w|-H1>BS>KCEy@?U>bN zq)Mom>S}!Afu;rFbGc$*wN&zU**&BlEtZGgp^Z<}3J??F~GNO^a8C*JmT0l~q zmgO){J#PZSZE!EIsa*k|Y8G{~_)TdJrz+bVI{0kR_*^#%H=Wd{a#TPQOM} zv;S?e6TM+ERx#z7WbxC)xodF;!v(|RX;&5{qz`HOsnyRDOk(ePF!J54;8t{ugc?$0 z>2EyxsOK3m6vaA&Rgr)mYpN)u_L5@&CVOo|s@>_f#wh0+Zb87$%c1>6Oe56$yCDcQ z{~+*fw90&)gK~BV@)|DEet=zHtAEJPHMDEh;M#iIy9u(tHU zcU$tf6H>O*tA1j+IR_BCx&_>chnVyO%ZCT(?`!OCPXHm1yMV6}b4%g=5Pkeo`>N5) z=O?eGID6J+Rc2yd2y+;dRDXHOYJ*IE@2%n&N+{8hhs@;JiFq#M5Pm-g=_B{UMk|Fp z{bc?v*yyZ4sXmCLqT^n`QlSf#kmeeBk^sPJBv)>A{ynCda#|CCakDYB(BooaY zgzR-*<#Fy|p@)x8S2`KV_w9W`%)*<-Gxy*SIWnyAT^=ERWZohgTzH>2sD-`qeQ zU1VO{!&Zp%8J1jvN0rXhyHb+(sGmI1;y#ras5>gagV$l;EJ7?uQ%72tKGWddZ8`HF z2B49f0oh7F%pQhENgu~pZ@F9_jS_`;p@n;(9$QaiSqL$P!!gud@OKCskdf@QR+)5q&M@-q{u34{?lKr4| z;8htY2jMATc0-9;?x$ZuPNz*Km(1asW`Mc+bh*hR=#BSu#)a|5^{u+mT+uV@p0DF< zl3Xx#ZHb%s>^F_*@_7ABj7}J}-rZ3}9dyFb9rcb1MM?}>Haa=7!W=4Pv^MCLde8E_ z#gfciTmOz~uC#d#w>rEvMMKK(H-SxWmU;JiOl76^Mzj{uN?6a3&2?&{$#M%Jb<~Mf zS_olMM5e_>OS}#G7Sz(EUOL&n!muDl?z8%x7;3!_1SZdDH2Q07OwEEPU5rzHq`sBA zm9=KxeLKAmik>4-J_|N_8D)GpXHbexCmYg7GQ_W|%Z&yp49i%OY*=`hryAT%^SyFO zjB_&%l|w75tHa$jOHX7e%{9)sGE}TFv+HUU5RI;ynAZb?$6Kct{fyI}O<@z5vf8To>#9qFM@kKZ#CzTUxC4i-*O7k#+u(gQcz zJ{Ch%px}9juw<+|xCu%EDu%Nc6RH$L9E;CF5a$;~m!FCynu-}gB|qE|$w(j%1;4|O zsBkEOfM9h*c$QR3$yiDtUP^0IN)0as``IxI@dRFMZ)nC3t$3heF8bmlJiDlU|lz-z_HTA3&u+I&S6zrDlPDp^rO-Ul_(EKoBlF?no@EhvHhc| z?9Q>w+NOW&bja`QH20(PB<*&Y@#asBBJ=}+%7odPch!dJI)w@}c%6HHKXTTEG?{`TKv~pSUeAf%*ou5&BkSP56@{Wq97B%VeWd7;S%$a&z zgPnrVZX~kf_~5zXa5^di{*?8=dJiDLH*I8+o5}@#wvjzCYsmk4w%KEyc;(B#^z+BW zz-)@f%W z`&JOXx!p;%)e^s347YsrV1YUt%p#N?K7>{g2|0 z$Y!Rd_HV@>(Un4N&BNip6n~oC9t~Z8DgLmG5WM1VxZ4x2_|x5O8pk)cmrru+PPbNE zwoG3KA6`zkemp**xbf~X5Yu^u`MKQ+o?Y8-!D%W!y#eOpL{sKm&uI;lp8+P&=$+Q@aKEwZ zaK&Ap(nGjk3_FMCyo3riz%v2ZtKi=&Ia^}dnG~;{+#UxFGDXV}lnSEcE*u1L@4&ww zQ_K)F;e=<86XyeD!INIvGNvS4qRQD=$wpL*O_~1nUpView_xU8=nKV@`c{-)lprAI zbn8kO`+T)qr?q4S&q6akmPNIrNTH|6fSN6P1h4`1GbAK^fUlh2iG99a57}9fVnPoz zM!uqjE)Sy~sqG)H6aMBjf`aw!4c~ynN>%n_Nq{K89EwsO!xH=Osa%sn8bQDe54V@u zNE*T7C0D{m*Y@X_l;nxC3WVQVmUusdXOTz^iJkTL+?3Wt+C?gt%_Gdx1S+G z$%!9yKL+G@5mOt3_j4{wCL(2@xYhVsY{z3oA%}7>oe4HC1e!nsAFV1eX&X&oGgprU zDqs~4g}IWQxn&`0>h0Nu*dmD%L&ktS_b5Rbt*Lp&q z*;GYJAYt~onXH?7NUSiAzVWtG5rp@=S29%>$u*nD_RIlBU7!t5pdM9R_wVr2J4gtJ zsAPl%O9q*x`Fy{`qhWT0Oy*iZF+Cdkb)%0voq%YpHyemVkpDRIP4H=*$K5Sr&=?2k^eZ=9z$Xt(P@zfjTkn($JXOQjiqSfy*7 zWoVR~@``}J*+Bi_Mi|JErGcBG36SgnhI$BJA~Syg86YOgEYCv^6l7#G7%6eM*Vs;$ z{MeHQN3;$y3E=2f_F_^=^BarzPc#v5lVQ=_#7d<>Vg)%~k&LW*mY+uJs6^zrvDLE( za8v%zI^=i+)|p@t<2em2Bl||imB%d^?KnLv$Dg0$ubEI*i% zrFuLZ=jyF;eHL1?^O#iaCT5?oQ*yHvjs{y!9I8-oU%e*1c`oPuyh>&+Y+*3Mf~?|( zUXsYXfi_V4xF3}v&VQe*$@9Z~E#>dxwbrFA=EdHhDh@S7QdMPJUq8;ychMEo+s(fD zP=Zt&o&9=@D2QcVFX)`|`6Jbwwsv!oWII{&Ps)uE8xt@6 z>^feO%QPNojx9C^=(a~T94=2d%-y|BGmT~T5bksuM=4Q862^P8=_+Gv(Zf~vO z-N)&9fvE}P@75U$Bg{MU--G?`);kJ+wRv~>;mOq5le@~E_MhiJb}qFw-dEncMW;A7 z6duoqev@!pw1*1fF2i5M;_W8cGyksdJE}r|-}@%h{L++6C*gp%_oJVm=MKJiy(;tx zBq>=~3zzL4Z14$bQCt8YwxrJ;!}+PWkpCi#PzI#&kNba^u>UvrZyX`(|D1!0QqJK; zxB!?<@}FdfIHY2L(%*7^8q-(^?7yGv;ISx>!SnH%5D7EGHckDfgxiEfauXJ19|K%I zkDH^BtNj67s#A+kjF$SrK^F(YH>aKflyGnbO|L9zsTjdWi6tgu5D^F=LSn1Lur~~f za1S`}vZ&H~UNN1h`COsRBa%sWBFN6>nftt#@8{vd``tt)@-x;_5Hxcexz14HNOW(fNmxM>3OV$5)otwwrXbW_Bz(*eKBmvu(G)cPYEmx*8Lt5&j zdF~Dds|b<1ID`v}V@6Xf*~dyzw}ebm6R37Zz&H|ySVSiI?{}-*Ryw!WRL^S>si>tx zQ$(WkTg(P3e`YWa_;9Yqi925?kCY*}7Kjr)GecLXhAQQzsAVr(f4RN{$X6Snug9mM zT;VS9w`RPs2t_ci{3U{t^mMHZ+{ih7L&8962u}2184D!&V5l# zv8DRgWAuzl;`Da*pJ0=j%u^^T8pVU47F0P?+8xd$et>n46{IhBka@u20%kfdk%K6v z!Np>L9~dOokZHtyx%(8Bzeeg@j?Ew#Iiz@082ini zs_^}ZHJKOu-0k35n+RWb2*s_EM%dhYspLr?I^Dy1x=mw9?xKev>S8xsgy0K|he)z* z3_4;7?PlJltA)+*l3ff=Ul*j5l8hQg_ZxK3{T`g&rd^b)&IZ@c?4Sxi2+Z&*|A|lI zA(b(*Nrf_(FQkI zZE&p0r|enA(6mq`(}hd=`oiD*KC(g;^+j8~ou%7qA-%;g@#CScio+nElVUTTi>wF1 kCL&p_6`pc1cE_xznY`@W0#pG=<6fsM^2iNsFc?t$A31E{@Bjb+ literal 0 HcmV?d00001 diff --git a/tutorials/files/server_config/camera_no_env.gif b/tutorials/files/server_config/camera_no_env.gif new file mode 100644 index 0000000000000000000000000000000000000000..d7a1fda7f25fd75226c1a793613b692fdda89317 GIT binary patch literal 214013 zcmV)KK)Sz2Nk%w1VZ8$b0`~$j0FKZAsr3N=00N`y0;uu_rtS!u+6b!b3jqKWpxqV% z03kC@B8XJA1X0CEEWMSuIVo@G%uUaF)%MNF)=bRFEcMW zG#CLj4FNZWs5*R_JQo2xCnP-{4Lx^|J{<%;9v43$AVeVoMIa4DBnL$$6h$*QMPPOJIOZL{m(0e@vy&O(zjeCl^j$cuvRuPa_adCKXR9 z6Hh4{P$w5qC>Bs@b5UDxQM>C>ClXSJtWzo)RdtkBF&bAT5?Cx6Sb3ORG$>nkpj&sJ zUMCPsX*DuxDivx+OlvwdYgt%q za(QgQ<863|ZHu#RG#YL+DQ-VJZiuaJ-2HEdtZ$jXa6Kk+g`;w$&2&08c0W9L9}0Lm z9e6$_c|JROqtJVYoqLtOeLy^aJtKcbL4QXqe{y+$mA8RJCV@yqft0g?o4|uhLW4_4 zgp#O*KO=>u(TJL~iAqL^PD_cT%!*7$icmg_q{xh;!;GWHjJDp5QcaDk*p5vqj)#|y ztksZ3Cy<}LkycTWq`{I}Ig^c_ljZo8tkRZUSeCEVmwJRi>7%*aq+mOww$r5C{iVY0r^N55$o8nu{;ALYs>0@~&i<>*`>W3X ztML1*&HSv*{;baatj__3Z5H?C zoJq5$&6_xL>fFh*r_Y~2g9;r=w5ZXeNRujE%CxD|r%fOt?uiw9b0}CEZxUk{Fh!ZPb%($`R z$B=)*V>fObJ9v>ZYu?Pcvrx*G;>6*$Zr?tQ@G7fb&3ZNFr0^zto=v;9?VYK+fp8%@ z-D!>NItU+5ytr@|uaUx&Cy(9j=g^}|56Q0EvknnD#7UPNBRdxzKp6iY-vRk=kg4VM zSGpy8Zk3^CL`6Z4d7_9l_HLHPj4P;DHDl*bO`9c{Eu)`S3#yIsD|) z4?Fa5G!8lW)R&=tAciPnXR(db&4RIUlv-uqusBYOFS=M6d>zTxUV++BQx8A#yfzs- zKo0aHkU*x0&ycTe$YVN15)>Pe@O(JplvGxk*JPDl=23$%jnhv)3(}KXIPE!yk9_si z)7+8lsOcti&P^syn)2vFkCM#MX{SIBrWp>GRt75Qpl6we-fA$$sA!@zZX_T-<&4AU zik7hx&U*b|8V)>{V#;1Wn_k-9di7AoVW#WxQ%{NWjjAe!gvS3W>#SH|8QN&+&;uw% z!I4KEa_BwUkE91}n2$HoP_qq>ly#HiGv(wXPi5>5QGHQ8yG4oBaGXRmnp-W#5IAX#eRW%4m6&!&`lGoUx)UI^qj-E3oF zW#iUE&9kZ+D-Sj%E;}uR^0fHPGp|b7?#LvUOcOibP*Xw#y{V`mfiEXmpqUN|3#6A3 z{`+G+nSN@fxS3)Dq{IF2+;ctHP#6w9cY2c#(qE3l^f=xGEwag2XRY-}?|KmdZ;e(& zDU4*x2qQeZ#@9`I<6t>pnKl+ZXT@jY9Byh5qKYcg9RB~=w5r;yM{ISOO1<^rh$nv0 zWZ!7hP1|8tlr}<>XO!BPf5w&?d(?vY4Z~$V__Wk_I*hb7jz2z*!}Z}q_0!mtL*Hps z2d((+xaY1=<%=WATB5Fnl-jcOST@<({8Y!@8s5;x zH?Z-IW)X-Q(vXJGj%OWjV2mCpJJG=`Gp{opOdFP2#}3!X#wk_jI@#Hd`yw(nv$=>- zBuSrYqQoZ3WT{e=@mQ8FqsJm)$&Z!FkRHj{#zs2wKK${IXtrb&DWPp3rn#Cxa99wg zaq^L%45fWabRt5c1&E?dr7B01J}spMm8*=UETvPyS=#cJxXh(4cgf3M`tp~+45l!L zNz7sz^O(p?rZShw%w{_Cnb3@;G^a_;YFhJ}*vzIjx5>?Jdh?s$45v7e0)}#$^PK2R zr#jck&UU)|`#p27dmem-Lx`~>Jf2MW-F67--3O(;Sas?dfq z^q~%oC`2bJ(TY;^q8804MmMU_j&k&)9t|l-M=H{ilJuk|O({xOs?wIS^rbG1DNI=k zfCm7erT}07PI0PJoAPw0Htp$6g9_A~7FDP}^(j%6YE-5ob*V#bYE+*p)uc}Ks91Gs zRJmN%UaX67PYH&t!!a?+Ry*iR<*Z{Ep1yg+Dyv5R-VrB?hsIQ_Nx%yI8|87V(Q^9ODz$*u*$q@r-Ru z;~w+)$2o5CjdeU^A^SMUJ4SMmlT73zHyOxJRFklU2$g3g@{E1J5!q0vVg`fu=ic=7J z(1t#Aq6xidL?61)k8ZS}B@JmsNBYv1&NQPjy=hH5+S8Nf^rt&b>QS3I)S#|(sZqUZ zRiE0`tbR46XD#Yj+Zxumrgf@y-D+OTy4JY{wy$qJ>|pO&*vLM%vU{CuW-t5K&n9-W zq3!Hehr$5Z&bGF<&FyY```h3Sx46em?sA*^+~`iXy4Owa2Hd%=eeHxK7=4O*pF$P* z&bPkz&F_Bu``-W$xWETa@PZrs;0RB+!WYi)hCBS>5RbUTCr4F+R)2-nufBDyXT9rS|GL<#?sc+<-Rxth zdfC-}cDAQ|>T8F4+vWatuGc;8c1OG3-M)9a_dV}?54_(65BR|wzVL|0yW;1bc*ZaO z?v9T<{=X~frKYGw39u_B0z3Nw=`U0rl^{a>d>sc@R z*3vB&-FbI<$T``-4w2mbF*UVGx}Uiip2e(;q)`~ei-`NwB|@*8l0q@$s)l_>PR zqdxUmz##` z02qJ*n18NUfY4`v2zY=BD0>OGfW~Kl4j6$AIDrZ%ffY!B5Qu@$XMq`bfgad_Ah>}V z2zw*=fFk&TCm4bxxPb{!eQ0ofkI;16_kH1K3$b7eIGBSvxPv^{gFg6!Kp2EVID|x4 zghqITNSK65xP(mDgiiQ`P#A?$IE7SLg;sclSeS)c2!#aDgJsCIEG|chGuw% zXqbj-xQ1-lhHm(VaEOKl(1J!_1c1;7jgWo!rV2C&emeLIfEb8^IEaK;h=zEGh?t0q zxQL9{h>rjGh>#eGk~oQ!Sc#T+iI|v)nz)Ia*omI_iJ%yYqIijMSc;~2il~^1sR48M>Ix&RE^*p1%!jo=uL;y8}vSdQj+j_8<<>bQ>V*pBY_j_??d z@;Hz5SdaF2kNB96`nZq$*pL1=kIxv80y&TbS&&^Ajj~9MP5;>6+ zS&#yD!Gy@*^(~#k}w&QCTWl~S(7$- zlWPBnkkhz**64@WsEsliltMX_L|K$Zd6Y<*luEgjOxcu9$&xr3l~OsC1*wy>xR5^C zkWaalT-lXg`ITT9mSQ=UWLcKNK$U2jmTH-bI;n@%$dEv3mU20lAqfn|01ePk46RTK zr9cRjFa~1~24i3cglPwq&<2Fi39X&Gjib4nyxE(+NtT)! zoWhBjZP}S{8JfSDoKJa|l)##<>6%`k2hMp0XTSy4xdL3U0xM7hGyn^~@R-UOp5p&G zp5!@`!+D`HKmZIHp=wwF2LPcBnw}ckhQ-OASs9lJ8loj>49ZXni2w%k zS)Xw52KcE5e=rCzst5h~2G+?10lJ+u@C%M9qCDE8J_?p%SO68U0|9UVIC%iRkOl{E z06S0t0kDQb$_YELq#IhLIq8DZc$J=M3!wROWFb!Ui2#F90W=f_pI;Mj_rf8Z7 zgAkiHS_5QIpkG?2c6z5RDTYicr2~MI6~GB;kN|%=rE7Qqe;TM1YNcs8pVSpm!tsD^q0MtY^bumcUCtBNX>Lb?MI+J#I?rB`YMXpp7GDXFvi zrOHqYU@!=XFbFR?s)>-F-P)}#dIqQZ2dZkFUm%;bDG791t?v4+c3P{6DYrGY(yqu5#!Fm8h0J6U;v4YABVgRtdpu88r37r36s9gKINqPYvORT|a zxL~-j6(Eob`@L41yA1%LkBX((H?5UBskED%#6S$tPzqq+37iVLs{051$+|@=qcYmM zNy`OakhEt|n^j;8PP@Mre8F>RySQty)XNNYkg^w$r28tpf?Bo83%(bSvbI_QcFPI# z3$V;^0}YD2$7`rzo4sOCui9Gy1F)~+o5MYvyf*-{^sByL$g6Bivd(y+5ep7tZ~?}O zhU*!r`HR8)OAME)2W!fvZ5j#mDXOCy#-rM;HF^eLkgl}}2o-F_Y~03MslkE!!wql% zA*`<#umf7#w=q1pX#m9uu)(|v4p%$KL@>kP>#qgS0NVfC0KB@r$ZNHn@WgU_p~kDc zxPZPoc`nSgb4n$DIkt>aE8M9nEvu-S!z@QARkgYn~si5nrUmTs% z*{x$7o#qM$>H5I_S(}ew4B*+y#(c~}3CI3A$=}<@MBocza04EIyKAtx`Z|Y1Fs~6y z3pdcs-8{z;ngA;+y#&Ck(c8$<`@36v&e{v1Fx<@`3%N#202k^D;P4LGo5{-fu`#>` za=Qace1=o3%3X@glF5zM;HjezimqmC#;tq6T+jp;jjl>t1B$T52K~_> zeUi#-q1o)nhg!V8u)Dk)!{5sZH=x4v8p60>1S(?kosr5cz33du zeT=*MipR|020C1^NUXbxZL$3ttSuO}L{I@~(8&hS$amb%c8d#wD#$E+vT48oLtMA^ zIso=+s7l(@n%MyM{0{T*4&VULu#JirS^#8A5DTx0+~}R&5UHnlY_U7w zwc=aK2Vm58oCc6=-=*9D_FcAHORvQXwn;jr6nddV0N|#by`_x2gFL+1>k57=!i+4X z5k9495Wd3Owr|MP8t$mgsM%s529WUKxZR8jo3cxKp()FTFuSD%t=?TpqNVVr)@cT2 zZJ+vy2l>g?zRU&Jecf=E ztSFwc2|#_`Ytt9X%m4`#S6Lp>wF=!@1(^+3HJ~ zxv?ChbkN-R`3KvI2&cNhpy~xPI@fd^>YP66HJaC4&;r?6o0kCC;NI`EONNQM=w0Zt zN}Rq2FaUT^^7Akc;D8HI zOpw8ymIKY=tnBYbX$;fA2iyOepDl{+qOQgCx#{J)^E-dQq3-Tx?CC;Zn{@z)#q9D( zPqT&I05_1?yUU;gZ-!AnhD)lueNKjoUWy9K>qc+`U0>(BJJs{7ir!AGNk5dC3k^97 zqikxXXZi<1iwR=9rajB1C>pwIy~Qv}onG+3HtN9RO#`d2>Stg0lv?P_D)z0&)QP+C z190LgKlX6A^51UwF-fAEK&GGDxt}Y#T>Pn^daC3aos+)q=BmIu|E6XP%&O|2>RJV` zd-Rq+`(NseOg;6h7|_ocp^-27r&#t?O#3cL49$QHcMqfMJ_tEpt}e>ftNRCM@X!<; zs;kTH>`vW#ebHyU{SyDI41_QI;D4aLKmOxS`DP#fDcQf5iu}&+(0cF&X7B}OVB}5E z1Y1!5_m2hizXeHt{{YdX$rgeGqikt%q=i6%TpWIJSffT8Tfl$`!SuUxujegzv=>{yS=n$>W~rAd?{M`Fa_5d#R2BS4hQr8~E-lDch` z{OFq(@8BPWWBhm$Lhy0vR(+O_{}g9O%WSqQ{)f9M5L_;>KOZI>)5o;>*A~nvUi^6S<<09%?G&n1s#dYa(#qBAclz~L0#i1PH}WI=0XO;Yha}ocB8ViC z5U?-=5iIP829H3nxFmc)u!$r9Yzr_Ae|YSYU#zn)L=i_MvBd4pLor1aS7foK^j2%F zJ=oxrZ9Wrk3=tS(nn7j;4SihfEfq>YL4*@H03k^gmMmdO5r%}aNfA&e^2s7oAb|uC zL};?f7*vQMhaB2k;Syy)#4$}Z*JQKJjaq~=PC4fk>cv1BVehr~;+xG)KWj6_7-&!l zq0knb+*1F`60n@|NfBmvbV(H;m6S;oDqXTjL=)u{128s$Mj2y(A?Bh#PenCVRV$;j zRaakS(auI=imQO3EW>x6-3nH3~<_`rxGUQ*&@t(}46p}C!*;iQAUaD^sx z$hrS&tFNxDWv#bfnchC`buLWWhy zVcENr2tnEv#z4Dp!w-*%YsD9Db*UTF_&U#5Y{d%KvJp>Pw-6u{@aY3RzZ3<|t^FbC z#ROD3=@d}Nq4R|)d~A$aFsHqC+c{!9cimN__l~Hh5*xnwemVR0cJbS-FdzC>_Gt>S zuoi|N#LQu_>XFT1Qg125Vf7%YUu=67TF8KqU5rOReXMt9zx~q!aQu#YJ2~Z)$@~3~ zc=Z8p#+ne8h=Rqiumv_0a1VR1&~HYUpaludfjBq;V3N=}&pn0^wb)+bdnoS_@ma0f+n!Znl=UX6;k!BhdGXDc9J0ogEz10IkOdtd|`EEEI+G4MdByO@P! z0E6T>un8+z!3C)}M>_r~5cj&HBJOC2Jl-)7e0;l9i#vqaq&BL?`Mg ziXZAz9aW{aCa_@-TP-sm{=7byw$3y7Sn%DmZm|f)3Q60!8RHLlFv9RAp>iDccmW$)=v20gMNnL>Gs-(LJz%fX-Z|vYHvOWjU~< zNn3#iE zHr1&MtzSbaXN%!o?xlW$Mm4-Z%wl$xt6eQ10WBm=r8x{}#yX=jJGO#MT-B{_%}hh( zI#;?jlq#yIUtXiC*SzADuXhEkUF$kn!WP!Bhed2+6}wo*HrBC^g{=QvtpdgTMHH@V zvZ6Jx4-`daDW9oU;-D|zz0Tf zf)%{r1Xnf}UCC~I=>rYTdUq0af(;m;upvG!vX#$ag$pP9|w8JQ~1)g!`=X zGy(eKevkv$!wz<`qZ{PQ1Ax5r0+`qQIc-Bu_<_{0DD7lc3u%5Z-A`Of6r=XdbAtqNhS z;(MVNovK?QK2`!hIsON?|Nr;D00h7R6u<%`zymbE1Vq3ERKNygzz1|d{SqFlQoruV ztT&hhORxk#u!KVB!0F?>IS@e+l!GlQK{+r3(qjX4!-Be?3-K$0*291*7?ldN!INRX zG4r|i;6JONg<`M(0EK5TLQvR-Z9s-)u!dEj1^TP6;KMOkhz4+YhbzRwEY!j+ z5FFciZvB*QW^!!x`>aEJzDAe;ZKyFu*;7C7L*4D`S~@IdKfH943AJ>0`R zGy^?6!4xz%HZTJ$5R4%3fg*4>AJ_mIq`fzU#9bM<5232Riv`|Ng;pqqZFmN1=mvHG zMR&^$}ngAUxlLhu7>q{cri12Z7OKlDQsEJ18EgDBtu7sQJn z2!bEjfIg_fWn@QH(S=+fxWC&!t5}5~+y-j!#Bm5kQ4~dX_=Zw^1|^(^RoJbfdofyg z2Vzvng=ENvbjXJ!#(TJjcc2AW$e;gqda}Ou(Fm6K|%b(n#@K*L_tC%#BhuYavY2h7z2`Q1(F=eq7=z-X@-Fjl|XSX zjC4xuct;(~FWt&SPW%Rbga>@c%B<8%e9%f!{03@3hE|XfR_w1=SOr;x$hBn4wsgz4 zEXH>z23w)Pr$h;0NQP1v0x%c?FWAez+)KXn0x%%V!UO{^@B%&913XyF1A2p&1SZBD zK@r@dH<$yob9tN}2nfxcW#FIY{!tbs8YgDkKE z$Weqxw9DMY3|){)`?|#WL&^Vpyh>5@%HlLmeAoxC1WRhzhH6kn-TFDSR7<#|&g!(z z>x|1)u$4B{O_I>aX`qC@1cN~UgG4CL^GpOUFi$WL1u*agFu;WJ9E3rLgh;>yOke~& z$WJ^F1jf_@JrD#$2v9^|1VJ!R0X0xTScLkt&-zS+L@-bQ6$JWBg!p_<#Kh1H)zHF3 z%+%b=EXagF!OiX@(V6f&`+`4OScYxrhIAm#NCXC5ghdzxLHJKN_=5?>(nOd~J$QpRfCD=4Q$NK6IM4$? z#e+HZQ$0Y;A;^N;98n~7)Rl-w`hve=SW#*i2db4A-xK%IMPSWi0|Bl!z|A#9n&ubR42s)M95V&g;FcMPc2;pJor;O_|pIU(qcW< zV*O7wwbfzW(?b;mEydF)oliR80yubsGoS-F;8rep18+S8ZWY%z&;u+b%pn+qOF+g( zb=7taiQd$|-+YCtqy`t=2Y7(dOwH7+90%r9MLofdSnHg~R#??xXw`Pb z%ThScNNCe4tNv22ALy^5=-+JWWW-*w;zrbV`8)e?o=8--=?hHk*u0Ultm^oD8Jm)E$jS2%@MI9mu7V+ao3wk6(V zh*keB1>EGN*hpYgopsR0eNy^#&@5fhNce*m9#)nmRvGSK%$-v~<=z!8;XvI}I(^|6 zrrDm=)*TktLfu?ME@2a%**_@aDo_P9VdDJ#1>M^({&ih%cu^~+T}}<#`kB`Rj)jIA z*fDlx2bN%l&CLp)f?2&%=bczLcH=v4P+gW-%Ej4`_26DDg;k)Z`T4;#>!M zSO-$}%5NA;`_V1j`r-zD<$gxhGM?b4#7jaz%)(vfm_<|Xd76V@1a9?H^p#=tHQMvl+@XaCp*;hMr~*lN zT65OTPG;SCU4<3>2HBNSc!-0c9%|wwPOmM_+iitaz-QgsXMXnQsQ%Gd9$rYK<-yd` zXI<%xEmQ5CQeltj5-H zN11*4KR) zhi9mUyV|WU4r8e{Z6F0`S!PGPJYKqeP@uh4T-{(Rm18tjQ##nwH!y>5eS`lNM&B=e zgFm&^W4&$M?$cx~R`*p_#AR;GwbgGm11^XHF4zKx*wZh#?nBmLY(0a))^4IbUu))q zaFp)x{#Mtl0z)Wg#b!sw*1!2X1<00cedSb3hyy6VYE;4LW!4O)WE+Ok>@D2G6;|FB?D5v|5y$P`E?Lfn1I^8GZ_VxY^;sQu2o@jg z)2x9kxCC-uV)lN+N_^sZ{o-oy1^}jSp(g5aNC$QpYX8<(unq9|%dP*XM({M>MSr*l z1#fT(umgYahh9wWs!qRw9?zs51h6L5WTj{t|7sB5?cD~{4F3Z;eq1%i;S48ng!Pv43QTAIJq47s z)OW63Fy{tV;D$>D^EhA!TK7r-C(EX`axhl&V$Vf3cXJ7V06VY;Ij8e?Aku(VzY0E0 zFVNPoMqEGj@m$T-?JZL^-BTSWa!$tsA4h~;Zd}G4TsXB{mDXcD?&I{0SreDjGA&^` zxO5%Q^iAh?atoGuX6^B`$aF0j?|mP15kKT@?eQab)i`Vjfg@^q%g>kTZ`|j`m2JK)s^O7%Zls|c7 zr-XQTd6^0m-$5w}+dM%*(D1dz~p!z+Xcg!7f>n7SB{^9>?4&os80^BZphj2~T%mP55 zg>_{6z54|eo!63oT>yqrS_g9%AnG`<1bqbg=5&p|M{~dj{Clv6W}kE5eFud#PgbZWZteBnkyTTbepbgvQye}6h`{~amiI&k2t5M-2*ji355hl)5-mdH5Rt-% zh!!PEG-!|)J#e_ZdBf2o7dmhZk`!q251cPtws2|r5e}S=Upk(7a|X^$m~Xzs>kCh6fj{*mojbY^eNP+Qm0a_YV|7CtXj8n?dtU_*sx;1{)%Nb7OYpVRH-`E zYT34L`}X0Zi|;O8eDKC`ixY<%w{h&?cw+qVB!txk<%yS8nscmF0+u59@-=FFNm zbMEZz>-sh9*jtS$o3^Qj7cVgBbZq&CjzEVL7edqn5s^te zbbu>=6O(sGJkm`{M0641Naf478$5_mAk2{i6E2Jtsp6uB6B)9vc<~JM_8oBqbY$8EUv8haGzOA&5+s zbyixBjp7zE;~2K0UhJ?lPCD?|#Uei4AfwnRj;W=}D6QN>8jwK>IV6!q0%=++sjb#p zh)p_)Au!1hlG}0yAtxUl#67ggd6ATdiFyBFCK3sl3%ZxkecM$j9h*P>q~>pHk|f=B z0@~>lciPRz6HGO^G@nZ!2^gS&IB}s;OJ=YX#h)-8XkbG7?Ux{>gZu%U7hvdchbq8a z_#~*IiaIK(rN%bmSv$5BN-NcP0}o*|-UZKKgULuEt=?3#7-MVg=+=)$3Og*Z#Tq-A zX{f2jnyJk?D-3P64Urp1bQpvs9uWzr9z&RT3+A`sdNMA#@$MFi zwrfU5RUTyBb!Y;&pLP94dXRgGNVMR2W145CMT3Z>M}q8b@h}%ru=IsS{Z$MHLY8`A zDMkrpR9{B95j8{>tNilmvni{*GRyxhZ}p2UXT_q{TBn>63S8sFDr;UdviRaQ%Y<^G zD!!@(Y_P{Fy)@HJ|AVBG%(^`FhRP5E#>Rg*7ZE{h;vo^2={;m{B%XLXE+%G|i?-V2 zM)F4@-r{kmorta!F&A(osBOPyTKWfc{V1A0DLe=?Q(R6OFV6N zF;3xy*I#`(5fola8!XT%%2bdG#4I%WX%hIIKvsf z5WN<(AO$Hhc^>>A2t();*2zp&H+xH5YDXg#8U``d*jhfE;`F{}|NF0=r8T!>zvc*BL@l!r`CM9)GNfe?#CN?Ym)S99nkAmDgM zIs%%Geh~3K<2XbR`pMYf7?Pg2oo5gSW6#0FWG0HF@jL`+;(6%cF1-0>PeW|U7gWNM zCX~PgF)#rl3yDYyW^eU;{&#hB9nXI#?34payl#C0l30n=M0j>|kLi@q#;YbYgdn>D?<} z5ev5Xh?O4wXt8v-q=SMG7{)NhG>{R4m9q2*KsZ7!C)P`KQtpU0)n)X4fW)o+Z4mMk zn1Td$x&2fG4=$P1PlI|XkPwh=^g2l3oJhYnx+g&v87993$RNLEOhE)uiAvg8&w0WV zk!EEiBlW4)d*1((pJ2#DGd$HnlG3%VcBKj=F`3DQdU6}H+gU{MGRmOwDuy)EC`W4u z(#0}XG_D-!T~h~)Ul;=#)362~TJVD(0HL#-1p;SX%Gu3E;Rw3qr8;qPhAprYVk}`T zOAf`$K2VvyYy=#zqKe$4J~tJ zdWJuEL7o3#g)Sq1kYWlhQpGCPER0>8TNux{of)(-jv3j`9aE6UJI3IO*|`EC*LcXe zUBQfVo5)1Q^N?$0YYs+xVGeV6r78%)CX@k03o*FMUZ!MT^%~#D__wd#=mt9iORH~q zgB;c9#42v~-=d)fEwC7{Vh^n61H1AUQu{K?)O&uR*_>H zpbY;dJoa0SQiP(v7gbB0GpUMIt1w5q->r64-UA$~fW^Fjp^K)o z%tFdIZ_%3p4a;8Rvix3#p_kC`hW{W5IXFDx5f9oR1VIKl@PQ0q5Ca(W!0{OOxX1r_ zAcG$CAOJ>3>!*5oF&eKY!Yq7%!ghF`G644}XXq(H`PTndl?3RoZv6oCig01os3?HwMZHCoP*p3V)P2`1d? ztzga}+@nQY>UCD)%|P!_AO&V%25y|~9UcS%!NSp=3Xp&Twtxl@!Z1Wz0B-*o(ji^{ zJs}i&NcD+Xd}ZI%ZC@*NLN!zaGLS>JeIfd7;WBi>`uW$Kp&NX~*DAC^DO^G+9KsvM zAso)39M&Nn-k}}lAs+6b9`+$0{-GZRA|MW;AQmDaUP30c!rR5d(?y}mSP1k9pe!i^ zH1I(W1c3@r00K~e28sX&D1ZVu00=B#@76X2!MbCC;$h501-L>1@u!X{KE4g9V8BvBetVEg2mIZ&h`0@_HF-PD0~7wN`gLi zf+SQ_KS~09m7AQ6g3-XA%*0GuY#%-@Bttf&Lp~%#Mx;beBt=%FMP4LEW@JW|n<{7& zBl6!nQcb?`K@9kS2t>dpo`B<(fC6ly0)l`DfFd}CqcpOj$Ekn{3>%|09K%f+r4d`< z?c{|e0Z|sEQ642yURde*01gzv!M)TH6dW)T+`%!PRVJS9^`0zdpaMF8C@LUIasVqv z06A(pN*)T3fC$*82#CPOX&^UpV{Y0e32@`a=_UyfVK-9a2_$E3 z>Lv>09xw*M;l-pV>gFekA`wOaIG%uQY9a@`01A*L2ZVqHv;taErg@&{RK#OKwN6@O zUp=zlDSU!m$|rpK7h7NyU-o4z41@LQl}2G7fCi|54k&>ZsDU0Rf+nbfE+~UGD1)Zk z{(&TVrpz!X11k7H25RDFHk@Z7fLM~i37jMXkfwH$0Cplk1kj{tj%WlNo)4gaOT8ZL zl>l~vB27Z$2~Yq9v}7nMAO}!@0`4e}0;!MwsF2!dI2QkDOCkVj244`Mz@y#XCsM!( z)E;(zXbNzEhgM(;?C1%2Cs~3(31C1m{KABuDVjEgdP1E-x#xRso16*exzP-S>gOYpa+pem}NGAg1jDx@}Qq&}*oRw|`ls-tG= zq%tah-l^QB>9Y)jF`z;aq(GN$;tTYg3WQ~HR$z^CDGJ2oCW3&eu4+rRXbv=9!pQ&- z+}^5=C^({k3c!F0$iPW1DUg;X2?*(kD&RD7z;*H{X;$M2tmuehW3H0m4`66m;@%I$ zq*#V1cfJ5O?&t>20Ct{02w*@mup_9xYe=psn@0a#wgF~f!VqKFXVG9(ovOxuPNBR8 ztiTQ|!4|B+9xTEptimoV!v-w8HjAh(gA8zGD7ruq1Od7#0F@@EiGt#nrT`4c>c*0* zthVR~Ez_lLU2vXX_ zYGMQc0j7OoxQc)SY$-Q-r3lDChn_$QSU@s7tk$ZfF32kt?iJbHXFXma(cCB5MJ9a3 zjHkwGa_zFiXsfW0J#$DC${9qx&Q-bV9P3i z2&f_qq;C=MZUh{`?XhaCg5m`yAZjuo@?roPq*wT^aP$T2*GAph?yK2i6rD=1zpiaO zvak+^P=zYPC0HU3aAPQn!0Vx_SAzd22goic(ke2ZDkr8uu(4!HCL;_0a1p?+h=w8v z_#vSynqT=D{4xx<-&juY_JIIC<%bp3~;A*#-svl zU>k#@ZDQwUT7Vh^;0_-$piNfv+OS!it?xK8+UBR7%B#B~vL&kwFu=kkK)?oY7Y>Bz z5{p3Zt*;1FtNVh0D%SB7-xC;9DFeU25$JCPV(#eX01zkvrK!LGH>=~es;rJ~a$2qo z#A@nBFf#hUibC!y8!#^lu>~(~CR%Waa=;P8_p?9$Ge8HlKo2xQ7qmei zG(w-$Fnse^jIS~jLn({_7}P)~hX4>@=yy^;2PA2Y7HP}U>gRSWm8O92NwF(4@Da>0 z7LTSV{@#??Y8dBi$ENP<#__SnGz3Wz9^R_-gOKoJD7(>j0%EG{2=qG&F0kdh;` zn(z#4z$bJwLr*nH0Yil@09G#m1Y|W=cePey^;U=VS9>*CZ#7txHCm^&TCX)*x3ycp zHC)HFT+g*zR|r*q#W29aCJezvc)S8K}>wM&B*OauS&3E-#__b)0laOIsq1&ih9BBL(1EGI5AP_wQB#DJ83qmK%* zkLD&$*50sf01X5}EKKHI|8^x^H3UomaTm97A2)I*w{kBxb2qnhKR0wow{%Z8byv4_ zOZQeAgCPU=Q~(ieKy(dE0T?8LgP4^eo#F(>u6mpBPMc^1q^OS`=}YFO(2i^hT=Y-> zG6jf0X!RBBlQ%h(9G!tYXINJXh)Vo zciN|)%d z(oS7ubc%d~wsYz=G7Z}GN#a|V!a zaGsS)MaW(Kc<$t0L$%3^OEIJW1(bMo^6r>%xTkM;L&qe*2^zC==j|7pg}{2DX0*1p z+?ES{QMaj#SEErrnlE(kQ%-&l*j!$?(zkHq@4#qJ|9e%Wt%vk}SWwb`VZlk~Uk__K zYP+7hy!xIqa%Y~s%f9N|JA~Np%SRqVKw&iK143*7VYxp%qQLg96H(edmU!jKf8}4u zOVT_IILQal*L`nmLPrB}`^M3nbbIZv(<`%IGF`}kxv%!RF42_K$acNHolEhrJ^OZB zboQS0FG&7bv=7U<0a^^O#D0JM{?EX(q{QXN%e<((-iphj!mdzUFN}I`!^RmaQ0y4q z%&gKD9ox8N-ug=C)I98bKQfDQkqH3+3VbJ>l(gzXQ;pE1ndSo8fW{3`Rq z)rP;bycrN@>Z7N4G3de0mxpncIv6jcdKykImWf@$p)1YZ;1Qd!ah7_z#}Eve#m?E8 z?rD;GK`)L=Bg4xqQ_{BDVP`h?iAU84{s`nvD>YR8zFqfoi|w3d@W16=jj_oKimFV6 zc!$@Mc|0~{#$>-iLs)~jWv!2r=c(+Hm@f7FPj)dAm#4QTf2Ec21h}=z=d`PXt{kkj z$mh48lr04&iah{63}aRsMR3cQ`<$ivjVQIUm7S%Uc_EICnFayNI3O{_q9utP+?f&T zJ6~g4mSqjUqe2{ohZB1Wb-#x zv2VQc_=_~ipwv?Nhb3idU_zl`zYbD2(fCwLj9rA3-c6D? zR(4l}!Ybh}{xsU9y+Hn%x0yT@f&|NqH=93|fpcdi>4GMcF3PAec{NTUIo@DEP*mv# zyK@q-x{Dts|C(mNZuPB#@dP zn+!1%Gcr>iH>9hBSuYbc!+K3c>UOHD`{^L%OY2$o_22O~lbqcv1kz@Jue3Ycyp;S~ z+caaZy;Aajn?by~idsAK%oXvkt*e(BBK*=y~c#^QlXZzI;jwqNSaH~lB(;pgC; zZx>u>R(tNnhn>{(w@>xGaN66Ev8%aCjAfcJ!+p^)N~m@2_How*mt=o+ z)=D>O8OY>i)|gbg@S5W(&x4}0)t8k;jgY|kEW8X%?QHC8k@eF^UM>T=eOa= zyr9(`6X_~m-^xdXPZ?-Gb@QbpPNgoB%k>vK+;@;8;B|7Kyj`Fr(xvisr|!9g8qzvd zwDtn8i{Vm!e$U+*{z9@$aPP;;#X}FX^NS=%SRDMxD0_{ZRYUMdH;GklD273y>#%%F zhRPkWJ8PzR-><5~`r7w}u!5z~dv12s*;Y?}3?`Os@c5;<#Bw~}d&d872-k8{s+uk= zDjk;oer@LW>wV-Y`^4w--H`_Fu7qA|lbX$TjcI6ebhj5Hfx(HIw^xaLHCmjI=iNY6 z1jbB$c=1MgMnl)&w1QeYa4M(C-oC_gCgzE8?K(fkFeuPawij{TId@^FQNVlee_k1( zrwwd;`WOh7%|6tuWqP`!7u&9%`#pxp^a{gG&`x$sz`F|Jl}B7`NZZcg4TBxI81J37iY>rN5Ao z(hp@*`M^J$+a4yLOb86En7{gXM1O_C(V=Bt`%gTJFHS~MM^E^C<9{Y`+4Yf2@$Moy zyhBEaDM{G9Q-dROvaE3OEo~Eh?(lHpXrWQKY9 z8zJ8OV8)s6eu=-_#pb4!LZ~xD4O;7aBJ9fl!vA{PVqd61$X! zb!Ps8*SNs@T&uvINy4H~x>7>As(MUKK;PPIivEJ0A*D5PP>W9pw8Lp=I+vD6HGFqG zGKLwncYoMrEe_NaGrw+^CnqE&QOX7LK3;ccbK_QgUfWh?+OC&G~bUYP< z+vc~Pmvu67d!)5#cC+fynvz+Wl0&UggXePrlpcEv-{VVn^6lq^g9|Qy_f6QSwP)?9 z~UBH?{^OS8MBBO@Jd zP9wQGR5Z9cW+V(xnVJURcq(g!pM8)vFt^iEobm}vXy>Xp+p=0Umgkt$a~c0qAy?C~ z8+*^xm_;lOXaSGtzdLkCABHff)#HHzYi~fa+pDa2Z64;kE;v;dRI9S0GxT8a3~X$N zO!mP)fQ@GE=fH`ft=p$7vo z%#tLH$R1V+zm^m9x<#qIH0)n++@)8k`s1H^suKrR0_b~^!{H^lp`CgEQL#UA*Nql)0q z|NAo}IECx`P>m*EH@frPZhvDVy{RFk@f}YmmEq#{a`eJ)V)R8mnI=L)$%5NKN<+k) zi_>j)r{wEH_0esmA0ezaoLd@|oeic}=cEtU2YIR5)`?N0Rs5ML)P&<}JI+a|GFBwZ zUsu4G#zDRc@?p_YjL>W4+*kK`O#Q#c2zVeXxH|<6?PO1wY}m)k;~TdI9Ms3cG%r<5 z_-Cww?s2|7P;-aL7OZTH`NH5Z$qCerTglq4S_nfkD}*S_x4;C(K!0_g0*+H-iFiR>-L^p7HKK_lA9DN;m40> zj!$msrrzt&V~8-P=oMILKZ>~S@J*BZ@-_O#L?8w5QFLj=k+nbh*<#tp)ub$nj!Y6= zhVi>-(=~0!Q!fur`|~2{gS!bXg4&n!xvBp;dRtWsJ52*Wj_SSJNmYD2df~tN+V?1Z zLF4BW<)Lypqx?mLs;miBgmPqr$R|g(slh(Phg)E&_Mno2Z6n@G-RbY_F}!_ZBcX9IWpp$Q3QLE2<}O_HuQ$u*eoEKNEoWPljZLLBystZJ#l|ygUm>UL zL|jK|Fxk}XdS7f3B5Ev~`Go6>(|g$imB5D}8}t>$)sbdy>+O4SN;WGV>@U<{>DMkj zI1chRgn4o!Y>lf^|GhD>`L*-bCulCyG<-(b{N@+$&yA-84Y3fVzBQ+7ja!$s`~{Ch zAV=TVB2-##URx_m6^d-ByLiAj|G8$RE`+o&UH|xf>77j3{mAlGx)f^+>VEP^(YryT z8Y35)yK(<6`4ms2FtO#-fr|_s_E+;?9sjywHRv^hoVm^i;x0AYcDfA^p8AIU0^s!7 zIm^amm2vr$uPE3wzNvl(0d`}?aFMdNgU%oZu=zNW*^FEOX^V`p)J8EjZ~IQ4DsN9V z*BlyCJP$|zWFe;PW_o<&-)(qHZTtUizr9RK9+$F?s5F>-jp%a@?psX#72p&5L@t)P z&pa}&S7*vE#vvbPctCwH>>hgGc!CjkCjjh+h!W%PQ0!m=fx}Cm-ZFUT~ zG?wh}l5NQttQfBqw-x!v$_&}&NNaQ4pAK@G-7wz+J7S_nEGCL?1r9YT5fc(m0($BL)zaUc_;KFzaMx@#buP=m9g`VlzVytL9Ncj% z2Ab6hoAJ1lq*8W!YoF1NI#V9?9xJ@38dnUq$^19LajjnB->hI8n0;Ew4E`jYJ`T&? zV-5*$Uk&(F+3aC%^)EzWOEYB!g?8XEuGUOMZd)SsLKMwR#7@nQ6TY{8(96mwb*PC*bjpigz=Li3-Zi0Q^TBvLyO2|C( zAon*~PEz)QA{Cqv%97q5(0csZNr;xos3P#IR_xFKlx7_8h*;_AF5!*TYxM8&Be636 z7JQo7H35_BJ+=YRmODjU2fxZ?*kt3_VC=(EpTQUJp55V( z=sj}t9n~Z06Rtqh1FPQ;^xdiE?)?c$>5~nvM=a5wn709(TeBPyUbxCb8AbL8bSQJS z-FqHou7ypB5b?3)q|``-sWS@}70ZvTx!Yz53m5lbPdKU3q9}G{@(uX2*hCjXzkg z9CLDBWvJdvRq`d*H8wow7?HDYWYAEFHYI!DpA4Tu&3U+|)$Uy6X<6tEM&fwdn^Q)c zmi?NY*rlUHCN~d+>jL_s8AiiDrwgQZW=)PgX@sxDmn`mW`B80>-1&k-?fpR8f5WuRyc6eyU9+pCS2-}~2_xBXTF@*4kx=%8shPXB^;gQm>yYxK^a;bn&{4cRQG;n&eH7I<8E~Lzmx=sJ zhea1qAz~QN0p0j_2Z@DW)tZkyt`@}-z?Y@h37MJy2y+~5`LQaeYqS{E{~`J4M>_h% zGa@?;WHzS|AM(}MJYvybtp(;d8=%f2J^$qIH_S20Zu1-N+Kc^bghAEsyAqhR&8zdo z5N3EyvV1z+a&70vage+FH;SP2>8S^qF@k?(iYrc39p3tLsT`9fmUF25iaRr-GbEY0 zwww`PefBj>TX0e3a7kx!A`80kkD!(hKgU{c$2^_sismUf;n50;TFP;J*~rB1N-6oe zIYqfew!2x}JBz&R9zpj#PH4DnFkPVPFsm{{q<`aZq?J@Qa5Qx^9Zyu;3K_08_&|5i z{KMWd%=T4q=_VunSU=Sg%DViHzn!Xc7>Q!9z-O)k-Zp)$bh_9{`>1L-hPo=v7xoRN=q9^Gy#^lBWf$7B5LKVTS`c!e}(awlcy+u~{>|w*! zp%WGf!PQIt9;CP$hvA9)rvsjD_n6gqdDF#?y&vusLfTqR%vH%=&F1-4ajUc2q3O^z z8ENS&e|BiaE+nk2)$Jy_P~DGO{^Hgt=B%WPn(J z*);|#e|55hikT67t{wu_Wde&V$`6{NM>O~LvG3BdVym|#iyx1A@#z{!{YNBKbh4&t zYF%0|-gjtrRz$MJ9%9xbdTRIXKDAB_c$!grEOT+fO2Zua_Mp}CPWm@ohM^Muf!H(X zOrs|#?x_vvYTw0$BN^z|-5bb<<)5quDpqXg>9YO87)eg-J zKGfA4)j<9eOhGqZ@N`Af;?xfsweilHmAoAP{;EcCWkj)ha77ULa@CJ?O-@cei72N) zvvq4+%w7xA+U&QKUe6r7JY&_Jm$wBUKhL-PfN>QHTjcnX8BzR1h9T&yX>-aFTTbD< zWn$A&^D7V6qd#X;j2c-1{|$r~3X-DfqiKizcy&;^ccyH$Q&IcXMa(m1OBHqP{H%eY z8X)%xrmGtea1cKy6~XDgYoVnT41*n9oysg|Aanfw(c=wuL`2rFc+d|Lg*%Iixh^d| zf;FbuyBk-#1Ml#UPT`m*TB7ajGkhrAzZ03lcyIH! zympw`)Kq{OwDp|+xlAuD%clDK-@(_!q3QB13-tVEG zDEI^XUBGy~YxL}q(v^g)!wrGnM`4e|16vTk)9`k>qGf?EzN9?2uzc1sKjmz7)G|cl zTIp{ey^bi|J6UW@vKqZQ5ft^eS~Sz}=7w07{LgJfJ-6)Emws9QxbWl@U#VY0D#xXV zQ(-(fZx>}W4r(qey3xCKr+@HB=*{hdS8SFulYe>3VFEFNZ?8~4#qTeL-GEit#sQr z!g4b&#kW1z_+kWy-Rod8A&m;3k>f%C{ycD}u9@B2BYg`mZg1PY%@9LqfzIE9}6yoD^+eF(8Fgej$;*Yu7K+1dG;Oe@nrf-Y3t5gsAMLaZyLe54K1VI~SH z{C1w@)k?f9zkWHgO&39AcL{elnRyj%Z&RgfO{Cn)eBT!mDwy`Kq$w3d`-%u3=K9i- z_;P81w%MaMx2~W45iq*Q-+1@OoXl2X+}qRt(KJie<=3h1tR0MBZ0rK;<#$G`?q9DF zEOp-BClRp1Oy0DQ4xB8-UB$eP{ZrGGt?rIg##^V+`Wm&x*sS$cj1ip?tQ{Oynze zX6t$?rh1`oT+$vPKSeB>256ammxv!~RU9N$aK$0v#5t9~s-2anw|SpK_pOQKq$V7hmlss8nfnR^6? zdB2F7e$@|E6TD-46m2GN*J_%Y(W7D;Je(lCp+8ya?xw`ncg0S9L8a~im&XRf2)3g4 z)al`jrbVV@v!H24N)t2R!WAjjNiO4)ze?F9OeNy9k9-AfMicVEO11W!H*?o-5Lnt^ zDsB;HS&79PsrP@_=1+(J_wFIvzkq{;y8A!Vr;EJb)(&I!VWUfVzl`5ar;Zy)h=;t_ zdpTorqXZIrD=Vpqd;_h&Xe-5-ju5x;RxzX8*S@4w=U|Sj5}cT{G)ZI2Gcr+^PQAbJ zp^;T0#r9!t;U~Blip*s$`d~Mmk|9Brci4)o@tE92zlLy{0-}v}1u~|XhEec4l=SuM zCn=O+vHHotkD?;Td8V`dIhb3Xq6g8$5-(6&ZiHeWbnStJFUyLuF5@nZxE%J&r@oSe zLCr)grlXG42#f016cP#0Z%a4D%80Hc9KPd|?OxuO#&(aNlfRV7Muw*Ubc3695!0)u z#GLh++4ws)Mv?|hZ+9oy3Z2r)Jln|V0A=I5o14Q9^r7t1+rz$Tq{y<-|Zur`Hnsdu($;mhZGIg&H3T0d8$ZcvYC|M-=PuUR z3~Szr1~;w%-Hi2beD{ORQp`imnzO2m6ccPEtlMJ}^5UR|NZ^?{>Xbo*j$txPd&zUy za3hjJk_@%W0s?DM5z1boH=G3UbxJ|3m6$3`dLJ4qF z3~^8f*DB@+;IXCaxI5K6JFqSGf@Q44qpe(YZCxhq!bw@eUy3N4Zv*AUc^Zd*xJ&Yr zoSaWy{`}d5OSU)+bXl%RYsYG()6K`4pP(6x!-n(gXFsT^P5m&!fd!Whm8u`{y~Ib1 zsN~d!KTrH1blbN@^=FX^W3S<&NFN{Pj!hnNW*#kzCOy(=5Vh;t!BjIZ3U$!TStK&#BHR3HF#w4v|gTQT$ zC}GQm+EQcw1Fy1QU88r_nZ&8(Ff~lPM{u%#@aMMED#dfdf_stkg~j5z`IMd8c_UVs z%~&>XfHMakbq1XXFnxF!E7M~m?|99^R>WxDYM@HI?3ds18%`dsBe>TWC2ZV3GyQkI zxkJc*tfVsjTN<~QZDNc+2Wlh*!cT3q5>d=H?h7c(*>6=Mg_^`Ey>^X-d4H3;I)aP4m zFP}_}H2GVT{p4$}J%g=Yj=eAi0A)5GyeK(k4YU35JK#@q&w|U>x3v)#35!y|0eb-W zf|wqI42IAkS{!?==Mtj~S}(?Cftcm%Zt!m+(oo+z>!WJxhg1Wo(+DTpFXF^-Q)BXD zQ0Viei66J7_YzZc!yZ2`HS#qdVmGP}uej)Q-B&52485fPv+w?cZ!axY*gWvRURV5s zwi@@DyV1A#<?J$ND#+lEg2(8Ay&-ZdofB}%MO!15u;I=Mz=s>bdVGstcQf?qP;Gn zK+;U2z)v1lR?-qIA zk%Vvm4{V!;_d0oa=MjF$D^9?a@Mn-AG(@u++(stlcyqQR>L>ff<5TuqH ziwUO4q=9wlVCgiFI0IWom*>Yr+{ER^%m6ni~9NOlQTEd_6ara|x8Z zsKdFGf!$1I#RK-1eIyrBSurVlP|#TtU6VgceJ2xBm-1y<$FvrpwUdbgfRcY?!I3HF z@F3?0tC>0xK05APF+2fMk$% zl2yS{Wc60|}o!s>g@rf`2DhFqR6M5-uBd#+Ei97$fOh!^a#L(0x8hIFGwJP}o9@hI1PQbP;f7GeyW?PeC#m z{1yXf`aiI2D{ump#}1E8{+Y`?p~fj)R;-sdi3I85^CSVFkR3|dPM*05NE-k?(1=q; zC0a;i?|uTP`4l$)1e=tCI7$IrxL9c{WGN3MdA1rmieylao1u1N<3KT7qBIH|eO6#3 z&^*6#%B9G?CRV5Pv5grJg-!hWGr?OLBtuV7#CiFf6=a_!B$E3POK^8S~E8 zs#D*1)mInD4;aZ9S}FX!Je0p$7zwh+!b!7XOuvHR0uaV$K+jS{d|p|)-)%0xvg`?k zbm_W0AVPPsEO!TVRUlD@mS@g%Lk9~%r$* zyjb@2fBcCzr9ry5h6w4VDD#pPc*|NIxYjjMCce@UK4VmI#{->{9vxQLLke|(inoWKQjT8CJqwxR^-ZWRY z_Bny4H|kS{G)pX*bB4?ldMA36em(W)2TBD)EP^3=X;p=L9ilF&O~%e5$Wr;z&Q$YD zz95!TG(NroWP(o+M8TAKy52WDgRedNuy>7>xxcCm5rYPs9fGM7Kra)#Mlj_fk{Gqx zC65GoqKqbJh{`zl$D7w>0Oh$2r=Xh6Cq)GirF*d^okddEN;|CrO^a&lgu?OqMk7HW zV>hJLzxw)Kf-<#ZNT8$LB9XfwhF+iY{>;dn2oO5V9}$glSJ^mf6 zOK-$rAv9^?Pc1}B+l$*o_PwM2OkhHUn*`TO?Sc{e?aR@FN7Bz<=2dYw_Dtn> z>$O6RFzx<%m1rus(V4V6R`s;t>`@kXj8Ww+K|BqW+Wy(8wS97{1Bw7JDADhm3`m)t zr`ZLB?ezKdwjBR=3TA|ZRC{8PtrLy`lZ}vt;SK4{n<|TUh|3;_ER!)iQv`APYP9dQf6?aAOy+ zCHPs;B-1hP(04xKi3zl0e^OB1u)BBi!Z|^QfJr+CxHhHv&?vm9d%%s_k12&HQo+T( zAfCgiR9nSin#34@F?c+|R|dp|DG>WP5nvL|MI9|oxE^WwcpKJkGtqlG_3Euu{T4%u z>#vdvMyEwf%VIeY$mg?Qvuzul;mRJvCXDzpbyZUy$>BxqO` zqkS;S9HgaAB+*rcSeEl7`cYQPeY2DOjS`dCVKY3~a4`vD-3jQS?he zeR|afy}zDYiQyZay)tv@cf!j*!I;umZN3*PYtz1$AOdgshJ!D~v_jO=K%y_Bp&AHF zq2=|94=g)eN^9dA!7x_=;Ig>W zu?uw#zEQ#7y2#IA_qV^7Q@iOHpTv!wUR~#KFG+B~7DX2x{&%${%4Nv>%0IAd z{e~v-AQ&PER&U)y1(3S86!`NNoFCL{py{>Bko~Ve!w1|D|oN#@YW8(oPcMPqcK+DSa7ud zw=i(4cW|OiI4nP>x^csKbuq9v0TSVN5#24m`$nkXL*sTa+i1dm5#&+Ic6`dV2QMV< zdhp}%cMMm8_XR;QxScG(8L~J*nwo$vjxLr4^PkT@Zhdx^MPi_TH{>}&Q%g;#1KTPRC+(k2)9nQ_}fVJ_!48Z0f2I1Mv=tzg= z(GbhW5_bK0{(T7vDcgfn{pO?n@0&x_Q&yOG-&(==Y^y0!YOo|TXDK=l*T5_n+M;fLbC z56e=(!rMU(sJ;$`W8B@nE`^si2b0RVFV#_xpNqYar`ImDGTo&z{`d*vcY$z}LLUil zdL2OgFyOpHk2u2oZGHSpja?NB)%u$5Hy9)MbsBB(_oq?hBD03AQCY<3vzZX zeA77AumxV7268t{zq$c(2f&Y+A$$kaTA9@YzeJ<7;r`o*Gl;oJFh~Hy5P^ixw>q1o zy_iP-TM-;NztV+9?x-VcTAjXIZ6+*1kpgO`uleT1jNp72{0S8(YMgXlBcv1w^c-PB zDPM(*56~cS9#m4Ym{|y)ii3Pi7k>Q%Q!1a}`Mw%^8=Ka5Uf&Hf7AGAnVE(i6`Uj)f%TNaOUU z2%-#7AxXQ}-^)M_i9#~CQgs4|oW!RS`a8Fc$W|YMLk4Yo?JudIg|Go#ucetw5_KuE zUu8d-vXYH(T=DLMiF)s%QgKtjQ}Bo$yNC`EIIpkD)`OVVLWm4?CSABp%>D1ouL)x= zWtXmTuLf4ZR$`zc(DS%uOh!IEBUm3U+kU8zxcItNtfn+$LJn!bb;ppyLS=Rs#^dAN z#NrleD~-!{@g}2EsOt(zk#u*kbK{C=s`e&zgUpZ!B_uf3dZyrkz=L%54~LD-KK1kG;J z*)K8hjI5brx?$WK85Yd#U;IQ@!F9E7KA{cq+7Sp*N-Q z{V5xSADJP=c+uB@03kUnH;^Temck^mC>pYf8qG83i+D@mSDf{r_C1U@QPEf{I1alN*Qt=TfJDo z6{s(s-MKrH8ct#bOChD>WwEb(zQL7bS6&HVIgIDm~1Sa|Czq{*SeY_sgxXavnbTwfElK zHT?b34JjO*!ISa04Gv|A8i21-nH1?P=m06=16MS`w{U~iZreaM!8QR#n}o=BjUmo+ z#Pa9j7)1-AFQPF5&jI_!d9s9Rq<7z|YwiNHv#_=rnJ_PH9wzJ)%jyGQWXIDX9BIR+ z`;CN>HE}ckNea+}SX#u(rKj1YnH>ssXZc(S(3PI&-B$;Iki(L&Oc54@Au?7Xv{G0I zsLyVPCt%RhlEY}@X>Y73ib`jY@&O8mw&`LR?b2cq=707hObsRGTzn@l2%j_KkkVti z72-Kor=Lc?i4sLW7y}EoqSATrhRRK)`YcE$K|3qRB{o=@)Cpj4YMjnc5pNnLIlFa^CX6v${T2ZW_`qw@{+7|$9pQ@IfQsDn;L1#k zWog%s)LRCi>eH)o0@6uLKp<0pSKr;~h9i)R|I@9m+ihZWvtPALm!m6TUkyiqOYud;Otg2H?OZu1JtqmIqvx zM$Ov{vDv#ktWyFaOX=ggKMl}HNZ=rwH#k->omzxK5niDm$F8w^C>3EJ3TG9S$Pxu zQ_KN?EkTGR!ThL9*unv}!Yr_04k~u)XA?uP`Cw!S59Cy+wiHsn{ANKP5Xaq)VT4Z( zFbQYy@)ZJValb^Ek~G0qix>IVJ9$(q7Y!i%MuA*XD2L#6OL#boj z4Dq#qek)YT5AI7NOU|hu=H@K zi4G`|S6zZGK?S^oImes_d8GPavZL1cA{peB z@4OS0b7vsY^mv+EAt{I)Q+a2g)WKAhP-7|ASeM$39NPpAtc&|aDHYf@(dW_f0d#W! zXfo^o*_U%y^gJ>03fY2YYIJd*&N~mV=lf_ea1N?BRYy%r-}7_ay1FH<+%_GX?cpj# zWUx!q=h3_)FV|WI`?NO0?0_TOJk(@+AT=yR{0olZDeJt+LWHFaF!7@e88`rBcubue zx^h^hQv)%Z-}t#>HG4v%<2pep7H&DPVkK=UoVwFqtI00>^(XlDzSg%Q4+6`C-`^aFz4r*fq&j6oXd) zfyE8#e=PwE;U>}HF^8wa=OvWlwa467eUIy6DtQYxI-+%0}mEWPZ38{=F$P)H!|Du$H=B?za14A9yg832>g6gy`S@(loI zDmO0Jr0HLM{|HDgBPqZLEK-l2*k^u|B3!it0{pek<288EK!4}+J%CmezJ(JiRwb0>c#0Kf6Gmg-q) z0NHc%xlU<#H7Q0-3mH+@iM%2>ur)!!>|JF~;1loiL9b_a3c1(JLj2ljL$ik|4G#9XvTGg#z8WU(N- z_@N~Vfha?;!;sI@l7AU6*royap}9QHj4XU|syo0(hekk4AZV&epR@c=fouqfWDjNZ zk$TRB5{W3o$nB9V_&{E$q!cBH)o-e3>1Btc-V56~#eP5*Ky0l!@bNO>CV(7!Iz|vR zJ11hF`FsOknyy_80wsI^>*O}c@2FS8^@;NY+gfhPD9AYsgU(5H@~#96jX;f`2>N5* z3Mr^DQt9M8Da=W=qCNQA!OEF+kPae$i zrDXx6om>2tvxM_Yb?C7xg2V{lxUoba|FRUVg5Lp3=*uh5ZG+MR*q&;oJ}<|YWf8>p z>iDIAXaE^`q9Q~|-a9E|p#fEWNcOo1RV>)mv}iAQB+!l^eOgMk$3m35l59%JR(Jc` zV{A^QU;!!?zbsXQl59%&;_Q7O=dg;>bs&Ran@n}G-68QJ)<4I~Df{s`bm1I)U_1-K9_eBzvz zA&~VNbIkNddW{pB(F3iGq}NFKGOTEG%AAnBx=7rSO{CUy#c%L8@iWE02;6+J+;m{q zDt?2VwBe<|im^@xW4eC=IiWyoDJij*dCE7lFdfQU3BrsK()5TH>`I(Wta!7bCla-yDRV-uQ?MHYi!u`gwiamo{D{|7Nt6ygs62snT z(+wHJ##z&VT_m!xsg24B#J_07q|aHd(8l|X=h6Z8<1^_{$ zxQTmxvS{GQ(SiVhOX~6!O=h5u6dAcJiUL?Y(}(`9<%<}k1ZieV%iHVt5PP?!dntrT zmtwJdb2e#7!hPmy(dDO9{Fnfvvrnv?GubLJ$>RiqG3{m=a$XM8PyXb*Y9wZI*2g0= z-uRL&=;lV-u!wcKLpvBgJdJG%i)Q(RD4KR z#qwm{9$GJmg_ z{ZycgBdu!a?xn=MDPBH>Jbfsi)Yu~oFlYNig*k|i=Jr^2{w#dIt;vaPjhmXBvqtwm zr_mqp*O4(bYzLaZ_tZb5-Fu}{rxp@<@Bn4#yTX8Z{t?2c>oXbWGe{}yZcMME&s#=j zvMaJftl2x!bwgst`$_jTzp1yQlMqZPPz6nL=UeuY=r!)?lez;bw8gI+FY+{b`ITMw6b5{q<32L9J z!{1a}073lc%j9=BB$$0Ew9)5uU`{Y_&~zu0v0lkGEl?))_cHUvK&ypZ;KnJ2QFY}# z%Z$11b>R>Bki4bB6f9Q@Y?H6{xq^`_@#zmX&yZzIaMW z>y9TUePAc>Yt`f76hcquo67Z6kKQ4AU`+X&N2cO^Xo9q}hX1KEp(47RXrAO%+HQja zOXoWKlaq$*Zn;ub#_$Xjt5;elkelIO+7$f%T`zfR?GG?XZ%1M`zHUm5lhly6&UbQ4 zHxqSA8JapTW!jRKZhBLiKo}nee@wuVUqIeli?KzLsT7ej4Tvvr=LW_xo{kfwN#n zd-HU;KICVtqwo^9)+woZ88{y%@k~J8<62EqGPgqKg~m$obRzfz->t_2dOuy_t%omk zX-1~i6&<)lW+?E5glKU;ICgyf!OAADlT(uO?zZlg1l3hug}rHOHuH}B^Zr4gPyR{7 zK?2a}153yOs7-_Jb_0E($ImQqIZ;!8Aiwa30?rySlhgqVZcUJpaqQAF5BaF9md3t^ zzYAOfe~^FE%%FFMI=&Qnbwhix{oTsR(M^hBvftLNyZGi-CH}MsXqDc}oF>d^uMq>f z^nt9!fE50J<`R?*2tiv2cUyFx5$(UG_sfM6$St?bdsM#6b~groR6p`g%$R6V`hPJK z2Qae}>gJ*`tP5~=V#&U3eJ*s@T(n!^@QCS@Fneov=EJ#pK?yeo{2T&~Xx_uqfO!1j zMG1+av2gRT`J-wBd)a6%urKG7fdk-^bm*WFRyR>qs6)!sgdQ6SSG_m!7>-I)A*mP(FC2x&$iy&Jaj z3k=&cx=fm_UwVsYG4F#Q85m_#XDMAjUgdy$)>kC5NB5tJOK7_lEgjghz_0?HtE*#7 zp+f<3QP(|~?6R6Xgw`@i4BZ7nYBg{UWn`q!pC~B`{n65t4_!!t$l}^VavS7qFP`n+ zUH|?Lp1ng^+hqDY%}&|-`Arlnz$Jk1GetIt_VFq_YGKD4Cd_b0>$7Q7g6rU(zF5;o zIlVFFTvPG9v+W3n%eo*W2!H!k#w z)s;m&*X;q0gGy@4o#i_6)oY~h7pOno-X+d+uHsaDo%~09>qhV)rP1Ob&EI5gS2!Y9VhAMZWdY6C}AMbo( zwTi6KRnkd^c}1&0_a_?SZHPi25))MaE)uRTYRnh6pJs1N>_2kXoK#P%fa_@T*;Dc1 z^(>H6&T_w`^>azN8|K@2<|spbR5U zV)8!NO*6tF4V_;giG=E65-;I$ussOv7A$SdCytFUG3nm2&*W7fp7ercyAJm;1-{HR z^Bq<7deg45;&wD{G0YYCAS3yq>cgSNBOx0bZJr@rc;5%Ful)RJmB%-({SYfa@LpBp z9ML`!zpPQ;0+f^Mco5n*+lY;a;yIjnK80b%+eC>X21UO5O7D9GB2VFna8>7d4dqiV zfRyXwn%u*}Zn-WCc^eOa)ib}|-Fo`(kL$(u=>u*e11Q11x!M0z{b%ag_LiBz;;n{; zMQbL54d7qctl}{u;_(%xGS!@FMV$kn|9hE1O&TEisT=@y(Ffc_?SVc~0r2_F_lAWG zbnR;P@S$^=-E0MJsZBDkDZbZu)H&hR={p9dlVz6~9Gz5#K%`LVq~JA-0oD_l;=T$H z=o~i1{l;b(k_DqfL3;a}2>q`cv@S@y^7b~_*y=Mvu-I6ih^+#{mrn~|I_}0ihVtN2 zC?7q!q!R%ZPz5LxoW?BfZ?=X7t(zzTB zcX}*wXKc}PnHIG~vv|wna3-WAMu;dUobNozh4}HO{FsJrVeb890ZZ>ZnR@ZDdzD(Z zTei=rz1o<40BK=3JD;->!W2B$S+>VkC88!nOD+h>_zzAxu??k3R7E2KCD#cQHVd^S ztPltq2WG#jLt)knBIuf>_{9)z@M|(fAU{T0_eu^(sYSZ{p%573-Hu!7u`;HtW=iZZ zl0Rm&LhW06k)pqECME@7WfRdUntF?=8|#%PsGb(7$8%(IG`o)`-Z>uMV!vJ*dHmIi zi`}ck@LWp?Ozd1oWTrj*5vKqi%B7~!8At!JIR;2$^hZ{xGaP-vT13#3byD+D>%P5hLaiHJb!UK1O&3R;gjh^i? zl~B8s1dXRBMrUan^hPy*dXtWKk``^CrO(QIi1}Dwi^0aL56jnhV+i@xlru-4d|1BK zZ-TVb0Xug6D%~~+#Q5F_&8{JdSHZ;+M*b1go6dhhT-O;`c%%K`6>jd_tDkngv!Cu( zZ7XO|m(6d8HRJS!Pv+YD^|Gr?Yo(^tO*y@eE+w0CZCokNzP+yp8A)1?Xa^A0Z)O5l z*NwzNv7VxMCch2TDE%t&Oj2S!)RJZ-x|)-0U~PoBoZ=}+lNG|ZEKeMnv+tBr^pHIH zpiAyN;bCLvarG?qsgE!BPFN^>_#`EIEXisz>bIDx#J)nt?7%RB|0Q;DYZLrXBj@r` zKJIA$+=?!>2m9g&ce=rEuqua)B_1iry9rlBdb|{#+)R!8F-C}v>18HYlT3r%IO&Q> zubv$%<-KKu1WoX&%%1*wPR8(i(0J5?Bi~{k-056sdI`_-lIW0k9Kd7+7!%UMc%yxu z3=D4WW7r!hv{fS|2UgNT5}TVK%#9f@h7?(tHmag}QMH?WQtjA&>4U4fGPAEI+Mo^~ zeB>iU5k}<*jac3{LVnbsXe`!E2glp;RHm*W1jEUTd5U2v#xsJ*b0$~+xS#tl*5!tH zWamNQQ(v3(6YS*VKZL1|{k2vzf}u{TugxEwb+&4{pUiAO`mP{>jLI-ya-Dumh9Y|N zL5Y8IvYkW!16iEXSX#)HNNW8^Mtc}3t#cIE)-RQB*mJQ2GJ2kR3Ed~W;p@dt65qU= zqVoeMA25qghYiZa49cv&Vwze2!_1D-Xy~|9@L{wbHkwm0xNK_b|DDcI$?;jeLE>bd z??<3^0ZQv{0!Dh^xt2nj6x8<2QxpmXavIvBG!a?z<0lVHOm4L5-Z- z6LOP`ylJ`B^^z~~*^k%+lWKDOqHSZGwB#t@K&pJmR4d`pK6#tpJ6@Se6;E$%vHDNN zuJ3TaJHz+hCI=B%x)H-;*6Iys%&{=eTRQZC;EB2AStLCjmXHu*@9{&KdP~KsA;$?( zPv*5|s6Z1X*Exa3FPt;XXf%tXV|K@4E!VqD=mc(;o51$O=S~-$)nH)0ob1*_hwH(R zN2Wd=qcz3WRay)0Pj7$)p63Y!!T9h4e)|@6I$l1hH-u>w$&!{bvM@`18a)uF)`)d6+hR@%1u;nG^&PclY#X2RZS%OpXtfG-}tB8tpS zqDw^Zp2jiFpM9+6?&cC4DVlH%UuCg{(sbG~Z+3=B#4|{-W`)+x~gNpRYai`2Y0&tK1rXqOS&ssh=fX=A^Y~05f zUahLb52hQWx%!)tJb;)@AGlYK#ALCKs}FOifdU?!ZUT(h>@dan+$4)@4a1egdzxMFvq4? zrS0-Xq`Gfs)I}E84TuS3O+I6^e_-u%?lESb(#H7e$YAk6y|peR%h0k*4`rw zPYNKvaw;nPTWsp~oI}t#@+;WyFPT?8*erYRbWwoc?-*Y7tLrU7O->2;RNSYOjradH z-`DQfXb6lD>Y0^9*h6rdZ#RDpGyr~ z5V=@_?v?u7bLb==-N} zR&Xh{Bvbd}a5~I=+UhfZi-Uwq^;Onzl?D zjWfbFKOdrxD(lHG!km=T6x<;>RemfZLQLPe~kCqjreq2LlB2Ghccc+ zEc=+4xxjf<5WTZ;nYjL5wV5xjTLDV&o)tq@{cn|AeEh>UCOWTIc9l6a^{JI;{gi$> zeKWs*kmq|b*>OQuu%CHD`fUT;y`S*8J&4nnbUPFJIprE$Q8aZX6)q6v0caqbH@SpB?4<4Fi z{8G7&3#Y;+8w80C>X}hOI?^)-O>X-2-q(U2q~45 zvl}oy-g67|#-#)6yxuq#x^(Zn1=`xd**)Bp16 z@X4=3Uzj3LzsviMN3WFbW||8^ff7_u3TWmvErM(dJW=VTEf`jM_`Qmi9d6oodVr|- znOdXDwn$}+u8H02z)=6@=#NwhvEiutGbz??2X1-*<$kGIbig^Q^%qGs z?kn>IKewUK;#<{iR#wsfIPKP_qECfwm884_eq#8L6P2n+YhA?;2aMh}n&q4xJtp~5 z&-0BwHHisal7l@&Y4%^9XDy1A2kLj>-s9&!Yo@BeZ0#f;9Ft^$&FH^NQ6q0y?X%CjZ3rt~IKetx{KL2fwNlJ`V zd$`3DeD2Gyvre8LEz4V4POzn?iMti6ur%NBKRS?}jve@xdh=cE;DKG#kt7{eGuWkH z&IoSaACbB4<@44ipC8~tO=mMG1P_*^j@feUT`Oz1r8}88iAO}Tu~tk^NDHM; z=t>it5%X`>H25`d4i{9D?*bVRb-qkuF;kunJnnZ=XuF|zl#(0~v7`^G4pWxN0)3UG z<2-|3^4P@%T$iYg8ORti<}eVCSIO`MpIcOc&7sS;Uz$8&Jg_oh1@L{D-@Nbhun!?A z!7_)rF?O?T;ss6~*%i;D@)q_dfh(63{CW@C%ziq`1`HUPT(^d^SjDsc#V zi3h_&k}8M_fzRGsw>EqfS;w-@$q?n&{^}Riz+~`;yT6~L5)`i5r#x@6HzgU#`ifbA zoun2sk4i{1?2>1~t|b5XiB3SmxlE8)N*X8TJBtS%4>?oKkbY+lPZf$7&Z(G8>`hga z{k@q>9O#MHj{~WfY+^HTl&oTp@YUgLrjBhVIhVUG8;28=5-WaZ-Y+KS9qI(wHXln- zzr^MO$_|;Nnk)X!vG-=FobF8k$Y_sYn(d;?7Wb;HPimMu*dpKkMjs-kgS}Zb(sGVX z+Cc?kN7l4M=y&OXw>KQYVYi+{9wdXK^ye_QT^L_WYaU`+e7fj`7lW!&#)R+Ht&=92 z#V!WDXgc{I>aTcI@XLFFb0O#dUvAyr`FkWLbh$58^w?F2*zotyN{&VU^VmBqx7xmX zlhNVUpshE9$GI425hn(q{8PCND#7%@0+EPnGs|1b*%?gpzxS`yDmtLV{!|YlyFaI& zd%VBnn4mFm})K5cf6kD%`UW>t>S4ui>qjjM!0r949`axBJ{q*LTP zB9UoE*6IU7x-Fbu9uy7FN>*LnZAF~eDUKgj(RcWmEEQu(s49rbfu@L6<^k%kS6j9k z*x|*LN-0K8gGo7^bMV}x9AXKRuc7NKvr+8PWtnn^00OjHUXcRUzxA8cm=9tdYqwC%a5FYizBoq7Ur8^$ znql~qJ=zCvUT+`c{H|`km>k&L#QV6I8>UTKj5ijH-P}sarf&{=<84 z84Qh`SA%`B-@_KBhB7}&gyJ1#Z`0a$SBCZfWA{2 z2v#R3D}8zR0_Nhc<|ZDya=08VQ#RdIK;h0jcY^nP=-B6X)`vPw*!7}T%+q(@pGOs@ zKR*67^qG6Bk#S$xm81Wn<`>RCmHf4MMk(sS*((Q4wj|BV63WPB{o#SSwX4 zez%>6KN@?qO1#3%yanlMh9|AeJN&;+WC2bd8!Ej;*0FKYgLyxdkxGCn31i<5rE$L4VB({a33)Lx`& zbt+$5FKX+sg{eFUDFuuO{#1T07`JJHY9@m9(kMl;hlys03eOp#hN7jYjuZUjIA)tT zoCJ$kdHm5v`md1H>81Nsy15Ger`+K*j?e=elUjomijxx-$lgj#mgA7+VWOCcW)`>( zlN7^Q(VHp=DSKGWr!tHkdO*`E^6Lq5Eed!gL^jjRDEgwpD%qJv6n)(raA``Twl5k8KT<;)TO>a2gTm2tD(9%o*qFp zNrsrHO9S=ge-^;$$J?2Dh~DggSCcy3Asvn_G-LGa#gfhM3ih`@2BWbr%MCXb&`&qd zHKR3?TndbMPD0seHnG|ua@hD(j6-n@uFc5JNRW1@DDo=uSXr}BJg@s={%c8;^;kF8 zc@}@vdR`+z)xP+**8wW4ry8f3I&`-*4IRXJ8!Buv zgf?$e-~E_?a*H3)OA2zjZr?|+1oN4#q~(wAg2eF;t=!61hHeByq(x5oDV-@P==ylt zw`j8*5*;gWBe|?R_ zzMb^fI2EDucYmksYDH_QF85t!dZWlBc~GjIo%lU`Scu}?7a6+*%!Q5!mb>&KJy(V0 zR(t#;VRz+0Qwg%Wbcp3{u0&`@h4lBaRMSw3RTb$>H5qKhC8byx+S`tCYE9!2II;kI zWP-`K&0~05+KIOAAi1)Qm75Z>)@Q|w>aWgA9}Muq9cjyzU!&`tN+^y-TukM~boER# zZZYcqi@>~>p4rBHkII+yU+gM1SO0jW*vOS`)O2ygZ+X=-RM|h_Z3QffO*v-cqcfZ^ zArOj=@!HGq%f2SD%Jlkt-NG|G|Jd2KByKAW)n~WnR4-jkYhvlWo;EZEiE7hF`Z1Pa zyq_+D*CK7Ll#+-E%5gY*%3bA<-e?SumhSEOz1z}b3d2F4E8w)^z8J?m30G>Ax?}Jt)9J0v44Xo$T184WPSFLh@n)pGliTlMn z^~(Zxdsg=vb3_A*)lnTZ!73M1=&EI*!y|=$3`xYI{z4Kuq25U5BKYUAjtZoCl&?~~ zMEIvO2ct44_IA47{#~(Xy7SdrP{p>)_4L12rvq~B&=VHonxBeFGwXr;F;=2;Dc3yg zIO#HtWWIMtY|rEoiZN!$-<9wFr5O|e=;C#TP#NKc5qNuu5V2p#!(SkV3txZELNwk=KRd8v;PwPelPJN!aH)g!RM3=@U7zR6l0X^`20#<9wdb%d5`JcR4h zodC9Szr~p>!9U_t$W+s3)+2x9bA_ap-XmHJo)h^bC?Xj3*dlWn7lo&o@W8!_Tq-Sm z)e7kVcKv*JXa(lkXpUS@b1|%dNl4%K2FEpi5b)&l@Xaz@ByRMY^OKZR4+Xe8wgN>Q zIEG@(@}+L9T9!dsY%Y)t6KVE^;E;rRa!yb$ph5^}8N)^xt&1i53cMjFYkqr$@|KRo zZ|Vd+^-eqQ&j>U;uuh60f8$i!4x7k9E3G{kJk}sctxfHOe02d)&a%>yRxdf^3wwN? z)9D-H&5)-p;UCrGI(&h$J?MmVmxAP7E@q}@Am*PL4{!uIJ0Scj9_;Y`M5v$B22o|0 zfqsy>*Jw9B3FL=MQ_vrUf74HWr7A@8syGeZB?dY#EFnD;kw=k=RV1zUyFyLR6;l<) z61>LHG$eF_l8}3^o^VP$xhP{f&aLe~Ak8!UqgsarY}In)nd(FM=(7`qjaHBy779T;3ZBNW< z9`-Xk2o<=*^*N2}u~|yO8b@$`$#S&6r!o`fw~oCAlaguvQH{4^8_{-Ft5l7!vAtk# zhB+()+rAcHYnhB{lMbgQ*V7=OT=K<(uN*k?zkNgExDKnxGMVz`-gKZR;IeG;f#Guh zXFp_3vVjW|B9VZ$t+>5yEm)UluxqKWoUBYTC$|S0{-G)%ZCf^f>~H#rlrL$zE1VLV zy1~`wRKNs>3IIN>2>1pHDA_71%^1~@gzh>RADfAm=M&ib@BN}T#!y=AX$_s0OX}`Z zak9D`@QF(pgf2XL0^Y-)>2xQNiKDV z4qs;n+^;U1?`D5Kz7FupY7X=jb z1{d^0Q~cSLBp5hu?L3_UvL#!ZnCLYHaC=ik4bNul*TvZ~f6lkO`InZrruebF&Ayt= z@4sbe3%&+T_$5%quMU8RXGp0Vz_^F6TiLqX7@R>5K;Fsqo%CYKysb>lRql}N9yUHGh%e>_WwiGpPPn1{7 zYV)1m%HxmZ{yyRLytiS9>(hTLM;gZc_I%N>?|hoWL$78OJsA)mUKVSdfhnK=q*q;D z#33<5EpT}M0yF4}?D&{8oq7 zG-HEqrPVBbq?{?T&jo8CYdPOTc+bLoH@@yRc+W3=wj6v&tw3O;FaISY;>f(+Y{Uvf zBq(7PmqtwhIoc%H+>xiL=WXYO+6m!gcFzTxz>>5Ttr$g5JAJp~7U@w5 z%XSI$igY1G{sm8`6+v$W9Et^#1R-hA;QR>Q@TFdVGPs`XSV}QKnq0|q%FJ=ji?oIX zd{2zE%MZPOs&H8VHJ90Y&pwaO{X_oA(|tqkpLY(^4W~>u`+or)pBacYwwUHzW{e;r zBTJTlGe-A%`uU*#f=u_Q(x^HG0E*wl{n-Cs5@XaeOHoy?YlEu#8-L zKemSXH|Z^+Z^a|Ul*|4Wx|B$njc|ODXfR3D$ z9#_4JgDO}1R@%zkhvs2R#NU?$I^NwMvuaS z2zv)7mQTZuwb4Zcoc?X4I^8CB>zWGYsZK2C>v;;++G!+>kt<9;#3@!<&E|UX% z^xHW4DCr94jObs+hLdgXD~(s@|3mD@U*@`mxKSZ4zL$G@$tcO!IHVR{EgR%XE^k?~ z?EGY<{iA#MSJ!Mh@)8I3gimuiz3?r{k#D6Eg#$YbioavSyV-nfGS*VjrT`uCJmK~$ zJ-u&Mw|Rc1=qvK>Zku}cm#FW78I?h2Sb-~iP*kzr`^fq@PCTzQH+)JX!UR=tG>~>%8MFT2e?unW1ZFzJZCq|){ zl9gBh_R7C?VvcpXLg|Bxb(L!3olPXA|3dc{80LHNsJ$4iO~LFYGSBaC`%Yg^TYoD1 zS8V8i%Iy#C%+F%g&XM+yW8N$zDKHi#54h)3K$G%N_kXm3MsgVVxmJ> zCum0qVwiEp8iz==rg=SZIXYpDEZ`(87+DEz;b=ZS_Cs2eDBcj;Hf6YYsB!Dl?=!fDr|>Yg?jUD@juDIYT!Xii4e3tI`EZ~sZ`wMpAExhgDs&L0J(vwK1ZZwehMcUTCk0=4HZc11M#q0O zhSCM#?nO0$oa=+QA-MYTFr!7Y?!ntd*Q>`nKRo(Fa=)T%bz+9-P@Z@3bv)!Z78O8= zst^z`f0iibcP+2*X0Ez$@NZ4;IX<66>VNBzPc0{3kZXBOEN@XBzr4(+=r17qgR#a) z3B^f69B@XyyzQ;Mx5s^}mcQkv`O%#Dt)>9z9jVt^BV_3|4q+cKTE=5De86W1xK5OVW)jPIJ=v z7^uA;M<$OBh8|Ri)jJQs%j!_xg#~XWH02x!0)~}oEk-uyO z74S$_;+vS4kVFJuDAvKii1k`r-jl_GY&^>2`YwE?JPtQg9V3%>1N*76hTQG>yhS-1FSN>^*fc(_Ujt=n73V&IyV2 z{tJ|EX7|MR**1jvW?(2@oD9ObqJ}h-DUXH}2oikw1Jua?{s?@ln>_KkLz{PdGCxW? zVswn)OZczssBSorP-()8GRv4(PHpq$MaY?7Dk2or<=is5+_A|a4cSfWhZirjchy1B z2fF#aq|)}YpUVxdPW(Q3yza|kEi`L)li6pEl!*SeGJko_9MP>4^9W;IyqVggV4D*| z!L`2Yjdw&ON#SQ8DP7lr%il|WjY#tN_al|- z+Fileo9#e)f<)B%axyjvzmg(r7GSM`ux3*r${p(~>BK?&y9~|QfOnZXYxVCAvh;V> zeX@j=Co|&KEPON6>lS-h;%OL-F*UJR*#X7D99LTI^i(BO+zuZOyC@!8oq{rl1eBSy z;8#qpn;UgW<%vqh%9p0;_pIe3h5FtIw_^g~%9$;U!Rx=m>g&`qsmm#((Etl$`4`o) znevz0!KPxD=`d&M2(BEa!E{E)tLZ!LF9_|!c3 zR5}UOufFin9_5JnTLjC;3)bv0UOvEQK;q#i;y#@ZK2eV~7A&jbGCF`6(p!PjCD7j^ zxqbrC^`rpyA$!G{RKGM&+mMCWsaV# zvNMk@FJ4JIQG0u5A^5?UomUs^xR|8=b=_PGO^?-|W-U(ALa|ZD;vb-H1&c}(Tl8^> z)Qd;v;3_4PY$`q^3je;++)%1Zx`lXto%qHN*SS)5`Kz>gy9a4dE=*gvL9;pF`K%Pp zEjQ3nYaD5cpfF$w!6z7vVh&dIr6^QU=SGm#`z>~Ygp1z*>fr8Gr~}CU{GR;_ckTNF zW@7#YJ%hi3ht;2mm~YbD;hC`ok^Fc@EMmsMjdS>fK6YS>$pc8 zhN%t^5zcuivr2}%b+EBruenjiF*~KEV-36dD}Dl$bWH*Q5Xfs`DWR%#zXCvUs_2?` zIThi3B{_)ypSPEsfg)0sPH7*>>!PSkm!Vght9Q*R{4D-vaW zv3e(~c4QLG@!aCG^GTK%O0$7m59~s&u~hhjhi|}lq2v@MP^(H23%|fST$OrMx#v+h zf$7@zD9z@1UIHHP6-N}ib;_S-JSa;rZlbwJFr-TSXM^1}PL)ldVLWSk(x3Umah$X6 zEP81K3)$-hz~_GgrQ9G2l$1Ha9S7CRf8~x5Vz7czDct;(9LMcTO#P=|pujMe*CwDB zgRQMmz??s8n-3NL%IV#R?AM8nV@>3ksgojSg63j#gsJkm{yM$h740t-hBp(|BP;n= z0PjCen53JxGa;HW^O3j?$JEJ65lvd(f$&$NgThBmqpT``id4UPEo3Vyvjk!L21J~lN@ok?cywE9uYzBh+)!z|ebf%E4=Z5lpy`YA^N|Tx= zk?Z);oLE+g{3|TjxJ7|)7(b-ZrruCA<|XK^Q!C~hSa|psIP-}z5S}*4eWtYNdaa5P z(W?-x9rG#HEw}v67U%F{oy~u09(XV69K?Sa&1V4(5h`FLlIRpZE5w(B{fj^e-%WSL zoHOvaP#}WA0I3$c22!+cU>J%}h*N!p7aO>b^mkFCEdhU|=EtT*YnEG#ao;awv1*qz zbvG$q^riSnt;htodWzEEfpJcPzWF&@Jt36^Mjvg%9Oih=OoJ=83=vkHDmV(1wzLQL zUmcdYiA@lgVVLv;$@&P}_eqvd-&%^<%^8fzK{ic7%xND7yng4SX5yE%m4^q9tTg5% zTl=oW6gE?B+w!hk%XIlIBU_fLB6|bOYg51I#@2HL-S5p4-)c@ zg;^zo>vA&%sr1ta2sWFi;rr|0@KDejgJ+Kqri%otYZ6pVx}$Y1fVSIBlUVEPJOnHS zhNa&Ay&+%DA^EBZ9Zq5wcJEgxxmkSRX9%m8pcOj2(3?S95YSyUh9y`b@AY-^Crw^ARpad=87lh>vLrmqY$o% z<`N^u$Dfi+q@GJYWqSA$tEeL7h%}GTA@P?ngBn1aSJnit;%E0p&_Wo{^UbA)=J+&` z?n$r;;=q(i%X#BC0aUr%R)Gi~9(B}yoGkBqjxRX0{d|56*g*}TQ2!m)HcAI8n=r3@ zyYWHDkeefsBCoAmf9Imi!Nal3uFjp2A-?n1#pT=%qgp&HIwB{bOlJ<<frIz;|IeRU0&<)IQ zmWL%zE*(4Q(u*ztKr=jwb!~kSS&0<5Su2Mu)aDKQ>l2ocQnn{(fAway7P%loHJSm9 zK@iO&;PVWDP8kYGRx+FftCbIa?ik$?eg&)^Yoep?BT+}z5swM;$R{ZY`z7{DF-%Mk z&U&A92vu10g8Mv|b&w}ftK_VN{JdNwM(O<5cHpH5)VXDz;7w~Ubt`RY)MH@~iEd{A z0Mq8d<;27cgqk@Q*k&0O*vd0r1+oIf+-XBk%0O>IxKplkKM@A?`*{R+f&_g})T&*&snP1aHKy}HM}bakqF1zXDX2Uc?vlt~Md8BSB?;yV(iMbij9!2WRh`3qZ{ zpP?9`dA#bZd0v<&kES`0k0F$CD->q@-U(97_}b~rx69bl$=(i#VEG-BpMsnQ@+G}P z1}#Mfiy%u^p=c)3OXw`uOU(lpWaj;2DOEaGj3j`%I*IwlEt8O-Nd?XL?A&SSWk26Z z1figY_nq;ng$R%v5&hVk_q=`ZiA{nfM>UKFt>(a#0QM)?VzIwammlz4`H~3z~yfB7e6py8?F@|NuvO3i$jzU zkWt1pu)PrFg-OSe(>F>uiw`TpGX^cb<|Js_R~xEXV%#YAnBJR05<*4ULl&lwn@KAUz5uV}gC>D0YS`q5i3Pno`fih8yf|3rJGaIpcPOv5 zmzZeyNsvCxka^6|di0V$!fGHB6k!G*CBO!*OXXntyAJ z(cV6Od6{amxWk(UXc({AlD5-fjHN(tv$;q1yna_ef|lypr5zq}jWr7$A)mCvg(d!- zl?`l@*9>To{e=|#!KBKBAN<+Pkj0$U9L7Hwc8EDreuWJg=ioEx4^C?|<7F&d2XFF( z^RMRcPmDs&dhzCSp!OW@U_y+xeL?&8ybdr>l?(W0CBYa_l{|<}pm^9wTZvyfd5Y)} zyu_1_<+0@I_SC5iMu0=-h38~j2n)w0K-}Rp57EmYgPa1W6^c_($*ZYPBP!27gAlob zkAH6&CGpUx)z4pn?wem%rK{l?Z3>*r3ZdelK5}_3g>a5o8Ct!G8*n5CtaL2bsLpjSmO5`AmQdp& zyOLcw4L|lG=gd1~NsFFLEv$SrZD7+?&*MVj$gSr~x7^rW0rt>*8blSrGuzEmb;Ih7 z-1Q`TjGaz?GonC5{Gl81;hJ87N|+)hh<9Wf{CUd&_^cr8I_kfE$WHeu3&N4nhss7w zZg{)!DdJi8t2f?S54 zl|0kLeQ^BpSRW1UrDV2$>{>FYG@;KJPD&R&X3{0mw`#4e5!|<4HlgkfK+t)L^W~U% z>9$*a#15D<4Q}ugB#QLohg%%0hn$~`aC+CEGLL^l;bt&yKwQsC4`;NqA&i;-wt1oo z{9yS@JVU)oN+y+TDYkONSXlIm z^1wh+n7Tf5tYGNb=@Uzpqd3F-V$etVN)td8$It!5rvCgNbgDmU>7w#r&4?$(!^HB5 z4x*SyKVMa-`d*fMnkCL#NNH%s@DBj$p!RB3Pn1XwO`D*9f9j>mG%jkJ_)cd1g47*k zx4_0};3lpKsf&_z^sDIBEPH+R0gjskHUm^QCrsgX6Rrmx^Q#}R7fH!-O?3YGtM~o> zOYew@4gH0W5)Yy#Ve%E+mmG1xKvy3&H-mFyW(?0!1YeniEa=Z?7+twEeau#2N^Hsj zelquUm|K~_A9+#S(d|iLa+sVlGT^BNDiAf61?b;4lPF5goQ{@LI{n zx?KZ9VI(rHE4j2Ls=)4Qou6Kwj=_&wSpZ&GcY$B^pVn`Az z|EfMF?{Y1Z4()KKk9*CNYsYUIOt4?S$Ke*LCD$$-d64uMD&8;`tS#RmDa1OhLCu$s z*-=RC?d_jp1v*$tB8t1z}s`ZN`Pm{gBu@=tJJwT!8DrPnVW z2S$+9R5zpQw-UT0UdKqhsongj^f>X$it2`Bj9U*X@H@nc!|gu#F=h-E&IU&e733~X zR~H3DEOTe2C}%1d23RbeX3vDif^zDXhCwd|(2Dt@Ll{2rIOzJpBP57tKrKX4ZSpeC4@4$5$mfD7S{bIw$m_%lN;Mp-JMb*> zg>kRi+2U8w${SWPj?RhScpR=>AurCjZTb|I%U9hH`N+|Z2#2eEdoMlVS^oV@7Vf<4 zn$)d{&-=b#D&QvN7Y9Q9T66dY**XGeoJx(kYmCEFR}qr9oE+{SH)W(LM{;!w8Z|?C zbk)=Yf%6**$XP7xGMl%#Wiev{mX8n)rUl+J9jQzNPW;fPVcz63hE~38jKm*5%LK3A zX4`pfxW}L^5FmFN^wyi74AGWn-Xr?zhPtPNE;B`S{|A9Ue!t!8|7Cy}*7X7}s?y5#seV7}P@6ss|Z_d0lFqZsX(D}jez0IgcW@!zS41cy*$|N*NIo^weDE+M`_s6~34i+!->B=s`<<}3R|hjy zz~v{Ve`53rWOVVKt?|&$Az=RT)L)Mf&98C+jZjLmK`~BF6 zD1ap60)i$8tOzaNLNiGIbMl^*T1Mt^3TSY*4op%2(P#>oJ$@#cawbihGiQ?um64Oj zkEMxu^2{mXg2xL>P~@00MM|WpNtR5Wv{XoCK|fetzzCuw|Bod(HS-kmGiMK+Bt@_k zGGz&5P&rtzltH?O4HP9!*%U2f6iW&hFkHC6!X|1|HYZ-ZZ~;OI7ARV}81;c7M-LxL z=FGXc#|#!Ab$KX}gS5;XHdd5aNfKpAlO#Z5W6D;sI3*jFA~a4E$u>5u zwr=Lccq@ByY8Wu*#$bISWBimd*~6IUCe|B`BJZ}VTgU$7PH^PQnalokr#$ZS*Y7yF z6T5eE_q%(uFb0_K>ieV*7M@Uqz1fx%7GrMfO_@uoKw}zY1W{^_Nmy|P8*H2*YA=aQx(JFF z38g}AqNpVtaEM8wLTZx34_o)xu4A|b4>tbnQuq%3KKaD*9N`OA+5xLlNevgXNJbs>r0`5Q$Ny6(>T(^Am{yS%o``VQ$8WQA9+!z$)74 zL>XnKyDdCp;AG6|_w}89Jk@1w`4xJ~Y@ILbVHjy_)|D;&lXk}cJLb_?HiDZ(3YMq3kOF^17qB;D) zNm^1(8I=`QNI9OAlYm#rBAjx<0*4}EE!HMK;u2(fUPrQokx9%bLt4Gwki(%al0^y& zE24M|1|E3Gsthf-q6&tuls!v}qhR2lha&cZ%kRt(g&+iB2~c>7UiP2`!C)Z@MOeZX zd;o(SRPYBXI1K;1MHy;g1~VMszzIBqg(k3JG$}Ax!ZJVzG&BrzN*fM-6f~a!@rD+_ zq2a@La~(1u2o@S@8kibEh8!ksLZ`UH6VRZa+2jUru?tjlCN!MltOq%lds8RSKqBYZ z@DqVxffE`*3k@ZT43cPCbLvAJ|NO+pXtbyT)=oqq1Br1J9hzL)^teYp_VGO|a#7s` zIY>el(vXMDK#`7Q8)H0zOCpnyGK!IjDp095QT$GpvhavK-KI}sq5+jqM2t^VVHIAQ zP%$1sgDU+3lOuvynhe#OV)TJdX(Z7wXd#76K;sfwh|X=GVU5~N!d7L-!z4&isol|} z3~aCntAsL?;t?--sG>+AERhE}Xwz2ODxge&7ZHiTWe<8N0uQuM2;-4r5oUm&UY==% zB76jSd5Fqftbm0a)CCCWveq;E`A;P%>ss^MLJ?x%zk=c_4|~Xi34?Hi1F|7qa@d0v ztgr+JDj^9HOhLC2gP02D|KL>{=^$o6zyW{>Y&1zgVG3H%f)%zf7GYks^qAqOD2n5lgyUgWB+k69L1kzqn2xbdZHi zXN@twpjL_{Sg8Ol(QM?8_FYMU0Z6>)z6gqYMS znmLh!PWBK47+@g}|E$1-8KAHPB_Kt7Z0Ld#puk+>>Lm&U{6P?aa0D%+Ykq7fU=Yrw z6)QktpKN&7yQ07bo!E*mOE>~W3!0atXfz5~plB4DfCCE3prj>z6~Dfcf)ju+1tT;e z7GP?y8E9YymuLeKn^v_QCh-nfjjImDQ>V|Nr#OnhYL{yB94K;eir6s@j2m=ASm08M z!jYl!;9Ap*xT~?Sv{6Th=Kk#wF5QZ~E{Fp!(I!XGSw40ogXg zw%N^ZhO>%scDHlL?xcXbJ7Yd`4#)jfazQdGku=ws&a(&`{E3(ASp=e> zK4%e5u!KD*VF^HZ7Z2q5%q~CyC?UaT8T83df6^Bz^DDy^c;LQ`ut5u2@NZV4a0DfA zn+>l(^3A>GjEoksw6{Kzt?5E)qXodqQkUCS44(HlMPQQV_DeRpa{LDE@f57!X@mmxQ=HHVz7`? z794@qNC#DEeP~3~KxWjkg{MOwN^{P2zDK~aInF-^de8}p*!~!!6IE~>5~;-5B9`d2 zS?EM2|5%_1TIjfJq@zV2Xpn_jnoVg&gWb_1*Yq0qhHtRhp=%7K9Oo3H6kr&H_iV@8 zTA4y2*;q)avpW-%sCw1RZLafH#fBpE;GYtSCPdAUT}Jp|*K>%%eD&*sVS`F2tzK99 z_UX^M9A$pc=3oDca;<%qA;C>4s5viUhIciAycR7ky7$?xBQ#+PC{V#-Dkxub@hhhG zhQVjDV!{#20N|Zy!yQ`tGB0LF5u9}#8qh#?=2Iv>GE_#C(6Ib0Q%LE3pd=7mUPIXw zgUe$?&Y-~zrYx)?$qBmR`03M|{2;lCOiYgY|Mmz&?A-tVC!3xVx&b7>0t}Kl!;Rj^ z{{%v~1Rbb?I+4Fjf)Y6yf<9mq>L|IFp`}Nll2xbzPKrSAXpl*w0X2XHl;J=_@vKR! zq)^C(1au8OSq@_Og<{}?PD2%AA}%%%HE9S3XJCa%$P2j8CX_&~~Ef5R@qeD>J3uSq* zc8Q=r^p*tEm3^rUuc$YBlK~viw?sst8E63$D}^?wgq!lZ9kLm=LOR({|Fq{QhEVE* z;NT8)WWHuVJ}N?x?RYAxk_{<<1usgXC5pfCQ=0hjjy0+xFN?GWL8~YtkR)2my4*iv zJjTOBOaW}h#bnH%QzXD4!EM~7;HWvj>;ytF1m)-wML@c5e3MCPL0+6IHE0C0ln`T3 zB~}s!uhI?BaRfQ)DOys4ZRCZHi=`|moEcPxWVk_3vxI`!3sK94O9?_hAh047ieIq= zZYULya7ez(3GU(nkEjTXuq4c(#xCl9jLj*el9;m}I@PoMsN(kD5J~YZ8n65y~|BMqL0S+L6L)14B z8;yFCN=CE;JBW=v%Azq~t0nnHH_@s)h#0b3yQ{OBjS;Gq*{LrZ5%{=+KnWU;`9&2S zknAIaP^g7hszp;YGQVVjl7kqiLD8uRqG3eLB0WaMY|JE8Qo$;cW)PeUiJav41Sycw zGa(&VXasF!tr;{1*YL_~M2_K@x~gk9JW+%@XiEI)B8K#*HJO*|t5DlyIQ zpas%Oj;c|HX?QzEkULz-i-RCYymJQK+B+i*3Wjt}=lRV!_$Q<=2;i~Kyx0Rq2!eYt ziX(_mD^Rv)BCt42f|_J7`7w$gNU(QNAB{SSC>Yi5w6;~<|5TN%PjOL}QQc4ee2eUo ziY5@sEhr%UG|(WJprrgD1`U{}e5rbysSTKdQYb+xNk6Z{7>yB}*I**9NlA+GiTFf{ zCisE1{ed2s3t5dG!~g;wz)n!(i>b%~8Gr!<0yT^>3Y{dc0W+WkGf*HX*300q1!Yhb z5Ev3Vp%jqH4WNQjV1ZFEhEvd~qrt>Xf|;-!1+Rjbt)!SL{Su^-Sla;IrotJNE!|c~ zD=G5DoH0w7S%oLa#4OoLoJrI9iw~#s#aC>S@aSC=S*tMv#ycZegH_%%L)e9N-sk<1 zBFO~S?L{?^EGq?^;egW8I+G+pQ`o$X3E>XcAV=!Mjje&pxcWL}IJcRY@;c?Cci161%wMu;xnDg#0#|Hy?v)QDKfMGcBoVcJ4?1OKuJR4Ir( zumn)UPDa3iwq1fK*aJae1YG$@i<$!o@_}=~i|{cEb}N_nQKx+>JuIL$7bq_*AU&hF z3Lc=mx8Pwmh=Qxw;qdfZJmj_r8jYjWuZ`fa4_Z(XzyTk~iV_+z6=+r}c-T{TGAzXp z=rhgpr4WrVA|#WcX%&&@P=k%JSL<*MJ>6X|R)#ai-p9(0Mqta!5kX~W0~d@(9>S1# z)y*+0v$DGmc#T(Ocm$4{qaVAE!8962K;-3x)`S z1PIBcBmqG_p`}lzO%$Qn_+=2Ik&{%8|HV_-B;FV@kwu%&YJ*~!Bq{+0W%yG`S&2Nz zib=5);A#k^FazXVNC(~~$m@cekO+ssm4{%wZJQ_`Ac4ntA2O5!GvEu%01I#lpRr76oS1`jmQR;(0d3j?9_9Ssi-R))JwRiOE>f>QLP{*rlVC<2gZX!fIKL$&tw7~h=PbYU<45Zf(HU(jC$vz zATTz#iY~yF%$uLAXbN0eAoU?m1ZjqEtQ zi;qHLV(k|Y0D-XB?P`&h&>#)SO&H0YXf(FhLGGOVOC!KR14C#yPl85RaIqY-lPn?w zb*&C6GL9ee99lG*%9X$BsF3@}*ZdpTl~&Wox-qge8X7?F8q&(S{Dfv`zwTJ;FjM2Z z8fm2FZ#`0KrUvkZ#pD{g{{xRr8ax}5GO1UpB4x*^B|%&31XLMa{$w=B>071{Ldb$F zXoLvIk`BQS&To_aQlY%#UBh}HZ#H@-lhtw4&8R5ocj3V9mBWYLQ7R3G(u0bd){ z0y5lr+ie#pHi~2jg%AbOU|fJ3gNd$aE8WV_I>qM5zJYu1hq-8o>u&#`1&!HUj?t2j zDH^|d6F}JSu1ek9#j5N}ss%?8l;IkdX@vsG^D@4URvdy$CZP7E}&qDg7gHKl7Sy+Ry$|~DNqGS zKe8CQgIS6zGgdJ$n~>{6zXcHw>2R`l6(d8*zTdd?^j6D9D27h3va+^#`jrzJ0Ga*Z z^&^uc9WanC3)uU9oKPS2oj2=JKlPtq(gDxkU83+%QiKcq%9t4g9cTk9(W6iLWDdOE zv#AbM5~X37|I*it@K2hOjTQ#@mBC2-1zPx1QeYkeX7OUihT?n*zg9wsVuLsgCoG8C zdRCV`uyMSw+W_Kwa|cf^)Qcfp-SHD|pEDfgf0b39y4skb*cD6o}zK-Ib%>7^3H1eOg$htvVX5y2MZ< z2HM}cR+t7g(Br4y{V^GWL*S{jp^ogM0Y})nOeltrmNa~{jys|OmXTeYkB>m-`R)I2 zp!a?QOm$&Ql%cAE%@Xz%+z%|BM6T;|6u~-0AV&(3)|e0D$7<7uu?{Nn^!x>!Cj|&a z!-5Gb|0s-@F<5HQ&@x7h7%*eatnmTEXip(Oe)5!&?wN8_Y9WjgM`5=BW$KXZhpoWn-W&ZJn%U}@^qiqoZAu$W=PrmEGfTKBNw z`i3hUty#Zl#gf&iPb^DdD8X_h$jlcn^5oGer;sUU*rZ9*ltjdgA1zjF7}H70DT9g^ zGcHJMSi(SSf9{1dDLuG7Kff!GX`ypR;M;PXsojAkTdJt z!<04q)aK5UJC!YO&b^wLvQB*xuDV0R$#BcKjVp%y>CR@$uxKfI;zZFY+rx?*N4|;- z|1j$6*RyZ${yqG~5+O{`kl{Z5{QCFv@9+OVfB_0PAb|xMcp!oa5;y?_%1pP|W6Bhh zNflMJ(Fl3*MZ{YtSxBJ>LZ3)MONQ-jNDClR7=jyU3O%A4dyg4Y%p)H*HViC}WI+os z=}~uCGnufUh>wjC14|=WV8~gIM)*f51VJM>aDWyT=AVUl>&K(h*Bz%q7ZCS&N}h%zMt3z;%i08$~e<0*?=GiZd8i)h65 zu}ZYR#;8mmpZIv>Cw)|*MkmU^xSn-)OxGhYM>ayNBel)TntA9cJ21fo8?4@Z^(nY8 z!woz9FvJl{Ji!9ZJP6rkuPHKQL$o-tinQustT79e88gg5#wa4i$q(ixqr9|`@!@R- zJq8QSAscC#GTeQ4vXMA8GGfi0$#_{KEHnbkL&v@LGtduB#K$0vv`JS?a!isJUwmoO zW*I5Dv{4swgqcyBe!Lo|N|7#cD56^|ngpG6KAMCNdHaAv5qbyV!x26N|1o$Gga=Us z;(fmb#1TLQ0R#|*^DsFKl~2w?5vxYdDoRa7@zbeTpjk$jb08&$C3%G;jUXzB;KK|p zw6Fmogj8Wn!3fRRM;0`EA}{U)U#3hOeUPSzZU451kTQ+jVc98nIB`dK#Jy)83kP8g ziy~w=(MUtmxy;&bQov&Kc##1oT=L^DYuO#&F1x)Vq){)P&Ic)Tp1BA6|33iRlQ8>8 ztbhhQAOaJpKn6L;AR7u&6+Q$Je8Hj$v~XW;PLv567~*`4F@__gFdhufk3$|>k!Nru zg%_1)H^p!S4HVJBBrPe0muW>6p5Q^_^avIqYzUKnVT)pvA`xGc{}PpUvWH2qLL__P z5?8_&CYH3sC6@5ROV*~uEo4dsGx#E|e&B;mZEA3jgB%)zaD+9k@drWZ6dcjWxWo0W z2QlaY`HMQKAGyR3ZfGIP8-u&h_2dKbtlCzxV zJSWAPfw7ov%w#B2j4>L42B4LPXRnbS@|yNbBt0*G(i~oQ|4gROohbx)I@4XxHfGRh z+U#kKXk|k$BQwPKvoqFt!b5NK3uQp#NmaXA5@#NK?yaT39HZqg`DcNr#{{33w{cPpt``PYD!ZV;*?Z5Ftw>Dp;DOYf(0#T!3t>_ zN|&@Kro50u8jVVU7zeX~QrMvlYIs6)82U2E(1Hc0PzI8ufL7wD)o8m}g%dU-BksvH zI`32u^VFa&^l7IN(~C|qZ*&C>E*2 zR6pb;8zePxm&~#!mSDsssty|)M3qQZkb>8w_%*PDO$t*Cd)TIU@UbiGUBPCpq9 zr%>`^LSxwb(bZ|nkisbbtex)6)i#2@j1ypS=A%U#qp&czV;4J1z>ao$oE;CD&8*Aq zjYhJTISm<{8|RUe9AV9%4*~D2@|Ck(|3Maj03kjU3y~Yg7^~1>@G#r64Jtz6CaU0z zrXwR7#ZcjAHX4$u;GhUiD24@#rxY^LjAp>F5eIt+Eyh5IXElkI#h@A~CNYVZuy=_~ zbTvumdlr?hlrE<$!ye*L2wwZT*rs5`vGa~>Xe)cd&W3Qap}pWSQE??J!LQ-*bd~mU zbuXewLW%*GgcY>-#X)Y7yJ+lWV-gPy%BS>wRu`1Clhy2kC5GU z<&YugI!9kjzG$(*Hmtd!*O?ZQi1i46-PO$+O0zRN0gYljq2$hgerM*~^668*`uSl{ zCMRNmkC_&{|4m*(6d``{?=1Ai=vmSfL87|Wyk}W(mm20zu#wTC z4HfcNlPJS9l)|Z5%}XQ^8?YK*xSEM+0vjv^8>j?+F#?+y9<|ZkuMwNxJs2ri*o6%q z-#r`OWte@f#7!LFs|@h2(YQ@OE2sf>1Wmj_4L$kW9hjRj zB}5}kMp}8sW!zlO4Pm?m$6KwNL0Cpx?NAHp+Y>y2y0y&FAVz4#h<03u6K2e1q)QiW z+`y&VDl~&~JX#BV;T>2=^Ff~+LZ9?mpB>&|oiPwZ{G1v*!e(rUGW3d#C`%7j0lD-{ z9}Hr_Kt{8aLecd|!E8t||H#I2?4j`Vj3YdOAsm?+WZwk!2zl{=AW&ecQAq^87uxj& zS2TeXEzyUa;3Ndwvt<~W*cx4A#7kh21+EkxutW#;B1YiBht0to5XBqpi3@&7R+Pb2 z#KZ$m#Z=IZSu6#&VZ&Z{0_3S!5)8%yxR{ioULz3M_;H>ioE{G$pXPPaE3rVpu}3XA zLKS4e?~J1~H3J!VmwVKbyNrwWS;i-z(!em2m61y`Q~?zRWR7IP7>ofRXrIA=24qRW z98P4()gc~UBu3&{#n9g`(SjNr;-=lf!>t~@d{Py}1{VGxuppE&z>p4*OTGl8ZNS1E zdyrp}&*Aj`H*s)rP^+h&L z$_lIi6=XsifJk{D1ovR!!>Ob+?N5@e2WW(byxE39P>UMiBfCY$@f7CC?2i*{OKAM# zchCZF2o^^&VO&{@4#*2~Y33)j0S#c(ys@EfNJwTSdeSx#wXRtisZ{MgrgsZrp^_E8X(56JVuga zCoKWPFU$xZ|L8$oA|Tu`(NkuF+F6C6ScM}wBQqw2ecmU2CdFB@ zqE>CV^K@<^rSus z=J}cFGVzT13B>pygvY2GZfsOBAj4694Xh~TBxr(2pdBkrf+Fo_nYhG(wIzmO7)wOS z)@)7Q|FMFkmPCS9>Xt0%rG^B9E}%$oYM{0!sD^4bfC1#e&g5BWE6_kFtf8&p8m#(c5Z3 z25`|pn07{SRl$oaVFpRWD#TDU^-zt}Mv>ftGL*uej$K*8-IYA0H0YgyR%)e2QY1OU z#de!sND_qZMV7!9Utq&XfNVI7gvo+zr^Z*;yqbeb!!z)OD8Q`D#;hom#50J3U*wIW z|ICgJOv8`SoGW!`lSv2*sKSPBOSoh~CVBvw8aP3CoEc=C!aa&lum~V1cmX5uX;GlW zp9U&lNRl*o?CG8^t%PjIek=pNF2ueX%a#pd3Y3 z_<^7B$sRO;3jEipjzPfQn{ry=xD-Pctish{42sY|8_ZkY-bm>Mf?=7A^~jm9|2&WS zgyG3htz%@yH!@riVj=g&$S}|X%M?kzsgK8{uUcgs`?0P6Hip~6tpMXDxYjFX&_W`D z2qXrJh@7T7O4J5*kZvhLC9>PQM$jnGlD+~1E$}P7qK|}hXD|K8&{PI%3{S715QioS zm&ynMes0>_gi(wx1GcQD)^17ME-PFK59_WEf6aXTZl3sw@NR`zWX144<1{{?qBJqx z+zk{zN>*sVqqIN<_~wuO&yjS3vovJ)dPam~LLZ7=jqTr&Qz}bG3$-+hQ|FbA-hKa4=^HMq}(c2#tcnL|6UekM428x zrfqOXN>Z!#?3SfPE@n7#pjp%WK7pcb6VLdJoB~!tMCQqu3qq{|3p@`dSMADV6lXxj zG*E;WV8VR46!8A=*W`)f^@&x0CGi%sQba{lNaGVHGZZ*VGZ#UfL^BkKPMy%nG+%Qv zBXc%K#ZDmcpX|Y-XaHYk!Ar{VB{oCxph3Y+vUDP*6t2uVe=+l*LBP4M#Z6Xw?8azd zmUc+bvid9MnU7ta@3KBxy@=Kqk^%ba?=MZ=AQv)3|H#QHOd?k_lNPXINFus^!Y+75 zaUB=^ok)rp0vm!?xjKy+dWakIP;q5}c$Ux$Io*3CM6Wu8{kqUu|G}t+ba4J96ScI$ z5Nv`)d=27d6;oz~p)`RLKMFMK4Ta)O5;QfWECDnxK{F$Bom}%YH^o+OH8L|r7hpkH zGlhLdMKzB#GZL>HBw$y}R}xV12DAZcn3un_Z8N9=Dh-2g43jxu577o(lh{%^x>9ne z0i+FCwy>(swE>XntJfC8B>Px0=?0TIq|v~S{7{D<^J6jbZ$y8#bWU{2Su|-Y@9xR>r~MG|Di5-){WIHOr~b6Owq5i6tV|3si#D@B}$b)2Mkex|oJ zCk1`3^;)aV9+0XyJ8y1_$P>Jk17DhD^Z_cVtFRo8vF7uQ;p6?%qD_;APGNDzr4nh8S)z^Zij60G@BSrS$O8q8euh9ik!MykGBBt}FB zUjmKF5HRQhjwmb)iyaUvUQm$tS`#lbGSyMIAXtufQaBP)d?i}0cT(l&e(l#z%y~!D z=TUS-1PX;lFr@>E^BS}Q6Tm3Dh@Q51QuE}M9UIpz{{`-kKp8+HT{!Y1M{>&@eB)|> zUWLq~mm!BT#7~#CP-Sl(w`^Ic_n0bK$UHs>w>W_;g{{62%hzhxa6WX4-+HjTc#Q8l z^`%q#Xv`IEGQv2IO0r}?RYok&c5eG5&n#}CeeoL)4e-2%I#+J)*j%xAWNu&Ykkddb zC_^xC#$!xG7*vf98#P-Kvzfy;yN`EMB}JUqd6~=kQJAGyZp2NvogbJ@f5Ig&|2rJ) z!5QF*Aj~%yXu=d|03mz=6TkvN(2~AQPeV{Gwcr))F(%X`?p>krg%jZu*jv9HhpZmm z(L|Q~g?yHk+0o8z`eo^cr;IYNz{*n`WlA`4{|NHT%Wq*#MkBmcGeE-=ygIJm`XTeW z(W6s?Krju6WdA-U&LBI8Ua%CDxSS!&{M}FlWj4VS7d#e2F(jf2x2=Q>fexIsaNdv( zD1weC8kOn75D}p6?(h(6gbK1CQT%7!rvz7~L`v~FRRXVk%lE(MN#MVURr0yo2>!q8 z!5IjG7d*ZffB_in!4-tT6dXb(FhRJt#*x$rAY71kCSew5`W<_)YxAItU9^ z8Bzx@>41*Xo-zQ!>%B+p{V{oj$n67*AAc>+aP33R?*?T-DHMZ2zW&fhbkQHZ^Dhtt zKm#oRN6+atq>acr?OERfZG2dV1@#PR|9rx6TNIF7i|IqVkYC2)0z!>^sIpLtw%^;+ zgelPU$Ym^pgwh8Eo_ z?58pou;vC{I_zgqyo$7HRo3SdFTsy>Rt4JViIhgoTB$MC7V=}S#%P@aq=Q8)U7b;< zR=t{aYu7xDHG?ogLk8Qoap%^(|C@Jj-@kze7e1VLapT9454SKOOBF?&U+XmXNy^t^ zj%W}C7JVu(WtYa-sbWYjcb-j^Wzx|{3az8&2P-S4M#?E+#vZjd1|L}LPuaNw1{hfK zb7a4rbZM#-J~U}?j|U-qaE?7DoWnvkEUIB54K=)|BbC4au?Ceu5-|%Z#t5T^DcWce zkQV{D#1Tar`Q(#ME)k-QR#t%pmRDk#MVMKH6o#!}j0wgSWtv%oj9_vS3>abvl;V-S z0{e*;8thALN?07J!V&k%i_Z}t+l+)N|t1Y=vNiEgXQ&CMd zRSO{Kgil4QQszZRSZKtkK;bhBG&QoIL7B~9HA@*qq)R!V85m1T-) zWtw7&fu@;(nS`d5Fca zs)BOj4z)IG>#J3sP&PG`8&Ua`UyW+2k2~N)S&_r$Z03nkCVdU%yQCQHSHg;Rt*T-G zk>ZIvPDxB;?&MU)|A|;~@zm?D!R`!H+Egvu?6c8MTkQ-cfZ)|&Ed^u<&8p?^D_Yv< z_K`b)&DFXpo;XFo`>0#xz}Nb7stPow8ip1tH>WyG@3Tg zD_TZtL*l+Sm6I`88leU;8P0tt`wFJI7d8bh@KdrO+u9%)K?zPUZ4+2PGwO#L$tVLB zcX&c09@ja)|7nF5XlcYzhS9-3V5v2qu@o7k@QJH=C0d^_3Tv)~hQJ+eQ2=~G_%fK3 zzR*H|r}#w%y+W+qjRi_dnphK|G$$gGAxV%q5-qM$wb&I+SY%McF9x@i1V+YjS3%5L zc;YdzNKZ|LF=5Eq(ib$`A&6Ei%vGqCF=cG8e`Z+)3?0!7{qZnZpixf@Lv}U$#YPQ} zxQoqjR>#iBsR~iiO3FZ%NJ)0(D`c<}13?)|MU72V6g1^2QJG5KwC#HDo6{=t_8cR9 zq6)3N)7_$G2+j)pgX@yaUuz(zEe$tFgST2Z~tAYq2)1PMiN0uGK+cSCS zJ1Bjt|0$KzB{J`l39WSRZfXFO(Ew;YxlAcG(JLVJh*$+z@uewkK*JbWv!*t+q8Vp; zXLM3{i6Q79d|vy>DrnG&Hi!wDJ)08?1Vkk^W#JLO`ek4!nJ8g=sZoWJm?CG^N%M)4 zq$O1iDOH(Lm9A867R2DP5~GYpNFjzyla3l}_0KFNri38F-tR8u%hmM77>!`TwCDm9 zoZiriUol3s(7?i^e&T~IqstJpRTO+C#U}vl7PXXuq_52M6hEC=3Wc)7-@S|lp%@0{ zT6n)~*>E!?oTFJ0_mfBNsTqAhgHBJTC0h21Wfw)wSDKN9K0s2c(ea8h?m*X+<2FQCF*wT0@l!l&?08Sx4P4|722l z2hA{bt(Kw>ERw51wEi$>YJ7@V_=90-{pweX#WJS~Gt*2IqYckF@m1wR2paUEYE&lh z9zl4QC(!lD6sARK2=kW1BnGdlY0BPkC7BLBfzC@)EmP>E(M4U7vwSAxPXB~Nvv@U= zmCamgQygj(ulU8KHgzg#i<-n0W0{741$d`o3`b~YlZm5+Fo)YQ^HyOM#K5Pm^Jb^5 zHVzhQFi_DFw~EDKtxC?@i8QfOP5aUEO2&|8%>>t}6!HpSYCzN1m{JTv=)ewk?jvSs z@QFsCci3l5&po#@9bQ!wu%4+W_tGd)hQg_ZKaql@d-#avxT?^C(Gm@;{~Z_zS7FV4 zR*GKfs6kkClra`fsxnM0YK@na)Tj3N$6FfX$LI=+wSvVaw{5Eo_SlR-j^;3^gJhiu z%g2c6Z;t1vmBHLihgCDrPl$C!tp2dxhb?w{nt`pjyqPRo%0zRj-EIR~iUyC!R-Kt1 zrc_k*0u5!jedp}Wa#vQHT#5wPkOR9^R(EeW8kZT1}=GlBWf=zcja#S5iCID z-8pHDJA|TZlRO$;sD?8|eufNP+W6yJ>%dZiobr`NRjL)<6k6nmJci|ER1&yq&S!a& zw3M$>tkdeOW4H}{10Hub<=u*YWxKkR`f7~v^i9CtzH(~CdVG6n|NAwi7&K7DFJO*d zMNLUQuM5UmoaVnQdWC%qq zZlB}ywP{aHd+gu~k4ymaO2l^l4E`Z60K=x^EUy3!kT_V$eP|9XY_7J30cMbF#*WIS zUZbe0<0v-Bs2Xtie2C1H0je4cYa9m<+F(8qh4cU_V*p{!EGp|J?Xv1)I)nXTA>Qa0N{FN7&ZrBrpxg>#XE{23x)s?b}%~1=?>EAP1tbe zz9MR30gN<wPG0#AdF+Zcj?6?*1PMRsUmYSaQ3amWU{;(p*!2y=0dzRd_d$O|Ye1t72;mT<1#A-M5CM!9V9jsRgPF{$4Nj;N`(r--4Oa$4 zn4Aq0EyXz`r?~P%oNlh0s*kt`2YmW*F50OUoon7=ai{1c+pHy>#)Ksq3}%cbg#=EX zu7@+SW@nx;a}F%RLWsLcm*XT2huu04eTeK)bIKH1TfnxqKYy4_VZ6R6dGY+ z{xV^jA`Wa)=;^{wQbJTK6hYb^v`qs;|1~ExPGPHUpn(Kwpb@l+KrO|n9zhN4Qri^6 zsMH`?j0ve0=_{a0If2Rvu7pJ`lZ40s4T_?1jNvM5Ncz?aG|)g&HO+^r#!=M>Em%}` zJheKP;<2bo_@tyT)L@66tS?ppQx@zqs3UOrOS+WpDB})L(kLDZ75#Iv_$oZ@ ziwp_nx&V(in*k7Z#%2huf7Fys-LzWYFhb=tTV0G*N}*R2)l+UOJ6;VIvY^*E(-3nD z6?^NqL{L81!#;b0m(H@gz9M+uv+0WM*l^D&vSVgWp^?^4O48EXFjYFJ!$43F(xPTp zjU@T{;4NW;U*R>MqLKdiO&I0`{|$sSN*{AiKCuYB=1a_!1XXqU#)k%~pb9QEC?i7| zDoNjt3r%aVQmNHiZ5B?oHD^z$Z8G7qR%jg+L#9|@P^qOqQnh4LgXGk6@sw=H==CdT z%;tjZ2^!U~$S_h}t}I{yD`fUDoC@0%bML&WArnY;ECnn2a;JPutzPgB{z?RMQ0TbH z7|6$D&L_=OhGpi&oQ{?5XsQz`rw{S*C;CMPx`iSgsuNb|Pdis% z>!K1TKk!ZBHfP5?L%ggM|M%1^a)9X+%j>)zmXP`a5XcKwz9;GqZes5Q{nl)nhS$De zp%d&t2LK^5!N&Lg;uoEh!Wct99A}yIhff$bjhX`CdT9Otjy9LWV+AOV(`#IWc@=L!op?BL`PjWXL3a zby*#&DgG_9zVtBk0)$WZaTHV0t^y7CtYE8RP45?fK}mo4cZ*epw!A`$9k_AmadCL@ zJfae5v#VZt&ujA||0L6REL~C61_Y-r5qP8^j`Im`=Jny~wMGF7fU;nZ`Qj6$pnZvr zSKLD}?8%VHBHm~T5ZDZ4!{)z^%W~V5OB^S{EE$=;0^znJ#~zd5R&P4s_u;-r{g`;I z{-l5wuKx_Hifa~&A5@FExRy)BrEu^95qMZ=%4q|bI^4JkHA@O4^>Kmj0+C2D5;c|4 zif^*)YNIM`&9ApC*b_DNuUt?eJMAFp_c>>(5%$)FzsBiM*3rO?k@{dfqxDl3!@y96 z0g1Q*1yAoD*e>!jXKv0<=$Tgs&76}q?k?CRonVS33F59;mKBJWZF!-O1M`dl5Zw70 z(c|fi^{|{(|C&8fyeb;^9H9>qmiXTFPGBK;y0$02f_E9YCt}n++=5>vc~gqZEv0Cf zxRMxX;pyz44^ldSWyRRUB$%sL8Cs!`zl2bVbRC771-PnusupVw$TYYLO9@3wx33w> zZ|^$FO@KP^tkK@SbQ%dL7eis65&A)!VgY7j0@Qk~*}ARW`mNzQuH|~J>AJ4%`mXUh zuj|?ZmP4=oTCMxqt|4FnT<>uv^*N!om&2GZjLC*Dil^Xt!BQyaK&r_O_>X6*DCSmE zGZ@V(mCG_lC?q%%e?s6gp>pgN+=x#NsxF@ItP!G0sa#baNk~^87#4IWchH!__NYOT zI0#d@|7E$<2m#dXWcRU@+KwipGWe{H?k^Oy(2nkC&|KRSGp($v^(Pi!yScl&z5Bbt zJG{kvyve(~&HKF3JH5Xf0@!=7)qA@KJFVUOyyH8*)4RRr+q}W?zEs!X&~>A$i(F3+ zn66_h&j%KINjmSQc54$8-4ccRcw;w39K&=z>MLyIW1wv4ptZ!D2!s^7dGC}VNPj0N zj7=?eT27ilW3A7o1!$hQqe>leslUe&H2XdaGn%L*OwLsLkdbG+XZ}buI8}UWqI;-{ z5tX?p?hYEeYdC0SILf7b%Bj4{t^CTdJj=Cw%elPEryLq+pcuS-U1u^mOt7pG)wS{*A{!D; zYfId$KgRY}#PZLw(|u*zI5ANdskfdh;hW-JbV7^)zGu;{5f-)@7MFb zW)d$1^@;_K{ejOy3MdO4odPrqDT$}%SFcl?Uw-l_A0LU~6l#f;twWe%$UHzp3P7qV zn9?cp@4#zGe5`{$KA~d3HH7XaZ=gGD!fgx)0l*EaUXM!(I^p3}EjCX0|C3K4kb@h} zkoOIX*VjB>ViTxGD>-aWsu;S@O9LnqfcKy4Q;tDwdE2eTG`_la+!&EaR(f{~zo!kD zaVg&7!mGF9d;F6D+MvLsIo9U`)u8Yz|NikmGGM`1phGeM!Wb<@EEK^qMogH(g$x@y zWH`(ino|gc5sRoyStBU`UO=J0Pd*v@^)RGJhsOH!F@{nZEiz6NRU8QurZHuXve0Vu z#AU*mJVQoA>4*l6VlR6dUHFrh6ErAkNpU&sXis7@X`y)nE2=_)P8t~-wo|IZi!&cd zITaSEF<5G(&;pxQD#lebPHBBej4CXg6pI>7iRKe8p1>l)Qq&UVU6@prssACfm?zo8 zIS=}6NOlz&TVfYZZnU)TWsEFfbslT@6Pma@tos#_k+=tvPT*^DF7`gF(1 zokwUQ^FEF|x$@=An>&AgdYGD3X~`-p*5_$lFOf%r%jeXs|}C;wh9SK*D1s8L*g zZoUa;oN~@7r!kK-l8|*8J@M36FUqFilQZqbLL*v2XI&?DycZ>+KWRjRBT_*5CvVmb zN7rKkB(rDB_O?#pk#{{HKxifVu*UM4z75el>Um6S;_kI-OHg>F7r zOdC1?GV6ddwNeEcS)Bslw;Rqx-h`eFQzWvoVT9o*uI~DX%Kt~r$0kq1d?E#dvdssv zjTTBu%dImjv*Ib$`UngyRkU%aOv>B=nS&uda->McGy~hGQ&;WTbu7f9%X7wfm&GSX zQU%EX0PoFr-+uG0o)pTgMUbJ5qWkD7RTyh8;z{%KNVoaGvEhbM=xGHgLxszrOqwicuqED9pKGchKINW4a-F`c;i& z)CP(Zr)F`?+D<%^4ma^RuFRGWvx?q--;aO(`tuf%8vmUDq8*9dt15t~LKP?iuVJVp zJMf`OVB~iivS8;a4FM4vVzwNLN$PFMVoS`N7m~(E%6uaMks3~Nn*B5bG)6lLi2Be5 z9{r^mk8nZ@H-sabgzh0zlES%UQy~-D1b8G-hNz0y6Cti*QwuTC6Obquwq${7r+Z?Y zK-31hWx*J7B1v2Yn_CX=Jo%Ho2&XTbf@YEehf6xDbDivj z7cou&NH?);aqtm_h3I8Y)CdGair^t2`anePTrDVg8i|Tx#YG@ig-x-*o=8rGL9xt) zCQon~D)*8FWeBi05Rwou?U;o|q|=_)nGqQYlQa>bq)J!2gB6)mAy}BjBRersUGj4y zNjYM0%4oy))FzCv*%wz<)gd;JY^r%>i4Y3|pH*30ZY~E@lh}6g+sgC3#Z_H;q zzY5l{dIlDUbk3tD3BSV`!x4QjY6!!Lt^acVN+}5BpCpF|t%N>Qmuk@JIje#gO*wQn zYhhhC4f?wKAd)Jo9O))m70}M;sw=c?3@tqB)xwCAB4gajOrSQ>6q@l4+*C>K+*Fvg z6e$y#=;#!VYTD%2e{s5G>a`D}7UvbHLit+SGiZgqbQ z-L(-Du zDJp4B#y)|KzskrbSP+U~uvfHuL1OTNJ~rP2#-|3Jxrn%qZ|eHfrFT-@*;@|Nn&K=39qOYsDRTIZiX2mO5?JSUkz(I z3T(nJE+%;t5ewx$51!zGu6}O~!h^25iPtg9gosgJ&-`bU8l<44an`f|JEEe}CB`R) zm=+bbCBx0JlN2z>Av7c#y8n;JLMCJsH93i=J`DP^)s%q-LxAXxTzd{#FsvU1nI%hE zcF?FT`YV}=iBjBAU=>h|V+A>4;D=2jmy!)4M}X06{Vt(0bl~b(YkcE=6UgL%Y2-zI z#8-iu^01st5U7AKA`i6IL@9ZnVUwg0q{HQ-VBT=CLTmLvK~> zI0rXj-m!qi`b=Y5#eUmnbm=I{>>Y3Mj+AE5Ambb_yy5Ajz=gQtx7-T~qK^Zy{S&f5klG_>1h*&J2&yCj^#BBYOMS)D3RhzK=e+(1-e8`^?j z4J!~3;*K%ZsBTcAy%Z@@B>Jbg1n`EaDQAGUR!=`+Gl55Su`}sbve72v-`7{vnxQ>{ z6wdIwDG=j_FTeS(C=s1hy()b~NE-vkY?N1W@eCe?PEDPS(`r?N{}E+ul_7d(p4 zSDPY9K<8IFM+<6TVG9^5T*pHy0SGkE3E%;NwI&cvw-z}uI2YI$I3YBt#4Gd{OvZ#3 z%Oy;k*IP}7TkjG~XD3OJgc7(DJG8+O?2>aKG!y2cb5%x2s#YmzcgEJ&%5i>DgCZl?6 zg%K6wLl^jBNizn7u!Z|_HD&<_WkZ5KqhDlT2p~ZuI>dDk(h5@GT~g2oE|NhC#5xHF z3p&+&w4x$35Ia{=1v|BPje%UX0C8y)Ml>}n57&7`GJTAp5o*|9r;sD1*k7#3G{7hpKN2AeW;{s~MnMylqE?7Yl^_c!DBh=b;1DUo;iiX6E_y(ka_0cp}j zRV30m8u5z)IFX_vN!3>~%b_0u_d-7MDdrKJqHb14+|jjw6v;pKxhXl@dNAT4S>s^^!685-X}{Dw#<; zZK*(SsYgDT6F^9p2WM~L1RBnj63&U2)hUt2&|1c!Ot%)2^6^~{f{{949>SSS5@9w| z*dL=8C#{qTbCY~$3h4C-75611^M*YsQ#JRT3Kk#U<`Ef0l{E04%6B~929z^X z3}g@r`It;ZazK@NHSxAsTcbOo)(m$rmSuEpS&3Kx$t0GDM{&VB4=Ix17gcxWkalS$ z3Zh0-(+tRIoim!3P7#6zxLcd~94u!xtHJ_#MV^v~lkRaA3A%`YB?WD85_|X;iT{NV zrvfEGnk-GhCZY2xlf$Gas0?Otf>X*Csp%l)XrCt|PH#bffboZXhc;-yOT&T^%rj@n zWEh|^Jz02}79mi-aho3b8ctboYe7iG^?^=@E>(sTxcGCEBc;IvsEA0NGzzKbHxnne z8)3*mG-(ka(+n6{9^DBi+EpJ7)J13rF=G~>@NymLWj=Xv3jejJ(nuFBX*`dZA>K3- z9YRK9_F#s&B~9r(b~Iz15hF8_Li$FTOLaPD)P==ohWgY7Hx{Dvc0xfTBwP8aFJ`Qd z;361WQJ?CfGG<}G0epN1BILn&k&3Py*FUSkQ&u*D8io?hU!h>d{1a0;zjg$0+XR>n$1x@&36@)roWeOKVBBpAZndUK$6=Zb-wwq)H zY3XDgV+dZuqk;`0JY|=hlwlCs@*rw}md}}^u#gdYcdhuBb^Xx?a5pE7@u=zQv$1AJ zj?fGoV}%KHHJ4By=TWmE0b3=rDZ&_yr`M8FA~^;dV4=5OfYt~$aeVH9vQ}djZ*d$p z^|IDdB+)h%RH>Vt5mS&jL!h;+ceGM(fSX2&wBjxD~*EfiwC# zGc;r%yjpqcLq-oGIRzR)7=^amvLfedB}0awaY2<|Be?eDm7%vp%5-9L;l6o3Myorpl3`^v7f4RlNeMVRmirg3LCwz{IpqYFoBiqZp0s#nM6oW22HUI)E>jHQA`*5J*u8P2%%^_+*Jj9v& zRl`7J@Uk)V>vPY9IK@`9%2#;-qA|+Q2@vy1#GnY4H@2zTz)7?qex*WOT1GGfOFOxt z$>D8MNw)x0vsW2B8VAX$(_cr>cq;w>&(1zBJ>6C;ZG z_J~!GqUf@|nrzPOlrKgcNk}}9ChHxen-nRRvGy0od;ff4`Vq3g}Dm`Kycfb@&dzz>c9s+S%o~%tv=Ll#prlVX8hn%zNJCVvD zj8=iZ`MZOokRYki&OaQA-PdWVb$3>K$?SX1H+?@IC(`z0B2@^jhnN)_(+mV9GG16$ zM2LE_>OxY+qRW-4Sdq(4KxpIDQ9sp%PBGO^oxw{RI5D$P;ifhR`a!O$QV-uOW>lPiY7PjQi(Er62oOQ$+F_X4sNC%B)52$B2!A1t? z7!j>|l)ieQY5sS=@APlPdx=2cAc8Au~pk`mS3v)mbLRbD(XAEBq7S3N1X z6rXIjqqUqCfo9(m!@-ZzA^S49ZIB6zBFzfa27pk^Mp`*_n^Tk-wYXKb%a@3@%Q@s* zwgH!YeQhb^`_msHaATszRM7_wirpm+Fq7NfuG19D{li7vgFe_NGKiQpxJOrvH%h0J zo%0Bl^r~~*!N3x9&&d{~b1M$pbm|;JjQ{m*8DT5dZB^G%1vC&eNbWR^AWDm5jc<~y zS}_^hGcH`05-gyd*V1%T?o~?SsShDd(aqe{{kY>L(-UEj`8DDWYT|cJCl*pxqLtp? zEfvPl2?Ntc^I>e9-DOkEY#YPMT2nqqLNVzD!UQ%pWTqcwp^@^m7ctZrbOC*No;2oW z2iCi@3gifC;I?!EAto$3<+j3F4sQi|5sHI#3Qn;ZT2(%xZ#kogcr)q6^Fm^@;cqUd zamkjER}v(S=gIzBqD*B15gho7NP**ja_XZx(Xgk2%6r9h`1~b|h7zR9EuYO`x`d_4 z%XFs{+Z)jgBu!gRjuZ++g)}hT*Z+(&RYp5Bi4lGLSHp9JHH*RfO-jW$=a%wY@!g9s z=+d2r&A)mrtl?J=LWw=5oJUAwB983Jj`8y3+)z{)3#1*$bP=eV=&D==(9&&=;7K|- z)Xw&t3G5f|?J-VnCvdzeRqgI4lL=!0K#>k7WbFuH``g(ABo+msIJ_{ljoc_KaG5~s zJ!oP)KUQI4&Bo;}R+;O?&Q#rsLsI`15SM>c*WiF)^n_LC8E^K`krG8TFJM9ybl(Sn}+IFZCSs>;0Ol3|H3Mhe^0c|Dah^NVW z3T(Q9i%8PFXFRiWlL;SuZ2$V3zHvEvd`-rn@AHT)iOhEy0bIUTjEW|S;wn&X=g4Ab z@pgXpw=Zem^}oe*sesAs`b4Ci{+yP5%;bGVPQh6=3H3Nd3wA&Vx92ZAsR-pp3jpTo zm-PwE5;!`8T2M!z#&fsEe4i)c;d0yb$s~L>5>z6#>+3x>U)vLwi1luIxJ~xqY!*Dg zVOvcSMpF+E!UPT^X6%unfe95ZWZ2N*Lx>S2PNZ1T;zf)ZHE!hCQP?nJYEBJv2-27_ zSc;w~GB%8u$ArdKp>dgz7)WKbRI+>tlOZu!YE}&+YD}53oyL0lbXf3Hm7|YXG^)uo zBF;=SvM8%+wW-lnEdM@%{3L~z%cWig;-p1mB*9^@q})-aG_6mNZBI1>22zm}md2PC zREFm5!<)uvp^*ZsB}behErLwxB(PwMgwce`l`%0aG*23x?21@fpHI9xes1LC&Z)X2 zf1bR&eKTiJN6@bXT}c zDJ_k*qH)K&abuSbwNV2L81jL@j5X^cI(N=@LhwDwwTv(Q)M_#;Zb#QG{`}IAVyQWsFMz({dPPictfNRjODeR*!JHga%mM z?KX>l0sqD*uQtf=4j5o?q)Oq55Zvn_h$Su;qxsZ0(L;HwV6@bY@_m)!WQRFLWUey9 z7myBD8|JA#&XR~f8i2g*K7UD;)hILH)i5recU%hJW>^qft(#!^B*#yQTqR1{@dqKc#mFT2XXdoP;g2D`J zpi96K^uqnv1$%)EGgVn^|mNgD8HTPMSbMwD?x5#q6S{(0!H4(VT` zivP*v>%`%cuN6C>Q$%u&jKa}A!!Scm{Dx(_Ns&Ix9}X;gf4Ywrh}E(e3p=Ed*F*d16Iy@`>xfE7tk||EA70+LRkfrLW~RIM5qqfXr6hW{G* z%uXDG7G=0@l7T}>Xd2OsPV}LQ7b%Eh`Vcc9rc#xw43061QH890&q`RKK_l4LK;jUl z6;dEo;b75*PmB^V_|li<7E&ED3ezU}@|YS^)(EIDMLzVwqldbshKWHalZ{DEP#DFr z{+(izC0S4wvUwH7BuJX_Y6BUYf-hqU=R-8Bpce5ZnKyOt5nPE8YR0K6dG#R+V>oA( zoPtVLCRCvd&6F}~iA3ZihID*%jJI%^w?@`UAToKv2M5C&x@B=TWw|INAN92-O6hJM z5g!Bvxt5fi>7@g?Vj$Jlw9u7QR`?1_7%3^c-RKl|$`FY&QRf#jj0TrRx&OoKh=Z!2 zDur}`j3`u-*9>l2$vMTyLQZG88ek!mp<^ZMSe2vEs=q#0Dgs?|Qfl+{^WLV4kTi~*C zeSJ?JC%1B();387uYp^g8qB|YfO#c#N73SQSNw{d>!m6P`(=plZTnLl} zN;Q)awA0LpWCyX@R(ST2@@{R5FB%ADwJdUkANSKX8+usIbJiA6&;?h8;6zPFBpeLS zq)dtKnK=-NOME$rl*YZZFC?{bL!ziElgeeh6fsnI6!(`)8qg?w#WPUHdzW|_1r1K! zkEcRclg@Q{f@V1iyYM^_*=1#95vHW8^cEW6(VEi62r*_#S^t?ft?Jb)tRa-?d~9Ts zsHkL`PbPHGp5}GyTOXAXFZ&c;r5 z#VsBYgLKDHyjg`5o?s+Gg=8#MG|6Jps4$W9R-)L2^nv9Paafz=6DX}BPF3a1k`GQT zWT_S2(#s`hsCVb2CNs`&^?$`aqO zHP^R4OS)@RC0$)j{Nih8J4;ug2DmzBe731r$90W6x&P8tY~TsI%Mu&(@L9((nKB9> zT+Lz&wH(H6Q)hE6#9f8RM_-ae&M-Ru&3Fm+30XJbQ!-JE#$TypeK2=kC7#Io8Kep| zb2`&Nl2wANX!UOPFKy`F9C;0?Y#xoB+S~qn;AhG@cgLMkRA-C;5x#tGG|F?M%Uh5% z_1eEW3EfugMnzB&ojIYM>4RJr+SBxla4fZ?dlN2Ns6mpPpDtjI(!YgUB`YaJ`21+hB&Lc ztDdZo4vK*x?E|M`aIqwkwhXBV_%V+X`X!Nai2rcu1h?Qk5DC9&qLuqAHxVfuW-NAj>eOqCCF9GLfmL!4MuN7$J#R zt*6nEJ&7&f!$32%z~S<~Lt>jX;R&(1H{N?EHawzHx~@Nqh*FxPM8mVV;FnM-C6gPx z;qZ&QSqky_t|Lqt^E-;RD6mBAKU&CyEYN|3!4mk%iJ*E!VK9nDKp@P)Fa6pNrV6G4 zG`X|uv=Fi~7=fzQsW}#Ez+oZ_TqBKd!^AVZ#oz-mH5fzGQ5Q7O83^eEjoYhbiT~`#7rmP$>v)7_0KHIvMb!d^e9-|T#F8po zt=t+4J24qAES!({B?@aj4Pl|?0g6WWF`Mx(dz=V$)U65hjD8HVQ^*lBTNqo!MTKNL zJL5%4D>*VaIk)R5Oer}!NkF(DDFZQy>tZYRyGAcb6ELF3or@{)kcmjqL}kPgXIlkv ztUSdK3R*y(fGm#4$Q5b?iBlkh$RRPJVxFBMq@H9NWq1TDTtx#cq?!~+O?pTJjH;U| z!^y~t<7q`RO2~!G%8Cn#`WhxvnnvoltLyujyc@<=dMiikpJuelpcsvTK%daks$XIh z!8$xFiIGyE0YFGb^mrg1>=r=i68|SGjsp@FESoa+(@80Sop=$Tt+_!wd_7>i3Rn=R zsY5J(N+6)s!W2r%9+$k(?qt6W0jIi3dnq?7%C~}f-XUHJSRZAJhVQH z9HgS+IGPhZmQ;ff6g|fKghq(2!88s{i5J7EluRQrnZP4Z0}1RJjoefSQ4_)fG!d&L zG6IabRTD7DNetL?nNCv5nJS3osm9MhuFD`4d@0S-j86}f3Ano%qu`FLGeHBXp8CMf z3>$_!XrJs@Mh~o#F)|9}xejX?k0Hnck}NJ6p#fFE$E~Oz_;5F20g)WENz8J=kZGUR z?2-OZ1AjbB;tHI?P{k4zlK&9V!XE2R(5w!qQA2__jc}w6eL9Q(c~2*hPah4g32HLl zK%-xzQH~KtNeQ$zG}73Ki+Nm4W2w%|dIUfy1~kA%EMbfK<02;Y3HUjMc!4h+eUp=@ zoaxx3z^KNrC=9T99Gz&KI1C@7aEnQrFV_$-#7d+Cd&<=zr79ejDU!fOi;*AkFJiHb z3)7=~>Cqo;RI@6Kv2+*ou}k6zQhREfZkx>W`25g2N}z5T5)m;r6`{9J;D{UH z%pLis7-w~o6 z#;qv^>%&#CGm0VUnJfhwIPHt&BA|$Bop`bOv=bSX=f1ffnCgHi3-n8*px8jvdJQv1SCo0y+eEw%oT0>qe~2h}D>$*gx` zkb;7VDpQ!7cm#8bQ}4v5Zh|K2^iyHwLA+QHmKoH~l%{wblA0L?z){Q)jX7=wIq_q# znBChRYRGuev;Q_k3xjHlR!|1#o6RaIIcLj+zDwN2p+h@dN-s*k*SU+1bPQmH5vE#9 z!~m9$6WrTq8y4tFS&^MWBEFkED#egZur;79t6SFSxmY0#7Knx91Jnhf$u`ou)cDV` zQ-n*p3$h@!Tq2ey=!3HZ375@WzHQ!CdQzhpnA*t_`N#x7Fg*W6I>u|W@DSQ?aaYgr zv2#nS2(2s6f+nPWNIZ#4{DFmY3`@PZocsaNZBvAOTT$pZR&h(3?9GTV+AUToh)7~y znv%x?k;C!)Pkq`PnhGnNC7LYgnQtXv=dEBO6NX*Z=-ooRrkuMvy7jW2&S3!s@`QsrAmq7>fj|4opkmlzC2ClOyvpQvQG$WkMCD zm1ZYSa3;trN5uz$>rzO105~~8>R6K(k zk8N}p>Y@^yfWg~~4`c8T6>ebVq10LpP=cKdqbS-q%AfooxjzQVv5}A5f;>CY3k?}9 zh5Z#s;nRq}W~w)sKUTf-7H&O!HFxCWWGSAOZh2LyI;Z! zivRI~)=eW-K%GvLT|6`(MYZ_EBu+~*=wB!b69_ZcWl_=MqKreyuLW}gSWsoE>yI|5 z-6dgVd=5B=ie>znkGaw~Y5Nx{2^UED)U`lH^pHj#!x&c%CJII$fO`mJ3b*c}H})k~ z_sv?rt2ZLEkY80IA-iawxDhqL5F6`{T^)|l%n=s_q2(HAcG?<}iPo1L!t~36OMnI% zkmoEtiYJKYd=6@uT(&hn3ArfJw{(OPcFs95w4Kt(_W>I6bJK^-O`He|Y_{7|t7RfKhdM`nn})mF_iwMkP~Wnkjsy)G$25&qb^5{AH%EfG&1LjT3E zgDglhv4&7(=)!vzYQ+9eMJU(v$(Kh^Q0uf1enw~VFkeSQONlEcK{8rp*o6bhq!{e6 zpitx&#gT|kkz$2mC4wZVeHLgMxzTBcCm`p*@o0{nj~7nF8(BxYMl)s}#05T$|GO4^ zxrDdD+q*mpc;@NEZti5}5?&@xLBl2GfbDuszg#A?nH=njm5JU&!BcA8%Tg1GJgS#N zT8JcGW{r!#;BGqZAGUrk#Yif#PF)hqUGM}U)UsXeAq&fhjVi?CJ!R2Mm`9;qrcU4@ zKDxQd{+YrCYUhsdk(LXZEj3r7sHPwW=*~~0fI)+PCq4$W`_$u1kqgq!i2oXtW)uX! z8$85Owh_nN$4n+i@}O;I739Zqv}Wi;0kxPk_5NJa^M5neQZy{aI@h)TbQ*VKV2s2^gbBe|g zB(@NX+Z|~_R4>{d~1hH)Yg$|V~U*-i7@qSBf z9PU<@1TA*nuwA5Xm=bwec&X1+N_fRK=EPZ5$TeWdETh)K}<!|h1ib*8|tm+^GBY_a9R%189CL)$OkCeYT>Rvv% z>e2me$e5$5CLFeTvP4wOY7R9vo%TIS9>F?o+nSF~=&DFhZe>s!BtB<2&Q=gg%I#z} zWzckQ5BZ9b>{qLv$9{2H?&jz&oDL6Ku3i~!t2NCQru_MrO~MK2;CBBt%Kb6b;~1mA z5u;{M1GG(C+g6c~c6I?W<(#?l8XbD#tO8_iu+O}ab_)8ca;W~g_7C=WkQaHd{}sb9 z^g9V$U-aO(TO}=-IP| z648zCGdp#iU3tWsk<_UateYju>0M<67T1{gT;erLn+-mtMY;KSoez6XUmwP9Qdim+ z#IG2U2+x*J^^OQq@G^>=e>GR##nIWTwNz=1Igk4>dVr)5eG7M&fu>@>Ds|2h86gt0 z@b_H86%~(443+3||8*U9_vLI? zoB+)ui@d`OYs)x2DQ|Y6LK|Omea^n;9e{wPMv<|C#vYLwMobvPh7KP>j3{v;Lt?{} zt;&++k+FpoKY|R&aF{V=YE~I*B!%EGkuG17RK@~UL;sSn6iI1R(BsRV4oQBx(-NXZ zW3W^zQl`)+Ok+WLP6TEX&67_Bmokk=tl*tcxw3){D|Rf|vS!bsO{-QIFj!KQL1hZ8 zWF{Johyf#OjFuFvFXuLMWH)ZvwpCUUjyP9YCmNsDJ{%?x<;0Soq@2nNSuw3DkNjH3 zta&rVVSFDcQ}*e}P|_leHOr)fqp{JhD=TZ1aO>%gweU#i$l@PyG1NjgL5?2rN3L z*b{SI>GD!hm*uD4K-*K_L`1*Ug#n6DPmR>T4FJ3^cbTFXCyb0-6M|J9OswAm#$}SWILz1IJ z1{_kYL0M@NPCA|I60j@~>r+ujJ#ojA>xxufm(=2%v(7ui$5+bHkyMNt3x@n!Cu-nD z5nzJdrJgZud_q{7ZJ-g$FYXz4n2pM`LPIDmBizXtfE*eoNwmG~pvMk)iyC(J5sS{9fohn=k~AYQX%k06U*YVMoI3F!~6`^UPumDRG$JC&Ht2XPCz+QL92AzczgV+o7!ckTn%PP%49)pxq#z!_uamP-OCH$D=5I@lfex-|i(M-PzNrscLgH`J) zWGoNT%O5{UKDz}e@@MD!^WXn%`@!oYi>XV~mNSey=!7tGqJjR_W05=b!8eO>goVIl zkwyTb8Gu+&{HoOqHJGXj(^F4O+Q2FiJt7OVNL1aLfre2aXjdw(xmO7rB;AgWXVp4hU5TJWs+>*uWZr>DOhEW2nv)U z@>t26T#|kC!Cw`#XvVhg{VYM*A8Ubdl5u_sx*I3Y#MA70!$#JFpY)F%=1g;8u+aa)o1-2zx zs|rFwhRL3oE8I(+1BprazfQBdePH3%oQ2@V$ zDcXJFGO~0}Oz^do8~+Vtpsry~BL+znCW=uZ5k=71Sa6CIc_(_9%w!@DcTSQFX{TcG z5G8A9pDcx}Rx)Ad^^EedtJJAh5#pXr?$EH2ezBkl-6~f%7cQt2MQE6rsZaL8IJ(ea znO-VMCx*}lvJO=>m=Q*x`ar{dNeW*;GR+e>0$2LfsufRA5;2aYtiS#wk*9D;qBd1A zwOFQXOfhR4_~|%hoQOQbXoRU$DzYLPi5Qy_VpNqeRnpuDJXVQfcBqKhuEI99Lv=(S zJR-W4knXi1A;}#avAT=iRV^Q-K^ClHHc6t+Rj@z<-Q1HVG8p0)aX~3TbnB4CtU@$O zvZP-TyBI@3^Zy|o3Tk+p6|9@q@F-3|S?g-m2{agVepSKhxRlX{Pw+xuMzLxt=ffu& zly@v0vkxkv8ks4oRkjLVFrZA-5@Ht6g0#p&CaRENM3qEvJ`3<><{~u7vSm^30Y(qi z08oj%PF$`@6xV2gH;|yS4dVQ3akwT0I|(Ec#0yJ}H%XS_bOvQLR0h-_%a=Y_R&vUq zL6WHYi7X%onttm`hM1_&!yfo44Bj%A|A)5W9W_tZt)!%~z_uN?@wr0bie1M{ku)`l zP+L?Nhs%;C8l2}pZV@wSE`m1nc1LarBx@R-S4y|sK`CUcX`K^C3!H#*vesfjqa}Bf ztA?(KmH&2`kYd>&pcIvkd-;SD?vSV4x~hn7?lP-mi?LP|<3)xDu8~UOh%6AIi^pY* zV>DwJ#C)p7Cq6I)Rq4bY(m)kaa!RK*jizEa;l+$qlxJu?5nH_wJ2GTwT+tAUS}-+N zbk&>fY9`5Hrv=DuXtw-D>1HGbQHc-%^{TI{D@RmrDfDhNzx%DlM>w;(^)5{s$$*AF z*%Zy{Y1hzT0hIz7`z)&4UGIouMyt5FBrF1SyD!7Wv=qc7t<;x>s#}&lS`Ryo#CR!> ziH3X1%P4#tqbO+v^GuqiLM*w?k(zA4Fw4?r++k04V0nk+5Ov`GUOE{P| zXYRq}(_8}@#2K605pQ3ya{KVc9VzvP>nV;?ko6>wOzCEbk_@LDksK{EJ@cB^3M{I? zON5aN4RRccXwT@}k~AVm1btJ)#}ayMEzcq%)vd;FNJN}G(ky!SQAQXErfeiXzb08C-z9E^}0 z>aF0u09ApN7jp~*-2K!Pt%RcWk}^aa*1b&jjE{|&&pU<4%c#MIGy{!9OLp8~3({e~ zSqsu&STk_cMDSHdtyKG^-JVokHSvftP|#w@1uUqLgB(*81fpDg2jGE=H?5yy%mt@B zi7VBZiTsa1G*=`+43&}4bf{1bHdOU+A$ACqLhM_Z$R4h>f*RbMm-tN;*8kxxE*M|^ zU=F5{6JQJCP0`iqQ5soP>xovzR3aZDSL;Eo4M2*Qq<|L_qJcH4qB3N{jqS^K(A{JqBqA~or>xU!xDY9! z*0wQAjb%d0-A*_;j5j9ZkBQccIKmq~K?R~50PIi495nWSL=q*o(JEAdBsK(Wpn*uT zM_xdT8qCw<(4?4HgxIjnPTFOJSXm!jW;^=KUIJ!ta*taO=2{emQAok)^@M4V!BR$M z5K5)#gvt*(6cVzZB6Lwdl@zwT7Vh9jB`L#d*4vFVOt#31q-3LvSkle~$tpa7DTW^` z^nnx5f@*Bwm@o$*3=MmljcGZY$!wp2wb5@1XMtwXSM^Q%asQ;0Y!LxU93a*mEuc>8 zl#mqA7%b>ryp#}pt<+|16A%&^_6emx?2T4j#6WmSV_~A66omug=P;yDg)Jy;+7K-q zS(1U?lC{mf$rCe5oZKj;feI;m7(*Yx;8|eGn>gsN5T`+r3m^HYG6LT>Sv zIS`Nn=a2$wW#StpQM#_5d(y*kVtH3pJL|-X%b43 zRB!lNU|FP?Fk4L02xW%f2c1%ue#w;liMmDLdw`mGZvRof^(lb{YOd~#S=HrnDk-Yz zhkN3n>YxGR2-hcY=d9=;tFA>#{E@cUhxQQNQ9SEn%9WVX%Dj}RH)h6|oQ)J@0w6rX zpY91psLLs!0mxWTNg#=46ot;ksZfH}D&YwCxtVl`5NPV^zLG{sSZB-$B&xcOF*GNw z@d;mWop5=b!r{gt(vc?)k!OnN!@}l{1y&Wrg1*X&Kva|6M3=Pe1t93arN*Is9nMRZ zBDu0lYAD`M1W{Ek9G46oip3i=nuT|W5WniIv;feZ9+)zmLd^IqO$9}iwhK=9AtSP0 zn_NVAa%Xzn$l)ahxu_4ej%j(uUF~(N1xW^HrT+#(R2;Oxh8mm_&E=#_)W*B!M7%=n z^_gf`a$n3g2fDp&UgD$f>FCbtEsb(faiUK#a0;XrM(0K8)I=Zt+28Vb7$3oBdN5mq zEix9ero88BR&Qq!4Lr&3NBzD$Ps6 zW^bm&Md$#-?rrWuZ9yiLL7c)4GLMngnGO;}>yAqgn%ycPTy!Fm)#V3(umGcioRUBYl13!w4$C-j=c5F1Tqzn8J>*T(Rp2Wn)aqb%SWflmHs7wnLDg&eiDL&B- zPn;t+eo8^~or%KC8FuO1&g}Yz5gHpOW5ADGe5;SJZC2RO5bJOr%gZAiX}bY#6JJc< zqK5)c>U+4He=rBtsBCl`OGjw!B1Z&83c+C3@LAXxyA)OjWA8eGpF`^aQj28564b85>T=v=9wi9Ya?e<|k5RlxP#)W9p^H*W!5ZP< zMYy$2+jX&QF+*3xaveq;_iK0t;!pOqQR83Pxk@7pHd8-Y7Su1+oI)w45eQrLDvT_U z%!OIiGuF^TW&Z~gv*uarfWwth8ac{ZI>?fVHu~fr8Nfm(JI;bUXP;2eXS)Plo3`Et z1OOrV1O*BJ0st($0|Ej8009612m}BH1Oxyf`2+k=kJxUZnYhY%x5oJg^v#fum-YTU@Nqep`ZLyBBS58lUfFf_=FFcl*QHCyv#8OdNRiST3bg6Zg-N4Iol3PLLZ(i$4kcN&tJkkQ zmuej=a~;^TXw!BSN|r29wQ%Fg6_~JX+ja07&fUv*>eZP7zI_Wk*csu&h6T_x+qbdf zo@`@|E9l^1Wq}=@(tFIg^UAtG({&Iqx?%@*Pd%$%tx@dEao<=8peCD|0NJ+%(hfW> z@>|xxgFh4+Ip$%(+-wUDoE$mO-@>B(LMtHnn*yaZ} zXn~i`apF}- zSaRH;mKuZ{ekEZ{)~yrbh}Su_S%)ZA)s%STiN~B^<7uPbQzoToV^Z)?7vDwmmBrqT zK=wqFX#Me5BtZa{Rb!A$?(`FE3GOB(E4DERPgy56spU;TQRwAh+{`G`l3SL^Qd1;~ zm{5oyZfNG4D&@EyTXb$mCY*SBB&S_Y-I?c~8|}%bl7JSf=Z9k%s%S^>Zz!vs_Lq&w(2UA@UZ_QD?6{&3ePzF@FS~U zwX*6(JPzbDNUz>`F|1T0fP(-6%m}~$01p7bz(dbQTdlJKJb*H z`z^QQX1i^<)}G7mw(C~wtwZvLt1h|qx@&K`=+0YEz0ksouek&!SLmvYLLQp4) zbaImi3^zP2vEAJ@WvkieD26EFMIIEQxCoLy<7kM@X;5q zJ@W*S@sKJwB@njQPA72s00P<0KKlZ^AAkGv!!N)6_0unZ{`l{Izy9;%9{~Fo!2b#G zfCfxp{t&o81^Tan5PYBn9ij$-=!_?!8yy1P0S<65BLS?V-PAaP1~k~rC>dPVJ5*?d z3tS)p2MFN^S98IggpL^-WWoxWbpg}O5IBuMq3A!rVFV-K5CPzLVE}$OsRAUR0WO5% z4nN35N(t`(qFWX?$X2AiWmH^GyY1UF(9qBj2(H0BKuC~aAq2NTaCditTN-z00>RxS zxVr?m;4V#YcMZ^ockg%a{Xh5I^X1;}J=W+^Yt^h-zk2GKy^5xsVTA`q1=!JQ=9~|06d4sVOgz{zp@U{Vq}HR2nP)-!#P=iws-GeLQ#Y-%E|hbR>us28Syjq+;jig&!`-`|kQ>$G|vwjP8B>m`Y?Uc8@M5ppVqbbqy9ibpyw7?#nkDZL=m(W_Kv6TmC32J#6tA@V2jLP zZqVS&N9mP%Tx$Z1;?2*C3nrW5s87M;-&LOCsa5wBFR1Kru<&t4+H(ft&OT+v!ZWO_b^0-AM%2^naKwB>PF!rZfW>Qod)aTbdT;!1PpJ z=57g*?&TA5t7zz7qJ-}i;&FqC1T*}tti*0%;ZvdqX+QRhE5{H#ip5p4RtIH`+a(9( zt=Cr6!kxf_gUT*K0h5l4_FixQWh`aSs?Y!E- zc>Pv5*>S_Js~3CIif_wt?`+<3q)MpdWc<->XEq^Fi{|G_E1a8uIF)*A;AEN8WWDo)5fL zZ|S2z77~Tgq%-B<^@^nq|8((#&|NYD1JA>zvMWtGr&ZL2t|qFusX9qbP6ZXG!J5^|EC}6wj({KSKU`1$pbSVcGA-)@{xHK%VbU z03ynL!IeY7Z6gki(ql1buIy&R|La;G;emU7w^M*-- zg1}*Ri!c8Xa9)r1*!ck4`>6YZ{qJ%4-=~|?AdcTH=QaI$-se+0zFx=3*=OUd0!Qrv z`=tSEEh2v!gnbXTb3Z)Y9h7DY|2^!e@O{|)b>jPYvGy79bbn)yK-?i4{6%5vKmwgY zu_rPBN!NHlzEeM(z$_7TXx%h15{?g428EZY3u7qQPk0>;65=Dzd@mk|OSfLAcq>BS zAMVdd{+uvH|BEE0B$!9X5aa8>FUtGV5D`cY4kARVhlcblR7x)AW#T{&1OHi=Vq^|} zp;Rx6)>*j5NDg7cKrg%JS%d*3m$+Z5k1ORY(n2nmbZ(%Jr}-?(Au^YIN2;HH@hsYX zB$x7LpkMg@ECve6qe7D&5G6f_h05j85DgAU@Sn%RBJ=1Nr3YoS&c7#(?zsLk&6^Wq9jQf*bK4<3O_Bk(&NNP`4|lnXDA$G@V1WV!HsAt;vPO;HY?z04)*EmBA&#`)ic*BJ0W!V9AkLPC3i(WzdU{ckfjK`rEdIjbuc zssv~ar}`95E{(I+>jD%g5gYiPH=IZ(-#x{|xgq1Zhwa+ak5lkF6ZOnzx$$g6F_+TO z6=i6;aL@(vSx?Sg#r#W=d`&dI)z!9AH0!gO)5fLjbCGZ%A}oV z8Mo@f+E6jr0_^v}lXIt9?^^q!x3!>d*B@~xkut+ne>PutN)zH7YqzaFY#fUr!d$Jr z)0{QfEF{fYB{B!p`6er?C`$oy0IIWA?bFU zQoXv_99BL>?!=|LJg>iqU>j;{acNvP{KLjyy~LMdK2gY++~9GzIDtIX{z`~qaq0B% zZKkYUnaZ+XH&)23KM&UKl=>+3wvKNVDi2J-_4%||O59W|QF#Fq z)B5Pl&f}>*T)pGzK@26kIgvd3ySXq4mc6`qHLJb+B(svef;89ty~34T8c0+g%Pk-S^vYqwdtJ|FQ5}W@#>mzqNJnN^zyZrs3{3)PQsBAT$bMR+LE7wp- z^Mlg}>m1~wm}@E0YK%X1=J;sMrSnYhujftbYu;JT=vks>ng;bji9m@r8~?6H~1GMt8K7sl%C6EE^~2j5WLD=V`>pdkOR;=wk6H zLwWss(!Xh@tCDCbqcW!}eN69t6~%Cro98JRJ^xDCNgkXgqrN`7sU&Gx9REY?(Ihvi z(=Qn&0nCwBO||P|-br(wwcJT}-!9(C@V?&L$%KMfcC!Krt#-3R|36HOmH%H8gS{N_ zpuG11efiU#5PF^fbIVZ)8FTB|*wS&^Ill}?d(3kSrQD~dmZFZ6<*zYKk==h4+8zt6 zky`H<*f@F)xNIs~P9y}6|2;86*v<#&5^c^0nF@cN53w~Io)2^Ovt5k5o3nYFOJbsE zImZ9_d1AyqK`wJeU#wV6NN|KZPlmCNUS=zN(6yMBB*NO86uWtNo3AaqST`qx_K$r% z>hr#y8bI^k`})c(fHw$_MJKd!y*mW;Ogc>pms%_ci`7cd-7%{#<`suO`TJPfPv4p7 zjh@qCsfQCm%rD6qVFiFxKB0u^rkV{ABDCkS3?=|mXfy@NF{@=2O{*O+8w1KxXQhH9 zYijrN?r6KgQMYUIfdxlTv4FIuT`YCNa@5b**7HY;W9erm7&tJ82!-&F@CpoNUy5~d%JTnI3 zMJwY{wHXOPL72^ad7Hi7lbjdLPJ)ozoaqve$61}rXVJNz=j+Zpkk1^v9u4{XNgv zc&@_WmmP{#oz2V-pp*jsaDCZQ8v0;Ly7rI78nx2Z{b$~>!P^Wi_LbF^2h6pH;vH-e zHahZW;Ttn&$a(DP_xmmQRwLFhyKN6)?r#Q^mj`6tPcyZztppU>Fx#elG zD*|!tV6{IQxjUmZCpD9*)G3dw9DIv_wF2mYkAYu2&cFupthtAUS$ck0*ZR^TqjOoZ zm}=;1{y@cxQGP$%%}4+&pGQ5IFkx5K0f=issF;vM1C!wZG5~^rZ03KWc-thRLd~k; zmiQurm}t#`9w8gC+*i{{0CtU+2IRn`$t)2M!_dti)Ix75b(ir)$GtC;ujD^#B!DMb zn0WdW;(;H*InHO)HF8YcDVB^9g`4zgR*Yv-i2)u*32W(rgv^S(zQBZCoehWCub zaJk*oQ_`Hfi6-S`7xvJ?AfxzXvF*n~9b@bsHyY(po*-}w*875O8Ty)xST@U&>}j^n zTxS`Y!M;q1(pAHyJpq`>i_Gq-5k3|+k#6KS!;aPXUFTy0gFQx&k0~@!d83kU-sCm- z^cUE`6Joq!&R-TjJ99R_@0q`rpudLAqr=KZW-OOzV5?Sm_gZ%8+-5>ILN0N(BQq#l z-(}Z$@9%L}f;w^`i;<=Gjvrx?c5;h9tkWUuL36s-oITF$HC)Ca?9Fewk`%b!WtA$_ zAJBcmY1zHm#6~*83COq?A~7*QI%%VIh(XOl<`4l5^ZtIg7?XVQcsZ&5`SEJjJm&Fw z(e3x+&1%RC;Y*t>cE$6an<(FVsfyq2BikJuh=ZC z_o|H7a7!-=owz*z~O{rtV>aWIM!zI1*{5(&Vdka7OQr*?-! z)p+-_=wGP9Gq2crPtY&Z^ZGwfMdF62n(BS|4`^J8Uh#9U^x3%vhYgv{>!_5LDiif= zIo9#Ah#(P`E3MiZX8({*FuqT*>UMM7#;QhAvo}Tl z!DnAC!KO+r54AH~Jhi?|0~ndT+V*$a>i0>4hs0^L+FpCTF;j zLvTCiJ53NLCwcZrB)9Y&&&4ibYL0@VG<2m7a6ME z{Sz^i$CRs%$p-is#kbA35v?Q---r=8XUbD1!B6%BNm4RHL9#r9&rvlJ;H~&CYSLRj z)Xc)R60}?gw-WV&!3^<~1kA8l5=gO`ibeSzgOY7KGozx}*n9JTy1f4@yzd zQc>B15jd(Cim(^SovPU=CCyA!1>J6CPVFjJGJu~NkmBCB_c#^`NENQ&6t7pkMttp_SMT?A)$|m` zvdKXUin@O;Z~xaJ00Gzl_0N$_|LK77;o_ZC{vcdRwnk3sPeC}ZWSpg{vU@`b-sq(@ zzM++jqWTbiDOH_22%}fZAooxj?@auSViWOxYN;lf8+Fxt`zW6`O;G>&L$Cc8=a2i( zb?^B@{}<;knJLw%v0C{LCTH-A$EOqS2dFkdjW^9AJX)x;T`1>{P_tWXvOn2>ojO;p z-|T?gQbxwh4sQ$oOV}r?!MWDw_2REQic1kHd6UR7?=zLo54K*Kq`gnY%s}o(7G|zWUpZ;r7PcjC~3}>VR%e-l6n|j z#=sv#)^?`cDC${@oCuPAV%nJZDUGw}SwUuK)V2UobZRKm!e*Qz*Yk(2!n2SHNJoEe z&jM8WzLlWqSxld35D?ZLs+|#(NO?c0>>j>vEh6udU|Uw<#V>%3Tb-EB`F8ayiv4 zAQ}ZbnOgg?m;f!q#=(BB1Pg&L%P4b*bC))DPFV)-f+`PtR$9-tz)+ z)IggEU~gRWMpkf#10(Wp|3va0-)_Jp+3z;v)$Q)KIOq+alj?5AcRN`j?DxBQiFWsU zMTO<}`*oghBs@(hD}D1fwBv!J2J=6m$E_O~EhkMMa)wxeoiuDvQPabdoBz|tYTgiR(baz;|_H=*T{{rywG{i2;6(^dB65s;`+uJJU8Gcp@uIv=)gcpS_(l8x>5UrcTofI!J=diifA7iWPo zzYrx|i$@L-hy}A~RfTJ`<`CAPN9d#cgUP)KMP(9s4r+eK!_^sO=WSf}2fhFOqEfWm zPg=^oq-Q3l6yv>|`wCThKm>Rm9YnrK4NjJlVE+;m6}U-@TilN~ixnQ^wN6_Q zd8S+u(sc}K)Iqx#Vhp}5?x#*!(A$Dr&F(AQ*kT{GEO4>@C&sRD+!Vg>8w zsf_YVOL>!S;^Sa;W|{an68U{`ww%;Wk^`okp) zWnGD!Pk3GF-ySP1RIpkp%VdVNIIG}H$~c~AP0{OC28j<%y=tcfg!1Vn257SL-K5t} zbZso^>)|7qDsT`uomG~^!H-Nuq!6pI3(Lv{NwcK(hjS|cm*!yMcmCUIzDFC5PnZh= z;R!WGL8hj7GFn53gqcFy$TBPInI1NsbDb%{62`}7b(WWNIsK0)$}fhOxA||H#%*O( zd#xlVUVenk+1iQ<@Xa1X&(<@P<&ufFXii5bqKjp*;qv@d;L(G()oIg-P-G0yWEbL;5Rwy)x7gvW@j3H6Me3AU&{`mhy%SKE6;nA4qB@0P?(50gSwcxH;m_+oW{(fCiZs^QxC?{mo8@~j#hIL2dy7a*gopFX(K zt10J>ZG2{=-+pP!-LShS`Aypkva*5}od^erPCH>IOmIelrh5K%OH*6S!5`PNcCG+B zy(`b&jpHAPMy(zu19iC_{-wJy^E5jJeP+;`#%LrFJqOb|vRyI@kMY_WHY+Uh1$I`_ zR!+MzvkJLg;u<&06Q6fke{C!lzbv$;v>pCHYpa!J^c;9j0Vp{7tM{1^e>kO&D{EN5 z`j($`dMk*nSQblD7mshQn8C$_wFQI}nQaHfIioMS?N;Lxh$v&~t636UmV;{Kc6HX& zH;f+HeJ<~{Sz(0PvRYH=Hw+0L*N}-ttWedYPJyBwGkLL06h6G}J2|R?E|o2Otx0M3 zX}2r*tFx7#?zJK)?AA3QdwN1h3`bh~*>r@p1pU=A{1?lq4g9q4f5W$ajs32R{%Iw6 zYQ7l@p+h~P1Rut{HPh(X!z!Hq{=c+`4}Lhpz2x)<)O7m}r{9Cz8fGh4p`9OAhckbB zA>grsHbcB01~>Zd;a*4Pk;**h32FuKy`!gIG|jdnx5~wdGDXU{tL6c7i(3f~KL+2e ze%A|0U&BN<-b#?2B8IUdMwtkD2n;-F<~J$f)vJgx&gs>UYOWFQr8y0*g4uSu`7p+n`2Hj1+o6TBX4TNYBdLMVQZL>&h{I z+b-VCN4Q>JtkX#u{p)t2``dY6)q0ouAaDGB%~wROCX%M=Ou^cG(6_FEqC7#>gu$dl z?hrUAgwZ!^&T?NJy08U`c0hNf^24|AD>e73@Bi9BWJ}@hH?5{KYbH)#i~g24WYjzkw&b0%xzN4 zS`XNz(A&4bW1bO|%>;58H)q=c83DjBI0)I&g0~Y4Ge9A6LpCNdhH*wr5*kMXz`<&+ z70~cM{jo$%AdLaAA5}=;p%HizqRUGHIHy%JHh=-fL=Iy85FYw4l8%SnsC4> z?F7%GgKJ@sMiET421ghSG7*e9rwG9Z#|AS1%BgJAI0NGMZ04Xzyzu97{XWxRO19%Y zTj$~!Z-@QfN!v{q-O?4%XxX1=2TG1SmvDSC`$n5+ipt=w(r1ZOq<6?0pW9$*rwHza zV&Z#XlyXMbHR^wt@VP1o$p^5%)PM{_zn*A7PMM4Z5&d7^yD9aV+Fmf3U+*RyE@T{s zy?<~=a$0b848x3u^H=Y}fN*|FI4D%pHCH4v`84xs!S$6xc;$fhizZO{Cs3LLx|SLQ zau1UmcfDYUz+rKn;^nPLGD$Q2@j1X)C)CYkmY-V2Zo1!1{cTRJRF1)XEOm-$Spck@ zHup{QJIdx9_x>Fs;qCl|VJyXm9bqEx$Pdn86Gc{&Go z85$}1S{Q`v#EGHFZZDf%s&_#TcY0b9n6``nJE~Yce%CUQg4mnqNSs7rEr`PqI1pel z=-_snY&t0N9YZzi4xFQ;VYp>(sWJ zy}@GthqqCd=Uiu2=zdYgO;N>LkmmT0@`mRKLLDFa7^Rd1hQ|DQ&(cN~f`{FFntPb- zIDh&c{|n~8v@DF`B#^^UX?0R!8mCV=RqWfLSXtvjtyv5TX3!`LOurv&A);w+h4KpL zr_!x*otPT?wic^;iD~_p5Ei$>dl_EEWEd>>^Myf%R>iHB@lHL+9Sk0&3J)bMuG`}8 zGvh7U$*T+(r@A%U^~mVWPiP{odMQvPij;Vf>{crB9Yr>_eF%k?D$y2>^k)bVpaltm zg=fWP#pc7LU6IN}d>Ube7*|MvaC96*v0@qkT{aF@%oj+Bp>~m{?M@`c(5QAk;$8tZw! ze)(6!>Q8=NzYJ|8^0AjH_rO&)e_J|-6Iwj0pbXg<^wlQ&nFrUf2~F4ZVoi;RhN*t1 zzhPQ5f8&iDu-s(OwVvCS^;K6Rk{aiSvI4YBfDFY6QsuH6O>*^3_cLmAEV2|mwR7XO z33ug@^oou%{P@Wx-TXP;_{FRHVpyswt#OrRtj@|9Ml_*HSH!J2QP+)k+$h3Ax9q)^)5;4Yn zubEET-IkYveI~8Wv$93s)YNmCc;Q2hI-!|z@W$~H#bS+IH#%21M)}i0$Jbwt6@6gW z@&1?0x!O18M(P8u5Ep3#X3L3sWZAa0L9o_l?Uz&S^8S{-TkCR3hyekiX?S?;!Sk&J z8$;qg#fe(8xp*DblFG~ZN+X@VO7dY>!sa{va^Y~_B8}`a&I%@*{sPZdn)__N{an7` zw)V7QCY=)b1hw-k*kC8PwiEpOVPr}`zv{1KnvE<{gxeg%;CNX1h+ybFLCYI=GqEeh zL@K3MeJvQRL)fzZbu7c@g1;wzXry8E+~`;lB`20~4kR~^EVUMAxFM7L9c0(4T}*3I zsR3PiVQm>;&5qY@IV66Fs93k@EgS;O>G+b4jux?Y?)0=9@zkaqW-E^#?nu^(}fS%Op?5o{`1ge#0y;E zYVwe)STa?X(2-l7Nui(!I#;b-CMeeR;eJmj^}cO7GSUrRQX*DoXq*~));LsRW83AB z&n-0PjP=Db9`MwwD>^!G<5?tJKWMrlt4}dcE;Rk6zQYu&H>j+bL|(0;cB0p0UQ=j> zy?KsKW|~51=KE25yzMyMsCH$XA-1Us8->y9BQx6qj2-~QWo5BkUe#^%Bj4!9THU3Z z*Gpi|rG|6>k-<`J+fvixQoGP{qwZ3#{BpDHazon^U)yq*?eh51(xCiu@5=HJ#md<8 zF}~2s@3NHv#LCLZ>t*=LN}Uf9keb~Gj-GxBE)~H%#=;x~U=C$L`m!MXB5Ol9SXX6h z*HLRX@@o@WkS+sA57k`7^RLTg&^W`8D&g3^036Eom%{7#dh0K+*Rkx@U#`MQ%Gb#$ z*Gbp`*iY*;zUvg&fAD?(Fe&^&qXJMzuX8@ZS$x;I%GWuCH<&Uuc*=;bcuG3Hg zMBCw_PcJQ~0MVx}OAG{&aUlwnkQxz4O(o_RVayu%rW)m33+I-a9UT0$Wnd=*Vc#^- z+cxvvHWmJ3skccUy=|tjX*ag*z>Z_gjt^1TakkrLFW<2f-f=tr<1W1EsIcudw(T#x z>rk$+>(;*Od;G_@d^Z$(&#fIEy$Uz<-Aht1r)}SRwYrz4uuY4-E7rAVrLdo_uoEwg z6PH9#(7rFbzDFmFldZ5sLRNLnGc=XlwsFVG0S?_q;_gIPkcs~00aP|0@ zQepGy_+0qp(oP~w`Q$d^L<1M+ABWigLU;|x|5d7c2{eO=eAL6n2GUA(b_c(p;EG3g zH0p^Ue5Gci|(yAxu zD*5Zqc!pFay>3Y@^HiZiu4p<-9m`CqT8+_4NgeB4h2AfJ3f6kIg&MP|9Np6T*Gmm{ z8{O%w4eTo|rf$MGmFn=-4#?B_7MVMzL01SCoafv=>E8P&DtVqMV3Vtri=|Y>Vi$(OzAR#?iuk^BYkjFW+y*NMaP{e*bvh zm=`Bc81~$~gv*ldhqS1NX}qRd@m9Q!5wjVLo9m4Pp>ZBFl)`v^LL$|;)-WXX>yY$L zy6d*4IhpODN|;EvGtGD=5QU#9%O69eC_9|S(;_>JowPVNO7xy7_q!f{asCe@8Owrn zyM5-utc3f$;=COG{gRyelD*RGZiJOpNo_StX-Ros$-&S11bg&u@UT(Kkua>h zfwoeBBl>2Hti0{`&r(JEK{FXgD}0F6p%bMe^`z?xL&u>T^ef`D4F`FdvxngAh?n~t=aQSOt&x1)T>Wi{i1Xg(L? zl0;F?zr_$~wNr8*RxYQ%s8d|cNEo*{&+6D8)lC|FT5*|Iv6io&F^+hwTQpA{y@K@SZ$8|5uL3%V~A{$E$hsindcM&Px6R_}An6+Z5UI`-82BnD)E< zmNDPmgKr$)9(Lmp?T`CwF^yPKfgin6n^N(p4>>!5FaK4l3r9k7#LyV;@vCs}MMkCh z=*OoBAi(cLecRXtHX08g&!a+@wD^dda2mh}p~m305G5?H3}B|q##EL1MAGdL%ww~T zNb9#+@b z2!&}Qf{w;su4u;qTzo0y+dqCUYR{tVB5BEYnELrA&!SyNXen=s`i0NWVtgTVRA|ft zqA$;3!G{}YFoOUXQl$xMBpnhMcTh%Q@_Qg4kfpx=|17JcKWz>fcwf&HTNaqlW-L9d zxmcah*lJ2GIo^SYmGg^-Y}1D@j~Ib22>hU1bt0F1+k}ruvD*jx6Tpphy6=@9BFjxE% zyF3fknxUB@SJhHIELM#gmf4CF?h@nItXfk;vlaEKWg0;Tn)LT-mEEzi(Se(ESIpDx z*s8?xSU>-b@G587bQ;8D)T>t=^Bm<5bQsB0ZDy~2#+Q|vzKzgq>UOEgm|-#hK(;W^ z>>MkVB`Rbc^0}k=ItMGjpK4vNSY!lqXadG z!C4Jb4iyXVBhx`8^TWfc=a8UA0>4-W5L)k+p*>iupEmp9!5jjNqsC`OJVhY6ryPOQ z5WUdv+%f9gTxwI^oBWZg2tb-*jqKFJ{M$8meDQ(8}E4Qx9JJL|TXve*5xE zX@R5+*Z7`pMb5tvo|iy7R{p+v6*x@I9rIafYE@?mRtOR?lJd(2bK}EHs#I-+2Q>H`l0Ve4N>YDU-i=5 zYZmT~UYkI&qB{^4qTPw?{IwZR1rnA$U1QCAzu?#x&YTcVyR<95Qrn)T!9 zM0v(dv`|aJ8|yR?5Ob(0yc&avNr!eEJ{wga#4hLF(6W~$ zLd18s&gGUjEM6llVL3Vjt%9wUlxN>QE1@yHWDq|{b^33 zSJAR4$qerA=%8UG%%GG3va*J{2I82@Ie5T2QQUVWs0M;0#xaZxf*j`z;4i)Q830`9 zF~mgSwmm`CFo=$QL?f?bDVoqhvvyi?3LN)N6BY8XW$juZ)(j6n?q2ABPUye zq}9q`;L16Sk2grk4p^DDmTOE(ISH;#{U{VnI<_c*gT!%t7Ow3Y)-kRgX*eMD0_O;E zXp^K{J40k;KiHKjNF@o3Lu{T^5O8YYHh1dzN(7y+Ao4OP!Po*tK@)?m(R!}aRE#9V zAuyaBY(=3FZ3lIwbj31qK<}-D7*fRoQLwf`eCHf|FPix1lg-jGP0O76Sm6I2vm<8g}Y1I-jblX^%(jrNIQix`V~z z!~&rh!#JSHHN zH=f49fx$(tSbDceJUCuuyda(*-tp>@?L|3T^##2praU<5g9C|jPQd$EvBgJ5Yy^3G;ev!?72Z%W+YAP7s`4Ukjx zg@3_t<+S3rMixGhP?~#V3+3haU5D2dWrJ7=9=)br6S>sRfwVo0$yMD-b;kK@@my?eVS}DZ%-l_R{KdSk4?Zd!~l($0GiALGJ@6OfegqA)d;u0%oXdq@)%hBNE=#`$fp9? zLJjC7jJjJai|Pa0rCg+}%dWUvH3>4W5P_kDnxS~%wtL)7iK*@TE$xfQIj+y({C!@h zHS(z})EbU%blRHVS<8`H-(Fg-nAibKtGBK7bx^^0VhM+fCWgR4s@5pz5G!VlbRMek zm_&2`TALNJAHVsG2LEbEhL}(;*QaP=)Hh0gnKd;tGg*khD6;CJ`YCBD0E&7Ciet$J zK6ib*Nq8{`yg6vNXN$Gj%WtW+>DD9WUPz0S9S z%*9T{GD+*oj#+T4^_GT}T&u^nDp6$j;6azRfSK*PQbi(bmwbb4)F?{h zZW(n9Ia0${8e(7L# z4J&4|rWv$6sM(2?xM-)T5cc;70N?58-Ka>1L$oi@2Itd8_gQ-iF;&sM2dz7MLSU)A z%piOVl;P7%s9>)%iT&7hbfId6#386EvJ(!rFZJkFQ19&U>XFcKdh$fJt958Bu%0K- zqD?ah_}M>>?xGxmu{JWEUe~WP^BR~1HI=RJJyhE@YNU=cnqjk`EghxPouu;u7;%1= zS&}#?E?+sX-W5&!ZH=~u5KO#lVG#5F%^NkLh&rlrQ?1Ab7*_1(T1m>%nO4=V_;hC& za+*=%I&Q+N%4#D?HqzJsv)k^S^CtmkajTJyS&NC;dPmbTYl!Chq*SS??GC}Dpv|P+ z<1E>|j8{tw4_whmmR-&|bvS7bRkml`y;oAui1OE*<8)oX>w1Nj9=^tw)oMSd7C#j9 zABLl0s-_;jY`UYa`UHKGn_T_vsJez&dNO8hjxN^hssode($u!24$lbhF&0dP6Tqr8 zEcINvO=}`+B_{yN_cZ$%JM1E8;k9w+tG(O()}_vH_zS9Nrr)2`Bz{G zt)>!&4~42(Tavg4RU`cRZ)77A_`x%@oyxC#K10<;Z66npA6NAf!&-t`r)AgJ9$O{D zF-Be+f+<=rg{JFlM;=BsI$FzrwL*#j*%)@+v-is$vn!D^Vbly0si5^KdLw+j@xm4J zV8PMpkyTo(H5%bR;jRF%qA~brL}_c@Wpt|dXMd-B|EsJP2UT-OnK{kO8#%H}4~js0 za>J&2wFlmA7Ml@9@$ck36Ps9CD@SjxRP?~Li(UBWRU&`Xe78afmoATn;kvWKYMVBy ztE6(9Bnqmdshga7YxT2j9o*YI+?&^rD-MEi6Gpp2)d3+>uCUg{kV=eS&@CwC?wL4% zfgOP5fE0o#4@+@JidfwxazFx~?xqm$#fEE?PEQ8+B5 z+#AF`9I!h`FW>zni3fE6Pp@D^szU~;0E3lBLsWp3rz80B(Vx|$RqW$Fhf)8G<9%Um zG+5Zt@i7nItdiM zlGDGE&`*)$z|r`;E6j2E=^H@B{!%^j(zxSF_vAw1#kJOFJQFAgIF6nP7pS6o?$LVV z%3+KIyYb)vC?HOro^C`DmprckXjB)_%;(46e)w=3RB;o;aoR_F@jWxlQ~&Nq2cD|^ zmF(whnTpG}%-b{eJ8%0tZ~goBPuFdD0F()`2BhsU58!CC~z zb+P^3SjA)cn&8T3ypf8BDf`EQ4!kH4rgp^BDTjX9hlk-8f4SFhy*Zxdzden0AON^< z5r9837(>jR6AD1WBoPiIR-*Y70>&auOH$hC3q|H2bRJOJ90*27Q-BnoO%#Td7{msW zC~wQ9aNDl-BrESIWC-~@p^&QVD&~ksQHqz;T=U#y=*Me)-z9>B=@>U^_J@@5la(>GH<{7W5+bz0xr!aZ6x!D|i**Rwj$;gs zcPp(SH>;`|T8-OFwG_cEzys}jTe>|N?lhC(F@CDZbr5GOW||5s689&SG=35`)N zrRL=uDXNf%DknCosz^W zmv@sAj6v~Vq**Cc3}5bTKo*yZU}0rJ%QdEdW~SY4?i8To{&Y3OpR z&T2XKUa4u?rq|6Gd?O&#FpdyU&@gq=omDr>bm3Vv%uZKZRHNO`d!y8_Rj+NIi;0?} z+D%|UkgagXqw6wf+OV>#f-6GcycIRKGHg?2O6+yB)u8{)%~Ko-eMOp7=#R(;>-*rE zH5!KejoMmow25srir~QJHj11h-A;`90D5mS4+Q?trA@#y)@MTU|L+?q4zSLT=%{pJ z7O?E@ARICYZ>B1m-U#fs3ey&`w0%)j0>KYV)pUb#l*-X6mf!P5{ZZP4@TlUp>&>|u zz?~j71#Y=)y z;Y2jIHa?gD$q>aPHZ{Loq{aBqjN}vV$#SdH-7JN2et1f*u_O~=mb>EyZX}tc+5`N| zWFX^E_0x}H7eb4BX<8R_?RN7J>Y{XCspEL6D{^ZiySgeh;wcMP*e?=f(eQs~PyV#v7)&JctfcLLK!^0Fa)l z6ZsY0u4NXA?|xyC-}jQjVxOGF>=KU>Puj%cbwmhFDub|=S*qoZYgLw!`SECdZ zK*Skr;0L53+pi9P^L%A~oQL(OW{RuGrf&WVSy|1pnYC^0bnx(D{c3`BN#nL}#Ib)6 zAzDF2T{MzR9;`(3B&7iZ=VwHZlV@4;W`-<#(1DehD?ha$Q?RAsuM%;2#T7X{fV?QMw;a(Yb~noQC=Oy=%taT(H@W z3QUpL_KLp6to(bB;+t~% zlcmgpzOl&ck^S!1b-y8R*?2okRv+zGvG5QhS*tF}g1n{v$Qj(BwER0Rd8Sh-tZmo) zRz_s^&BP)d>67VK!~4hHS<408a_@F|a8};?JEfKrkBAzTHth!lM0gJSeJb^wOxbw! zJSrUyZ44#-6q42-^P#1k5n6AIxd{8+M2vLbmUAq3x$z`ZMDS>L`(-ncsK}F+FFawa{(1}HwXqduT zY7PQ;nsu930P&8~h$m8&Be0142#!^8-|mT$Ced2pj5i07!=e2FT*5~>OnDLy(3QB-Fo|RR^8v)A}2&(7$B;9}&0-Kph5|^+)d2$V8 zk4O{{Fx>wV5fds`U+WQkgvewE0E-nmWr~XRa)x2S6@cTl80Q?hJb5({MBlNXDLja9 z#A-z~{26392Qk*)R^n85q&d7NVjlo#3d0;XURG9?sMff%au7BPNgl-an6apO7gtam zeX-wcJp-;cwPB`4AX0EFF;)G~BCcjqQmxei2fBFFV3@e{oZCeBMg5y6r=M&S2=C-fEo+S4FHDgY z328)SqUP*%&i+_Ys_mWkB1C=Ys^BPq)OkZqQf3GLZQd}eC3;S07WrQ;x(C!8VkI??X4Rb{b=Y#L%_j`5t+*EoW_WHpGEDjtm0=kvUxvK*@NKHCr_BOT8Gr zJ?9W>KN-GL#=$5u3V%{bOxtA!nY^rHh*+@(IMIc{u8K4OE1NW~qp*Y+GqzW5**K8f zb`Pw!wud$DIzDbdN{uFJ<`N6a@wL6SajA=)ywj@xjX-2lGTsx%=*-i$#!cadhYKG!Wz zS<2s->5x;luVrf^AXpQIgNQar-nn@=l-rc*y<5VUiZEK+i&2bEuvtvbZ4_>91yUVL z+!ywX260<=T1@5EHNZ3>?)A?|=%#k%TkkMZCeqol6-oca-5?xc))P-7V8r?RMF3I} z>Y9$XifAC}qB`O3@U7)kt~-cD6!gxF-78mMk}JCez}J#t^ce+jpc!OVsjP4=yaqOg zA;M6NQ6xp<-&rlJz>^(y(ejzTOhziOHOKnQJt(j3Q2zzAE~WR*io|90N4nvbOdN!v zcVmIFm0T^pBdSP8ae`uCn5Hl_D5bV&w~1=LJ<_B8{3G!2PHRovU5-W6VGu%4q_NrH zv*RNh6M()dA}k5}nyCI&L=u())yHOB7wufTWnCuq`52bW1lQ z1*GGO(dN@!FIrUq0)lWH#0C}ZgcbA=+4GjrT(A7*%pC>&e7xdS_QZp-8qju>&;qW4 zj#VM_&Vgg_L~T2Om)*7{*hIU=Ty_bHJk9@-%EGm{A-eLvM0JMy~QkFh+rW)+CAmi7_=Q#j=HiunB`ME4(siyVt` zKw!vJNK^q-cJnYQdz$K;9BN{vqakhdBMB1V!Z41jS21n&W7vLi(ALuOi>+()99JNK zH&(t8xhYZNC_qbfIK~W$vB+Z702U8Gl5LTQYM}yf3^zDeXc|U#z1Bxsn3MC8bNIA){me38lMP(j z)mX3gd5JY?u)GCg=>cW4d7wlCkwin}=93mzjF;+OBCOD6tjT!AF-*5bAX+_9c*iUT zXtKr%Q$b;D&nIr+v3CF}Zz_}fw-8^7xq@!&9Iumpj1b$3CT}Q{kNFX8_VC4_QkZc| zjOK{O`y_4rN?sFjWq*q-dZm8*i!~k)*||g0mTTic8QC!_3EKWoSL+X%Cv?FsAuu(7 zB^gwkXwgFKXdXyipo($>)LJ2T)z&ti7IY0wNpMjaT(SGcDYx<~ec?`^PYPBFM==NX z#YFblLwLVQSY(231ji7*Pwiyvv3Z{7;b%87Wb|6R_KJTsKwh-$#N!#VrLuJ0kye7O z{UtOk-bIr6)0>I~Kvt<1Ln8k=CVVczkBuWfQVZ8;P?ZEE{xh?B&!@<*o_o5?HKa{G zLy)m44JMF+sabpJ_a~sd%|s^4@|(*<-%0lxN;)F=_{a;x5B-F(6Pf4EAh(wx;U*3( z$XhW+N#Fjtu9b1#myfKHjo=%EvgmY8mR4RU_pxIox`lm@=(RI`tb74R~UeB8{WiYh=~*N2StcuV@-lm%5yTVf&c^r?8`Ecb{*@svk`&s=WiQ|dZ*$*p*v z_I~;Wg7QuscP%+1*9o5$c6O^+t%fxC1&l^9T(P8*wSHTP)|b)8U)paU zQX5!SsYqm8kNWHJzU7V|7aym5qYQNFd_Mn+eV%2VtHC>6-t@kD)Ibm*gaQ_{Fe79ZFklpJ5U;NsCP_ z^mur|Eu5vFi_%YdHdqjz zx~3Va&*$3LRj?eEDHkV6YIl@VDcfr8AJ%ojyeZT1D~Ki=ustJ`iP*{Yi7oDI(G91(w(PiHXA` zQL_PkZ0*rfI+^$Mot6Bo6J%LDbUc8wd{AD#h)nj)vmhxOS@=%fxQK`ZKG&O40b5b@ z$}9BtQ2ZqJo|L>Cy!CV(qD+eyE#I+$@4p3aMp^|J2G@P_aP+e1ZQJh98KcdMzP#^j z;BV#?U@uY|wE8p1Nc3@yuQs$kL10W$vHewWAty>$hyxb~S3=Qab+KOq-A|60Y-K|_ z<%2e!Ba>uJ-0cIj?V{iLdq1}i?9a+Brch+8!&t%@zQ4=dOsUfdlj$t0a7oL@U1!KE zr3^YHqUn|Uy4Q`q>M>d$m0}e6N0ho>g#ph2VUz(nCdUBk9-q-;nAT(9hC!EzCJ;367X^QNp2cBa%xs@`tEFEDWZA|Hv+Ln(X(I4(^)%s0g_apgKOtP+mAXeT-J>@ zOZIX0^{h|jHA|B*OV=?QB7%IVhMENfFp>e%;Q;hXqq$0lxt{6an(5)u>EX(&Ibp9k z;R=X3-E0y$03~LgVPl@!i&v>*UWFK-roW)Z2vE{rh$R}4k=Im;T+kq11i}_%J}#;= zLi<3An(~^U*aZ{21=+ugsvYxM`b%;c?+oo0Z8jDplu;eopo3R7Ju&EYR~|hq=(SKt zb>VWD9VDV+8JlnRGb2>bZppY~$ueU_^Y3C>#bP?+VsghyZpVtA{F24TrJ{^g3$GrO1~=x>_IuWV(ko!BkyVyrd&U6>GC zQ1x2f?3nMDUy{OFQjJ_P>R5aFxOvpEWyiSgHnEymx0*1q@O@$fF=uJz?>2_QN{Hho zLeB<3VROxkxG8dd3uA5X{8!h++EK=01@SD{V4db-v)&84+-`gGOTTuyrPkO4x78+R zlh_%gqW0S5ccGg*VuA-0@;myI`xH#SSZ4P6OtwJTyH@h+2AS*Y9}n>__B`zl73}sg z6%Hf}cC0TB>Ge@(Fy8fDq5Hw3W(}hDUf=h2{}vu5j=ujpi2rvGVSgO)<3M_IAHjDo zR)8T}@HkZPB;VkquyQt>>A0kFxAe!cFXp=nlGB=~<2Zxkq93QtnWwFor}0duo%W}a zB0HUeXBC~NgFnuO1y7Zw!|l(vNiKE_ zW_uM5sst~NGB4=85OA_5#A7DTnV{k<&}$~ZEfe(q$0Z1Q$<1=PqzBxOm^lA2acO^v z=zWEpb%oS*1&*Hh_wQ;3a{ZU&8e8ZZm-!ms@S4E;`u)~55&W9)!wm`Z4NT~UO6Ypw z9~e*!_Ju)%V1Vc=FeCf}*!Sv&Rp^%U%`F=ZzS|!$oycQ^CGMJ8vG;jG^6@4%!pWB5vp#8ngK)g*+TVKd+P?QdRUqMwt!(E@**ma#yGn4u%g&>WvX6YzBqbZ&zA?+i0w zP7yi;|5KLzmjzz)hwAU26Ow;oKhUVuvo&&ICyM_IbFi6Ccm2!MEF$mFo8m_YG!f+T>;(4yrdmxK#Z! z;7ORD!;{aex_ngO$o2$mr;}9`gJJ4*7GDo)tO=(+HX3bhFI4o&%dNZE?G2Nn*@ny= z+#I4HH4b>_|NVZJw${kxO~k912{Go~TXFPsyHy-;En*Z1LPiYzi10@36L(YCZd9jl zp|&JI3Hhyr51NRGq>uI4?nv9}_{}sCq7(%d)#IQHbIAdW&H|>0yz{DEM@&`*Xdu%S zBuB>IUeSC&$}SKm4HgLHzBBtw#|7g?41AB@^~+)q-}=v>q+%uk&2XEIY@9T6ms)Wp zNl}|M1$AD&vJ8P~M6INa08m0IDETw09RH=BZOP3jk&-A-I!Ad>cqTq>kfW{TE1ZBa zp}%fMaweRaHv~=2QeJFy-6iXSuDkr)ZOd=`*;;v>j0W{-nwJV?fE_x;QM}@T z1U~yeu*zEs#nL-Br5~t~uB%^IRwRe?YlxL}fz9$fW<9utC7qgTDaf*6MZ{`4q2!Xc zDe6S2&a-a2IJ}n4(myB@Be`-Z#ehbc4d#hoI_hQ2T#>BF)g`fnwK9s3!{L^;iuPF3 z-cv5P$Dx#y3ApNfXbCoTO((2sj3_dPE22maKuPbv5^j>pg(>d4zFa?0_UhnKVT~_f zT;WAo^nGkB8syfR!3xSkm3SKkCI{1W;Ltkt8}bwIXY|Jm!U-O|5HWxy@=14mtL|iN zb|l86fa?T;vlosZ`2M>LuoWtNPiHvzQNsn5Pg`>(+WXVhXLakDcV9P1itl=7oLA1# zmNwF|6`7UK9rsF@({kM@zYKqEQ>f!j3<0 z{mRzlwh_p~LFxNNOP5>WpK}#4bQ>l1@C}Wd%>TXayB(rAGkOA&@z5)BQ|dq0QaEI? zF+00?fKpN)G1o{hdU{xzf+m{EzN4mDem+7Qd-G3YHtd`yMC_uZ;jj^!4LOS00ar3pmC-AW{gTv`i`Xza>~xT0tpGg1Whi=3JRsiIJ{$s2>z1M0-*)lxc@S zh~w-J$cjZuSHj{=ev-w%`%n_Zt5OFXCa;*cl%b~sB%%Rig9G9U{|&rq{QL9%^#5Wm zc?wfza4Zs7An=iEmEtN?E2!z;5l)Zq>{X{FL2cP3ujAzssRX@0YNpeWK!#oI-C7R^ z6i}3|gvy!?S0MrixT?P`2JFQ~+WrMg=#Y+y#qU57t!?3E#QfSL8i}<@4Yn4nZQ2vA ziFH}`wpJqiIx~q6b&ENtUKi|&?Lned88HE**sN>9_&bj2 z;w(K4a3!)vS$mq295xT}KRCu{o~0d-Bq!*pU(pl5|Db|}nnysx{lvP)(S8;8`BsFomHyHJv2r9GS#L zR;YhvBS=?)FxTLGUuOxfv8B+BL1t}kmGm6`GUJ9H7s`6 z$n%~xK9-|YEpY#e0)NiO;Ha!3VtIdBo336M&_1+p#F)IF+d-pQ=Yp#(Ctv$ z({^S~y|yx3h*XouXlsPC7xyxgrr9roaew)M*& zk1cDA7lAQ^8ylG%-+Lp!{J;y~T-)?PMvMW*p$AYPpz(g|Md`fqes`Bqm1F~@zP zErU3{OYbl)NN&oz^ECU-#z83QFtVrp-5stzfYa!)iU z%g*CK-t5yCa#?%+lv#?AcyiOQblN(qi8L;!o%NDB>ZvS2e-JTUJ7V+~UIW~*QqXZ6) zc4I!`(&opCP_^vF39~)#{uC#nEr^rXK&6aRkbKpJsak{qC6#o-WyPuR_hqGZt!VURwL3Cpm5m3#ORJjxwU)htSA=IZ-Bh2;YhNcK zPV3r5Wy|Y_nLbz4%~rrX;EvK1fOwE_M=*(@mt+G|^ zPlIKb9iy)&ZQt)8Td_>gyY$0uQS9`q9%Q^_mR>Ze@vB};RmgS!Tg~+Af%m5W5hyt^ z-1JfC>fH=ddkfT#FwomxS{G$5+TKoZN6&=PIo_Y$P6?wh-c5_++1<@ZQ&-&0 z%5k6H&3)vCO?QJ;%UOE0xFJ`II*RF>!+N^miKqz|sw_T7xWwUUM>;=#MPxegr{ba++ zmcw*!68FQraC`UToT67)D!VSK^|WY6q4lhA%HHF=xoq?IMb)iB+eHTood2u|L8$$5 z;9XYR>*GZKxtZdA({VMaD)jeyQTBBsVO?s=YpZueE7^yod_H13OTv^@xD0KLER0n25B@P@mQ`Cg^wYC6Et;N*mrNbkG0 z?SBkBO&C!X{ueK>jT36o_ShKn_pkJoh!!iUk};Ymy8jlUw3wXvFYLaM?Eeuc{YPrf z6N3oe1|sIJ_QoBtfLI-k6!ntd=7A+>xn_*j)5&m~j>MV1D~HR>n_v$;4KQlNMi{l5 z;8%r6a<)1~>dTqpZXHRmxneQ1L}+6?9+j{blLd?aA5wFHRbV0V5T#B{teROK0rAR! zOd?iX{CGamY4RsodzFX`=RIml>raZaSn&ne`?Q}*Wbk^+zj*GM;#wJpi~o<*ynwRX zlRSCvJuB~!G^T3uFoOkKQi`N0TV2GYzyWIt{)8o+YU*OW3FnkF5~&_(^v|$;lDaD? zle?S$mYOTTkh1{?W$3siP|5F;b(#11R0gTda7CI6_RxoX9pQHmQy?4;W)-4h4CF8+ zAC1~<^Z{z2-ET@Ebn!X3UNjPvCyHS<963ak#ZpPjiX9y)K|AHY7}iE+6I<^JSRzYw zz((Rg#Gk3Fdiz8PR*IT}Z}WbO7b<3G&9cjUP2IqzrH*Ws^q0ZTCY2}_PB`kNy_hQ* zKC@6$Cm3QhaVdS2Tjn<9>5KmtnGRwpl3N;GY;3)+@QmAGxGW-tT2FECnuhsUo7GB<`Kc~Y>orHTXNb8(XGc1VTk z16bRs%LA+=3_qm?G9;>%A{MOTvy5r0!z+e?K&JV^li)bOomQsU>SS zBlC2V0-UhPAt?SVUN-Dlke#?pLOJ#~|m)PSo(h9I`9ej;_SQ-^53Z z=zwt=|I8trJgbnoGy=ekr@cuHtA^ zAlJF+wdtS}JoXFIKLIlzZ0#wdKeHKoN*fLF}lDR zPhP@VGlGl(s#Q$aH%c{JL*;x}#?j3DEkeYG|CoRMAX8&ny?EbDOiAl;O}0(9G|+{J z4WQioW+bDw5?TO0SD;Q2CnN&Fah8$F(%YVeHcXz%>%l=R!sCa6FV9n_99gt@s|T%m zrmF6>K|I3Bc>E0H6QWjq)XCv!Q=PmMAbc^}M3F6D^IvsoG1#QZH4*Z~%VU>VLpkS4 zVXS#>bBJgR1-tmWQktVR+dTCUq?kZ4J%mm#j6PB|h><8!?@U2)d>Xepo~Xe4x;uz1 zEmc837uaVZeY1wRk}<&G9T}to8eBIQk!0?(TbrPeT&OF8+D?RzQ>}nc%2r{0%Cx&C zN75*)gf;Wn{=7Q0d1n-hVdQ}>Zh?@~U(ea_MKFRCVp?1ec&e5XdTTo6Gub@IJ$e0s zsn+igqN#zpz9C`x4v{Au>f_Pli0Qce3%ac|#LG4TactLI9{V^njx-(gxVk<7`o=tF zd9kk?sR=mTZt}MK5hWLIa)d0E>6HC#ZTl5O(_;kaCFkvPaHH_(*sfY=5ffcN zrBiJ$DpDqZ5gMuh#Lpz$t}>Zo(Q=tQv&fHRlI0_ob$8# zh@1_t@B@BCxxxg|C-7T&l+sz=o&LULnBrV;(%%{n&%4QvQCsL@^7$IjgGr+i%ul7z z{iu=omb0E`kbm;!KLVvs>^slWt`!QX4t_sc4Ssbv%RJMJb@N*q8*Wa=9ias>} zdOt#wqQ4Wwk@3QRMl$(`QEVWOR}W(M!Zr{3R!UH!Y^SS~bwEQ9R#gANpLLfv0ot7- zhd$Z`SKbP^$m4jP@ubP2Hu0X&T+6VFsE;_7Ds211{Y|2djZAGulGeQ53K3 zCA9HsJHlj^RVnb1uq`OtRoxt628O8#aKbzC3*$1J5jK~`a}jBxoiN9sr3R!a(VoBp z>hO@`S)8!(kY$Ghl51&mMbTTTJ-RgmHNFLEN#mk8APf$uDcqCf-C!PUV;*grXjU5) z$DjrydpQLCn72ULzOteXG6GFw(sCj5<2tKZAT&ETT;+1- zS)K3u?!eVeapED0gNWEqrXZ0}TW(|;3xqCYd%i`h1U9F;0_sa&kQY!OGt!xF*E(tfQmG=a>hVj45v$SP&g{T&T7ga$GG8^*nQaJ&yb zt?SoHsqi>5sHcy~m=9XxQv`dkhkP-uB7PKZQsACe)WNdHD`F&Bt*%B64VDDcxO$6H zV{*D7g=iU4;F%ge8gNR%5~y4kp~#Wcv|Sp`s!m`(8t9kGgoHn=XPg~NG7N#j zrM9|7-NIqNa6?i){?0Y+ zgy@%qEDcViiFgb_gyOOr9hrhd(Ts5|*oO6AtJTKSz9Fo>G+fBXC}L*|e#YH+_XVNB zi=jfeNfgh{78VFW<|qNxcB#^KNO7j~iD8~bsfg~r3B9r7R=yQ0winG-BHR`tMJ5#v zb}rz^E(=5iX}6%D;7i|7_F=uz1NJINq%UYx`c$%9QDOV2!K%?VA2Bn&u zSBK4LM(%W@s4pgugr=A*`i=8=V-Ll#xLF-M`0xcu&?PyWLL(N{A%{tjL`#$ao-Y|k zVI~jGV?HTZlBhcmFfe1rN}2L|KIXb0VzgnURBoVu>Vq2pH(8Tfvc-!j^@f<+cR zmm1xfTfCu`h)64OG{X_()iI_%A@N4OaekO48juT?$Z;gJdKv(Iv)w)_>6@WKrRBoZ z8?^5Sna(;zuC1~zKu0@1-MWIJj|aY_bRnpDPK;8CAD_N2E~ljPIN!lFf-ijB;4K+l zgD9R?Bo&{8QBkAMvoXVi{KSV0QebY5G_L$AP5baY^MOyc z#i8iWYSlkJaS~y>H%ZjD$D*1nx@m0HGz0-)bp68?+6*!%O-kmbvz;+O3<2Gd3r71s z%{n2D<;flCSiQ#m#2kh~y17Tf(I|c?Li_fmMqM(FMmI8qm-Yl+K>fxo=_VjVP`Xs< zo64gNOU6hDf+{V5PNT@hTOq)~m=-FzmhJUBDgUI-($zu|ojoPdI*r9CQ>E(R#DUh0 zo%YdTtJp*Bsmdy?(dM(T1idlR=Q=_{mQdf|g8LepPr{1Q)d=C7|WV7 z9!*;cgIuK@-|Fh-pi4cvAw}Xjmp(;$Iak@96mlX2CXf|bwl#JWw)YZp0MpuPk@OMY zR>k)gfpwb{II`{r+Y#%b26btb^1E?89vbF`!A&9HFoTV6Rw zs?O-N&Tse9SH8(9IIU{prC`-ggJxPY-s)=pzBBdC#IZQp`cBVZ^5t#qqZUeuvYeEf ztdC3b={MZq^?+5>qT7_Vgj_T{ydINRff54%_>v;n-n1m!!;kD3=htjI?!YhkY5KII zoxjGrq{bz@ZrY_fLd#Hf+>r9HPeZj&%|$KXEL9bL*Dn{}nNiRo(ym-AUaB=8p`!M+ zzOacovHAvkKtcTz!kqliT$q=sr9niM{&;|(6}u^{$o$V}HBq~}j4%;>e}RN9etXAs zS{vxvp>EuWHljIzzeC8Peqn5E`m|;wt*CC?;@eDA<-SgeUUN9T#9Dsm(^v;~a8t&L zdyaU2FZOWn{LnMHktC$mf`T3HWbEBHP!cg-(oXyPcUz6#)I)os$u^L1t>&g-q<6gN zX{FaoX3TA@Xq%|Zi?1o8qytsIY5Y{2K0>?ByrgU+FX|T*ghv<7ZuI{y1=qLed!7e z*Jo3$$2lGI9x+OUjDwpxQJoyXLxWPfHE}p|j32dECHf4DZSN?uln-XMiKK}1VWW!@ zpFCenuV&Hn5wmJDivq?N5{mQnreIAmZNkPkLj&zEg`I12KE%u2mf{}(lUjB4Asw^t z=rvMJIv|U)7d0%37!qNBmq*&>)!OQf>u1?)6E5JU>ndl{sv z_e%*#0wqiYJ-eh5sAI|Ic;*V*(?*S7GPGX;jO3>LKCbuwH70Wv%#N&={xdtX*1jNM zRT4jukWX8<78Nf(!a2Tfi{TjGI*JMpuQd^0x)YZ(-_RB~m{?$t{3uF!9!<-Nuv0Qex!B7-OsQVifLKP9xH& zkh$Rl1$&Uy(rFsrqP$$1xnaDxCh6g3B4G<0QF4Ppifvrt{bUWde|M(IR+(q!nk0u~#{Kd$`XiZo zcmeGz84(-K7_El(a+w?Ml0*l`<%^`j>YL7Mk9fkHUR4f!ySA-%gVS4lKMucDDyWb{ zf&5Ss2Ly=GAP8_|;R*ElaRh<;9D!nvyf%+Ou}7iygWO7b-jj!V%ZGtK5TYuNgD!ya z7l%ocfqqQK;jhHi=26n*VWQxPH|BAw;87*XX|TeHpZ!U)!7=dji7(S>ZPZDn!bwHt zX<6s7ui!~l<>@dQaba|P%z`09!Y`fPuR z^yV$9;^hb66~dbr-^dT;f0FAMr>O#7kAl7bmRll6*T z-7rkaBC=eeT-^ZSP{8%Sn+y9}9`DQFOqT*em%N6z?92cW=DUwVmjXZT5Pa`A;5VY) zx3chCuBpp6(YG8zw;DpXN>g`2UoN$yZ$U!$yzo0E#aq2M54v0Te=aWB;I}4k?h$;E z&0+{XV4;JI(O(1cmTGjmtQ*g*N3X3LpAS!s^Y@mQ_i|fzH~$=gSB^T~4itJ=>T<&H_xy+F z&yFush7VuhA0DHXUba8{W4XT^hCeS<{TCR@cLjS+%D<*hk4C!vjgZ*ZQ7aW;H z@7ooj4cJu_|MUN%uk?TSt<6;!4rS`UxL!DZS;x}SRCl}CpU4_g*b4%Xf$Zxoy{mgg zot6GpiPv1!KdYVqiKJC@RwTJq~ngPl`S; z^O=$u^kaaM4;n^IwJ?y1BNm3M{z_k=ncF%J5ZINoN)j2jD@%RwKx7+&xntK#lSSua zjS&Ad`}&F6yWCMyg74W3+uz8MMV7H?ueMAk=3RE2Os|~PxI!U=lHA_(nfL_z6l6}0 zVo`Q2#JfNFcTvYU@FO>_ z^P0<}zU|n#4Da{L0dB)7TP&ZgAEwt$hQ@y}c=G&^4!Dhduq2<1yjb5K7>809YB8Ji z$>aYDWWS&>)#b9#@(Gv1Y%=+&D9LNyDNU6KizcmIG6*)nO)*dSGRSM0Q38_0%kriQ zG5Z;W_4_c(SA@?x-_4@cx+u$H*edVSzbE)^u-||VSuS(pd#mCuWd5`Cwng(jZ(>1d zeZ(4Uj?aOmQRbgbMiwdY+Ab$0Y&#wg_*W_?DpN@t4SfTztT7Z>mV=)5S5N(|F8IHW zP;aT&bmM6hJJ?|9-K$L&sC$wQhE4>Ujw(uhbU`ZWd^#KFjDAqlupHvloZd1>w$gQd zgP*AN7Ef4zA(*=JY5Pa#x^X{J12O@yk@ScFn7@UL0}Qiv)>;4ffJe03g(Bp+>4~go z6i}~OkZ^?ho|@Pd5kDAa0~S5N)=7`#a=x8Vl=OtdQL-&hxY*{9-gw8>4&LQc`+RZm zCq9M>^TBwco|OIHXNO>myxn8Gy_SVr01=JB62nQrx1Zh6pNUHIsYQU@2!3y0MLnoD z7&f*h1exSSVuC!PBoEWU8nkJsZ@8NEK1Ta8ni)gLoBQ#i{DZQKk@I;T#ppCh2U--`V$s?!(TQrgB!TWwspk{eai2L` zg0{drDr&8&T**Ir!%{|Jj&ZDTA{5S;nOFbusDaka9@_x#WGAOnlCFRReY^4}8f!M%JYuN#)}>zNQ$SX(hy2<>kvJ08GK#J2FU}bT>ADHlC%AvUIlO7=MVpd?rl!Nk-`sY@^X2Q<_6}m{R00 z&%TPHSfoRSDZ5_`(Cfy?kK^=5!J4O;Z&GhvOi;xCo2~bzHcGvd{U?WuBp(A!lXb!oIA{;Gy@RwPw7sis!d7!5|mu zwTF>zT3G5rZW8R-_KOeFddef(QnJ~;J>nX-#zALHo&|)_Pc3H&sJYym=ze+G2rjd6 z_U~B|r%^)>m%-loB9PtT5T@Rq6yEsR|J|gW$eZ`GX>8YoYg$42rKKP5pPdJUkiTkZ zy=R{2Nrvq~Kl?GlPiLq|`eFQ08C=&l{5GAxm3R zZjf{9UXqi6yXua}xcW9>b&2$_*7_69hYX2cZCL&M%J=$@0_aBSbcC_rOgKb2wQblX z`Jx$R?0(yN8N8PAU@^m~KWMt#xers->mz!9_-&H;%+VET$zgHP*+yq3)EDAY zb~qE`wZ=XsXgHwvO6sT(nVo1BeP68Ubg6L5I5m9yzT6||T9cGv~ zB^VP3T>NY}^?k1dHIRajG_+k-^ljFW_!!DX}Bre+~=EVob0*9oV9i79wVBRSyzxs<;^!1Thb@#(0n19^0qi z)JD*5!B6gbT=2Sr9DBKw(zKD+anBO6)DzvWZW@|83Tr<8_3XM?L7@#AsQbgZaXvW# zVtM`OU!QS{Bc($^!L)u`_Gz?_rubMe|KG7fA_1r|6B^e;g4N_vo2sn z+CF>tiV*>WN2f%%pnO{+uT#86cAz><5N#e(%FmY4Si(!$?nLVh1jL>&G_ul9?G`_A zSKWn=Ki8w~k)8R{&!Y=on-XO85VoWC5Q@_p4+kQqcNC@JuIAuK<`JXjA>lCunfZuZ zn5O7KgQ%Q)scl7x;zhk|dNI#LTEmGA3AshWadl{V|9$Fh{v=F8(MOZs%dS>Pg@{bg z&;w`SCqnfQlkni9G$Syg5u*|B6X>U;*6TB7K{izi5{C4f!TLq>1I>8)#qWAeu6iYG z#l-`}DH!_Ap#3uC;y@*2x%obMq9SUEYmf=>$<}Hox-W zi1gy1`QfPi;_$oS7z*kb?2$M@Z0H!O$_Ia-UkWiQJE6jdrU|w!bPfPPr=e zTfd&}bd)uH+3fNJUJ{>iR~z^Gp-*`k1w_2(^ce<#5L3Qp37Rn}ZjQIq9ZqG7g_Fp) z)*rvFE*Z%DrD^b40O^!joWE~8TdKDls>~pKwBKm5yZv|0|Lx1K?qEXdsP^WY!;w7x zq|Nr<*Qet(%v+dVt!}3)eNOPA$`1ag>#eb$cwY>>zCWDKWPN!9@9=!Q-JR<){J^CR zcmwDL_<-K>82O;!hGhFfn2xgjpszbj{#YtJzx?quLUIC$?2mGSU=}nc!K86KJHe=e z+rC&f&{=JmFVWj!o1|&*t_}NUv1ydR&e3j^&;xicMiiG|FIJq)I$t=!naqbw0d0Ek zr?LVnJ>a|9YZoNobl;L=QdYJj; z;rJlSd6Tv{^9QmFP4>5&(4*|I_p4U9fugNPIZ=|M#Rc&)I>-6Z2BWlv3Yc0j1cW#` zqmtsx($bRh!qt;kb1NL}w7hDOuB@Vdv-ERi`_9Q}W!D4RS#>YlHjuzdjmk7KisxpS zJcZ-!IeCT|$gW{YN4BCN#b~XfaWm*Y5?4Xpi>8CPGW*t*#x}dQqt0-9>S%zA49&yN z*lfr1Lt9lR{q;*#7Z8CVrW@&BoPq5p)w#uV43lP$jw< zc%LM2Ge}YdsU0P&dtFJVYKyoTHJ~MVTiG5CCkVB zapT)z#p9;uBmDev%Lm0i0f>rk1OQ-wtpEt&+>=kcQBs)CdvTfy&-;m%uM*c(x5?+j z%wWvlN4ZG~zxVRr&qxv)q3kfMX7w|@oYgPcznnK8R=!-cKML~qRds{ZuKLiY-d+z8 zcD=nBqi2TRPVqAX?&f6wYk$!2&%=n*R{P_OzhTGI^3N)-$0P5oA5W*zTR)yJv#S36 zIh(ue{Cl;_?EUx8)|U4__*xbm87vG!tM&m4WP>KCJ3-i$z;KW3Uuc#9@Y_m1K(^5i zNwNsUrrIBeV;xz7rWZ4cC4fYZ6iw=z=qpkXz{EicksTJnm{kg7Ehj})UG61(hzVv# z%*B8QHuvFS&V)#u8G#}S_!jSfxtOPI(224R(5X1${NLN?%L7X3q7MJ(Hu|_O5KUMV zl??`j2EcZ2@OuTwm;%0?nSOu|5B1~3#o!C%lcBUo3vscOdjGWWJ!3nybfOf&o+7;jT3|3tFu`I6{HeFxPAcZ(3U~HQTE$mpoUGf zi1yaZ1zsRp5^wP;x>wF+ZsZ?+lzrV{5_$L;4Y#%A`v=?#F!ol3a<5=IDRb2t-B>kf=jM?G~N= zHs=q7X{}Vz4Pw%TFl@NHR_4$#8;XyxOO^do=ku62OQb1JR0~$s3V+O%s5e+^B%m#n zm^5S*+2#`KEsX}tI44?lSiLTz$u_n&R5*B*>FvrawX8N&+NcLI8jUV>{=TpB!C+87 zI8w03eMm|HvevE&}QK z&kj>$rE}3I0FZ~JLEQY@+LUmr7&pEScy4RaH8xqEs999KQ4SkunY%A+YExHdHhI&k z_Pklwkrm0{zD2mWfVC4E>0pkdNGGcvFy9T6aA3#L+eYB$>3L(|5I_j|h4#8Ag;coj z%su{JH3FSjYm?KpDJ&=4x+o;ZkMe07y()bdAxq;2Tx|sK{uQ(9P<0~RcX^s!fjD+QD93g@S5qcwTrWfZ>RJ9K(Jo>sv_%*X z-xJ?zX;>@wi6n$s_i;41t-ukQQzz_Q#HEM)G2?#3EAflwA zsB}x0Fmj`N8$DojjqYZ2iF9{&4G@t|1*8qwv+wu5pF5s&o_}CJ?Cf(sJMY(Zy)G-h zGJZ||*txm;58cvqvaE@#m**?x>?-QVY*%}h7it^oL%xq4n*9BP<#}2GH3JP%DEui= zkbRC}h?XCF;N9wfhS#D8S?j5_``3Z4?$%(TsJf8wC z-k&TH1z$Iwz^=`I=r{?yjzTUe>KKOGUbz@;uDio4Lz^DkE`e7)n7kL zv9<5<+(?h^e%$}f|9ZNe%ELX@XDL!p>W7~H-~MuwOL(GhyH3jS2jc5{l}K)S)o5Kq z@y_mv*p8kY_4Pe@wjUG6l9z0L6o;dRf0)|e-~uaid_z-kqcbUg`L|bf^^b3EPGUP( zU#Q7T_%p|*4qA|eQVG#S6Vnk#y0x)F%M~^@Z>`E5qerFL0(Dx)m z*i-CzGa+1Y@-{T7?)+EC@J9a)Yj2KJq@oz|WWe!XijC*FKc+Eok~4r3fly>XQlxqd ziMs-89GUcOUNs@K^?WMPKIIyq=@by9Jmm-)q}JrDwuh=ggKA#}e;o1yGX!fQg1^aA zek=h2cY=+%Lo~yD4H-iWOHkiZK)MQ)7AYY{aJxEf_^Dnf3=!&3Fb9*WZ5LmkQo&yvAL)j!<0O0cMWs_asu?^i_h5qGq?xb>!Z%(r6DK`QE_ z0eH5_d3@Jrdnih|BuZ!B=VwVs^Cj#E9&2fkY;B;5FH2@RyZJP!Jq!02+jGCw50mK% z5OWUe3Zu;I0?2fcdq_km>js_-0K|}#uTGF~iAZ*vpc_aSi9{;buss#hlN1vvx*sVV z7WQ)A8zmM%hc6bOJky2~5|~o!F5t)aJDCIqr0Z)iYxYbfgO!*W_w(KOQ#OX5yyCV z7u!T|4#&Z5+!C4){JViW5`nbmVZq$U9Q`<{P#bbDHyYwxsipYx;h?+A-ZlE^PZg0g zVU83M@%c9Ke8ZON8Xk29qLnpKV|!89-Qa#ttBtUz(Lp1%w4}vU&`h{2wHRzwpH7#i_#`vVM6BF!8PG+zTY0myxpic%YjV3Og9$w0r6;_#sywmp9#iJ+gu>BKn2 z-1ySe^~+Fp$v{$xK=$8xj~^H&GDN(z$*C~NcOws{F3Yh&QhxFxV(21o63V_FE=lr2 z@NMKHX%ns7Q1|)^rFld8Z8BRa{4^w$*ANBj3Vuyq1v;gPifO3BR8)UyOdZhLyqMBJ zvU1L_QX_y8zYUeShJP+nzLrsVg(Jjr%L;PK0$cnu*C?x|Kvm$9(gVt}+%g$<^uttu zc^7DUs%n}x=kGo+A*~8MRaN3e)Zq*oUZa>sRt7H@Jr+;T63@0$3Z$a-;VKEI(N17s z4*GY6Wc(d)*_`lr#Gh0luy{|OP_g#URlvOiWCR>pHx#%TE`PQ}(J@ujghNs~I_E`( zy8{rpDsn#0mdQUT$}Y)=sCou}QwWjfh0TOVYbazYMTY2ITNy%amHyTlrv|HYXYNCt zAuzdx2My-08l*obgV=%P2LuerVsvhU-C9ba7ZKlMV3kk~#+LZu8UZ@D2EyC;Ft;*C z?DHls&~vmwWry;%CC4tefqV%NywvbesLF=68T!XF=eJjCzguj2V0w$!_(C&}u6Hh} zSLmX>8_+xRsi#MJ{2{$zH$IZc;FV_AQvEkAq2IFXfWpIDDTmK3rBUXn`SC5C=r>`j zA-HTUN>_i&_6rKt$5S{;8f)43ag0=Ne$=Rc+xA9Ap!g+`=Bt)Z}x<7ogpgHBX$?8p9YCO);irzYtk1`JbGGSZ*b24gdmyPwP1 z@5rT2(Nak$XRlo5b%e?D)oSSND(Q&Awf9lgYl(AT{nj#ULG+l45Nn(Ike0M8 z5LhLwL)*9?(u{Fr&!%>@`EMbN82 zUkt`RT7gC;lr?F9sQ*dFE`+NwWaI$BgmShLpt-IrNz~w7*&L z7{3_Bx4q$9*vUR13eCJO9-CxbfEsF^+w}+HtQks~XgyPd0NZKEs){ z7%^^V%{LaQn_3dl>JU*}Tvm48obyYfO02!1DHqLv26Bx|!9fFK?1S4;4dy4+@jgU@ zYZOaLP4|2VUV&ZDA{<|#y`&)!M3KeXPAf~OA-#PoT^}Hmof^9~KkeKT#<_6TZ}Ps# zMkS;yJ|)b|!IX$jw}C{|^+w~4EVvwJ?fjYF3^tCnFZK<*sXyQf{j}@U{oARnZSjQl z`-}(RRSgE>)$0~jCeTh~%LnYpt+ZLAAOj7oN>c1+%;2(s9tI02o&kdFBIt-4o;d>cwe1H>-T9_|j-o9!M|6@4xxqoCdC`NQdAPCG5z)l=4O%_HOMLAOG}Rx!uz z1cZ_pva#;M^Q|3mOikH6Wus3MmTkU>lC8$1LCbiCX1TQ;Di*T4nT<42VW6?u1kcS4 z3{YA#X3%IvH}2uG z2mUYt3vS20`B6_nk9iOs-1K_8V)fve2jEM}FsNxTGJAI~WX!KEg-f0{0XkHaxGOd2 zrkuFho(&+aXdsG`ulL@>pZz!*&Bcmr2*N2XjDOC(8Q_w1zxbi^_R9TphU>Jh<%>6v zVS0B?*ap97xE%T$&A8J&+3D95W*<7hIWb!&CAJs0_1~lW$gQWpyo{}SctZGA^}(P` z8b*hAB{s7QB=!|#2i}ie*!3K65S{P3ZRwd%-9M{`5Xq*lt2h*R>en`|U*@gf$ek=JQ!Wg{r(=@=U(G1HGZWt}f#g@}@U2%T3OVQY zg`u%(M~PKCXNo!4mEDXT*F}-T83Bku^+jOF{O9_|dn}g-zKhFXon0O6)=I74_NKas$fgyb{Z<}0plO5ozImzucKmJ&Id2L zqxG%Fb9XPyS&Fq3tbcpHG*EqZWq_q6;D`KW$<*_GAnb zNw5wzy|e-!ok^Tm|AGrm&Vz17=sEl4s&vb!59(+syQZ#3I{(2x_)`-fk^^pP-rRhZ zxtVqX%uG5gbl!Z$#Trbp-OTv|zM0-EvE9u3-)`sJuCm>(I^7=894?yP{Gz!%Ru?~b zcDqx3yOo1G`i=v*tVst3kdr-RNfinR2qdH8ypPZ@{}2pfGl@!F3q*=S2_+8h+a~cE zR)f2R=|@vPgL|W>+?ZYzJvV=8(^AKCwmp$1;H-o_>nN{{`mh&T=g7{2t9tT_DAYTn{>cP&q-MDZSQXH<0C5RrfReP&@;8l(d*9^ z!^FHsF_{P#i+0$RiEQuuLXBy&J2@>UsQzHC%eXW9K(b*DtBGqI8TjT&cxC9a?TxF5_{nif+seX$xcknnDJ@VnK#Y~!s{zfZ>jtbMiGm4Wi@ zYp;vb?{-$5x3^zs7jOQj#I;76h(<=}-PO6pkJ{e3S*P0bfk^(U!Ta|$s6b*{H6Li+ z5ToO$7AIcBH6=kly@V`{lZAC!>7!w(!53QuBX zgcYBrSk@|XNmXnq@)Q@=D)CkK36D}mt{kM8)!`+s&j&fasJxhzd7&zTwfv$g_8s*? zO=7q3i`uK>z8C6JS6g4y-{Od0YP|bzjDSY=CGMjvgH;_qtPuQCQ;`c(r>Xp`|D~3y z*mj-Pe7 z$gNn(@g8O&Hqt`3;&&w^tP=F(@ZkZYkl$8mpNb@Q(jg5JkW6?-GbGD*Cv6L{>M0K} zwD;6E$E3WmW47geNNN#XY`u%ih{(xH<&O(~*lbsgj}h2^9^`Db|1v4}3V-S~Y27Qe zH;jQ7WAScSj%p89W7rL zKW-P>^~q_!p+|1O+J#qKX8#i-nD2&VoQ#@6mRH<`2L|0HoOW5VeHZtEiMDdbW#|8i z5g;}@VSj%Xnn7;Ay1X2e`qSaw2@ru5vCtzd1nIj!ML+om7H9Q3c8JSDC*Bik^6HjI!Z4$SQ5^ zH<@viVBjzM7OTwnI6zfo4w0<*`*~SM_dgk6irC;NM=~&*;2anLm#5PK9P^$&F{Abf zYsjw;ln<{#qI$Y5* zR1EDBq1BfE=`%u>-avSDu}7N+Ccmj@rZ$tQ_h@;iOHzqa!p8=)ifD0B^WF ztl|T}-}pNvi3U}-&C|q2mUTL28zqyO2;cb(iu?LJNTu2*$(yuTUD|ME>vRXcCwxnb zUe~=Qx(PZTapwc#9BHl5ANze7?;)RKxsZgsU($AEjCEIBglqR*V-`@5k|XgX2S@7E z6>z^cl4-*0$iY~f=ZWr=ghu^R0PkJKps9SG@sH-uvuWt)M3-D-R(`(7^du@4$H=Rd z3H?eSCMkVUN;uvd9vyd#f+~sVbopIIrxvA-i1R-JI6}3NNB594QZ`BG%lr0}^+en& zc~kMVRe7!2Hkz;MsT`K8vVZ7rYwOx*twcYuGcYJpe`hNWYtRC)e<;)Jw=LBLPX>D> zt`0OkPpUUb^vyWWlV>Q=X%S2;gjto)uuAH7$l2ci$RZCaAB=Iyt;TrUnW=p#ZZES; zsv5I|;Pfi5bu=&MYta<_+D&Bb7dn$)?pHz?>G%N6qL-hGlYT61gw2dL=xV(3U1gw& zr0IdZj1aZlwDI^VT3)kI-}y6v_ZD9%pP&yns|W!Iw`ye{Ei@;LubKqB`t;5!nRg(| z1X!#Yt$~RDtnKo{&Ert*Ao;5P>pT~G0V&PZQ#jo>-y+1eopyW3eB0Hw7I*SHYQM58 zm>GvWSCKHqiduirdRDdWaHJ{l(584bwZvaczsqXxC7;HaL!e08G7!$Fj@iyfE#0C1 z%)S_{HCI+)eooaXCdzg$CA<@;t0u?&^58<{#1c5(tTagMoURDrDPrdCu>RJ9N} zro6}gjz|9e)vZj`b%CmWz@VJ;?_7SF5aW_o0o!Rnl~cg2yy(WTJ&vNhi?!Dm>8%nyhKRn2Y;@X8j zSSLNvUnJaoG7|he_nmXq2cicf8UrcGZ(zornpG;s7IWRKk>#61jN{T*uZp@atWlqS zSPs6b>1u~H#I_!YdA*u0`s@+J_k__?-lt|}=(2-m_~}T=tF30g>ps0zy$$Pl;gf&V z7W%7aZKvW1xzD4$SBM^rU;7+d`7{@#fsqI{^*RI}b2c8||wtm(4_hK5)so4;9jdo=ll#cDSpVa;IJ&&AsEx?$lR(WCEOL6mH2ZB4&6hr$nm z971TM@&p^XGxaB=`@wYa+sT-3Etdz_MsM8l!-xOiM;oIBV(Pd5uFsF=J0Uck?Kgj} z_YX}c{r&uZ0|vO(eEaYR!j%{wp{UfLW+8ZH{3!T=A2d%B zq(Hw!O5?*0h~TYlGLLxHKvod>aspZqB|cDM5iN1rv>A=Z#f7ml)Ha1^1z@RVoT6~^ zRvcf3{>Zn z@1LliPs?$AJD*W|F<$otB&2aPuMerbSTKhFydc|s{JAO_=V%kU1hw#NSh6h`zg%|c z^o6b1HmY8&I9Cfae)ZVJ{S-@%B@w({LoqmBuZM9}U2jB*ndlMf_@7*CCF(i;-cHJS zCAyTj=XVGHntP@=a3C|E7k?LtAQlcR>GIh0W{#F0NSWr;wR7` zehoAGYt1a6d}BA2X1+tA(N|L0l9oH!0w^wGGjbhn$$QHL!O!fOAGz)}Jy<>o5g*I@ zZ|hvr5kSI-1mNh&D(@&9g~_QrzME3g$0__PTrKMH{bFuBF8&pvJBDwam-Gv|{)#lI zdwln0X!q>6BaCZ~86=_KLtQi-ZKqwpY$`q|9TGc@?-&#zeIe_H1}sX(DM zqA-=h#|*`s(1?P+q;7)B62JZf^f4G8&R`8YaE!TjOp)Ls=%;S|p?>j!6PBktBO z^M+MymA<6Uj&X`MdX769o@FebTZ?xOt3s8?$+Z=*Ns^%h5-o0tM^VMEcNNvA3G$OW z#){wkck}bl+4HW~99;j$=BE_7Qf;$p(s3r&Yc9jVh@R;z6q@Au?eKJr*LeZ^Pb+CU zrJ4Bj^FnUb(#M0>!@~J$L4}c}q#r$%3~F7Yg`=PH8#T}B=P_n(45}HQm-qUUx?S^)7%|Bc9_7NSe4&e%+Ps|$8|D$#8 z%sQm-(H2$ems_=UA0jb0jBWp;Q$15rE`&?hGjGYeGxquiX)3$EwI7%&0?Pk58jQm1 zTo75*t?fXu6KUCW6-EN(GPAtupUYxstFC2@^+uN$T3{(|m@QuD$E8l(n*}=Grt&+f z&U$+8?-QabE45geRxtF~comIcUV1xC1&*M`2o@3n#z;yr_PjWcE?Ihda`NT(BJtVw z!6GbwG~4gwm($kwdb+jfT!x4iTW|BIe%IH^$rdPRMO6A-jefrs6>NyNB;<(bHdcDD zPTTg0NN^cB^r5ah6{~8Ax+AeZ?3#a1RKGOjX`2}Zobd}=Rn46U0`ig>b2^esp-=|T zFcBYyJfex3$Lb$J%#7VsG`EgVs=85__;p(CN{+iBZBce7W+0z128tAw<*7i?m|q^X zss;9g=`9TPWf#@Sjbqz_l)$cd`+gCQL6k^S9*w0wkrfshA|l>{>xX;Pq*ed2=42tH zlH>ovyfC#nc)E1Qv4sD5bWMn5-3Ben`U^8c87L;6U#rmcD}ect@e|@6DnyKXF6%F- z`9U*{uSrlk^P>ZEmX-#TpxpDh*Mv{b%_cQ@zofI?A=|r4IAO)yR0d?47wiHwK^8u~TrfBDHk;qRUp3JO}n#X(| zs^TNzrT!eHSpsJo6+d3mAaH_zZ(POb5BTo0I?db(T>atL$a-3NT>r~x6}Hyce$V81 z>Q3Mqij1{$DLTTtvDNKPHN5X_x$Z^L!YDgU^U#NwIi-fcdr~<14=?gvqRrO=$)R1r zsS@vY2R8y~&6|LN5dnMY_$k%#DNjCLO7e7u%?FcDIhmk-(Yj>U4_-PEaljtBTbgFj zzjOjVc*q=W{*s6xjWK{3mJP~!u}D_7_*ezrWwV~ROJ*5)~0S(^3^GyzT* zb$qGB5NpfwDLxyKc)PoE&tV9h_;CQWhfawyW}<)q_?&WYrOSGCjoe;r46 zuoB07YVyy|ROe}{@vFhD zY;(^oJTCsHr!1q~kk1%3-%2Hi4o@jqe-JH1r~VGKl2>IYt_RMFOMdDPq`>#Hntii$D4VDG z2wqv+KMkWa0~3*RduL8jSe&3j!9?XX6ks>kC%N_rxxm_D`**42Orjw$V6aLT`DmBX zx(8L28x;wJ3ajBFt4ooAmoRF>cNm;Xa>Ksiik+hMogp857qPzB6JHN`^4PF&3bL@_ zVx)Pp3vki*D1>4o*QpCaDogJ)Bu}2W=u5{CerMaoK-9kh5!rODPT&k6TqAf0P#o9_ z%0wc8+!8nPc;B}ro3kr8jFM8{voeGdBSh#0CF<0NXNv*hNl^oq#C1~?9{5QEbD~$N ze-*A3CNDQ=Z(=6`qbTd1T=MfPtN12tz zMOV~hh=N0n(aTUMI6>hd8i`_;;JR{en@82c{TCKvNA)f2y2#zdJ$^R%v#pU~yMhm| zJ*(g$qt~9?;^?&|{U<`eJvs6)oH#IWQ6g5{sZzrd*aX7DMI-d#LujY8Ceh#$ldzJA zAa3iQ4Ip_^3VE?G17TkeJqqSx6NM#raV962Guc=T$g~-hreT?;LD7MAg5S5Yy>Mw} zOmUS+X-otVg1zW2&BHjXNf1b`VREXpD0)Tk{ZbS~Q#9s;fVf#7R%{PSMvg$u+^^%7 zp~O8{inOjMi7W6!XDUMSSV?$D%!zB8j=M#!e>iDElXNgvC^&*6N^~c!FA;b6PDP&YBcIgM1ltVc|0AM6d~I&B;SZdXl~%cT-z;i zYqm843vnQ(i+p)c8i`QpT%>3lCeD^H07Hm0u=yH@7>SfP?}h@=DIi#0<(@&*XqYSa zaIjf%s0uottt1p43blm^n(q)mT8yanLam|ElMDV*)`i{*)*t?ajv}ARE=cSQMN|rf zzq3hN!^x9X3MIk-6!{;*4?H4HB*JWMoU(!_FwSHk$%t%8Uo4mPQAn-_S83>!do+}a zRgdB*Bq^RzGTzH{XPe@lS6)+kd5e;`*p!73gAGi>L7|J-ate5d(^?MTXD3be5(2?b z?pj@ElIv6OC{*5r#Q+t`9QHyVp7cgaN4gPmo0lIqalL z^rQ-wYi}nVqaMCc*DINgo%V zSR@%Htw zfs-=%hh35KE35KW$p%ZK22@<03K%jo_{EMnIkZOKe5bTj(&rmIIU7M{9+LShxol<; zHQNL<7xnqmPzlpO?vchhu6dWHM@c1<6Hd8~3LzjPNHZ)-g)8>$fsa6w|BW8pv8%b9 z2U_skvvU#ru`z#HugR0K+2g9=$w}sut{TadfIV){dIKYigKE{3EH<>43uRVjO2E`o z6oflVlEH}$?Pk&SWzvi6B?D04ulbpSe zlFUuLu;vV7udnu^syIlbgTzefxvZr`TttRl9ftol@@X&bl;v#7MLK&CHJpYRdRsP- zWp+`#W?+&egmpo7%^@@kL9}TV;Gn0vO&|?%peSwf-@z}twKclpF(Tnm)3Cx*1XvmY zHf3xT6eTmzLGzKtdlItB_h-JXw=AQ`Gs~iWF+=*~RoVDU!Xh zx0q8Lku6J+ZBaOBLh^V-x7g^#okzX^#aS3OMQOK$ZArIADPkx^4=#~C9(v!xDA8+e zz|;YOe!={g@};&^J0(M>B!-td>d&+--x|P!UK@U?Ya3;5AT=I7eLd-(md6URluE8x zZqhFtBc|~o%gTt_mDMRX9^>(zQji%?Ox_0m;?_yP zjHdKOrCQ1u@25NpAM5d%c~sdz(`cs?tnjE5e)T8Ac12?aw_$t!*(zSynlSmIAn?t%mZ3R0I&d;+8HpET~;1yfSS zxk(N5zMMTg)!4_Fyq22Cp7)FVX2L2j|4LvY3#VhnB5y@6vbx2RS4BISnYDWG z&Cn4bT5fD03jQjqGGb<9&(qptMb#sREDWr#nA9G-FFwV)VmoJRF+(~|XMq3Wk&X@) zur=vn!$LY6gTX9?p__F2?DbSjEW@h8=SbgC)yjTVjXTYS{lutws;IDWLD;6rnt<{O zRi5U;?Af-`cL8M|6-k2E%De5WZ*Dj3lK}WAkUf>y!R(O6Gwz_DcGx17bRZOr;!2FwH%MlMj_;a03cCP} zPQF+WPTm@0>D!?0tuo$KNIdLboMF6GAYCXWr8*X{KAg;&Qp1dXrdG6V8{g`ebLVjC z?@;=6F&o(NEv8cIV%sD~mdp(4JWl)`~H> z>}dSiulj6_@*Aho_EWy-Pc+z!ThnZ}e|`E~xO za1tj$p5sSbYw@k~XMe?n{x+K8E#ZHg{R!Hu|90X2w#NSLqxm=B|8FSgA08Kveg8Ls z`#1IdpBy^?LNuk} z$CIv)TmU>-NRQJu-$_d&lwoZ3)fHF(K)+zy8^|<3t%4YHp@t@YYe9l8DyUR!e zb;le74xj#?`xePGwZDAlf63#XjlU%z;1H^x+q?I(gMfqm?!5XDr15Slz3$lv=PPe@#jD)D8O8Z3dm16moVima0n87lk-r?;VNuwq z{}UGv^0T7QD!AIYd!t0Gmcrd{2K(HE1JGNPxQ{YS?wT5J*pi$l1!-gzR2RuKF>3z{ z7teM4yMM1oB z`Krdx2#+Uy-Z6QoCPEAds-=Xz* z;MK8uc+)#T$Ia1Sr*0xH7Uy2lw{6aS40>(9`q&^Wu7gjCeOyPM4*uudiSy2te0YaF zF(ZAU)g6zE+XvI>N|(?JrVL#di)Jb9c+Gi^6#T2lpfCKpH)%F}-Jk6ZVk1`U&F>92 zJ(*ld-~mUXim75d{=_f!2UUiHhBtvF4=;4%&j{Fl#$L=*lp6HIDW37XDN=|fq+#7L;xrpKq$;lS3S z^-MJo-Pw%q#1L`iVP%2}=ZsyM;@TD-HCV%JRu>1CutS=f*MghcoYC&9i)MAdi1^I8 zFS5cvB{TvXcyexJpzphfl{3gJvq^%XGTxTdaPGN$hOC{pth^s%V0Eus`=AQ46q5#y za|K+orDoKUn#m1`i6GXY4_cC1={r^!!G0cP5ne#r!d&rN-yu~u$vOOlVzIQWttRDT z?R?St93hcXO^oEcnB;t!tN@RCY0G?}@I{#^Rq@AWN!=VTx(bMZ)%yXBY3=tq<(9#G zO5+i_EoB9)yK6!3254hpC7Km3B>eKbhI(}^M687G0K~N5P*_cUrGbBe3d`~t zt;WoZTsn*6gjZ*5T1m)4%JF%H9m;>+&rPW{g&1_wg}eH^1WUV zR_sYbY@bpxOXB2JkNET}J-%&w+fi-0+~kjLT>HJ$^i;f~qKOVq4 z1+$(Z=`v-2x=CHVFHZtImX}HN7Q>1BY9t@?o5i)v_pq5fR(QcOM&-s>@aulpv)7d7 z^t&~5jDF6j?=G?4GVsE!myk%0*D{QoSMA3_E}`((TaVQ~u;j3Oem0C7{dP5wg4xgj z#$o>TvJCFiVwzl&NzhjO@U&6WOV`xqe=%^fzK17tcQ1PxpOwB(= znJ;d#_IGh&WL3YL_4P2;zZ5A`|8$^JoIYO`a#3y-ZEMBRyD-e?QPusI(&TCx+j%=G zgra)#iNU*B=sm19$-&+_){t>B1Xh>x&E8haa2ZQ4S6~0r-p1+c*C1WFrv4iTS9MQ< z-8b;&d4X+mvfOWnAy=Uy>_|^+#_ClAyyI89lkZi=cibhsi{OnjssG^DHAf1v|1TSr z{C|g&xt*u*wn7s2`(YaBo_C;ofYH_!kDNzj-%=%LY#a5VBt7SbHh6JP#6MGdJNgsV{_dlcFGP*k1=nAK#am@5| z-5N~cb9!^r?7lZqpfzansrBL~wl@gJhHG!TI$N5B>rJ+|BhG$&FECaAF7^BO^N2UmmN{ci7&tsx0+xxfMB4-}?|h@#ooQTKJB>%olHCF>z9u)XzA_7LukFpgyL zJSzT0v;o8nN-t+^0hKd|G^o=zV0_-9AR9$Eb!{Fib+Bj=BXYzjhn6MW-;9#!7}|_i zq6puNS62!zj3!*s4F_a#_h0}tnYNo7NdI6j56RiGo9{1tuv>t7jK`u8qP9GRA-WNzg(;enHbptEEu}@- zFp9F${A5YnlEUm3-ZJ}W9D83y-Gc35Wz$aCVO87Z!C`e5kncxLAHCg=3ehny3u}Rf zREsZK@0qva#?|Z`>KB(&1?rb!qdyz5Ud)0`Ut=P-c!=|um0AcZUZGolwD8fk9XBu^ zw_l9#0ou=&GoE$a9E=`!+yX)P)n|sNlWrohike<>ypg;2zVg50exOBL%>ces>oUOZ zgnzrT=>7OL{M4WSbc7?;-gSh#wZe6jzmxy0o0ti|04;i+`8eVYDb@MZTLyu;X_^04 zX`lQ&pHUa1x|q|{W4)Nyws7!RFn0R(1@K;@o4;;l0D75d0aE;#0Qu4`y6jZ$+pz4a zt|+$Rh|LmPbveUjJrzLz-)uC*Q|SF9T3+z?|6rr3kgDH1nee0EySbr)En8-$E+lmh z1rDO$tQ%tr4sALG|1y?OQvXHQVAWcGif>GK|7azx_CB&He?P@X*yZYjuhPDyJ)NK= z_C1?>JK1(IO(`UGIj`*BezoL8<9D^}Z|Zlw6Y2lv_d#RM?ccq@$v6MbMkjA>Ha9yv zZjbOSTHIeEFz!HJ`gVE}c}tl~NE+5fNO6LsQDG-~ve!kDuFg(EJ48Z!(lqUP62uP5 zBa>I?xf`MiDDI_44|I_(*Q0|4qw)YI3cZXyCm|wzc~ovgy{vyULZyG0(c&x?d-xfH zTohFD@1_j(aZ3IQ*YHs$0G{Mhzpn}+++(7zzZMZx8o>XGyXpHEWrh8wqs&+e9*i~( zyl8kHZ68&@yiGPJvHUp(L0s@~x@l1CGA_oy&0?!ZF8IFasJ#G7JU%YN!O(mc83Pni@=Tl@sp9xS*hl|coH(d9N$p23^Iwy6s`X5%s>r%+U&TXdHcO7WSo*?7#al@``@u!=`+6SD$dO^VabIrCUqWk^M$N_1W}30 z7gdPya+AE&amt!H*LPM28nKd#MGqQk!gOrS-MsYsC6hl#Qt_Ly@huI!Pp*A|38Yn# z7nQknj;CWS=X%wwqP{UvDgAH#xgO=RlC^Ni9fuD>mr7rkam$wtO;jp;&1qUG%X5wG zs{H%`$}8RUSB(Ss`PLL>xMk|2%Pw(HyoP%XL_? z>JwIU4&xLuR%QO&Rrpb9<|V@Ob!GXg<9gi50pA`S;=HI;(crzuduZBizR;DTDipvP zNzCyN-fhhi@I=^Umi&spE9vk9XDw12#D+i@KIizl5z+fQe?9?x!7DWUSHWtgs@%!S zE|LzvWKL9F{~eRX8u$o=&#w$hQw#G_uIV}5r6(V53JK!+I`am(Nh>Pd!^px9aISmb zB+UAb8O=`2|Aesz`)zD1wQGGi{SJP^J0xWsG-qvWfdf7FIAfgZ0#OWVzsD=ES)0TI z&5aAjl7pYpRk%>SVVQA^m8mq4k2Ggax$Hx4ZR^~N-uNYYZzffACnk7oU(Nf^Eb7dT zwAgOI&N!&1*Xljb+7B}4A57$!nhz;7l*XJg1&m+b9Jp5->6;|Pkz={#RHl6nOwP0c z8gliYqnBqmLf0dnIJ+^T(c}iR=l3>{XLRHrDL&m30byywDBjtHKIo){uYLO5a>sUc zzNjglvm?*Q0Ms@=@ikXG-XZqg__5#Lzu#d?Kb<}QG+Fc4LXbm!kA66laSEBOqlSnd zd4+`N-^-_4<0g4DAWfzueMFm;dX1%y3s$jw|J594`JPjy-No{&S+6KGXt+Ka7@y%Y z$%#DtZ}<(;i1>bKv|$RZvBvl}067>0Ur z-d1_g83eTwE}^9Bc+pkV#B@S+LDCxQZbyN>agG5npgr(71o6cHYE7pLn)zM&q|y2xUWrUQ`(9yzV_@nvF8i)a{~-pj zBGz|J!^&v^asj7$d?k*@uvk5JPawp>nM!W~goXH92obI?z{fNw^tuADa4R&@XXC`j z8x|#6`A!MZbe&y4@@Isr`(HLyQ$Rbp7eWzjm zd8y=wj6j%B&>E+`*&2ip4Y?;zzSsz383c{86Mumc#Rvrfn4!;q z1&lLw$%&VqxUbEZko!Ee(}N)_I#!V~WOhR#xm`Yyg|Rl*)^ty4N7;kr9|sfN0p3Xq z(G&+hPZKSJP?g}WQNqo(&t#lF_gjQACcc+Qd@2j5?0Xj`VoSYaJ;X^}GWBA1h#19A z{Y^JIl{=2mAY!%=v=5;o4fnvW*YTqW zx*Hh!5JKc7())oJ+a?M*cQP^9MCSkO#!ml7hH^P2dNMTYe`gT zI69Pzmd2BVI!$2>2@=qxFqZI*hf_0((2DcW77u;8lLRT5iZ_CWZvZG}NwcVV0Fx3Q zBIhV{abXmB#TKQ-zPU)B_AdeZo>W5yRv07&l+mlY04h=BB$Jl&r#YvX11KjAj=kr| z%N1P16Ru^DemijLx*|axu9S9+PAORgtQebz8BBSmXN?pg(&*T_mn~32Q z7d=3})Ca$6uBeZkX>r%Eoagz5GWLX1!0bh#jC#g^>A4R-gM3v^S4)n$9QIlPu8%e3X(nq*nu{0`V>-FSFK@xsWSrSk+7!Rj3sOL#A^)3Al2B$ zRyYj*czPx?Cd1{^uEeY4d(xi(sJQDu6C=cS`x%6B*()M>KGHE50L8AfcP_1C{9v)D zM9EJf9W&(r!`E5%Mg8ynb{H69fMJjZ(V@Fr5QpyW?yjL*=`QIMq&t)j>F#bsT9A@Z z4Cc&#?{l4NpVx^eFt_H;@B99&wG^J^RN)+^6s6!iaj*~S!)j=A&*=QnY=!>-gYM2% zML?^9kXI=~2H;=%xnw$C))@q)(dr34fnoa9vVqO=UF5O|Z$u`@O5Ikq%UYg0v+YMp zGy)s);7j6!uGQ)NLL&u|3h`7e~^qGL|CqJ%s1&kv6V+CcvcRZ2^;~*X5XiLW9|zY7Rq@Z z^cpxGF4%_y9*ZrP4coS@r3XWHxr=drqW%{-PXzm??Q&--!Z+IzW>@R1Sutvi!e4e5 zH9KH^-DoiI%`+f&#d7$N9Dwg!MXPY!$m8MX28Jvf*cb|@p}GW5?B6=CMdVY8A=ZaC z7Wg6~hh6xIc^eZ&4|;wC6ti4PH}xszKR(lIqUC}hGcEZIOM90^4Pi~!x7s=H znIOSlPc9J*Zl4G*prv@WdYS! z5^2vz3o3sxjh4a?u%@gmOzC-tG-M!7q14z*`cYH zp@aqI;J^%p0p|17S;3AM2?WX81sZXOGH#GOjtkR+$a^K)#e*Wzoq4c zALg7RQ_d$C!>HV!u1={Cd*>kaBg!FuMDnJL{_@D)&ISwK8LD+S=PIBOGNzk>Gw+Bp za;wC=bzWfQD5Y?j*vk~ugNrgyFYtJz%-*lpi!E&Eu1RT*vuyLVA&=Fl>h#f9Ri&0? z69pXO7@*DN+SH{wh61Vs$_O)5TlIY95dU*thRGv_`sE*!YeoeNxM@$1YsGQZ%ddv- zy~mPno1VwJF}LafFAQw((}zvIkU|`h4xh)j`FfctKC5u}T#XBp&7^gS9;ocOaZpg; zPe__CuyI&PO^XQMt)&dF#ry5N^$aA`QRfrb|0KAht3A%9?I(aQqSrUGpJ{~&Cvb|o$Q#BE)uUcXyp*i5!_XnJAgfDJSS&L#`=bD*rYUgd3=ySO1s$h4wQBPu(He=$Hc5#2CAS#GkYkGPAS`!VC zPRlHE>NT-Dm0+e7J{CN2x~(E0zqqn9Wr2}gEC&6WE^~^1E#oSp8Q-qKxIP0hpm=`b zsuth&Q_$tmH1cI%k>%te_HQL zapcWndW;ylq_fo29^-Wa$MxZ@3>Jkf^WXWBk4~hWtJ+-Oz7?cX7n%!0z9-LoBV^R) z7NC&h{AzutV+t}PJ=|0?Jw;Et_-1k9Iix31(DzxPOd#vB!9OUzvdiH$%nZ5Y3gyKtzHB05*L_f6G z7cOQO2W4M1I1g)e4i6zxieat^#MMD&zgs^`_eDQMHjFExD$Yp#p5C7sYT6;Qzd1Oe zSZ)sy4Sy&))Y!PF}N`^0>awe z+Ik!BE6^WLv1PU%Z9qWWS91H0z2w z`w+60j%=E6Z8Z>ZnaUM0OPm&IwV&(N$s*;*=f9e6&YNt_7d2QOL7}w&HgcmLRk7T% z;C^T5^|^9tu$KY1Hk$+?1ZF7i=6Zh>b7VedOiKJ0SgBchd-!c^?MR6c``v z*@JY57Dmw_iN0p+a0VU^o-C=JZ4N6rnl;5d38Bq3H@TH89#5vZvHS3#e!_gC6orfz z;V>jTmSKq8L?Kd+NOWpm+DIPnNao2~yu=}L1%BI6eb;mud2*AjVb<@h2OpHUdjEye zIwt^7C@ql++K82>iqJTCw^|sK%~vnHuKW*5J9Ps<`*TaAhB9)e&k3Ll1Ca9oFbbs= zXz*yR!EOm-V5^Sk*UmOZ4VKwvulsMajJ+Og$V|Am8J4wQ6*!Wi@%DhVEY)=cv@C7^ z%1EoeWQbbSj(pG|H&@ot(NT~5Yr~4>k;9;G?pviuZke>4s{FrD+RcWiBui5==&&|p z&+)RwSy8ewEmhx5nIFdfU!Uq3BQBRcRf2w~Xnl77yOi}g_%70GHl(XsTC&dB-95XR zx21Zcmj3mfj=oikzEVtAn4eW6cZ=U%QV&Ci^}meV8H3=g&oxg#Kh<&whpXqa(K0BG zQA%$Sv(5m_jk%!F8!$favnfRqr8n+=Hvis6E6M|qO7GA)iO(cjIKAeJ0;9A!i$@;= zc4eI|!1w|wBc~bFpQA)wJC4hZEfWTo84xGkkqpFGyEsaQW%;Rvz1j8|m(o zlCvl=l##ol`}^h8!3($PSyHN-Z-5`&*M%=%{b4I<$X)VS*0byJUNyoB_FSJ;uJt;D zwEb1WGCS_^{rm=N$9j&haQoX_ctd?M90Qwy_@FRaJm70Z1Dn@EESI>`X-)40Ht!h1 zI`DdwsW<2bIr7fu(>&Kxv) z97xg*$E;`f{k)<0`Pmx0d21I!@JpIGT~-3(GlvX+?mUGb0|OAIA|e>1zu@TDOOlp1 zMzVQX;8_R{lC7vm36_4r_s*7jwl^0o`p1GmDJBEXED0bCh}?w#dmFXnu_OdRv89xG z;&jq!N$P}U*iGHz4W}&0I)2LVgw4lW&|6W?|MOt#p5Po*LN!e;_hM!~$!4g8^3acj zuGp2BsCtPABqA@#s!mvNLPtwt5c>-!BX#n&%d_ODMnXr2O`=d zZ_EB_Yr(~w*&r%*4;+xVQiaeR)oSDM52zD0 zZmWrWg^%UadBUEjTjL)qW()t@ylRs~-mYz~g{D@*TX34rs$HX5l-WtSkwW}Av!VAA928IYTBJPNB0%9N$FbPK zHrJ*ehbhm!ljS(iZ>OrFAgJ}LUBR0LmXrL5qjjdD7>J{NQRKz=NpY-TKxJ`~ESRM% zP4Sm~S+;BL*Rov035Uw;On#t=LRs}`buA>a7@#+V43Ht$>jR%9w5(8;*7>ZHJ{|NLAPHK3)5qWd$5^4qvtHs)KKP)YP>d#Qm-VdMXubnQH;KXdK6M)7n#w*#nv>+g*-6i`_%xk z5^6IdmqS%tNm0ib!<2SY*Q2-Kr9QZ1Y3=t3_O@@|C%H%2Z>IQHQ2|%sY z_xzdgL7I}Q$d^1TSCM@S>+1)UTDeL%&X|D|R{o4U>@H-&(q!bzQVy zs&-v=Aa{OWwUN2~zV4cJZ> z@t^y7m%%^JDrQmU)f$4{-yaFoHMate8<3BGel#G70k@kgoN|3bB;1JDJdy*_Y&eh? z;Xt5mj>fRohb;&VBkG2M$bNRU{>NNYUk3nogaEFNdr3R5BDrr1O@Pd7r8Mf{B+{@0 z-pWCA)0AlVpZ8GYb8=}~Qv}}N&q$pAnu`)F*R{t6$PKUK^r!ZwDgk|zJ}%Ls-S5fq z(p2W*7aP|}ep4mSWaI&%VnuO=|DbeVUjZJc;*+W9 zAa3L%{FK*k#Utn`7}m$+4HrT@w@Mg=#>Z6yzNhiLr=^ion9!U_1WUF9KU+si@X@+@ z=33FynfbR1Z=_~wh97dcWh)K$@MK!$)A7I+rYtFMvd65Ao`WQ_(s8h5SZi?O)E&^Z z6>oA^rjGdA45nQy7xOmKZH0OjW)PZ-`Mb&$!t(|*UP);MS5MW&Hak?kXKwQErz(UC z6p&Ky8O{?(F&L@XM8<(fsYTcsHWFmH>LIk;xZ??x(oBl;aYqNhH`WxaZB@K*@sB0! zL@6fvq-}5Or%LGY9TfHM=hNTcma;~&DCtqEevN)?#}tY9O|3{UBdbd8 z%6nIBfR*2w?C6|IX+3+Tw|BXbLELJO>|z5a>N4amK(k*lt)B6`(gL)pLX~bw;p_g@ z>Wmlj?V}DLT3^;Cl6#d0aMuvo^NlrBS3vH2N|8%xsU+3JV0is~OMDmo0qn)fzvm(b z3t)DYMpx1j<|n2v&KS$-+#jpJDIJ)wndY|%^v;)_`*rP>i7JoN?%kXmGf~b(DIoYS(P9+Z(KysL2~iWQSVrz zI2V$|Hp!2~5g``_8OjHYf$KT6*3-5N&Rw-E4CvJ&b^dsh}XO%Vl039*>?P`R0kH5I?!Y$bMhEzh}u@+&<+#M-U( z8^#D#sm#s@DBLr-V1Jac&F!6ORIU3D|TqJaBm52bmqwtCx#=sqtN%xJLr`?2+9 zOhM~q_FYw~ysExuZTKU*4!fs0D{RKxJuDL2z64{vMMZbLljp9-PekyxTsc`4gCd>s z>F|P}@*SZ9DKS`(QD70qbD*4C?C}c((Pv>ap||d#>a=)=$a{XE0w>^YG}=DX@lUwx z$=6J}`VI;?%<+DsCm1u`1N~c9CDE$4#rr-v&$)TB&Mm_!zKY-t1ENKj+#&5?IQ1SN z`o$L7x>P$liH06l_2?V~Eishhk~>;7!pH%UEpG)i5sEq1 zHb{NeBC*n)Ygk$Ka4R(xvNETZdlSy0Gh)DT}6QUbiASZRsphP zA;)IXc373V4o3*TN07lh0s_Dc#r?thz74O%13zTdxDJM40S|X+MMS9k^x5z?l3~`F zLx}AB^`PE=WU(*I@g)I)L_(OT_iex}YqgzgoLqqJ>S@ z{8P&O_5hfR^w4)F!9g&{aU+hPtW}LZ9@IA)IOhlTg>c!&2g)lMVY63WL7bTY4}GtR znE)$|al}H=D+mZG8sHlP<`<;f(Tf+9iwJ7O+YPar&yFR?l#TNV+a*uh%a(f%a}XGo zJu@)e3rOyr6gy&lB{E*^?js_XyhT-~{@n)wk z*^uEfCI|?6MqfeDL#-%q^i~k*E4kOZAWy2eppo$OamOf@#_HWT_ z$#h1s!1@jxqp!zcP}{0pa|ibT-FG1Q@D~`NPyGD*fX1i3_(xYo&6SYr#@J}BH;EO_ z0Zae_7C_N%FrTG=QKRqql@GtL-w`*#VbL2hA1SCnSYl4ei_Q{Dtt9abE8Y`LmMDxz z2D=#$#0rjW@xYq(Gse~?d4e?Ptvo0rvViS28BLb#SJ^w3*l-cqcy-6z30Zf7=)}e_ z4A6LC;TnQefh+*i8h8{^Fs3aD_XWOxJE@o2h!yCjYfu*A$($MmZK%c#)?FAi%ip4vl;JV0a9U9B$r69 zRK~hQaPR9Zr$#=YMe zrgAxk4}$|I`~2hd@Cxr!(Sh&yWpO4`qQ-18D|}-AY#5)byJ}ULF^uC0m*>(uCTAn% z3m-FzC$IRlVl&cVet%M|f+fP`zJ`Dd-&6v?@ohNL4&J_U9{p`NiExLvJ|KV(bqNiB|Z6fS${nc1;9R<*(#D0V_MPEZtO zQ1%(bAsXE8;C~HG4Bm%OS4U{2c)_vP5Wr{nlUTltd_9PhfQGI<+k<+ctqMEs2T z!vs}g_>g6nsrv(xDOY$SI5i)8Ts!BPB67UBiSdilld<)6n z^gK^OGHT`BDab$Z6+?VR325y?a{M!a_UI-QraFF|d*+o%XAn~s=(V};86)6k&hH!+ zGNsUSjVJSvw>k$*F!+It{49fY@O!@}j`Bs}? zmCtdsQ?dM2{KH2XY~haCO}xf`G?MedZbo$c3WA`}L7^cfX9VlOD?X^$h`UvJ0lKEt zWClowsoEHWO?!@CQA?*sQRxj;Yuq4KaGo&n5A*1Kk8Xb1j25Y1NV$#-68F{^IKN^C z9}ttgRmwZBKRbV1^t6On$WATD_FD$84%pzEux&xm5c)u!T_ju8ZJk^=E#dJ9mvahX zhotO^aK>w*Sfv3J!mc2#a^EGKBsvSCd2;T0i9Bu0j2 zx~<)%re?O-GNOk1mFGDIm5RUevSTa&9;Uj*OpbjLz|lr%_2Fy}*t0tmez*q}G1b5@Y2*bp^&&)e#dF%H3j9 z<}!;zcDB|ALBi_TX)ruCn%bc`{&`seJCc`+3bOMEmFYQtO-%neHtNz1oYE)}kwEkc zcKp?$EgLl1Np>xz7^%hA_@!_kyXu2!12H&c#VdoJ=@JIwxW&Kx(LmjBHG$NVpodtSE#yE%-~;ouhsw9bD;cA`R7w1`)&R= zCab$Gud}!3z6@_BOz~s&ybfibI50Vs;iLNk+WL#9w=5{UclSk>VM-)%mFZ$DUq@#C zrPjR54wGv$AO6%U8|~*DQ{yiC^d@`lL3?S`{A$QF!|fB#hwUZl>3s@D9lRx_`*SIc z?St%hU;U*4SO6j6p4Gs_#j4wl;u&GLm&40bTb~n8QCFzMqtoH<*n}UyrW+hPKboZf zN@vEKisI1o5I^C1cFbwDHiDP(l=JMF%2_Yo39rtY(TcViaosCUiSPKb!KAa|Kcr%A zcEo4a3#VlbiVkwcFAg|mSjLV&_t`pV|aC|ggz+<)3O z5WLy;!uyzSW=mmYDAfIo;n|m^sWatTYkAu>m&Xx~@=IXyzR7{i=4<$6{!Fxi>}7#e zBgyx7_%BrN_*Ys#AHMs}Y9>jM@ol*K)JLUC9Qor*w8}o?<0M+t3Xj@Nhp}aZxYi1B zY1;>P>CZJZPt7OJH3LBM+%rdW-Iqh4eb9630n@vvnR#5KR&dF_G`bh;5>CkY+33!$ zj{f_a_)>WO^@3wR+vj`N20{E?w4Oh!oV_=$`9pm(w;JJBoOLTa0*gQ2=?SUYaZ0gC z(4BFq+|Y|_`A6QIK=yx$o3OY4FnE5a)o?qy#mk{;@~ULNt`y!Qt@M`jeC1Kr`qDgA zYNLGi^NkDx%nNco`Rt0& z?Jg@)TNm@EXyM}1XLqaK+KNAJUvhnWwlkfMEI6qoQ4hns-+2~B-EjU)4W9n)++m2J z@zw7O>h zcewWmIx)g?KA7PA6L9^XD4lG+{kOZ@~FBmT@oVR$klH&L?-GtDwzR!1g=PSQNhT3y1Bo z9JY$!o*(BCBOj47s_h-uhd7%kOo^F>L#NSl_z9G4?T^V&49;MoSueNcXxQ`%MzY_S zOUZqIFZKy~(SGL*fBFj!f(`(%#L6YGNQ~$Dup__J{;##xJnc|2{^*_z4tvn0LHa@z8uko~WVQFP6x`ShIx*oMB0mEFT!DWKRsDLYK zE}E6m({w^N%9>hPh+LhLWesgJ4g4qI8vNt14JC3NyEpqcN=G0o{3WnSr`;m@d6cjv zD&Q*2EyFq@Y?UZG~{yi7z$+joM^`k^=bL`4HY?Z&NV5{W$9-%yI zZ!lljzmI0@v@apjEltx>75OLN8ujAT>=IhUoTiRpujW|ScGT(AKof{TQ{#Dl@AQv( z^}Iqv6HL^2;ELw^U*my%V^M!NHW91wSmXP_XegaxzI>CVjN2@? z*%6`AyCWb3<3ZcztGKW+ERczCNayYZjQNqKMQrX;R4uVgw%`qfO zWI#}z0RFG=QrRrZ;8Sgwb{RpoW`Uy)T(e50gZFQ)4!g!j(~?a5Kz!5Gj6xiCfSm*FfntsUnau&08i4+13b3kIMr!*16)})fojnM2sA=l8>NbJVHMr|QGs198lO@2FKf9wsH zTmA2ci<60PF0R+x?Ox|IWWLBB1qBa2XQMq?6*Dhi`tKeMO6d_4z6|(wHyiI;DAxPu zx`Vo6jwFl3FUJm3Q^Gt9XcB53hASRZ6ppSyZV`#EsQ)Drs8VSW{gg2qB=JnFXbXy= zLIa2cR<#$y**kw0$1^WrTg9U<`;{befng;{d^>CV$>JBx)(Ik{6xPY|lpXZ(D&kf2 z>B28?=ra@*$F0)!R9WcX8mZEhXJcft^pV&W$D+oA)~`o-h!K|Ke6JM;y8>V^Z3>zq z4pVtDD<;_ft<{rX$L}K`arW=S1Su;^5*Y)SOH(PUnTy`O2w*A6P<6B~&*bc^EKPpB zQB|BCcKWp>M>Wnq*LeilX`9nL!RnOTauion_YozPtFr^vI5qY>$*Tca<?W=CvPp6ml9kG|;6)y0iy0gRAG)OEt`k~!};(W~~p3Wu4M{`_pG^cZ(k@%+=T{f}mk zzpmPzBY%HiRYU$gnJw)7`+NV*XI zDWvEUJ8z;;jgclU#t&^Dq7~GL6}Pq|E)bSs#w3i5@W}k;8rkRXk{E&^ zY7VRs9H|L?n}BgvJhdb*TS>#6h?7o6g?d*VQs7GRx-B@y=1&MqPcmX!dIn1N=ZK45Gw?*w`h8KRA1P1cL$I2WQ5FenIF#>dE8<=^J9zb|DMQBc#JO3J?}-r%;E znCMVQZ24V0UX<0Re?;iz-+cJ=bF&gK@(U>t=L^>N`U0)m@O8EC$aW0`QpNeT~%Zc$+F zVDD06cv{m0`pMJGDJuu0*$NSesHR3~T1?Vc#2x6&kU%2fYg6UQA0IT)jQ5}F#eA{G z1ZuiTY633cMF@l+zSoeK-RjdXA{cm z`{W*9PI4EdG^=*08N8o2S<3i40vtIc8S=$9=z zjmRnm|C+55^d?!Z2tl>?7U-r@An;b30;g^<-59rbgbKyWk)~*30BS8&&BZY%njA}o z*MEVaK_xqZ#gZ(2@dKAWw*|~3l2nRlkQ2pKNO7ba!yy|q7sn279h6S37;1J4js{1k zaK5nNPw|OR7CDASi^_B*s8q^#M-)kiM`(eyv$^~1iod`!zbaVUtbX!AR9ItqK$Zfu z0q=SY-o$I;g`$=bD+D3$MZmTixSwy`+YawJeTa>`J^-adjg8G%-61{jMUQm}XMSsi zhHE|IXo#p)#)}JPRfTDqE~bD&Hfr4|{M2OM0R`-3L!syqrcG!9dGS)L{G`aI!~vtC zTM~AmLsr$-+0h}l>`?LW;w}u}sNB8;)U$n``o=z5GxEwL5O1jICI*W+?iwORWGH+o z94-2d#sLj=`L0Ec{Q{GkKvCI3+Vj(m|6A~aFJj{(v-4mP$=_{lU+kwxP`KD0O%gYZ z8P6hSMAWD5WZc?twVZU0VQ+rh|EgoSi;vqry63BBM5uuLw5BMwOStY(3H1fcD-;w4 z@eI+PtsrgAU#5YicTy}-dq=-8K0gsrYMA|!Bqu=XMIe5RzUIT|m9g54hp4n#1%@=g zBO7uKEo$ApSZjp~(g3{3+dp-<%880~!BRSf!6wn8?y~PIPk zNwjsbK4}v`SbLG7cT*cNRoD$_aG@P^j`Bu##4T{9{Mj%7+=684Wf(*Jr}P2m2g3m0j zoaLxFQsQy@o=vs`nTK2$-QB`wEf5Xu$StRA+@hyRJ+enwlBhnS^wT45p2GKmpt2u7 zJN4QFb%liZjK0wVfbD2WvWlx%n|(ber1HK(gvkS&;#V?c>d4?tT+G9iY)SZIng{LW zB5TiDbMakedjn6hlf1t2x{6?>P%Z7rqgT!Vp`%=zh1D+PEfWTvB|i1CD~5!?T$w$H zmlo4U^P44l&YXk00PP+l)aY3MB*GH?+7JB;WHrR_DB94@6=Q{W_e$X@;S7%Stl{szO z5`TLS?1&MpZ3gHLX;_)MjX8` zcnk73H%C7fpnXU3n%XufOjpN^EE=80)e1_WNEQM^3Ru;JKzd8;weFZ+k7BK;$D-*o zOwd52hB@hYBZM+QycJdplmt z6+q}V3Bd`sWAUB4iC@BfO2l)J{~XNoVK*rP<{5F1!baV%`v|D-;O&EqE1+OyG@YCS z+dTk8a5qkl!30wf^e!}ob_vXMQF&;@l?nF`J+-y4jf%Ica@rrqDAl#xjaML(@Tj;Wf8SMDk_?|*`)?liAX4hWQGqTL=qYw(2@>>+4uUo zV~$zNM1rpyy^Si~UPYE=F-qRL2f{C5Hr<go5C5*K|U{zMc{C5!=%a?0;V2bbdmc?CVS0R`z5CTw#NbdjB7ghh8+|vF`cB z+7ooNrV$)bbc{p}Bl&a|uuaQ$9km#uJznTA$7$!wW>5C{^cM#fnWI-0L2k?ml3qY( zauD@`B{*aRNv)wk3xXsad_`M=#$zqpQ~QE_9lb_fHYUj{f5vlKKC2Io*7|1DpoFGn zVF8|eeUh4rK(kIJ5A8d78D6EVMXzm^Twr*s!x@_mZ}EsGuQQz| zDHGT;PfWhQLUQ)0{@Vg58ELR8ishbv_g zC?(D$Z~|1}$dFV@m(gy_kT~?%9OO`!vXC8AiCQ*XvQvC%E!X#}fkX#juiOJ1vtA^MjrWO4>PkA_Gk4VF^IIqmiZN;oR?bqDNFn3RNDz2=fhp*`eV{$ZB)M0$8g(&k4fhn(7- zkpk*_0`L#x)WIsvx#pop@|$h528I#V=9MQnu%~waL`;Z*uUV$}kEZN^40ku3(m?nJ z=V1?#GG>Xhc46;09}L+@s@l*9t*|E@PcdZc89Ksw&262u3-&y=FjUwDg0rcH-l4U` z=qLm6WQQr?PWSqs2b%M26k`W0tR=N1y0xu}Tgp-yA$RL*I^)g2nl$k%|h$*%<4q|IPl+iyF zvA$2n#1Lya5NlXs8%pc;>Jn})QK!I2@kkH?ePenX-@}fJ5IR$$qpZD@*2>oQ@yHYD z1v}dp_l$@!Ys1=Czfpv4>8)FKrYC49q-(vE4Bm2ti0luEr4YrZmAD4^<-ARa%=A08VTR}j@Zz@3m?ZV5x)exiQK zJi{mJ#?R&|VpuJ0?D|x_wprMLue~`>$uT5N7nMt2Ad(Zx9MMIg&V42!}AU}-YlA!Jm<@CQ9ebj?FGRhj`e`<8g{{I zX^AcYU1Lw#kAow@R6iCapiXo#)zoQC{<@ApqSb<)WzDCnuh{u%IEPe& z3<{`+=s9Pu*%nl&W>UKOG&e_jTNVdB1Ur5on<;eqE!t_*ld$0KYT(wEFewrVd`^&g;&s(+csk z^B<>;kEczLv(EZcaUHxW)3c8d{LW`*pOVf7Oi!D{&zg7efG|9Cv|tPvU{2^9i~D?m z^L#n!932jr=Y(!OI|q)RuezQeygmogqyQ0sZSjlw$Me<4^NXbO6V>yT*B9&WE`WfG zv-*qg&j8zy3-s&DE6CO1YrqcY)D48 zg8%8^!?pN>({y1E#{^zs1K+dH6#m`l{o98m_&dY(V`uj7-mAw0GeSC4fV%MU6vdi+ zengE2SI?2(Umi_WY-L7FDDrRz+e2SpZ zvK^Qx4&BLuZ_hS;mv0e+>$sIJwz6muR zh@qP0yzGcUNUtNS@He>hzq4(EpBw2KWiZUTtNAGu`0(W$Rf+mYNeTFQ^B<>B0JD)I5a?G=iY*h7qZCx{}xw~g_Hq!tpHEZ_^u6d;83asdt z46mI#l6YhOIF$x=C!sw_M&UCMQ@wv~3rYR$H09Tiatk>{Hbt&E z7nK#SMHyS{NDa=qmEw#5P5!zR6&+8XnxYm`<%T7M$e%`lboG z^<1tdW-(utwet4(9Vz{?&d~7t5%epDmlQzp1()g3=UhVa+3&+qx0paQTcNG{rTNRs zUuPyis2?LTdA2SVhueCKzkj`aE?p!f_5(CW_npt|FP?r%J{0lh(x^!4u|f=l3AF*P zgUxQ4dazY7kfDHYMH1?*3G4H92m(9{X~vUwV%7)*mzW7I3fjV$n1fl?Y|cXLq@rpY zeZ`)}tYhnSPy^j*YPF^uz_x?B&>;sk_AOSFEk67tDat_85`;d+hi}^85Sd3yg7cvx z$Hpa=B_bC-GQ#5{f^ToBEzhQ%$+?uz6Y<_Y8&E$wA}D!Ivr74z zO5qZ$t|gfZp_5FdX)Rv<7R0->O1rw;q~1(R1pHYFz~-6I*a(G|OCPf6eO`5L(%tdx1cgYG5 z5Jn@hF<`$MRa|}k?cp01QT51N%-_SnfMLH?HGv%DUq;wHhiIh1^|c5KLQH86o2Nju z2{8Tma@N;A9g6(Lgvph5FyhmgNJ0Mh1UAgl)RY==s!PRBhV5ne0yGkRwBLueM@UKq zV21@Ql`_dVDC%@Br135h#NhE<$}vqY62$=ieDx*g@M(2!KZZ3c$QSPCCi)H_WORWzsf3z*8*ODRdZ_VRrJy! z%K*`KBM8yos)^^Tbu#gfjZORGh>oG{Sn#~lq1*~X?47z zGjZf;qp!6m+l<{SN>QrlaK3N&if7|P`aMy(%(;V3p5aRUN=sejxswf*(MG3kOB=_e zy}Od(&c#Yw2gubeJbrTvf^a?=C}t3#8kid~CyC3k(=xiaQr3AU^=%7-%t5e)Yj88OQzS!+W~vhHy@ z-IgRZmdVZ~2p_@J8hK2)!G#RQ=ic2`&wi|pzQXiKi4?P@B{LWuQ*oVk-HEJ`2Z!j7 z`|+l~$BVa~8<=Qj#^lfqJ>+O8CO3KfkU99xhC9n(%9imaXF1XuyyV0K_Cknr>r0HtM#7f!aY)ZDS#0i?7Ak75DRSil}$_`$;$2Xrl`#=bPCMGDpKfw z>-8uB+yFx~&;Q@#Sv(w1&Zmf1qF6GT43mm`s_>z7Jk0|0(~JM&rH1@${&!w#K-r(6 zY_3E;jkSQH{Ai&0q9w#n~fq@ z6~}fWew9)r(S~_tP zG^mn@c1EZI<3#iOX$wSq)L6ix9i0l}M-aJkKnXYOlL|f(_2?%Zl=bmKfH~xrSlk2M zL{e!hMpaRSJ25f~uo_uJ#lijET*(rsn}lWUw#x}kMK?745nx3~A0Y6Zrn8D$fd@`I zXlTu(=J+d}jN=$Z%C*knhchT!jf9RurStu~k;+`V`5JCkP!^Z&1fn5WOFU=D&6*)D zG%w?+%S9Z2TeSN$;2u+jJ-~sSBF1IB>*XeChZ6a?&FQZi~dZfx4o5 z63(wU!R-QPU3bm!y)2z(d?X{r{oksD&HnN*E|fMGo^I;AwuM_db7gR{%MW_6BcFJ+ zgaL18H05m?pD)?%4sMg-pHrz4j}AU@fv^_mZRCFpvkgd(Ywi3>Rm7yC>UJ3_q5U|6 zbrN5B7smUFR1*{V9%BL(K6im<4X3)XY*eD$SbiH6)Ch8$756!tW_VK?^j*49jDLwQ*;1;M_ z9JY%R#V!TDcno(uvH*r{L|2@uiW?pSfjkK?UrMC9AT@|d31Ch+TGAIzF%i=*qyZduVDXMk3maL>ohTy+7a=A2>Bu0Z@-v^xFrWmek-IR z{6`mX$j5AW`KTHRO3d9*VIj?89}g{`tvX&ilu^#Wrp7kI@XnV9n6QmoqP-`YC5R$$ z(*IynE5=R7JZ}NLPSXq#!(GKg=E6=Qs#X33b^lF~@n-&`@c{CarTip$Yt?9KA4j$+ zNk~>ZP8rWkBzti7P7G!!9feT$3S*X6YRS2@djXCK*H)1C;6^0fp)u zH5F5(!|6>bijLo~(eQRPS~6a_lv0Az#}q-s!M~DAV$cuGh~D!hNCykO_eE1}1$FZt zH_=P=D*%cJwSuBbLd>W!b%zw<2LmY6t&vX*P~Z};AQ>h)4!KVc+{pfaD(S?fiIWF8 zvNH#nOJy}#6j2-RM59r zoDm#UVV&fz7h>V6TDEX%Mv|nQtH#X}Rl}t6E^B^TVXAz!rqW_=HEs0Np>o**jqfvK zJPyJly$_m|VPv{$=Xi~AyL_p5Xr!7S_E%l-P@Ukn0*!q86Sq*KEt3lRr`YM$cOBDn=t544y#$T3gN%h{~> z98w!&gqxy7Ck;oumS9s3ucwkK#CoLzIt_SDhQ|F&M%k@x6CZ{_(g=!Mk=qPoOrR=J z?{~!(wTXqmIH;ee!LI!LUH%<)1arK3!UWqvQ~v@<*q_lobg--039`N0+eDo?z55xq zo@&>n>J6SUfwI^I_92$6ji`saSy7tuglD~mV56t(CPSBMzZ#QZ$k%=tusk^Q<@2Fa zGlf3Bz3bfLpG%PJRBKU-jg8_qdsb-1VVqKB16Xh5HDmqQLRneKKvScNXe8;bRvDWz zy@UIy_n!irsA`l+NHtD=24<{k`D8&QE>CrHO(TD(E<2)I6&u(VVt1bCGSanN%t1>1Mm4vN{-%{+2-7c&%N`B{l1> zlvfQ%@S8ZB0P_yYlQ2&nZQ=PJt?sMnPW;`E%xXHaB%6C~wo&@bMq!7~$3|F!--|Zl zai(exCCF;O(Z8Bk1D0wHtgwrzYgxCR+VfGdI~(4Rnjjc>Q{3HFN6o!EIg=S)tg>qB z86joIU3y398rJl^?bX41UXXGD@9#JX*>V_Px3N^hg9NARUdV@TK6j;mwYg(o*TgPr z%TW2&L-jKQh!*K0Y|)NBd(wRs^^_4-Q z9V(g5I6E8C_7fuCPAk*Z z0GP=EfNTIOv@l1xFmr48Xfxb{Alw=)%rYX(RR`+c9%fGmFed<*MuY+Xgqfp-hr&i9 z%m^Z5(83Yp!vfo(HgeDy>xj>zky&!k&xhghd|{|6Q7)t5aXR5HXb~8yk;r1u5GWer z9Cq_1sDTZ-gb#sdWnpE}9dJ|=8@PK^wFwGoBnNc!fxFnijpX1iI%s!$Oc-y>Y?`w@pgcLk`N(! zfIvkO5CJmU0OlqnmaD*xjZaowPL_{E0nVbOY$a>xrdW%ks63+4*`ydOr|7e%7!jtL z5#p-wr&@WY3W}pxccj`8zOmRs174yR&8E8OrjgH~Hd?27b)*p>q{6dCAHwt?{`3&t zbZ7xujw7hdBt2#<&7B;O0|f!|K>^F@sbi_%$e{_#*bJT-xi+ae^$AfQqRot zj7&FlaP@L#?PF#=VOAr5RR(C~a&tq2aGX8)kCG9}suxIvYM)r6| z_T+N*^keocVa`wfoL}-egZ$Z^$k~)v;I-wPjmMlV!rW~bf9|es?!IU4VMgw8NA9U- z?n)%~8DZWvf8MPw-1?rk^_WZAp93razdq*mLGytE`AB;CC|>z!nfaj3e8@^Z=2JeD zr~sof5BpCJ%(H+Xvw*0xfOw^V^r?WHsE|^ikV>zRoG6)&AsP1=`opAvC=<*^RKy`r z#HCln<5k3$`QN^j&`OcWQ<0cg0exj5<2clQu5it>V4 z3OZl|mU{xrSY&J4;;1tKUipiSJE6KOg(LjXfJaar0Bp|ya3CtP7btVqD|7KGbIUCA z=q&SEDf4+M^CKz`5GW7QEB``N=Ewk5e*$;H;tMUkpl#*lL%P|^^yFJ6m}!|6>75ms zD;3#K6}d!}`2v-NdX>dqm8F@L<(-w4E0slh&|wouYhQURQSvuEXg#zdQ6L)_57~CY z^mMMG#0JYn6%Ob@+tRD)%)o8!@RV6%gaN01HfNZq#-ARLkXik^GI7?nhD;nxn^?SX zT+3reOyD4P}`(eCB;yk<5_!M2|B8*B{ju7dIJB52k&@QGZ2D1ylU;9s_!$g zBmY!4uvNX-R&8|R02u2S19{i=>IoC-pI7PzK((0f>KiUWm6w9%k_}MPXuZz*3$Ky~ z6R4eSG}cK2p>2rlLsR5Bk`mpBuzKml#K3JzTt|Zm6XUGFI0(f@G@N z%TL-XtDrW59R*cwh^n0#Ck++eU68p>{dYC=jDQ6wsBE?^<6ZYaG_(WUS*PDoMG26} z>SzJC&qPB9KXh2GfEr+{ZDp(ND_!61@j5&hn>UEM8mrp-K6mYZhOT#Y4G5(5c6D67 z>x~HP=@k6VXxjuV=uYBqU9Rd~%jz-kE-}gK2G)0PNB8bk_0FAi9-q`;p0=T6LvK!c zwHdmwva2-T^za$TKj6T8X=ws@U4!Wc8~N zgSQoWpE}Zuw)%nfIMwuZB;FuCv>{*tq!|EidIHB0)v!!7+D&FwT?(e%?1;Bv*_(>=oz!14#bSsmx;da@o~Wxv&kIymy)l` z8NWM+CNt{=1vAU5(tip~{W6$Z^qKmdJ+;z3wYD}@RSz1voML-vT{oECSDf0`uQh)e ztE_1Ls5m|;02%hI<($mA_nCRfo@pcm4>|GxRUluhXMo>_iSj% zOsV>KVuJ}}P+$&EY3_%~9AWGn(fS+HMak+bCWeaQ!730Hq{T|U`Y_;-lm?=aur#0I6~KUpYvV+8N0rcv%dCy zeS>{{ee2))Hp#}W@W#I3#-Z=Van1&?0Wf8<7Wut-8e`-#r_b@F{T$Byt?A`|%>91~ z>`?&BfUgJ^|6eK6wgd_CkJ^9Z4$_~UHR}_VH@S^Vb&bvq-N&03}Lf8F^lKyDexgF8h&%p=&!J_FR_g=T% zu36uD`Foyj?!sqef4>U8&fa(Y&2xYHp0;WI-0(KvKd z6g>u&QhW!min2^l-%(!-0>5+lgWgw^wTr$$oa*vEWLls4{uhR|%K_lrTZ*z> zExwweKWf$mN$<4jEM*Mz+Ns*!|Il+9DTrG;N}`cnw!j~@`;-+yJ#D~g{r*_LX_~)x zk#l8^GvAI!Fkc9h}><2^c1;vjwTtDMqkqOGC8@(FaN!y+* zS_z9L8J3A<$DGC#Fc+Pdb^T7=M&=ykSS5LfVN1)KZEUZ-^f z=TBw&126GVja|hmXTZ~PdC&{G$nFlAjGx`Nv8ML!gQ?BGLXlFS3c8yeU4NCDEBWyF zHs!^flCw|mcpTcxnl6}3j@8#hnh8G9pS>KIdEYnhWu5GGqd)d(k;<}cB`|Vo(|wbB z018pCIR=&lZke*Y=|)m!3&I>U`9wvRh=D)L3biu{mLTZHuu=(0)-?gi4vMeFs{~>y znwpW04!lWK38NM_wE+}Kj&kj@@w}K|z?|NTs8pQl`7h(QZx2=2RM={qAnM}wF4VSo zRz_rwYoySn3dY%}0y=&pOOS36%^V>I3Qd^yQ1YRmpqz#67G}U4%t^t1bYTHWF*zW# z;{NtgHh&>i;sgx}6r9o6rzZ%ds`+SQ%w)nfXoDPC4dkgC&tXdNPOBzk-CR^Fh2bNqMLK>wYU*Tv=H-GgoS)` zvk6d^AW7kxF(+rvW)A0I>>Ip8kEMX2EPb1x)%-(Pb25f1SWgxLLaHe3{3WLC+A~j| zZ1A>d6HgO``Iep0eiP^9sTFO}MYYPVbCQJMEv4iXb5u}raY#3k1iFL)4L2O$Z;UJ! zIioRJ2INCx=&>0KN#2Hf{o6Mg zd>u52yQmnp>>B-_gc*+5IAI4ee_3ak)94cViy1@yR+pDki-V#J>oq}EW{Ro&B)8a( z0nW{c2(m)^?9f+yq;?=+#F`U1uE`;^ZOKuV;|d20q5D1Q#}Wm>7e>I#^c*p+k(|bE z29}@!ey=HAy%>=lPW6fyF>>4pf2zi0Nc($IjId}44g9Sjp_U;O&+q`ln0WR8AjzR) zy+1P(^u>sx1p^;-hy$4Zbu?+PEXYw%jJ?3!B!%L@qcZd!yvInT4LI|#r9m#V{A|zU z=2Jlj->@3S?9qU+RtQIMr|)els-(BYM2>$gSi}9A&jp#=Y7*BoO)z8n-LLki7En7! zg*)$2hiuAKfTuP;o4P$}iQnhGml2Ajjx)Xum5YDNjQIn1r$Rt5f`5=bRFN2ojk4m1 z0Lj-VglT8Cy~Kh*Y|dnrxxGCFbQ&SOIwuVdAsb+kbCG0*dXpCunWDLtR8!1Y4hG|p zfvcADxxx(4cF3g&5E9jr>3Si9n8~xwp(a_@K}e|#lq3*Ouv*;AgIl;?i%hwFynE}X$Y7uBZ!3B5#s`Q*Un*nQWNQszMqyD?dSk7G4}LwHkYR-mxkwH7yBVq@!_L|))ZI@ z?jl}13JW$#=D0duzAr(+6^qyJi2>OVW|SMq33=$Nd$8L;z^(n<9{MpT6P(u;MqwS& zjPW*GL=@-N;XrE;Pi!F--{e+mLhH1eP7|dDndq;4qVw z14fpw8&A*11JOVYh5B$bMzyW_vjlo9F26bIq>Uo~8aI=CAR6zcF@7D$?XA?$yiaa0 zBn?eU^+pafwsQA19}#;Kq_O$SRSRxJ5ci}(#jLnvN2M?`XTyl*)mtpFDOb@&!v2JW zV5@2tr1w*gXr8&#g5IaV1@#J{FW6Bdz>%FDS;OQFl9Shg2_~S`=`6q%2(Y9^H4&vF z-S3+@ebw49LVU~nLMXjL8Vx}JLP`6pL#&Cvyn5@pW z3Wkr0NpimSwh3yWYrv0E?N<|u$aLu3FDLc~k#Y_SZ}s3kO`Z?V_*A8s1?>=7Hw`ju zta23!s$qQzHk3BE5L73$415X~UTga{-*<2U`k@^+FEWo<=#`17Ph0e-B;UM4B8WS3 zd72Y_JAD+Km%WWmBo1N#Gq(11xw0-ruObpX07DMZCae-M+z=F6PkO6aA*efm6urP3?3qDMHLg z?XZ_fp&qsU1C@?06@>jkquIzG0Y!F%xq*stFaWBEN??6!o78OG`#Zs-L;VLHN?WsJ z*gT8#4pAOe`jG`ecc8cHty+zfypxMWLxUXRsB9d)l3!TLX0WRW<`w^KeznCt(f)-l6a{LA7g&rz>Ia8+o9(vaZ8 zCGV3EOgN~6Un;^C$&)aa7Q;o+a-D@WkVZQwwi1~>5E?`%B`ZL!Bn~6YWs}l+HJ3ZO z%`qP%MW>RV1*(%&FbQdhZI3bUO5`qSgFd@JkBS6ZbwS%EmM;&fCY~%h%hXSZf>cFW zg{{_eDS{3BG(8y#l{ZR+{Az@|X`nft?nJc&Gi~BG#G#(_3S$}WQfkYO*qar^afG>* z2yz-NYK_==p6JZkSA}Mr__^ks5glr`HnQvQlXJL=No@qkC3&0PvuLQup=YX;;PQON zQyoTTwJ%C(K}xOPPSq_D(0lxNU&K;M$B9juM2M7*!A??gLtlVQWD&}j9+;RZo?Fn8 zlZTibZO$1`oYQypj#o--lI!E~dwrfnby_LSIP;9{irlZoWt=c`hjb^$IxPmxs1l2C z_RMV->jf4bcb|&^QI1gsyN(ZrL?xehQstyr1|NlSwu`V~ga6RO&V&VuXH3+yUG9)e8nMO&$ z{6w9hwaEU|x#GPfJ6EawmMx2cMoC(x7dkecxHKmkV^Jb3PNc5@7Ei~iG)6t1Y z(jSeldbxU0uQ-56(oeNqmXZ7oWAk8B&T2+=Qb_gt>*g4RG7JfS3)}Lv;_4Ib!t<7o ziYVEY#UE@!dDMus{snWKd^Ow}V4^sohd&h&Au=PjEKyO3+4A*^k4>?J8h8WbA(YBM zM#U%R22K=>m}okzcMZ)~xf4Mx^Hdq}&+R(VRMf~d5t)2HhCWiiW7XKsq7$rre8ar! z#j#abTfHOoD4Af~#IhhE{r;FjhOwU4t7S$WO6Z!lQ`)wRQ0zY-Nhi?MM$sUfMTEaA zaJ(%$6f7H!tso;nxlN&=S=EwW1iI?7~8#2D@Qpm&E`#$il`$eEnM2|F5FVBmyo1@}8 z2SbgZo}O5vt(>*XcbYSloo|l4ju$dZ zx^ij2)L+zV%L_jk?MhoFR%%kDgnww-`I-^xmA$A?6sDJxDc=nSQ-)b|FC(eDqf_O3 zR%5?(A?Oc2Q+B+qCWt#~DLCqn-s!^Vt{?x9{=y~a6V2?fmsRX+#ZwKBTeZ`InB9mu znAa*WEk!@wF>T*aL8727$OG@ zv0=+{p;0h$@aKR81R$oY?k%kEPd=887$`~^Zz7FJT-G%>$A-E^AyZK>4fJ6)_ufse&Wae zlF6B;%lXAr^9zT0p8sr?SZM)kYF3K`AdfL8lk<~iY7UY8=ex6c0_H_<%`fDHISyfH z0KB3M9}?t)Y$yS?lz;|uKx4oXe4^4cy96Jt02`Lztz;ji-`+~Udy<#%?v_HB0WIW! z0A>JuAQMZnoGc9W##ja-{BDY0?y>kC%)A^+vJx*0_MiG4MY7Tu5Aujz>d&7AoBlFf z_h}Y}(*B!o_g#bsNyHd)tx5pBsns^aRkS~=z(1?Q>kFM2i+c8}pOjWA*{71txdYGufvp}B>z^Y4cB+Bi)q{+2tnPk@DM>%iUGz*+myeQGDH1A>C7B*`cgOQ}^4`$=%cI*)xDk8eaEI zNcYV|_AQL|t^D?_bN6j~_U$(I9bWexNe`TjwzZU@t|Cx(7N{o+zp>9d zVMyFTu)|>}to9(h_Aqk#Ao~0;7V|Ky?=VT^z`+PTr|%#qA1!_QC~M;=|MjTw{HU1p zxJ2Z*H21i?=eTU+xbpnC`t`Vx^rRW{q?PnIlLe420?i3H5^*@{BR$oxB^eOeCs8{c z%{>)=1x;?8PSt`YG0%R!g656Re)*j(=AQlTIa}E{TYEj*AU)p_Io~!q-}O7+I6pmh zfV$S4nj0-$vOuqtm#&R2Zv8H9axd;{FCKa>UN zO>TUr<$tG>cc&+MgN=2kJhSJ016KKXRVQ}CQ$Z@YPK2fKG5`|BwB*V*{5 zi~nD@yuU7ax2tScti=`WVEQsbxcI#5~NQ$_Dn?dDVc%u^%msfp~l+5fpU@42P- zxqarjbMus!4D1gB2iAdeVUGo(5C+)gT22{{8O#w*=e# zw{r1s4fb!F>~$CGbzk)L!1(pB_jUE+WohHiKM$Pa|Dx!(RKWUF!uqd_4fH$%1F#<_ ziv=NK;7fU^m`a3!Nq9mYRLrEJ-Y{zoTB|HnX*US1Jl%a*l0%?Y%9YAc`@f3w`-+*| zn!`9I6REP_>NF~F2ow(gS8+a5<4CPk>A&K9%TYz3sHra!zgn77t>J&gc^)R^+y*21 zXe*Y?0PF3=*3c6z2ZPS9XNyDL+Fy)%y#L)Jzi2y}47e|MYBFwBDkta-`9&FepV~N`#bG;Y090RecRq5jg98nf7Bg3fUfbFH1E1?ucnrv`=;f>n$4e* zHY4@r7C3chHTmtDFAVuX%mC?YXT<7+F|4P00JwcC$3%RzCA++Qs&r zDE50ki(r2Ij@=+}9)3&jXU&d1-+p#_xl?#BH8yH01Bc5^2E>xOCSU0kJf~K{1gD|H1dwa10(fb|&IE0vDMou*;Og zv1EkE+chczia%xukoy>^^ESPYo`|)n1xh$EXulv>cl{TyKi_rDc z#QGAc_a$6`>~u>%LK0}yke?%A8bPBH0+f2tC5Y7J`xExox!p7rM@_sS49|*=B7)p4 zeLI{e>d-Wju~5z|#GY!f&kIqBHa<=eXRrt$igL6Q&yTZgo*+kBK@~5U7z$M#&b(+Nxo%#|Z3GR#XotwKK~j?rX&PNXl)av9Iq&$byjD$H?( zo0&7e6n1>d^6Y#Z6UPvu9xR;a9^WneCIGT2O4K4cDoHj26_;eV!KKVee#bWD#m)@J z6(vEowv|P-$CZ`!t+1$yIBhhQsu)v)IohnwO5INdJ(Yyk^^Ta}gSz3uNV~joP}gVt zN@9xu?{8Ws#c^?ZS!bDf5{WOgAmaTV*vZ0$cmqh2h1nGyi zCbyCAUpE|@U>Tw8z-2S2*14bl{RI7w$?NSX-rR?s2wBpmT_&*8=N?{0rQ3b)ovG7R z#J8ZQ)xbE+>Op7PXPSr~Y{_emimyC57y>;k-cDjP;ew7WBRxgueSbxsFA$M0HZD8f z8h2l||4?SW7~#cwxt?3C^>LZhhY6i6yy^A5-?*6ebs7~kUc)o_xn8yI%DKvUe4gg_ zbZ`@G)cZ0PW@L(A!^qWDwDwN$8KU85hO4G#*$V>~J zq^JrNiYeIVOKUD_xQgu$DwfkzDJK_{cs=Lw#w{ev zYLgSczEb6R*tr0r%gM;7Mfy?wA&&Lw+iHiS^ocw9->4L3|YAVPS9S|%{8I3J_1B1cE< zL_CBz_%wg)yMx|*)_OJx_fUtDGmc~C>LdyGLdNu;N$0GKm}w?c-Y|BmZ#f4sWrAc# zuB3InVO>_0JUt2X_aC~UUl0~9OG?EpfH>!(}Vdn#SVwRGj)0rE2JD`b z-RzE-WYtzNt_Lsn;(1R`sZ3R1nVsT82Z`~I$E-pcO+W~F1c@5a`ew2O`4FG1xJjDY zp5c2_Bip&cV-aTjq5Z>I#gl=}x$RFPL#f$+mxF_kVsCtS@eQ-Uw9 z$c3BLAo7x(udL$3@qN3H)|f?PJMjm7;seZGt<4-vG5V|Z-O2m@IoEH($T-{k2K@si zVnZ}YDj*Rd0#{(cU|6l->T=;>r?(_4HC@O~D|!HyRo1tSq!bZD3~KQC0|P>%byd zg4{_&Rxow0Rjx{dd=BM0T`v%mHS3Y+9Lg)c!EQ}awM;xl6Tv^*Z!9RMSvluGpEbjN z&IUExV&Hxd#ANAhE}_prdjy;hKX&a4yxkgN4<|uuI8VTrT>!!y!()&GPEJ=$1==0L zOx`gZZO0%GPmD73pu$=2Vd7oA{oG@o$_1ZeObNHhr5aEvua5$Rx{&7FQjSV3Q5csy z;_xGk)LEc{>4X?eJp%;I(L%2I5@;x_3}TPu072^|#!jmaaRa@oLYYG%MF3r7kvimc z-v{#gU4s5_+Y&EY!?t_dFQ_m(bTx>(PB63>7mdt8`cJ)9 z58rnEFm71d-e*To!UQQh&${r!e+mynb25T!`*>%LZU&`Rt=bmTc$#{&n!$I5EYi@L zcr3+xzhN0(<`l*)c4YN@!Hra`(|f;lWQ%nkD2G-cA_ba5g0SnU!E7QK$fFQip%p9`6#J6^^vdO=E z*Rq7tGUDdIiw_=+z^4Ncdl()7oV`BTOl;xd%0zLd6GlV`+0y{_wkXvsec-6+^DP5h ztB=x}@6WbAZO3CRv3Z%shueR`Y-lsip9Q_NMxp<;4bcMOQfgkQV8FN67ghW&@q?nQ zY<5dAeNiZv*c|r6g2c^v3EZJX+ETj6V!5HA>m{a=cxDog?uz-wqgIIC<*vd5#?>_L zh#KBN6&u9^s%ckENlmCwilfdD(t4UsKqwNZBFxkk<3^iU_dfm=FM@T{e^-|I3HfVO z3yDK|ylpC0Ft;1pSlDhWWMRo|i%p*bmKvd053$s-7>dVI5A}`Y(}WBowLB;wxI3Kk zs2wb-0k1qF7u?Vu(&gifRI{9Uf!U8iAbvB?G^}Jc6bnN8)Do{2GfXmV_~*29 zG9a1W!gl@(&#VML-NTrLuQkutx)$|9RR%g^|DZY z`8XO6s6rE$!*v{5g66%Hg}wU6DNFCUA*-6SBvUpWj}hn5dLNTTkVC4aYpUn#C&bC{ zKnnu7p!ZW9eq3RGN%%lHj-*|6{L|-qy9cp&$8SR4+g&r1rH2L|=hS z+`%Dq;~~7(`fZq~s=G)x?zh@?xI`-vZ*g!9M`8$YHkTkh#I)W|PKLtn6Q|U@xgAHo zn`98Vn#Bhm9lP+)_VcuedbJ~kJe|0fXr@SF14fG5R%X0PV_z{&<@h^;kK96Rd$u@M^0EtL=?tbBGtDR-0kv^(f4w|6Q2s^E6 z0-?TC`kDg=q*|#OEB#dk13G_;8)7B$dlS@>1EfN^#j1-N~6x=^p z1+$8N5ap!9EJ)|a8j=*W5Pe9Zm8|rZ&r;2PudQYURX=21o99X8tfCoKcj0UYMYH-G z34XX2cu(UN|3T(WVLpG1U^>AXdH> zrJF-p`VQU)8l9o63h$cpWTS5ZOb;88r}uY%-~bn2)s_^>piJG-4+QV=NByczNSK=Zg}P)L+q{{SvV-D?=^(0 ze&8YUPF(jOyb)Mj)BnEPaRFAuX%fL%hu#? zUIRl<+|`ovq!oPv)eiM{pl}tog>amu6btbzPxs>Y_f6>bmTT{HLCL=BUDFhI0*Aq@ zb9T)GyF78(Qws)Krtn>$lPQCBPF*OZ>H`#mEz~RLm)wxIdOlZMAzlaY zyFoj%FuSx^M$Py3=aPaJ`JmfXEa0!d)r)=qG$^`Zec7D$+RZ8>EVt9gN{X^8!bBY#$9n3W!ge{~$UZa2;Q#CChe{_@YR()g$T@cp}! zQWKC=0_dTAhp{OYEAFTGEB}`!q0hS4qz-y=zcXXMrOT)_=OBKIL}9GzDWdjAniV0$ z4Koa0w^{VT{0&qmL`dH@%f>dTBLXiufP-`g=!5_tL2(*Exmk9YF?W>bw}DQGJS@BL zAe@Hu7NUCv36hUb(b}6pC9ue5OW9ESBI+A_8V5>KC1$m zg%2EF592oA7e{eMN8kJ~^pTHd>yJ{6j#8(OGBJ;HUJnZ~kASAf`qW41EYQjgNP5q4 zWiBK;7m^?XWpIEZI07b-q`GTQfU_svEYR;PryBUDy)37rMyDgWr$_~-JtC)rJsUke zr!#)1!^&s<4yRorXTM3$`W(*Idd_~4o~-7dZsw%OyRjuP|WwZV&x#dvk9)dTwV(@1$WTs$>9o=&xXWt0Q`6fF-4o zccRsMC;J~l2ihYGwIaJUB)gaEy@iMVA3xr0ZQRRz`Rn@eUNi5uPx(&63Mrr-`d|7V z5AJllMn~G5X76vj1bs$4iu%$HcnFgp0@Ang1v{M>&_} zA0fHlZX&;6qxIj{=iO^^r!g{%t^l(5}8Cf8Yp1@iqxrAHj~5m4u#r_-R5Vq1(Fcx zf75a-y)+pYYZ#h_iI+7`bs8LGAkps>W#Q-dO!d%RwR0yPc8Elc*s2kCxLD!sv^0d5rgYMHPmj z*{#I>w{IQj4SpaY{_D6t==tt%EOEQ@pP?Kw|6HLb=YyzX{W3Y7zB1J^q`pcLKTF!A zUB(Pq4U+mrRS@EN1m=f|s~&9=PWSHG8+yT7QHqSr_Sj$(m}T@W4w7RN@O!GI^JlNvI4N^ECx!9#~wKW=~@r_;BWe7ecH^>knU(fzX zBKigWF^TlRE*BVr32ar^$2S7^f)|bk|7P|O#^HBu(j#EVvLD~g2D~YGn zJS+2DtR7(c6Zh~fk9LtpKHJ=Gvbx-646cT%B(mrOnO?x+mykk6Kqe55(2b!vxr^x>g@tNxc> zWZwT1wcm2bnJPbL!J{4M;)%a9T`b(RB3~o?zft>BcS-Y>IkDOsQxU&zC;Z=9{fF8= zzn_qIFVO_R7Yy4+1&}jwM;%N%@OO2jX!tFXWJNkGlC`xu_L7aQ2(8lo3yiZYhdcJO zH5au4jFyTY%wo9TT#rz+AnWp!q*?th)V^&+S!pNCwyJLU$tGTUI&s&*b@Fq%rbk-*HQn zZuR;&TvhVlY15sc*Lgo&=jn2A{l)8M+7$lpX4Q86>3$O0;qy=_pzQ(_2CH=?h!YkDw`~FA@l4h-9dB1|Mc&edsu1+*;eYM0nd| zY^?SXCCL*wi!e#STRbPE!7Zk$-eT6FN!D}FAj7F!zhXLK7~K!3@F(6uGL^Wvq&g$o zFHPU&T;hIZT^rGV#Q8HO&1WMgnFS*nzjZ@LEWSkC<8vPud}nH%*1vBqI~$AVi0BzlyM)h5X#wI^1{N@k7Rip+OzC&Wr}2r)(5cw}>?y)8vT#2X(soy>26KMnX0eb@;UjeP zG9bu1XAmnaArQj=yccbwla6ejt)afjk)e5&R!L`f6Ze%H%2}$Gc+8gNa#g6P2WuX^ zpG{bEW-^H^)-5&oP!y(I5|A;ZRb8SK^NE`lO34V9|Myp|1aMmzUq8rQv536qEn&{D*>YJO%lVBO zcD={t~DwMlPF2NZ$l@`);XF-#UM`wt?8SeT*}sz}vBFH7)6xG|~Whw+6z zuD**%=XAr5>&b6l?|v!iFQWXP-1;R??c>zpScU|ue@emyn0(jyG5r0$aLZtB6RR$x zNrJX;{Q+X+f4-WqCoPVcN;sy@wwiD^@{aleUV#s+9e>#3nCoc|CGcGcD^u<}i1Il_ zL4*$9&z(p$Zd!S!$qN@5LyabD$!v8aJFGco7mVH3@B2COpfF zAP#Y$*}b~TV8(#-glg=hQej>zrH(DdDD8>W*5Zsb@PoW=nt8^?WGdwMDNO; zPtxqhT-*sYRV`)9@-uo|N8e5s$bINXyF)@_`tD~}_Yr+T$CUY}U8epAOR3DOxV!Xy zp?UWSZ`SMdqx32uS?}AnqwdI#BuP3-O_K&%36{o|BHP}_+4{_>GDq(tNmS4Io)_op zq>N+JJCCLQ3YXeivJ=bsQUTY8@#prK?P{*notkgI$kaceP2#0 zeV@+O;ahj@C)4f6fhdN0d{zGKVQK&bKLCPSXPB8VFuoI*--%w=iSefsbEXq(rxW|S z69>8L4Sp9cbr&9I*V_?cf3{8{gGA)IP&B7+2;ks7(N1D~G;DAv7A}Bn1b}_eMZVHS zvGa|Rx|@=-`;%BVl~OmgQ8$fKH!Y-_F24Kqk0b*=8X6dAXhuYmj!wGMt$+Vvc(eP9 z6*@C=j{{W?r&g%Gn;_Ebq00Z=#s51&|9>hnAhZ8xf*$`hK|lD5Uh)5#pig-Nq$PkU z2~QVF=dmZeCg^91)k;m;O6p$|^eR0z1V;(X3)N=BzXeJgPNq<~W6%cJlcWioUC%Ix zIb17rT73|# zPzH2;0H36?{eZM;*#Srr3mXBbf@YL~xbpO`3HnDm048D(9#H!e26&6uFeF)=*bwZW z8^$n}@G1O@$(QYL_OOt=NWM9@yl8>oSgJ^oOR1e0{uj0UIME6amY6yul>Ba(PCaV@rI$l zr4@Z}jH9xeIq9SFhP|+(issv)qsn$5=5bZ`9wUH2gtlc~hxspzS$6^hy*zaKvUjU? zSckv7VZp)Dx_&X>$Qrg9@XxwwA^7JM17Z%oA6iFrEs$H|P{cexxtQ~%f z$<~haPo}C9ZMl@K0~2-Syz31Kvwasn-N<<_jv-cc-#g9pi++;875hH~zmDw(=%YvM z2br?UY6h5ljvYoArk@-}IrhEc5D>lC0_F8ayGJukaS&b+Sr z8z}*6h@03l-{%ZJcitcwuRq@|IqC}BuZIf>Jp3m?|G3$x+y3vkHPN|{7OAjAP~6;ztBwhV=3t&JrjLHlV|fI$bbFCEc%A-F%dw1 zOaaFL$Msg@IG4)kAE|_h5N4hSFC0HFYo z@ePMIQ)Qk66ZP}4$GY1gf4mM3kt83RjF#NVAT#(9!SdlUCPX&>6Vc#+gvSrTM45Ez z&pd-tKQH4FM~rBALchyf)cneR%BL6jJ_Js5i2p51!>FqMoupIVMbk2q%!+6D%L0OU z{Rj<`RMJ2z4V$@ni~drLYa?k7o4@*q;oqOBx{klOf6M?4 zce-OYunIx_-^U!HH~>fwoh59AC0WH`84;eQdrM7Y?tQfm*YW#Xm!a@+&+h4rXXFE+ zqb3F4CBW-(-|?i5y^(6!oIh#42Q8o0c`>WN>rs>jGID9Y({~E62&~$ z*T+VZrcC9F@%jUvgjl1TBQ5$f(+pN+JH2VayV@a0+ z8q6(eO%kiz>DC0xl&IPt)3CVfV(Q*ExVCT9S9&p^e)sNkZB;5b*xfl?_2*`7#Y8C; zUTuPr>O|TwivMPDZ_#X>O0aU2JAy=Gu6)5wObs+<)ps3U!6jD>v3}Mj3CLL`Y`K3; zO<$m{E$aBTbJW~;CwQmW8Qx!l`ngT)qT9mt$P^p~KoSYD5C4{^?~?mubxh+_dy#1) z=9Q&?7w&2$e18CadZ*HGmK3WONdE49yZ?X~2?Z3HL&hE6W(!O`mN%N)WWBQ-S2oXd zpWoc;<{F1N*@PlQwtO{R=<%w*Ity+xF!*yn8532P-{lS%&{1yvM~d(^)jpC0NJ~m+|wV%o63u^A~3Al2q_Vp1ckuc{cAZ4ATsU z55rPYeOy0#BV^I!2Ii}fN+rM%mSqpEFRg#ayY-MPwW#u}MXN(EytLl_^6dGhLGM$^$mBWR|nrN>_Ci-(wj@CuMS$c!SG8KIuPA?G^J2x50uFh!J<;1-{lbk zKCCbTq(buW5jVb2{_NduRdvFK;tJEU>tD9(Zhwd+5*}d?LKKnJSwf`fp**%j8{(+I z{^e^*LhA1^U5J5RK<=!CRt+4qd|8Il^S#6I_w+wsxDF)>A=CI`!Hy}sXH1KH(JyQ? zbc3En1SH57q zp}TMW22<}{5w4&e3SdQZNDEL@r8-Oj2vNmw4{{qm*K&#ReQ@<^p#corsbUkWVJG{( z@Zk12$soaq-oFZz=w%Tn?HZ6V5b^x|T$~&5v1WQ*m=^+AVJ;}0+Ne-tP7|-;KIHOF ztSviiz5&CL&cH1@oB}pPXeSn8PT&^6X`L4Ep)qj74%;ghONbu8Kj3x##ciu9@M|!p zI><{XIVcttUAHK3Y7Z#yioN0Igm@k(1#|mw2ic!6cPb2&kP1>xW|V^ky67SEq2X*% zkkj`E&ErCiZmlsJgU!rBdN-WZVQyh?4#cSQARj3-Q91#MbLg!-wmK+?%FbP14;fJ( zNgNiq6=RVi9L7gaUQU4{hz2oNGtrWQB2pj=8wMiA25sr#18h6SEoCE-*CRPxU}2xVeoUav4V0S=7%YXh zb?&>L#5f;gQErDFE*Vs;VqM}8RxIW{|qbS4tMdxl-k#ZQa~u* ztAmq65xdZV--A+wt>o zp%w{6)#{DmUT?tirI(W_N?L*?y$g;+DS|elVL);1y{ZGP&3z{uLf+8hu()FfHZglL z0QSIdI}1YDB_j>1B14E=Ze3Iv-J9ZliCLGA$$0F+cwDcku&;v?|t6GXjL#)AJ#u`}que}Sp zU)G@s8t^_yF9nW}8LGQ9q-oH~5H}X5Fe}^wDJ(fbQyl}lIapoFUFpEi5H};aIT&bx zB+wW#!ecn^_ltHb$?(0u7hBG@n_G5vDAKnKMrpV9p-9>=GbLg_h+Up_mA{KxR7Xnk zeoW*CP{;%S(jKry}B!zoSvHCoP^mz`M1pjl$z3(-c?3 zkWOx%hDZS%EJ{O+Of!~(mba9Eg^y?3@+yzdgnC2y?!PiCG z7YISA#dz<}RhnChmep71YwcX=nUiw@(3(-pYQe}^!N}=hl+y=fA;!MR`tEjaCbR8P z;kDf8K?HG#3*JYl`h71Me{`qvtY!bvCNh4C(`%e=FYZX zrxh@f21*op(|Uxp%>Eu|f>?(}Aq}L9fFY9$7#qT9`kfIgb0+UKe#}EL*@&wg znI)Rgo))Z3)oe>J6ta;KO`pa1KBJJ{Et(N`8Z)e^DI@Du;p!56V;%t>Btn6gfRaoz zU2xm#78oDZQ(zi7U{CCa*96*PWD5cGOooNNJK~`*M!hLwp*a?jGNSEoX-I$R90)hz z0m{%!G#nH8&LRv!C&315oarL7l5x=^5C0zJ18e^489M{h zM2-jz9SrvpwywQ`YVgLo+(*s}2Q<1x4x7|`!A#(zkJYbA+%3x3rLXj|2#PBVl#(r0 zlTL_))g~1N%9w|Y03)oZOK6)N5jR?eutIX1i_*`nW5PhQCYh>iK&^Yo0UeG8dM%AU zq+h+R@E+3fUc>Hvjv7C34X9NZ;x|%~68Zpn!nF=H$2q0~0K|c|M0vSoFWhQQT1C^7SmJ{%uMPtyq&5WD{gR>!jWQ2~oF`w~`TRS?BYi4j% z4t?o}tlq~v@QD))Rs9D+DdTq;U6)2iK~p4=?1Z&lw0U84RQGnd#8Fk*QEm!qk!{%J zll%g;^*}3_=ho0P?=M1Bcu6&wedu}wx4THdmIER@>6P&$^X?sL!HDM!O z1SlTgsD{sWreRO=1Cn|Y-Z2EO!=1FQ6sDQTWX2jQy0XqnYX#Ndy-`srFj)p8IYkpt zLmfn@q4m2$4rs&;z>qlsm&COeOH^Ny0^35ljHqmaoW0KZ{SLTgh`bxT3v530Y01T_ zw8Fv$VLw#wqJ;CEzwt$Xc~vUOeXDS!K_iddJ7Tsnd+HryD#OU3`HmwZ~ z$jtUtYy>s5w&hmoR1AKqsxg;O36?aP60M8r?7VPKM|m!C$IRTZ3=fcw)R4{y8_J?& zjGq(iCTmZdU+vJoUFnX9^F+{;;Zvf87?}neDwLTL;J6$3Jtp>e7ObNJPEPLt%y$+k_Jb40n#riSwdDmT#yhN#U> zYWrcd%HoR2de_r#oz_g8$7as`ERl^XLc4r@tLn|O4}t4C?09Li_vBI+fpU&DcJfx7U*_+B55n z4a)f;pB@0-)y*@5N**TZeU53o1kp2o6S9GNtKD~^Gb*?Vm{tC>r#Sub`^?8r!*5SW zEWb~@TzrNe*KY02w_97)odmKTZo*$y>lO74-W?v%F6^nC?w+0;0>%7P4!7H;Hc!@W zUU%^hHT@aRmyB^P7KL4}xfN2=Z&%~&lHqbfH{W@zD&ver42|`CV=z@s2vs$zMJ|a@ z^(24oIS?t}jVTz8tt`1H5c+O?%R6zp{koeum7ufj4@`A)X^37s7`rJSe0M6Gb;@mH z%lq*xD)IXD816II4^uf^71kNYv6~_X^_3_2`_?6uvDy3^CGt!|v_cRC^HPcJQi{ne zX4EW~>!Vh~EOykgi2$!+&|cabBjZy=Fd@+DT5mJhrjf%I-{ML*TA$~|*-yw|QryiS zd)}i*y7eQyX`sY8DwT-^9onmJrNt4@m zJ{q#v7`L{vcOC0fWB zvccv;Isr>gboXY>*#WfnNSKEU~RR4Py4@&dv>W`%23X3P6`m7R) zLdS~yeS%G|mxzRk_Q8HFY!2?v z#HUH%%6WUqKd8imQ{GXrx}z8qCx~dy#q)Bw|I9FqqSIzf*mFn)r_t%Y;M2O~az*+y zx@R0vs&<`cN@nRid)%I^c0kE>U%VQ~O`uLz9_I!<1b54cR^00!x5jg4&P$K027t1o z9T5hBxS&^9CZcA^fk{?qQA)AA6PtXSo_oOSNbcJx4%K;A0QfBh)|QGx)bIWHQr3u+ zD47bn6C-wuqQl&9^xqjFxlw#OX4jLFncaRvbOphm@)Ir(^8RxS_lI4ErE#Z5rW|MB zFXES8e7zC&>Sll(*Kq3w@XM-I?I`=^*I%O~dq%ZmJa@8JqrCmCiVA%HjD9HyVzxQL zWySv)&B%+-B0K%y7|eH?6yE+bGbww7uLu7Aj)hYW^q$5^K~7wbV}?Iv;P2bAFg(DV zWopXJ2Q4d>Jr&K$#TylQw>D*fw)g8Lj;^gZ;eut6bEAs!|#m9}q{g67v8nsWX|{d5rWuwv6s6ApNziAbs3jfbb{P>dyZoYUHqUAjc^v+oCrAPJD=DUJ-Y+fh z8?vbUCFo&Mn9|;SR5SnlXjxm!ng%HDjq)fhSzHUVZ18ONJgUwz`CyCiMA&&!w%7aj z9fHIrV`9o19FxSp_fRjQ0Xowa`+la5R(k{5ahj`s7NLc!386|ahe-zV=Z#C+^`_VF z2rA&RxQ~(TvTWPGdRx))^>M$g7V*h;^BKp-rXsc>&CR9lW!Vj}u8%~v9PYyJ0qd<0 zIO_D=%lx;w3e58CDqhcU+vus$JTH0n`S{eiPQGq?m_wMU-Izk?7g5G|!APuWRxzwx zLoHm6E9!@wu8l|l69#fmm}my-Eq#IsZemy3yo=WZHtun?emR4?X?PLYdc0vG z+1YqhO77l>HTKe=?7W{T_=YPuYB?*j{IB6{Pvxosy$Z))?tgw8QLc9?aFb+ z#2p95Y(c!T280{}4iFmVl=;D$x~b&r_q!YgymA&Q)2Wv5u3fHWaiApH#=DSd6VU%u zWcvRMVb1_Ugwv-pUMn(RcMs*MB5LB*{CmING%5JpPG?Cg?F*ssfddF||zRLmZFo`t(Ol+7bm_3G2 zBX59(+h>0B^qR|~yN9V3DHRH#Sb&2b`7{>{h(-TXk$L>6#`#*239?Ws;8QM9nJrQ6 zwNR;VR<3YyF4je{RO{tasY#qI)2;~uOugn^2xrS}gDkan`Ba z%YBWH)KU1=x(#-TpyE~r1TAWP+;i2@K~``h8h-U5mARUv1S@^6mc?v?x!NogYcp|v zjVac|+Cp&_`8VMN+I4gFoqpC<#{8N~b8`)iz1B9)Et+e$bB!G+thS2$T3dpg)fM74 z4hbz&@>yjmWSC ztvasq&>m@K_EvoaGguGltzF2suUl`D)c(-YUW6*A8xZC#^fLL_hwFbe#4#1`LNsFu zqFb(l62p1p0Z$9d9|Z5WM$= z4GYF064zNLWd{Nz9upC)bpV`l0z={+Lcm8ypYc}n*Tq~{L;on~7Xl7KIue=Y4=7(v z++XF=4@_k~^`$6)BlY3bxyA%&mui zbsdPwjC*u!cDKCFJ6sr2c%lebKZ+-`AmHeLx7h_}F%eGtz@XJEGoiYC(@WNFeOzNS zSuUV0Jk{Pm{uWW8a0B8d@O__hyTijhC*ez&n?h~*G{}&jFiE26w|cu{W~F4oXE;n+ zQ$OmpPq{~@;69$vehnji+GmUIWm1~NK!AxBRf0UmzKl6lxUMqaZ%8Xt<2V)55gbX( zdIYw$yEM2OlOGR+F)B??7j?8Ai_knQ##UT4+-01cPYlujTrzIq=PdG>^IQtrbnUxa zB~g#%o2zEM%OUq62vzXd<{EeO+Sn#h+bmvadBW(4)&eArd+hOaJVu-uGL@@|ABg*g z4WSa;n5haJIgi`T2f}qubLqTK%roz1uDtL1;XHyKZypEklnC;0edH~p+_$OLA18qS zwhe{un(pFnW5*6p?%HpTl7yDVaRIZ&pKs2h)9+!G?GL-Ydn)N7=dr5d|9ttLw|@D) zz}KsH6@^X>I}WB9E)>54l!Vcc_z{YN!Jwe^ZNcZfrs+IExMnBTbp=qiqbIiWiKFwp zMYw*t^X+woN>RtUqu>FOP}-KzeUI?F_^#;^p?{WwxK>?hBAqK~T^~uA|4<5_VSXd3 z>wKa5MlL2&6Tn~QCmi`!fHWV5r`1ZG-(CIKiki;QbRPh&g_^msymDQ^Fv+Qe$Ml{EQK5|LKH?)VIvzwu{M|h@7=o7o|MNRQ9 z(L{FW-M=6{{6CUT#fk&;h{(;qF`C4*7+yGdB_V(0kBh*`pspjqY)_C{5kuG&QTp~b z1takQji88BhRHy_7R?}WWe~>vEqw(uA8dj%E zQL6*#gEF>MGxhz}Kq+w~K%fs2UFfsf>9f7=vqSE;$M1Kb?sw$ucM|J&R_eF=6J}ip zEi;pJ$?tdP>@SD4^?3A|?MV6rh$npLQ}+T{UeyFYLITAGAW8#4MgzgGf_%t8Nc=$P z6GXmh04_fOQK3gEKR^z<9*CBeLQ8LfE;lM4_y3}%`*R4xNfWnh;cc1j4vrg4$sbIu z8%+B%m_9R@u``(YHAq=4$N(T6%P)|{Ig}Uwoq+l~VERkEle8;)t0KOXB?+)G3?zD7 zQZ_SGzB5!D7Gyvl?8Y2yd^}V`Em34CVQMv0Xe48gNT)wir7+A^@`Tb@B4fz`G*KjN z8yVJLkm)!c?!X`Eq?T>xl%Gkj`gn;{^7HBQRO=F z7<>bNY?E4kYX)T@_dlNJU1r)SMCP@x%)K&WhxucF>&A}$j2+L6o$QRA=F9CND_CBB z?z*j&8I#1%B-h0{*XWZSU3J}Mf`3?LFp&(73O$(8V3+eAka)8 za!nwKParE#pcqd8ohML(z{urw`ch-hbrU)PudoOJVPK+s0gR0@iA^wxOEZbbHThP2 z@}2S|zVRf1^CV%=BvHa7alzz!fgfeWKm)a5%-tX6seW1PKr*huk2F7Nhx{rh00>e) zu?GOO&Od2_rf4Fk7!sx!3#ORrr<3?nE(*dHh6~%0J z2fiT@agwsn6%Qq*vM5WA-R=t~=MT7+a>)N4OD|f&oD#P?^a~OHZ90S9GKcNB)z%94 z^lv~0AIb_cV<(A1fS~^xzJ-(7WFFEl9BsbYgXzq19~EQi8OG5{y`C^KnTE2(TC?dA z?cs+1M7Ul#4w=S^)fTs_zsi_;mFpdTNSGh_MT7}^3~Q9|zy+h7%<6q;cFYe|!o$Jj zmhG*)9Q)&$qJ|$=Q#j40U-ijWU)f^(WGcwf?XWfdUVZYW9b=Kp4W~Y_Ls+fI|O|mAD>OhzhPlrcOsEf6zK(^vmQ_czL7xNguGRe+6*Ez3E2$(;4-iY z{TPh474nJkz7vg#03PKeN~*&GPpk zZK}=K18s)=9K(L5$8E}fmK`vxFx!>TVn4?Vk?$Zkm{yuT*GKR#eO?UXl39MdyvM7W zK|1X4ccw#$d0~o=^xxmQ-hNvpWetD-mR9w_8IQ{9<}8lNVS6P<6|J{RCD_nUL%7Wx>GgFbaK>}IC1HY24B zR|ub0Fxj^Jo%&Y+xLD%<+0*Gcvf)D&?#vU@7$)FZcwADbO?X!EbKA{|rEeQx(XgZKZZ#b4eZLWH z>+^7!Rq6BZIPWw3-&Kq4D>kz4EA;SGxi0hsFC~Au-S0p|obW@$%6#<=#}cN%))U^8km{aGIET>7=3uA}bQ3n82eC!uV3|twyvJd+ zmjYx~^%1f*{t$5&#>&No&q{=--JgU=$>zRI8u&xYcM)pvUKjxll8wKH8>D(nM%d`q z&1_K}uEm@~M26bO{<=g{ljiM@ne}nz+CwZN@-QU<%#6t6k{17Rs;@zR1RpQlyy}oB zvZV$@{)ZSz0*T|zoyW#R|kx-vb!+Jwpq3{@o+n|=u2K_!_@Zl;sjM@(%0&0@syGoge z_{~{ZTq1iKqi%duP%U^UZSy#VvyMdv>Sq{ph`UPPlcnREFP3+XQjF;m`~7wQ`?$x_ zRi-tsFj}b;eAMUhDhp6x66V)9Nbw^V>VZ`tGR^?7;dV;nxug|a=amkVSIXV?GLvXy zkOqq=y*7e+?PqL(X{Rvr2&%EzAlU&P2#xBnVmnrZ0)&${_!M%Z+&Fo8K( zl26IbrLIUM!Aw$)F(Q%grWhPqqO|V-K-h@*tu|Vs0ym%D!24WSaeN?3GbCxlXqiLu z8i$Qeow2S_F1H({7e{RhFJ8K-a2sV(N@0+rN}s6ITrEKbV9N2pav;Gpr1~;2AP@5` zQeeWSFy`M+>5SoTx1MsOXr$3b`s&N^y_tRrVXDTY{!Dk8EwxY`UYcXPEMbKp)5V;N zyn&bbzq9l!!%IF#pt8$-%f%UhH$x2GOq_tRaUxPH;mN%b4j^o0Nq5XSTINfiK(aCG zGc+byCHjqqK1|<7YtPF)8WmqAP`=CiPGeZ1X1*0&pxk4Xf9&oPJ zi>Ip}E{h~8%;Lu_nE^!iLuz9+iPJUXL=^$=xGA(=r@mk=wD}Rk+Z4Px3co%bLpXMm z03=W-W^X=cv6@GVgGIyNgoCFW4bko*Yxa1dFIV4=)div}DGcNwaT#-R>G_a5Y(mu2 zMC|2K6|QKthgYUP6&P5H_m|C_pU7rpm5d|b({o?+ZmznFJHU}{8z_luGsmrVWrMA1 z+1b4L!P>2Ed=3yoxW4$O&_y&a_8EcNPn7~yyq6LffZ^{|i;u|A%Z>gcOa%?F3_&ZX z{~mVoGydQ5x(|CpzXjBpyt@|BT%3VzdBV9=lLD$1+z`o#n-}GIv$58H|IZ#K7G)FcP1fOUnMvOppQBC4k@s%a=or!wlBgi&y0R1pzfwO zrtV)RG7U)307Ovw=05^9mR}}FPkjG1*NNC8ngwy0I7N=R z>Hso3`e@N6!zP6AuQTarC{<3~l>ofg^TKVQj~X81mM!?z@UM-cw%G6eKi*WllEcP3 z4~x)$ch&3239gI-dNVg06VdJ0g&ul7CE%`d0LM1R1ww~oF17>=2)`5ZGhgoWLAHeT z*&%o@;J@K{ZU~0BpxA|^M}vC`&>WfU^r3`}0SB)EkQfSA7zKc80{H$8fg#v1Wo3qE9e`v29S8%$*v!kpSS4F%G$6!e6(`$0^Y{Cj z&=|{fJ<8UNd)MzK*63eK z;pX3uoZP30RF8#(=h>$$!YY$JuH2SbO=W8}GF zTN3+a)Vrt9dHjJ|PY6rf5eKK>dX~CkXVqa*pn5c#hLpffxzo9%rg=i+)k5hD^jLNf z=*)Z|!XRiTy2R_}gz4$IXhM-Zi1!e-?hq1*OoDzma&W7KfJ8n{gpDa46|_HI{=2A5=FYG#A=E4q5u}AXjW| zJI(1}%MT`g^$Qr>6d+lEPOl!bjv1=fy=YJ}^TKcU5ST-SDQcReM|Bc<*n;P_lE;+` z+N&WzNXcWC&@%-!I373d-(DJO#`64@k+dp2ft4UszWl!w$r<{WV?-8C-Q*`gD_2fT+R`A09I|i=&z*DCs<6d zBWR2`F+vi}{Z=1p=x#WnSX@ss^c5(5q0DcwNJ`>rY3p`J;gz7T&N9@9NkHDXv`Yp+kcnO|jX%Dovxe-HQu z)s0-w&EF8Yx6`|vH>`#$(o~h04g})8_Ke4k)q?#(tU?c?e^qQ_L$X7P&TV@spjGpp zEBPTygiuBXuj?1xCCkfEjWbasl|JB2Q9=%ygHEwGikcIQ4fqk@5o?;#Chqv50n4Y?Bm+%7#yC-y z4RMS?DF@ z^cDJmV4{e)ITJawl$ZpcU$wdC2ddrlfNT0l13jd2Ge~o=;i4(hcSfyGJZThW5W!kI zZa@FR#W2WrPO79dvpMRPcr2ZH+#BWeayHKmrS$B556OogQ6W(F+>n9yo|T-^DSD_( zgVqJOHnz=i96zCH6o46Yk8=3LuTP=ssLp8pu5sD%%$d7J%6ndqO~vU;#Xg(B04gn( zV4#E_a%M1)U@xH@AYYAY`hgpGsEQ$>hpKFm@3)uaFX2lC_8n%k-rtW%X7F*T(xkGB z%8gHSG6`vIPU;ErElYNm3-eFWLna0VQYWLEfy+;bO)zLvrV7HN)XOc;{euIOAbO51 z^;n;XeYEaep>{|y{m3o=_rUGfOLOO&es5~}(gGsit^M%o!h$BC8<@}j?I8LYnnRpL zBAAcL*8H{J=2nhtrNqN28)Nt^k^Wl=V-g%+yik;gun=r6 zts6<_zeD*Px7jA1&gQ)O^{D9Y`4AZw+_ewG#WWgKot*tl+_DN8*ZN=tB}wGqMy!@n za!F?vLJOrk`||AU=6m}wH?)t!(f?2#g1XR$&k-Qtz$Tz;`9x?i53ofQqum1O>VsPf zT>z_^eG!Sa5r%bj5>@Y_O?;SVZBp%@#th5k)~%}GJ@L5s&fk4o=`P@qELYF&{RX{z zcZuChzQv3tIGuFaen>VEwikx{F^!$Lor-5*=rapdq5qz zJpxpGr3T1N^xcZfT?vZBVY{w)7S+hTpS=9IUp=v#+#X?kDnrm-sX6t{Ii1y+Uik)e zwXYt|8o}-P>isE2@sHorvb}c1(9A}3YzK_CXW}nf`n^Vq4FDxnuZn!0-%xN;P>xwR zm1QEF&WD+fs)QXV=h3mI78Cq_z+ZJR3-XCXwoBg}RQeNRGN==9tmaRZN64tnuHh@i z3@Xx!OqLR<^wO?7fPK0jN*)+utSfa;$+zSmZuGKD@EWQ<7FiF*@Z%n-9C3@;04|~? zl{i%EZzv}!b8lXQX&H2;H-a8-f?xK2nAfZ485>oa{>m`zI~FsZc`}4#_j|95oj%1w zjR!-J^qs$VTg{oMhx^~}c?52EO3AiBDS+xsK>Z2+O&8uJ3DDcGgU~7__6&JKJ-8s&#y zD--Va4n0`wSk(y@jERZclJu&`JQ!^ZrzZ``oy|^X%<8(Q*PT7hfUWHe{5}PwgK$Sd zl&JcC!L}Xm90I5YFiWhF34l!|$t6E$W9mzBTe~uuTkiM~v(rK9N3I5dF3QoN&)9!{ zdkv91Pf@J;Q=DYcJD`m-lm=~f(O*w>v`)4;qH(C%;_S_XA{H=Ih}9=LzZ>*^)#jFD zFp_-!A)sv}H#aRAtRwkvabIf*Z&$^kSLw&|QkAxzuh*P*u|LPa5cWv}$Ye0?VlLAq z@tQ|kKe3bwS)ZZITCjEkM^4h;%0L2Fn!W}&ZGxne!S^yK5+*P_-#Bl%Gw%g|9!iYB z5LeF$sa;rVTV3(Cj5-;_7LRsY6<0?db){zU&sPy$l~YvFJ-7j9iZ96ouYYTsc4J<; z&Cp2`&pIJl#%SMgM=7}_(Z<&rzlQz^VAjIr4(wPB9oNRdWE>d7)`w{kr%WV_KX(pd zn`y{(+ojlGN~76;lVvrM4~R-=O*H8e^>{u`y;i|k{#X~CZ#$UGr6ezK8G|rrK~&&z z|MDp|(oPl;o#e1~L{uf2;&t4hUXI)!2_9fM;EYkPmkEke5z9}juS&-w8?X9g`Ff;m zJ}Mgk-!vb{KB^Ou#dO*O#Cp0wphJvH3oH_jUQb;?Yy(2rv_AS-v%pz_fN~QCriq?} zoo}ZGJ^kgqHEZqDQlXtRc^eWwEol|runQ1P4kQR95M;?vKmZZ^)CIM)y+lO zI}+Q-)!xnFG}etO&U#)XEdb|2HY`3Kcl#)ygNN9dK~f(i4-rz2O@ zKSLaoTo@9#LDkto$F4rmQ1TH*hLtRtj|)D|r?E7a(e>Mjr}KNyAja06fwJvO`JL;r zd6gZm)IZ--pH)s1bcKRc5EL}FNV7if>THx9NsFsg`t0?*yowTJ(Iq8xcOr|o_2}8v zx=%X!T=|CDvoTZWhTFxvybcU0B4Ju9eyjdhK8J12Xm$KsZ1A%M?2PS0?NeJNQHIDh z9@{f&v1tW)oxwPDY8nkf7Iky9Ec0w=-xSa;T z6n{eAqDKiEP>m2r86JBfKg7ml#8NSM;|u?!DTrnK{u>`WB`+Jxr4W^`enlgbL95(= z+{}J35l@T08~^ZYB1gF<1l{j{n-qHg|A`UfFwdkCog(L}Ta*Z%D!pzZ zMtqzy)eF7upZg-#c6Zf&gW8{Eqh#MZtoCP6`ns&#f8Ofz-gnqL2G#FPM-#zEms2YD znkC>%!lTIb%1lMQ6*PgVWs7zQ6S>%uALZ`tcY0FzC0|-n{ET36lB#oB?zJc5(dM?9 zUcC25J+-3Ir_vrAszV#?|3!@afAq=gKw(T_1Y~MECWIWm^HStmM%=Di!g!2G;g2a8 zgsM7t078TS`&X_Z0AZ2H|0Jbq!a385;*^fWifnGnw@qU$kN!EVq`5$8Ba|iM-Aw)z#%&R|P=Pv+Z z<|~CCH!A75Eblrshdij1okIZujo5BPU~orK9<=QA6B|Zb5bLQKJBup&f2*HUQ!cNc({`CG znAcWXtyk7}8JwL{G-Yv_Rg4T$PSSShB9JpL{Et4lvX^_g91ZL!SJZsNy<)S7mBi@K zA+D-ryZAL*+jWtKXU%cl$xe>v1chit0DZ$%OY$rtY!q<6TB{fEu;Zc~l=lgwQ+(+S z8+TZSsLAns{`hN4U>{{d*Xx8USywPeBoM1uB8M?i&&R!VfJHkIL%B$AuHk=(5!X3J zum?iB+a!;`Dfc8&VBhtW)Y)^Qx$Qga)UE8#AJyPSkOwki`79xu4@RYu4HzO{{oC*N zOJ<%@H@wT|N-U~;CHVA;-cXBTBYdbHN>p>(Yq9Ns1HamJ)g$wp)s723n)-(~!0ek? zfDiIwyNM-M9LrwuOjSAEA1-rNS(8~xzVJ9scJmNfUh$C;@iWO6cH7x4nijUb5+juv zlQjqx={LEak})?PXD9b-y$oj_7A4y+fB$}ILIE2+(Dsr#j%_1x{w&exZ}U9s_+Ny* zRajeLqi!1l!L3D$mEy%)+$mn%o#O5i+%-7GU5dNAyF+l7;$GU~(B`E7T6^!c&$&4F zxy>`@_s#K+fgCtYxR}fgp^&=%v^1n<9fdaaS zMB4o*ajc4%MLX!HY4mRz>Qv~5jIqIO;uLpImc?1`5RKbJsFtDOgj19--~T2?Lic>g zJlm;M=M>#CzoGxeAEN%n8fA!NN<7RvLYEllH@vaEy5}K0X$_4w3pFJ>1z!t-* zAkv1Oh_Hp%#RVXl{Ub)6ala!2d8e=-fRsUERY16Y5fzB?v#iv7Vv@d@CMA4gr`eE{ z_8*hNgi@+%atY1hdyNcP&2RH5l?OEM%=zSWmm8Skok9V?SEvXKd#}6Hk=VfHs0Jh^ z>BABhlriP<24Z39s$M1Rh@a#w6ge^`VM9k;%{tR|F0NTyNXI5ALR2u-QGF(DmX&_v#`#;18 zqfbZ`3_wYW@gHJj*v^8hQ)kBge-k5fvdc|h!FDzpo$KstVve=3AUktXz4e*pmgeD0 zdvKQC_SJH0H|WYSj8uOQ+oNUB$==1jU-us|a;*X1p}I%USc!k3WG ze`$6vMc|ZPI2&;1nvWo4^@%7G8o}-M?NzsxBv0mCyt`Y`J0WXHC0Y`v)ZdYpaAG9d zc|tYvBG=j&8zEnuJSJ=y@-91C5pGgYT2!vOf3emT1(C;wHHI%to@w2$ukZ;nshi}y zQ*JM;?;Ga|4f<(o!J`+dMaRu7s$n~-N;)I;ceo*^+up%rwoGH@qi*zfZKoK4v8LhL zmd5sVi z9cNTi8N_}aT)Bt;Q3z~m9kgt_A-08!;x*QYgj13IZSO`Hq@pI^C)o+4TJ9H?6HRhl22F z1^*}&_HH~SL*`kvIL-1=%@ZwYpY={4j;9+UW2KDON;^eV3CG=XHEP)Gq$0Tae(Q%8 zUx#|Cb5zl>;Az1_hw0C&->F%De#A#~sRIqw21s+SA`O}OJ#*bs2OlrKqWCR+|KNpy zp9}vj($NnVKv&kwaU71{#hl_V%evgFlv1Cw{+`uk4;aNsUYg&vaqex%cJ5V~mY)gN z&hyG|gNIpqZ@AOMbAUSF9?~svoQ30i;*qzNByvI@j8B23{Lbs{}#lN=vS!ZE5j8jF%f;TWya#{!!PQmt!y`E z=$Q}@BGwl=8Wh2<>Zh!#8=w|jRD-`metM@qKpxVW?K&_?`e~4{A4`9LkxUHNZD3(g zbjYT=xuPn(aey74ZM&|$CP`pGFN}q`>QJB;7Q`gLjz7q2R#W8q>1Kn!HhO@oNvQi- zj52vpgobHAjj=|6FPb#0!?sGZt-T={#EUc}Em)NvjDEu;5l!8tgp1-fHrQ|$`kd5} zA2OuO$(*s*k(|{QIoPgd1+wDhZj0v6j}}!)98i_B^bHtoKX)IfBx{7?@Fdalukd6Sd{bEIKcIk%m#boQ{L-TP!d$pRau zsKz0H9g?(Ds5mN;=t+o2=%{D%s8`XbchjiP(5UaCv=0)JC}pTWTq3eM8bmWD%o{4a zN(6SYW_b@-F@G;*Qf_TQ=@KEW1&;y$@0S& zq4IrG@?)j43{x{S^0Nn1v-s0c8U-klg8u-0IA^<7Q5B#;t}Aq!f1t5E{bTuy+@yH7 z(nF~1>h$)(^v=yRY!_+fJO0cb&CEXM%z?zrq5RCYo8tE3^zov?Nzu${lj7;n%-NLU zNmbtfDaccgS6jYyl}3qQmZ<`e(*5;g@6hmqK+jd^?0xd=W|q=o`Rl;wxepxJ9A zeuE9J_Zn(WXlnzjtGZoZl>1G26*NML$FgCSh#QcduWn(*zyCy=@r!J?St zqPWJQsJXhh{i1~5q9l0nbC|kp%A)MBy72G2AJ>i*|`Y_dnhg-lcLG z4R!F6df1Xy%93{Rl1}rI?(mY{(vtq+lELlL7tpdH!Lm`cMj1fEZn9QYV_C#zX-E~B zbF0=oMU!qmuyPE5(6)>T1=t^I+TAYO!QGX2|%#hYQ8hwYhM4%EeB#Ev%PyTj23( zcQ!)WQ25Wo{n7W%c%^`zKX(sn=Z3R}-2sn}w*uq7g+p!-+6aCr*jDrE?onCEUV zs^WuD7`7CoAoLACN*^MChHw=TQxKj%0VY`OL1=SVsiK)m9=^qVs5mi+`S%10NupZJMt{2)R0?x7Dw$;?=qRLdgLoHW#FyciJb_NIiy*yS^7 zhDol@QMzqK23@Ab!1z&?{luw7Hu&iCajxg<`BC{Cbt+N%C{+BD{4i`rhJtX`%#(r` z#we@8Bv}%;JcVEOv^Y~Y)4Dj_;pu&8zB@@p>9>-ovx?Fdo3qN|5t!^*RpD|)MPfdi>L!>fnE{h*otVF;KCY1c znx@^)ZkS>DP1ZQeiD>USBk@DuZB`nV?FN;@vARDV`rMzu{WFKR1h7j(=`fEpdE-m~K0F z_gf1&_d9mtiaif2xv={O`?OjAhx5`M;U}639REMRN8?3a?tNx^A0N;2{s10&@8R4! zNMaY^zEu>)RcHSe)qwEYJR-dQ$~|p02bpKAAKUvHH_j8pYzK_iN`QuPy#J1-l`e)q zArZ!6_8r530hf42Ih?Dg0AQCcPIjdnA^1{&0}GLnpd@jINXHbsc5EA>;8uYsF;l%R zB_5{v_%ljzhzh@%VVF_%YqaLnH{w>_5!PV1stl9*&B}jJm{?>PfbkfLFh75tpJ!Jg z#pT$j;GJ{4KPC+&%HyaQ`g}sDU=bDGxQqn9%U2JKE#mdS+Td~4kaR%_I-c@zMVDVm zxtO#J((fl!6MrR_;2+Ym29aI1|4ONgDQ33(JgK|>E46K^nAKi25I9!vb6`tD6Y+k^ zM0h@ZNU-E%(zv`C|L^pC(*a^SolgMV@m%Q3iB{!DTo0dk01d6=|2&zo&!&%gZZKPK%onKwxcDs-@1`en{!-#M+GaU1L60wN>=-BwsF9CFs^lle$88 zk)o*?KK8LTC6!-=nKZXFc3_*o7|I;;UG}d{&bb+hPB;HbJrq>s zmM5@vqI%!4JnaB(jW)Ql;lYcd9I+ae+y0e#-*qyb%Z5d{Ay%{8O4?mby+f+MvA5h^ zV^8CEo3-;8o;hJqL#KDP*?rgCzqxe|rnNIbS6Ugs&2XY`Ru&T` zufI>l)1TvO?TT`)-L1Jio?!nmsnG5_z0zZyGW=jy+_lQ=x;EkShaI9IfAlfyamvcQ zSapr@0Hdu9HiFp}q_vg3%=2S;nqQHL;wPqMt#|w^&)x4Wz;qynXCKtTo}qw^|Aco3 zFt^>=Ux?#(LM-=$jK{@UgmS6QkJHxn@DVRj%UX+3Tyx+}DtoF*w~Yo*#!{_2SB1Hd zt=eqI5_TN8hL-t=^Z99|54)ufv^yCvzZ?)w7(#qFgly7x147ETHV;``$f7ID z`oLmlsn$G?Y5%+Rw90-Ua0Af=`RJRW4}vWR*T&@^j_8zbOJpeNdb-0|%P{-sk5`{C zumAqG{md9BpG;+F9JM8DEPL1`%TufR_dGd=`DcVy_8y+)uVJoS=N@;mJ;FTC^so;{ z##t{13@{}=OO>u3i;!oB8wWT0adK?gqXaF|8#M5;GC1F{McF_BX+Cu&G4eK3`b&pXfHbi!aEPglVcpU)n_;Vr>X z`e15LUyA$?kukRft|dGsr(7vYpsUITA>mDs;z-qKmZn08FHP5HtYmhV8lL&#RIFik?Vz$qC^R7NArjcy;EeTmrXi*)SENUVdh-yS3w=oG#w?by*8qXYpfHpfnc$I;4!P}Cv! z90xkaS`(b>eOq;(A77cEt4~65K-r z{cF@PmyMkK#{7eL{fF5h$eyUhb&xY2tP3sl02yNlLtq|6D^nZ21jgW>u?t~(@6W^s z0kUHOS0m1}Fwu#lnfM~l?jwpRA>wOMsoGA|e9iJaDmfDa#Ok;LX!)@B*SQwDsI$6!-qbogtQ&G@t)`XFD5|$tMvMB)$eW?k! zV4g8AEqcqz^w>N1xQ*3x3V_$2qu^g7ZVbf4Hx{U0J;L7Z#&LS`WQ@i%t++V5XN(hv zQvlHBEo0K(r13<66D++aAsHVbU}&mWkELS*E*z0@{3=Z><>apL8TH*MfAuvaf)ckn zKk*x&JmTCED;`xF_$oj?0}VKr902j>c>_6zd7%0nX0x?xSCet;zhckOr&Q`ENn%;oghpKa+Ag!XOiuD502bZexMGHYrEGp35nfc<>; zvY5=Zw7lO!)R|evD6xD*_G>8N^JQVY{NdX42@;U-FfSgo$oP#1M@AB_af^saPj|9* z%<4LRMLunLwA|fth}fH)m0i@z6G**`v5HP^JVS}tX|_K@j@;*{%EgHAvcNLWY?<-o zIHSl56s+aQs1F&*WekBh_Z}VTDKM`xNM@N-bJhn~sz$I^LOx14rf52(JavND6)Mqqg=!j%)z0-W!l*(P{}d{(XXh|_9Ab`Ztzd>_o1i5YucwzrC2 zQ66tf^o^$uotZdVsSVxK10fGLi_RO}whp-v=Ixu%hZdI~-&K)*qgjbr5kEavSyCDk zGafUs&K-Ui*RkTmU20b{8fKS~{y-Q<19A&0$V@~ogr0#-)6?tu%6r@6UkIxvQqi)F z8cpfpmLvZj%LIqX3aSSo=P-8yGpyoW{@`@9@ij~zn`9qe$R=8wk3ic=M5!lNfDb{L zS4GmaQF8DDgjok&kS~e$P2R6@f8?mVF>^RTm{=D_D^ z6+I;Zt&$Qs4uE!c9R772tvaE!O&L=wt#KC(t-7wfd>j)<*~Ld%%>oC)0x_1IQ1POW zL6I1sw8nV`QCPVBm*zs`LVh^EA3KuLLJ|IN%lmh^-FHLiX(yWGL?E z^EWmruH6618=36qiAAsDbY_Va+=h9uo*2e35JwB4>dHywO%7^nO&Eg&cSLQxfs~CU zMV(~JtYveoWrs5iXmAgOwboVn49R24@?4juNlOv#ZblTgB-u7(OO>`G)Bt^{lYtO>%5Qk&A z5Q{EhANf|NTMcjD!p1k>B4ICl5Wz9;s`y;3^oXj_xUQIRsn%%u@$?IXAJQSN8RI)4 zsal;GYWxZ|$NZJzxw*-$$V9a#Xf^R|3dmY{ucbO()0Nf6Xk8M)AB~e;U6USMwccE{ z)So*-!X`Uoay283A3q0`RSrSPrstXQ=I#)7l{ofRvdt%{r#z;ZYd9D#A zBd4!OGdgt=D0WA1*O5<-Mrgpjp@8@-^bu>lgp4D*{-N{?Zsk9zhB8FNFif|uB_YlT zOPXju!U_kXGi8J{jRS5Yiv0ek7~KcLV2jA=5`6`*qzz=)W|t&-&pHpgWvV%Ko>9S* z$-boMA+kq4g^|St7gkcY;Jd)IkR>i-w7b)O+97f8#)J{dh!a`!pSc-n$pn0(wXjzLqqQ+7+08q+7qF1m zg70mTvCPXfApjraB%w0#3oZOM45{peB7=2-3goX5_%WTsOjI&uh z{k3fC?`-z(cgRP~-`i^wSgoVx?i!qSlwo;i8=>SO#==3?T)XKYKA?&6$RqZ@#0?-MycYKIlYlMt7c8PoiJw;cH$nlqj@?MUv!iq+C3-YiN z*4A{{uK51?h(jK_{N5i+lfL!*ebm$L{Ybi1XY*B5O|9Pw3xr3LpdJIm@U_RwHIkOq zH-rWcSmp|vp6KwBcukPJ9ZI)XmuPq8TlT$enFg&cWb7D+Q)?vZxY$1sD{Yq6NO-n1(iZo!w4zG%ou)R|oST$Af~KR#0{Z6k)-b^R$I|Hw zvtf{gQ!@7~H-*NL=3zmqQ|(}@eXIHO=2|lO8u9Xc&-PCFvUBW+Wd58t0S>IVG{A+C%T}fy4syd_43O0%I zLF?ZIM`!n>@)=7UYU2!riLANgP;H@?f$Ga`hblr2yWY{o73unsyW3^GT6Bd&IMlYJZ|sZy!pjDk$X2b6D;<9 zC&~OY{o7iiY$-sb56)ip@@TSeVbI&Xef?Q_!)xEJF`(AIT1rD@erM7SdWzD-!L+*E z%)ZdEX&`sLcI|Tftc4Ejky69VHH9DjNcAoK5s}i*y4s(*tZQU!&-L+Z*e!YB-sdin zFLFzocURD`(s zPd&jc6iXAOT35YzS!i3&nHEqeer_k7+xTP09_Rk1*5GIF&dux&Ic%zX2L_Ld{0D`h zkVselE*6eOE*wg%vL_KmfJG={6o`O`L(1db2K`z%`juA1``Tz|3?-RD5}lGy)l51a z(`JS_Qq_DqUdVYJ)0)FVI)RGs%gOjpL_BKwoR7w9A4|pyWXk`>c;UTQs$ezHoqpp+ zJ)5RkuX(%9bqM)jda?RW0u}nMBMsZUBY8!IuFH?@@sL#e+HfEc<1Ke~`j4IAU_1_g zvNs3YdN@8uaT1p1FQ84E(iCU^1R^r4`vi}Qu#2H-G3^E-A<5(iBay5+ ziDP|OWFJK0$E+X1;NpBW^onWsdhnH``l}Hlt*-0g*QN(`2;?49^#};=FJHwm!J7$V zxY9$)LsVh#tsIGuo6Fd{Xg8Np%*YFN>DR3XbE9Ddk8+rx zYf(ygT2eVsL$e?()y(LX=o^vPpB&1cQV^Py#ZV+UVJec(WcbRGI0}n%(yz>$R3u{2 z!qXAy51Q1JL_l2XD$=wX96%)A=0yk)H*g7{j}-_2niMx{=s3m_EQRZ*+-m4K+H+~@ z1avpA8U-nEz0*_zYfu{IErC}7*q$l6nuX-<1r~Y5?#p%{O7VOt##g)e2w%Kt3Bji0 z!-P6!8MI%#_6dwq4K9W~QoWB4TX+2LmsSh|&OzEn-dMSoySG{m=!E2=W|V^TB6!Tf zld`E7TcEKCWU^r&(xd5fS;sUY;Mjft4~2<@ccg<#2;MBGh4|_0#}-noT@U5?y*S&1 zwY;&OOxnr-6ogSgep{(IoVXaEn0UDkbl%>X7_+ghuTDAUbh&;}p_75@Kpuy9ZD5KJ{(PJ%iXFk3Q;X2d ziyapS=NFrXVh$|$H-30j1UHOV0{@F*u;kEpfC_3RMa4+40)FhY6psX>=3JE4&^N&6 z2nkmAdWhO))_uNbKXd9_jHQGr3H72dTgzPRm};RF0M4m|QsFxfnNr-gjdIjn#0Hp= z6F)M1ReuwNY34aZNzg7M#r-kxGfn=T!yP{l`utbi_8=0Z`A9kU`J_Cg;-N(z*$}I1 zpEpCh#NuAK;x+RrwV~$Bj@lFZOAWz^WN$yIzn>)C`~+yj2xBz+Cr?>OM{P%Vh2(^Y zpdOe3REBpVJ|kJE;$<%V2Zgbo4x{17TKs6OcV`9O9ga)M8zq3A{hs2U971dIuRuZzCjhn9)c zR?Ni+Hx*FCT1oSutH$}e710w|%PLgNC)6w!vxHfHHkDP){C1Ozp@Bp%ZOkhCxbRP& zLc-KPo_&<8FL^nne3_<>z^-AVNYJM|KCE7`tyHecg{qlmqfutVRbc>P(i-N+txe^s zG7~!2oa5JQZn>?r^E=ng;^!(qx{9kswSmi1Rw!%s;@m3=KmDCpnZwisR47X-q5YGm zw0I0~62U%&S|^OzSTv*&pjzN`>KMDHHs;;hS$z`Fol8w^D&?}bQR&oOYJuOQMh>(2 zf7kvePx0BuW5&0|b^G2-S?nii6*9T@y<@qpO7hA%B}@N^^}Y>sdilw%b7KQ8Pgxmu zfXh=1uCCy1<8s|42huMH2W*5oaARrbKY5B4*B$|?*P-5*r%Ha#aE)%-M&Bd5By5oy8=L?GsKO3ELSbB)=V=3JYAc5Y2sgGu;ZYGS58_v;PM#?-tlBrrGae(Zxwl=G!uM;l z0myFoAR#M}m5eEi?GJ0~T~<;YngNb~C8PHR68P^m3HpcsD=Ol+zL0}_TPjHopL?z^ z7E9fhYvkBy+CI&D(6RlPmv5C?SzrFMxRYUdZt_!eeW`*NR44tx&V*=Vb@cxg6(PSc zqP|<|sb2RW@UwOB@JVm)(Jev?X0^%N!!JY~ZeNIn-&JRA{rKY1wZ-D-`Jbo=Pxr0g z55MEA9oU^m-!sb(m|D@sX8&?2;N~8~$Zlf;C!&q|JH}NogDK@4djx>J$Jy0sbDtdk zHA9lZB{6>UfL8i(TqD;dwRZE6CE{_6EBB{WLi=z7*mDTn^P870gL0R9M0DsKz!|bn zCMoSbpVH%2!n1X%6yd#CEDWxIqcEC8GMtGjT-j-{$A&1KZw{Xgh;Y(QqNtC;`|Afu;nWDb=hl zH69aM6rpE~wP7G=R3FCnNeGYk$tMx-xwPDyQXaoEm0s_q*4*1#55Egz5uX*dFV{e? zu7QAeUbTAvq9R1OjvR)@!p>i=N2UFLrS$q9@$5X#M)=!JA zo_BUgTPCYmhrjJV9ZLs1E%o}}8H(&zDoff0^!w?C?EJk?BmR=2Z@iN!PL62Z3&8I~ zpbw9?gd;9QEs#rtci`N+7el_E z0N*C3+nXV#p&CI633(bxLf`OdCL#e2@y|`HuIxj! zn}e#!lGt`(uD_d&T-)d~ zxQaE=cP!&({1(_nT+~QaB$`vjqBSK3A{)yyo48S1AjdtZ7UZ*^d6)vN)OlF)in{ zSl2wutLIT`DC66VG&Q|AH3R2hZl<6} z({uRK^EA^7oYON+Q{r_IK{5)9q0=k))4?*b!-69tLkgx(m2?>LuUtP+3x>gzaN+Wl znLW;#eTkU^^_fGnnIpFurIXMTIAvoMrb-D>^n}Y(6!+YuNYv|wr>3uO-uvVC{ECwM z@~q&%Deh`Id*?QLA3FPx{J-QWT}dWwN%=$F&o{F$-&s-hv@t!>pPW#?C}z?aIda<% zUy>$HgQ2J?P_$wwdNUMb7>c>1j28P(EwjuVKDY^eMLS2u+4zGQim0KYvnL&dEAlX3 zFVoph7!5MzttIJJAtgs9+fpGvoO^paM>#$B?ox#cq)JUNPo*(WZ7@&sXO3JW+$>?< z%xRuca-PXvmAP8QU_+>Lu8#n;pv*X%C%^{k@MMVXYv&&7+f&FTgx z^+Iq<(xJMPYLz~zI%rZKY#mhF$%eKRsR$R!Y#K>$K z%Z}tUsJMY3T!1qRstfsw8}0u@VOG3SR=kT>e41B$hgbZTR{RgOJP9Di&}1#pO7LwF zS|6(^@oF*WYIyTEOc_)xTtMVfpe$zDYIM$OOtE(C;cD#dY8+@So?tD3cI_+ITB77y zlEzxH`C1AA1Y{K+wj~=;tRobxeUZ49xwJ+QwidRvmZzbjfUsT=mi|9YGyjFxr~m+{ zFaQV@9}u43AB>8_C_m;@Fc^;eRyGE1ni-BFX0w?Zb1oc>Bkq5BBjb`4Xt|M##{Qn& zd?J-Wqb3IJ_n~|itNBq?dD78zF0bF!%XlNhTpnN2i28(E`9g_uo^0&@KVFkdizW&H zAOk1>V?M1{UpfO}cT1B*wFbRGfA(mrR_b<#+=+hJUl2JTj`?C3wp8(Q91aG3!pYs# z;yjqkRB%kqe)?%MTWk<*@kgh{2pQ;@&^{;t%@OWFM0>0Fl6WmW7>gpts?YaZbSCL- zT2J=V@000L%i5kl9quPP^&zlYRzOFeG;kV2)bQ{8FS>6kJY2bOEi2d7)A(ZagCgEh? zWcDC*4P_?L@1uzKBR|&g7DoRBQ7Iex+n7Un(WjI8Y12WP3-k0UN zGoF z99914dAXVdAlfE4XH&WP|N6{;@|J9305ifxb`Vnpeyqk)gX?CnP3?XTkXj1Xk5C3M zy9^g3(Dc0rroizUV41JW1Y-R~!_I57Y7-GTJbZ`H*F5aS@LWCYU;(-|TykVof4)!8`!;cu?Q!*ZoFBpZbW)V& z@N}AWT>W%b)q3@GUiUxon&+#o`>X$r*YtKEAX3)){+eQo_x(L34(s}jC}SveyKEW% z=MHMSBXmFM^H%s_E=lCi{YiYDKOCZ|{rh}T`L_L4l8EYfe}?1ViNDW-doUOvR1yY! zhytKP13@%!y-ZmjGLSt8$IJ+cR3=di6^RhBJ|Do&fQ#j#44|0W1xdDjdhO31N={~s zF4s1ISAiSKCh-nahgY0vUOAjMrU2WqO`P-z8Y*gMj0>~n9U}X64H3cr_Bygnf|~AY zq_UgID<57-8qJ@Ps&-Ta%~q1ECeG0+NT!5?tCAo6>tlfBxg;yRfxxP{Si8`D(zR77 z{t1;>kE$;e=fu(iPxbME*`|~~AEZB#BqoF`n!bDGB_m0f2yaQ!P}B1TBI^hGTWKrO zl9llNePko7gM=|if1Xgy{FPiLU(BdAKB3w1k#HpX|H5lL#wWj2)WkVp(y>RpmzN|| zOLvke`S4gKZ^FuvG3Zvpne}$tqVdr}q@>6l}bPr(tJ5+O}OobGK< zuVT1MatkDk<>)9?UXP6j^96$xS}0!igwaA2gi*rT{m#OoCo^ zE=u?28}W3R6wkz5ocB%PD;5BMtPzsvO~I?I#camy_Y>ZK_x@L#=)drqaz&2{XztTZ z>3`!j8$mZ^G71%{X%mYj{7VJYk|89iAtD+#j>)}s!-}mFOEuoNm7FXU+M}||4Vkx9 zRykX0D-+8t9k;<0BW_BwA}i9=3P^nLN(kpqq{71*IXA{ZD$E* zreN!LEp5}6l3a2tirdY_UR$=d5ptV*B=>Da#nmoplbc8UX{jBtHEyMPI@_AfjeUQZ zU0Nr%u1N0Ncd=?c;do7uG90f_U{m$VQtkBCY}<~l^*v^a`L%xE^DtejvoyK$_ety9 z^5KQ!;TwJE{CyuPU5!7{)Go3>TN*63E_7k?3qtQoAKFY^xZLwDw$H;Ldjw7khC z@+$l&Q5U5F=Rx3YB33$41Pf+^uXOoRI7HjD{1cC(DWDf5@!JRjwCPzPF5OPe#Ox?!J>FV4UrmU_y9^q{wHyuBfAVlKz z76PM@oM+!4p|?-Kp4Cr?tmG%BE?y`fElyJUvsFHtYRySGG*v}2o$78pEhC#tfk^5Q znSW4XSz7^WgA9T`(eJKUuLi|GznqifBEZw|-1T_Z%3rCTk*8!pxeLlcq&Qg{JT-xh zUk&U8_xEOtYfj?nC-*r+`4Kz`Wm218;1rB;&81&63%cOBKMv6f0H>|bw%qm$#~=}^ zB{C~-KW4aE<|yzQMDJ8^>h!#~OSA&c<9p|9!EQPe=y2a}(2wba)Cv3nn{gdv`+F$A zKR|@P0tPztMH(gXZ($vNs9>@^#84)iM4=xj<2pM-_~A46SCQWaW#*!Z-%}X*m*JM)9uqkV{=Pqme(E$;5U)Xv8!zTRevbZ3KHK!D~ z$dq91MEUYZBENe(+8_`a+KrG=<8z5KgLV?oJ8C5D9(?aJPh_=>jJ?~3)~#g_G>SP2 zz?LxbttRx!|&TWAyQC+ZFgO{(*P3rwyRPY zJnSJHGJzRf&UVs(j28FDQFonDCqWqx9y%WmPX}=iU#un59su?aQ4i3AI+iD*t*DDY zo$rEl(1lr$G?DF_bT{&cFrzk$w+~)V$Cif27#fz~vNVruC&a2!+x&10sf2K%Yah&F ze~<^@Zq(-;s+~0|TFoeCLZ3TUz6X%kGi1ax@*xz~9Pk5n4XL3FvL80Ju>9;rWaGvi zbVuhU;T~jQe_pp#L?#Mi-JbMo+7wrFO=b4Y?(x{WO+f9YP@E7bEGM_mK0*4 zhoGFA>FJoY6sZRZVqdf3)Jb#a)049{sI&#i^%)lD8Nm@0fYKBmUTRq(+y7Jk2tYy}W zYhy}U*^MjTv^eCt0}%6Fa=j1>HM8(R7P&2{=AS+L(n7E$t$dKpk#NmJTTLBMuKBEKZ&dy&#Zluy9d)zmoJXsNr=|qF>TaQIe)LBDFvQ>uVU+^ zKBt*3C7K+j15Sj5DuiXSM!M~MPTS|pN6J(_EVp@nRFAaMnHpC{3{2b@&m&vPaekA( ztCLThS%AB&9=V!JMpE!O%#@O`;BA;9a5uF(#freD09aAL`t+?`0ss{KhDVG0(Yp}S z{38#4;T!WpEXmg*XN6UGMH~}_1m;E3jD<4jDw1b~6iY>j&W`6l(JC9iF?*Y_XBO*v z%e`0^DO41BA(rrG77}U{37qkpFbd#`02u>fToU*3nxp z^=EXle^OVR(Bys+_>5khNT3piUSthB6R=$`gFKZc@|Uj@l?HjMgEQ3)Nd#pligNhn z65z=nu9Bvt(u+^!WtkPNbQRU6Sgchcd4a*10Pq{tGA!3_dsO3{59}4 zQPb`Fqs*GKj+%@0nyaT8c0vH1IDI-|?VWe+gN>jEB_nO4>f=)_fV8e@kRk^cy@FjF zm{o_~S(ihJTi#fQOIrV0pdMeZp3tYB*tQ<|K!n}w6U9b7<#Rn1X#`&|;z2Vny0?kFTk}(ZZjl z2E%W45omSOYjyW&_3%-1=xpVw#PEM^?aRk7;%W=kYYX>jgXpORVrctrv=KeGCNQ;m z3bZHdwWs>DyFa(49k*p;)PJqSXaRKG&?wcaca->al>G;RVNYGO% zn(S!H>g?$3?AnmMxltvi>l}ElWlOs{%KX*-$cF!<%Lj}5*^}1K( zy4QWWH?q1npS!nVq&-^#J-eOV6O*dnkktH1bq6V0`T)#*4|07dWPPZDeSdBHu)F%u^!sqD`rL~hbtOA*4|_;9YpzML zfX3LUr~{~wKp^e_HS++i;J|Le0G00mP1OLC-2h|E0Q=McyZj)d-5|%y03Y)pE7_nB zCN>N6;CsOV{+B_?sX=k(A$Gd~AOiM?5hhTyv!kwGGrQ&&4eq!RHqZ$Bm=bUdpQ^nK z8_SPa2##3kk68PTm~4*Ny^PqBjXE&HA1b5n`lFumqu#!wJ})CD*Tb}Sp9Y(GHg*k`bOZ1c@A!rYQ%PE}N4BL+=&Y)-=krWJu>Yh+XF`ZImLGe=d^$5U>H+0zCw zV`_q9+k&&h9U{OFGY{Fb4>8kEo3sC1zvNJ$5ERJ(3Y?z3$`;d+o5jqjtTuv6dgopX z&EXr&5em(n%fJ4$2_?&^xPs16lFvsI$O7NZQ2EU>uxM^(&ogh$v;LW9CpX#kt@}V= zu)v)o2XtHD?_OvcsuujSuuX>hKb*Yu08_vc0DeR9pPLdgnY#S`pxW1Tf@5_BgAusY zve`2A--aX5iN0)()fbM&Q;J8CJ+h|)k{Faq^t~ErC(~F>2eRKc(oJV^yY6k4H_|KR zVnx_DnKNn5Wzr-u8cZx&%o$4*uAeb9S1gqaH~wAx?;%nHzEg^oOe4_$Phy4Uu129# z^#46X+UW^|p<|P+p0PJW@XmFsDycRath7cl<=Yz$C(}7>x2M`0k7x76qbW#lo%Rf4 zh}1&mIa8ta3Z|2}LSJ1b=cClrIQfWdY&YnvG2SX>zmqL1RjEvcBwn45BN=jQeJ1a? zJzc3Z-KpvJx%;u%?*qe8^6&Ecd15McY_H3*zr`4>Ng?w_lli$8sc*g(M!*aM{B7L{ zd_f~N3Iq{)<_95hw^0UT-HlR)qA89Ug}oLg{vJs36j2aX-{tbw4X7fe?o%e&WEi;) zqQ~VuLIo58K4fwfihkJRHI3z&KPimknqM_d5Ph;Tjg!K5EBY$_m%%JSZtvtEQIP8M zL6W>K-(j4#Y`J*?doZ;!C*8MI?axdN>4|_Q)X+G7r;+!^*>20$$2p!y<;S_ccc;gB zfv=IG^;^F)45YA2t6QmeVi{jDqvH5Ql?viyQq>>H&2?pj%1dvp0&dSS5 zDk_Sr&=ce%oibp^QxX&dCg=XOP31G9ow^lgwSCA;cD119@;Drwvo+H&Ki*+9KITV8Z&V`r%rV=GQc@0Folpxx-Y$DCoPmG6VLkzAFPCeRWe7Ffu#A zZw%;%%k?4JcY@(##5`JwoQL19nU5m&-xiVj5tVp=)l?kIS`oobD^7+n)=ULAn9V9? z7?hl!CbMB;H*@}ut43;CuAQvsyeJs|Jj2l}r{ ztloC6hF2WhI6*Hl05`l#Z-#tVp{EP^xl7JHFCqyreNHd7&q))?Th+rB(;Dk5WN<^& zc^)F$%Wtw2f1jf$oS|oW2Oc(on@z`?amGU8_>LpsyGGyTb&pzq$@%C!PjO0&q0WsP zSkIrQ|EIC946ABgxLqtdq@)q08wBZe5z;A$lyoDYv`B+A2-4l%4GV-tcL+##cX!C0 zxc5HCbH4An_x|P&&wS>3#~ksFaryGp?J~Fde)z@diPrV8B*d?()T5gU<-7ve(#1dY zLY_*!!R4(QL>;!m^i4y;3J~yz$&pV!23@ml3O*uG@Bfg(zuNK8{CyikMPvQW?9 zajK-?;oXk)Ya^5&;?7)e)LASwXAKTzOl#@a2W;e-R=WFngKG2HJ&MDLp^T3^)0O2w zONlGcigVPDX<`9R7&>&;$XprWp$2bVC)?KPE7c%W5!SSo})qCbM< zP+(DDa$m+b=E$N|$I&GrG|Z+9eVQZ3F*W@(tWNoTI?La1eX&s}=#Rp@K#{TCr`a#G zi2L3U82Qs~XF?<>usu-8sWyTp(M2XuBzc#yy+Gp6I)N4Egp;IAxm^BbO0p*i zfnu4s->dN?<#M-;;u`xt0OG8IldMiol_|~bU*4xZjJx&&@-|R{a~bE?uBkZPc7VHD zR0hESy#$ZTk1&g|%qMqwQerYA!AQ%vcj8+VD3m{9pr^l;l6RWQlJwxT=bwb z<&y-IqoLvvuI}|W8Rs$@> z#RDINE0d-KH+Uxa2JHtclg~mngl;tYb>=H#DlyOv%Zh|dgSx>8AUHT?D0!$!RTioI zmb4ahB(A9{hhtz%{xftm?N?QvnEbYKB6KXCARs+5Ixb6`B(hbdGZH6qGr%m3f*2c8 z!jT52bE7!{n|CPlXW2D)d^6dpz+DkrylcX7Gc_2-U6spX=xH)^2w5sYDbpF804$_5UY=i+Gh{GHU;U;FO}lL>v}>BRJwDF2jo$mPl%` z0_~m(nwAIz|4`rj!`N4e9PhSgdsJ5Bw3@xq2I#BuJkycP&$WB)vq!un_>l1P3JXf| zm8>v1d(N`{*Q>;a2KY+&adQohbOhBF!1x$kIf#c$uFh}~=IM`mYy2i|r7MgEbH?&b z8cSRNI)LEp9CHQX6tYkF_{`q)@u9Zj)@ed^CW;IjVjg|2*_*C2-)Z_Tz;p2XDluk~ z^Ij~(;fwo|BhxM2`q!AgXWRHdtA3^B!r=FYi-X0s;QMEaO^sK3WBSz+@=o<-KPau_ zo8(TencfuauPh8THv>vD5IzS1&w#n35v{;Im5_9$!q#yd8E%x6)xfposiK4g+rb+gg z8XHND>wz07PUrc#sjj~m%+h?p7Mp4Q`&aAXqo~H~VucibCd{Qpl%D(_SPQmtk{q|U za?|`6xAU@MEDCZqQN;TUaQ1nZ^vm1t8N;)|<|MgEb@K(5aShw?Or@~v>7CM6B-!2a zHd@P~iVp72yBYAs-;`{>zK9Bkl$($iGFG9H=hWs|2ZhzG`dRL0tfbtSKsRG%N}&1` z4J8dHtpZt%N7mbWMKL08i>oKkln$Q=R*4r?7T*F$i6>r(<2xR5h zJ4rdTKX&1GxR!T4`TE4Rha@rSV@Jq7sa3)+=(Lh(Im#1D(c(B@hJdi4zO0rEUZ?_C z_iFqwEb%e~@H*(^PrKy^$+*Vk756HJ5WPmx`s;5Sh6^}nTo=aoKbV|Pk!3T&m}oot zXGJcFeBTub&HJCvIU8ni%|IOPS?ok^$~csK-dD;eGk&5gaTeQ*qq3TDZ+62LLPgBjN z2UeA$NO6&OgJW*d;LWjbHd@0>1Uu*Lp08o7U}(Q-Gv2wY*!{fdrJTpj*3bMGLC4d% z&7&s~l2}ckY|>O+_n+@df8DX@PrBVK@SKK#v;=gncKw^d-t8Z6B9lcmKce*|E8rt= zrXg@GHy|KkeSk+@yxo7?g6a}ZIarytiigVsr%HvFYc_n#f7wDHoaGH8rI-b7boC8j zd2iaKV-n-G5?@s? zRt6IGz~!jBx090mMWf~&|A&Rt*Z`$D$!rzSBNda!JV{O?q{8AQ`NZpVsD z$`%Re1g=`T?hJ^cIi={$jN7)8zF7wtu3@&62R+p|@<-4>WB?M|iRQNW>%;M^T9bY1 zaT1PJBwxrU)=3OsZ{v-so1jOFpsVxBM4;3s)l_7sym`Ne3lx=8jP(pUKr53EU2_Fj zq=!CDSEgJx<_e#n-VfP7ZG8&Av>}YlIP5~u9xW0P&iwpaxLnu?b%H<#9qs?{I#M@% zr34}Z)uOz~lR-eMzNRu>!Z$h8=ywFDNJNGyzD)jYSX55EqkniEz*SsL?9Lko++6Ls0phU z_Vt&~q8ehOh|C+@RJqkT5N z#9(cNi@NT)Jspp@H$LQkoOQ)AA9H2rwl#ro$AJ>Z2d~5BqT#{ouuDg8U?z-1(ioCU zp~Cx>eDVG8!RwG+xPI_Dif!x=VDmQX7tJ8dhgN;PI~m$q7=4-dZ?D5S5KY++6h)zr zrghm$1b7`h{Y$^S4$Qx<5<5*2brN;jQh@>Rgn(FByMy1!tq{)Cb@DcqhuQV7kloaE zL4K8o`^c?Qkk)rg2_J`j6vw#mH3Cm3rLiYq40;>sQIKFmVz|QLSU+p@>CM~5buq8M zh`j0t3dIs8iq^R+uV@CW!#I*Qm`%Ny(}-1@3?xgQ7^AMom%3qAB_9=;il9S#F#jy! zUQa9>Iv6x64xaUT{%{U0F;M-eH*#Dno4QUVd_k^#>c{MyyavZN!?Rf1Hd zzh(DDvuSm@{^q_McGF{lcDafP1Olje)TdcLGNm54Z&m(iu2LrDyX?~_=|Xixqq%}= zrioIWHg7Vf8s@1=lhKTKg*7Z%WwN?G(S_U5jBrkG*5-m^OXnZB@3}1Rhou(3$5cA5 zb>#+KAf;n!amzHwiw11|Kh$#jGJlhni_A-*Y3Up}maR7Y%lf{EN>+ zENGc~mc<9G`Ch-BV|}?>@!4VgwV~V5xUTL>^|*oEBkn0fCo9J({am-2X{*vb?isT_ zE2mlK2{-nix{~)~@=T1N4M2&F_&_Ya<|V?*f7%89|rtN8F!At$>Rtyssy zUc$SJDED88#L01$1BiiGXQX;N1^3558F2%=^hn2aZ0RT&;+g2?>B&bT*AKd9ZK^qxI;Zt+II_41@% zCBIkyCPwg$JWM-_9O&Z^V=W`wfEm%A5#ldNtwp9`WCJMynau7Z*6hDi0zeC;s=3UG z_CpEBNVKhX%4-9!UV#3`!d%gq(_aMX0edvvcv7s0-YGx{NBpp=2{YnwznSJqLX9>p zS9#BXb%||UKhTEJ#ei?6771|Q4P{upyaV(kxtF<{Z%KOSV+9Z%?%&`V$OlpawkIjS z@N)Ub(iPm1suJO8%=qD4l&oo0)6b(!#mKIe>|fYtjJs|^sARBR4LIXT=JI%-U;i-m zQ_Z@MGLugK^g7BQGMOpVMD`ttyj5pZHpgC$ybaJla(tSbC6@|(!;kl;fAu=H zU@YgwS-wIjqiQbW&jQgiTtxP5WiJM%_X;YY=E(x~2I}z&{E!UpH_2fR@Hf51ymB)!T5G0X0YMPNdWV(`ovi08FjZv>=O zAUEi9jfZBR_aj3pkWmQA$)MtuY$WkT8jw~C)hjLLdaDa3O4FNy$adaDOIMm9W<9{m zOs(}wYcf+UD?rRnmgfpNyDJ+VxN^F{S`>qAK* zpE2cK>`goTRj_mhpnA-3rHGv_LJc*0Gj(=5^8*dF2MaKt2Wi!Dcf31d2Dhw{&u+a+ zU-qkl8x$aBrItg3ZVeavi_O6g((0|_M%(**nC246#y^PF+{;GZ7AIoY|J&? z27YW6oaFvbyooXbAK=9eyq*!v20=nK3K7qU$_Rq4W<0enYi}hoP-?DaRttK;{ubQXhZ99bg|h^3+gTP7m(1$nDh@-NPV7@Z!7nag?4Myfj!+Gd(J zfy`#QA8pWPMi6)JMr3&!aj0w+;<@=~RWz38D#1?J8uDwzj+=^HTY z`WRE??0UF!Lpb{Qo0BU0UrzLM42z+YRsP_)(LNoNM)>Fb`W2tgtmg~c{qnMra3)N0^VUz1Nev3) zRxlSmn~VPrp;>Q~gb8ey7+CGpwmvm9sAwSwW-LTm96YUEv3}@yD!n_Obvn4aSoDAX z>vAsDQ0VLcMejDSdG#22T-Vvj!#}3-^7gKFx-fL`(Nllu7(~41~$%+9yZP< zo3E#^$hIqEK-0+0JS_&~rOL0EZr5Qz$CD2^Mmmb5R4Z=6!`#^t$^sl_2ipcAzOSyJ zs#F`v^r0Vbe>xh)W-HNlu{2l%@$TMUs-2SLC_pM{UZ5XG$P1&*zYe+xF^Owu)I17O zPf7ueAiuiIejcockxAr)5~gNb%!934EO%J{|M8HIgBVYq76wx9kAxFAnTqrBF4%euyQ#`GEiNo>kCYJiRPKO z8Ip@rUN7fJfRb|DPlw4TeXsC&UL_U8lEHs>HRMTh>UXM5C!*mq(s_q5tRsbQi5`;n> zfS93zf0jRl&>o1{KOwY2?G1pK{hm83)Vb)LXhM^KCk7Si!OKpzkkpg~2o)LJ^-e|_ zEtZFd7I{5I*XYr#;fgBWHRh3x>9>ffOj`>weMve!qG?=}#Z_#fWz0c3yNu>r*LlWb8_A?S`{JU0_#uS$zY?>5I-cZ9 zT_*bG&!PWG%mzx`FCIc@{}8i9FsU;X_j8v(h)4+h%ox$IGctHSBKRHeWfpeKp>JqJ zFuEmY8wv{h7nWUpZ*Sgq()|yCd!G#OzB+g8zAq2v!!We!o$SCbDSvLWyR3&G)|J+H zB(R^ZXM9W49Vl4tx4<51Lf=Lt6+;~m-?*w5&fDw8DZzn<5sDJ5PR!U@@x)&r!#GZZ zc(~3#z?5QL7`Kg_$cWaCV@yz=yEZ=BOzi^)iR%VA&&m+SJ_nPQc(~^upvedLk@RpL z|4MEbrnUH>JpKsNdF=o-vod!m72<d0goFPmSiKAb6=s_-3pw)1Z_({SoOO4F(SDoQH7EeKFLnJ*3( z`hFK9USA&U3;`pd_rE~D==3}ht_k~GWTYMDy=hozU;+RqTk^$IGh6yXWRkb!_r!4% z;AEoo5YBSWj>SMqnv+GrgZ7g_LDtqwgAmR^v&<0Q@wk;x{`2mYuL4M0nc)yjbE60; z+VASG)&bQbJE!~em_jAG1lqOnJC*AmF)?A8F| ztk8T=ZpJ-So2j4%*a)>1o(w7qT;AR(H6Z}BzocUq%Cc_SnYF@ll0vQGUJ3N~`5pY0 zPpd{uESY?ZvC#{wH_Vw>OUB&MOKc~@3R!c$IBM+yY=r3`kxUtPJvpbfK?{0vKC>p_ z*lvgw2L*!MX1CXchtcQlVyF_1DC9W-^W2{gHBg^7mI<}WkPpM)Jv0s*2#2D}JJGwS z!UZT6n3OtbI2>Q}{^EY37~kL7IN8s6f&Lm^-S! zvEkm=Y5vY+&PlEc+*DKM(`;2Yfrow=JRF#Mda=Ab?Gxb>QEMN{7bPZC1{y%|{j|>b zN!Ded?1_tu%mFGeyi%xA98}xf9+m>^s6UE7CEx?zcxYv(3Idm1~x*e z3n1_$(h_0cqN|J+*y5$-GeRSiPpN-Gh-H+wL!z=d*E*EqW!|&~M;F^?SL+eWY8(f} z)R(W-f5?}0`%w|wyH6a2rvHeY5sk(nKaUY)H=Kw4SSQMD|6(dFVra;|2o;YDwt`>2}D9f9@HjPdeJQT zOqt|_*SRp=HU!b^2Rh)PhQ59)Q?ol##x_v!?(^e4Sn>OnUY0F2rrCPu6aKmUTAKwZ zc>kKLhya-L2>4DSoK*Kw6$XAHyKmuKu@;F&eDFQ*s>0O6^X`fib*geJJPlP8TThX5 zD>qqDYf$<_isz5gtKRwVIGi+aN7kcX1{yA9J{NzCWVUMj^fPxbGqH&IyGwV+c%_pO zpf;&5&sW>YW7#D0UmXt*WxgcR`fh%*pX}dJz|~}*T!t`teKy{7>r(~s3G*0uWHcs@ zLYuefjlsRS2)Pyd>tsuZT;bU3`4Rp;*)Z|`aKd=t96^*IVc-cLf&z(2xs^QsdcyR2 zzz6z)_nHBaWdRvt;WTm(^k+!=_9lE6OH*F%`r4TmN?l*R(i6n+wu1BOo4(vPUafI$ z=f@lUfdV+^r}+_v!#-kx5(p%m`4Rz(Avgjq$~3Yu!wC$LGH2@z=1dD#kGRjw`kjW; z<_z=ujo*e0R23Mom}N{AyEaYPd08{jb-INacJ#xm*v7`!4{cRgKvt^LA=+lm_fTsy6M;G>t~*;mn>$%xEss zPwZ5^v2$R|Zla+3l}t;N~fNG5PQBe!|Nu&yx9sR5*pVJ{nJW zfUhc1&DdKg_(=g^EJW<3YLQKe+_)@r-kx`j}oZ4`_-59 z2Y%IHFcamxh&V`iWO;j%FJo-O(1w5{_jjO29$NJWfTDltiFu^8v^!OeINSN?Gmp(g zlSd^ct2Wosa^6=eo?=(Nt@XiIV!6pKP_~uPa;9gP-)jzL7rrkb4;FuRZT<7(A{=O4 z{_^_;dAJrvv}zm<`}5<1k(s`HxdpjDPDs5Q1oR1$@w~t$|3)qKm7FgFgF(-z=PQK@ zV@S`4v1}yg8+Sox|BzOQ6Emfer?Pix1h9Oenh7c-zgNS#O$ao+v<6S@8c$T1qsgmI>P{=Z*@~qBAV@K5ne5E;{xVhhV6)ioLfeEN?<;kaI@D8 z%W?STs0yUv>~UQR#tZCJ7ePs5l`yByhyMgkxK#S}w2SO;UnrgBH`#Xu=`B zb~>UaZ)?x3I#b_YF9P; z-e+Vd6IeL}Ea1z;D^7$)6t&2W{XxGg1c|9pNERXNIXRY4g%gi9ObzjbW%}djqba+uk@yWV zah>tK8d+nx=Xo$Ebu_d?THx{PG190f%4(kDSqY`kMiMF5CM`dx$=uHkq-ulKA0VyN9R&1oD6$?q$Ed@4M`YhGpU>FD zJuq^cjpy~7l>JxBcJfVE8|ab3ea*KS=r?=K2j#bW8#W#-mm9kGzxK9M?}w2gwgWbv z*G%NKoBj|m4&qt>HceMlM%PTKl|Kw$}=#w?fWIsL0cFj{=B4eHd7 zn+E7bSI;;#Jul%PwhfQj6MG-H`W(>iE5b|~Y_<%5<;XVN56G4u= zr=!^#ss-aeJY;CSSts|)w;9wsj3<0W)#x_gL6;_uQ2uR@XCZDx}~AAP^P^h8+bGB+dq5p};^fU?ubHDD+R#G_hJHz^zbyi7T3T?G)4;Q5{P0 zPBQd4oB(ams>WI(*eX9f6%{ThJk5<&JTJzN_BuDi>&5gMyd}z*KjH6Ky&sxA5Tfgi72Lo+iFN%dfn^D_F=uAC zejBRA-1xn>ffc&u-B$uShcaT5%u*uAGMAxXqpK|W7233pd}9i4Ta~zFYsOPyF7LpX z#bECwvT-f%eC*L*-Ug=e#D?Ka*&d4HFfs4f5%P$``Z*`GImEDcZeG+q9uOk4Ja)C{06-M@2`5mWrUSKd7M{^yAMLI3c)E0wSF@^TPoEp+I0 z-|nnPbaBxFI{Q-x(eRDCi0?is)_kRL6L|a^sGo$dwlnPTF3Y1wt?MEALkI%%wijXC z6%CbcKZbHgg`KywH%jae%bn(VfA%v8H|~uQ>NXrR2tEBi<+9L!aNepSE_l|Z)y#EH zX^tg4Yx^1N?s`_&NcgHFvxNV4MA6sd7fvWJ1ptzJDj!!_ z^9BWcbrFtA%SM@%8H0pl>v=B}OhXWoBrZzyGN7)|l?)GtDHjutscGZ+oQeGMln{!b zy683_FjL=a3W{73wW_`$N4b~oZu0Y0AW!1;#JC>^9PKn8cLOBRr$n{Juga*znKP!z zo#1?#*Si}zDKP4|!r^hx4Sn_)A zOMz&CpIO}uf035V?!DJPeOj0o!zN+^P3W= z+fY`&mXmJLvrQ!nhp{M*T?Tn9s45PcLzV{BwsHiTs<~H`=@v)YDnxQ@{@q&C0^_2p z{`6QpE*|yEnI$^qE|qLA2kjr)GwNUXIrH4ZlWZA0uh$cVWUhTpRtt98W(kSDlf;xp zGQ(s90@Pu5yPqI`lB|a#KHy(Rypext+JAiE$t2N7kP8R>B_A2qc_Rt@mXF%Lo{AW=`e$2r~Tda7{UFdm)lg$<+Srt-&-uLW>>I(&D_k3*`~Vr7>hRkLE42j zvRc&307ce!@7F5!8v^Poq&{&pNBCS>kxs|2Fb9vLaLj7B@2(m|6Jk;bIo?S0S<@>r zG`nj~x$TVG)Yt?xG&p3gTRmy8N1SqaoF~7?-`ku?`b^TzM8-KE(U%~c73u^>e$;aR zg;e_@+}|YY!P5UnK0<>)fU3yNbO^#K zUIy@)H@p-`9^|Y9M`{7w{%3H+qYT0L(LEA^78*dM@ML*2Gni^>6B|wxX>0i_^4=tF z#B=WYrI1$&?fM~DuX>cfLbjb(W0-_KQ3oq{o3DjK(Cj^fP5t6bf(#YfslUDK)c6)_ zA7s7}X~oL99M6hbmK$%pPK*;{OQ1GTd1-3Ax`i&13v!s`3kA1qI=`mA$=` zaW#~xjA?ZV7UrelNKAW$ct0$Ps>>w`=qhvOq0HH}*Zg~RQc&sL`bloh?2=u6(#(WB z(H-o<=J8{Pu!;~)&XI5Ir zmC6i3A>>{|i)>?r2K16WP$#4CM?Ok8m!Ibf`7@^I zwL#OI7BZMy&rZC!xc~DhVgFUjfRSuU4FNwAH0R8xh6#17o@dCU z3$bKDR$aKKY%DTiNs=^nPJbe)Y13@a35|R*h1PWc)hN|qCZ|*9Zcn7yj{q?%%IK>o z)CQ_Auq_8kKy;u8YIm1Y%Ic_~y3%LtR z?&drgFL81}`<2MeU|8>L2xVz}W4jU^O!#u(w$@~*E%N1!?~OW#`JfLn_d6@~Q{&=1 z3W2a>O-9QJ|Hq`+bHsLA^8s2r@5nA|7p6pHxqYXGkAL>I`D}dIN_5)Z?n$iW6nIm& zQ&L|(b8j4XTz45hz<`9}38X16MByHr6eU;owjfi!IH4I{y*#KXN1B#8$H#m78Nr}K zN&FTkJ;58!g-~DXLWo-lZf)R=zSC8N>V(c?36yEGvh+7FI0F2|Lv7HJUmJi#KXs`>x~#)4Fe>R2+3bN63;k5B0+~_^1RtgM zsX;D{>2SOWt*3s3k=0g=7edj7K`5PCdkEwTaD%d*AH~Dq!nl$1t@Sk}@eEwmIENrt zpS<3vI!R4m%_eoelG&0qM*HA{3?`x&F6D9Ve49~~;P<|yR0BaJ-WBr$sOod)ljf73^#g;GqaXxV+2{5LDTy}f1Wf_qW`lb> zNflQFajKDgX#HeyXjDX{%@vHZEKuA&0hK>_krVJ%3WLajw=x@$MX1R=fwmlY#J?pY zG%Q?kBAj&bfd8B4@|QCCm*+xU304e4bwmMm<+pmKVm+oeqV=O3`C^XOWEXvyFRBaP z5Mn0x1jeY|7)uy;SEnnc$dD?`){PraRiH1S1xUuSPSx43}(P?#kiLi*w2Tm n{jm0{H|&+GZ`oabE6Irnv62V9)YEl#z7!JwZ|1HeD%Z2(3ipyD&2 z=L=v90F*Wb#npjo-+>wyFoZ)GFFF>9kdV`qRN04es*3Qw(&hxmvgM+i9gUdhM4!U?BbM?L88g$iF^w)KM)7{n4)8mk*r{_UW zkAt&+4(%fxI&snGpqGzd;9&^p@ZrP0?hZ$f9z7Ns<9~$Yf0^x{R1x6s9}t&&^5n@= z!J(&5pFVRYC@456=+$y?aPYaH)1kpFqzFxDSDVv*`Bhpb)AurnpKcyxGjBo zDhoY(lEw56l3l^yeR>}}h#XKe#x&&(y-+uOUky1HG}x;s01{xSWnS0E6q zZ}zp+^OOgm$$!GKL7gl>o@htp90FCw$eXyy&La_H^fsLEARgL zD*ru#-{fU(ejeT2+}t{>sIrCjbo4o7Z%cAC+(Q5Z|H(n+7X*p|KmmIH)5iZ~0zhm5 zI+2RbJZ?J!u}#-sz`NVY!l}6yI@c6;UzayJKO?BQ*PDU2Pf>KKE$PeFK2+)7S9^aT zk8q~H(B*OI&@J=JA7}a=myO&ZGEhpcb>*Y?oU?TU`s*s5myzzd7P&sDeEGod@%h*N zPaaG>3hYc#a;vX;^*H2tWxzoF!|4X{e1DN!L-p$x%F4$?w%#6c(7QaX4R-WWAN4TG$~usH!eWj2V${yw_{!Ly1-`80mvQm@m=8%+Aoxs3Et5U1mxbxJ=peOSV`4nn+(r1>w9c ze}y~;p_krilB^g$fdb=SVRHbfg@tWi@%j4#9Sy{Fw(Tl!IbZ=eIC5*-Ib;p96Dy0I zlo~eEB8yxfgc$>z404svf36Wkz0W^$-L(0b^WF2EbX05P^I^3l$Z3H}7iY!OWQ6(L z(@3KV_w_=Yw~(Rt%IC5juIogM9jZU*h?BwlE~5dcos60bl#HA9G||t&qoeyYtHd3t zMQ3emyd0yg54IpJg4B*PT zRa}he_f&8qG|nNp2&$OFwZjtYaNxbBm(OQNz^Ak+(N_@$&#GfS;5;lLc58ZNnA z9(Q&9OXK@tLX0e*OfJtjla`iU<8CBDP|SB5)|Fi)4Za_LGXxy{&hx$)b#yhtbKll6 zgEVbfpHa88cYVB~uS;c*+KvwI+nqJbaF0f47ZYvU(T}uGv`ggRB09ht1Q;QbOgEI7 z!=;%+^na@$;emMRDv|&8R4FZZ(5Y=q9v|r|TL)95$z+?izv*dclP(Z5_qxbDCyuoZ zq^c|b60p=JyQpvyAH9TRnYM|ka6bUrrje?@WqFF0YQkk<^X)O)zH9B8(o`H&1H)q} zbh{1BUEh{K(DRdYk9Y}lZOlFS-X*DCqUP=a8r&>`mKtjPNMYb^fqr;4_U{5iVS(>- zp8LHgN~E@{UDzE}1(7uAIV0apQ6}3#GcIk=c31iU~05h5I?z=LJ)% zrRGBwp3(i!Z~tB`BVu*E6r|Y2JJ-scpVGYZ`d^e(j@NPN0?L_m`S~X?p!HJ*!6K%iO9#OGX zfpE9Uj-5YvY>%qbas!h+s=nLO@r)oXx1;@=qT2kSsmF@#Y^-cxeyA&bdtwZk?a2Zyb6U9z8Jq=1o1CD`t{eZZmT`e>Ms{sw46S zW)>}fHVMw&oNMW6i@Z{0u`~wYnbM3fv9#hNxE$aAs zhx{-v$!zegMBI8OUZRG5z4d(4Mx(xV6G zmH({w5+!OmEcXRfgi5evREW5A-JkMnAW-6Q zey{tY;jLeTA)b#5CI%NxTYhZ~k<%X+zIT6bIsI#xyst-pT?F6vr)h+`csUj3v1F(4 zTgdjTE0!Btahf6(`|NBL`=ab4K zLmz!xe!t|UKdCzB@#)y~@A1arC)LqIpHBSwJ<(L^MBuoF-P`kaQs7x%n>Y0Ntks`a z!u0yOGLJ9kkN=sP9R7D38u}6*_h(up(a_lI@ihqC^0GbO-YBd6YgEgh*W&bs*7qLY zVyFMSSs!j_`#JP2;m@C0fMg>d?kT2kSt<5%b?R?WA?m`$x31a^U0R;sQ;u)U$&WPl zmTasmW_9WjHbbJo+|~@8;j;6O~cXQD_8W? zq==Hu!o*=_vBKXa=W`v>@^8eYR!Vbj&do2%Jl86Z|NZDU(mdWUyjC6e_fw!`%Ve+T zkJ?**KZkh5O=PtHsBiiEg`Ckc^D3PcGWqu_Wu)cJ&*7hKfBt@>O16sNUh5qSn_{+C z>zv%kdXLrS_mn)A(cF};mfz-be(%QEo#9_)yJ^Uql24Zoc>Nx`wYggE_4MPBk>BGj zn`^v`r=QPx{h6BH{Lwh_^aIxOKWozbPrhWEnB}!Gr?9my@M>Gm8`)U2+WIBTXj?7w z`up+t*6+zXZ3{XhzAyf3TM@CEx4!mzZ7$#1+F0^>_IqMv^T%|;4sph_jrU$#zo&O? zQW{~VKSs7T|7>jm)&O}s zLGx&Ue3hfCn$y+&=$aI|wjkkW16?oV+OH!tf;_{}oMG(8Fr_fe^BHCo+KzJH(q5Xf zJQE+1kY&QubcXqH=*=vs`y|tIok^NxF3CZU387(RcrqV$kdqLELu3+BB>)r`fTRkc zpIFc!GMvUoaELzfeAqEwqN_Qpbb=lg!rDurj)^fNc~R1E){h+ z3K)>+ z1gsnYYJ|+5%ukzYOq-cZBjmGpILFRTu$9+i=H;NNf!Fh>(5Hj`PDIPnM#a@LB2>S(-;t(#aW@5ovlB*T&4L{djZ=9_md+oDD>FZ;8?@o3gE6 zW$(Mm5DBi9^hO5pVSaq}!cxrqfy|1)>#2CwhY4sZ00oV@?t2tf4nWn&({-}48p<*@ zmNEc+QIJs12AfmYfNT(RBtsGY!pz5chz3HQPcEuaJLxtzvjB&fmqRr1&>B1PHFdID z04Uw$Wc{1@1L7>8Hue!Q+k*qP5JF5XF#BU}=DV;5ahN7D=H{=PX!)ERv)I&fD3^#z zC&SO?=XjlC)*pb~7v^{*qY^j?2MO>J>J6?CkwAu{T~NMA)QRK-orvVa=7o>pxqq~C zH=J`f{5bHVakoUlVKKpSq51W_@PHq|7m#SVqo~seRP0s-Qt@V7swkL#^Y*nEG&v?; zvpiqFFaK{DrW=Q1fOH zj3EooNNDaKcJ5=dqLaD7Q89UMb&~4KpjCv_XJWL!X0W_Y(tHI{pc9u6ivFmR-#|ot zZORfO)0X?Lbq6B72{(;7U}I8gmc>nPF+3l~r8#4V`K6n3SaLr%5=9&3qZ-7e?Hp7e zsVwp%m#h)%E{^oXA(hTwzb`~Ylam*=CU4h7r}&YP9!=@)l!O3MU>Ywq|2@oksk|#$ zH7`%~gs9?CF9I%$yiE?w<0r#Rli)Dq*p9Ook~2^FJt&KL@HR9Ke-r(Tdfx4P-rHX# zshl_(0TWny+rJ0J7-@pFPEEUNUSgr3!q@9$*6Q3 zdW?si--+y^VqXMeZ{d&vF$=tI+$03Y;2ur}V&_R%R}ySusSMCU?c|^ac-LO=Q7r(* zcp!E{$V(7hLr?Q2M6BgX>NG)OUWiQN)hNUv@<}xtTGi8H-cm}zXdqS%T?=H_&hW4! zB2)?Wkt~~*A|LC#^@o%N~_L4H3U&9NvAYHmDx?B9yqWOLv>IO+sJqL>WM z;bLa^*vLR|J^(u-#Q5=`*;drwza^S@;47q>X|cpC6>^G;(N*Bp?WSIMb?vexZD|S< zqvQW61-sOY>DZp!Noauzuwt=9kO-9j5^NxboteKj&1SJUA?=kCRK$-~l=~JXDA?_d_o+(UEDnL11h)LtaNilK$ zoLgbIC%JM^4ha>_jdQ`rN>@Db1hhXnaBr|F1Ef=bZpVXDXX`_!+n>CL2aG=$;9~|k zm1j}jyrgy09)YsW>bt8A?5ALDru%8LAGsh=k%VR^?fqGK)R^{5?w zjB#Gm5E;2#Uj3`NX&B#|&aIxcdi0IkYDa3FAYz617S$HkB(-&(1Gm`{J)OW|hq;e9 zqNcY*>@{|+Ov^R72UssE_%siEnb(V8w}sztE0Tj2h}yn=g1tTR%x(ZtE_~)N@GSp5 zqMTFFqy>M|T~~IlGMO89SXhz&lYiIpp8th=f0hdWAc}Ul*DK7lE4#;~;W|1A9Rp;{ zGf`1FzSFA`nM7^q?Q zqbxj3n*`6qVL3PipMZ=6fP;mIJQ2KE+#?Vrj*_dzTx<~z`$*Ksji(m-$J~`m2;x32 zpUFuO(yBIM1IYaqT;$xlakA2htP~U}r6IX8HlBpyS;yHCA&w#-9su$sLa?79c_A@B z<)PV)Pfmpn0+a9cRo&a<->ZFpFR-V5IKKYL`;-&1n2WtP35r$IgH`$)LwogxDZfhI zZQOo8NdM3Zli~oRgv03yUDq#wKzP894P?{xzHdUw2t4?iP?Cv*#^Av%Ldj@6xS4G2 zM+P6`K=z7ZBYbQuA8bp2TnD8v24MOk$VnoUfNMFaKbBB{dPW+X;bQYRy@aP@ zm#i}gPya1d?`b^5{0r*^uK6SmYD@T{3}U~oM$;A1dH3dsx+HPLUiJuBg~(hVCSO6uxJr{iXd?^ z5W*969VbDj0Fp5{a5Wb*!G|3pW99)!0u^~wA99q7{RV&=;Lz(IyPHKXrJUz>hRlgr z&=P8YIUlw%5W~}gf8R4-?vA=lj?1K?;<*#?0ssCx5ELG$OaK4@KxF_>2M_TA(2onD zI<-&-GQ^hyVHFj2Z#>ERBH7=1&u=rh;Nd$5*SLVM@1~n_;jRsHp^I-Y!-OsW#f8s{ zYKZr{<)+{( z6AAW$3wOeyy|#U%h$SdIa5WVh9N&W(_!#MmeWd)UMgsk$tx2pu+XWcCWhIdrI2)ZY z+wSqAG$bW}j2YrW{qY~f9GD#mJLdUigoh0iLplMH831tAzhg`pTql+QKkfd*`igJE z8V*oDe`S1?NN7y$zmJETxjm~n03&QRWD@?IoXja9{>jAsIhGv9A>M+;$CO%DS%r(y zJOGfq0VD(PJg~wp=y8(Rkud2?g}R9UlpSd2qz&S|Ugd5n#pQb}Ywj=ER=Di*qiBBc zxWSz%gVrgN|5jAkE2G-)BX0u`{1uzo;ctpSyZx)z(nkO^4-qkJyyvN!CUa0-y(Z`N zuiB6B;)}ENe4Y9)MNhSTQ$K_Xu(J>4nZIi?+Xtpv{&VioZgC#+{c)#dfFu&V;5ZG@RuqDy2BM7kHNzD{fEu{aLFa;hO-FS?RvRBz&|!?9#YN z8t&q^&s=i%MTJ}Hogy1L4f)2(%|>(Rg>gu>oE2Xl;_o>9~e$wvubG)5@jbwY6j+WS=O$^A2D(l{Frgy6(d&Ja~L5ulb~ z?G3{2yIWe?v6w=~>`i@DnyoUkq#_%xhf=$jmIJWgVP+TGo2!Iq(!%aIp~BM8IFXfP zVDY}>v8UAzbfvaUM)M)f%DSemOy}C-%A3STJDs+6-)W2~+hxFyh3yO#7^3x`FafYT z*51_af~G>=r_5b?JK)M^>qT^q(uspU+>V~nV3t{Zd!|9JW~WK*xS>7v$sT7Z?2W*^ zABvBt=LU`<_3<}{YNsPw+)4Ub7d_B=#gySRIL$3LSv`mp*!-c&DiEkzx>Q}OmjbxU zR*hoQk>{TufAsX{+@ZY%&Y-uQnZGxhGLHRSpB{Mzl-$fXrnRW;IO#*W#F0VRW(vE| zyL0SM4VbUu9Hi9te78$GpxLz0f8N0&c;|oW&IgnenHDsNDgxl5e#1xow&uCo9D4@5YQ3hO zGE#%Sg3_%(JuS(!O%A=GRsBXv?fym7v5!7(vpQ#3^`>c`o|CTeAqDp_ND$iKcJgKJ zkuyc$u#)hh?Gxj<1lcE6WVgf|t36Wsk!I%aF|UH|2_}!u6g*7DhI#aOp-HZx>L<=W zLq|75`x60>FS+Yq5xaxT=MX!B*s91xlbFmM-ciZ>x`HE+C7A-uD07FGjBv~7%fyMPs+<`(ryUftu{adn!7f%M~!Xu7C0)ME1RQYGkrUBVur?C`K z2h4y6u@GI7G|a(ch30HEUjpl-5VVDIp*R|s_GlY@f2-6)mD^3Vh0F5$B7zyGFu{%4 zkM9m?2md+5UHpNmOjVPn>pB$IkCh+D?6Ac>h8hgdrAD`&(Z4wssFHrloWcgd;^bi_ zBHQcARU&DQTIwmB8cQ&QynOQ>=0d)(X*dLA98I#5!Mr61<+V_SnMe9=L#_VSXrlat zc5-iy>@W-i*)iP5qpJusXzBxhNAn{x%s?ovZnx$4ezhli3^1M&V3~%c1%k9OhDc1p zhG_@mi8V;ER8`=DRelc!h)S-=IQ{v;$wWhk+Vz;!1Qn};yAmx12UbV&O@5zDk5cF3 zx09Vsthj)j5`IBQm$J(i9<;Z5wA?1ObQ&I`{Zfzq z&l!!kMFea2pwBgWC47CHWa@Kka`Hz`xqGnA5HDr=V|{i@rY%&LY>W2i(t9tqqlcFI z6__|o{DLY{17~kMgG)TsdT-}pZQJc*%jtRoqORf18HtZ#6U!p0G|naLqe(WzFo!Nx zew?mIl+xQ*k`xp!FT=Al({@2HMH*9GSGPN?2NCeQ(u=80PaUDa6DA7Q}Al|Y($#3<2`wT&X>@Jnw*POKjgYd zu!Um^*zOySJH|Kz=JnsNpC!-l=%yy^`(xoh_v6Ez5Ol~SD)>gzjvO7!!G5p$gSzMC z)pkypBpKWWT7VPw~EE0<8bJm~5B{W+fG8_)+OFV%x|9DDBJGi`0y!ifYq_ zLqpncCH#nKvU}e0JOF-1mCyZT_SyUN)zV~e_D~(g8b$UEx}T<7N5jkwYsnIP6<*Aj z8vDp>uYGdj>rt=x@OFefgt2cq|G_gE80yI4>3AwMG0?=<*~dU{|7Dm_(TAg)Ce47a%WqPw&KhQuegfg2hy=n77I4IGn#>Y(?+GkG4GqzKZNC!rom4 zRLsevU9g?oFx$;xoOF{YxQF{cwujvD^J!b#C9hI zn6`EGpJU&C%I@B;Tb8E$nrHT&zHXeiZZnDe78GezOG3Zr( zmC!g2>MFBYTk&bBosj6>fzp0AtW2QX;W##T?~AIxL0rb2Z?jnthCPE+ImNzZ*#^|0Ce>C_QGkzxz|W3D#}v&WiKT)H~_B z{4%efv=2FLXx61PDf(WyY2)Z8Qs!X4U)rcS^~mGVuIk`(v6U11%zgK3o~^lyIm+C! z!+GGx&R&E83lr^RA^YQ&Z#;`%%!ql?_Vi29ne`uo*aKfLfAgPn(PRaAwVzmjitFDqv>NXRu08iecPBe6y}}DJeg@a6+hiUF0D3_MsnyReA4a95qDSPdPLZ!@AEn^aT0zc*i^XMLOIhC7sZQiKe>G*Y#Xb zuRhUL5xme7zS{F2r1$jso*OYvVaC0e9eO`l)oq}9qau5wnFsV04@9{4#@6-5$tYZO zucIvVCam^e8@v-!nCaKmOE(rU!cwnTn^S`XNs$6ps|~HSD#AgKQs=xC_Tm8hg&=Lg znUW(&ZWVB3Tp|Yr>BfE84t<9=oaI#nnUQ^YC7oIBeK$+`3QF2<#AoI*`-&D^a5*lw zApKk!*V7#?3I|!o?E6c6`tJwzmqzxNG5gDN`YTHME9?3nboE!g=zqA-U%lG@2r}?+ zqwlWzK&|n>cAb7LtA1Y4Kz-yu19PA;XP~KMpgG6ws{26ei-D&L18u7V&me<*nZfqK zr%wi5uQ;yNuvu=Cpe+MJQpA!+poqRd-+jnu z_+8NOV&rhC%+RTS%~47}MZk)d2mN#Wx08}8-C6MhxO)iI+8KVunL}pxPjn5f1&#cO z9Qnx{S?_XrJ>z;s0FS3IS-%;fek{s*(k?1^GkzGTAq1I_>NketDTyE4Jxl96T_{v* z4m4PhRGA8oM~uMA8N+onIeyY*s_RAlc(}DZ zNL~Osvou1%!}k$Dic3IqYSI<%m~!w7rz<`s8=jU=05Ef!9c~Pw50#?;U?PA!8-5W0 zLQ|;dMyj=W(w;^toC1(wGb02n3I&X5OoXh_<;r22CICAsT#ZXT{0^XkU^#lY?tV9R z+GPBU<9LvV+urVe*{jU$e278$bt4n-k*knmt3+!yO_u{B{H1e@n0B~-!es1iWLgq| z1Uw7v2v+2Sy@(U&*cUPPk0^cdhz|k7CTUJ$kOY~k-zYpxp>6{(9khX998@k1grYDk zxdwP4*jd1k4xw&2`*{<{fFo>H0-vQzq8{JwWyfc^1OjEt!RFdb^#Iq?hsSfTyvj>_ zm4A5PH{`h!5$MZ>Dp0{&4u?$Eh9aHeF@VI@$;mxLpx@GvCz+i8szA5^iC z8E)?CLGAS#d?4+VGwX^7DuJL!3E;+Ds$b*5 zQTM?hK0u|>555i|e3{I^j`-^zS0K}ng-NK3uDLf}^(M{;ZutKQ@_keFN{X16?MypK zgv;|ruQno%GECuD~0;%x1}@B}Q_=8tY7niln1FTF!RgM{BRQ zW)la{-7Gu#kw`ypHv(Xf0PYt;)h9!b0g?jvbhLaDg*WYG4xhXTcP27S*Fh3Xfb?#^ zw0C|P(4$~6So_AuZ z>!5fs)8p{rFN%i)cyC%XSn&Xu1lI@81xfI!&#*Jg8Z(+#$F#4~bg%~#9q#=)Jg0GX zPP4xLb=~ZrFv#E#D>5If><1l5W5rQH2HHuRgGa6WSP4s@mjNuJtASfFY>^)VZcGK8 zF=vqj2Sfd4aP{+60DXlNiErT2Q}Xb9?n*Vjq21xW~-7^*6GRw28GAEuFd*Z z$dqF<4ECJaEE!d%h&FRxQ#cT19<$E}enpTJ)H5G^cClRM#NtExWxp}&5P%+^b+!?p zK!WwSFQST09q}8}<^xVN3XhVh((>?lDi|z&kSAo7l+^II?fI1yt}&i zJ|XJWq0;_upIP?uw8OANc4V3~`&}F#q)JZIEe3(d-)%wnoq;coOk(M;p2D>_Kz9T@ zf}3c?PJ~@t%rgA|@nES7g$aI82?BMG*uyRmumb@L3rQm48Id6@N7<9$Mlgj4S0V#2 z&ga}h0P=vO|JFe$#Oc+wp}iqgdu`~Ez}aKy;A=e}tHwY6fGkyPc*c{Nw{AR-7sAv@ zG;_im?@6F+2u&rQsXPgu|3cSWpNlU~+V#&iyve z{$auKzR9_F)s`T0I84x7X?CV zHY*AMQzX5V=fmQij0KY)XU4z0t{&Q|&h39Q$coTTLjCoe{S1Ts7>bflI)Y%4x${PQ zSeEs}^VPyPk>QhT9^sA90QvAf2ME$dAz z>z~}AoxZ#mzCvhNo<0lNW45wobTUFqZpGx>N{1)en6+ZQEBK%FW!Z2UmvGr)V#S7a z((>8Le)ww4(B*wvt9I9p?w4G3II;>>inNbjJuvI-aB|h9Eb?7gq;v18yVk*?&wZXh zBWqhCJ>=F7_Ih}3tsXkC7S_7lhhOuJzVgd>P4D=_qk8x36dtcwCixSRG~CxtM0b#` ztp&Hhv@$crpdD}2onD+u3c4w+aW+l{IpN@MoB|{oO=Hwd{^)3hU5+* zOpgpy5thbfGm^B8?sKD#kYE=CKPVGF4(DP1Yxo(b6_qlW%-}=uIEECLSwTvvxM@G% zpL{zMZpR6{l>IYli+{2A=N3C}JqH+F5Xj9Yg4}TQULA}zfvzCn>6^n2QbDKR(soh6 z-;zO!M3Afe^$sdigL24#4Gr@{IaBBgRGNA|_^b$KAp$v5LH2(c=koWQFN5si1LY~; zGv+@oAz-HKz}#6z2=A8*o9-zD$>SMsq<<^$fCk!oSz3Sg(bkg>{HeQUc=cKGjdhqB zBHL<-)<|J_62a;rOgnAJIX@^q5M+ph8fXJe^FelGhzc8cgae~+m^&xwZX&Qeo*r1P zsz?NTa3SW-;5%gum3+`XT%sQSc?XB7LIs&2HYCa!cPo;#2_T}7X-xWiZx=|@nPC?K zxrk?O?IbeX%pu;}ifiQ(EG*)lm~F;AqU?VKqu{mNDX`a180T7sk&$nJ(E#;VbUo}FLYVGKS%dSZPJ5*{)q=0BgZ=(wO@X5)O?cKV0sc8r7Uh-OUpm!fKUikNonlJivK zR&*zm+a!lfl=mH}Mk*fA5@?0YOnJo8LJQRua&s-=Lz2O_?%M1N^883dV#CY+>$__mW|7-c<^Hjs-Z(k4V4R_U1 zcz4xZUnt1rHg+Gji&khoT5%0d}?@rp(3ahoG`kzugC)%;iAXc~v#>krdVIX91d-24G#q?IQA@Y@ z*r;}C*!E{(v@Oa)J=1Y#jCz&}9eUeiy!E-Hif*ImpVwM0wA~rpx7Keoo%%TC;#NYGFQusMDnT;9>J`-Kv_l{vZ#} zscnwiTL&w!MkmzoqVLC#%b(0Y<8(?h@b}ZpZjz_1SLAdIT7h!@^Zw5fm^-82K^k#) zM;Rw?>{R0@cxlJp+^rIzhBXdIxgfX4jDK+6beec*(5Uod%id>y7un}4t@|tq?NEhy zLI?c0Yj*a78QcMb39`doG@ERMlpr^P2J*VI&fLlGdt)GB7SYOKnKn9P(syso%SQ+Z z!vKa8u9|Gm!aDGZ(^Lp0Djq5OGVafCt~+;zg!j5ZQwIZ`O%P07-p}7RH`=3`{FSf zLH>-Nhtj~DnxT6mBGU5k#=-xoF04Yu+yg=4>K6ytb8?%RX4yCl{?&}ztatq zGEu=@*%4?I+8StqwxM{KetY_-`q8V3W*h78-3r&@v&g+c*aI^T_fn13fCw++Zofli zCbw06ZH&kLSN=Yp2?YN&iA;Zv(aX*9)iQg=lXf%MS!u@O9m_rW*I9~0BgIY=tJ z+jcU|^>NxcW{|=J)oHb@p}N+e!JNReQ1`#5Ds|j9{zQkZPIkhy@oL`0!c@ewMY}NP zdwMS_RaQ&x?$>mB6f=WAfW0$XE$z#@eqy88Z4W|8GOH%_to6NV;*z6Q?OVT|@?=cA zcCW?QCC$?i>76U(y*A6E&gVa?uGC*j@sMX+zhbSfx-BN#YO^FGJzia1t!cY;`5C3$ zR&`CIiaw8s+U(mK3z{$QrblpU72g9ibPrYZAFi#vQ5~*!c*ZvBk9+F^~p zfaTh}Hh-ALe>#J{zGFFMikgPm6@$Tsk8cjgYieKKQFPM#alyFy8N%I)p^FiZZ@t;j zH1GW75{mjLc z$A!Hc-UqG}CK}e=mGF2+l++zf_V(G0ysGVFR5_YfYgD}bueP)O&Ro}iZ>10H1D4|l zUA-gf?(ez!!O2E|NG@`~?>k!+=cy$$Qi2&x#(0y^Y|4^xkjjs2%m_vsv)s%lN zbz$iQmP4ZoGEf_S@NwnKhj!1)UHnJ=uaJ&okEUgx-D1cQ-|70#>rVK^ znp8zSy|Ak{rN8#gJn}%klZE@S^st=yk}0x1?t~C*ic?ek1#pr}ATzWBRTZ>?!8yb`610CD*6EL^KptUeu>_y0uOu)K>lC zI!czvB${=pDtza|l@mxQH*Tvbho~gE+&>82L+WfZ!*{!!sbQFPb+#RJPI9?(5W1HL ze(?G#f!WfWP4zg`D%(b$7JTX}T~ym8#yQHxlIYS4ca^sOhPWB%9hE3k1|vg--300- zjJ5nJ`30hzf#Png3J<8}#Y! z^|bFP=)Q|IANw8}!aw>f#5t-kM{2TNI``$H%`MZ$34@U1*)20CZH={VSxV@a0A+{E zVJCukn0US_>~JI0w4j}Rvg@ARX$sV$_%3oE*?x*EYa-i4Oiy?wngvcUcQs!cBp+&h zId5v#V{~GBB+F2FKCn~Lj}PiS^>*9yv;#Uh_=xRzTe%M*y&AE?X1PI?sf(pi)~jww zWOXxX+Ylwp8(ezwk=7-*w#J_9>ec&X|7=C4P^0j>=wNpS?-TjFb-`QInXumr-_3jU zPaIs!$*rCEumsaV`v>x_7x5g-EN5D-uik(D^s8-Xtmc&>iG#Np(|Qk=A3qF#cd+_c zx2{Qrt4GY((`{{^{>!jh@UV(*Ido#4l3~5LW%S=b-;uVJg|^m3`@ONg5pPyX_Zlx9 zc=Y?_yy3XaKAX>Zw`0ejC#>Diu=(0)^=E43#7e`6jre=>pEuj~e|;voZ~2+!#+=ce zxn8e*tD(OSIC?+(J^pNS<=&&e8J=6e-)!w$*UA6;C3}ne`ak3o_i}sr-2W7xA&OLj z$2NZ+AZ>an4j@hm2p34;o^{rl-w)9(&Qfs@aKOf_+h@tt?vv{#-1O9wzZ~)Vie_Ew zX4OJ~uyETJl_XPhpgh&}VXD1}LpxkmHD?m1qCc8mJwc4Jh0HvsS_Z+Ah zgdqp%z{%cK+1V?lc~{l@xpXNrd(~dG3ZOx8F;TZg0XiQ-;PSN)6KBaH=YF{{X22>~ zhfh>aO)PscyDNeLaB@}L*QX&5ix08i9(MC(Bh-V(Dv_B}`ElB_@y#o}VglVqt+-1~ zlYWigYgGb771C|YZDlur(yc^k5=bbb$tsG>L+s@i(o6?!ajDKSG9WV_d$}Cj^}#{O zR_b*nu$d4f%RMSdq3zM$8ntQ#>s0Y|(jhJR-8v4oYJ&EVi|ui#U;+nt`--hP!d8pi zX-Ki%iRe;yplOkT5|Gz-^Scci+a*OrNyQGybY_6K7sZ*kS+s?-J8UTJQiM)(W4rBq z5H*#t%Lm9Kg9+qzHjk!)0P3gO6MSry`B3F}npPm~KnG3tx9XuJDFSMQ;PlR6`@DJE)K)S?}nog zv|Zj-mDHgeX-fcrw+Gs)Q#=0E2?42HYFQu@A85g08fKl6i3F;P+f(zCP3wUE=RrFV zwiy2{y1iy0!?^=T1S+uU@{vR(e=n23c1eJpRtfF=7}t3pQiID^Nu5*3p=wsCOKm_6 zo9%qtIu!)eJvnE>H99mRY3GVN%olnUDapz?n#x4_rN8Z(ruU-?98_KJM}L(%T+n6U zTKtBJl!9~~`AXd#2DYHkv7dovGYnZpTE1VBbSwQl7r58K%dsl)uuZ2`{Po>ccaBDO zNQQxo)k9k1)3Q_Fq9*y0V!kAwC=IaRU)X_)q%rvRvHT9!Q=+P~gk%(7BNc4uK$B0^ zL@&^cFb=kg;D5!FNf_88O2q&eFE`HaSNvyDyw8?7x2JW>UbRrL z76O*#QZFy|D&#|z8j0#WxB-GD=K$UtUKSPgK02vlN8&jb>tdB0KKcc9{xd&z=AD$N z$12`lG6!h73RdG1b;$O6R;dbg+IEY!dTeIE%>C`0PBXkMSzFUu@A}h&c81OeZ|*}L z%L49Nr|sg?l>D^MD0i4x_nj&1uxSMjq!z110{+dxNH5=r&rqM?hvdLmB|ZOZ09ez* zULZ_UPwROm7yJOI^6fdMogCRv-yfX{pQ(u{G>o|8ELoGt|gW(P@nM7vb%qDF6FZ9r`?+bP5qIM{zT*WK|ypuO9 z*$OmR*OCwHG}|D`BjBb!FtdMs)H*7PG%lgDXmfgLU+r~Ajw(t9WWhgeBykJV+M)es zvEp_}3ccq^Zj%2}2dk0F<{%_m0jfDd?eiU|*7l|jx-4+F+xbr3&Wf7N^8ebpvvE4R zoi9Z06YNGXO(?cE$rl=a%rzwKexW?lXs4&{bfm_smULVYnz0XgW)UctrhdlBuIxwW#bLYsCAO%p4s9n; zagOcc*da$BdAC@3u{Ie1B6BP|t*m>(LV~w%ELlP940Q=Pm3!jC zkZ}%-vGCnrhQB^v+yj3w^!3>N($qw8{e_7+7%zf``pn%ww2V8gM06=XTca5b zc?bLbs|RFfKt?kldd4$&TKo~F128hmr+nxdVyG*2E!15QlKPTHAZIwT0< zy$G5Vfv!!y^byu6;ZPQ;XRAkW_RKis#o#hDCT*JCpyR9B1>e%2b--cqRWY$=Q}l+iZ}QgZK+)nxpU|`D!Qu{s1mNO_4oMsVMw?`AS)=>vIsw~-or}7j3b;*| z)u)k?U-))}RId#I)|wBs4zb@UAnLKbTF4NPi(u`<7h>E8HMP29pPs9?K;l|Se~X0c z_)&A-z^YI2cBaD$hk*{2LbiAN-yuEak$(AqL+s$#KW3dWlESq^Tikn&+h^plK?H(> z)+$j}O#kVym9jQY+NwIW&EU~i7S5$mcqWe-YA=Z|SUCm8CPM6w5e2x5~em+WnI{1o~i$6#*pbsJM7gb#6V`ZRE;;!xOG8 zI){z+X-BQpQ}USqfg57B^?e0#O(X5JaQ2%V>`FeAKm|3|k`#Yl-wtGGg>~#93MpIB zF?SlM(Y?zxSuS6c-2P^3e-F_4{+zCLf^IhJ3tgukF^`gIq&={owYhDrzitsm*`Mq^ zceRmud3)k<^As<5Ql9zsT>-Z92UB_}?NyZP6OA)ZDQbO<=>w>=>BbB<<@8Tu>5>)? zR=3tOb~Po#V-lq-vel9^)hu!(UnZMb+%W6@{9#J_2BYg?r_1*2mp0k#Yvv)2U;`pJ zEa0eXfcNZCUu(?&0cAj%zk@M2TgSx%Gw=eOM_PfA`Ibj{#Z7sY_c>Brd4XMm77!#> z6&Nja!4^=0pE1*c-$E_~R)+;b3=o62#d%Ju;Gh$jHYhUtz?M@1!w;BY z2EIW$aN!|L11I^~98bf<`C1;RaH{XQl9yAfcl&i{*d5%#GoK!m`f)d=o52WEG!C5}!LJZ6S zR-FT3#lt&j0UUf*Xmvr(Q`U6hL#P)+fdPXS;J^^*K^+vE!Y{n6ar?u^eOG|HxI10N zXA2R`K~vGe7gPu$bOSyRf*WYUDWnG&I2Jx^%N>A%96&)2{J}Z&!xtn$5*WfIRKW_c z|AJ%90uNvTBv3*XzyK-a!zz416%+y`bOJsELgA(ZJkS9UUM5jwrSbctxK0LAFv)TZ2Yj%gH^tJJIbuXhb9WKb@8}W z$pWvR7$VT}5rUEGT)t{aQoK@^k!Vq)N0BB~x|C^Cr%$0ql{%GbRjXHz%8SN`|7%yT zUYCUxJC+MY94WT(UXn26zWoUE z>R7dJX=HHgx8+Fcf`(E6!}lgdtfU+90sG;_P@+S7V#T|sBuqSeJ$47HX77y*ZSQQ7 z8!j7qniRy!QN%i*etrA*@#oj?RO?s&T>%SFzyS#?(7*!`Oi;lE8T3mqr4mCdvBe5{ zjForL;GzmJ(plvO&GO;H1the{&<0Dwk>rP0rs?S$8~!+FJ>%|)0*r8Q|G{Ae70!bm5e%O$qn8A#K?w20sD5somvMI+T+v54=h7x%6@r50fv#Fha zu&`pbBN=*Szc=BGQ_eZ*e5$|y{A*CpJ^Ad@&p!bTR8YVkZ0e3Xdf&=~@b&EgT|v~VW50X5ZdvB8dYhEtQV8o^ix9US)PCY*E5nP!@JW>gKy z`E5g25+}6)3?dopr3t2s&Mi4c6r?yF-%* zWsp^;68xwjtD)x<{Xk%9GOHdF)mvEZdBoBD-=@}Ljya?u~p!3IjY$%wIhc3~{a<>MVn zD1(;Lafu$_uLUo7Lp$)n1|nc19|^QU3tI4nIqbkquk+vsK`5u#l`D58G~o$Rm_kAA zPAcknSUD16l!t|*Mfr#aIdnmcZlt3doO;+f2o@k;}*oQNbw40 zk&Rd+H4lqNG)>1DkH>` z3h|gnJ?@c@a$#Xq)RB&^bxcu$tcb(XF+47oBO4nz{{=A85e`^HAqu@HUPa^qMMjb_ z9xFS?CN&a|p^y=j1xw_WIwrGFUP+b0GbABR$+A+GQj{41qCB`rM_ulcmqfASfBG0q zVGfg+x%*?C{x=B~^hgCVa7C6f5}#f!WnR;?<~3XQ%RCj6o89#0H~(}@I=Qfu$v}lC za&eKCVUwNhbm!}|`4w=^lb-do=U&8#%yjHimhbfEKLPr!c$({;1vThF5xR_gB6BF8 z4Cq548d3WU6hH~J=tVIa%!NvnqaF1qJh#HMie{9gB{ga7Hu_POu9T&7qG;1j8dI6h zG+ile=}mE((>jJ!q>P~HPk|cL1>xZu*f8o*|B;$hr7o4JO?B#1p&C`GPL--vwdz%| znpLfCm8)I#>Q}S+QlAQytYtN;UWf`-wXT(|ZFTEg;Tl)D&NZ%LJ?mZZn%A|Ym8;g+ z1~;~`4QWUN8iVcXHMqeIX2b#+*Kll6=^9zdPL{Hjwd`B%s#nc!7O#BW>R*AO2Pg!g z2UR!(G7dWqcz6P3+n@$4U~yU5&X%^dwe4Ip%URv-mZqM?>R-np3Lf0R3x2qR7G59( z)NU2A;~+&9Ji(1+V8IK~xb1bZn_ca07aO_d?RUX@QQtNdF-+ygIA$>fEW835+Ze|< zf>8!uKsKw*mBuurF^*;ED;m<^?tcLs|6l=s)w|&}@PX+$UZ$2;sn;0CJID|{XgnjZ z%Z;lOY}HJw{onQ%34G-hqxDs3{um4aPBsK@1_W0tQ$hhBB0~4S0;> zuiT(S3^wtOV+f(T?3dxgfFzg3-vzlEPh~zajfD6h!74a>^zQU zQ1=-HhetIA;*8@VLK%pb_|u`@Y>Ho;>Qx8SwUKIRF2Ca*T?k62x$%yE_yGl^cn2%$ z-Qtl?0S(4DFDgcGh-h$K{|iJQ21|JH;D8U@3(ueiru&fy;L$+|uTVzR5uf-(Pu=Q` zcf5kIepIa+waf2-#0t`&3<`@q4`o;RAAk!CBkfC=%ef(s)c1wK-d z_6HxM3Q2&4HdK*>4je)nGyz5sgb)KuwBsGSMgb)f%LXG*f)%Ok70^k*0`2F{P zZHe#r1aJWDBJzxC@{B6604ouK;CwJB3J}2=-T@X?PVKnC6O6!ohM*2sE*kDH|FVD> zaxdV{ix#xN23|l6|D+-8X2AxIpy~cE24!%v0+0Z0@CMn!0HF%F#-Sa80T!AF)iNv^ zG|#`9?-p*s7*OrdT<*Q1p%|3G!N!3I53LH? zLI-y+u>wmPo&g#r%;m13u#Bp?T#F6c5cjSju(;tGelM}&5ck|`8?K=Z-K!b6APRUP z3d3*_8Ih~T&CNzwQwQM+7@8#-YV zUcsvFRGwB^ShT9CINR%<&x2F&))$9oexR-SHja zF&^b{9_g_j?eQM*5gs>TANjE#{qY|GG9U$VAPKS{4e}rnG9d*r6;Nm!z40L-QjWke zU2?$!fRKqF6bBvW!FS<)p%@*`m~BujE8 zIkF~g(jrwdCqXhNQPL+ZvM1fZ4~ViTjnXJD@+g&3DK&B_osuX)@+qCt2&8f;Ke8&B zk}9#%D2+fXw~{EifFVoBAtSOZ%`#~w@?0DtEZ<@+#j-8dG8f*$58MDQHqtH~!7evJ zFX4g<|K##5{1PsV04{QY3kcIN-y#(d(=9fkF5A*E-NF(4;4Lb0GTovu^YSveAT!${ z72JR`Z-*?;ax_V^ThcO6DiSi;A~o$&HQ9nL;ldGIb1fPZE)>%?2U9TPA~)ZHH{BvI z-@*;vvMq#@GTmS=FY_~v6ExSNGAVN{pA$G&GcIvQG)wb3u`@qT^G_VX2$)kXQo%co z(=y%SE)#Px+aec?U^v-=E$0$B8IwFa6Fu9)H;I!y*TNCLQ!Q$fGU>B9-7`Hm^Eu_S zIjJ);2NXf~vuai+J00{v>0~?kBsKpME(3Hm#WOf(6Fe`JEsFCocQY>h06yDd6AF|q z|LpTMNt7)-lQ7p4E{GB?HsL?jq9PacEOJ3IV^ca;GeOhyKxfA~A#_NIlqn=sPrCC) z&4M)(^F=ijH}O*~%=0phphDXsMg`MK*+M@(L_Z(L3w$PwjCi?U4&MAy9>L zP#vLA?NK(>u^=~7A=gqN8}m35axEP}A^m_+JM|(l)jJjPB0m)&yYo$-Mo8=QRU!0F z6XZ`bvQ{%PBwG?FbJZtzl_!BRD1Q|vb5dAsl2~W5S8Y-#c~vC0(ks7`F1g@Y|BJFI zrPU9jvRbcITAlSPud-UZRa)cJXq8Ow-~vWmI6%0y=k;FoAS6Lsd)H)eRh$UBF8XyXR#q+cHD2%aEb6s9HMT6Uv@K5*PUB)> z4U|!%vt|QjVk>rNz42lLBuCX%Op`V()DvjO!ee2SWX*zL1v6&N;yB~NMB}1GyVNeN zwk){RHl=oBUlvDwc06~sY|SE5JJxB#qA>j+V$nrtiMDR1(P;l7W9e0G|H~pgzm_bZ z_GAqfN1b#obGAlXHeOehEwr|4=hAJ%f@+iVZ^zLP3 zbbS$T`@$^`^Ki{{X)`x)-9j-rS7sr18NyR8{9tyMA#o2DcXjtH!nSI&c5KO_Fez6o zW;9@DmuCUgbCtJ7!}VN5mvp7~rc75a6jOE40#QYDaF^6|JF{>jQ+NS)aZxmO&7yH( zlzdrMF1VI253_i~;&|zGc8Pa$I~IG-LNS^5d4sk=r}uv?b{0tpUAl8bLDf_h(jqmr zF-27&sZvvu)F1V8f+?7St+j$NID;i~Gc~w_W%DyVSc9WAgf-YZ|4A5wL-mAFn1fY# zf;X~-DR_ioc!R5zC@r#vtucQ`}m)_(!Gh>KQ$?`Tj8Q-`JXhkZC( zpOuGkSc-9YTZ!_7O?ZZrRExJ*i?eu!zZizYxP`}9h07R=xj2GLHB~zmf!mmkRn?7E zm38?fdX4yw1FCxK0(E872-J6A{rF$8c7El;d*Kp)OBRvOmwV5mcN=*wX0|-xH!KDj zMim)s#kX=98EpBMlV?|dw^m+Ph=}pHlz&l=<$_6fbdvoxVE;H?Gue1!`E9GTkSBQ= zEcbP1IV>FcYHvB0=QEY*7)M39EjO7gX4HH)wwMK!ew%ks|LoY5rTLmrIW~njId_?l zDKn5obeGlhmYF%2IW|hnIhu_Lh zHq+Lb<+(uixt~osj{Z46uNgrnS(UfBqBUA9L{^d=nw>A%W-%Hq&Uv7B8JE*JlEryv zZ+a{^wxe6xo->!8S2v#>gp^PEsjU%-fk{u&RiKG_rdKnZF|?w=_jO}BetY_6(|0aL znk;sjsK1(adm4Q$IhD1#IV<@*f4QvR7O9DuuK%K>|Dk%X(Ne0ni9!ApcL^Fdb9!pK zIz112tIheAbJwcP+OfyttRtH)B>QdCx-cQzvNL-b>Nj9-xw8uvcRf|2m71iTny*ot zol<(4p;%jixQ1K%S!4SvXL~D?5{Ga5DNoW^i*+Y|RatfQS2+^6msPlV*tdO>w`bB; znY+0^(z&7gB2zNDoqM{eo4LF4y0IH1Hyf=^JGH^PmsWc$GIoL2l2bJmRTubz7kEYu zSW`E$y{)w%+mTW6@iXz!E%9+Z?>kcOQNQnzzwZ&h?~yL~^uP}sQ4xH>$B`--oWY~@ z!56$cQ$fNHe6)w^yTg0K=V-h+Tbr9SpRt-n{}bCods=ecH+bm+uj6;9&6+MC+CS+c zuFrEW3bU}+_OeS`O?w){Q@6VdP{TQV$UkVj2YZ#>`ov3oEk?XO8M~c>6UWV>vcuwb zDVr{!oTk|~t(W1g0kpd(8m`mXt~)oCecV9wn#k20KUN#WvDwCVJb#y5OnbV^ncAZb z8_QjMEE>9|*|*MPJUAH}v*$v71v#HN+J4`e#fuuvg?!B+-Dv(9Zs+32o0PFzdCOrO z(Dz&{`n-^(yewFpm+3;CHNDU|eZ~>p%hxrZL7BA2JkIkX%_F_mcdDmgNm4yVVoOshrfWJlXyHUxhuX{|6n|(fZjDUDnBV+O6HRZ9Utw$*<+2bx&=s24p?#yNeV!4W%$Ic6`-0ZB zec+9h+X>1q*w&z#`rA2_+|S*Ry}B+&eHlJIYw6wHXI$RNyUtA=)Hl7v@vvht=zQ+qi!+SfyLLs~hdH zTkY4L?K9H4-Tv(3Uhe1qxofp6|M5QW^?vX9zVH41?*TvX0e|1$BITog<ku^e-G@QGZWAbM^Ps zk6nKp|1|c;F)qjPFo~Y&ZT`cX{wxgt@Cja40~^cBy=3#s@z-gnZSVr3kuBT#*x8=3=t}12yq}nKM^Y;bd#$hM1)*2YW%ni zkGgdvOPV~1GNsCuEL*yK{|Pgu%$YQ6+PsM~r_P-`d)|~6jgioyM2Ui|n99h*qXZ{1 zHR#68(}I4uOeL6#ORB2}jcnz*%*|J>ewJR{L=kK*t6-NIX&ZLzRYzv0ZjuT%YumMQ zpRTRT)S+5O9l7Qr+?Od~z+6T8d<;3Va0@fz0Jwk&MbR}r@U=oBnr+EY`#HteP_T*sNKTfdGy zyY}teTW;>mxouL$N2?y!m`iDJ-^IPQb;SOv``f6wO6Q8Z?c4X{L9T`CNPSbS#oSbW z2^MZXB1b6nT8-!tgQ!^8xJr;#5xy2j;4F}4R+Y{B_hUXV|<_*^77;;h(|eM#BQ7H%WuE_ z{)?}J{|-#>T>=-3@V?O{%rL$T_e)pA5$7v$#TH*oSV9>Fc&TM%tDtvcGzg!tTxaWqnz@^5yp)%+;mI4^4$`9 zthdB=_sw_25Buxz;02#%IKhM^POwsp|I5X}kMCQ!;i+7XIlf|H&Uxpaa~|R6qKiJ_ zM_6->|9a}GC+c-)8W9Rzvk{$$thAv*blPXL=~gUAyTjJ|N7z0^m+rSSq^4=dFZAq@ zZYqYZe@G@7eV5Zibo%PrZ_hnKCLgTDi)7O$i`Fve&%?DsX|2`Cd^Vf-eFRq;%bq9j7eV5O1XqTKf}C z@WS-G9R05#!wXCYK@u(A*)N3B8{t5*l0WFhFkKj2$Y12dB?K~Xhdk`zOB@)Yf^cMp z#;Tz~E@HnAR-}LDVfha73j7EYlBp-C>IFQ^~s#?v1jS&r!JpEv?giIl%YoI6)4PNDbWKm*7 z$W=Z*p7D{Bgy5|j#F#a@ag&_X9vrhIk?0_jg5z@{di01QFJ23gVKJpf@*|!TRxymq zVkIP3BTMv1F)&Odo+B+u%h_GhPoIfSfi&64WGYi$pJYTG@wf~mrfHY_`{lTDX_5J? zsai?FA|rc*#Y#dDn$g7O5?L9@-yl*jt_tQxhIuY`UehedT&6wmxu|AFQDvOc@~r%`_?` zq$F*sQ@7JhYDy2NHdLucS&BxNj*q4bNhf}UYLJ_PDx6%^C>B$gCa}h|rw-bpR6$bI zb{aLOO^FawpNiMKY6e)ra%QU7%2uqtlav~yWI7Qb+n|V7hi)lIf&&ewW`$@YxiXY6}?trvYl;I2&cD_^(|t$ z-EDyWwp-x#EpNL$(9hQPvg0DRWwBkZ%bM%l14S;n(rp{frk1qGVRySs|I;paxm&gG za#ysaEw6cH(oE-)jk?pN?%Ajd-RSPjWw{lu-t2p~!1=bfzQu3K6z1C3E^fB4CGft8 zW#Fn9xN-#>UFVeI;0S|ma}tiQ!zw&F@}76Y97c&gO{LZeRyI9^wJM8Bj8OLBl(4YG zX=VpfJhx)8l~^1S7JbUcoobeq$>CF58{@7H3wg-iIqjqDqSbHdxGRM1V~Pl?;@}82 zB9R42jH^}IWuW!RXPxXqWD21dM{`y?>giEEDnShsdCjB!FjLH9(Gb@W%3g-bk`qbT zgr;@IVug{IwS4DgT$#%<#-fu=gU}mFQp~xi3Rl(4=14o$&Bl^*|5s9+WG!X7Idv|G zR~yOaDMKX7h5a)Ze>&q&UxmzwzHvtZiqOSv@t+!jw4`s1PfE8`)C-}V?QXnjzXbbD ze|Af;;pgHRlN#A-8TOBy-NGAF)GyQKWuh;76z7P`*0}C=GIec97JF7BzTOM8>4eZ_ z2&cxD7D$Wfhvi~dJ4d``Ub~l}YEI7>$Hh$at37H#ZhL#+Z3OobO>Cenm)leIHprp# zQsu+)Io(@MwoMyekcuy9-(c3$z2n;N8?!o|rVBE`Pu^66W5tfOJL|bIb?+#9D$n_z zVyf?5>KPAuM>AG;x=$T)LwCBai9R!@|0HmfD?NcK7YMBZ{~Gg`D=W|>PIaJZJmZLe zWaoaKvBtZVXP~Rl)p<78Uv-}4wOlIcOK4sfF*dF=VGt~jMO+^kf*cqfEVEqmgQ4uxb zwOv&cAvlLJfnj0WnJpkf=H8u%XNhGrGXmrfpp4zL}=yW*8Z;J$fHQrX**WhKu+seI*og2XT2OXn+_NeJF{*$9HvDelFsMj0Jk6 zcN=}!i3b6GwgP%)S4@Jqdc+ebipYqs=smOt{~nU~bg4mnVnTcfw@7-}d`(1rq$Uu+ z2#RsibMAK=lt_OfB8azCW~0Xit_X|KcpXh=Aaz(Nd`F4Kh)cwm9>iCC*W!)9SXh#1 zhv-L+y=ZNthf1@yjDVO6&?t@Zcp22lKh{`>Fm#9KNRI1vbKHoB8X=B;xOIB?bsMLS zml%KPf^(BtZ159qMMGgs(FWD0kxofvrhjU1W-guD_v58*>IRafh&)%>|9KYYb#;h!(Z`V*nU2nQiAqUKZQ+tm$(A$$ zmCU1+Uj~*5c@#O>d;eGwWcg+w*_B=AjNVv~F0zma;gRJul;Vh%&=F#5*_Ms@L$c^P zi!_&$>5X(rCxuy#e@BiXNme-Njl)Qc#dwuAW|UXycxLoijOm!GsSJft^9gbCtQ7 zdO0i{$xfLkj{OM|$9bNs`Ib^S|CNAgm$(Cxm}rvTXl(KclAQTP5!#!136>>Ee5C1& z&3T$gMV7dvNn!Vwm^LaisI-b$zp8wgQAXT0~>ZNWu zqD8?lVQ7J5nm8ZBg;+=z8#sk*DuPm&TQl>7@U?`=Rj1G8UQI)ULO3;h%BNK0gMSLB zf~u#Hql1QusEMkmi<+oK!>Er6sfOyPk@}2X`lXlpn2yK@M02M$6JKR>GFqsn88fPD z3a49ms&~^k7RWCR$f|+D|Edx=Tc48<2q<9(VyhPBf4S;8_`<84lMBHbtfP?%!fLF? zimb_Mti-CU&FZYfnlI1#qnP@TO{bngmy0T@q+Efd57nepnjj7;q4u+x?B}3SYAWSw znO0_-AeVX(F|E`Zk1A)N9M`0?X&BwQ5IqWU;`*IJ5~1U&Q0Ho!VTq0BTA|Joq4nx& z{SmM78jS|$XrKA70_CqPYEa(DkHm+UuN1J@326RWuG_juO^TB0$f688YdG?-5c`VY zHl(Ivvij<9Dr&Gj$878-t}q&-4mzVWDzXGCuJ~#yENY{(HYzRavWs|qCkkvcJF*3< zpNbK%Jo_!>DzNui|C{1EwdE0^0Gg5nTdrlKv`dSIZk8TKOB&}&vj$Qp9MB5&eo1OjWvo=e&oG7k88=BsUweLAilnb^E z%cY^qyCjib1$(%AJO)RQq1v`#h8?dh{BF2lZ-=erAi)KSxu(^x0kJr1QTZ6IN zwgBY12@5FVdb2nyzV>N+tt-CZi$=)1v3l#Es5`x%Nf@A;y^*(^DAc`gn7+&Fw~!^i zj!Pqo%eEnmc;@nwGLjzxC^O_e*a1`$GMT703&}2C}?XYaduUz^Edw z&#NV_3&49B!s{x3;`+c4ymS&gI}|Js!CSiGO1y)lx*u$FcYDKgySmF4!WOJqimQ0m z$)YRF!YJp$NeaW!w8TAJy#KqrC0t12i^JRE!REVXv5UL}a>7_U#4Ty5M+~A#ygp4_ zvBcxL(o3Hn+`h%=x>fvU#v8Ife8Xo9J>q+`y4!O`EXD&z#ux0tD2zhL>%?F5#yl*= zN5R8bthG40yj*;-|2wx|td?Qi$L9IRF$~0cJ%*Q(V4s49D39${sAjbMeRr zY)N~VOU%mlH_%p7UXEY0uy z%+LC)qp=C{Y|qKc8uzTv!s>hc{Hvei75{920zJ?I$T+YXs}Gpa3T=USBdVoJ7!O^l zBdDfTAu9O{h(N_r35j50Pc+nV0U}d<_X8JfD{n0}f(jpDb_(8~?oQtH~ z|FuuS!@eB5Z`{r5C(c#9$pewi$4JG5iO05EYq9*)K`PbnJQr2X$`It$WBrj-{M8?k z$lgrFYK^#1eAad?XuX`rH|E#a!`5xxlu`ZG35VC|Ji#|S*my12;5^EdE!ncmaDgq^ zS+`&Ds!#&Ni?bYT? z-QqjW10uQ5O~vO8kj_2VxYOFqjeewzm3S@Mk#sfN&D{~}-BbM$x2(m|-Ncnk|HZh? zcfBkS>OHxS{oeJxjhr3W+-$x6dEfb+oTn|)nBvtkyh3>G*@fiXvrU_rP2ci8-RHC5 z1`f$5EZ7Zl}Ro=xw) z%a|MGWv$J>?A#^3DmBjF&@0_PPFc=<7&P{%U#II_TD_c-ceq| z(HG@(ZbDJcxl@Yej_2opo^ne*=xJ`}HQwRbR^_+pnOE-IiSA8{PT)NU|K~3i<=HJ) zqpj&}8R*1qXRlu4(K+RBj_5d!90;D^${ppQE?JST=LaX>f@bI1lIgQ9Qnmiw1cBU} zJL*q9*^VCNTn*T!{_4pt=^`}jH7?{Lx8uCs;?8c`oG$G*K z<*ZHV;!ey=Vcp)D?7ZFV=x$HY&fojQ?p$uJX`bx!zU_Do;3OOF6!A%?6SS%5uV!|9wQvz@tySXOfK{2 zhv=xD>MFnJjNa(nPV{Gu@Z(N)7{BO9zj$9^^EbaqIgi!~pY1Vg|Hv+1;|HGYq;9uq z9`yTe!r|`nqi*hfyA@9l^#!-&VDB1PZ}Br#^*!(Ff4KGbuI=QV^(f?<@Q=} zs5C7#L8$(H%KkXW(vgGw$=^LW-~LV$UiV+q?~j9P0}w|1{|qEp(BMIY2?q*P*w7(D zh6f!@q*&47MT`@TWaQY<<3^7mMLOc*XwylQDOIjy*>aN`KQ3j?WC@ez%}uFv?&O)O zWKW<$g$~vElju>TJGrsPR0#f~Lg*6dldY1OV} z+t%${xN7A^qg&VR-DP?8?&aIp@7`Q)HvJ`BxUd^Xh7~VfHjwe-znlC(ro1PwS@8;dx_iy0Ag%1xt_wMn! zxA!7e{@0P4=6-W=j?Q;<^}VUF>!rPY?`Q9MO@~hf|2;hI*xm()U-q0m?CQCR&!=DC z{(b!U^@BBz{CIRX%=7ND^tM}%yw=#e&O7bG124Ssyz7oV$IeSoLgvC_tw7o2+wVgV zLlkjD66fpBKf9XqLqP9pd+$Q^24jyp1}9_h!2ww`&^8O%Ys^LrdGwB?=sYa(NF)=+M3FA#h*U7K8-?6%Iv*SKE+!vwyb{LkUh?rk30>3>Oza#1vO}wwbn{I(jMZFNjnl?zNp{|u?D^)^W_)pb{1du=OI|6KbN)-i3Z zF-u5E^>GF@SHjK2*k%Ja` zXy8gtF|-vE&X&}QRl982i?IXr#+hZC@V%NGkzVlXg*-{^toLI^O zRr+#A8|`dx!#npJWW=LUTxB0gS8(p=G*=Yg>Kt#latK*(ZgH=5uA8*LwqA_$&wKa1 z*U&Q?wpgg!R_<=MQJ>xT+mOF4W}IOkQg-Fw(^+@Jc>jHS?&S=gvf&wJUN(C*r2hD- zWs5r1^j#}&*=4$pc3FPerk_lY#qNH8{^R^!H04zFt1_(bv8XR;|ituYVilpnm?x7?{AXd=eU(A3XSk^BoKFL}#LX3{dIqYx}Z!%OoO@{Fe$WORl}8W<*wlZx}D zW&*R!%v5k+CD|Pvad}N_VnvsE3Eztf`L-58vof0)W0X|cJXAW9mCrk;uv|I2b;<^g z77C;-vw2S)ZZm$QycRGA|5VP~fRcdUh6oqb7jUU=MuALpUT=v9gMftZ) zS{mq~Xe{Uq#aWq0%1oH))XXtsSwfwWv@#iMp-L%Zy;@q+qBFgsE`ex2_zBdTg#_qr zdP+W*Qs$k_VPhK$S)ogi`=DR*hnR(8rkd5i6#hTd}lZGaO(PLR5sVc!jcJZt-Rcm2?7rLo% zYATCmY-1h!sK-WDvQwd0Q!I;=09{tILoq^5f`Sv!resB-C9O+J0@{&;#1AD&ZEHKi z1&6x!A`dZ$8(>RY|J>p>BDu|NfPDK~E-dA@!zFHUjeA_%8bP?jMXO<*E3(i9SGq<} zu5_(?UF>F8yV|YpcD?)E?^YMN<0Y?gjZj|nrZ>39GeQtvR_Q7tx2c-Dah(P`=Cx|t`_STig(=UkB*u_b5buYk>qkcs@|Nqz68U!3cNPiN&McLqyy zm2zhGx}C3r|8>Q6galupTkaXJD-+^B(b+Yg7HOHE>|st9Pu8ej zsT+!YY;fC0pP};SjFfGdHfJW?AWd|P+x-|SxANSFnfG6Q3}k6L@!R3%_i)BdR19aB z+v6NK__QjUgKrhbvJNWHP`x`=tp-W4$9&aL8bL!+~vhXqfG( zau>1W|D6#wd#a)in8#e^GpBjYZGLl{=UnGI=XuY4{&S!QUFbt6deM!3bfhO;=dHxt*6QUF>5gd)du?cC@Em?Q1_f(=UFsE_vK9 z4?lCQpS+Avi+a==7i!dTH}%s%yG(M|3m)!pc*G}O@r!4C;~oEa$VXoClc#*;Eq{5; zXI}H0=X~cq|9Q}FzUgROIbI3Rmo=mL?$oY!SOJerzC*^*k3KzMx~>>J1VSFW=Y8*e z|9jvEU--i(e({ZeeB>uz`O9a1^PT^E=tp1r)2Dv(b^rFXK`8d6vHD}a9__pPy7fH0 z|GUUdZROW1d0BXvL-pPNe)z{<{`04Q{q28$`nMnZiTkI-eXMnt@xR5my{n5d0sNub zTaEyY-tKMJfs3%o!K%s>s?z~R%s{j;1Wi@;CnKGfL0$9TF^3cm#u z4-#AqQj@a|YrxH!Kn|=y8@xdr%t0N*KM%ydB5J|cNWU3d!5=9Sqws4 z+_C$)N8B*Ra|}p<9LNkz$AW1kL&Qg1+(ml~#(W&ZY;=x z$oVr!jFYE_L^oZ`J7bE-cwER{bit9NH;3Fui$tMkj6#pBNt?XM<^xH%|8pMz+&W&= zMJU5XCHzECOu~umHeD3PZ)^^Y#7U=oN~n|voy*_tjmQ|O-7qctaQ!CxHrP`=R7 zl2TCd7|oXwQrlz9S#i%aGtwjt(+ic+;tWs3R*s4@a zT`h}*>@J?&FiO-{pXRq4_KE-(UH)dF4J zRbK5?U*%OU$W>aMF6ly5V?D0(I@a`h2-^ZxXC;VcjW0~C2>Y5={Hj*|iqz5~32g^GpVKjaPU*270B}VHk!|FalUOhIJnGel2g;>f$t7E;aNM+2SbnwGTPT%>Rol2FTDslCk0nsk+*|j= z((n9O6fLAYO%sJ0+`_$Gf;?P|<=T6N1tS23U~pWhDBH>X26kYFdPv@SINood1z>;$ z&3y{aMOd}1ST<;c#3fzrU0aKVSr^P(uY*$3|I||JP+Gesp*Mw7*cH*kcqrS&UHCOe z!$e$uP1s;y15j{Wv3&~3HQsvQ2YQ%?d8h>f9$>LvgE>4pr48gmfx_RIDZQ;TU9hlADeq{qT2-x9` zT;vU4ci3Tf*oPk8hkf`5eei~Ppoe-`VCaPk2mV*mtyeZE1?_d*uytU^tze_g*uwDO zy4_fgEn#?5TKPm2@?8!u_C*oCAr^LFHCDy>l~>*k22juf8_or?1%~4dU}5lv9|mGR z=3{s81|p`1;{}H3U1I80TTNgCo&{L_|CI_VHdqLbV4ua}aQs-hvSc_tWi>2hdOy8wt+8(v!r-fS9CDAg@OA#bxQ|{(CY~y)V$Yp+Dhv$t7NVece4hBBpgL~y%fi2$SRo>-g-f94bUj}CG zZDx4=I7?1F-L&Lfq~>f^j1=yhG5*ViUeRUXW^dkTD+K4CtzQdf1U4w=$xUZ(@Zok& zX(0aNdEkd{;N@Nh*n=enBY;AQEhVl4oLsE})V{{Upqc86LJK^ZTV24>4@aXmBM7RUECR^1$=>-2{L6+RU zrtO1vW(lQ`+}>b^#_t(}W>5a)-*#vsZNvUfYh=I~>=5E|%-@ayScIb{>J$%`3 z7Y}pzgK<^v?qIlV=so9Fu<#rgYnJYDSb$zwcnUHwgk!F8SOy0+&v7E=2j?|ggY{g5 z&WpkhDB%7J_YO2H|Bvs5q3=WgO7<-b+K3x47jsLWJ~HQ5HsFKcMRQpA27ai8J*Q;^ zZ}WZdhEd>$S%`C9-UKYT>;aE%&NlT^2W@spVkZ}L+Xifm9xI1F@x=a3;Vw&u&hi26 zZI;3z6jr!cP9k50KuVfDclNo z4+IbHAwUET?g<170g^!1xA*C@zkU1m?R&a=@N*4nylc(*&iOo36CTt8l`>Ud_=gz{ zI8`srv&3jt+Zj4x_|f@E-Jt97fq-+nV2n6J>p0y>59E$C0rs^>(aWs48#6!+P{lntKc#}psK!I&VK+vr2I zCtZ+Ec3r2k3m6rMmi;EHO zLN!bcj#{!?x`|acMgyYTPsD}jCVn`WVZ^^cuOmAh^e#3?1OTFV}LpEC!h>$Ee*#jHX`cvxCg%eds@9 z*l0(U@&>GPz{e_yi>O;?j!XIuQ5em&Yb=&bQtj6PKZo8y+n=`1i7pR)0Q; z&e~yGux~hN#l`4${c6Auelj2W<@-yWxBlUthfQR?x;2x0k(JsEoccA(pDqtPHl=Kg z6s-FM>OPNQGYUaJDtSHW()s4h(Uq1619&$F!XANm4L{vq569v&NsU*ftL41)-tQS}A!&+d;?=tzpHhm!#*v5` zu$`tpNI&b#W6qica~Xoo%FCW4_ey1sRU{U9*!}(lNc{m96%n4fEtkr-5f9&T?3Z-LizEtW zqTvbaYGshe8T(x2a3APXfR7)HI!8hI=m0!)K&@pgcS}3<-p!jWU1Z97O4)I&nF82% z(Ns?`%?zmAcuiX;nvQH_ujfI9WZNv7);GS{$*&K!%Lp>&aO$aWvy%kN50s;bAs za?@B?G1IHB^mqMUf6a>ZRsAkZxV{O4sjy`jyo4-ejVXdvwV;X!B|^%(*bhtb?=xDX zb4shQsbUej&*N(00^stUt60LF6&7z(q=8nPgWIXD7o93oz+ppi>+_>?k$;sooE$ZCMX7?iwdewunw2C?o z3Vb$#a?O6O`n9CeR%^SHMX9w*39L=|yS%Cwh+(g+5D18CEfrAXr09L<5$#Y=?cK^E zI#Xhb`#=rZ$>O~V%&c2AGuVGDyEoXaaXjn3S@YSHv_fQZ1m~wlBwupWr}f`RG2Nt8 zzso|{q)nj$Ri`=Vsf?SxR(}#uO{$)s6Pt8N>P@kUHmAooxSh_qh8#X)`84A)n`pjY z3~&Ax#2ZDmj`%rPU1AS-bn~?;&z1KqO|a`|4rM@6&EjL)$PHR0 zr7`&FnQ*##AxPSiUo|?TGT`X;!fC2~!`lk5lv)X~)1mYvM9@cQX@bG*aI*NX?PTo9 z7AI`Jv;D485=DI)7Bz<{6@l*&su}F*4H#pwB3K3M>+DKT zA*?~qzGd#9&SR>$%;{~+`@MA=g8&JoyNA4rui$oWj>_2D;bp`*h*1`LLYNxh2T}1k z8V6<%Pu3n#W||`=FJp@LfP1&JzKlJ+hKgBf_{2M_eX&mHWT81St6)P2M+}R7&UhFY zP%-)W%=MxQKEST^ryh;o3xKsf2G_MBCir8_Fj5d~OI$RMW+U8+r4?RQQ=>elldh*6 za5vZckI7 z^s8OWcr6!)u$GsjbfekTK8dp~C%!*SVlll9T!zF0N`{OExLvD)%~a zxp4!9&H3GlqR#6oTHYW*@z2APZWY9dr5X;s385YpIhUuEv_8}vS~8IsmFFK`{J2ki z1g3{vqroLry!24lh^v6+D!rBhna2lebv1Qdj(JNfN^*<6IW*6Mo_^atEfS?V#DUThZD=y7UZ-x)?6o2x#>J1J z4ZV+eVkXmJmim%>-Eo&j2>J;9$98vQtK=`qapRBJ;;+?t0lou_cvQ=~S0dTfA? z%{2Vq+v;6K7NmMPz8<(ufB1+TkGO#2_&blHk1tjOvXNxdwL>w=2Ni^9;usOw?d9Bv z3E0ZwI66mBjt7csLNqEpGoKzxU?g>GCA<2)e?955NFogY(S*)^6{>vt zCCu{8VEVm$BskqkD$yRUQ|YO%@#`s3iO|(z6mjmF9T@}x09jgNS@JQRt+rs$^2kJh z<0Hs@9*4j10x&H5Le8oKQ7{a(v7a;B?Mk@#!aWDBCgeAG4x~iIUTNy?_)j*EOJ1gv z&tMDOGBnTc2YjrQ^2@UfUD8Q4=12-ZpO$?VyjIzk)%?w~Hn5PqPg&LBFeRGeao(0p zIt^tjN5@;od<%DoeiZazjU!jMMbK08Yb}RAK*BzP+?GB{{9og-~70Rd#Q~V7T2|Lv(~GrlUEyV47?^K{3a-h>h`jq1boStXswsM z;)EKpK@J$J!jU-3vVzQJhR@(4EvOi|D5A@#Ppk*ojI9NQP${=$xSUZX&cjLjfMm=O zJQeg9(J1ThXsN;@xGH4Hk+VpxffGTi--_aPi#7@Jt?us%_hHDG>*o@8W#R#JO6TDg zkjYT%=KY-&?9}Yogh4%|NPu>0S$yr3LnF|_$RA!PG7AKc%5d?GfX>h!cRxjoGz??W z5A!XfGFt-}DV|{2q7dPXJVlI<5Ln^s%L-J`;~7VA7244E4blRJXq{y@?yNP9^`Yrc z2yJays}%2ROGxwS!Y@b%S5jKUfs~WPt)vA1CC9F#tGq+64Sq42LqA!m)^ z^hF92q0&Fd5Pq}NC}iOKJ;=ZeqzsJQ;TR(U!6e#tHT?6Q@{B;Bw15ZlljMwN`@^*B zC{ZBmM-v+jeM{-f-TNPyF(#i;7!mqB_Wm*mpr#V`WjHFy@QezwNT8f%v6O!~ifOM@ zFwGh{{*VYkuS_(=c^yusz$8J>xIR`o)`~*bGDI+s0;ZP})n(+-jMLb$x5>!SJY&|n zVNUx)rF{ToM~i4W-IQ+H)S$7^yWHK@uk@4Iuk*E`2xHJt)ix~K#%dVk#I#G7Nfy}} z#>$l)yF)=A1Y%{-PyuAQgye1mmvtKx{}wOvm#BQXyeHS_R#yzM7($DsVfAc?9hoYmkqrB|POt6{U)`{k0FJ_e?D`Z(5sc1}kQydW**&f!CraYOAlWr?Zpsk3wk(KQmUK`CRY8{AQx@($L|zEM@r=OR0+4&k z;J8P?gI(ZM5riSfxfw2b!7jOFF8M@`er+y~N-@Uy!!Cu>wS>;HMXSd}8yrPD$3^)r zCHKcAVYRu_M+hR<(&-vPijz3VNtr8qtN^53)wzPoIZD;FQWX+$P)%rkQswPheZW?- z?o`vp#))P{B2-c{z(&68#IZ2U)B;#*m0@^&0ty`B0iaT?(}DscI02~K*0P(G5!{m` ze0x9$%>;8H0Ne*)#jFqFAqtk`)V>_e?{w*KCAM8fb8KTI>x?E#izKsk)FoNylFF+M zsjBg<0=~2L&-&6GJRKuB!PgQgi;bmWZfXh{?c0m*;2z;^iR2lj6%>QxV~WvX`gJ6K$*;;#o2!!TzWh;*5BP-M!I5anKq6m%d_z{iOb#-&IPYd0vaek@ z-9JuSw}Ww&aQhy<2tv)mbiU1+?vJ z`h4Ay`18T2!zGhm(DUxFxZ6;h5e1emy_r(rZ#de z^&4Rm)ug8@=qf#tv+~m|MEA zgUADvlbyPX(^Fm3BY(x?VvomjR`nC?u`cK=isEdSH`yr^cAB6%nczOGvM;cA7R}HE zyld14G@pC(HW4&;QN5Q7<(d@uhMN8TK(qOSY23Y3+#1o@)I-yb|M%anb3YjsA$%|3 zdoMDPrAWiPy{jA7a?kg1c=S!qtfzVZK=@8n-IcvCeo0}_*jDPFeP7i4ewL7M2u=QO zh>!N-J21*Kdzn{<#&h^j^PT34A7#z@*?dEue9J}6s{<{1A)c6P=b=L9BlZ}Zbcm}2 z>_v|R{DRYKS3ZE*G7fRFv$rDdrYG^62~2PdTI#oJ&HZa^uPxO|?3Xt8(`P}>V^|+N zfln_ea!m1lPWy7q(j1CO~l@!Amo>&{+eFH7Th7uUowP{YdtZD^x+iC zplPPo03^`a#nnDIT|n$KuofU-v}hL)%&Lsrq4TNUq&FMuY3JggEbUsDL_zz}7s8_L z?BCS43hoQhymsTWCPH7v%hgIW`+I(TU2b>Voa^uX`F(37G4zSnK;PZf(T94g_XGXE zexC2nlxV#j`19-b>g(qFw{IUG0qE>o;b>&eTM?M7HCvH5B1c#^;7c)t7C)e9oNAV*0hcYK3UI zaFOaKMx`3j7{f27!Zd;nO5F*K_j)#yDW(&3`^OjV6CIvG!JtHam-SxWnZGp}3&3}q_vu^U@D8@yFv-o9C zxy7gSHQg|rwKf;06tB-`>%rS+i~W=jXE^tKhui5Uabd|cm(P3NsYu6BS@?DJbJvd) zHwkq3Z-u;NdK6VYbrEu1&Q1I;ON7MGc{_%}v1U7##{XzLjy{%sC!RUmc?ZT`RkM@8 z)p@j&$T!Zunvk>zyWn2;Rwc+*nUaIu7dsIM^#7U1^GXQPoYw`egqFw9wYP@@!5YJ3Q(wr1{ zx9!cwYD3GS+^_oPkvZq*DC=hw9x1ySGj1|~f7h(re`%I7A5CWzCNUk3QcLN-X_o8y zWb3Yc6t+C8{ZVVhR3^J#ow5nHF8+TT}ZQY?;*ibH1}z>7Gurx6@;1^7#Nd_0#UFl$m6a zSDLi#7bnYlQ2c`amouv$`V${>y85qgujb#!D!qRwzy5K$`zpkRVBq)vkGuYVOS6vm zGPR)``*3|jm;Eeb$J+gDbN}Q09P3z)gIxP;mxDa#s@j8m_s-*k0?%=d!$RNBE{8>d z2epU)o0?_#aC=oP4X9aVt8W|#!X9jBI>F*>e7TX}R@`$I?9@E)8Oy!J=O*8^?(L## zLrd$hX?@Wo*;Yfzhf9;jj`ziNr=9EmUr*m`#d4l?iSV?~mK+qXIrW^JO?mVN4S>HF zUCx;~_210FUJQ7h&3rF-SmbOjJ|-LV=sTh7^B4+&te?Lv{ku#0%g!+Z7?5@@>Mzfu z+#=KUmo{=uwv@`m5Rgg~QnWG-!$91weequ96P_f}!M^O?%p)031k2RL2^gUnL{EA` zg1ir=GX!4bf1JuVoJ4vEX11I zh~VCJlxvlVwmLf0`kyX#+Ts%7V*cxvTmymulmI#8xk~ z8MC!)6o$tM>5JFd9f#2i29r$k?@dOqXcVj0F4|2;VHnwd3(R01OJuZ=7&Q@Ocwfx! z0%XbasaYuh>y}KvuKiH0{nsr)HW1evwS2|k8@KeKR`yUC{}%j!s6YCo=(YRC7i8ufh>`JwI0bxm$KO77rp0xhnYy080QsPu_Ich7+ znw=-L5WJTu{2XazBtL)ZCAZszIo^qk)n~LQkHmpye*6;M{g~>lE$JxXclz-SoXrmB zS`hgqlgLpYs9uM&W~s4_f9k8)p8Qz;Hu8@&@u`bhG7%-T?6UkG`QPwVrg8u7~%+n zZW-e7U}B6g^t?dE1k~Ct#zdY0W!oeHZ)Lk=@{P$d8J;ucv^Y@w5mV|DY;k*8D4j}0 ztm;EN)4$;lL8NRLk$?Yz2$i)FM9j)b>_U;+Do8|#MW>+LYC957k)!^4GQEt5l>*E4 zoATmrMj9v^Zmx1+uaHI43xF)gYel5+fQK7uKn@W+G(OlgCKsBJ5+HXN+V#e}i%vu1IJo_{*E?oxqQ#N>_@-G; zWLWDon1pf3DwI=nw9zHL5bb;%2l<12nQ5G$*<3OAhRHNAqJ2Ue(Vx!0IMy@Xf3Gqa z?%%#*`NV{d@;96;f+7nb1W+TtO3+_7%y_UwIueuk9@UetbR-6c7J??zTB;C1z-c+E z+*&>sM=NPLOL560o53QRE##cRB%cf{5|iyZryq?KaKaNhB68A%iGugwwU=AkW!Rx~ zUjnbIN2@f6<&srBA-d7pc|^3qgd9uBsBa@Jp#GH05%#?3e>=_p6wd$GABZAfi~vA` ze6jq$UJMibc`ynS)MlFnDV5i+R89Ae=VRp1MzG`c#S_BWl0g!|>#tRqpjySsu8Ruk z71LRqw3d-7f~>>r5w64P@n~3N;t}*&70bjb5oJ*D?NvZawM+%@4~q2(LEXn%gG2~u zFbg7AZPso3DbS!{Dca$ku6jLL{~4*Ide`d(@-CQWY2QH4~G8@ z!!RPXQxFjSpW6AC<~;N?DHu~NyvR`AVfW^-!u!_!dMbmQUMS7}`#kH0lu&xX&Su@gpss3;b~vHz2= z{4X&Kqii=^cbf$Opr?rz{>*L{UAc!T!$@?nvztQ5YP-wA`%iTIZy1K{em6Dd0now{ zV-bwym|_K`a7=cP3S`Z9yq~Pf_ZV2&%9pC5q%SgcJ+{sb>FjnWaSg*dijL~!V9oWX z`nxy#r+1k7HyLB(kZ2FL*!)w*&YmhGi4+XF|G=rK^qjHg!^}wUK&4g3e1vH;okh~E z5XrKjCY!;hNTx2Vqc>bgM2zyzWYL-@i#M)ruS_42Ss`8;$t97-x)`Bf;3~->44G}R z8u9qkMdWVMYW7Z7f5wkXyOXFrn3P>~@55^kEyz$kiN{8Km?*kPm(dmxn?@cEo$;;B zmp3E~C=b2M=bOL;B`G?v5yQ@mD2t(?sWZ#|+u!>;Glr?dBsM?}kXwS=Wfu|G@T4LjnaYbrC*XP{~F_F$y zT5TdqW;cC9*lt$6Unxt<)3$^C9Dc^y)l93NY;Ybx=-8CeKEKckz}Pkaja2|8+tMo->_V(_PV9bRnT3l z=*9a316PA)<2NpMH>AI_JZ+L*;eJ31$+fW^jp8VCfRVfIPH}O&UcA;%%t-J@)e~Y~ zZ8h$zptd5 zY6jRnjh)YL=VDo4{1t181b<&HVWkistj1R}kW9)K9-zhk9;;8If#iI$!U${n0Ew#h$`EZI(P>I;I>@Uxwvf3A+-Web%%!TZDQvu(Fn< zj8#fSo~MZ8I$J4EPs{cTrh)6{491S!_4^-?saDIG0d+H7uvrIz;=PLsS<`S2?Zv8O zO@Q5IKiXrHB)IEftuGFYq4_PRb*DH5<5ftK_Fkc`DHC}%7Uar)I!l;Si22s*IHsDk zT8iR_;L&^;u1M&+0Aby=x)`d2rv?6}8=%m8C~f=gdHk3ST~1-){^j_1NjZq;{~0}d z{NInB{hw&yKVmgT`KcE+#{XKmX0~n zis2GF801-wb+t_E&s|5W5UQ%|<#CMpRr%Rc*oS@|ZM7%06;hAbU*W;i3DpI)T{f-( zjp)cVA1tO5wAvZ^P0B|_d9N6tkcs_Is@tO*#r2lr_ zkLoiqIYNT!IpH6oZ_ZD>O4)ERqPiFPW%P;OdW_%_hmQBym1@A$G--)>(FEVqhG;+G z_HW*EBtL(x&pdm|b>;nto_sz(LHgWxP#M4adhyQkxA}-RD%TJ1ZhhSI;YIOM;eil+ zrST_`7lgQJF2YfF^-0p7h>&bBBtS^ia{n|)Z=16Sr?+gyu{HpcR{cV`& z%X)IYry*~8b9&F3&B*^oZ;t^qC=vjJe>e0X9zn-JV8iwJ(o!{-QQbWaCHMpVGglaQ^PBh&nr?r7gD_=CiUSQ3 z!ZBGhOn5Lw02+(K+uH$e2Vx=c+HJ6A6aC7X>XO5se@KI58usv=mr%y&5RBr9H*L_hW? zLM`7OYa@{z<%k8Kl+Mpet;CSGuP>q-G@{>qo@-AY-a5$~A3jFGoEvnul3&aO89H>X zoa87af^Lkj2S41l7l%%OCTIgwB<^V|((&MGJV^bBseBO1QLiE}!48+MfZCtb)=Irb zZu4doxJIt?CKKXp?7;TrZ0Z$hx^>OR0Pun29GuxfL;*h|Q@xI>}!?9vLS0S7d!}G8I*{ z)_kh1awg}=)9IuduPTjH{1+#Cm!6q(1?JxTLb)f^?-00AR7J3li1bQzA3{G=gQ~^I zg5Ub5fmsM9B{OjdEo46ReG7Rn-kvT=qe2I8!hbfap5#lp+!W8t1b(A39`r2sZXcC~ zdE{=SGM>45<%0TLJMoF0ntC(Ac=)d%a_uC+MHX_BEM5YW_mysOTbn*D!0*A zBtW~0K6e)a`k-DIu0Bb7#Yu$!M+v8Q07b!4GSCwCj6ibw06^( zH%25ssEoy>Y{;@}bI6bl(ndeQ{s>BjX1}p^1A=PGGckzZGjN}1PY&1AMj7B%ur?^nq>iR4FW-p3qS74bT2n^l3#qHci{>cu?W9vpLzGO{ zxzY@LxGFm9y0HMFBjBG?V5uN#D%l4o-jKU8^CcP|! zCrMR&-Ptn_8bvA(Q5jv>7D!bUiACdU+Z%G|?&;!c(N$^618E+p!ZIDlvRSmkzHxX~ zf>R`rGhUV3wyQMq;dH;J;!8{F*(x+E10&uIXXd>2s0=*ZS7`;ybuwFFHJ2z$4=Z*@J(A+(JBc|MpXD%yQ<6xcAX5%yr1qPD2D_NE{) zgL`YDX?wm51%BH5P3R=S0jY$zy@R&%uQ~kv6Yu%Q)N*5PG-<_MtY1CsV84E;>$tHu zg_Xjy_0#^-A+Y=x8bGYtt82B~sE#?XP5dTesv6Ao7UxsYHOY$%UTL%1o3aPbmrEVA`D{*t2jDYqzAc0X{6R&{c+{3WEv*fymbzGLrK z)5^y3a^zHWUtq+-#4=mYuzSNq-!LdU%aV-5G0(p2ZeRWH;yVGzpojq^{wBVmDD)0E zBn$kPQ)H9Dp8xMafE`dAYcs6PBfbrlRBffiM|{lO~rpR48DgB|LaU6xw) z0xn5l*)HTx&(=JOf()BSDdkDFS7@FaFJPeere1 z=*b;jSjf3=tR1yYI^n)5vlW=@ntdU<=v`VnV3hoiX2%Kz-%xM zQ^n>e|Aqm6A&oa1;OW0aY2BniGtaKGxIb5<3qnHeK!R{2)J9zMS$+o~;6~0{%luiC@&xD{n!<<&0s3^WQQ4m%W%j4j> z;Gn>wCu#Z2bl&xI3i)@EKf#NPMr{i9cqEC2_0Wi!mQFuTf@AYH1iWAT3Y_yc`mKKj zgZeJ#+J>TEQb7xi=>a3G)Ia-P&o=Ev0N8nZ*9Di_94y4ZzCA7lgne&SwZZ9}CD>Ci5fq!wioBw*?j@ z*cVMG`tXfo7DN=T9IZG=K>~A_6o{r`o+yeKGN(hiR&rA%S>Gf@th2CwflHSe0`X5r1eAt4O0!O+kN~L*i6>^?PKB()O8=pgu7cQ3XjZ>pzn(*<7L;*>R{C^zQTmr|aFx zCm)0UKsp*$+MVUI+c{*z&9DT5N$Cst-Mf2Tu1>zph%zi#Qqe2VL&`aq1Md+1jGy1M z?oMdKG&v*nhtUPpMXP4wzGtKI@6#vJY2@z~isQa_sE1&V#u{53)2Zk1SoZnt`xYlw zHx>4*Ni2EYaK#36u9v!9&4u=foUKk~HGc@|d;R09qn7kDquGOMOH1<4k8@51j!PlO zZM8E>25e4dc$0g2)jq45qn))*YtLvePTV{91;4ynCUv&fUghw`GZ2aKjwNAbCz=*& zrF~5&HTdm(5EZw94=h#Wc@8DP*PkEZJhWDhAh$Oj1Yl$XoC_Gp;S?jB+t!nERF>NF zgB*8&4$Gv|_7M39)IfFHXcRyD zOy*3u;YoTXW)@Q-y@pV_JRYn4mJ4xwbfmV#Ey50kVuedsL&}lrF@1`wM zy2po#d$gE_+JhJ;w3Mw`^%({Qoy##a6i}p%$MlE+KvI7UTP>v#6f(-v(L!lTJe`9( z*yzgFy9uZU?y;#NY-s5-+%$;`;VgO2IWH%%V>mIowo|C5aR}{YfLKC(>XBHi%3cMs zZ})w$F>nB$C^Q$>nY=V0PcmF|`7Oa#ij%D zsKvMUYF?wdL`N<2j%t3u-93&j*IX$K2OXP1*1~7>Jci5Fmwy2fuoLwG)^fJfl7~=#arC7$Y2`qKUanE9?WG#W{b+_4ZzUx4; zFZ9a0=-w%k`C7Dl;UG>5K>}&)isWNVbci`aGM9w6ed)OjIX-;^{vQ1V) z;eX4a{7=m?0APtifs*qtAN&7ied7TDb7bKCKdi5~b~!ZTuL6;&w*B!;HjC-PzY0WP z{B|4be_7vj3BMF|=xb!^8$?BmOntlPMbs1`Q{UIspNdu6{B3+)@|5ayL6Nk-^f^}A z6~WE|!5yd54xYQijq#srmwTM3Ne5pVez5HIKz#{UqhPeE4#rPa^fS8n2-F$EE>=(X z+>S{p5SUXZ6>zGBE$GsHnQvQAX-Y+JxA50z78wzj7|VbTjhhty`~x3tz~ zCZAupq&F!#*Hki6j@1-|r6lZegI+(L)TOs<2-K$=7> zWa18$ePPTTEmL@3U0y#YlX;%jN;hKEPOFmets~!3?OVsht+2Djx;GjJ^#>yH+1~SU z&hLHK<6!sx+k^TS)%Pio!|t+5H^TA|_4@BanD`^;Ojx3YFB5nCAt9O_jHaXAzms`>J-ijU}f@N#HFVaqT5(I*`!@nclecGeO zG)vYa_iZ*Q=K#U3gHP7oMr7(-=Vy39nE&ds=SKG-W(1xHQ&_!6=TYaTrvF)~G*8uf z3pMl8&5o-F;jiOS{op54QH_3|tOn?w$&T3dhg@0hCigET;S5NA&iOXLdj8?9`0Ucm z%g6ptUz%SDU!ECB27MYy;x)PZh>UnDNPKG-=_L^43!XO6=$hqDK0aqvOH)01uRE-oN~!nkt_1Mmr*%6hMBPx-*99Q+bm)QJ_!}vU?dI2 zu_yi#C@kXJXz7CkMtw1)Y`hMn{FC@zr%R4ZyJn66v>L-ItkSFDkwH?y9>cDrGOe4j z7>n~!4(0Wrsz_P{eoIm%my^nj>1sx{dsij*q4kjE{bkPJ?@9))BP?x-tK3QTDuJ9@ zb*cHYJn&0ap%uk<}#ta zo!#i}##xZ2y!A+_1`hgCjj}Rf@ToOPR)W>JXi}skUl_Cck(8_#I8C4x&|*Etr)(-r z9ENMd5jw3}J%P#H$4NobaJVT(HR-+T3!AkDamb`66iF>4=Y*FpMMf-!_pllb37+U+ z#VZW+ccdb;clB%{)Qx2plCOSI8TC%LSJhO9RER-zzbK7Y?&u|Gg|dtAkat?o3R_t^ z%)CUGz!_it>Lp?!2#$LUR4Vp$zjclv0$HpZ(-Pg9D zf{YiY?qa({)$C&|GAM~o?x+;S^dNr3LXuvZ92h}??%$1)q`_`X=|0m)DodE;b2eO> zKhM4lS6k|7t9)vuf95@sy-7-oO1(D-6~Ix}bE{w^a!*F%&qsmr1eOt}VU7#(V1RXx zDEd@Ln5`whX-hf#jWTC9!#+fk1VVn2ry86xwcX>mDvb23&qJ9bTa(=afn*c(Bdo>z zDVpIskCY~3am zMiUriu{F|Uhu0A?tZ=Wy&uz9tlz4kje%@_|Rt=Xs{_+VyeZF3I6!$toueH=fJ;m;5 zhjNiVPDB9(Y^Mz*BN>S16siRqrj-(ora`Mjag&|b%ZQbDc&S^r7eWu@N@H8>>kQ0o z%{i*4TQYyRyy8EoBLz%&#*T@k5W>u?<*8Bm(u(H^Ro55K(u$CAHk`VsMCz3JKemQVSlm0dBjtqVA& z>x@g7-$!Y4@n9A$k)*ui<0Afq=GyPqlUzQ1BQ}Xp-{2u^d3sp#zBgGwfFa;0hUb1` z(#DDM#dGS_@KJv2rxLhvuS;!T?C@0Odl^%Nz-aK4R@=M$Ii$^Z94=`Vf}C{eo|K=Z z3HFlmQwFlxGLa*qV+3;pH&}Q!f|H$uGZ=Y%OEfn89U4uA+z)@UoONDl{eH$(wlJ#i zYkc9frg%d8P+?@HeChSZ!pg_!*Wzwi@{w@pd7ShDGw9E$wq6sffs@HW)SsX4-|Rfr zRK5_=0Gj@Q+J=5LxVc~WA`%p4<$c>22y^4RxHckwxPw_$$VE`!4V{C%oy4J|Ps4JY zu9OrpMU_9idG+Zha}T4}ke)M8Ok(p|l1d~DOIZ;UGh~0s2Y2F?sx8|jTR3Ws=)=cn z-HOkjbVO(~zuGer$**vg&I$WW6a?rB&AJL(&NKrYMry+Yag4)yx5B;ASo0Cw`a~YF zl~FNz;pZ5N!WhxTOQL zU_OwGY$Xe~#uWSRpxx@EeTl01k}1UFC{Q&c+8Z-qXe;`q{L^4#VbWNWM@&=3 zKpgGJD1dQXaC-v!L zxs61j`^CL+PI%%R-MsuNj4^RVDdJ^jTrh;e$+PUtkzxr6sNi$VRC`&K3}({IOq^nP z>U~%0@8#5A%PJ2PY58z<1e$7@J`-04iEyNJ!^gB9X0_%~i~vszB9(MvlXT*sbSjs0 zlDjngJhc{P4My<{W|It7m5c@742a6pC3_9Vs|*kzlQB~R+r|obgk$_DXktl*JGX_? zErUL>g|k3_JF5+c!f=!#aM~Q;isEp|JGdMru7r!Qgt&=eCOAnuOF|rOUYn)o^0Wa{ zd~Pd&^W&@3%Oq{P%(r|vVkW|wV_8~L7;nzu&>)fxLlP)fmi9`P{%)4X6h?PTmbrLt z^l?s=UUKj*&cxvJaCYV|#t>A+xO_MmzM_1A32ugamg}cY?O_$0sL$x9RWYm5w3$`q zdDd=Wc(<6*>8jFs=lA;gwTTyq8x%BH7vxM~+Itq{tQ5T2QcfCGhUb9`;K{=A+!ja4 zWQtyyCV4q4nD%Md4dK|xf2j7vZVv~q!oc+{MeXxgh&->VNB#T;`XVEz0{fq+2)=@S z6~+UVf;UqI{o*CpSg8|+C2uJU@5KwpRI+6hn7!h&rR=PHZ^0vZ;I~+*73Zi=s`Co5 zu#3`)eju=aYnOrs@xR;^Rcou41*ukZ6r59(cuEmn(E4jle zybl8Z7LPg(Ec}*Rm?rMk#u}bQS#E#s^?^gRBD|3~JAFKdrgUk8w8)fi8 z+W2LB;A#MNC4p*1Edy(Caeok&v38kJKt63one}v;D^+U1Jmxt?xu8TjhG`+BDy4rp zN#g#MVU=w!U*Qle&pu7>V|QgmTG8+Gij6JY0d2s+;}$r1wPu4JXUntHNWuV}L$v`J zIi##$lqe|YQ2l07;C7;1fnA+)UFJzuJrsl(btz9;$z4B60@ewjnI=fz7vzV7#4Gcl z2^AU;oMCIc)YY0ZYrG-shT-{&AK_r*>B`D*Y%56JMNNUVX%)3VKDBMJYkpnbv~q+e z#uuvUhSd_kgz}8#ly+DC4%bL&Q*3E#i~YNX>Tqxz@<${Zh9nwNPQV-1cpch+x^VE) zaYH3R!D4U$4pm8mcullvTF!k#jdjcIf1~QHzoLNmsNG>;V1gKsE{Bv(L0U?>LApg6 z1f)y4W9aT0y1RyMq|>0K1q2mPxt#O9_pWpQf?4y!to51i-p{iQs`w}?^n;+=Y`HZX zRe}0-2O`l&Rdra$C4oxV!AR{hVHohTdhi%FvQhu53N_+eKgx!y_%K;xD5A8%R#3x( z;|54!wJTyL@VB8FIze;LRy5=TJ8qv#caSJl*$|+A*P>BfMRfwPn(K(qNj$Qx*z~ST zQSQ81))!x`08?VEfM7M1O|{6jQE1m~70O<;`4?q(&qGc#A*{Ftkk^z2{U`!cFod;l z_MM;fwKkN7Q#D?%*VZUuCrS1Q*!PT4@v75T)3NhhNJkFYHC+njxw6A~t9uKny6{xG z&`JcwE_ojf^NV9Z(%CLQ3<+uh9pC-B+fMpEY(j5%U@eHezRs%nDX3Iof5M64`gklo zOQ$K8I)idn#DySTHgqkz^v?#m;2sUj?H$anxtW7tL{uJBX1~quqoy7_gN@v?4GuPx zuHLq2DwpVqCXGxb^7h0XMsgk=Crm7db#FnW;Kuz1`3>wfc2vW!KB3o?o69z#!222y zdtPB-KCHS4v^Ajp2X)Rq-cHqh>H=l?Q_lCG)FXw4zTZd`|20DWCLpmgSFk3aTLX}T zEDWjY0|Ca|RK^Iz#x9KpOWi$q?TURxVO1J1x<8YeVj~T>?G=*k{naD8P`e-sWRh_O zA9ZwNSI?T)M7S=%E2t1B4jM>3Y`0l&chXyWGAiSUZ^I5XnS^F&0QB1FR*V4ey6fZZ zyW{U>w#7yoV_~XOIc$Fh1Hl$ae`b46rwns=RDn$f?=I0Gz+f(*oSNMm#SR32ygHpqG5*-^ z{m~Q#18qUT*@ZIpZBVf}u`)9}UXw&G6+8$C7>k6y&nZK*OJ_HId#^0hDUu z;#9)qU9^s0!7N&F2&lIaUtFSYAJu_6BXE3_OMi$!6*zJ25%64epP&&S_F|0qY_-I^ zt*mgiLnSxKA15Pd?FTNOou$83Pp;M9o^jk3Bm1_r-bF!nAUzL!=I_S|@x{N#>!n-Z zMyF;&EMJRN6u`Hck_xo3HCLVXH$g^ z=M^H0+IePB6Q4JL0|4OVrvlvOG}SKG6KfN5aG9*Pb2MV zP7Vr8Gnd-?2}^Ak(_$-Cb!OstQ4;_ufk3$=pfzXppo>rRTbT7{pMXiLf<_QM!_9Y- z1qg45{{#H1QZv))>Y4?JTYT)}z3R#j4cJ??bqvm3h5YsBekbE z1utlxB>ZRJ`r`_$HP=nZyYKAmaO|TNA&)*I`!#cd%|?@1ym!z5c>7C}lZLq}+(>PG z=a(_BHEH)GBUPI&P%|n7pFxsWW2Wmj33u0D?f`X=9Z0QE*@8DrX;kN;0dKae{s)K$ zTnvEz+ae(RS~VGdnDbP8?DbFq0r&UXYc}yCPyKH9ML* zaYO7>TL4y#{#!k>s+9L7b`B>w2&QmK0N5gEPHe@k0Qt0@I1UoKb3e`~N&VNr%A1Lvz?-T{ zfPRzNv;0>%x@U%MPM`b2sa~A%R)RuldRm*9hNGT@Yksm#Dls3R?#*+05^Xh+0)71m z^=1&WYDm5!LFrUV7D(jq*R#zX5wj$}ioetDa>y_dEUoHGpM3rEwEFEsFRA2Psv6@j zy#Wu{f$7dV-Tj{XY>z*78LbMDB9Dyu9ryU97iy*J`%5w@6WRweFa!D@efeS@T{;M& zQU%cS-tSn@B~P7lb#5ohxKz@$*LDvXs_j;zL>Fya__91wUlWpS5#0&wlH3{D)hcN% zb=Bu3Z5l_jyccljyP|z1ipnO{FYJh3<>%|AL6b_`NRoTCW(RT!XaiJ|#*0Iv28g4> zqd*s#dsu}H;R8!U6gd#(YC7{Z>4|(j=iD>W>_PEBa-+lUo>U+&-Tu#Hg+8F5Frg|L z`{n|pzI7>YriBZ!t-R>N{d_MldawE8R-9vl&@w&sVi}QWXUzl27nh?_!f0}3u1@X& zEPh!+D$C@i$-NVpoGxYPkLOfJ)CX$Xt#|X17=Nu=Uv~gTG>aLT4DE)Kva!OG)oim- ziJELjD#cTlRUCxsz4r-PZ{JNYl_~Qwxi&@7O7ClbcZS@w>>Y}xvm7_~uF@JL2oqqCM(_bw`EkE`hOElu>+|XKEn=`{~0Z*SbgyHY= zZ=+&XE6)o+3n6OJKBXO&uKaQvAFa$)9jx~T-$a`c(eeFw^zy1X&rdhsrCp~30eueE z-RID5YgD&v<Pi#++_n~r;s-+K3g@XzzN z{Zc%|`El;m$qtdfRIR0?fYJXDH*g-XezmrjknTI0A zsVY(7A>1k?*l)?Ho3`E|s8v>Fdq^u+ifREbg_Q5qq6XVkMmXhUr#j6$hGS>uqWkQ2 zeh)vZ2F|INv`og{p!o@Z@P;E~bH|UCv`Bu|@LmK6lrxNGIoCyN|P(VWB0 z4ji^HcWrsg2Y7?+rD&a(z(azhe4%!{C5CEE<8ZcFIK6E2jUi4xXH$4`#xNt(B0XuK z$3jX0)?1cW!jo#03#k>dZ`oe2%P|&*d-uFap?w!cIyYmj?nSjXuiL3i-+J+)mROBT zZy9W{5uY(OyhiIYj^G0}Wy(`A@|8{G{BKeO0O()qmT z8G?8p-|KI+_35T}UI$jeD>9)E1pNjgw^M6Q55`ZT@lKN?vN$@f_c9-S#Cyfa1_ zw#hP;P<*(f8N#Ll`9_$B+;b{?QHd3)yl?7PkxJatVa_$ zM!aPa3|bmP*lFisnT3zyz1fWyOfPOF5p$Zc{jM<}(Y$Howm9B$)M zagJ9LPuo#^%^dX{8dID<!{EN8b5HHCtiNlF<~G22&s?N3b#Y7nXg;IMsD%fISmrpT7u7(W9~ z($JJEdNzqTUl#o49M^nvFA1o68YZq^yvva|Q6 zFV2@!)O&ybjx`H~qLp#r>JBL9x$`yk*;s!Lp#wjo;f7W7LD!v>4PSB$wA{<5oAi#AxVuaY!hO_h`NT>hgOO1x zjC9{!a9&|IeHiH;V)7i|7lzI=(_Ixy<fi=zB_ee|Sja&zi|*faLUc2$P>QEoq8u;4Oe%6)-9^Osc_ zkJrG%tYO!W^!L#=LWx=G0i^C}Kc_2ra8NV(t?K*}F6GQc1|P!~7K_QmZH1NBM^elDqo{8HiO&F-K52|G;YMc6K=?D4RKTmrhu&-n=shM%L7{pf_Cp%!E zZGWJXD%xwURl%xyI&yCFkc+1p@2jJyOOmS0Y5UU>M;j5c#E)?kFNy2>x+ZB z=w0J-hRAbN`^5A;OUzP;z6nn5eG>5J;w*)KP#4S=(oj;iUO z4;B?o8R8DoCQ}>sSEOl;X|?L|)jcZPqiS z#h7#G{PdRl9+Sv2VK7tK;y|xBgv9>euI}faJ}Nu=@yfTy(PyUwe1`@f_044pj0|F) zEBj2YFto&{leP)1mbEL3^Os1m9;>GVNzzAoa&GNXcQeD-%PkfhjQ|-7>qiKFvSJ{Zqzsqo!Ui&a4rCU(R>Kf zf{vui-6B~x55@m;fsKzY>gLI~eO_cXE&8&XlA5gyJfxK`5a?FAHpAm$iF*Gs>9MQmMNUX*!0$U!C zJ{p5#3!JxvYvux^ZUBwASar7<4&y*~uN>F~-5Fvl#8 z2!P#VoHAm#T(x(@anuFSGB(Yn@am(GEI&D3BgiOpj_!Gg=oKkU=;n6m&_&FCc z74A;?=01i(@mwUhr|;uuGvaaHMt{_giWpbgRR}R6ca{j3G%iUP98Z9zX@82c+EGXl z9D6fBVmOtNXwi|#rLS@RJK=&nq5gSd7b+_Io7Pg3N@a7xpG?hvzmf2DC8ArWpJawo zg)aLM@l=&suWu4xkRqd4k{Rq?C82R#N)iQJ)$typl{oAyxw4{eqCC6N*h%KeBjrd~ zw3c3L3Nb128tnX&Tw3bl&9llR`3Y^sqa=LR#B@DR;%Lt#7aT2v)N&6;HUnKHVRMy< zG_`0?FF3@4BJR!Yd!@7#?=t-ekBsQ>49~0#e^z}{c+$y!3LB}(nha-cdXf&S<+5zX z&U14-;RJ32yBB)Ml_wBQpG@tnOx;_PxLXrC)~ugnmJxvTOxASAA|2wDtYLTcg4+~I zIVq8hELYZys*$WpAN3prlF2rq6OM%h#Wi62woVvV9c2MKV|lY+W)wM=!a0M&>g`9F zx5V)`8M#ikBC?PS{*}!6i7fYZa6ABle1JnT(BL>ge*6}Ar!#+-0xMcF|1UipkG}w- z3BdL&_?=a7*IDpqz2JTw1c<@*Wx{de!NHzX08c777J}m3`M93&!v^veqSMgV$)wxa zEZ#WL0MT`dIJdU!&vrSW*Z$ToGKDHYH5WO86qehP8qB)6T)yhtlEo&h#(fZjs zR2ZkB(>^gl1X+NjuNk#)5nnd!TCarTXBt~Ja=O{{pcMjs57{{a$D_f~=3sv`&<%|f zc)<(t#c?ad3FQH&xs=-)miuZHf<$mEVha7|3R#A*OyGQYz7<~Z3Lmx#mN$H6cNM0T zD6?a1jtkxo$2d{PI6-i5+`}X)!aV;QYkrbsKKQ+9FeHUSE^~P?T{R|CBwP9Pt*JI8 zWXGp0&K#`CgA*KtLWJUk72?=zKm&N7u^QF(8r97)<@GT*kd2BU5fsyp>Hs#r{%q8! zZ_T)GjUgI4Y6CU9@%RzoXh7w*aDHkPB;7YxY0^?^&brJln@$%{+F+WGsJhiE(_^!a zfP;fB%ASVeBx^ugCLvi!NNyqawNm}fBqWvx`gXF~ON1}-xGb6y3|M-yWhr)B{Frex*>~2j}?v&fYN$YMk z*=#*xtwa`bQ=gbBQZ|)D6`z(SIx53=lA8{E>!zTU(Qt4I0#d6{?d#X=pVNJ9Se=G| zgl;y(DzzG;K_s#5$?*CrM9YL<&lr2FK2>L0Y}rD0=fM%SiDd5*EdNBY>cR&?4a;JD zh_QDNj@e7`Cuhy66opscw`qx#IR}BbW6KPbx=WDt9e(|fey-R#XmTNHma;Y&-sv?5 zG`g<|a_On%f!=g?{}F-y5ryD)|0jJ~Ga85s0(CTX9zybuk2*h}^saS5wv<0C`-Et> z<=S_*ZCBA(E7w7ufK?=`wkE*Mn@~_;^R+!xBnKigJ#_2WEz%9{okGP{wUV*d>Th8i zK+(ZL=$5+3R0V#I87x_KDGI4-K#Ms-v$kNlTVv&gLn3iQBFf_uHO(at2nd{GAUn44 zJA1DIJH$_HvDjNt4dA90pHwQMR=HAv{U zCe!z5P&T3+`B)Y}Kw5dmM^)wmRHmm?<{+QP0;VA#4M^ezigFs;#JuXDa;)THh_ZG( z88BxmI*N*$<=kxYV_Klkn>?J^0;`{f630f_?U)8hKq;<}}4pr31cHsW?gJuFKa>TBm_zER`{7Gjk_^U41< zi}rkyP7_eV)AEW0$ zWr)qcpPGsRO9Q8?*Q#r;YBziGzD^qhj6QejZ{ZwnfPKYAggM5Ar{_Zar=@C^lP9^~ z*7D?R;TQupi19bB>H7o^XP{O9$PTcqqzekVShdYR80`TAExLc1?EawnR^BjfcKZ0v znXktNfjMr;%ua`&j=jj;`niEqg@EGW53WBrnZ~(bYJ6!tyE)X6Fhi9`IrhBfhpf7E zZeRynxJhEa{naLpx5s6=`yrqnq=A8{Sq;rQ;8I)q^B26`sh1Emh6IdO@$3fs4><)6 ziBx0TqfbO&yFs`eRfzn;*io%n?BI*T>Dh&2EiSU6ZMBJT{XST-?3XIlMG%I`W0?T8 zGPqy0BUyJ~?+lII!bHsiK;{_EYUkIz2URZl{#(E@|FU+8ak106$3#n~@C4`z1Zr+! zs~r~eoV@Lwv=6|XnLRxLnvK4ARP2a1XiLyc?r*5U8ziAGT_C^wr&#m3+qrQ25LbKW zWAqwulqrD!{M@b&e3@Y5rSbjc!|cJ-=^Tm66-W{!_~BTh@alSFN5mLlC|-%^nLP7A z%y4nz*Kg}eWDP$VJ|qHVOLAY7#b&Nvt34241OUq>&U%YMdQ6Xt zUc&pi?j(ZhduAX`8i%V@D>}|#XN}+JL_(GRH}L+bfppJ)mn8IBZgwDC-v!2Yu<`T* zWTN`^L%@Me;NN};IO{__w%ym;$7)Ck55zeL`!lS-y9Syj`9q5PUc?{N^l>w5Zik@O zN-VyXA&v_L2PJ8&0yLGjBtyzHXk^or=-71|C_Pu@?1(-4fkh zS88Z0Jo{|!u6Uwbi=-F7n}}wu07@(o^Q5)aWVhHAl{2wJl2`Kb-ID3wHWQa{RpQcP zQ43kHMc_SEN)>9RABm%Q;n_3%jZATpNi+Kqh2OUxdH#22X=2faQ@ii+_=XB-W0cuM ziUj;67MM>@e&{=l9!_&$R7hkdf#-O()-Tvs63N%KEtGaLF-Mq5>+|i4;5ABDU-d%RB77 z(qtv*czj(R?UGWeJR?RzS5SP{Jw zyK>{@CQn>4dRO|BXOW{XgC%*QImc~-aZt%VxE8&tMFkgJ!+NenZb4d!1(l>cwW_%H zTwrTgWRrr*z%W&uE34QD-`0H->{PA~-Ma`CCH>|&KQe4i{7#Ni_?RVg+-=EqEY`)(es=ff*dSt}mV4i1D`I6xZp%xR z=&Dp!=#yxyB@J=Hn{|cJzj&3rBVq|pN}(4q6$Y0?ETVFI=B|2v&!BvA6jYdk`c$n! zWos5#G&*HgW`>^3vY@8#658|0*IFe|BxhB0?cYi!5$aTdXNfZVe1l)_B-uLl44oh| z^3-u$+@WnlJIQ`F=K^x#_xp=-RNSn9F=`0c@2w2afy3^*s68!`s2Sn2=j)8j4J_|N zl1U#R`777t+;fr`85LZwiW&&`g&ivs_i1l+l!?r&!Rc}bnOS;bH=i@i%x_N@M=kzg z5!*_KGgC5z(<$xS*1al$vsPAEQ`(oS#xA644*#P^R@?L{J0z0bY%I#_7Bv7G$q2gz zUuVBR@9f4h1k>|bC3N$5ku9dk<-T7LX5>^j+I$xp?#Y^oes4iauSHf)2=a(%_D5f&kNEu_4$#<~Xd!i-xtjNP{d3}uc zlGFS4C3NC6nY}tfDdwX_1GgRH@2lfTod@!T{;3AJGZtqx{$13Jj!nW ztx@v)y;UDIA9#Z4p&}LRF(&|3Nlmvn{7!vL6m{(AJ#56pVHl0ZN?#Q2(k$Zsj>a~8 zO&A!3v9JXnf~VxS=)x#U>ghFuF2|RuO_!gl5*l(m@Ggme`oyZ<-`TGNou@O9{c_Nk zA!2Y#M4ZtP%#6~XsKAa6yuDLc%{FwAlM}0wriEBX)yKE z{X-TLZSkqy^hfJ>;&0P1aXi>!Oig;LfbuR4y{6Ie%5_`mr!!9Gsm~ve)R+*j|uzP>a*|;1`3xz1k zV&qfOc3(#KQe!xC?XZ8%JV;cJ-U@w04!@3{M-gO?SAOV@O$Nvl4-T=L%0dA!5Wm$3 zyLBTov)hK9{hHhpi6cBZ7|(aNwXugyLOmapHsQlBK1N>N0^oxe>N{G9{=NRCuLJHn zQT=@9?R15{%wYRdFP|bwb^t)tV2?(VdE%LFnGRtIq%MD@x4W=1>!rbKk(Zu~j$3&d zAEq?~@9X+s3A*|1QRDWwhLLdMtJG>pMF1~u=C~~`>kbd}qB57BHWc#nf71nUx_n$L z!1h4BGC=~L?<|5b+^bB8!kn8#3=D%jYTn{GsI3~p+S)uMEL3d_cJEf&51vzni91@7 zZLW>Uc{at?+Dl@dWphjIM}O#wO(!-SlUQt4I5e&?>fzm7TXyoh^VhZF^&7^TB5ZkT zbS5D2ynkB)l82FLu>{ByG6Z{3&HOvaHK8DF=DW}DfiF+w|F}{1)7YSFHBB%4UlecO;rsYsH`x9Ean@ESyZ=hY|D%Hb zzocI!55<2u>lRzLM->W>c3a$kNk9H~kCO5C=Ck>dp>=;)|3msIq|h=|J#yB`>Lp6A z#&z~;|BvL>gS`rv(-lLbtczH$)`sYwdAB)j0)szI(!e~qHc$?{*laE@&cm_5C=xwm}xwbf*&Jm&J()>e+sF|)0|<&ROG0xx4O4H4Os)g-DOk`xio zsSS^x4EbWPZt8=8rP1L2pBh&CQ}+Qcc5~UwZ!nzM9tZ=$}NN5RoZFI zGb7SMG+r%lv;2RO@d=}N_0OnME2~e8yK!*dqosJl0ZZLj@?LO>l=dKLQkts81e_hy zuCq*@`yVm0baPVWW0$*33z@!ax5WJZ-8pkouHZy-G^rT9Y=v}Xp#fZ%n&^c_fw>wM zi|UCZQTP*0$EI1S6#OuyVmtideVHM6i%lrvA1g6ShDb0gORmU+PE1}=ot|N<9bcXrOFBri(ycn$#MZDd-Z1Y)jArk!3Z-GbfE* zU89rMwS%f^nX5hiDF`UnMT)rhw+sw1YV{r=w`=dNh=Hq7sM*;9EoC+%d)s{`eTiNi zB)uXA;KHoNOC})ovZvol!o*LASo|C4T;%4G=`{w%h@P{_tdmOaINa(CNzp~jV}#Sn zxoDtiFNr0`2^2Nx6UE#QgGcc|J$!Qr8R8&?dTu5@zJC1RtF*k)Dt`wl?w5=og=Dq> zFw2ZNS80mO;YDniPoXOY6Nph$lFWN)E`;~W93za*^7KK4K}CzeSb!Dv+xBz-ti0s5 zn*JIy48&Qg87EnsE2)CT#$UjI9EPRwg)GCOXv zN7torsyfD^?I!{fX<|%&j(>;qKnllUGr;r7C!T%e%R?d9FtrDo))Ues(wcHm)%h|P zeftoN46|#9K5iH;du9YnvTl$(F`5)JNnS8Lh{-8#mc$Am_pu6r6)#X~M#YN-V7h^8 z!0P}k%2@`EIDH}Ra*9$sCVP*+flTd2(W|>fnswUa zH`+%%16y`z(4F|D5Q9A!i^Ei$A1wj5ugC(I!_C5y=}M@_Yo>){u-sIGQ5Ys<2SGIY zmU8KusInsJWaX4IqU7FGE4F?t$|Uk9{0(!17&yRMX#paKR;AqMi{yRC@xyF^BWny} z?^fU>lAB#-d?#pvGPy8?`SW!cOkMY(#-*5@?gz&+`%~89hzr|-rcmqWi?7szJsDMg z#YKz!IvNl3{HR-+%`EUVCOK+QHV(RyqfS zzzcxSO||)7HcILp)hfg5Vr5PR-8@6;JQor*8dir_B-y$lHLbGhtrJF?gIb=m0=ax| zvlM?Art~_;G2jGP;1c{)FU0pmIme&M|C!WIw$y1z1SO;@q##3~RvGDdr_$#!tGf!i z^>h?lHBF;yt_wOSLf%sgSS+pF1Dufv*yw~oxeb<&!%|R(*11F~f7+q^)iFX7MK-q; z9z0$ID108{$S`6M-jQ11ex{|`{N8XWW>~%qtH$%FGe1wI9l>`sufW|k7v*i2R>E5Z z@fn&wkC62&s%4jMOH)>T40}61b21QFLStIrIm- z#v398da$@0^$}$Fyirm;+qiFj4>QX(#5|d{BzdWh;BanyYJG|mj73iv%>rPc)C4FH z1KJ;ev68acOVvtN79};~{r;!mO=e4Ow+opN^_s|Sl0u>q{V>U;!hIk|F#(Wb7*VK< zBp?eL(IOou(5tI^eK??8JYE=;YBk(%#15j*$- zD4gQRV3qY%fd{$q&=;z^f~&rhff5S+Hs{|zZ2tM`w>>n2L3?3ImE9gyE;tC=f`ora zU%y@c9vDpFT1;Sq=-@QPaLGMmC)--0nz)I>41jamN-YN0@zT{82k9yllcZ_9Vp2JG zu=v;m5N-GQ=w}Mx!V;s4Bmdn%V4di3dyNmx{0TYS{5nMIUXC~a&WUVzsZ>{{vsDbb zYZmy!{iVXgiBZ93PyfF^_1sYdn19^SoBx`(o^QQ<*2MWVTnCY_!6!wT2-jwOdd=|6 z2gKtx{tO;a2n}=bagnzjj&KUYCZqAP*Ux}3ya>XS^7Xq6!sHFaj0`-)F*#f{>f3(< z(sOya;uXUTCvH~@+_(K#>aP4ur*exyRnHwW*hqpIUaAN9_wB>PYG~G0Xt_C5iac!0 zCK!{@R!kl)*I=$w5lU0>Hn}38VC5|c0SQkxqB}Igk_ypYeZ#09Vi{%B^a9SR;8()v z8vk4m>8|7pRH?im;Y#!Fe*rf}LG`}D9v}0u1|r2eB6kiRU-dr#g@Pnld{O{j2BdU?4f8#W4N`!Em|e=gMd|&vLms+ff}^n-Lk}Lw zbQZt2hv9L67-_wjQg1l1jk^O_8@g=Tj$t%n`2j~WB6`iWyCb$#E=oZN?w1*Rc^Eoz z_+C^uu!{-aDhZ!ni<=>3^kNt-M+4fIoO3!IkmAA_go?KMwB?SXgQ?O{!G$bSeYT zaLgoWQY*|xu=ru57&uvMJQ0MBl<0`m-7`oaIa?Mb|Y>R*JkJ!Hm% zkFZ|L$81KyKW8cv$tyj^*2K3Fdxr{Un&!;Skc!OE>&)0bA$WPiW1l^UKH97MH5}8x z6BEPNoFa?}98`{Qej5$XvyJc&f@dSmMXu6aCgNY&xKmc9UXGc9u3|s~P*)+P1cXzC zH~e)pyih)^S3j+^EkU!=2s116C?hHs9$g?8Wzz}Q1$%%9tz0HRRwG)_XRZxR5ldRB zMf)zhs0^%NX3!hH&fz46+gP(`51or_;C8IPZI0$dl#yLz-!j!D0O z$&Z{y71AqV&RBTdyNe`xWIgGRenBxZrDcraJq2N*uvKY`IK!*F;)NI(A)ODQm79>O zLsl$|4oHs%kifZNylH`JX}D5hJ3byJx)}5T>j^!$p=WNt9-&B6$ZRLPkRp4IBJY)A zA;>-tn&VLKW+RMc)|zrA@T!m zWATHJiEL*cksZ8+{{x9|$*dQj#9$$2BUFq97lgnyu!9qc5Rx2(1F;jK+nC}Tt{~Uk z(lrSFgsnR{VIzOGeke26q(1f}9J~RywdAU$fOtohGd)z6^o|pX>Atbc3N^OP1kwR1 zMA9@~NIht|euNYf%vY2M7veOQ8S$Z@7D-T79&)<`m;s=g2im#?v-ZsqVZ$w-d+Trv zf6QSqZY`}kyoECp6tgQs4d8ucw)uAk)06Pxt~_pE-Ey5mRCbl=WIEq)#(|Jh-8!mu zGV(w&EHeh);+qpU8EMT1=iG|M#()$zgfjSmaEmHU%b~_=m8E-88wNtf8}%RWScxDg z!)(7U8^Z8xxS~6cs}TItMpCOiexEsh9MlI#s#nL-5k4Cc4>riLJx1C1 z!o^^XVpJ`yor&5!5Q(;28zaC!0N`p4XZ%I0L{3g3x>9qarZLn!jj18(q&3>83h!CM zvqq(j4F$1KX27IGzo`N2CB>YQP9gj6k*vE_s4d=Yaauc{EoTW+8GSAIr8D2L>1`__k$ijz|1 z-}|jA-5ub~j@%+bAtS;($#UpJQk&v&B*LdNGb`k;o%;j~P}-d@tx%7HQAYC2JB_K9 zh_E?U`pL7m$PT9Je`Jja2pZ7S-K`7{;{jzy$8ZQqCYM7_s(aFpL&u*%By?l4HFTGN zY6PDBtTIV0euVcq@MOUbkY;u3QCm8Da;ydEH9j@ttvsOjmChF41#LmKlI zA%x{I{cJx5$S*0okuXtzcy=Lb;u~IiPN(=(^B0#+riz+2FB7iT2!TJZ{vo}%?Mj&y zoLbw}U%$#TG90DxA6A zaRXU}f@a;OdSO%Egy_dYKcq)T?)OMPObn%QOET!dsMG0aH)0GsX$H!R%lRHYL^ue7 z&*ABDM*s3E`#pvwHJgfQmE8aem74Ib9+AhG!@L}QyiTed#|Rpgs#NCUsNxE2gz3-T1GD*>g_)ZX&h6OZ0hgCZ~n&Uy~G@ak+vKgq#IM-Z!X0M#UOO!#G-tdO;X+1B z*52)`B0B%j&<1pd{~6p7UVuxtP|mqvP`jcXFh`h#i~ILusyN)g2L9?SOBzxr_GuA2 zMYjEM#PT!A+tba0zw6a&1NPISCBvf?y`NB=W0f=Ts-BHne=D}4F>K8e(WHjnv(4Vm zn=c*+KPTd?Uyl(c(M%Rj!)KUkC39hopXO{#;GHfc8#9{@xO3%y3AZ>u^Vn?GGK8=O!V{Q&SxQ&?p+c&2@(9I?apBfS; z!~z8!h;4fSw>=!W;Kqd@SBYDdh-*`1ooOU+qXHV+Xp7fl5ts182Q$r1@oeumvn)m{* z%ft0jrWl(&Mb8RM1fH$spKS!5Z8V*I`Ept-ekON$y3=5jF4K5^kZ^uJ zdk)9=zQ^_b+1Uw7^7~!i_dj30|1%~0M|*MYeEz?pQvkpW0}aUi|Gnpdl39%(y@@h9 z5SqtX6xSk29TI+P+5h{V7qO&}OeY)1q|HZ+YI@6;j`!*j)L1N;N+o-@6NgH%!bl}{ zfYNLPw>QSRK~XuXn-55oKRgrgdxdN0E31Y3qDf`W2dqc3)~b z0U27kGLPOwk(L~}GVSUE{|r89jmiG$!YXvDw|DD%< z(6W)q=D$AwyPGsYlOW*Tw_H^>yq{#jIRcOS(qoc1bpBYRt@B3T=}Hyfr%UNVr71|m zK82fk{F;w!$6YLnoOq=Ne-B|>vta%2XkeM6KHxv2feZ;$|JF*F|0|-GQ;Xb7R$SPV z|KPjK#FWbJ>AjK$GOv7_4k91ePd5*oV3IeAiQW(S;qiR>aoWvC86&&pzte7t6_TEh z({6czrxWG!%eV9EQty|EbL9i8^d*bqR-$c6kpDVuOJh744SfiSx}K`$1S}nvqzWoQ z1BwDg>?%3&#|_^Ee+IFl%9tMv0j!ODBKEb(zNHhk*==_uWpTMN)%hSEzM6t&+8hU| zcS>ul)vHn@$F-9OKG6-!vlHN_>s+F6H|(F3PO4?eJ8yaZkBGkQ#F@v0^y0kdx(znf zc|AJmDAhx%gHkCf_N(u?AvJ!7QAl2M(LKUNt%7oKbGOy+i@-YSYIyY0k3J5+VUJOV zO7o1@OJfx~{nM>sE;(-+0FP6J7K5g#ntAzV0-g0)y;!uxxa2w7{rP8ZzU1)CW19_* zaw}9QJLZZ~J$E&G$*}jW$DiY~`vBKFlLkV0zrQ?r2W@soRT3|;-Se;cu3UNghacez z_f@A~pS`~Yc+orVJrw^3)ZjvL1ut^GSj7G~fzzhhz4|_m+lP2ocVScUa+&FvE;$&+j@(dnfH9G^q5a!#wHz|3lYVKeZXQ4K@V=BtZhj zp)KwX#oOWz#f!UJX>l!3+#QM)32wn1f;)slfnvqorD)6M{dRZe`*vpkfoC$w{lk;{ zy3RTL!bkZvaTAA#%a;$Qy;$Ex*eA(MIu3`9%)NzNb7MSWUa&kpGWHvEckIBa3jf}u zilUGG*$R&vJxTdJa(Tu29Of^y@b&30&*qrPTh?FcCS81!HUTk(kD2-p7zJ;(eogsQ zNPYiTIp2YvR6}%UAeRdhKqaUVKJeR6^i-@KToU{M@KxS^KUQ1qFP6YJlzA7X>fOLJ ze3HMRgTf76-aJ{f%wp-#dN$fuOWW7?~<0b$bgux&tP zu)47+ro(iyX?Hw$VvuD@;ed_&7%-aHq}6#;)z<;?#^D$e`)SuKY_sh-pzMk%Ruuel zg;K5=B3N+le*RE+mO&sz_2WE5A}So;R^<+?x0D+gQxbRyMhcz5esedF5gn_7d5d36*q4EfX%RYr?z)0(W+*ox`y8 zA>@nt%!L>xvGmqBmvO$V+Y}qVW|k*>1)s@}?EogGS48>gG3svqT1-dP)55EreBWwTx-L_TE!Qd_cS0&5vsF|!&Rj;T0U(C z3nY2RXm++Off=@+W_%IEFL0{lmgfcPa|f=gm7h&dPOtQ~Hom56_p+m$(EadoUwVH> zwXNfXu^FJ<$)#*2VeEflR@fnW>bg&2l(WjDl;b@v5}b<14i@!WcGD$7 zuTIPpBAe>^jU(&097v3da;=2=xqbtIKwRC|@{t&E415ymKj-nE49X;E&?U ziH%W)u(?MKwnB=28qB?HTrpK;NDW|9{OhZ>+Bl0m8iMUS8PW(IT0}9jxDbojQf#UT6k+ZP7X1=ylpffc!yZreT{L!I z$8*KQXycPH_1%ss$RMWcmyjxQ96*m>9uf zYQEl6;q`hZ=2M81SnCXXV3pIbr2L_N9>cD-axfFVyX{vz-N05}K-H0%0`xnK% zOUb6zIRe*B9IFh9lLZHUNpN&p`?x8N<+uj!al!Id1LSysht#l)p)|JQ*h4N5b2wJ@ zjmYzbPYz+qH|7{>3&3G_!?FILlFcAp%;3*+0q$W`J!ZidL%2Z*pgt0qfOI?##4^b9 z1iE19=K=l1amSHBF9fEpIA$faQ#S(hV+Ixy;j~WdPGTFh*7&~XYiKj{GtIDb`xO)8 z({oN!ui(s0;pc*pTX`Vo1gvSDNLiTMh3WgvU88iUm4F9GSx4m+lZb9FxyGp~`7Ye~f`op@OK zemxIQ>{kdW(|e9PVNLS5!zN##3urYdRqjr%xj~L#FoZ=o-~{{qpVFuSvgDWyDd}(S zQ|1IOVREufcm$ZJgXVjP(D1&C_4W1&D^yBHaHQ;{#qWx9SX=)2X&u>WyV0E3f14p$ zrsRi6OBH4o`}9qm$Rv~nznUK_NL&eJ?yASY_M^@ck4)PKs=_pECM9{wL2s=XO;Rr* z<+9nC$tielX)jTb*=Nv~$kbADf*!rMXumSk>qUn3G(z3P*A}vyLphh8XqmRjNb>35 z8Aj%OOa8XhigyH({_XA6R?Io_Idg_w_>X4N!M^Yq()3_NjW-3H2F%5cer1W7X$5yK#Au^^1fi?JqmNDb4`c=QA2#V`V zQJ8p8QY4O>-d5&zFK%A^j+^B>Z3HJU!T!&FJUb7xyRWQFr_6V>Y(W5L61}29U+mMJ zoMCDxVsC42pF@59EfSSc<7#zesLSQXaS*3BGHqN#+KH zC13+YYhsYt7>C%H4)C)~xKtF-IRTD^0yTW$;0m~meyuD8h%Bp?BDyxn1)VY)CQeZ& zu1N3N2+B3pfvM4zC4k56+%F?JnSILFS*y3~tM{HnK4iLp^r5jb6g4qt*ngvH{^Lud zhDLKk3z6Xaa&QuAH~!2oHW2>Ypq7FXTgkNcc~&ElZ!L8e%!sYdl&#KEEz^vxPFACi zDO!ic09=ZwD`*W!vd(j3Orq+Myw$C?bFa@l3zG-eU_4;o>H|>5Eg*_OF>L{gw?t-v zP(Cu{hXysuMm>YtbW@oAS+$-o9D}k^qrEXftu^nVwZNds)E6BVP0!#^$K2jj1g|?E zNnahsa;+#}6M=g8HVZ(&`=i+E02rAlEU*HM)&q*lY8k9(`DWSygg2}N2H;vl&RCH_9Cf?O@hc) zNyi2Vt{iJ}jxLR)Xzp?0s#j{)n(0c@uI5Jrdm@1c_T5U32(ij;(U?Bqa-TmtR7SL4 zRs?3XR7>kytAsO9^`r(t-AoIO52Mt06?y%I(E}1bO~!_GMhI+5F`ZnhL0fmaYRcXg zfnFd5&TrOwL|HGJAzd64Xwg_*fapih?|V8NM$L>u9maef`vPNXz*J4XV_1Jg`;?XO zQ@LA2j)p}H8`LZNt)oYBjz%m7u#L_}^0FuF7)Gre2WbV%VJMB=GU>Rv-ll!E*cx^l z+gPI`xGQ1oeymR zY0IFp=!svCy+Pd5c^x{h#6}00d(r38KW7zSHI1TwGCnb=H$q@B9fG8J$3_jtfNR6& zI5S)?5a>_&W2fv0w0!Ufzn*KhF=a9QXW2-}=aNnEeDj|=!YK?xSLtcrqUp!JbMqBX^rV~!kyxJF@v@a38?_b zQ-c-l>0Qq{4}Cxd2>dEjq!fzMSV0nx_q;dynWgwq%*uGxzg*GQ} z757N`a*xfxg8emmCikE_@Ru`XZ(CH?%PQKHCLKO$6Qe?^fq%f5(;$Bu7|!{IK%yY zVYJc3y>T(IlsrC*sQN8P2uwuuz6)Nas47Y}8ZB()Ovhb0;?qD+gn(ADEm4T7@myvg zWK?vW*ctkUY89Bc_>B}4J^{>rT(3ajH?B>dIpHw{APrZyyUw;5R$B@H({_g&ug0-0 z&vYFB{pSCdH2OD4=$~Q4jm))oZz<~v+OsWP0oHVv$zN5V3IL&;Xa`1O2j^4g7Fy6O z9R$hHUj5Y>Y=F08sJda2yJR@I9UBc%^xuI|Z}RuuT`n)`BcEOV3tgb}#?zVw)xc6Sx{)c}6uA$2r z>|v;{)))a|0#H`M0U-nW3N?rUCr+e6Lo7Q^MDF&8Gaib3DdgU>d_5Q+8(&F{6_apG z##L?FcI;YhRnj3XdXnYlOU{)9$xx8w{=ci0cc`AC8Uj4wE(yU2f?J&~Bs>u%CIo$?8fsfQ(W}0cJtPq7z>bC@c)It*!Qq3(J4w5*^S2=l{TwQdc*>*gp@6V(1yYirS&crMlG0=JN>@#7NtcK;MPfMM-ef<&jdH{ zT8(}f&6k2iKxs603j6?oegiGG(lWI29|`*n3WtpE^e&%Cf{0i&iZFTm3-;GdBSKzjNE;Fq4#akg1V1u=-je^uu9p-7(qvIk zd;Nl9Tn|iCs!|a_!4Rp>Sdv%fFyJ~$ZK9ex z4gFbW?Qf3|GOJORl01D&B89~kspnN<>yahD`3XYlH%56CIX%Oo#dDhVfM;>w2_+^CLbT4T9JbG#B!srY8-ywaS!7 z(InKGN=j9{fEEit2ve>vsi8)iz?t0@>@rl@0*;90bnTc%R_e>Lto1>a&ZF}+g5_%` z4RkD(>4rwX;&hI%R@5?3xz0}4-id!rekxG~Cxj%|M~VC(EsqK2|1pn2gnT6l=9cbZ zuRpRMQ|x%;?c-B=!N<8_pV&V!El*%89e#q{KY4m)Su68a;=+~eJD{pIPy)0v&J)Xi zk3*6zeQ2+q#28DYpjgPUrl9=ntVB_z+V6UX<3pJxk!Fa5rm|*qvU8gN*N8orkQ^0z zgoa}d_PpVZ-+71e`}@>E@py6_xuoE`?FBIC^!?X;|`yzri;oawqVgs{;Z*t_S=X*w#o={sDzdgWmAouAzyK z+3~-(zOy5!OUv>yPXRba1u6f{&wQ##T@P{HtQI)eO;yxqF=gNA_nYK|FO45e9Fcr3 z1-#cv5q8dWXu7jD`FSa*X68Tli7ei$(r(Y{+i`!14pokBUqoRMSs>W7Zw>_IlP$VH z3e0Kr$TPB-rmPPdH(pAVYa$Q26z%Rv9zh(DtII!|B z4OG$pe&@d6x&7056f7QUBN5KfbQ}8f%+4Ou>4dJuAe2rx&g}E8u91KrtG=^(%sdD z+X(g=oy?*W-cdW)!dr|n(HGu?|Fjk!xRfD`XJTo;3ZhRxle=0Ts3RcWl1t~)e=olv zAurzh)qsD!f>o~P`Su20;xIAJ3Rbt@2)+&d`3UaE^uFat%P((^a)8Hu$+-zILOjv6 z^HQrQ86uYuU<7TGsvwl@$53#p649%m%Tx|yNrTR3z-;rM2~ij{vGy@5I1`(LcfYuG zUHcR9thSot$tu5$>g)WGOie-)W@inoOmhP3GRUq0h_ot*aJM#< z@-x+#R;g!h1d8f9njX$il{lnYKVGJqG`Pz(v-e$^j94Tb35;hp0QpB#X$~mLbwU3Mw z!=VuV;x?`)Tk2b^CnGfp{ z?Vr_&&}Ok>>KXt1_9V+;`=x9W$)dbE|7~h_+6aI0kj@!zBd^;2T z;+4Z3coTx6>#l--GqBBpT_kvQf7A^Y{rcyj2yb0y4ZGt-3w!0GzmzE5?eUr;!fDGe z=OmIo$oEu*@X1=3H!0-1Km$;AlTU#5Z5yEJ@?QliE>{p!wR z?*A*>H2@m_E^tL{vX+%h}-{^?PdOV+1@d4E$#m!+gpzN zpR&Dllx*)SDPLOVZPnsPEbe{C^8C70A5cKsn53a@W!x!rGUw6T#cZ(ZA(&BM*e^1D;VEg(1~NxlriU|~g3DeQ1zAUe zNnL_}4d>{!@h~Kxv=S4tW_uj$m*j<`L{?;{RMY0t|*_7JBh+QZ6*IeWG$ zM(?u2>W)7LY^3J*tVi&EACO~h??sv8voV3Oqxwl%$Z^Au3y?#O)J`2kei-2>Q@(1! z^>o4zna}wDiHSG)j>Ap{*|^%h>qKF>3z19e5r;m)r`?xn7uL@Jq~q0;nU70m1xx#s z>R(Up*TZ^IU0&BI2m#ck&FVxSc+=Fu(Eol`yWSqZB$_VZm)f*TX*6Lr(FYZi`B8_>_FIpg_G zRkH-Lj2*eQx2hquwcDk5*ZN9|Y#|D3gRn}aJfFj zo&J#M(&hzuy}NUd8Hu zUTftk$~t^|MEVw>`tkXb>)O>8QXC{uLv(`Dhty%c+F6qey3_m)%p&c47N_QYENXVi z%-rEY4(0koF8`0WRC22p9yV0}9rTG=>d+Y9hk;tQv+dw(-1hy^rHxoVRgI*xxu(RKkc+O4scrS?4f!owmAExL*;wg@Tfrn^{^5%!< zHkFnq`vZ?qsWc}YTj(R9h8jWHO@FBYMoBRAx_A}NwDt!GHSlv8tE{=v2o{rfo|BZG zS>oA%;U{WL5(vt$SHFap_Md|08h$$3+Ifnq==!-eR{FDi>A1{r>q?9p(Q>+UZa2WW z_|v+8453R5pP4JRc{?EU+wHp-(ld;xdBzQ$FRy*V0)a+;%f5X18I1gs!Q2kCVzP01 zSoxum(s9nu#cuj3#tYM;=$mDYOV-sYy;DJ9!wV+=@1pvTI-1=N+aF&G=11=DH*{J> zt9~LllJ(4tZ*2(;k?QfCGL-h}ZY?dQ(l9f7hA*TXfIPDx5_@A;S|FZ@Ws&%AxqR6Y;5VcIqP0gL zbHaJdt~Z%i>>uM4VhSALJumX^VVN9vDm;SS)&akhOE+_zJ^FW3QyZap{}%LUUPQu#aD%a*+7MH|N8 z4SYA>P7gGGIL8)EB<~giHU$wJhP(bGD+?T81gytsA~wi9RR=f+ZH~N> zQaWA@Ic0w@+hxC;ZIk1?RxKXFwSi_+PUHbuW6aKMmwR{N9Y8*{b&y0{-)^4(7qd8z z{Am>b)@F{UP!gxc`H$zb`Xr37`{U;a(}wHIfif&DoR>C7Xhajxm#jO`F3Uh#`(}i| zYu%nGo7=ht%H19RZPkxzrsy4>ag1r`k5^x4I88LazeKzzz_Fxy>o;`P&y`UdqiKpm zjvpUJd2$9>=4$&>X*Z zf9@n!efZ#WUI2pq`6ApSb<(d$nc+Rz;6@$sp0?$^gpLV@kiYo0#<965$>$)}5DS21 zV5-g+`X(GW9A|wEb8+@7p-|At1>;Jh4->x$iDe+Z*Vh|2w`Ka!+3T-tdwd_{L+D`2 ztXgh2^A?IN20A36UPE6bGPrGSgPE>uUu(G`Z^BxLea?x3EaXFv&{&9VgI<4<%pH&# z#0)cjB2)Kg_FJ7Hs4CYS^a|)A6 zZt~7ARWq_x3C1=|UEuQY3Xf!#K=en9%sJNXspNX;C+~d?DdnvG8tH{CF3>2WF8ie? z;(eAHcvUOI^w<596tU1@piGn~+wksxdPwkI%l z_-R-|$~IwFGue16!Ax46E+lzBIEtn$npp4M`?Q3xqQo9_Q#|REz1}#v*5uK|IFV~j z-PTmYUmC$$n)<|P=E7-~dTBb^X|^nBFnAh52Rwe0=28ZdMPh&4CupW+L;LjM<2BoG zFJ{09X2v#~5BUf0ZOlNIjEHX;QLPz~EP8Qw9}=%Kl34V<+@;sKehUcvHok#rxQ3N` z_idJzaDvYkHbMwT0K1WdhvrdxlFwnnwusBjCohN?Q&y9A*3+Iim2k?C7f!&Lp!P5B z?R>Es1z+}cOqE-zz1~zBmgnPVnGK9tonhJ2ky&$~tjvt0Te{RC01MDEbu=-n=Sef0 zgC=AIo-OiIt9Z|9>@0hJA18ASyTwlHlqGkQFB!0f(;d5XMCScI!@W7f#RcOmow+OBd<;nBQllnYV%@#M1;siY+rCs3mkh`}~8}Bu#J8=PXIt z&kK3=3k9PJEx7}6ZVHRIVJ!%}YgEn&)$HL0XLEy5MW-rme1$fc$`cq?lmJd?E~5gzxUKPuO3RP3>+!qxs#W5cSz&>pyGK=6f zYMicwing|jVl}`O0v}Z_QUjN1wiUspF~!=7@R^Fn?8|IH<(3o}NRcY*sN%x5;^kij zrL5V!3?)6{g>IRUD(SLX){0Vb*cTBnYGl&VR&f$l5vquPgn$(xSo(d+VgVIeZIyNR zg(L)J1Byjf3RPh)ShM$KHuhEaQB@BLsY|0(UNlg?0WBNF;v#tAoBKjkx#>e`|zdes03A8^@OX`+1@S$oaSy>_Wf&ETkF?voGPq8wNmSTB$X2R~>P=|`w< z7I68xo_V3p9KXG%q$+*taGka`4O zfDcU0zNuaug62?9KU^C9WzI7}PH5_AsnP=!Y%oUc04OiUwYiqc<5WLH?iX(1FT~wJfq`4J=nHz|D zCfuVPj??~qD6guINGdR^Axo{SHVWLJ22*orq!X>{rmTyG)I}Nqu92{JBCSlan6WPA zmB@BgQTzi|98|?Bm$H#b6#tsLtwF6){|Q)CtqyBjDeAf*9Ulw;AKEMQ9Kclx9XS_`@PrxyS?{oik{ky-C{+*P5ne9< z?0>YLGa}x*auu9t6>^ z)E6Dy*sF#DDR7$v>)%kA=_XXBFm+x*8&6z1Pq=#sj&RkL@JA|8?*=^d%&L@s_U zfo(oESbtX1OWgxq?pJZdi+rjaRu@GbwsuYXfe%M*c0O1g^8>~)&8C%{cn@96bhWFB zg?Uhn(uAVvXh^tXoq+PtBLwx(p;gr6mkJ@^2rfs!_#kBuMTIbUWyctvg5hwq<8U~8 z&#D@PRCz$qcc5lWOBMk6b~Io_ZYb#+*+^N7LDQ`yQ>YIIZM3ypiFW8X4280fy`~zf z?`U!Bs0MPkT^|g=#W4e@i^{lR?|nN7miv_}hZnM@pg65C%8`#t^?U7F=?JU?$_W#( ziG$&S;LQ=#M0jZ&6EnIH$FurT4Z?Id`r2{mHTxLVo3WR;jc;QhX2eD5YGr>H8`PqQ zp)phc49DO5)x|$$yOt;+J=(SO^X$Pd+GnVE%>5=7#Gs2*IEiXqzdPE|X!R%QZevq;P8oQ9||hrG@7$Bnk!^OqQ@4ix`P~% zGfD%<`@tl9NNoTL_Xk5{;cW`B`lfI2kHC#DUX1Oa!bb>D_-OSG`%pjIn5uuB3fQp} zfo(}$l&t}7N$6Mh>r{@J%bS>bTkw{$10Tp%=A2@#|!&npWgX!*I-!J<18%NZnUG z-X{>VTo?#Z9aU!&SSb<*mmal783Mk+vHv=CqObSOElowR;{g4@i7_+qF;o<4HH(U; znQqp1Vjh+U3=;kQHgm0oy6?q{pP$A-s4f(-3mTeP-R<$TmI0(<4VG|*etka)!UO;5 zoIZGQCyi&{Il8{TYO=;+hOf13kTz%045Y!z!YIGZE>bttND z0Jl+J6nu0)8}4HZLjohuv|-fN94{Ap^Du$jn@Su|KTc?A)!h5Zy2_9lhgDm0lm^?U+2yA(SLWhnG^MAj&jR7%60Adtxs0P5{hQ=5{?x6T#6wAG)rFo{< zMr)2Z%8N(l8e%~0S@EZJX(<8xkEgws$IFaP+I80+k~AX z=fx`Irn>&X8_FXrqoctS&M^56hTMt8$_<>M4Z*Hab=;cVfBWc(pr8MCfa*i2@SP_D zQ{ttLArMRn**gl@qD|OgG62|cLSKEEOG1`X1{5Dw0AXvVm3BVEPn_-v&d?&4hO{n3 zDfJF#?&hZsY=(ExINYJ=1bmEXtT*F_Km>Z`84H`}Ry{Sep{pOrjVY*ljb{vb7(XdB z0#r~}7CF|px-?_19C3e{zX*=vj8sjGyWD6SG<$jNsQME;wNDGZax>|BJO0~0Z!rv+ z#z%PzQUy!1mR>vey{^RPs-A0f#=CbJ2PXWCFF&>DhQs~;Fxqfq)19#_|5{qZukMp4FXV?-?V}l3Q6L3758f_t` z1yh~SkWpKgFu@`4ab;#-FYq&GFqTe@+FgvJR`5o%N;Vx$XMNG`7VfE4q*@|ww(ND7 zHf1FF)o7zn>uRr9L*;wdC_}o=+(=g!=Aj__uR_VEFGZb=B-+DhE%XPCzCSq6LS91v zrqoSZEIlEhda%OiF{^f=EQd7}`NwC6pKOd)M?Te0FR#V}Dgp$KzL2pKDN0lXj~uC?d$QVo1t`T~{=@91$6-IQhl5UFw6 z1wakfQW&BzDq>&elMznsN+8rnU%g7>0v(l8UsQ@2V#R}mmr7~vA6 zLsgp;Spo(4r9Cy-t1_1$ zUaQ7KeR$tU)2UpL78?ou$zDZC?4JJ1`n&s_)ES(ZtBO06Vld)kU+8TaX$7mGw%d&R zsJ6(VTY9g)O0PSSYITKGVv^i`A1p}KE(A*rLZ;k*{y1=)hDOq=7+H?X+RXH`lwOJMOIS_a?|UpE=dPe0^IExYFmkzP?FIn=)KvQj{%+ ziOehCthh5~E!Gljwi3PFl3#V39JhaYotJ$>I)pvL8MrvSNe+8-{EiwQAhi zkC5g2ojqUU)h|1@A9h6MVl>SfwzyA35gH4yRU`KT&YO?T8cRLT=pH$s8bFwmL&Ts3&Lets$4iaq&;w}e z2CCd1GTkLxMcIENnkltTpMTndX=m;#oPC?W2&S>fcE2O8`o&lA{5ndy{Xly<#GNc)zg+)shE69dRA78-!+?SJ6-iF< zTXWo0N1Ua3(r3xFHJcl4ei&>duASj;1Urr_HaB%A!nm}Zil!`C+Eq##hqw$|*d&z4 z<|oao>vLC%>A=)<)Aykb1}d5MA1Y`kyZ*eX%-MBf$O3Es^l0ea2J7VNf2W|GZ@r>9 zaV=6>{6!(CIx}$mks(;;qxpRM*zmsRzyn2<-i`UD5vI0ksPQ>kTIcHPkEGp{t2c3; zP1pX;enFYP_cln|U9M|zuN{_)g9H#Wz_XxeQB%yNG&bN~O>m-v=^p{zhX09VT0ZLp zeE;v`ysyA?6q4zZj|hX(DQ4>;ru(DGh-v??VhwNH>zrmJncxMn_(;-vaq52|naLJo zk*pt^l&v&&N6^Z+=cp8~@}{E2;tMd!Q!G`}WD3I^MG|e)${9G!ix%pOW@|vrvJI>{ z8)J2-vje0g=8z8hu);~t=E*r;<%s%sTJh<*N%*HbUYRUX*zfMKS=tl*8^@JiD*Pua zc0rbne$Q7@oXp=&XGXpb=}HeC zcl}Mj6;qX3Kl?WWd+R618<_+C1rON#_PzVNWukW+DVG=cBq5`vSCx-xY6ME!HB~X6 zZq&8SQ<483&R`ZnYzQH2$u-A9sMYg`+}+el0IDZ7cl44 zsdx9winqGZbb@fA8@VH^7=xwJPXSbFUDxGYTb4^%@_;EdN9FF^E z!8~0>V4)07$j0W_d@R5=GH^^OX*6rpOsKd}b+h`v+gaXE9JgyBeCjt;pXsY_H(~@& zZa1Ua^Q9|O+SR=)C9SKy&2ZMoinAAkD--y}5}bYZOTSn9>{}2X7ccZj|ZJ`uZ;iX3J4 zo&0f<`IepJ&%Hf54@A%ftMZVT2)6XZH2Ud_yvKM9pLj@lr8q_c@Jh2r)`Xe;=@y zY|qmdX?31>Y25Pe3yl=bJ^E&s8c!v+j+!RXr2=oMSMq}yPmm%Hp|x#G!W9pO|M0E( z{n2m@TApOg-q+1@-OoLRm9Fu^r-)4FvnbFG^F)?Ka7Yxe{k2ly zJ&{aHZm@VJr`K6bb-_4sMbG8CPmKTUk~XOlMxQ9rWziC(@oS8c-d&FMvP?aN>AatV zV_(9)fIby3pN{$+^SFgyEnq*{>e*x7(;NB?KJ#JvlG?VlHrIP(IQz3Ae!h#IVtzut z9x+)Qslf>@{m%s)hrwOurCo9!pYzER(b1MZ3>)#z=Db^$$(odgzdU4U{3rPv*{nZAkW|H%X# zMFB6p(#>mX`L&uQ(*HylDe#&M6tQ0zb6w0eaiZ61JCzvDTs&_8)NnG;TbU>*iYJ?I zea#BRHacWYYacBNsU9HK{#&kR^5o&c2HK3qJe}9k*r{lGr$4IGq0JK+!Qc296e2w2 zqp?M+oEyKAfzb+1>>cFHj0SRQJ?=s)U6f1zX-IP7$gWKopi_t)DB;-(Xtu3#W)Aw%dTYL8Q zAp6c3OVGG2r)%bXjPQj2{?o)m%w>95@Zw|7S)LaskkC13*Yx&oDiH7L`?>O-Bq)=0A^U+1RhKoEjdXEwvP1ODN<6O?*XmLR5wN|K@=r9+uaKb8qYB zU*HJ9d+aZAn;Z6d@HMIX_j@zso*mSl#%kj31PA;n3Gczw@LJr~dAiASHRg^GeB8CI zx%7XIoBf5ZjM6mn?!y8vlNp)bgcP_W%dc(}l{1iIs)9mL2W) zzKiu;_C44)1;mq~hSD#OW1T9uA(LU!x}7Izb_1(G^LsS@-&ci#oh(Ar;O-g9^C~R2 zpJ12pa)z$emrTP?oqvt5E1o289yMARZ|@$y^Oe;;5n<>59mf{%`@T43({-8i>i&`M z-RbW(~ z0XeD#Sz<%}2tZHZ_z%<}F1KM1Yq%OrVTgo~g{F}G4>rz7*Z0_N7HD6zbOGrf{DyWt zfe279BGmW^`|C7mzC>o&Z4A;Tdw-j}^?1H-ZjznL_eGrdw$%tBBNPzC+&FBD{ zksp0qoRo#6y3*rH{{*0Bd|o<$Q-OGtdZxi8SoJ12VK|iiF4%C-?WY_hUDp=~#b$c) zMvc?}m(<||cgbbUiSEqq<1Ic_C5iqm0Wa?o9nz!QbOC;65JrWtA5GX?w-LSYq`dH$ zyWuazaO_7!%#0T#(=>4=A_SiFo}v{+S~~v6tl#*=%FHzzf*5 zWa@-O#vfgPH!a%OIXoJTem@MU(*V?KM4TX_7rBD$UW6ub!;TOk0um{I&qE7;bEv(A z5wpYSbpcw#A&oDhdQ#n=-c1rmVtxKtM+r;8%n6{fNbvho26v^1^cN9JTrfG0v=n-O z;98nuv#U#~V4((}VV=z^Exi|$b$>7`%_F`7?$m!BV9E`n7J}7>XD4uldk%_Yg@~Pn zqU{qPcs#C!O%eDM{tpcR6dn z%~jGN9sZ-Pip-0AmdUNKUT5Y%A0^zR$&Lxs3Wu9aapFUUQw zV*GB>-)2q-TdyV*Bnm-vA0knr0q`G5Kq#jH zCZ3HKM{X(s5s-lUP9-Je1nUIPRq}LfqyLZ&`^WP$xTd!m+;W!N$O8*F2w^%ztt!KEX)8<&08PlMnbaWu za>4u;_UB2ZaLu~3R5Z@G^Na&#&y&&D1bVtwN6cGxLtKN;LhjyD($vC$i2Ga!fE@C` z$Zg2Z^#SaMjjwHM3GpoZ(&KLAvV;utk7g_AzkR6UhBffOlCbeT%HjCJL=N7mNL82v z9M(8;kMuwZZVSsRA%DGu#;r0FU&K|SYwsKQ?_SvrYCJUJHJ!Yyk2QSA$=zIv{+xu# zaFlMF{8nVh4Ld`@b_^i7P+ANx?9dilGSo6-S4*W2<%U|K51aAS;js5hL*=I({~*A#;}}I z5Fey;Po_^pB=8^*9RD)hroi!W8?$C7>4^AlM0q2mn+O{8wY+nVuDf@*ZRy5osVI@~ zfwVq5B{8Jovr;sf8U$tp=+1Cggd~KfwSiblIAmb=kBSM_!C4xxa*tZ#8c36EJ%p#U z=DIdAk~M~!Qn0O6*ry7v(kq`?izx36{hdXgL5|x~o$|u60gwVfi49vr{$W?SCnO6F z$y-BRcxDo?fXg-dY>g8180>i-^gH^SifHz)Hs;S<7kfe>*>^&Nz8cWXwSW@_-}+NB z0+z<|@B!OpOf0w$zS#Y6fr6VCQnv<1ML^JtIZHc4gnT*|=0GHa$YJMcA= z)3M-v-jc<`Jl_ZQradF%gdC!|>1K9AgbXDSZQ%6D6fy&7u0fQy1Vonyl7b*2j2n)k zZyt>LLKN2lAnm>nr7d308My!a`g0GT{Ub3=r1+g=tjq`mr81EXpK_J~Cm{=+BV%Ea zvH5T?w>LN(NpMS2a$hD{_b^?dXL!u8fgrc$(r)CEFXi|B=cbhEw~Mw>7b9=zCOFd) zBuS?tD!{g+<7hZI2oBS20r>)EsPX>Ym#23D{Sgzr6~h+Xl@fMwZ&hK1{^h6xCB1)U zHkxJyR^m)w>OTMIiK`sjKOf!Vo4U6$1{4A(U?ADY3kg_AtOme6`kN0TJ~gwreRxol z|AWL*E9zLx?@y~z#;j;b&{D%Ilkw_kd8!npIlDcvFr(4bCsT3A<+wFa=o$#Oad$Ib zv}FWFqZh-+2h;bQsw%Tlq?uRtaiBZ>z~7L7MK#qCFJ=YdPqENuDbH{}NJ$_6)a3Hm zxWl&z(@6vKq5F<3gve$F%hvS=8KU z?p#{*@?_;)1`I5N1mC{=VioNR_7Vfnm;O{({M2tc8U{p-w8=ZJnE!DK*nJO_Mb(6QqkhHwJ!jWht=0(BE)fpnyZv(H)owv2W=|0&R!*Cd|aUd%rmBXxGPgK2GSMz$8%U{x<8B zAQ7Hi+zC?##bND9Wa?kB#*@`vl9FTs@z9e)&1^e@DJAsNqaDqofRFjun4>+?b!f!? z+poJ;WF;x51m#bTr@;AZZpVN?7!`*S?JvrOb+^5jI5ne}e_4$`)86!hJYx`NN zs`kT)e8Nhv>X)$atJAReupt%+D$}#Rbw&mpZVq!MJ9);$O!y21WPNu2@YOks={cJz zKo0}t`+hF)3f-DWu7fLSv@? zC}^5|`SG0A{cmnDz6amwc|A{EN-G6omulZZ> z<9YGQKRfJq7vJvynh2ab3mDHXos64ghCn`0)6r?ZQZgq%+QZ zk??j@nk)%*^x{9}3&xg24^G|bVvT$i{^8=hcxk^P+m#X5!=f_Ue2)W_hKhyELS>Fx z&xXpSMvAY=ZGALVE3Ix>>Dqa;)!#df&9jd-NU-a@FEmRNBb#b0G6S^ceASxI`-i#c z4OhpccqS(>&uMj7TRvNl6={`slz5&Ue8XCdX1{E0I9_UUK3pA_HqTq_if$lNzeRrE z81g4TWVK1X5Ru50&heuJTpl{G>!n`SF->(G_HGgJ)4sfY~22#-^jxv%n5uzwlwD)p@ z1@Yh;VXPA_%b{G5#8E{?-^7hbp#iSVsQ-}iBzHe19uJ zLy>zsQTvU}c9Pz^((Pm;H&0`pC;r1)Jjxf^J8_l~rS~XpceWH?#aLQd3fP}-g|Izo zU-%j>JH5c69_EcPWTBdX5I)*b<&^zJ9S&Bp| zR7H|6z3ycxq^sCuxs|2IGv`3=z(wU;&9Zit@+{{2F*cMcJn9waRQs`hA^M5Ty{wP7 zs*8!dH54Zmd5=HO$Qc4CXWx|{HxLT9Zf4~VL`)V@H`j!#yDp^L;B6H>Jdit9`5fNJ zS>t*b?Khb*-F}qaSFLQ%ez+}nH2|f^m#%Sr7t<_ygiI$>;ydf3(lrt;piwnK3_N%> z_KpW0%6C5WFvZ?!2v~5wGYtP0*4HD`{h$uvIAi~FTynSK=Y)jm&CVAfpz=d-e@N-! zbNht?mrhlQanV+@`}XlK@i$W=Tk`)d{ZKZDwbc5?9UyHx3x3f)*_!{i#3uh*smr3`-ixR$+zzjoLSAw-GVZ$TZI{hQ`@1>qNifhz6mtGoFO-T zBD;TR+`RW)LNM+sr1xg?s23_IW7ti8SM=xB`Mdm6rM7Sk#ATC!@^9jt%?>s<+gKn4Q^yFM*g*R!`I`zK>RZ^f^7-(M)$I^UtisGGm!i z?lIv0IqR~|$P;Pqy8;#QgE)B`qpit(wzrfg+-rn%vYw(7pV_ywKN@lE7T`}U&#LCV zaZc6*g;SyY$n)>^=lgHr)A8vu7NizwD!L=nNi`RRTm0cug z!=XlW;gbQ1Gr5pTHAVii*9nhjX!TWN{iH*1kA^U|t_?bTFp;cZO=Oi>A}*BGT2_qSiXX%cfkoBOtd&#W93T!<=1P0&;oVSMZJshk@?gTUkBlIO zy~l5=PTsz43_IfIAeyUKbcI_L+R7DqCBECK%M8Mj;ZJj?1B^;^qYkw*WI8W%k0A=g5b!#Qa6?83@hMA}KK3KiR zhOU^CnR^7nKkHR}`e3(A_&%ks5P|e?IGn#*bn6EB^E7g_ty4`Pnds6a-LX+XraGkTZ(hty)xU#uWvdFzc#O0WDJPinna zxB}-l_!`~N(_eUdLHGJP8TIuhH=2uST*K3RKE(gb_`-e{ zQdL~@;LVa7sAA+Fw}eYgRPc}I@Ec^P^Z?^W(fp-vEODp(!s=|%7CIAI*^?M3+Vq)p z+RUqGt~qH((2uy@8~*x%tL%DW2zaZWv%zzm*5qgHu1qKWJ9{4nwf(Q8S$hhf8sACt zZyD<8Z?mYM*Z%%zy*T4`=B2urz`HXf-yKJDT+;FUNA+JB(yM3E%tJ};>$WHA5B8Fo z9-nRrpqp29#+W`he9g+f;{0Je%tZ5hNYx&qgAJs?!fUmvCLr5nkJtaer6ku^El-hGxj@~!H);e%8j0A`n@`OZ;pIRalPAjq2vg;-TY34t2O@?gI2t8*ge-9 z61VDsyG2U)ku`bH$a$U(xY;I)95u3KezU@IyaNKDx)Kf?@5wUZ_|zH!x>(SK?%Om( z0DB2heu`7iB;@<4zkCCD$PHR428p{u$;_i9bfML*R_BEd)^iGnx;{@>-OI#u<>vg= zJ>K6mc(LvgunE^<(tCQ*gSlc=v67JN44Ir5e$ZveF@CE|B(*vXnSu^PY zDzVNsLmv1Po_3Ocuf<{NXV7~do)P{*o_hA!fwvVz9C~3Nn8gEhJc9L00{G^G1yh6T z5gu<}Ghwljev&XzUD$>=%=`+)n*udg2<_RG2<@{_z}L0;ND@Bak27CKXhL7kz1Osc z1X>4kHCY9zidcf0z-?mhvP;w4A?bT= z4+k*@!isj&dVpCyS51lFYCUKX%z;-g_;HsDSFxp9D6|9(vFrl1rpC>LK@^L^bo6tu#7czCXmk=54`T1Z!6S zmM*vh6~?|tPH>i>ITtS94{6g&>|H0dh2s;hBgy@JHN%rWf$jV~lU^xXjS;;yZjR=Z zbPXK}AOWNSHIgAV$xUVi7_&5co3ugVb=8ds_T8BGa)FXh&9w+oBFOV5=u%WwAAl?un7f^ao@nY;)q zyh_(m&Z^^vC20WkCNq|XlS|DK@r7}SA~GmvW{O8Pg?VOphymlEZA32QeW_P~UH~gH zSd%lk#uJtR1EMwJ?3*(bxkG5onR81q#U)0q^I00;IN$eVMH(qj*9a_7@70sR!uRu^ zc*3ktDgLo>zaI`Mz~+H$DV?sY&UW)>QfbOiZZo?s6+@QRp|IPuIL6R|m3>y)v#{p| z1&=~dZPz*1V!o6Md9OV_K-Y6yx%6G$Br1ABY`H0@r3#J`vN;zqFT5a~;6zRd*Wcn! zYP9444ZJf1Ofd~&FQqSxTVEh>vD75Ele?IP#eK2~!_^Y$pyKh{2I40XqpspaD4V5~ zUKD2Qeg8K_At32HxRjEmR3{vzY@3+<4Km3cJRxrD{*L?#nML3aS<*KyEi`DmrYHbF z2xP%!_bDoD3z8sE7B5^v2FpjA_Fz90hj_8>kk(HUzHon%_0Gd}m>-i`9K! zRw-8oMx?%`A=@+8pv|;vsID9 zWjTh%$K{@nI<--Us2#GCr^}H+Ult3FZf#*R>Jj(p*<|2n=d+-*H$=1RlQ|Q=l(k^t zvtU>2kcjH_73CLivw9+fy+;6%MOctLFcE*iUsv8I#mE0L%8Ws+YiXD$ysMj_qA1^1 zm?uxz;0X3;c0loT0BKKXAT;P=H0a7V=%zLZ1Zev#5BjzZqS^*ds9(Vyx(`QwCHu>XImf%@N5jZh;e{-vg) zyun!b^Z!aU0v@DTsimD4;C!AIBbhdFg(}hFQq#-BbvW!lx&Dqy-(DYrUFF1xr=POq zD=yUtxp+SNB};%L;msvmefhU)Gl}qRXS|JIuDAUG#-k1VYBBCyZXX+_Dpy)PI334= z>+>ixJqe&pMrJ<-J6*xNCP%Iormb9Pc=5Sa<`e&ZL}&mj-lRz&Rlp1|h#9ZTDENU_5ClMHLfGZan7lU`OyOv~5kc{U zZbKffKC}@r6|v*)#%Dc(sCoK=-469m?Ya?N8>j%kIm@9$g52Z#IOSpN} zHSg(v%4Xeo%oV3SB%EzuJN)E);`(T&c&lw_A`{R0AJjDnD^u}4G#(@hUQT_-{_Kyi z1@EJo#6tdzD<@fw*!z!$BW7jdCMZ|h_QpQ%_f@^ik3ORASLBT}FqVVLyO@s_yyYEn zU~fl%iFkc{flyN|x<^|oxe_;Lrf+Qj)v%cK(!r?Qp+QNn(--zd{~5oVs_OTwlw}p~ z`W0~%;82U`!k%BBgscnmvkxlNaWYaHy&uUw_eH(LLegEN}ggHF?{zIol`!9fKPg{U5mvhY@^!S}w z0ExH6z1t#t@={#DDFru|G-|WpjH@aG zDv`!!*doQUDg_#4_O6sY!K&fKYLd<4g6$}_7Moo+#6)3dp~QbVqpka&+GyqFoRRzSuN#e?vT{jL{_KtYP|Qu%(b!z#mv9(ciZ$B_~qv;ZK# zt3bWuLx=Yf0V#7AKG3qHWAq;Nz)$y<1tMeycY zd@mmjh8#!-ybl!$(=qC~hY@14K-NSAjLA`Dqc-)n=qTUG_r?BgR+hupN8eI+p@Aqi zF2|w4P|~%bm|0WAq4ss+m%`!e2BA(t&VshH^G4G+GfS)Xh$!7(I zK4iZT#4HLQSA-q+u*CC|RaJ%*(05G&1*5v75EJpVKV9U09AQ~oXgWh6n}8x3Ln%frw}h%%W6(#nLZg zmDnuJLf<{K5Ym-WeiXn0cDcqQNQDy#6(RBEAM`R=?sf5Ue8g9^X3G*m_rIve!&L{@ zOUos@*@XQ4pUJ!?=e!Q$hoWLwZvAOr3?jTd z)a#*Nv?c(K*^*5(knV{LJ<;_PwqEJ!=9+$32vZFsq7@+B%R< zGDuv#8}G>)C9G~6_=t&~L@_ zWc*l1ym`#ZB@KdM0t38{MdI;`{({o(1<;i-WLQ{MA;u{)x|A2)SV4{!+(SC0}9 zQ?VBRv3jq4qpBZ4`J5qM(jT^JPX5$v?cR(I(#CXM$szHa-a%8rt6Vq~Zr@Fs#~$)2 zATmfo9uI1I-OU*>BBvR#K`1nTuEj595p+%4wHRhcZLLX4^aKAcFx6U7>@z&@>*6_; zidmo5aBHYVK|GyY7``ytd|pc4pIRKzFJO-V3;fg|r%;f+KaGJ&=>3_7{4YbGs0A(P-rd7TM+@lSR|Wj+oM8g|+;O=3 z{{KUZQ^37rHvDgQLY_j%sEE^WQq5*<<^;cI^p$b{HL+jN+RJKyUua`b91FBqL zT2ldfNtGGqG*yWTK!6eKK@7zXm4RNVJ zHxWe6c4hTUQRp^xd)=Cvf9GF=phRc-N$)cdTZgeea_hgmaZ zU#As$Ay(5!Lah|%gHw$05wx*hC&R_rngl`*PcahA|Nxr;D~C?06CPV;m!D38og2_4Bts}S-znXVqJ z3lDK*9Qls?=S~pMFvOd}-3h|5__UoevtLAXSQ@;WoP>cn_sY8Fta8WCz{J{<))A5N zqXxlWzj(3T0zra+ulMzD=PlDyQ*D7)|(wWjlR875UVdpb;)ty zplZ0Lg}A)+Z75W0z2Gv^~$hYs$>8du+MW^Sy|{c;1(8U7WL7*P?LCXqAyxdLMN#Oxe7 ziw?L&nezTPXY z{(FsI`Qz!een8*A?ZvkbpZ+nRLf-woz3Tk*_wS+UZz4Sa{(US8B!j`fH`I0B|B9QQ zA%u`qx!Zg>fHb`XLnJZOO{Rh-jXK4El$5*AAT^=y2f~d~U3V z+-qz9$ooMwU$dzd;E$n^QP-?=N}yh`2#rWblKe4zrGdD#GdjDAw-26pg!7(!48*ZA znWZEZtQX>f9Um&-HAoIYdfvuGyIA6x`41|qPr845Yakx(eNnufK1>X2HINMJXS z2G`f<^iwuSWzs0$aXjhh*gJ9NeKiNKgjC<#eu=cOZqki&XEBvL!Ah=)4=wjn;XcJO zzWOM~39XRk{WU4ygvC z=4z|*sn$WnVDlDcQ5~HCwQ<{5<0G@?=%gwm{(hsg7VURiJw=>}wh1KcU#kVgN`0&j z)T`6yi~iQvD9!SkedC$`C$%&uM2v@z3A&J{(oiQi&SN2a^R;GGG$g6;)e>kl2h2oG z4-|p&@1Vp9;6;a^sBjhW5kBKI=dhllQ@4$O`IL zf`Jq>S#Ivl%|a)x^<~DLJKDJ=j32yd*z-*B#afT+1$7*?NjUySC63WRwaMIBo^LSKy8|L2M7?7N(iE$s>WcbMfdqP%=_Kupl zt9o8Yw^Qj`Im3Tu=0dAXed-iysQvueeB;msIz{hmt9dK7fZyK;=hr>Ri3lf30U zG+6pG*EHc;B~fl?NG!+HMb>}~eQEzzFn@kXy`eUc5o9mPz<~8__*}CN*3i3I{KgU7 z(75tsH+N$RI!)L#7!4_NRDv3G;q$1RwL7-ntfYImbK}HsUQ0Kt*Ao&QDVjg@Zx|Tv z$RxXn1x^FVGs&^Rl^m24$oY7GQgU)LK%q4oBsR70+^Q_;`S`v_b>Mx>Nz+h!ruEf^ z{?zE*S8JjCmM!hsQLRxZu{W>G&q7C^tp`_wnCBDD^4~?ja=rR3@Mhv%Il*3Lv{fN` zU3IB)wQbj&$$6qU<|kjBCnM+Ieg5S4wh!|cbNQ8+#)jeB+vob58WKNizLHscZuL-1 zC_4{RFw9gsuS}VK+pUva-r64vCZT3}A zlFSv;W{=LpU1pz=hR+nQlB2DCeU!>Chrj#&0?m0Z+KOerr|pd|b;Cn`dHl6V~YVUDxZc z8OXX&e}~iMxsvyT0>2qfCY38cDR%NRGx??noKC3f-yA*d+=^0kZ915GrIAvIoud_|J&n`xcH z0$x~a4X!~}uw*Zr$hP6+*Y4WkXg57#*G4ROSOR4_K&<#HAdxokqj(^bMc`NeK&3*m zJOt4s>eFWwQ3?WNq(PLZ;h!Z$>Avozxsu1ZujQn#Kv6Ds^+*+IcF4g%7 z(9c*AV%B7JjwB8RLWN2+-_N5&o(sKg48hiG?<1h5T_A5)Xe^2-6a_v*fGm+LOF?wYxMao z#vu#n$g@s?rf}j4A<}aUsWmL73q{nZL3WHGj_QKy!@#|0vJeFEDGc-h`6&YlT0oNN zfm~!gG(c3I5NizSXJljujO3~@C}!SyIMpq&BnroPBhuFf-=&}-^uF0c#OcUr^5F** zHrfZL&_Q_cZz0@Ifo@rY7bd~hSa2c$l7)aapb3*PfyI-+@zamR7-CZm(ATa{g1^1- zl@tC7CD^2poFfxh!_Zce(K6ghS_L6;QV~j*5$-UuGbN~DS0aNHX;CWlc8_EW05R!; zY-7m6yND(bpcE|G84_%xK_Z~9Jt*lDCy749HSz&y?Ohv38$+ai2(kf9J%diXXCuhT z_}oUj>lEk+07tI@KM0X-=@C~cgK%|O^du04O{$>-=^()Sr#P4mC}j;8DwO<>vgvSTFJ z2}xXlgeC`kkVrC#P3WUcMrmnV9PhCw32WfM&)8w_Q}@s&E^N#eu(Pq zr)R;rV};-!LL?^Wr0~nIPaNc6FHEo^WWb#`Tmz!}4wDbot{%wxvg=B&qO2;O+pn2h z3xrO<$bW;O{b9Okp4MZ4bnD@d(*4BlFi?%S*BHi1@Q;@82 zl-C)A3v-h@8E7}zrn|Su8ldFM{*?RPukfhX>(ePZI4vEFNS3~`8s*U*x5d>;3W1aI z8^gs_FG{0>Ar|xctSV?lgOZHo3W%3>zDnVQK~+pd*&ZbE;Bo1k?VH5UMyw+#7mrbK z%1({<^Ig6Cjz7z8UsMlKCQ^-5d2EwxhnL#WWP!`0f(+i}Mri&1gOwYsW^k#ZGORI7 zkEXMG^ViilHWjmy?gqN!ttC}0<7B9z-l}d-ubMHa^ZX!mpW2lo#%#tsMDv1k8n41=Q+)X z={kqMH=T0 z82Ej&1r6C0wtd07XG~Xn2HrMmWfl%}c--3NF+$8T(^7TQvPDml$ZLmF&T-xLs_8&x zgj#8S^>ky}L=9vO5HG~}awW$eP=M@kzP7_RkODIYoEz?YKG3PF1AW>bgVSE&=wfOE z;a#BjMgz8EptsAQm^F~;gFz<}aEJb&=>xDMg2+W?&}VGW&1mq5VJJXmC}^z19Rob& z?TomK>X?mlC^(fVMOP#B8`7jxDn{Qx#hEnu`gMHz=iV^3aCLrM9*8~#B?y7bP$Ti^ zk>XpBrObdM$)N91|IuN`$!JFuk{}8(I`rS8s=nG&+ge2hpdXqh*{73j)M~xW>UiA;`n=i3IonPD|t}^QHSvZOp%m zFz@KgarqY)qc0b?U+~(8PM#Az4Sx!0AB(w_nS3xlZPdV{6kTyshXV%Y(e+oHI=nd= zHtqthZFZRQL3U-x>&+k?h`A2roMqNrJ$j<-6eN5+dIkj(MUSOpfE!U`F7|_>j5B@q zo$Jm7>&`Pu(GKGkGm|7!+P1}C9?QO4-@jsP7 zgT50ixsyykF<#oJTRN$n)P#ZcmzRRFX1e*8HOmvqR8^I?+5k6w8b^L$_u0f1pbw^F zigfNm2$JJFms`2=j&yM)Yc6Mex*QHc%8Z>!Kc(F8RgN{T zEb*Oy{U_BfU(Qe5j;Znw|7oc%yHPGJHP7)5tQkb=`4StW`ghwQP)A758gy}GWu<-V z-O3i`C3zYDDv0!HIAA`la=~nzyixwVUiVD(my2ADScX!HSC5(%FDcv=Z35n#URI6Zgz0e#_j zt@8IrUe{75>GJ$ff^7JcHSzw$oC9LDOH$j*`#}xWjx|EXyLw2lE`NJA3VLZa9X|2v z`tM-~`IYteUoW3R+;fhyasEWi;rHh&^=8)r&#nT$uQ)%u>M@&!#mmk1lFr5QT+3FOlXUq7rDwNIi1eZL>Q%Qo1vWHRdD_SPS zQS;&EC9C-KBHxtb{|gCcg*E3lCfn3n+s0amIWVavYwb>00)77eJ1^15Q;5dV;x6`v z&@n?uwcs);ZjEgD`t$vAl%R7DN(8q4wfs#bknUELeJo|MstB^y;_~8a(Mw~xsg;7# z1THV&jMF7BmEX+S4qVQUQAz9$gwQ9Kg~d_OM<xa>^Qpr|Rmyd?(hrFgWx5ZW zbrh#gs(T)x!6%_x;!w{G;&o#vwJ790QqDxqS6 z>OPTCd_VeqG7-mpuEtUiUJP%p+8G|#h9A!%A8cVcqE%D9t>B*c{Cq*#K}9*cbXAaM zV1lON*aYWBL*3L}rom2Tzs%6gPvscJh%JzsYOLD%(_4A1;o;=#$*pIzWiu~SwO;u~ zt7>2Y++)FRhYx#1#=#K@81c`O<=9oKav>-b^N4~;+#Khcy#8E+;uSHHZxc>sjFQT6 zaiPk;3W@qM{X2$`TZ{eq*DqiHI)1cKd9A7-X6zdJCpZa?ut~~aE-B;bsq*3fT1-NE zIU-nzAmnXcL;X~tRuNtAA%Ckc({NAcHXS{O`2#zc^rn7UfeEBh`Oz-5GbwKAxc~Fl zlBwj%7cH();HeSsw_y4mQ`{>Rx6q?$(nP&Lkvf2Apa}3gY@AYs*I>6Th+JUrZB+kb z(~EMfK@}|G?jQ%D1|3wJ;JmrG1G`_WF>ODEdVQ?`0>g9 z-Y!@cTr%E0%*&pwhu{m0JVfH)sAtv^Unu%}Yb`j+3j4im!xnSAirC&}$+5gmAb;2) z-*FzNcISY3!F)J3$jsIJ%JKZUxqraNTH|GMn%_SO1yHOtIR#*@Pb0dgegTpZ_5S32 zBJkLA%5oJx^c$n_)auWT@{e@nsM3YP41JLYR$8#Y#QFQW8Y~-kbbiu)&2a}E{&fk8bBKm#bSM8`k6fM5SK|fgdiN*vIu9e{VQ_p~Zi(0MKZ?z;W-fb`IY~ z!nd&FwBx$Gn)G7TGkKK0T?G91@aZqY5(_er`P}`r2y+jDm}O_~J(*mz z;>7!h2B$$qQTQ6O;n)`h!GI3&^!56zjgtFsfW6ZCniB zQPMQbzAoToTY8}NGy75a2AVq6x1^6PTMIoY`|uHKxctj)9;%kSzN+;e-qDK@V#|X6 zhrPG_YU^+KHG>3VKqy|^ifbwE?gfflDaEZ=i?$6Ow75%fhZMKs4n<1Q;_ju;Vr}8% zci+!*<~eK4nKfr--prc$1M+5Pt(~3yy*}5aT=t&U$tpx(!KJQOuKi}~;+62C zHrXhJ;Wqn>^&n$yTQU8;G5DEY6;U;+=Bc7C+in(J z!kleO*eeanC7oVNyW~;;uRX2AZ0W9Zg)|l}1r1R8gM&>L%ZZ{n6LBQAVlOeKPR9aa zpomQoE?H*@n1 zr!~e;#r&lWIiY;-iQD*J;5c&e$Y+E6w*Ri71Ngst0G*CJZ*)e=HYl|5|)@8O1 zC7l=u`DQJBIXrXo^>I=#AR0a+KJ~HCQ;V?L*(uR(+UZyoD^TK*9;MB~d-Jd=x)RE? zxH*!beQZr5SC*_r&83#eC~@M=^!r_F>d+ol)2dH@U9WBwm%p=K)jThFc5C-+<;E_|!$75&#m}_M==ir@yLoC5wJeW|+(fSO=rpU4$M&a1nK)$t(aF{cpSuTt z_06TFiHpS#Y^$Vdo-hWiD4LnXCXx%5&*!&364vd^sJO~-b!q9J<6Hd2aYDBF;{Hg> z_f9R(OK}CuC_ui9$#2Lvh^UGkq4~Y9*W8_xm6X1!ODXl_(NP2`aH?(HQQr6J!O|#_ zzG9Q2t2fcud1o`iw?y&b07;7Ir26h!($a=mPCN zo;B0+psVW(IBWd_);5o>hDhF24E=Sv z8y3L@i2z*V(*+JEo{-$m*poS=?DZCyjX3`{qqA(Qz5WI^FD}a=7QXOMj)Nngbx`JmuAP=CP` zHV->ML9t)KJ66#~QRz>g3Qfg)R^x?2?HU&%{daFqz5JY4i`KDtYmdCDqEMPxcz${$ zp#q=&PyU}5q)+ubrMw4ra0dEFl*lF1^n{eYP(~ewgz0S)6?8Y6kScpq4O$B+^HdG! zvJ4cQCFfa%KF1w=nLNmyJm}=oX#;CF>sJaBS27fe;%XRt!41#{4S5DqxzNb#eQYhV z3Mm4pc;PBJg$`LOs<@EC^Ejj4;12p^tLV@Sy~`f(CmqgT2Xk=KqvDkiq{{l&;$ft{ zL7~HQ!;vqMUX?;t-eTN;QiO&7&;b>* zmB#-;5!PDuMbT_ZvAm~UoqvB{UmUGX zc6Hs~1Mt|_5xC?I7>e*w**bSarPC`apZ~qQOndkC zE`i8K%nCK8#MA~4g~AlU>MaT!r)jK%#UI}P?W4yfx#|W#tO4vCSy~FGfr9@au<>=} znQT;8=S}!MjwLqMr%HRt)Z+u*M4EFX>%?O}QUtG4n}dt5ddch1VTs@9;rBRfiod2= zJ!pl7iD15c#Fp;rSJa!UQ%3#d=b>ku^2UMkR;zISn2Gh{Y^CUNufGQ zpiW!&=eW!y6rT9B@;}~7=`%hozV3Unn-J}SWlpoRA1@GI6GJ?1y)G!)FGcwAg91&i z>0NkKSm;Mab>sD&Q`H`sTy$`(jScfh-@(7dwn>mymPfB5hS@kDB+Kf*WRY@|Q!TKi z^07j4QhP=!G}XOxEZV`HX44dD()~~rSYVur1+bV%(5x9}VxjgMCmF3v@P&=BW;%}8 z3*rKb%MxkH)CP>A9w6@|UJAS&N#O+`vcQWw@~ewL`(u9ZZJR=-W`}!iCC|7Z3%@;y zX9u4{LCN6~nx*uWCK_+my>k9+vB@^pX$AE@iv&s`m3mC%gR)6-M$DNNT1CHr#f4s5 zl$R-i#U^9J>(vag%isz+c&ShN1p|$ z7nOh4EJ(I~s3CIwn1U^(fL{7gp@{Q>QzFdiDH+pT+3H1!r9mEbOND%4K~l9C(Ak8i zVzkv%s4P3s2Fugf;5~020qYY-(=K(gl!@1oZ-AUBdOZt+;+G%eW4Uc2_CO=1mvyPM zbau>K9TU3~L`FZW98@YLg5nJuj5k7{rs$=)y35AOzdZz28fNqNOQ}TGo*`~NW8YTK zQ!!GvYWD~Y^9}6gmVRKhCltNBD|pp95zFgc3SH`6XlknE0bm-d79Q9F6mBR^`23;K z)Gb-5T4R*N$wOQS%UnULQY%_gC5}YX&f0dV6p3gG}apOMg0e0cJ^&Ie2Sup=u#Ue?6AGeQweh~eF;6kK} zBut$**?j?uOPRk)TM~tz7DM;@dPo*S2fVEUi@tq@3PfO_i#FO zt1g#|c2_Owb~;x2brL~yBoxP=Gi%o|-)|IY=fL4<72Z(M$h~L5);iote!kv&v{5L`O)h%zN+z*_mOjr*t|@%g4ey4GhmhKu$!Y2`3t0O2+p-z--d@_7beC?*^upM=}v zac2Xfk!F83DThP{9#8y;QwbzQowW>0&_&An8b`O^FPRA{PsBWT$=>0QxTay+h)MsJ zO@&JD`}|5f+?=18>Yag8P3rVkLVL%iM1&v9uFgeKJ?474i;qbWBg3zJ%Z{^CKBy3S zmVXG`>^f^3X4HNCF@WaKuo3!8WD8&qLRN`t4w z&|ddd$8(y~@S*GRtX$uWh>q{?@Hy5SExqITa(=}6_)a{g_b`rsv6Jo7GDc5mK8^wIDWhK{>b=(^o{%nbkbN@~SJW*b}}a#Ra> z-`D;wFm3YgnnXnA@g=rmG0z!v1Zwj~|T)Y(gjak#8`2dN3yl;sYn(ybk844Cw=S?BIKtrpn}g z4XT=VpDlg=B;A9BGDJQ-*aiUQ6%AFr4t{*?9<&Z7Z?=7_tg$YFK%M#BUIp|}c*v!P z%KL(2y2GrH!5aJS+U_1YWzQK5xqc);yQacPh9It#5uTzE-o_DcR3p5sKt7@o&2ZSe z>j(rTGMF7{41k9FB9ZCHs1{@l2wHZJK!y$>%lIRcjU!WAOcGuzC98C9_mRdpSu1COpTj&_j6b3sJ6rAK$PM0YMkyC8rqzW6@f z`27ws1HLh%=`rKTn2DAc%tkR(#aEj@c23oII3>0{j9V%kHs=O0_e3Oa z-#G5TH}23l7~PHA?jF1=`hisxhB1=9a0t%b3!ZlW@OKz?PZ@tF8V^v5#{lZ%{NYOx z9xuYBC>7<=n=iZg18*q;C>K1;(m${nhpLn%Sc!%o&A%romxEKimwJO3ity!5OQ7=u z^Xw5y|t-S6TtEcnZ?dvcd27{g)w<-sHTurXBV#g(t!uzl&pyS0cU za>Innv@luGkABe2g_xg%D&n|`oi6x37J>rV!%XUcsDT|k!kfrhGx zp9*F?RY(<4)OsV5pk`eArHGp%2cTZOOO^ee9W~qy@?JRm9Hw4YMOE?JS(ZL@^D7;dI0&@qxk}(d7f~PYdRv+6a_de7|jfIrzhT1uW zet~#=y)D^gEpPHKU>Zt!r&@x?S%NbPaX=S?%TNV3wHX8ja$_?7; z9^hq_=6B{-mKM+w?$^{j(&|htdi$#`-`R^%t(8B$qBOdd&o4Ntvarg`&UCx^!x5(? zwU-wFoL`zd?%&R7+}u{#?9|@W|HfU3x}DoTFdIMXdqoFZSqW!LyJLGA|GizoS1!*l z^Zw{X^ip(iOngezLB~t6hA$GIw1-lMju3GS_+;r_w`M`QQxSywoq@Y8JzO0LW3MI3 z-^Z9FWZLKOUwsPPZOwzWN#Hl_+6O2<^slG(BBZhNFipgj?0mC_dsW)~z$lz$*c~{nuhuwr9WF&`>W=joy8qUK{o|y2tOaX}Zu4Y6FlFyW)d(frBrz1G}b>F3Xsc z`^dhlK{s=Vw>c!W4D6dd*|FSTW{bwYXW)u||TVy^uXB=CSJzAb^{`sY(TQ_jvu|z=i?dO)+Ed?8mD3@yD`@!e4qp zM+O4MY|X+#q?U6wcVB*70+vl75ZBP&*6@BXk|4e5mzsC6iZ=$IN*NRtnC};!&zd}X z4?pgq&u)UXl)A)&oJFUa-Jxi!DZEcepv4r9RJNz+c+fB?5HL;3gZwQKl-7+$@p*!V zph3jJ{Y>TI-8vD;muV;niP2H+(a1nuk=?RTOak+mVMgFy3d%02Y@&)dErvr&ff6u7s=W zgsbt3*|Brtu@eP6sQ1HoD252{l_?yp`O1~*>iZl-fJIQ9)HkaVFfYwQu&b{A3d7y; z%)4tS3L`08Svc+{Oyq%$xh~&UudOn`GA!2Yb7smv&3(<8CUl)x`n!m#o_q6m<-rMJ zOKSD~r$*xJ)x#5plecJ@PqSS)Q{86^7XZS+Pei}h32&`7+23ulO)RhT6a6|Pz@l5} zD_`3EgSp}moy>J`EYk7QisZ_YsXH|H;f7-Fq-xXTAM=MTJUU0!41>q3TU1lre`k-o zi7pUp9H)e=HJc`#n}4N<{&W-C|6TlHI=?%PA1IrRLjdb$nE53&XKk@2KmhILp9&HU zqOAr8>TCyU+Z+F~uKbA6Pcl5M+31P~x!m*bc;68i^1{p}cFb0HOeU7C+-AZTwjL7} zV-kw4qHEF8%Sk+&>rBi{r8k>&)z}# zEr^mVmd)R7CeR&Q-0l3bnyHGPfxerFqy_JpPsPzLVtRmIEjPzk*4AZ-fc!J~w6#*7 zCLGNmE@y|trw-F&eN~M6%u-*V!ADyo8?EkBm>t_M{u5K}<38R4&d$wVS)yO?b!_RW zg!uh--kF~an*&;#rk0y?rv!_HTivLcuYYUdbd_par*$U|HDjL-?zBT(kHDU@r#w4d zT08h%%hxsEIVYDJWr^0}Ap)K2Kkf^Gxl>gaEV0mYz6X$n#1XwaZDpzxw zt#B#V<`W(r@nx^F{QYsfQVtyk;jS(Gbo;aU26IXuW!PYzfeLy04dqD1v{D;$5zYUo-Dq zW4^nH`F=65a$XO(#E*r@#Y4`u_by$(C)8XfS}p_E&tKBXC_eu&WQE&`xbmz0QI_P0 zCcf6Ttb>#R=d~^`FtHW)@9dV#V>xRwuTI8k|47#o-Rc0U&%Rr|hhhq}AgS*$(nQ05 zFM4yoM?e3QBz4=zaiu_4xqDxIs~i}fg?_0+OO2*Kuam*#1o1(u3-#SZji_tRQvzH@ z*mX7094{=JA8y?F`+SlJAOM|{HEtGqG4eW^f#(gd!*6Df*Si1hZx+jJ-{~xV|6}8o zwiIV0{=_~_LWxv8)-*j%3ygg7@uFtt6W7)3R+o%CZ1J}kI^e54*1zchOiQjrE9ak< z+~L>qyFa=EnFdFOn3mi-AXIo~M8hTc?`TRqgM@!0gZ9_b$>a~%WXQHp`*CF!#6YLk zzLtblZo?{2;|mlNr43nA-_vRKb&Q{8Ef*gq>7M=5*~&=2rhDn&pwj!e_zI0Yr-Y zRWG%zLr4=tnF+}aA951aVDEFHYOzDhL1+pnZcrdpG_7!e z41U7&iWi49f!BDthCfq7Oi6o)$(oSk`90ZSwzsn*>+@j3T>(~Jx7NuG`;aJo>wNx_ zwtJ__T5@y(_9pa+y#8jk3gxQ~?)l_h8fSw(!OCa{WnYaR>_mMhUhWh<^`2s~ZI<)h zJt%Z|8$tkW31+8?94xk?g+3u=)w+g%b{wGxMnyXo?-DtG7TN2#C~r}1aSqm#vlaiT zPL8LLJTqI#Tc~~Y$k_baz0eMP^!bV8+bfPy{5EU8inFwlIgJz(Z2?#jEs1n^@s~#t zox=_SlgnO5wL_L(uUeJ4#un8g5<=l_UhC`(W~h$WX?vnhg~$(y-iISv0oqJcv0Fd#tZSs;%2=M!aoTnx3~hXh%nt6Zd+R!4%6* zt}UoY3BmRw7VGUk+KDGVNTvTJ-7jP6Rd!vC7VJV!bKHSk54iG6@ljvyb3wVN-f#>3 z>G`ucwmO4E8~duTAE&93MFSB;vGH3p)UywPdapi|D%x^3eo^86yZM2E3#i)@W;pwF`jsLV|(Xa{GXNM80>WJ{t7HUGVLIvh+rsRTq8a?L% zJ9UFMGg)hr>Vk>as1J)gsU^&GHp8lQi33XXf}}QVUvWo38;5SiI*enfYIRa-*c7=7 zMRBWMi9?KAnG2Ex#k>(>?!sU5OG)=cdz5ItY&?E-+raYp>LAXl5wm>PA>nK*i}%kY z$pFG_^61X9rA89Nfi2$%pz`dr;@|y1T4nErr|H9`zn02`St+urPJl8lNGnm>tXzH- zuTPoZCruSZ#^F7P_uaEBI#XneZf40_sX`MDmP!m*6~6lOu|HmZ@2h`~b(v ze8)*DUoSGdmA%`?6F6AFUI!SrIb?co0uYkyb?Yy3QdMm$4)C`oS4~m8=Q7=>RlnAV zuiWqFP)*EzVUpXA3>JD(Op#^g_b#iOQPyM}JJ0k? z8Npj*-Nce*ug>4KLwTcZ3V@U;Vi_=q;Jj}a5(rL9G6cx5R}M+z!ObHj?ZrukhpRL_ z-?8dX>mdqARLT{xl&2$ps&BSV0S7oB@yJ%)`PiD}0X`O~=?cNiT&K3uS1F}-v~+zS z&8;8X>o9>_&hm*;I1rJ?lci^6m~KL9vUvrM|fwEQ+0dj zLpxDi0~(-!?eYWKfNAkIjM5=` zL_>-FDW5DscSjV|xQDVEGgj~X5i8`)K(72s8LM*&yDn)17b8HR6?Km^4-5jP@+)Kc z--QXC$%6u?@Tj^0Z_jS~4@-#%)xWjzWMuv2%vZ*dDp(iMewo|&l9i=iM6FWf{gG74 z8IBf6Iz6i?Qb79X1%cfZUVsBG6*|ODHM}f69omhX!xg3C*Y?UCi+>#$HWS9KisLet zCg~eShxwl}mL|F%hV6?VfWQ`INAReIXrQr-t=d2rUH1VkFQB~q&p!EoqzYz$Xc>2> z91(+q!QZG`{4@&F7@$X>PnTL+LSJFx1%Yb|zLjb)R5tXHw=`-&*uWPc z;VUkjj=*;4bD|8VJqvzm6+T@k$-W+hogU(Z2Eu$pgcb40K_QL`gR%}dy6!lP?1&L) z+uc}ydW)1=Uv2-bqFzx2Lp-_s3z}BvROXjTj0vg6$peC+gQmyXW)1kl?g(xMyyt%g z@*KjQtb(AjAsnJX*w?r=-2=+qfO~bTaC??0I|n=~R0y9a77IJTNLJB)3h&MOAhs-? zgT9bD2v^VwXvrV`epvzqk8LCoR)dN(XGs;5@#YlCPP2bf(jA!gO>W*CVoVf9bmW>T z;?ub!32=tRLnd27$a z@z;ry?TOQ$6W_C`x%wuCyctCJCofnaQYdUF5{o|`r$Y4U1vfy%D&&I=HX%EJ&mBkH zJ%nr>Ak6<%ia&}34Z!dvlSCl7}X~pLvE8E`C=beMi$Sm3~hy?DR9RlClxmo z4Y#$zvrnIacn%hWx~vdDn{}BEmspZ*(liE$p-s;<=ozEOGZ(K=9a<()o&pI$h+Ucf z5^BWREJ{MDk)`LWCfPI0?{`i#xVTJWa9LKbSoj%mZYX)Sm@>8iz?yCxWnrr+^mFze zG-v9hFX*}I?+c{SygI5Md4rGu_t0<4z zS9d+cM7n*LWB&KXVKZ<2n$}_{GE$FJP?yWCRzm5C5mE|NlP^^Z%Sx z>wm(-?EUu`D*~Sv6Jw=tyWT*u{b!6dUWNB&JK4zXW+&bL9~8#t^kxqg!F#)3l;(DO zP*z%Vdsx+cdV7Q(;{AQxFz@#Jq-77o!*pDo{>Jbye1FdRDgNPM*lIC6jL7%@uw{HT zdi57$%c%W(x$N`(??1MTyX)<=S9dr6*fMU9o4?=vJ{#h@|Hqbb|Mz;Y_8(iucMOpQ zLjmwryRjdhAwZfaY)tYSPy7s%{6_s_%YZ;QD8`0SK&qr3TX(Dw+T(RRD2Y5#Fgo-h z&Bk*b2YK>vov=U;%wp$So^mrR{Bcn}$kmvFc2_5YWBY~qJ>pt{fmZ?PE?`X@i&Si$ z;-@H9RfK1wLOE9%iHoORkSuQYnzL9l$e|E&$?-^%RQG5nxqJ%fgV50UgfIt1C`3b- zm^EDh=|Q6b=JOzCwfPa__w^IiGvYan{#HLZf1`90`)i@&*aLlqkcTqG?ABAP z6@XApJ{zk_mQQEILa;=urM!$%%oulh1c*OKaO8cQsVlZCROzTSP4y#-eOVE!TTT1n zWnxkacvo0LP|L}hmux4-o?wIHsUIOOGG2F2{K=PlZEHi`u%A`-l2Eu#P+~nGj&k3+ zZA#n6v?$-lA)6fRq!VV?kX=r>r!;*-p)B+@pX7#}hX7wY)QvQoO3G0UTA^oru9SBY zxUWL&qZ8Yd9FG0sKud#tA_qH>5B8T`m5fOrpqO05+F1Tn*WpWXuWqTt36wLcZ8B7c z3=mCYE;f0fPwLrN`2^RQ_4|Xbm3QmdIIT_+A1VwyOZ2N~1G&u880TA0fh9^(m8R5( zlTE=%Wa?G}=8q{CdUzEGv-r7L03Xvd$_#1)a_kJTC?+jP-=IAap)W)j@%u78DXNP! zn8y8shOK97*Bh#=@S%|t4~3Jmfc?fw8V1An6|allC$U)*K#iven*eohtMx3L(xxG^ zO-jF*H#RvU)(Od*LK>@H?Twn09I{f_<~;J0SpwRV)?|CS_qq2hnNQlybwoDSSn}%5 zooGJ;qZAKC%#Ich&zqpRjojMLM_2hT>!C3^%g=u}8_#C?bXWmH?XG^OISZa166ud5-Inesc;qjPZnj!-GaMwQ_e&-0(Dh!v1)f8Wk`8e(H?8OPQ>LEz@x5SrA_$959G z7pKDCU@gNf#n^+E7HXP&$=Ky*?H0=;9+jpKshu)swlD8X`-J8Q7zt-x7yUk3=Pg;@ z?9=lbW_$hEc(LkL$YE`Wyf9zPe8)6TvqXsG>VDS;&~9r*Yj$AG-h+1@GuSlDW7bU{ z)h|Rw{mm}F3B`zd1qFVwAzci!xS#VF_;F=$v6{7xXW^rv<+g2uLXUY~ats~0p7};) zXM3_EJ{x3iXYn!jiFeWK58S%@-TldWUUMZt-md@WhI(7*Pm5fho1*sP!hxav;BX_$ zEQLDyblTGBDmo!`o@l1fKh-F`&#ZBZ)BznD~FKlQH*27AAg zAbC#s>bEWbne*ju!Anb<&Z|!$2o>Oia9(dFHk>0yeM#ufIygw)GFNMU;~+q@YbYsc zSGZVg{kQf7jF*ZGk=K!spnL7Byz-N5RupbD>3`FD_bX*ca?R`24-dLNf=t%)wILqA z^tAf5T9JLeREFCT=+_^sAK30!2C@Sd^E!y#eE$sCe!uX&Z7t}>w_k3jzvrBMb^c3* zaa+sn_YT|E{k;)D6{Y(~#qAhhdnHZon~Dcs%6nNMkDq%8YQs18Y;K9oKJV?lC>`9~ z5Ds@& zw1k~|MR6Jgi~M@?(l^Ya8xiFYm17+Ey)X(m?_Ld3To5tlFqS7Si_F@WZZX#V)c7ix z%_pVoRnPU?i)S%-v(bsF3Q*%n;|2H6s-fBJF|4HCh&Q$@Mz0Exk;1C%B@Wv=xR@@{NNmD_HAFa}gcMnkmcTCj;n&Z|lrqmbU!OCTM3R;S z?13mAUG_t+I#sh!Q^=2O|j1bx059h-Wb~^AcJkmeq3>0z3qt*+~VU^?J|2!o^t!?8bzk`Z4lkXKh_2LmYUeKi~zk!VPDm9(wd-zsnB+J$62+U z=E$s8zmSf5M^6hxKsQx(uU|G5ORSgA>p{%9FFIS~!WXD(gB_Fw>;}!K?))#Z6 z)bn*pick$j8i%>PjPeAmd5@X1#YEv%CIFO<0}xPX zszb4&%8+(B&QW=1rQhr)gIjyPgCTRgxLw1gTX=!<>!+a+4va~d_ z0_S4|5KRQuEqktxN^F4k=r}fu!>~V=&5cxoZ}X6b4mP7D>bv=|>-hbL`I&9yBb@ND z+ww_{3ZNBkE<-h*I`oMX{It8G$`nw&RI%WM#>Ik)bHdk`3L8xTMLIbtyQTd8DDkCg zsA*QxQVrFu+>gwB3R{||nTD^UYTH|F0>t5^>hL9TG`|M=H-9}Qx(vKWRlhjQTe?B7 zh}HC3x%Y7}Hdtd@MdsufMR>xvi>sXvU8d+C&l{0miC*TCfrLN}> zsJ4o(26Mr%<)C7}^T@u{E6e7D;S~lS60W+#gVY_n5Dj!(*|hr&PbF%9w!zL1%EvS7 z>`M!{1E6SkxHYs1JE0}U8U2{L5+|x@bu@44ww~`{*)M(!571QWRKKnR#nB}Qg4A4R z*c?PcXeydZ%H4I3nt|&?DneR_BSFA|k8yOdm<0SM15EI!(c*V|XLR-Y6hvqgQomGv zpblRUL(Lvm;ON!^`H6ttgkBnLO^$7<;#L0Ne5-%Ajc~RH-8<)Tj)MNGp>VL;K4i5- zQ#T!RHBFh7HON9?TqS=GN>S)y?2Y2ErB*bg5-8VXDPB3pRkQH>ePU7Dp-Ez&oNxBS zVtx|Dr5OB=SoKUL8dTYGlGPLATz||D?Y8Rp!m0NBXQ{wLH13Z^A?kWO>Sk;#7#h)( znAwnvk4TN`rjDTDAeCnpZ|BD8$zQ4*t87OdwctdzaE>=BjrZaRpg@_r4C5V>M~&DU z?MmkGW~&Aot{TDPZ2gKhk!2e3@jj`*Mw}n@r4LcZQxNW|UXLRJcjx-gM}t6tdQmg@ zJnq0R0O7h-Jy>Jlpq)sartF(v7EVwB_KN~-jW<^J%Sb-v7F)?4EC}?GX1$OZpafGu zk%fby!_kP5+1nOFP54k|I}qJo>tAir-WdxW0=l;l2ILut!?E^*empdoA~ub6Y0q@e zlF{hJ4uXn&Yc1;_vWafN?g0a_2t6u0u{TC{p#yoE{oN9u)grabmS;zzfb)ia<^{W8F3w~(D?)dIllhK0sN69d23CJMUoyDI3Annc?u0?B?g8Tz*`1)C@#BukMxDZP0MyG0E>t}NHiKqV z^(#w#VLa&qW)>5hMF>gS8&S#v7Xk}SJ8_mAqmD42ngq*@2>(tE^lqtvLCfLKqrXkA z^G|0=j^hw_VYTIiO7!L7C*lji{qBOQ1l3Qyt_ zk!U~*XcT2??w2Z_fXkA9H8N$AV<1`$PjQ*X!6Jm`Ok>Nb*sMFEGjl4~FfT*>75=BOAjlS|NastG^S93hl~mg)c!x~D6&7Pcgb z_RRpj?m%fB_(!d2fE2X)p1V3xtGgb*c1~56STd_e%H+sw`EOu7rd$&x(T_dtIB`5$ zw!RWwNwkW>W0HltNDbVgX6&NBa7qQx8Ao=y4tGnT(5O}Mzw=-&=n!hWbCE=B4 z9l)Nib1QQ+xl34_S$KXPXis->=i)OWxwDjVT zd$;^)JYHx)A?Id-IpDB*nmtm*+yZ`~bKTUz$L;Qaumo5{?1 zHaHGn5XZxPLHPatEu5O*3q{#Us< zvytCc$1I-?UumPv#n*~gz}@4G_yUj$G~~K^cIEbKb6U5;sw_08y=v+J_r-DS@68-3 zxUu^Yc}+dxu4CBBGL8U5pRoB(0+NV^D1JBE{|^!s+TgHR8B!s_`j!2L9iMB=_&uEd(NKojhtc|cddxz>)39< zkHNsx%KMmVR68UHfp>8-TCWcOzUugQbs4n|&U6Q->3|g9V+zN$AKlL7zGWu4PFaO1 z!g%3j@FN_7Y3h#Ef#n}K8{gMHU5vE%_uPFihX2I*IHtJ^M#)0PwMP>zh66j#hg+2* zG*muIK@%C^qudu!5|C;Ja6JGrv-@i|y5n2Mmz$W$Etg9tzK;&tI<1vCCT8%}iSwXj z-D3WU4{`8wDNJP=?4Z5IU6}(N%}Xh1oRd5)COCR9cIn-)FZupA3j5>O z2Q++@027~4!7|*?884LN%HnH7^WR@L6aHS#EM9bhx9Z%~zt%uCT;m9w00p2q{P3;& zV_;d%73S(5-~aDCjDCedwI!K48qtl7g81vH9+H*^8Gp`I z$}&7LZF03`nziGmP_rB~CZ7sVGnTU+T)qR+7@t}7hGB&em;q8=493#RgpUhnNa@l* zboPHl&es(IkKc0mGM-~zK4|4B=a~L-nyaRLTDN>`24!r$clQwOg__g_hicP&QBrAm zK0gpkuaawi>5`dH zmrTdTm}nMPHNTAk3Mi2o*?d%@D9i+q2Q;jsqB(exI0`lm;6Xe-B$hjpo10^upor9e zfGYFc>g7iY3=gBuQCf5^BnZ(9!%=Mb7!gY-?HJzt(tj#A-Dj$tG5W+^ULD3;5&BqL zY_F(ZJ3p8MM5U&U-tH6U@3zUtj*)YWdXbo49D_0rpTf>ar{UgDpx4v0)=@d>$M7&B zI}P1zdQN@8^j{c4a0nOJK{0$~>?nLbLv}!PPW*m@q1mf}Cq`f2p>R{4*?DYXL)fi0 zh}ibn5#&?s$Pti5UYM|{V`&OEhh3%^9=UP)Mr_8*bdN{l&#l1WRH>P|iKegTZJRB8 zUaOZ-*)hCrwhVwm{)fS;4HhHTyZ?2aHPrXN>a2Ga|It~G{}-LLy~_WlvzGivXZ`vg zowdxrb=FnJ_5S}1R{N{OrsPy9MVZs+LuSFyQ#2FbkvM#kR`RdXs?`%Zjl#vRZZknsT@qRVi4#Sh)~0Sw2#tE z1EAMc9}r%zhq0_MGKP^ECPN;Sf5o-da$DF&(u3YGZiF&ar-PJQV^ou<;}-M_v|1U; z`lGlF`?p*k3{Wy@#Vs4p#0%w@F@KO!?`Mf8rV^Wp5PML*od7-^-d5C92kj`hnX8c` z3Jw_W#1K|2*d{@%!QIjDl;P)^FEB>ENTP~^M+$E0lqdzIOO|3yn+ejbkeHt%TSOGF zBK8mVg8B{_f)k<~npslDqlFIyM-Ng7!+agp-D1?8o~kOETJh%j-xdoxwS9;?`z9bUJ<`MdnxM1_rYBW{lK^rN4`2JvW+^1^9l8NZ_Q(?5hZwMxL} zLiQgIAD#1+lB=hj^^oMS&t%V3n8o)w+a2vT;qEYB<|)eRM#MYAe_WB1>#*4|Z;G7Yf&U~3#a^5lL2C#?c! zuN*)!(LGFBtCVu7GU;Qi5Ail?Lc4>;Pnuci2zgb5z9<@XBB{N>oW+XE@FO-`?Hi?X za_x_X4b5)zD@4T75(lxYN#i~AZ}$Ui5>#0J$cKDri1{(N#a4STww7{hLY{IPc!qgj zKc&)Y|1|vs`1S+5Q<~@H$D0tW?}17T6?|{U&mKRK`qeC<@#hZ-W9mf={)6M4$wxCY z5G<&>WVlPMWlt9JJlp;gd;WI>F^#$)?2Y8%iE9wdT=^$%oy_kM4JNk*TqR8h_}E8y z2%C#4_EAdr2mMz;xSC2h&I{f7s-bVWjxF)-Ux+GF`MWbn9KXO3F=oc*MF)fY@+Uc& z23|ADy)_tLgKDtHvxL72`L)DA!Pwh-1x#S-?`0wmv6s2itc?zo$WnGJ;4T zNvSTKliN-pKt~b;vQO{#;&2ab7s9?7fBO5{BhqsjMek-jOttxu zk-0Oo_c)3Aokf;iOgN~>Q-C?5L{FDa}NG$vMjh+OX+vIebQ8sksE)K~{ zma3Q5s#u~Hv#r4?Ui6NFc^CHsxW?l4G?{cU_sQ>4I93H=>O1~NPYPSKVyjC%Is8_I z-g`cgNhML(!;SoN+8j@cHxRQWsVbSIb}#RuT%K^Nr^+AnfWzn9EATFG7)PsM0_9R* zj3>oTFs8=(f)h7ShC^SGb!pPaGCrn*JCDb?Q8(_?i)rO{bU)O3@+SdnKEEUf#NHFF zbGxmx6>uQI$1)QUA5#J9O1Rn>=FAP^4MO#URdlEf}vEuikI1*gs zf$*;-fpObT$cFhL1(v@a+I&(!eD(f@YyFos#V1ewXh^>J?2%>Sd*InCxnNzum9mco zHWr?|P|ODQpG^uj532ptha2SE)zGzCNj1Pw(2MFd1qEKGRb z=X+njnRU+0eACuCXBPYctN_=&_qF%FepW#q@s0)P&u?+Ssglg^+)F(Yuhj@rM;NBC z0(1{^!7k|t94N^8Fi=R86e{H{9g^A0`d$6dwc-=)$U`Zx+R;y#N{I&rqSf7NZ^CoKnI@K=Sijq4aYj6PEQL5TSM;W9X^t& z=;{38R$VwLE%+=-)9Yn9GMQZbaV_5X@C>VM6a5=3#Krp(3KJ4yR1^B91%T zq-zjXi}l!$Eb%V5dp%jVa}K)KPYGT-8z1!YMPUDd$71pCeh%p~y5lSq>A|?fS(q`FH79jDLZa+j_`E+nYwEGAiG^) z!2O@A6RLRi6nzGCxm z3HKKVXc_XS2m44PX*J$>==mp`NXE`QxBBPZwV*g0{qPW@)x~E+Ipb#!r`uN-n&i9d z@3ekfa(yT0b*>GEXeaUC|N7B-dNbpKZja2Tn7j@nR1HI;db4#WX7A?mF82EnzgS~n zqf`5WUuQe^B<~G&XEY)1+osEL|BKPy;zu4GDTR6vJDUr?w>8 z^az;-(1f2Ae&5Ju5}Cu^af0ps4;W`o?o?fTwPSep{!Y%0!)E2#AMBe!07pPG+W+eg zS1tMqNW!K-_u`aXjPE%=@#HAp)3J<~UcYsDKcit#x!`U%o)gHt6uCq{1Gq=yX4p!d zc^TJ`A6NS|-uv9upXyNgfh*rDqg9g$LVCPyV}UIG5VRhil>@JO2C{wzP>2mwe+j8% z!`GgUT5E~5I~VmBcV56T0w{$#?8w`|9t+weND$&LrNC8){-An}WL>!bRQMhC2$wbl zRo#sPmq+A3%D$wx4>uKd z;yiW}%>=BH$2jvboL~TFmO7l0le;vYbKB#F7BBn{G7JkK3@8S){(mi{`x4VNk#xH4 z;=c%TS;KY}OW9WC!?|*Qkzp!Mq^X^08L8f?*eAn4lIY<=!xYt&zp`J<%gnOAMliEq zPTjRDwM>d>X0jl)S_9`G``IsuzV+E5f&J{4>2zNxGyCO!*vp3COU&#S@}=d8Usi4E zqqNu^;j<&Cw=Y~>*QLE8s&g0m3$)B~3zf2HXaq#j!uWLK>NEDVcMpuzIl9NqWrR2N zMVddR9Z@rJ$S%0hGt(Ln#+m-ZH~*TY^5aB~BcE{#A=l4XKbk!sKJv7r^3>pp%?k@?9ex)Rh~Y&Zz&`334cKid-=rHwot{kXm;zTgs-aZlwac#psAX% zECv~hlm4ZuP0Zgv7hB}pf@5#DmMXcf>`I@X2|kovt)nQRSjBd4SE0J7f6vlhust*)b%}yUhBl%8}@0T+;KVI%6IRabHiF*lkcOAcMr}# zW(jS!c3NPwenx9Sb_Ry&@iuK-4pwocMFQ0PF4VSH35VX>I{h=aTkw3R9ZJ_T5NUmi888;6Q8e-ep_<2=N5b;XmKp-U0%Z6_vI_z+`9pkj5?v^{9Eg% zR=w`-@4C3OBi`5B8(;d!%%i@v9`f+hY#6nFQMaWjXbU)QeInJ9D}DTrJ96WjV55C{AKi2CQh zDvr?rYR^+R;z%v&Nr6lK8Phb*FjVCfR9!P~C>z{|J$B05Nzn5o&+J2-Dn`@Q^B<1r z|KndZd#OFA(r~})H3@90vQ4&PuBD|m2GA?bs`p`!=+l)aJ5t3&zI-@Uiyf?SJIt@* zSR1rBba3^n@=Sa5XJ_NP&s1F>;#n@;8`iC0^u&IT-xfjEFSa>`%e?3FA@j*xw4A## z5>q?wdXdA}`6Bb$oAusNHm!_}uv;7jmPhGxy8G zU)jTx#Xf339$h63(^Kpe_5`ZNWdLQ9Nm^_=j<%AV6lrn-!Z3mzz?+vSK@f;?%;ZBA zCQ1NyWBeD0LSfpH=Vk8@z0Bm3UwEaolTlu#Iw15SN#I?yx5=?}dT9cB*E}l&m8a*E z;D*+x7}=y(EoFl>`DBuhyW+~P(`=_b6kPn;-x3XDzq?;Qld3O!&F>J0XKrBnwC^o2 zW!0zXOrAyM)eDl>&gF)$$N1&M1-8G z#mzrU(wWijfvI&;4Y8_^IeOt5bufFp23Xo2qg9UFNK@^sRmN(y)2yxgSZ=xkv_{nt z8XYs8_M^%!)_4m#nAlCg9KCG!URsbNu}=vkWB*>)2!R1YYSB3nTuAH~P!_CgzbOsI zVT{!^MG_jDP`W+!W*<*Y!qgoc$3Sd(qI*)A7uy-#-Mr(BFhk^HvRnVi3<7V$MK0@3 z;C(Q)07A6SW*hU=>;1F=8cAbE!>UA2aaHHi$7oW(3U!^H{85sAZo;bLz+jOti$cUYFLeCk8hO=w9ijulCgW)|; zCA>SZiNGe?RszVv8%RfQ>iBE$pe)(|k|D_BX|+$pGZ?pq*gS!Y0_cl*WEQB`{88Nq z2EQhYDYVVwpslM1VFwNt*s~l18gECf~o`& zS5ML{li^E8a2Sb@t1YmoRds|8iG&mRFEg)9~QmG-BI%nMz zcFqK9IJX@0J3?iDjA!LLR8R6V_KNMi@`vOZUsN}}fS2+Ai8_yLLh{vW})=3td=^-OV( zc!8icyaWUQ%b8*Dv;$0m#54FR6G>#NJcmkwB|A3`0Bs!uH`gLb4zm=mp4O3e~cf3vxB_>ZeDR!v9^{l(^1XpkAs zQw`YPJwA7$NH;Wa+k%6qVJicxb9Rj7Y}AV z=KicEa>yazRnd877T>ha$}6VGXJ0XdJXO9n){~q_KJqsdW7z`eL{~ z=%#n7ks|wihU`0(r{EK5r&%!*oz=2TyWbVYH*D-2E%Rvl0ZUmP>#~we79Y<2W{WS; zFaLal(5ss|=>gtFVRii}P?e3qS1_*RB`UA`=! z-5eq!rO)PBo>SQUPBtfC9TgbRj*XS%kt_TDwz@`TFNVS;8o?=3Tl2QTH?2168l>*- z;EV)MaZ9ukwMJ%Qf#==~QKq4)#!}**{v$|mT}R-Q66wX+TX!2~kX9vpbFm^pEhBe` zmF?kYyCr#=(>qi<9{57u$h@8S4-kDdA9Bg|T3?ZR^I~iekXNK>q*rb@rrN_XIdT~E z+!dhKOAQKFZ{04k1`Z&ukaP}zHiT<}R7$yqk6j|!SAZkB<1vn%-P#6%9*m(EpcA$< zuwYv#OxnjCOXEa{b~R!s2&^HDD%#XI{HsPgllj8z^`uSk%{N7IfoC;2*-vYG^GKku ze4H}5ofD){cPe#IEy5LJq1+TBC!)Sb#LakXM{`g+VMKlMt}r{q7BDrph?J2x(!|(t z>2K2vuT2?Pst`0n-Zj{UsV2a+GK|^#oJkNoN*&lFxhjo}B*4_;U`|$}!eiG3Eu&5!w-LyyG`C>d+6jM`lquk(P`^sLX zXQCKSVRP_LKponE1naTj3YiyVnafQee_{_o2oT|TbatL zHdA>Y8fb(NrFO}YY_syP_l08hl5}DLeNIOt`0^%u0nG$>utNe|RF74I)CGMH_GWin z5rTu`o6LR!kVoKs8o3@Rpr$(a5ROVcFoj*w5zXe2$zswg^aRvK;EMPL;@89Cl~1u;y@tOqM$jSK}^C7J3f!X3uE zkT%SB&Cww1df0Y2^TGzEN`M?b77s?ET*M(54oD{uX+#A~%i{=ww0ILsTs%Bem6PMvjJ|r~-^uwNpbB^Zp!F{~r#1MxhKac{Yjz_7 zlvj~N-|#d_<yj+c|1+HQ^pCx#x$f@zI z%^kMLCuOL~<*`(w3tQH^pR2HyHa85P7o-i}zMF5!71_&_b2Csv8%_fbExzv#B}Xn% zOk5f+%nkK5AeH-7MWKoT&fDnMov|0AwxLrc*~A1Pfw<^%iw$;ZDuLwz8yA+6Q#dIg z+_VIM&hiPsn2lkqs6Js+6gu%>+h2y&DI;oBcw1(=QE-th)7*nH*RBsTbHiwFOzS|z zkKdm87A7v2x0vkadI%scSld|f+hsRnWd;Zj|MX~s; z-aC02n5DOU>!Ocm?b{r7+sjYA%rfK-r@9XEl^qAj$f>&0W#&h2sf53e-~d$g-h!M5 z^|d!vJ-MSH#_c8>QEga?b&)*vVDf}wCA2hit9*t-Tfo~Fb1rxv_XPj9Pu_MMtaw}-4d#&z+QwM`@X!0759__3_s#IOd}7tU zWz&08if8l&ao`%rGIv%%;6?a&C7Y4j!!lzs7dQBZwDbE|rFT6Pfp_oiHX?ddJMdp$ z9MX!en_-P{jjrnT`}`K``E=y%MoMVP^ZVX=I}bCXdtUM0ARagnDIrCCb6`Dr^v?GM z!h}rn{o_&7V#L=cA_lJfTy28+@RU>@Ab?vUIOBQxcHn?=ZPatIqepX#jR6t!q$E>? zEYFL4I+Oen==I5GM6iP1e5%5F?r^FypTh!1+YaSzQ@-T5m@NCwaXwx7%ZgMY5E)UH zZd|9mn0>UJ!}sLuL4}DNY@v?K^;6D5*+i$aR2kCQ)XBcw*Vj2|SACPW(YdYFF&4KZ zJY&l8yrV2CP0pz*%oPN!f6uzDU(x}HA@iq#3S4U%`XWd*uxY|0`x6AI*p4k6&_m8^}kWc^mOqPHLipE$6xaHkM_Il6KNX0ubBnd z@<`F4E6gzDZOJjR$v!H1L*A|eTRIc5>%a^{mLVL9ATkZH9Key}U*DQ*or)A}vyTq9 zs0?H<+wa?#)K%v?!agp{UCL8>^BB+a-yMd0(DQhltI=y?mzG7}w)|ASDBGw1TdeSYpCbdUSKaO*9Hu4~Jx#Xl~G z^-P!vUVP))IlZ*~;nk;^BaeUoI{hW(Y$Sk9-Xn5Tz}z9?w@D?#?)kxQZxWzPY^LAXg;a`XZXEL|5o z(hthyTV;SYahZI&erD1q`fk|4c?6Yj5_3*ILKNkKe`R7bSAF&ELtK$QJsBJdwnMSZ zVXsKGy=ocjt>8y(BVru3?PE8jUJTl$ogJE{6idlukKKg18Ln92gv+Fj-1Hj#tvug4 zl^fo$c`za43B+N^1t4rih4kF`ssT}Uvbv-!&*y!0XwBY?!kv5BlO~l^*_Z%>wq%p@ z_eK&U&fmWSVO2Ef1#R4|7)8L9&3j~_m>RJ82c_y6goib=A@(7K4Ex;W(x^jVtf@2F zpNCa?QQ_;D`iyeeDVj&Lj+4^TEzoK z7(r}g>RBJh{Ud2Gq(zY{0P5@5Z6H2h7iK8Yp#9kf*gkp5?@3?a5I59A+n$Th7@@MI ze$*jL?GVPX3#u{Tuk}Piw3jr38Rt8E;mOYKo<-`>Y#a>)RdQUY)tOlVB?ykrCOqLW zqlaAtwvw@64RDFq$6iFn`(;+@R4JI<%{tUTv{OBSq|-IUNb1TE^uz(XjO*i-MvkPl zHtE`nu9o?5ltI{u9KELO#fVIj&cHSqtnrDQkRZ_OU{7QAWv?nRg>oH{538(&nS?R( zu=x3%Ndi!IQTq}MVGnx-Q&%qQ8aeEP!*FW#mxaKQs{RH5_HPNoFf5(}#u!F^VI@R& zaRpOpJQJD6wFLk$79~7y4IqJy336w?{(Md3Bt;)jC_B&tT$dzO*U`T10{1+$rsfRc|Tli?)GYgP#?y#o;Q}VTr^NENu=WH?3rkK z(M87`SJwsZhb(x$b(*5#E~~)d@Fgn{=wBiP1ik=@095`dLb#i^9ESN+rRdaoOcJ|* zVgwT;WRQsDx4Z1G;bnRqaXj{C8&zU3OZr4=uX%&?zzr3-M17$4Nb1fg#=JFAA^wb@))8wBKjueHQm~6D_fg%R8wTCxS z98&^SC}9PWrPc=JG`k)b~8hdh8WC z9>0)=EHX+E{|HLMjB{PxFmZ$6&%Y#cK1!a8ZSn1G0WQ_tzT_S9vg7LGJQdOCx&=Uk zPeYh{>65{wWV23^y1}TJI+^HB!~r<>pm_!3wG!s;Q#taUjn`Xm>c1L z9rgbDu7vqBa+%NT97yXB>59f2)RwVx8sP`afN?+@*kb9fl z_Quk&QuCa5(#{Um%*NV6Ggx>(%M)wHpYA)P+E>Xql* zK=;j8jN_C|^-2%$y6KlqtjKqLq~{Af9b(~Ibn20i)a{EEt4sgmA@`OBd#k33PA$5! zS{6?FAM)o`o!|u{j97=fj;#k`8eo{WHLy#k^n})c@gI+Xu1|LGzs%br{ldgEYXStIqElM?1L2AMgYnmf^!(3=lnxVC1Beloik=$~V z#=Y~Wmxs{c%arR!eIl>`4OD6E=+Vb(4Dk4qA?weYgA51R0Wl-?RB1W%1nH=Y^@gRU ziPqjeuXME~6xC+OEEUHL!0ck3dtT*@U!@IL)dtB&wbXEy zT&=USrgCfsqkv~%frw0Ht9k5UB?x;GDxqB`;QkzGG)+rftl8-9;dC8p6}(=jP4@E| z(iCo_ojbz_i(b^xUtk{fhR?Ha^s?}X@w577>5BRIcNqY^+H5nC!N&6#9v586Q9<`6 zPax#1Plo+w7thIKo8w(LPNnKGNy`qypo!lGZdHIZ)%K;wQ1wswyjH(;vqYZP^cOW6 z1fzOrqBr=6b)KT7{y67kEy`ES>v3azXpT$dMk3sGPB9c{{0zWpE&z$<@7SmU?wiqtKI&;H%?0k~+U2hP^V}EB zdu1}CE9~S;07uk`e0*7H?bUMVKWw=xfFwW=Fz&ym9)BS+N{$0q4*!kF*pCFL-jFiS zQ~!HRnx*Q#Uls1Fht#`CA*LoLeiq^7YCeKjQ-anGX4*$ z$Ex(@Vdc+dPPUf%GLEO5W6DoEF()af++x4`I(Vk)SJ?X&#>m=*G_CsGa;^RDpcwJO zqEaNCUhPomx{Kp7G!!W34b%~y)V%eLx4I1TJygD;DC#}) zwk28deN|ar;QQ*TivRy0G88rK{hLSBjjHaB`ZHBY;U)q2F?%c02=+My&PD{ z1zjVU8n|iBTC07f;o=M%ml0fRRDQQw=aYlhFp}ScSszkx7%We*w$T_^5Q_)Dwhau= z&qUkgTtBv>1Ag}1qI6pgX%M56Y>15ZInbvJ-lb+Fc_9aSJE)%gCQePM$%d{R5K|b zj}*V3Dp+`csk$_Q`?v>yzfFn83Fkek3HRZXqb3^o5J*1KMj|Lu;_NXLCpV&72;B*g zB@tl3WN(hE@)*7?52E;rVX$G~EgiqEcvP=pFh`=f=3b#K*ClB~U>+{npve|+1fIwR z9&-VXVKaLI7NM5(9^^Y*&nuyIE@fQOPY9VyTb*E=g(q+%2}(Z)N^uHe5`Ru;^8#iT zd7oOD0-2*8EA?^0KSn)<`=g%B@KufzDJxmmMX4yVf1Rf;zHdpx#uU3N0X@ ztXWNY5;q{@0+97u;Z$R;RGeaMQH0_6L}fpqzQJkm zo{vi`+C=iICyN?WTu2 zV+krWGSL1T2rdr?tN52doTlOps2Ct~2nE8TiSPx4^k3E>0|SG4R35Tjx_`M1Be9|b z#T1bNi0H19P;$zIEt$Q*9E{+%1$dANAVeELBxw8^f8y7sQ`jN{|8b{7I6RAETT)OUDOhlo4puuOS?oGON0XqSBK#ig=Im$V#DVQEZwJ9LeKn_r)%b zeht%@PS6^tmFpv~R>h^v=IX=_wk*Ebr!8k2+IJpqT)%&L+3L-1OQ2AQxycPmv-~f+ z2+W`6l|IwBvH|%1vm2n&vYC7)apk{fLWg_|>nVL{*3wKqQwC}K08Oz+t9}elY=SL4Cn6EXGRbe913sf%(3(s2VoLw$}E`Q``&;J&+glLH{=cCStV@A()lo%p(cfiH0wmm+lNjq^T`U{u$xm9 zD4CSuYYr2$5?C{=_wI;Rz?`l!Y;uJLfy&G8@inrPw)9z!sk#%QZXhr+@KcgH4Hf(>+N({PyTPwnXit+}Si9{cn;&>fD2ewBxS$k&ASrPE>Q=`uSqHL?jiKUr>QDZS=)8h_PNPon@+T^2timSOPX zbPSBrO}tXWn|R>NOi87M|0RJ$vIiJHk>nQ5n~3HMar9%j{0KmvCN&xy^m4j7jhbR! z1nRuvvtg}9pM-GgOJ}ix2eE&SR`mgD04lKWpRrCjbawo|Vb1>O0RIcj*-&*Yt1H+~hfZo@gqTyR-9IMP<{U3BJ# zF)zJ_@n(RDIa{Y|L%i}cSqjDbxb`$SaMo_yXGzW7L`FyaE4 z)%(4;&CgJ4ReoEcZMV+$@W&%+kgGNicc)iT^)7Foh}C?ZVsIw!B?k*d?|fcK+nwBU z@eg{p_PDb6q`S=dHw|;k#~q#He(eF0n{xSE2rtC1T7j9EGjX>sd_g}nP5}roCg#j| zXU_DF|F4@-Ow5_4g8+Xj7|Fz(L2^s3f`8|pNmY+8msVp75aty1e`B5gZ>-aQW2}?&Mm%bS z%%)54;*Q-&K*LHn%*?y_3O5qJI-435*un*pN0XqQ^O!uKQTg~rvbHtYAW8#9P%jk% z`}b?^McV@W#<1uadAtsB9^!?dp-d-}b@22wDQ;FFkW;dbk9<$j{6=y+++5BP4Oi}r z7qlw_BlV~Wp169z*Kf@GMjTLY|7RFWJ}O!Q&_I`_QRFe4UVt=E6*X1t#{#Bo3U(H5 zE9qV)frMfcK(k(aqEwL9x(1Y+MuwlT?$^u)8XFcd;19?>U}b`7@Z}yhZg>K3vm;)u zj38*pNYJ4Jk}X1%v$aP`j|xk$9M+Z+;ssVf)$p8XN(tZr(Hr)JXeO*fy8*06h{Ke_}WMyy@b8lqL=%<2TbmXR`yIA zyLvVbXiVqNcK0b!6!&09Hh6-{9Q!!cX)KCZ8ss6yl^? zGD?Bm;w9=3ySWVI0lc?EC)D0&adFc@8fPK)qB^C*%54DQ3S2xV%}_v4zUO$KIzjfg z7D{~ugdEpMR7TLa4pL2&gEGP1D5G3feG{NOFNY>IUa-H)voBZ3R$Pw^_ffg)WMIpp z*hGMdjrA!y4|SV)0C-i8nDR_X!O_t`eo=If*f$19VsC0*0D~|;*klXV4Dy6TcmS1l z^qo8`Hz_*b5;YY02G8pl@l^WzBQptUpeX}%3JoCJR1fq1*$6mV*602i$09h%U=#G{ z;*KC#%OLT*26!-!aVSZ8N}^FPJRxpJ34RpY1=0W{h{`v(|N4D{IoA=#1X;5a6*;6KZVZs1&Sjtgu>kGfhUaaQxG2G)afI>0G_3-WkjD2@OsD*?3AlT`4)G(nui zFjyi1_^2cFh6)a-X41b3vKXL3=gTP?| zug8czddUJ%Q1AY9`;m2-PZ}zq%(_tG-&dtl019yYpU)|CQwcY}U*!C|O{ITQLq&OI zSuOrvNBwJ1mL=u(k9Ab$b83?)WdAocG&bklNeXiv)oln-omPo;)BXoFROEvHT#dlK zCDNn%%b+F5seYdtnx;wI-yGkkhOQe*F{z==`*vHof0*@f9S z=aS+N6VHc>-)zJZPC(|SDxW^y!^mxT+R|jI5WQyuroUH`W7!pxO#-qw5ZCxx4Fq4s zqbTeyfms;&l9<$k-DWW#ef_;6?+c8X1Nn835^3mEU2Lk{i|E+^H~3P2ddLdh8(2N! zUwGYkOUK7FtXJMU%ep4Y$MmF*Lb;y|H)1~Rbc26pww2AQuh0F^&5|_l_!r>o?iJTi zLC&BZue3B13OL`bCZN)t%hYq8??S&L20`t+xJ(WQqQr}R*UeTa5pK(Dd3;E9xe(In zLuV3FR|DV&BHsJ0Rt8R|959f!gS@Zy6iRhTpLv^yuA!dYORB!v2oe5p@5JbXMA1uU zi68Di7IPM*_S%(yp!UfQ=hk$4RjxH!iz(f?H+EVnm%pLe>|XP1)Q69)jAW(twxzuD z>+LHQch?`RwR~9b*yvaK)VclQ{HKTC-u(wQmA2^8`Tur=soc7@HLO0M{CPzCWzfGJ zVeYJbeu`mN*&Z_%4Bj3$m%Fz;VXgad`x(|u<;$eQncy$a9nanSwq&7f8caE^B_yeKN zBMaaFbUz}Rmg;`l0NiNYzlIA19#-!WcSCh41-0*yeARn$W&y@PEHF*%o2Sr>V;>mq zX*p95fQ?qM@ewytt-j_6&9n`uc`?8^N`p{<2SFy}`=Lwb@hr+7T@d9isNeRp;(gmn z-GlRFAd4W=6l43ENt&59f{LzmBUIrjc@H9l?lhV45iu}_2@scK8*^M*V=?v6P(T#! z2b>xsoYXEY9^6<`t*qwq+gK19j!scT&P+^OPyl)Iw4?9QnW5X-Le$xK-m~*ei_4Ic z#PLBvkDB8Aq>c;u%|Mtn`}y%}1SSnBo+Xx+G!!Rs({ZXBBAhurecKBe(#CXDXz|Ap ztSDD3P&us2naLXjBlP^lBQy@X$o>9|qQcEJf9jL$b-YmnxK&Ih0p>`PWJYGWIp+MJ zgB)(4i~b}|@3&%-%r5}P_rHkKI0n}%Y$Wi z3S~`F!_E<`K=sNN4|1iRr^;o;ozmZ0K9eF|%TEXmo zpZ-AuUXlZTgV7CcZCRsCa+=1cYYbg^We1h+4tQfD9;53G)E60#6=!mToZBiDE+YJ+ z(eJ8nKNA-ijR~<-DMY>~Q)xgWCrSuxrxZVXozS%r=|2`6Ilr|Od6Ip{h4H=r-K4j- z8tRYHQ3kw9DeRO#+ zeY9#v^;zxFVz%_c)0cS78^ z-G~EZ{(t;EFJRl1no`?D!~f8pKfCMU6-f4BVY|3T3A-2He~+2cIo|y5g!ccR40N=V=sNDQK%$a5NKY zyw{y&2yOlOh%@Yym1mPdttX=KXT*Q6+f@y5LKJ^H{>Rw|eKV*mPPV_I?`}bqqttP1 zw3;hYP{@tbk1O}xN2e(&kd{5Uv7j+w*#oh*0<7<3H{IC~W4rNk$t0^&wok$AWN z4omSNDL6muz<}fUfVa5r<=#x#x<5FK;)&eqRLfiB+;`vn6DGbVeeUdW{B7~>dq~pi zG?MhU8hJXIZO70Xmq$Iu9HO%)*KAcbWnW0LKhA{=l$;i~>Jyu$%g0MLKEGqnbILZS z>|~n|y`8q&JdgEjPbM=VnDabU2&28WBd0M*JKO6jm3Bl-vq@Q#9e?c*l2of@dWu%l z(Iady*%gvXPV=p1zH1>fO^Cz1B`5i==H+E}`#QC)WGJL79K@iKKCj-6z>Ikk3BAFb6O?yE>OcVNXV+I9r6< zgcoDEN$`N^GMY}r_kFU;&ESVb%xP&_(_qO-$;O}df6>vWK?H-MtsP#&)sq=>%Kb2@ z%%d8b&~cvMvfoJQVOpR3V~a?s_C^#NYqVAE%thwKLR*SfsHnF9xyo;<_ zI_`dAe1Ue*jzY#1;|~&O!WK=C12y@tp%BW%M#*7gw$W-&1jj+Q7`l->7Ba(vL~Q%Z z9=NxaWAh74tqV!kr_~&uWEO}jnT6xnU9|t~YoZ7+Zt&ufGs!Y0S5=&8EWfLn^*sjJ zLSTZlkUn8fHpVKz!HEL0U~(TXW;k-D?DcK-3QEQ`T5uCzEo$S^wAV_~soemo?MbZ^ zX+;#YgtX z-ysZgNCW{I2Z3w^Hd%2F7N49R^G2&%#$l69$vDrVQ17Qi^16AtIW-{eE7fk9HF>KY z<6H@*i9+{UZ18Djnt!?darT9hyq)Yne@7zOPWSt%-5gL>Gdqs8{xe8Y+LdBefwBr+ zDH`Rj13THU-N>=l%}ScE4Jp(6a;6V(1*C&!U;IAu@Q0jb*w+HmadVAVI#zbs$|w9< zr*M`D6j?sLNQA7qEiZDTab9Dsvfqz~29yi2J!0s=WZllVlocjGv>XSO7C%!1h>am} zJEI0(Qlo>;5Xb~mP_5Q`L3(Jj+LK5%uusXDLD&dO$yW906XM%KQ?<>&F@wxRj@8i< z_EWesxS>_AjQ5BIVtbmg!b=8^36-hct+L}N0=YjZw)H<*TnIBHdMh=m7Xa&M2p zB=vLc?p|?^u$m!vLQtxOuTQsJP1}5BQ_6#C(>(p0mLRn=o4SxzxM{6gP#aBapz~o^ zRx6*ZJK8)H6cLv6%o;g{(apVpPNW;dRzvKY1(-Y&yJ++J#=S6I`KwRzmPe2Sf?+oR zA*hxFOZ7iFo7D=R+SGQHL0Tw8h=1cRL+jgRyooM@NEh>$-6-vn%*v2H+Od$xYW+$0 zVjnWIxR}Dtf>dc-Q_mwx`NufdV$)$3Bv)+30Z(mLMG;8B6 zjV~F|XI*1}u&ljrZ$|mkJ$CZ9Y3$&p+h2ndsWHj%yr$5n1E?7($^xy-!E#&E5&M(T zlam=kpQSJ`#a&8AiN|yYe`=#hE?NoOKc3}1?Aj9$(bt_3@7*S!!a+kN!9g(FE2R5IGSdI3TVPPUpF*WF7S zg=r^en@~R3n^4+L5+N?`#o(sVqaXH0JAP93Ha^N>#M%jSDi%s^E7KpWK zX_r>$Q{s=D5tXk;!aRTknaMR)#EpZSvZqZ5h&{^6*gB1p1UcOcL;tl`ZkV7CB}f%- z{Zj&yb0hQRLJZ6Fa?!8y*m*JSo~O+#-DMwaOW;L&<@RPfO(g9IzhV_BZn6*4v1eP+ zQO_$x-hcKKYN73AC}se14&x3V6(r|JFG~zq&xo)zZ)q^Mycu9rM^y=Yv?tNxNB$DNR_%HB7Xm`SYncl|MH6I8Z(=aU~sa~{p3i;fcJn1)OxkBs$a(A?3{}0f5MIb?~f7cr`t0g zWYtf^AfG?o{}Xe~t8t9eCpJ-<)^v%-9j)|2+}FFC)&vTqgQ|25_(_ z$E+e*7_a}I8>GcC5ZN*Jy>GGqsfbGI;yY)Mahcg)$Nxt78#~|)7e*XqLA z$zMM4|9kwudicL~@c-rqH^k4dX3@9FWe^DcbMjhR!@aM?Jv(WQzE7N1A1oi0Dak6= z>BrTa96_CVgs7;rKLDQg@O|aOknP{>GOdBh0&aaVO0o}HjWC}0;#JgofM;oU+ zcpV%7zz;VnDxLp^qrPS#m8B}_=FG=4Q)!zHvteuiKE!Qmy(P|zf(~SC+0j< z4*W;0m!;Zx>#{xSaB(8hy6K)rM=9AyFWS#6_U7({W7%KR{Bu;=i$9tmuPrB@INzi) z6!AL$y_iN9U55|$Be!gPPEdV}WyPH-gmdN&C`}pRyLD-L&Y^kLIn1kvSqmd;IRX}%HL6(Bo?(z!r&WR%f+ z4*)TSQAMB;^!5)cmmps@{z2wWQloP+UANo}d}#Z%?adT z;dkQA>Mo}{-0@Sh=wnWgOL~jR8Fv%0W$-DSyF_2Hs89gK$M|red-;f2?oAqDeR#6W zgVyh>-OP&23~)o_IuRFk`{ngLGP6yQ6(LxvJ*IWlx-+ z`QpF+H;=2!Cu)qQ{z;c014i$@0hbKuoeQ2w=FH1aT&-zRpdoj?LYQb+;plbg%VW;O zOgQrgZGq)+U3F+*JiFaeqn{NzO5NOeSJ9KFc*FGm|^VZsjGDw1-gX+NwN-#s4hp5-ym5W%lsuKXgqdVfYqaityynk1?DbAFEJ zia$I(vtN_guxFEDg`!MUl()d7v0m|4a}Xi7JM%`=+_;n-w)o1fQUl4!T#cm{DgWRj zy!WXhM6&7=nG`(p#ht2#T5sV2p^MV8FxJcMtL#V|b-d8B?QvhOdk2Tf{+#E`>H+FI z-tkr{@j>GHTMzT~5#RF{GjnB#qn0(kTA8=6J(+vT=pWXF-g;}= z8_$)kAarefU@Om(o!7OjCXn$1Fej$x0B@#G`jxkwLt27iHoM$1W3Eki)Vb<3uFLA* zc|a&i_p1TbRYh5?X2=}81r^8s0glaqd}F|L zT^Ylw#ce-oW`^#SZ3*Nxnb=At`4?wE)4#=R^u>mWzQk_<0nrD#yzXlw924s2hBz2h z*_ZNDe@snL7HcJ$ZuBrniQ`8~HOF7~Ej1zIvV1LF4KCy>%j#QRKwTY~6<;T|d*jD5{z#D8N@a zStVwKtMGcW+|I;7SN?-V7>$p!R|XIkq5j@D?|oH#{c5?fXbVa2L#o&{-6_XZr?r|H zS*qRp9rs?fUU5bHCb`3jIsPjX7y${IxXNf3CFQqZr)tHzA}1#LA)(JS)CR>Ve!mvw ziS%i~rRs7@QFitoyd@MeD&j*R9y-%vF6SF~U$A6O`K14KI}{a_(m4IW_Ny%6?u(|X zQtQSMu5913aF6qlNnIIW?)-LF?T3q<>_^UKy*3Ysq_188%1{wp&RhQ08Q)MnLT(c7A~S=Y4;sb!_w*1R3#Kp6@V8!IQf$pj+%MY00baR#0r>FV>P8iz ze-Zhn>a(z4GO~f8lL^ze9=#ZCeAa}R$Y`qU^~rLtRw|R?v8)c&6oZ@YDU^)6@85_J zUH3wPR$RnNWV)Buy)t|`3*}e8j+pYsGcQJw@8=In;Jt>vD?CwZcWq!YV^dcwjmnS( zQqd9MqOX#1e(=mXySN$;!-N)?JaSJVdTy=G4?8{G#nYNNc9-zITpkHkf(9@%WLlPy znXO9FeKX-1%cGVjgB^hTD(#BiX$EeRgQ)mg@D2D#o8z3Atv%Oxs;&PGioJp>PV1{< zTip&;Xs68~Z{>RP9cC1%oMtG`Q z;8R4ZEkS`)%=SNFUQ0!@bQWDfMpTq?l?w&!{>b>nL9*$RmqCV7v6R}02*_%MbhjHo zGOvaJQM|#A`SiWTVGQ})0<(4c>ErXaB(dQdMM}zdR^v2Sn0$ zEt8?L2LkZ(Td?7TUKXuu1pSqte<~zPuCsw(>xmW-&Cyl8I0^ra5u$%vet&1e_33XO z*&{iW_?_uk#h&j^%EsWBtL(L`h7;f4`GNBAy`rm5pYErKt<@7b-7QNaneTh8&qp~8 zKrWe$n>1G2MRV0GPH=xrB2A3Eo3H7XFiNEP%mUcj#H>flb4jz_@{V87%%nUZO)*%` z;FbfF%EaJe8?YwQ!8>B(VO=nNdI6VgK*X0575-f1K} z=%X}7ocE1Glyru|4EN+q{926usp-keMZe0JpHR|UUY98q1FV{5V%P%CL%lnwj)C-w}5b6BH*RQ1a6jdKnQHT6@G5VUU^ z1GSGj1xTa6^PZ)2KPJ?7OZ}R8G)B3puKx45Sv*#5?LhC~tfwLeZ$q#o&>!2LK@1@UkQLHW?WE)0084IrVGA4jQk z>!x1L=k3&(Gy$1zg~fa0*QUn2M^-!{^_8w0=w;bI*uoS#S_>UafOX}b>m1S^<~$Qc4~-2f%NWWb%hdz_)xJ8rw6RhcN!2k%U}?TqQxav2XiNXS5K46P#t%&EmX`4;MEV$*)1-?vP0T^4$}Qf%%Tk|PuP2F^bK3A zHC{RtqUSl@%{_L0-OjgZ3d&01@D}#aU74ukVV#Z&;#qH~yWov$<3%MZt^Q3KvznKe zz#Bg}C!?nwL-xr(4&VJ=$g))2t@g!T?jqPNM-G73Ltv51O^Rj057;j|vt01`1wAA= zN~eg4JG^__BSXXna{C+h1!ai(8&1K$xQE6+MXv8whl^$hQV%K9`1qy$%mh35xH5b! zwah;JxuC4!ixc%W8&dCe(ebzAS6JVXZj08pHCBIgdBCe}og9YTP1?%?yA@ARD$kVy zb)WJdH*`(QUYvl+{+_T7ud!1-^tYFFA>PqJQ;mK9$zv>hJ|}wr7ELk2NEgMu-lqyPFQkI_4{D#7dE+@bX?Z9UQR%%#a@17wk(G?si%j_RtAsFi3^tFQ zABbn9I&Bm*Le-L+!wak%YOLp~Y|Pi}Zn%C&L{S>OFpmkft@3wXy2xf?Z4%g71Hwh? zygGe`R}1=+Jog)Xk=RE55w0edufl5$6RZa0=495-O3O7o*k<8=7r%2^crr+&_zd7KbgLy= z{$3kZgwpnv(k2Vsq+uf*bRuz@xJ3U*$Sp8xD1W3SYhNz>>!Ed$GHY=0(7I*qX?9zI3CTF|%KeL%?)4;agtn(!x zj>C2cyqF|z{}ocx%+*7}w+>fJb!_v=Mi@rw=ZO+%TnB&waks@Uh+L%B5t%AWj^l~7 zP5q>lI*KYD0r1__18VT|*>W)wzraQ60ZxB>K0qW4tH2OUuIO6A&hdTP-EhBtutI1$ zH#6=P9H<1FEh2dYA=1e;RVp*6mqOH@BQ9-loP*QMjthh5h9jYC_w>!PJQ&rnQZ2@oDU+|uj4&?JmlUK&pWGWic|tueAEqXr!>aN@sYH<7 zYy6R`ZLOY9u58Z`GrgN7$~T?g&iF{;Yn-wf&smH&&Zf*q-ec+Y;xPvj{bPRd+zLPX zpK)#R1yI=PckV8nY=i2?;f>Kana`L1cP~JPm~AlgqJKPr#EXwY1~mOpy(2xZaznhl zhByji#jokwjt2|t%g5~8?`0ec1cYiR@ zlAg4FtL{xyiOE})wZKHygt;71rprlxgx46t+!hpV<^aR|2jxqeE$dD!uMK5apc4O3 zMED~z(L@Y)e%Dvo&M#OIkgk$pz)i*)w~HgO?5r7$H$z+^p9b^(Yqm=7%+lidD!#F4 z)8$aEKj!L>2*PDsE;4=1sZ3q$ddL$&ZoC52W~|@(7<;@Pt4O&8>hA9hacw@+Ez<9I zmloHaiV*6v+sS+rJTljw%R2(pA4+EVC7U=ZPRE-nw@beX`(?>MvGuS`2c1%D;<^l9 z>4@fZ@tl_LL64TsR9f*!<7^EpS^V8=K}2)W-mly4rinB1vNF0*q|K7p?}ZPqw>jD{p${7#hOzGhrS1s(sP6Y3ZG=FEwYnGsE| zu^%YS{iPSL_2;cTU50aGPd`5?Q-9{@-YOW#oi}juk7OuI_GcSw5H?DDH*=}4C?RKa zOz*RA82rm?1yOCC$+|Ftt)4V{wtDc%qKb!D?65~<&pletw@fs;)&5nUBgOdi^Tvca zoBf7_mQN-r^8XYd(&m$LYu_%a$Sq?Di52G*n0IhbZ`@zIocW9C`>lpd`M4wv-Rae@ zJAawCdaLrAUPO}A1VlnI{YHbHbtdy6UYtH^6j7Hmo$!e_D?cp|{Zw@&>0f5vYxz}2 zVN2RY`7v;D%J4muX7_{%htO(V=Ze z91XnRjhJ0BPk!46I5xN#n$c0u-;cjqOy7wQPvLVh&lvc`GGp(fjuYLEF~?n-G@9)b zSm%TLsd=b)n!d%O2(GP7icmVBEUTBmYpQj3((;b%=HD--jq_^+@v&M%!*=I3#v;`A z$f*=%BzhBQAjx0aRbP6iU0l!dL*{kENRD)N-MuJl=a{DQiEgPvlkQmYw=U#wm{3)c znYy#NWjsB^N1`fIQED+TmEUjufxeei9Kw-S!e81PJ?>)v)9rfTrG&UlR3fW8p1)V3#gZ^rrzB$^M zih<**8Odt;jvI~7TPBSiK?{8VZATZzN-_Kf?f*+O)AyBJ?b06}{ti?65Psg`iyU3m zr5-Py+v2Ylu1F8;S00)4S zw5^aey33eHup%cwY@Jv887r{82();SYfMaZTPs7 znP(%c+$49YKgl|f*-_L<+WgAD$xzP)AjPV*UbjK;SffPtf@Nbxz2&}*(-q=-dy^l! z=}z@Rkv-svt2$Aw{I?`39C!kDou+9P^l=0ckujzVGpU5bvz)OW@b|)NYQFtFF{8wF zzc&G}qOjMW=TTeL>^np-H!RKX7wK~1y^;zeIoB!+ z`!&0V>HOU%JwnhX3NxY{sW$e z3D6D0w999IZWUdIo-{zLts8LVO@%zCZ-69Z{Xql|Qr=pQT>)b8*MHyrR9N#Oton*| z_N6+!v+3yh-Gud$TS#53sH4mRzs9w8u033powPRopow|?wE|5lAqn0 zAFeP40WGFaALHq6h0e{JVdCF_$U+H9DJ5$JRsm1|{6dvw_lEAn^`D{Tu)V{xwFDpM zj&vYxtPvovHyl&`8)JG3{zliAH-B^|)uHI8usX(q*%eJ?#%vOJRcYvgk;H`h5ZLOb zB%%Zj?&+!_L&^37B>xv=vKbQJc?%c5eSzRg5TgTv%?oROQuht|W+C^_kchmhc z_L_Q1p|JCgKYvGjnK{l5FzEIxSd*QQ5u4{z+>DmBCIrEOBNwv2c`Y;}99xT@gLl>* z-UpZ9Kz-R2h={HbGcyT3t?vZg2}iVPJc60iYjV|pKwu9Eb!P2ackwP1iL71ZRAu_X z-~)t14qKGSc;1o#Ahi2BVKVl~Hzz ze#h^#0Mci1H4sl=2a-k53k$Q?3QLEFRrcRkCq`&}7k_^F$&PU(cD2%qqpEn=k`!xA z%mv?H1Y?L_U!ZGcOItl}vPA~Ast5C=OB;_7To@p2ED&c>t!zVl(E_#lnCr4tJyORH z{brunv=13VkTqf_nYdMfFAyXq8MG+DJL+mR3VUzp&;Ig1uT;9Bbq7gMF}4;lXVwj{&taOVca)Y{vn<5T z0QO(D)trPDf?WW)UL{!qrX6#Y^+9jw^rDh!FI=~%=(4RZm;_jf3}X4|dW3pBPX2Qh zgSnSg<&J}D+cq=0dL;g6O;~OISAr)Jy>MGRxgTKF0vvYzR`bs?0lsF{G?3BJ2Ox;*h@({)^i%X zbh)NffV+R8{7T~SjJ|~a!}Z;LK?(BBxMunxBf#fET}<~HJ`OF5Yj|JhJ@0$dS|fF) zHt#nf6I?G3Ofs|Dp?2|(%{FX#y^dOm#qsOCl|U`ZAYw{Q@hKWvGrw;Yz zVvYDy&=>^ou zEB1`;EX*QJwUo7nW?AHVLD?ju>fS#EnjU1n(h%F4avmLeF{q_it{X6b`~bNtM^_vb z9;v^sPwsqHIKGTDH_F9E6K58H@}e1MCi+1?0u^po5y(i@XFaj=)QVNj?^qjlt)}`i zJU4gBFwsTYVmgYWpLG`(ZF9&uYSa75sd%1Q@=jluIbsCh{+mUpG&y%S&2KIGpjnlpaJ}xxA1c$_;$Q% z*iNcQu`!uW3$Oh7dce*d;$^9spO!3?fe04!*>?|(*L~z{*`HL^S?a_glQVjbP z`<`1XoM;ShXTz7gHgVqZm6-Q;5 zS)gWOg*cG&z5}PQ4tIvXxL}I1S*DXes_juf+u@L%N~(=t?sUw(8HW6juhSp zm!;=r;t8B|Zjm8xsX^HhH4UlBn!$()aDK3&xIg_*WB95&3vWn&^jEn|fS+;vwn9dy zb|)xSh)J$=RKIV>xgor!!K3os>~#aC*z9C~CBJdpX1wnW3q$z_*vJejWIL5XTOC_V2`Slb((7mr%ck@ac00y6YtXZLSi3TLj>W~VH3v5@7arL-FOm(c z8U#%Z1GXK{2cnpXVcNN?4}LYCLk|SKu=fovpZk_B+tynB z$a{k6b(#@=viMzogNiCxPfr7f|q&Lu8P0^gmb zno}(tbG`0o)fykPd-VEs!VCpww-9{=C_%f0Gt#u}ZA52WfyJp~)u4cA=2g%%zMDM8QD6T2i z=Wd4&G+VCUh%eP-X84q8g+a`l#l^$pC)gw5!r@ZtBJU5&`+$TXGJ|)MxkUcAY8#{ z3|I#;qUDKx&ZT0K#ug56PnwkITRj!@fl0U=i$nmczN!6Ukfn;3g9a^{YEY3iDYFcO=8u6vO_|`RB!}v2y!#km}cBnNY_FLVX zZHb53ilL9s0CEBqcoDFIBu);^8sFsa&C;K8eE7>se|9mUHO)t>ubL(%g?ox>ZW!+LZ-{4z%_Uyd^*nb%g9NHeP^{Tc;KFZmP!`l z%8MBbkw)_GNQtjF%#)0=(njaj5rnm;{m-DKW~<6-Hq*q7#gO@i=E_Tsa;$5(1v7$R zAgWWBZOw;YWK&4j5PTFlQ>j9(sN+oFD0}e&+v1 zb?-pf7vQcG>l*g0#_!q+DDC4avQNzS3t0N>Ll;dAXrGA$O(Yy{2d-=xES<5s!fKDv zKx2?EVd(OsblvMr4IePswL0hUU#(Bm(9B={*g1OZ5TeauxfW zwV4kH4;ZUz?D$9(^0(Xkm8_D>ak+26)^l0xJIDF!!fNDOqFfDxU&^PVsM#)nT!E4< zZ6sH|Nbz}=Gy=lc`kEU}pnEH0sEhr>YeZI#NvGQzl$)F2r24WEEwLXpNpW+&9JAQV$>%&PDyC!JnB@iCdpbW8TL>G1w*ukH)HnL!>OZ3pE}Oe`(QGeTa! z6hV41xWgd52DAASS1u*Fk`l$-uTIQUg-s>6y2B@!!bLAWato~8NNU>mV`U`rvn_JX z2gcv=bQ_mz3hOSU4@$zN)31|T&4C#P!qtw7B|KTza!umvlkrlPQq}$KBXH+MXVji@ z(Y=|zbBdt-=c7SOqA2l5ytH}@P7oT6_>v!v9oL89gjq?zMg9hjTc9YhPjMQqM@sY+J>)it!M9nas6nBU5zrPD=YmbOm{%Z&b6Uh35}#kYjPLbPYkuMh$vi@ikO)R&U45wh}`htNzss)a`7M4Co z@H3EDhr>P$nII=_uJVCP<(= z0nolb4pvjosA##>Rf+0YUhp8Us+xereN<|s`shCa!836B#qVbn?<-Y| zXUQl>?jbnBfz6+{Gdw3RtB6qtBP7z*a2q3X!<=IChK`{>6I)D{xR@H9E=FW?#SWij?TZM^M|czrtSha`<-bckdYa8 zye@bbwt1T8l!Qk71M2E~VXEq#!^q2*@RuoU8DBaGnu=X@47N5*r3MQ3iX?xrid2;$U^x zitl|vVuIQAgr6R6*X5`h9MSvZ#qx~+K^6*QE!1f0=5bxJmWxeX$Qle3xhD{*(kf8V zQQcybTNEhf^_Z!zEzN2XFT-%MCgcYX`K25y5(U`t&i0H1 z{)!(quvK6)%HM7J-;S})<}D$mj2wZcU*ccRbgP4!9ZLno{?4!!j|-qhk2 zjS#9er(bo#W)`pHAl!cp>KIDPWC8#%XsPO5NTQ&=E-EkI@?ML@b=l^dn+w&Iel#r|Cz(!EiNsJ$9<~)LI}tPcDX-T8Us`)=Y?O8g^JMD zPj2i&5k6nQ^Le-(*;dCUSSvA0qptt^kZ$7nulQ+6kz|ZT(xc|ytMGw8dYZBxQVVvM z!DY$cP*p**BfMq1?t;ZdoXn*0$7k!lz2zeV#uI#Mx7~Ds4M%-R^{Y_>QY|YIqM$e6 zC-E2C1tMCJx5TMjy!M+`UQf1Eiag^K_EBH*p-SkO8i;OPc2Ru(O-O)!Ao3M%d16fm z_NA@5s^m9_b*$XB_A{4Ik&cufdlqp)w8cy?Av`h?XjsaH-Qrd~NGXuYTrPHx)BhI5 zMS7TfAvUzsv)nVc{_E!G_X>#t`)#kFK+FE41>0bfj@2X@8kPhK^`K39Z2xXSe4KSZ zC|ZXn0@a@kPuwtj03(}S0i9g-`0G5Edfs)PmZ#V17aDseQIZW2=i~iJv(;f zU9thuoK*x$%{9DJDmS_I-#wBtjgOC7S*wy7K3fTQHQ-t<$>9ff2NT4@a(}yTj{l2@1-r~(DwQfV zSp;`vrD@B`_T0QtDz?oZ&pF_k7eya^`PvY5PNDy2L%breT(0Q1=B^9v#?x3`^A!l3 z5&81OunCUibZ_B_>%91ukh9~$GA6)CW1cN+z&i%?Yeai!uA3K7TgRDOTORU3ew$Ay z2Ipdi(&_p^$sNur`ARG**OEHJKP4D!GNipBRs(T0I^as0T)d~d>b6JW;L1TSbH7nM z62YXP$$Zq~E^U6ZpYRK4Vfm8Rk4yzvyYiy)edA#|4#uQ;Ks8{%-iOk!e^BT@v(0U)y%<66vG%07i z(oOAj{TDjChZVK`PZw`V>YuS~E!+a5A~%u|TkD-UQm9NU%yTDSb{y>M5JTS$Zqgob zr?U7H(Gaz0c8Y#8WykW{F^-XDbx+jWSe=Mv&jm7(|LNC z5v!|EbR@oKa7iX^Ju|&q0G91+x%q+q57>4}Y(dSo^MF>&RuXkXI@HV-eE+Eo?ZBi~CYVO*E4tlVL*Q*Fw=;4tAJP3GFuWmTZtNh1Rl zlHb`X>-0#&Q%7r!U(l&_+W$qwUB8jgdD5&j0gA(5%q)L@yF9vjPH`hVw!tN_17P** z%Q1I+RE_K;@cEGo@?R~s#fB5UW2{C4kycB(NBN1nu4J5k=3DXeJ`;f}k zEDXTTSmdgum#3l!-m59^7pDYiEh3cVxBA+qD{klS(3Q9gT){`}Q94zDYFY9}WBJj1 zymi~6CUN|Bj`6v{3r%->zfxG13nX3Xc7yg5Hn??hJIT+*#Ih6qaNn%u!FHR$?%(f9 zX2#`QmJosK`a3!*An8RHNY=dR8F^|k0XG3sF>-Gm*8-1$c zv@HjMfipZ@=1IJFyl6c4W`CKa`SG@l0@^BS=kmSw6>0xBu*y0bwN@YhV2HT`CZLV6 zbEVYi>0S3%2`(Jpt6xnIPNeHO8EAX0x_8$WLkKe*q!B&pXMxi_rJSU`M-U_Q&rBmWgt4W{QZ)0Eq0lkWnX0Dwi& zeVpxd4N-aBuvoNIYS6?~OxMD%#eN8UgWUOh(~DDh<|5POd+d>_HsS|ARm>L)bcdPJ zV3Du)!gEBu<2Iry_Xb+d3O)f^FIVa3-wUf*`Ux$jPY+6h0#rjb@9Nnrnm~&FXAv+z zp!dDmy0U3uL||P!GK95kX>Zu2ex*#1WshiP4xIqXr34gUg@;?Z`I-aa3iGmFeA_QXk7&qG7)Gg__A|Y#}DZDzGAw1f_U$Wih2_U zHt%b#slP4nQaJ{+NLteegBvSlpT4(jatvPQSI{raM;u=HS7SmJ{0<%Nk*>h zPoI=d95#;4tm02UcHjeVThwYgu_X`DNXJ?u(3wncJ&|PCy3MbwMa;Jmgc~XVJ)t%w zLxC)164pHDu!a2gn!43IjVqYKHw%{?A8`n{0nD#Tn3hOc9&r?GNB)v1j`Bht(HdV> zuc$5Uw3DiHp?%x(tx*BVl|~fZ2HLy${wQ$P`&!AV?W98P8Fv#ygGFx{Kc`^`8J?d+fuCS=&+Us{J`0X@B6_tnd2`GttmThb!GD>2?atUbT z6lFXVjSGIHfkrz#SjL{r1Au@IAG)C=x^J~guFUX7c(sKVU8Li*aKYNnneA3hoL1`K zUV5}{R?$neaHY&Kr}xfzoh}Zk*;%c=K=m^IcI>|IMS25J|L+9?$qT8!(*AuC&PHQB zkJ&SAUbyQ6n;3)23cfZ1yLVseHMR<6@=ku6Ynu56UX25%<;K+Z*X@hGo#%tCHsxu+ zo}>(=!2oUvY{3x1_OAgG;e8p^kxa@^J=)q|IU|{S5fuykkVuXuVnBdz^9F;8*JJP= zA{EA?W&hUMAMu@{8{K4AXFl#HkVx=d5iOU}={VVxfN&Pt(e=Aw|LmwHAx%>e48I-q zxz%Rz7l|x4j08b!GM6=>%!HApmLGrh)$j zPwae{3_En5IT4cDj|5h592LZIAUxA_Rb=qqJ%6nC^hj~An?<-(d`roVl%|{g;Oo__ z9RLN^+*DMi^N@L#`GVNdekNvq`Fq<57+!uCObkmuE z)XBCjCt^b|*1%@jPN>+Rj|!~f-8`Q7iB2pRd* z1$HmbVY(V1bV0^{4IkKtXL)`r*PHWz3KnnrOkD%A1GIy2x_34r#~gFV7g8uW z%TUzoFBj4Ay|_MEg@U4gtxy_dLuy$4Y5F+&#f8{eYcdptqYs@P`c-zz^)P^;+I%-o zILtQL3jOZi7=(GWM*6-~tu>@3U#zT-27=bGPV)c_=%L(g-#JbuVUAps1jtzZ?7|#p zSrAO;pi(fQV)hLIpvvP$XXI|i(NBH(83|eh&jPUDN2~;Sw@+^tXYmP()e&99nMsOA zQa9ZqNtJu&+z0T_I;kF6b#fa}`H86-w3T}C7L5;Ue(AUeYM^fAoPu^%XZtqtR@0(X z=6IR?;f&vR323=J(=Vu-o}SeUlwWymy-Q%7U?#M7?8X#wb)EdDKejXR*Y({{mLA7& zn9fBe`t3m7JNDFXl|hY!AK7zz$>9wJ_*&PByuT|u6ODS)Oia6)8RxBxtS!M`CcOlR zeql-0)_${43w_0al1pIDb?59(pjWZ!-)dTJ<;x6kx5gC!usJg=ibkmYN0tn+OYksTdR+c?5- zaM;C9-ED}QmY1&Z`|ueDvS=a!JCzhSm%59D{D0WIm;t>0DhldkG%9Ou>X@H>Axi@K zC6WrE$3vDXoWvrpNp(~y1@wh1f$(KggJ~O`Eg>%o*Wa;3v{vD|dgL@|T(SXO3dV~1 zw9x<#{7Z6OK@u6ol?Pu`z>{{fmqK(KTO|ij`8PqpZggc#lD=&Ixms`&fx-b&xYESA zzUwOIJCSIp;qAS6eiHZM^W#cgku@uRVj3Yd(U-aRc@Z?je zC2wOQ7@WG1c#GZ{XcbEb5rB6pi+5YvudQ;kW_PUuc7rebMvK_JLcc>f6<<=26 z^+Z1(;Gs%d)b*Xk^{`$TJR)+zpJmTg?#wYWip>c-6otw3t`b+C0{3)`&`q| z7SOwo+a?ld+>PgA{M|x!1~pKBi#)H z3?&VcA|c&FcgIjeNVjx%gOqd$2nc+y_uk+44?H~2%y8aw_Sv!4+Iz;VEr|OEORpzy z1fMp)a!zmpe9jN82X!Vp+{QJPHO&3D!$7_F8&LPTkj|_9;8*DwV&T$p=h9Id<>zwl z;Xn{17x+&*9)W=Uut+S@#@`^1EMN7RG3Y!>@Ge~0_BX`mCT-qaH@oGUT|cM$Ms2N* zbqD}eH|Fm5{12p$GH=z~jd z9n$_KftS{s6XyaHGs@Q3cK#h@wH0=W)^u3H4vW!^ZXNWtHN_*OCVA1GJ3Oz2UkT8y zR1XKALU~9BLm3w{wi;JpUhGa=i8F2e(xNz=_Q@Q#z^diGp}-FuBSEdR>=< zTamSLiXe{FJ69?kS}ViDnTnLw=57Q~&Z?GnC$SoMYA|_Y$5(}Y7kM$?^2X>yr`4|2 z*ssl(mg6PFhTj1;CQIb<#k{`<^|-#Jr>KpdNr%D2V;TR;hFKvW?FxN9Wz{iT53pnf z3ItNWBGfrKe}0J25Q^g7%wI}8$0ty)W@miCi7EV}kXrE9*@{`!Mn$f-Bf1r~84poM z`3A<(`3o<=IY_9hr?aBd=@VtR-cX(fHJw9P-r;4Gf{fh@>d;F z)<{zZw)`DouAf0C+iR%B(eEuOVfV(--0Bp+hm3o$y1QDBu? zT9Rf|wgcbVPa7*E?Kj*sfIRtXtYr^?M)vU1OU5A+Se!N)FjO2n6WHu%hB%JVDoI)GeJ3W!{39`+{26~Vi2M#FCYH8No( z#^1XR%0gEKvL1F_068Q5ogndqr!A`M>(m0P*KuD{F;D%oIYgXK3suM-A!f-Y0=(91 z93nz@>?iB|d5St5b|?2oT9mr5<|SrjRiml%K@xU0US0tKSV&0d@<}=vT}c zl%=hCy@cE>B4+1Haj6yD)>wCW;2KzSjMidDBj2>zUXA+|#TN>6GWkD)6lg}e4UzYD zBOr{|%(M9YVG#wwTEZ1(rVGkq6$XG^?qXWkgSWM9P32tSGb25he^)C>FkK;yN9k!< zQ^}YmbEUBP-H-oR+u@1{>{quy=S9HCkVS~|$c&FjY7F1sz* zJqT>%=l@TnnX&O~P!uL)VhKdIe|-kW;j~2o<2UZQF`x04y1y$Vp8Dc8L~E>ahLvNh z3`VZhaaaM8vkfHI$wp}zqsiaBATGFLRVj-LnWNVcziCzLIl)?^ouLMis_jk-J7j^V z_ww(o6;^cR++V5pSD3Epoi2JLWb?mQE5QuokPg1mp=JbF^NB-QPS^xcZcR4d(zi9& zE#nRoosM;JS3DM9F4;*6$`Nlhr|8$TzV+5Va&0KP^ zFH<$wRP7{%m_HjZnurxfsDmY9grMcf*($!JGy_%}HF7?g!X(e7$_Cm;!*_`!t&WlU z4G3cs6Xnjk35T?HeBv9EQm)3)L+E^Avb;RP)y+U>zJZOM3q-%5>G|VNi_?$=rOAiM zlniEXK>He*>v59LlG6cGW7Gc_I8t|S%W`8lQe_$T9pF*qwERxzs7<^hdBP16Vu1en zCa4!rzICsQ_Dq@Wi&r{*{3?%sUqCuT3s78l{aykkjUUFKh7-D&dfV6PqrX$DV(PqE7lI|XzU8uv4^8J9Fv{h{%M~i zy4Ekr4=-P*JS$YRd8HE0Uhq@zH*mpfdNbP39E@R?9m<{T2J>6Zlt3;2+U=?69D^w& z>-bM&a`G&#nV_SvJBb!KJg1??)lmBTyPMw#%F5YiksFc#?G1F6a=rj>Ai3c944M-7 zqiU7Y48()qERK+%Hu#S)C}-V2^EMvPL*@_lQ#0mzk`+nb7C;pCYy>5HFr>U;oQdea~CF=)(ecIalTBw?QLuTe7LnT+N*1jFH z^9D3DDZScJ<)~m21L4F{sf-iAyxB;DwHsVl!ykp;0K|G7`*CtZ=iJ~ASc}WOH*CqR zApInrkZ`Y_%UcquV8PZuFAogQYsO?Oia+Az+4yK-roxlL0Vy_G*zHbv;Yc~B3RtY# z*KXfcz+ClSp$pePQ_IhhCTTa)Z7r=m;V*p(K(*2l_c5Auw^=-+I)YWUVUGY($P#xT zfk<9orm0d{d6)bcDh|AFO;a7y739ABd^be%v|UK#G@lm)>Sfb zf7~XoLjmtB!22>O*9tKoniHC5nSPkVEPMgTW?*d%DX>Kc+`8`(vq5CWRh;bwB zNK?K@MfA+d846Cn4JsT3oEHn*{*p?Tc6DRb;+!|$vakPp9dA)N04=@T@i9G}3p~Ee z8(uvEtQRP1>&%00MvG?dtvLlN?$5s$Pvp!Gx-V2LK`LswILDOB1mES~$-ajH84r<4 z8GoHN{0bAopV8v7mARKbt!W{*-P9f(N2Wmtd)8V9wpKFv8R!f)oT9LWLVueNq+$n^ zKWmCy5%BIr9=hI4`+B&wCTo?M36{Q?YwDV3O{{@0{wP!0qbbHHxbu56n#{O?=-P?A zLv;fxq$xLj)Rl=Dc``coJ#bjQ4PD`@`K*Mg!vXo^21|!ErjNa7*ay#6R_kMoxTbK* zRfO^hH@$&!n!Kw3`^n8*Aqnwy+A`DKj@Y#r*e(d%F8_;Nb_+nisxcr!2_E)CP{O}hMP7**65ZM>4nm&@xGe3$A{t&%KRD|&kB$mfHW%lz7KN-sZE(=ccejqPuI zSTyCJG+EGN66U&fm3U=dp5cx4wIG6Q1E3_qDq=;b#&A8Puf6FREroege2}IU2ww(d zT)9GzbXuw)PrIV%ZV0^rMaLF6buhfFERu+K0b=Xnp<)ebvYAol+&3)2xAt=tw@2Sa z!o!X6f5c>E$y)t1qPnOq#WJy^C~U%5UIE?sP}5c=*~{Sk+)epc^2Tgwz~hkD_my>( z@yh{@927q-D=wXEfD``*+x19^ed=B3(N^ZW9JuvrL4DL+@KM@5k~ zyzIwnz5X>dI~!Z*?$VIr^dw|#Y^-9*-uCjc&s-6B$q%gRg~1kOEAgysoca!L%dyYo zfVx{V5tCb3v~0rv^8M#WAAh~xf^F6tw+^6R6AgtpvNef|MP#4P>^qUwTr^2N%9BkW!(3R{gQKu z$H`L0ADV%e0ttP0Dz;viwrd?0x_nrr+KJ24=DLmz^;`lK9a+McWqF=wU>-nJ4Jp)ktX7oG@cYB&0d6o38^piD9H#?)%3bKNnd0H z^4z2m7s*zuKYw^oOT|pIW{@LEH%x-qqSr2U@uyd;#gj`R%M%OtfP2RVb%--Thv1AdoF+fjygngADb8}o3ghB zd&mOmtsKc@-=qqx^Fr(2zW#JX=lgF8RIc)`*T+3^!T$!x{g`e%rL%p6ZWGxs#e(;} zfZy}>`Vx;PPcPaUdK$2^KL!+6_yp&?WG@SN!_mZepL#p>uy;Fu!rLl|3{T` zTZ%Gh?f6#a{3TtxoIXj<$XXaY|E7NeU3L&=Yig*e$x?Akips05H~>?U%vq^k2ZIv4fL%*K1`AL*t+Wd?ZE1ez&mC!NETh>! zqW`R5;G|m}9*%D0xrV}Lz+Sed4sZVM=neQv$AjUWLTw|5UPoS12rrQVe1D(F&B{^2 z&a)GCT%zGE-xM6d^XBD+8(xwT!^>0^ko;dqDST1au=BRTk|iPa{X^GkWEYqEG0e^gyxCG42x+ikguCNzchh@#}0}b5z_DZel27 z$9jpy{uEyE+)|ak2i`CIY}D{$*BrYIwP*P5uvKIvf zIe_>TSW*7KeYmB8Rf??$WC7j8OMJjsp?^A{G69zRy1LA3{n#4$Ip2d~S0JnbgLd8= z{S50i?5|@TEsi))$vxTSRLohliw9bRH>QP(9Z>?QmwS#0+QBnd`l4;JCB`CU>;_Hj zT2LZF5{P1?Ms2ktIUf&C!I%5oy}kWe8{S#_2Dh!hdVCoU?4uJE4UbrW`oHa*8_QS~3Zo}R5tZc(&MU8}i4J61rh)ccgg_{k7dQLncb^uj8@44=!T@kwQ zYbTP^W~DKOEoApD z@KC*lwI6L_4H?Z4oqdm<;OLq#+=TXP^Dtgx*Z~lwnd~X|{E0MWPJdfX*@E6A2>wgd zD8vhIPaim7Bos5@iHz>siXA8Vy4fc7BObjj1ydj4Qa*svwqlCu>lJ{Bf>e)}t_-!tPuUycWvO@W3J7f3i zQ=g$sS>w9*oS9+;CjzG*;q7mr`+Iwu6?3zYhLj#)g_FNW>kk{g^s~5D6v3@k%hv57 zPd(mQlr8cGXP=MM2YvwjjK!Kg2+*={_uVNSTm6sz+|l~zas9rvQI&nsR#Q~ufq#dU z6X>D;Az;4%V4p>v&X(=Z+-8D-YdyF(#U~BeIvX#rWLBE@{Y3%wpUVmf0_%$qxXKw4 zqU+5u&$*d%CMDmjn}wFGJbrovT7LruAHU_Iy!8)4_e~ddu(Bo3n8D{m6(ahJpCG=*n^? z^9N{Un#YXs^32jL;W2MeRj;2TI=?`4xoT;SHoC@q_;aOd@^xR(67`Z1sg}~A_*Dk^g*|pL+8Ot;RRNC zbj-o~@bE~IDr}q6X+b_t0=}v(y*vDmG4~k)MrrIv2~;kbiqkEu!NvsAD`_DVBi| zKq#R005GOnY(rfSqny4SPMu&k6A z8&fa2{XLQve=X$`Eu`sRsl~GMHeQzY&egkM*IFQ%wfQ++s68i1XlXz zO?HJCU=^qHTBq5odOA69{mxZSGr`I%otDOEjf5>@xe1CllVheFr<+!^OjOqG90^@y zv7GFgFF^+QjC7V;SjXGrK)$K zu42mg@5YtGflDi_rLeh?_tV6Kup{NJcK_#Vh7S}5QptHbC}01-3?-MW&nWiPqSb@5 z(X?diz1L|!P&A^KizyDXNl*eUSmW96rsvM`_j_H^9Ww7P#tqe0IWyT%TrcvHvRj>O zUVr_HHo7$ol((YA{*~M--E5Bi9@_yAG7jaOPglu}yv7DE2TmH@^rj*54h=*|@WSFk zVAgUa1K&#IvttLlk$n?iZhyc++tnJ$MjOwR^Ga{m=Uq?eEwGi$KV_{b>b|4F@^j1K z*sk_WWXPCyFUEO9X0B6>HLtyal8bo+(;nahzxDN)RL`MI|Yf zBzFO>C7!NZEGAZTQI&3*JGLy05#8?dsMeZUw-j!dhmG*dFpbxe?Ezv)&mj}dDUIj4%7iy0aU(mSBZc=X1{ARX$e zDCG=ukp@`ml7x4kPM-TXs5QjcL8WnmBaxss5D5KX?3sZb0b4p(n*lmA=sSjlo`Bp( znk_XGpQ5z^pUfF4H!~H93g$*?cmf*_`+H{=jbh$`g^nJZr{H!6rRZB_I**?o4;@b1n4S0DsZJx3`n$kHJ>xZCBIYVGU%6CM{i9Ar?4gv z5B2N$KK*$9s(_#yABX|UcIe}FP1%>um1Tg+fNGU%*${OX=c0rsIE9Zx^s z62GJN=rr8PAatQF?yp>M$u(+Y*D-l&KKIY_2r_Lfk8H!UPs9kM?}gT%o)~qChckYC zrer~;;y@7FiP(J?Xaq_cuS?f8#^KpuM9{t9D=@b5)huJ`Cvqz4(0+q%ML4{QO)F4b zwp->lD^*hOmQ{vqAg(|#p>lGt|AOz*j4p)_Vtr>SPe?4tn;po=pzoeIBl$_r@f9I33h-;< zS}bN-C?0N2MWFQY)pswG|I-4fe;X)v-v9BiN@ru>OqZnh#xI(hM^bneEYw7K%vyFV z@J#I$ReokOCFUon%m@Oux97 zpemyCaBJ$~o7%@6R&$)ZUEQ86a1Lv!dh0{Zr^%MW{bNWjlOis6wTS=UvW`i9_lspD z_Zg0l%_`(5Q|oGR3HQrzAX6Z9MUfQkbX*}&bly&!qjg0g9}|FxX8XBG$?1tk@`H~T zC>10WfbTIl!i{5j`?^(k6b%V}B*(-vSf!<iFUnYVJZqd{4^JZL%Ac zlRmtiNKY3Wk)_i*ie5{s@x}s-iuG2DS%52(CNBA$EpqHTFlMq>2tIvfjjn}>i-bUllj)FH*fm_2QUn;@y$FAst`B>EO{!gj88TL`P z-9CZ@oQta@CYT$u;b>kZ!^fVs_f^J(hs0Q|(&)O(2J1%c&Q%N^nrakikPmHc_*7mb z1Ib5r$rj$oRvR_&1S{&V#T5?q*~K&Q@aU=}EYF2HVw~&wnbEbOgI(ekd*!wujRo!d z*3VXORXqtM#6zn9Mrv9p>qRNNtxnIMeQ>&FfzDKN^xX)kMtvYC^B79@9->T z)zZ~$fm^$FwyLh#zTu%1&y1b(>0bN2wGdv2hTJ(@xV3BiE$4m#TdnVY$I4_Oq`mh2 z_Y{J!&A$V0->O3pmmFVp5~i}J&VjYAs8(TeENNXIbjGRQ2B^BmTQNragffpbPY-#>1ofp-IH_bHAPb;BXW{n`Y#g zIz9>|U!uCD7mbQvLgZ-wvm^z(O^=^x*{`q7O85<{WIv>ZCl9<@q6Q4x>!ls-7ef*- z8n7kTv?S=%E^$hdH*+U!qo{=DEoLMg8jyuJCDG| zrr>IdN}V-QB78q~VgG}Mk3jlz>y+#7ezFUZ%TtpCuX)f-ruTJ^#L(V1+DxnL-u6t~ z(IP(Z3%{}#Ws_fJ?|$ua!C8=9;-kZoOZnW%q;#B~V>&(WLQ$Mv?cP7ilfBHADFRh0 zBC3NRHM=Z|AVT_Fg}Ay`+^$faqS4Y)3^UeER(6CD5P#w5ZMA$?x#V_%f{gdck@t;O zRNF(!s-JeS5ad<~gLfxUJx8z1aK&p@s-r$Q)B0p^p;O6fG2@)@bhpox1NN3XHyF9@ ztqpx@8BrP~26NG#9vx4gs(2rsXV@k}4F-bUAi)StAU#M6_{}zI2OPVlxt=t*P*XpF zN`ZJ^aQzRyzLFeZ2#x4HxmS?^KR90X=q#i*kwiKytFE=D&1@)PZ|~*y^VqSZfdYd7 z(=0M`%P0|vir31S-q(Kz*R4)U0}-LH_7uW61h$=i574wdqm!#H$G_f zL2}^2vnRy0+p6xYbqNeaI*?XIz(C(64X8R@7o~;<++iXm`v!iYhOQR$0kr91*1Zty zH{n0>ixS3^M4R`s_8`;6I9vRE3Acwcj>J};-LR$GVHh7_JGWj^PDN)2!3pXEQ+%_M z0{Y$bWjjKg7YE{v_s{@cg6?`>6rDZB-gJ%)U9hTCtW9IV2gEe&h}WY#GzOUb+NEXN zIAX-21MPBPP31=(vD-}@37U{F(u2{3xFa@B8ocu&{E;INw0~5WS%Ml$k4}+-sjl^c zVxE`!(;ro=ry&gM*7%S3=>v@2Q`B@sXDPn1nxxFKx6*!Z^BuTMY&jhwl2ADD^c(Re zelIz8BlE0$FA3zdM4sFJpnCWuhCga0l9pTTBS()%FP>T!&YrDslO;!;XQDuq))Vq4 zY;6z^?m0E75VG%WP%h$_KhMht`x6t1>1lkg;?Kd z@&acT0%#e3DqK}|BJb$B$=wgT;bU3ar}OwYE*A#a3t=Mo{&8*Mk`mp`65^-74gap= z{*q2)Ia*CSyi(`Nufvo>bUkuV^^;qv&495o)r@kEc+xAL=D~SsJ;$+eK5uy^Y6MfT zdgmVm{}S20AG36X6m*+d#?=XEIrD7V`ME01a@f;bM1tmDm=5hq zT8(j_J%O}mXbK0OuylZnLXJ*fJ?(t|HI4XJ)&X@jo#}2HUFC3CSZ(U?-74VHc^lm| zWV-o(kzW=OKr9A8`w`ajoqy*$pD~in?DVFkx()xT*>s|zTiW%AnFRRRHNK1!6R?X@ zrK|A6#)c;~72rKb-M4@WLr_!Ouk1AY5=(LDe@r!WKtx_CA7Q^Z*5cAR4G)2CMlF^w1?kQQrmNw@Mld42DYBJ2ro<#h4%JZVX zI>6*M%%rG>=0lx`SH>z0w!eX1n<_9@iA!ilk#)8Yp2+`U@oM+^y7Q3{cVxE^L!B#y zZ*YNA3UR50NnAKk-4hnP8qcG(#i`Gyc2>T4U0 z*Y66v#BO3PL6_s^XMxAtTvLvYcvQcBi<#J@A2Zh0&}?5H^oj8Qysah7d4DWP#>asW z#Oi904EokntZPiLwPu8*I%bSE*MPG|AXg&8#yJqb9tUb7J#Zs&m8ZOM>oi@SXfgVh zqRrIX<#m?{d*x%gPt7QEM<&D2JAVE#$mk{Sj3ALQ;8pvWe=c3vE`}7+?_=)O%}CV< z+fRC#-*BK?V&=QWUnN5lO!rb;Wa`MgZTYdWpRo6zUj%%j!fFyuv?kBVk!|RtaP+id zz%odP^Zy>SsDwP%0YT#sppzeDFn9W9%SKPAwp$UhSr(j17*9B}xF}~~<^7tJ)Eqot zm-?fJyJnyH5s5jO>4OyUm%8e-+Ya}2;?{TH9?5QAY0OKTo!{RP1f`d{q#xOTs0DJ# zpJ{z{!z$!2T=gg$3+_G%WYG<2r`>~`xpabOZjRxX zV-U7E{4!QIYU6{uGPz+@M5Qj_%+a?2O4EfZ{qKep-}2GalBg7Drb$WV==QcQG!cSG z^OPT0;+|XQqv^ zGS|Zqk&8TtYRv?+AQt42iq79RW%ZG@7u4kh9_`-a*6z~gd7%}njW?HY)%3h+eTNnp zJ5lqov{R6%BH5JatHy8xjO4P2UYlSdhG66}qpFQJWgk1z3%^JLoI!R+k(%`p#X>99 z=Y9^Y~)(W)(ak~0Jn=aH@gw)}<3D*+`98g7abSq>9Y8k86 zJM{l#?;F$Dzh*b=PjHXTYwhIT5c9|8Gh{FApTMfN_sBexbhWbs0q+J>7c0e;{meV0 z6Iz44xF^RKA%q;4D%Gk%OK)~E$VHNlNSJdy*w?#eR4w}|=;Z&M>D8PRj-g&HTaiFb zJ#Q?Fle;XNBJox$Jv0$`3gTL}z3(HD;qO>PwB%q_Qus5vmG1)Agy_xf_;81rb~5Pb z(p}B;$UQ#4)6phMT?;b9_h9MfKxuGsST`Cxq3Q+uco9s5e6xyujhc^o7u1}+Xjoci zNhACzW0SNYYxhT^qi>$v)Y0`_EpGt!#Uig!rIPdk&CxZ^=Jnl_&#`4=QW8aBLl|oO z==uHMUtV?CW8|W#=%{afZ|bQB>PHgC@8APQ2ux?Ni~z#AhY3WgjONTcQuKtlyNcsm zbi`>}bVUA5LPH$tEwf_{qrN&{x+E=r{B|+%j`Lk7FkXGwM7Bp%;BpM$fPoU_VpXwZ zR19C)Y~O1j(GMtx-@4y2R2jb+ylK;4^V08*=`A7S?wf&V`;IA)H-k;XUebOja&;DTqbn; zU&#yBV=Pwg(I|Y5--6QIjvD6ZLS$dEu?8t!?JuKyEAF*8{=wp!`Ft9Do9U-&P;g)78i?I+|K!j{@m7^|)Uh ziq;&6*j-k6c{hyu6#`l%?2r_5QT`AN zxkNFIiRoV39j~{OO31QRS6BC(jN@Cqt$nH1H++dJlB@*^{?J#)q@Zi$gC>V4t+tFm zOgxn-N5^fo5?9la{bM+t^oh}UerItv{HKQyXC_O!#t`zl&%W{iniajrOB7cKy2o24 z0VU9_Kcp89%ytFY!JPh9I@ET!nsn73?D zvs)!YLUN5VH|*=cyoS85zvmlwcXtrCxn6>_1R|ZBfw>-Tyc}Cz`EcuHOUc&y`)cnIN*#}xrkgcbx zkC#h)(^q6y=RujexsXr_4p$dv!hp#;9D;0RMm_VNx}T+igXJu!t7ExxS7U$*gj^jS zvVfR|Yh)^m)q#8V9w+d+!M(Donx_3sk)F}~iXXUa`SEcuy!ru-SJUq7*x*Kl#mQ<*rdI-+QI#_pBGAR$U7!-G=({sqKnVOA@nvNqR&tZ<;kGb?%sqEY~Ten0{Aq z9n&QcUxK&@QM7LOY__QlgY1rCN$ozhvTAl}CD5S-#kpr8SO#?#j&_y^@NeE|T6&b~ zbr69haW-A7r0Z8sqzG7QQ}t04a7IL8gQrQoKgO-~bp5w9`1O6F{^QQRn2*;hV_~P3 zPs`zb$3~xJnG=1f&1lb_ikK}dfQW?UO=`n5#}adAHN%vr_C#aS7*b++#V<8+5{t*7cXWtAFRv;6BEYz zT+9W(L=2aYE?7$GDMjjjo9I2cp~@PMDofWZm!8oGS?k=P&CBctbY~mT|D^U!!`JWCcOmN%8%82Mc&6uo$kndf_VSymOaty$g}F2jlu= z2xA49wB{e99v+L1xBF~e->CtRjSbz-8?%oXkPJ!>`Mtt~W5f8>C7)GifluDvdqAbE zD?duG%hj@Wnkimg4YTU2!$@G-{i`Qv3#{}Lf*flHDk4=l&1$macSDX!Saks+Hl~mm z;m_S!w;idE`8cr^sWI#+nNdc?)O$;$oGl z)9^n%Vd}TK8IAsVn{7YxTN^-o7v%Dov+@u<=EF+{e)4KLIr?d|-q6!FR}e7Tderh1Zw$h?k`H3oaQs zBBKt1cG=Mvar#3e8yeV^rGP!hX1=EJj-b3Jv@%0)&O^=9{9?yBfJRyLXMpdmWtQS~AaGCsQ7vCOXpP~<<%I(?y zf-La~9Y^Cxj&U!}FjGsp&!b0A$O`O`htGtwfLKb(SR{&y?|Pz1wt34h;yc2gGxTgCVZGzL+2k zeQf+oEB0ZGKlgXL6;OOtx)=`zii{sU_H-YpR;~*@Ad@NNxUlOk$DlN67w;X`F=G>D zbMVj3ZDvp8lQq@cax-y}R>@d;K1J)%mq->1#Ykk@M}hmGzbeXO+S<)@NlQfeI0ayJ5K!(O~hOkruW@ z6*V!!M-#2~)4q2+UH*mbzd_t7HYA3$JwJ3+5 z@gMh4fo0yVd*cChKRs%nOmEZV+)8!t6z*r>x)})0q)BxghcVbLA_ojwj|wVNvDzL9 zMIEJ#>uSF_3D)q5SL`1KwzW>o%g>+e^chcS?Oo)rzaK!{G0wZ8-x^TS>5QHc(Hy(B zM;=J>>vFs`1bA$ZJzBee*1SMV>kI>Zvy~$~lB;GjcV|XWQ$n&u=jb1yr~HfZd^r-5 zIc+aRxsxyWWQyVG*cKZcW3jNvX2oh0nHlP$Jou1-=^jxKj{`X}uti!y8H8g4_6?s{ zIsQ+$n$fin=5U3M^$jt*De=PS_FR6RAE0DedC$FPq3m>AhZz;R4R zo6ek*W85NTBDS7MN};5-wlO05I&9JFdsJ8?;FtTq%xQfi#hstV#l@{jV*EIIeV@Ee&jx%U^m|C1y z9?uVYM18QIdN0LM=b_terX6AFlF(qqacS1LlTPh`p{e@gugqr$Bv4#>cJHA&20^%> zCdy5hMmwpLjFv2KD=U!R?Or9jGP1X>ITi}cQ#(|eTR0HdjW}0waG1I?hXCK+!ar^M zogO`(P7?I7tn?Q&QDM{+Y>tMRvo3KoW1^-!#!xSlo$KfMmpgPKo1-->`2~XBW5;`-(?!=)MQB4RBB?=!$ zE*IZar3cbxtA@XXP@9xlg7Nd9JXztF%&b@$ecUEY8h;j#1wMb{$OIV0@<$)GE8zlZ zyX{RGu0*+cNQf!Ex)YAjPdM3%*cKBeyqLCA&lrm(=A zijEE}*u>LB(X;utgt(?&5&z$olIY7yOf!}CKD~7o#i#3ij0O9X%WJWKy~w>043uK1 zWg7YOcnz}=Uqp3sCpRK`+2?Gv=%Lu7O=>WyLbRN4aCkBR1nyN#oT5m3ErC^qRHFpt z-TC`O04Ev!gQFh)t8rr=Ws`_IU#|yRF)|F_<*24Bt|e48<;(7>+YCi}olsBT(m(dB zBK?DUJ&wDY(h8%27I0J-VU=Vq#7dnBRi7=|f$&scZ}bZB&RTyeJ{OZNh1o+h4nCj62LG z`ur=bua5j)QjY5AUtn|aV+B6xltT={!Hv#f@%B9z>-*(jJPWbcvzIYa#Dl*vbUhNVM9qbXZe2Kp}&r- z`O~T3{ZCrabImFTjz-)OZLC{$yg}JfcQ=~07k=@PqeQak;3B!=IQ~cP@8`h8?TOV* zqYR!5k)Go3YxtuI7nn;qMZV7*yZ)ll?AB@M;N7F)5bqa(*CGR~Oe_P_AbxEfIkt?b zY4(J$FQTa!d1uLIlkIC}OcfM!LEXACh*k-UVWEwVY@@OYLK^_B0wm7Zp!#leuEy6R zKs~JA3fpF>5Dce_yJno642}2Xq;>pxrq7Y2%S|H~@i(``lp%gpoL~@b9>cP)5(Jut zPHN$e4dXh<@8+Du@o#AKK|ex;mxdLN4f8VZJe#P@*c+mZlA^}209r)!gUM(k2%!rg zM!FsG%&-BpJFIG9L;F#_C@QihL zWUk0%9eW;6mH-nkp*E#W9=w9T26OxGk^!Lv014>8J(7m)ToTydUwr{E9Q}w9ew`f^ zn&eG=yy}UZtcJ>6J0RSFfD^_6HnlC(CthMNb}xnkc#o+ZLb@n!0 z5CSpt(U@d-@CE||qsR0HNF}t<;b%}fi3C=QrOsg!wJ{?o{s!waTyeP2wAGL}p6!_e z9U>)oy9i9XJ2j~(c|0KZ#|w@}{tyPTA5#aLnO6RuH`!3ovf?jJveqa{WIFp&qD*)M zWD!7_R$)gk-{Inreo)B{tZk_O0mNvYhRnV3=JoIXAF1(?_6`aJqYCj#Ih}Xkh8~sz zJexsknx1Kt5xA?TqraH;j_W>E9eeJVRcJ$PSZC^GLSBp+Yj9-ByuCUbQnvoAHO!dQ z)bZmURwObYllmU0E`Wa#YiY@ZSD(h3#3`9k!;uq}{a%$gqY(0_9X%BBe_DVs{Fh*I z{niI8yVj4a3&yF@aYvO1jcITZ0C*|el7k?oNs;`KaWM65E^Quci!GzUD3}!dx6lQU ze`?zwze>esA)PTZC>{E>BLd73JwwmroNAlfMe>Eclznb9O)P6rB01;j#!V3!|Q)>3*wop;QC$Kz8lpR#c7yTQyv`ttbE!F5;K z2kU0oi^a_pTK15M%zE%2T9LPiU4NXD6#fe}3O*6{s{sjxT#q*1ha|8)mM&*F;VF0X z;7timn4rj8DHZOL%4&vMhVW0VhH+F9_&kUjV`hZN2v@e~j*=3In4ctjP`J(cqhYxA zyKBkeKaV?Ub(oOqG#%1X2?aXC$h+U8pQB3@DRxEG+3MY8CnOP!KnA2!zxqO5@^%y_ zi?IZbE)Py#AB&g9$|dM9)^wEsK*5mc&P$k7$1wedk~PZ$$4i5EBcD&#nbq(H-FV;( zKuTFjx2K>lutOt^#}}r@k#L~j#fkU)r?Y1l5xG10L={T6$AP2}wuFi9vxbP65#()z zSROp8tnq|xL2l4Gp{JwAkTjFAv7L}?QbH}ciobPirxg^41=1iL?A7LP>`S`c)46q{ zc<*{kNqCn*T`$d%G~#`pBpjwp9tPx*stbgX7XV-Pa;)rQOBet+ij`R+>TtgNl%-Wb zW^z=IMKthk1UqHBrK2OAi)MfDJ_+}?3`ZS2UU-x>T+o;M^DBTOu7AZAxUdndNrNE~ zypqLSOo(hB>Mwf8RYFD8LY-G9B@s>4#V)thNnrWRIdPv5>ti0u`9MO7nan;0MYkdf z#E=ZcB$j-nsxDw78jj^>+Gl;u7)70|WJ8nm#c)3kw;qP7*v*g2cN=$~F%}Zydl98C z_XacRYN08=7PfL>H$Z6aP5-vU8`ndGKRRSdE=Ho5&cLTTs3SjqvQgM3$wqlF4IR~) z^MA6MP|bRr-R-hUW+xF^b3IG%+Zbi);Mu_YK-BGVk^JTOCXk3%f8Dn&_g2R+9w@J@z4;s8XJpqfNsbE7f(X^w)OEaQTBdl-heqUW(9ne$P@m@CE)Hd4B}!@3pH})1YLw0HgHeh?2;Z6 zlEg?Nr@87to=COio9@MaNzkNQixf52R_}7qFOoh~*}Y#$5vzPrp-xM(f6l*A%;=2D zHv5Bg8)r9On>R1Y4EEt13DA8}lBT8h{p^E`E5X4X9};c}S{avT?6zm$qoH)f0OyiT zy#!InOTi2z3WT@cz&E+>0^*f>*4;2}A%1=OF5O(F4%a0WHZaZs z$K*)viFm<7(QKO$Bm(PrxAz$b|>BfsF(0DU&@jqE_T{qcQ+B4ynDIcnCNPkX{pWU=+vcFPLMqYFC3UsH22E>B5j(aY{RzeUEW3 zwO&;k`k3+eXvwA0_Fc9jZFB(yJNRfv*eBLPM>$Z%9I>l_Wcp#HtzP~KifQ3Z>;aIV);WHm8_(NkxgEO~`6eloP)+VHKp~#!lUGSckulB; zE3!+xsZqukZu+AZ;A*@0cBjHH$!^GGBjV<(-?{bzaZ9#6D>RvYUNy(-D>8R{(X6x` z;cpot9v@nwq0fTsbg8hR&n)34PmcjX1KX0y(E$VJ)xO`%oy`SxnD$$Sp7u(pyl<^~ zGi*fD!n8u_$gG0+L%!I4_{0le0*B!qOMTRKz0@`y!SlerV<7@4m;!!tdq6O#q5uML zKEb^n>75Tt1zN-J>0486-@-FCv1z6M^RPjF#-K^>^Ycay*NY%Mu`hxtC&4aPz^yym z(`CBj8+WwI);2r-nd?x;zH=15D(Mi{^g;-$!J2FN+fc~D(u#=rj*|6Aq*X(rYKNVS zC@6T|H6B1wN^j2c_^fDC(e%0VtYeYke1NuVvsW=7q(rqX{xLHl5}x{GV*^j|-hZu8 z{w;75kxuQY2qr%G;XQg#+~bvpMc!hus>T4d+x5*%Z>eOI5m|6`)s#oZ6efxaH; z|9_QzWk8kDw(Ukjx|I&;?oMfG5JkGALy%Uwq*EG^5)42ZL`p*GQfUNHQX1*<&8_FW zd*9FJKVkF5S~JHOb8Sp(aV?%l4;kFaPIik}y_)z(xAN+eap=v$(XebUEi9$nMaAj% zi1e<6t86`^MfiQAIB7z;nS>x?ikdvnX0yN}PT}y#SSp_Qm=K}HOme*1C(g7N6;S9O zTBLA`XRe`6N1qt#paRKe6NN{S&s7>CL)+OF)d_0ZCYFu3GB}c!bS~O1M!zTxT}2Nt zB%%Fl*Z%apL|i3DKGJDj`&~gQ43ud3TLPTA9!Va50@t_IXmFHxY62lrf?&(Xxj0z> zH*P##Vt+t~+L1z0Yt^-+Pbq-it3=Sp%CH}ScrP|ZRb;a0za4PUfrwZ&K%4t}kL8Zj z0CiK=GOjZ@H%teF&cm#Reb>O`XD6+>XHR28u6(GCD8J^8L-#G|VQ3{g2GE5xJu7A zwOQp6BpBhJl~`?Zh7^82w3@;U;fnO$E5p-<7qY*a#JfSCvXo>oPFI(#V^s5AEcVPt zrLtb&D#}fp1KL|R5A)Q_>CalO%}F4FD_V;;s@LT$asm;nfrf~$p?cJ6y7wd3-K&xw z7V$b>3`&u66wBW*_fJ-1+4o702ik&dwm*Akm0=}}$I;(HG?^~X4urnBeo~b5+(x^KmoicFzNJVC zV^aL}awrP{e|*x)sw?40CdTRP32-9U;JkvA$Y6PXgJ55zzvP_Be}sPNSdvR9dfLEp z*cWlud;+nZf`SvuEBC&T}Tlnq8|yJ~xtR&U9Hy!xid?}CKKie({bV3Fah%9SaZMRm6HTAm#} zmOOd4RpiC-un~T#P~9MEHywN=v@lVNh@F3f>;4QV*Nvq!PfdH$qB9kS)C8Atm^~=_ zNFk&*w({yl?2l)en;F5Z3oAM zkoR!kD}%L^P6 zeyyB>)6Q^>o#{u2aqW>3Y?W5zlPxu-imV=o#)|hpzNtD1`$r~DN4j53z?3p}quqr3 zaeTNtrIs{-q3{)Hb#iSX;%fg;kt~sMISOUxLuI_C!x0u5x>e$xkEoFGJv{`8#;J~b zSH-0Qe&Ef>I#=e!hql(r8AjX`jWc1}ce0Bk$66v?M6sYV6<@*3cpmW~V0V4K;h-h< z9#R4Mb?)L8d1l(s5>f`%eMPQVaZ5PiK=f)wt_s9xJrSwZ?EBJOD_nYOvEpJMA?lPj z?dir?vzF)GrjI<)wP#Ab%0V%w z0ePKIRoY@uBegAje%`mG%P#QcXgMBS)!uD;Q1#xfl#mTqz)PTU0j>ds*1Gp-{~%9D=dovew~# zF7x1g!}Z2H4wsrkgT%w_wmp}}x0W#BD&C?pPtu1v4K#Uv7MY)u_okt7vRL@a)$mQcZpG<|saHn&Zj2-IaH1^fL9ssq(v3Q8BeV?PwFY zH!*)Ur!{}SQD9?ofay@g2jG=@}E@DuI zH9PPAia>!b@}18aw&i)BxaT45OW`i|zO3&^A>Rjc^2wGFn?BV_qP>&BjmC&_>6SNa zr5AoeL7MWiuziW307U{vc)9}dpMM=;TNk*CbnKhbCD#F#TnP`UI3ENqYDGvcl(1o1g#UNaztAtgTW>V!y>?wPfVSTzmARl_h%b0MrXg=NF z?TLS=YxL;s)Tw+#Wt2NgZnCX%WIptpPv!S`4_FJn3xn%;-_Y_RGbrTg=o+J%779Utkc~fyJ zF&30zsb?%doYjVu0<4n`McbfmLhfge^I=eS*FML*JLz!o$k zlkHr?o0q>=@f%HzA1a+LTb3Fgfe0>#M3S)9%%`){aB@owNg3@ayvhcOD~bgK8l*JS zK~o&}5xD_m&L{j1*D$Wfha*RFD5=>k?H1SFURv;BpH$wVToyr$_=t9sVjIc zm}X6pcLXf^=f$aJ^o-}#)?+-%mXT}Z*J-kxc*He64yHuRog8jR8T{dtd7CE&K<75Zol|I=+(pUfm%$H-aHb&Q>a}J6GR?53>qu_k=81_ITmuqnE(Q$&*b-aU zBpNo>adn)5_haIE0142nep{+mcANY4Zz!-+HQr+B9)7>Wk-4q4y(9YJFMeFTjBZmTBFUK@Jccin1Z~3Vdt-OO{$}SEv$Vj!Tb}ba--9?0&D3u7;`NM z)7{cHskZ>BJHXP8vtZ`$J~&N{wVsZ8h_5U;uy>Qy-6|?KN?D$Hu*2pqPA!GPDmn=Z z0K=WoDc}CXRzOvj_F}||p7V>XxH2iOK5aehr13j4z*0k3@_C7S!*xT!mWhgWoE^OX zDS}nyvqot2L-7z#e|GLnH2lDdy^~Bd9unc7_Iao~To64hEy1O)@@ec*$g&p9ia0M? zstJ)z$?TBBre#^Inj$ytLCYS^gSU0z0kC~$ zd9qX(pX4)ETh;8*aZWf6+S0Cu4Tgu2;+CMM6ZWhBJ|eWY7d+!r3pKH}LnZ^}ZCuA_ zsesIJ%Jva;ihZ;2k0#D|Z3eaP12z(~eCddq$W%_Wo# zqa2saCg`_@SQIkoOgTu@YN>Ywv8&E$MQq|`FY)v%xx==6QIc$@Gs3o| z#8O%fnYC$^3>0TY#0}mqxhm6vX(jk{GUsKX?$%E)!zO{?K&TvcaJS(8hdjCS|SbYLR2Bpql+6(HcO#kxiQ5g-jVUq+odpLtLv zn6_LnWk(mXi7b|qzG^e1G2Z8rHA%<`z?>-*L5+t+=y<#pN7%o}L{fbFO{WH90cMed zrVIg0J6Bzt#%ow1+gOg%164^>%c#q|Re&6%=b3b=*Ze$5`sLU|{- z0@B{vElh5<7fd-|YPR_z>W!29dT6@XA5$${Bda&k#<{9!_Tn&Vl4PAuffov_96qFy zu4n69zA>x5#ULBF&$LNQ{0M8qWz;h+^)}PfQWg7NZ+yY{aE1YSO*YiVp>O|`JefIz zo*lHLKtIv+Ro??xFWOdK)g_>GDiTpKocN#UxqDSFYEXm0ceDBDSx%#OdOyWiQyy4} z;zA`h8u8xnWHuV)wr48+a|c5mbAQNnM=#~=x%kTx=u?3m^3=r9*H_VL~FUqvV|>2+6i^m25;eh;@hn7 z^k&H&JOz29G^}ZFVmd{KOb5d2*v1WTtEurTrLM;Yt+-8JlOn7N6rJSN)v!))%k1b* zaasz2tsTi{EX+?t0R5;we~#&dl*54%K*>d?U%iGM5yy5_Khy=S56$KJTWjxO4oh0) zNdL4@Bfd$b;{PoF{@afrp~7)7jr8&hXpBAIj}~2JP_q9N!Z`f%v{=yIao%h{iH)EK#>XCXI4) zYAKQwp`6+Y748=`izQ2>_9%IV5z|akJ4Xh;sJ?Yfz$)v8c@r0TT)BBuE&02#*5f^O z^AjA`-$X@;OGFP6FG=BRsC}}V^9qzFYntjpJji?9Rr%BrJDw*t)?{8iRYdFIoPRHAuf|N7( znE`CCu!Qo<*9naz2<{)&5F*Rw&{E9gLzo zkN1bz9{h2{gwKWc4}MerpnZAjH$SuH_YUv)Gly;_aXHx4)c|(&O9vWaTR=AIp2ptp zp|%ZWyVkP&xj$Ldu~ardkzaL48iA2H_HYUU3;~nULR6>!C&hS~Q+K zx}bWck36s<2OYsKea6uyWrTZovG*)0L5mGh@CURp$Kc09YbA#9w%lEqyVsn6q4V@tANsbxviu#TwKB{+jJAMD_jl{L1vI2&r30TL&j zx>^d^M;>H#SNx2tF9!E4_{>Cu-)$Pww(XHni=C@T9@??_CFe<<-lZ1v@2Ebw46oCD z+ud4md6nrpnGVgQ-3$(0yXgOF5l6lpjio%Edli{A67vrV{-RSb0Q+GHU8wzV)w29HF$1BiIHFLnE@|V^K zpCRV$c;2HT?=Ti4FFl~xxbvCn&9hrK*QXktkD48>El&6u4Ue-R8PdkPCL7cKK^);- z=hELmleK2J{Mj%;Sw0EPM=ORe=>&bQ^&wVU^G@5-SPi$3&#E$>=ffi-*)uZVU+@2T zO2Avtdh&2)o0Qm}5a6JFx<8zUo7?TlyaAduUMl#4y7>RloUWC}f%6**y$`c8ejYvi zX&0nEVSlwl5B9^C<4rX_jqz}5zKbSW236iSiU37aaddAN+vsU%Lf$>zlKp8WhH37? z2%U0vtND!~fd=V*7%4@3jn&wR{;WFpmLL^9fO|ms-Nr}y4JBVI#fe4pUzRLt08!H; zQiT`f0Y+E_-M#m+Sh>RrVY4^w@U!FesmKBfQViRG4fuWq>^_-*M?t^mmbE%LQr~fP z0@VS%%vG2^aaP6RCHfg&qZ_j*KT+%-M=G}}$In<$>o3dE%i_%-CK0~)BVfx|_m$9$ zVWpzCBo&`pXLL!YK^Snm$mxMwN3W99SO|moB4F5?X?Z)Xg~GaVRCf=}@=q%dwBoD} z<=n#jH?-KJJ3vhe69#L_O7>ddB(=fRwuOX{c?%be)8A$Eo5uZ5)w32dR-*B(#UYw> z!(B(h1F5Zp%~Km$el~roZ_H|y5%zz_5o+Eim#;&UHrY~P`g_Hh=b4QSUwdT6W#71D zKzN;n{END#wz8|NP53#i0}5L#IR`r0_=3ra;BtTtRJ{PjTFu47H-2PCwqZj5)dD1H zu0-J&&73dnCso{L6F$#!vNJRr;_yiZEx(M=dOoK76B8z~b*9qxQ=J}DmfGMnLdrFk zQaOCV0u19k^YhaqZg%C=mOLoo^{`6g;iW zTQ8O9+iYK^V8Lrg!_qEPxGMQ&k&xs1q^I#z?=8kD%R~BgC%YmqcD4N3qJKpTzzO7rt0>=j-G*=%6R0CXc2SmQ?GpIo{2? z@BQoNhS*aG@6yB$f4S+tEfAVKFgXtTL*SvJ z!fv`KuV#3U*kf{LwsG@_Fg(3dR}!o#JJs0rD$Z$)vOMWqInszZv2fQf-@X3aw{9~ZSLa19rsL!PNx>wN@G<&#(FVO7GdB-t63r3VaTzdtN~ z{ea%#n|X|gqj`B#&Rmh7TpHf<71K=Cf5;f3;&QmADIlLuhV1JEMsKkhcc`t;8n7+) zljGtYTeW=p_^!uMOxP`i55GoHAgtUK^0s$J93b5{@oRn~=dV79OXs_jZ545@ysJ2+ zuaA1-T2Pu{RDdnF)z#biVKw`$Ea~1y0-NY1|LE~zU_6{(*2Nb zqx0*xoP7%=_(tKU2M_Q@aEJ$nLd5CyU;B>`LsH`PKgmHdPebuXqqoLLP5#yOJt-4+ z1b1PkNc@xmsY6}cNzE_kbq>Y0lwppxDL1hW<%6mD>Ss3ds7K6dET zC3Jln2?UZdb$7*WV`fEVq6al@^Jr19sk|`-84}jC1c>jECVps1$R^L_w8>B^N5(I& zzQ~Z(5R45AklKSvv?=5cP<%jicL@j4j=h zCEXZXv%I=8Ehit@x{Ze)5>U*Yd7N7tdyM24%)+nlaHT9&{`7p$sNf9axJ|mGr#8F> z=;65{-nHQ%i3z)_bXzIokZon^bM^!V_Q~hG>MN}Vm2qY~)s)a*q=wy96hKP(z=Ud@ zR^7_@V2^t&>j{v;xjp<>=)uVp7Cd)aUeWbcNjVQbwdWzgKKT*m(q9?Bp#+#2l#n(( zenf|%;`-2TaotE+(izF{NRIRsFMc14R&$^VIN4*%;Bfbl9@GyoOhvzI!2qX-;5rX- zlGL)}miZ!K8IzOCLYU!KAoGIr0{}0;^^@&5eUX9%c7~kjpA4!bKw<^AK_7?~0Gelj zS2`>}5rNd1kB*FQzC*KQ$)wYWsAjee_abj|$Ior)R%Iho1;$`%ZVMs^QGB?D41-;J zNqLfiAbvW`_*}qsAuimY%@H~2DMJMvNrzME19 zzgI%!TL&Vk?6OiSv6!JdfT{Hv@m|Lb*~v&y{<(rNQ!@HIO>8^7j%9PL$8tFb5JhP1 zi2IP{zI$??brhnEiEZvNh+EPuJk;Ri1muw2kH!owOJ@E^*n>4{otrnzmpda2N=#+t z6HJ)k$d*YXCP6?v46@sh02YA8ltgeM(Sf?%4$MN&AFel;+~WJK3SA_KIg!;gjOQ6M z@@k_CpjeQGzMz2?<~3T5N2;X-WEVy;3B_T>{3Kplx6**!rHs}+vbkl(Cp2AqR=B-O z=tA{0d>hhOmmtY_7x0rfQ1Dc5V`e^#(fpJW@O#@sON!8!h1dW_>p$&JILX>ngC1Zo z=v0y^!%7TF7Xm7~YiR)^7Ca_VNSlD=wWY(bE3sOv;wR51`s?(r!^Uio*|+abFqYK7tB@#8vCyYH};bL0Fo;+J`%8!x&bm$ zgg#~79Ic%3gk=pu*a&&Wa7A{$%TXT=_K5(&myhoMJ#r*$gowB|;wM-m^rC!TM>&xm*xDp=3jwDbK`tZC4=(Thn~_s26q#u(oU zG`@7!|KM4rv0!!>q3G@aXN%BNw%ULXJc1YeBp+%RG`XD?UM+0zxIOeRYpvOrl%w4n z-_g>-n{*IXp0*@*2@1s;f{+n%mXvuIctkLz#72a+9xKxRPvIox4Ha#)4k77_I1=_sU@HHy{1dL#gmMx z^895!Zvs5jvO=h#9|)^W0KWZK@5-k}{p+*kVI$CkU5FDk8TtJ(M1*K!q;Lncu%?j@ zN?St^oKjhi9OQ>?oPhV@8dAG!CVqfgL(scd8EXZjT%!IYmiIjo-@#ByoYH#v+6QDv zrsFtseVwyy*=Nv}UkUr{e}@FlCoU6br{&*YmA4KV`A(=NqNkQisLqEG7{9G!8=!mR z|HB`giR)y2esz*`jxuXtjO0^CkyVg0}ZTd;fmG#ka)yLZn0egIVw?RR0vw@B%OM8 zI9%rVyef{!GIH;Wl?C%;ZKLX|0$kJ@qtN<_x5@IY8XxW;!7MmZ3kN_Z-sVdYEG!z! zrYLW$mz7rl@Rvxk;E6|8Q6uT>noJw90*C=e9;4SfSR%TZj#$(Bn5dH&Bo6rd0~#ja3d*+}2wBfFYYtg${LUWwpaE}XiMDj;?Sgu8GG z+tLEk2$W!0nUp(9#RBIf&&hi+d~`n~?*i{-?RTeV>Fd=;Q4_lpa{?#!QC0;b6&=W$ zHs7#MOOYF~0Wo%JE08umT*r9cu_-Thgf2b5{5r;`FVYd?_2QY!T)^7dZta~36_rhKint{%HpE@8}vAP$Ha++;b{k}mInemF$ zCN)X1T&N+K%RhUM<|^AD4Q4(S!ig|C!{koRut)vQf*U8_8rNO>m+y@5dx*x_00%+5 zbaxs8ghH21`=s)u8Y!DntR4ie(`2zG6-z#$S?CNvf-YP9g3^Zh>Z3s5eD>u7-wuR_ zy@SH`{Gi4X+Agmv z=N5}k{DjQMKP6cV(UbMnjz{}fA}X`o2$3S#i6TQbuWnnrD2A?Zcz3`Dz*hNVUzYawKh)Mb`j zDXiVmZYXBRmuM~?*?O;4VLg`(`#R$KbMh)+ApcQR`x>g`TCHfCAb9^aUL>^``*!z} zMT~(hnMjA&EhgiK#4;^c|rp zV6+>LOiKAGky&du{-{xcY%@;WW^%z8h+xs5aEb>5aYjwOcgJJkFQJ4% zR+6i5(i5^)B<>SI&U}DDLdy&?hA+r+V@}ew5GJ;u7><2F*_FW8eh$pYPFK`aq~7(i z>>pVq^8#l&n2{e$mSJEN9YGE{np!`ih>yhj;SnLd!v(+;-|kf$tw=L6{Cc{Bc}?SC zdVp8FZF6~fQj^0XlO)dd{W?CXhqYoal64ecPqtf@81{u{@r^c@vLxXl1W%<-p}ae! ztDS39C;U)kX~8AeG{OhurvQFuuFWrA_C!F!fQyHUA8|%-nEZ4@2iaY*uV{tkq7szI zFS3v@-?xbbCqQaImRCK%eoE6F;;=S$E9rij& zPG!v*T7UN0QlUjHB(w7Co|l-`<~`W6@N|PQOIj%S11kKxbysBCdEFy7ASy_~tj$qo zE7lk|>?EE|=piH##wyJNwg`WU$OWscj+U4(MS~}bZB9HL%_ljS9 zMKlXVEgqGi67yuZX)@9`3!1T}wS+YXK8y%#+|HiJjcK0Ejv(8;Bvc`XiQR61oM)~E z^eQx8j%BnV*)QtSRO>`jYBU6d#L-2@8<<{;%*7y*|90iWE3_Q9E6A*b)H->{q)}oh zrzYederyx}oj@wK-)4Vl3&3?%mg@UaSJc?lL>S%WPY?N?1A7OjNYqQcT)cZtNbnio zmHK7M>GzFIhZri6NhZzPQEJ2;GJJMrx}6>|&zZ4arl_&-k>Fdo`;$XQg+Pp5O3!|) zDC^>kM8C_;)vaR(sgoLhsN7m?12r+^lLc6~J7-5pPc=vtL81jv6f~d9kWo8ueZ4Zl zRN*H~saX9W28ti1>)*fbbPaI`GY+77;5qZc>~I8156dcu#n~)z11Va>;NvqM>6*~^JkR<$PI^C@JYhQbTEQp^b-aV%-z)oVM(XO z7^vgVpFM^y@2}_Q>sCuxzN(=H20y=Gu%}`1x_b&%xtQDHBmc)abYx|BAc(c&G>Z)Y zOdEJvw2kzKLbHI5JqY5Ce~=SDI-eVr*eB7dA^jY3X!%+(v3AAM4}5ZNe+Eh-sQ5EDxG;@x@G`c@Uh4o|gHpsb z^orb<5N~w8m%r_YL$p#8jW=U?+xFAic0}k#_v8On|D%)MH@{5OVM8UJ7vN7qck!e9 z)%=k-^~vXn%BEfZ8iLqL6yON}%I71yC|???0B6eiv+r|@=i|;ST@V#s`PUM;9grpc zPaD!#>4cv;~Y6R z=ty=ZLtIbP)Z4<7d!=LlAb!?i3nJ`nZxTvqW0TTcH7-OVljgkx0B3x(t>y3lc?I_&Cm`8Il7z ze1I%@VV)f#j$Nrm@2p-oA(G{P5@eo1KW`J=s&8 zZ8Th>{?}(dIvyb+aafl>uv@gvj^ zm>s>OfZz|TSMgQ04CW#WJ){Ui==OU*7aQD%=|upaZwl*5^e(0lHQ(3&8`+=TV#gPh zytgWKBWe@oKwp)+4$Al};UJ1u1UlA8fqiB(wzO~sNjWIh(BP~B8Zr#qs2b;wOwPqm z&pXy#k*7=cUr>h&PW>yr<|~hiAoDzBAOD+qU>`i66L#T)l&I>@_acHN5Sr!5dJ9k? zlz9XfJk{_{I8wnX#`ySH^P3ESYDtehV@=jD$c54iKy^3auxN4xP-=Wo3P ztcS!s%tC|#Rz2n3ZCzwG&%P3k*?s##&%FYOwa=3BHKqFnkT@9Vb`iIjNXDO_2Y~$H zealtIXi+BK!~@_@ChX-sTCtl7O1Bicg-6oO!_- zzo|@+GIwr^GZs2i?;Sp>KejE1sosOjs)8{e?FJk+GUad8Q#5mng^zOVd{m!=7}DOIYXQring3D5HvgLW8V-DE$* zejWGAx}WAOA}ae=h6xc*s;lqct0CUaLs%V<5{P=H36)W6K$ zTDSAhY0k7?;LEpjvX!>MUU%;3JNW2D%7^Hl%+rnBS216FLeq2Gm*>^hH&kO^58cdy z%ykWmOAcG!luf^NqH8HXtDmjNejlkJqn`in+?TbWtFO9z`vC6dQt>vep-4q@)9=8> z;?9IDEyuL*@sQI?Eth@Cbno<{WF_IVn3tv0*|cBEf)pjag}&UH6SJ6Z-V#3tTgn4J2=-5BP@jHh%FEBpvB#{4yPMjJ8h5Tw2n4SCoa9RFidL z>2NifHSZn+?U%TqJB%w@r7dSkFxW(WH_Xt8i&Z~;Y0l7YN!|J*TMF~T0!2gE2FGog z7bjWTdynT;7-LVr4`v*!cLpsPs?%SM_SK+kKB<20yLGp5_W83zON_p6$bI=0)R}sp zLg_c^OsO!xln(Lzf}0XKG<#{>jB-syP1>RgC`b#zbCKTj-tbb?v~{R*_IXF9B#=L5 z*Wj-CU3i?}n>D@YCn4p%Y1P0dSyW#1f~ED;F7^kn-`5A#^=pjA-F`~FcQ-C~=Bq0tWx{@o?x6ugfDN&-7iO~P7J6q+%auDGwX3B59^a2H2-g zwOZSN7Z}0co)f$|+qH|Wu0-rv+V$M4zuoykCa*bvQWWQxgqsFlxlEJxHZ5FvKAmwbwX{#S^@$%{HxA)!-IyIL>TQ?SbKVFBmEV9?aL*;z(C(`EQ zo~_AFO02bn)Xr>GGkj8H$JIMkh~FJ;(X=yBFup z?^A=PZe><@Cw=;kD6D!A7Q%O8>#?!MB zBk%b)Mp7l-pJ|BeyI+lCpy-)@9-v)rX1~gU8o^I%$!5(BujLcq6`q@|C=+IgLvQ;akhx-!{x@)x-aj3oTNU<9D_ zJpc1K|8Zig^|VA`XPmn}F1$WDiUowd_XBQdFC+bJ`VDfTeVsMOZ{9b~c+I$)?wL-) z+3&tx)_<}6*)ye)9_2)E{3|>oKJA)09v@a@$%c&ZhpM+`Ql&-}!~3eN5(8}aLO8ek zW~wH(z8GYT+N8fo_IP>iIp^RI&9h-lm^16uqfhaKr9l4_NgB_U?e4EG(Vv`CBOc*L z;pZ5kpy!!_^3-~om_vLuwwp3|)}+N(KgBE894@Rav5}IGCHfHi^Ax^-cd4B@Qy+VDG#S8Q=m8$)IA1EcyY01E)ZjIrerEWR zjYD=$m947UBz?OdqVCvN=@$^4r>l$QYw`kKtC21rTny=Wpi@Oc{&PP=NH&b4DbAO zZ7-{GwJuLb!Rtc0cCAPRA8E~Pd~h;2Eo>s>es+^g`aSYY8)KDX&UC%*asnDzhp~QC zn{LeAK9Ssp;+lI9rFSM#D?=db)LbTO{u!`hqAKR0H1r$*m*Z(rX?uKbSf3@Y%MN3` z&cd~GgB1LZx{SD7R3$#?UzjObey9=I(IOC63RD&4?o^GD%1QJFH$p5NUuSvw=Iw#| z4RjF;sk62}J6OhMdH8~AQ|AM$N;#pqv0sA=z*e$mL(BWP7degLR;G!UfnMddo%>cN zk=sSn%TwGAF3DWc3>17>Rjpvt9$SP>v$Vps2X3hN))vcVeG&O^nizIu$=6X+i75)@ z(Pp@dCN2S+kn|^e5$F5i{tITGj0T^qfjnr#Nwx4623P6>^;iC$o<|PjvQ~RjC_@=h z-TQOvypv{ZRBV~LjvXFyu)ZcKs-MRQM9QZ=JrTx{ggAQY?J%_U#Z5{tb_tBi&ED}~ zIR~D~+&yZ-^|^m*J{8`5D)!b#Xybe4ly|mAGhzyLM0EIyQWYNzy(zBo+$O?8gnh$2 z5r||*F^3ce>1gm&1!BSI=%wg@7*{Y8{P0pe>~t#!U9ZU$Eda&I6#Ssh%v^U%L2H#v zP3d*Kg`GTtd_%q`Lmc}T7u7IR8yH2(i?^uVUpF`}aOf(hs=pC)&?%3QeY5%gpn&U| z50P3Vh1R`3#>q881coHxo=rk?%+gne6Z=0@rJ~oja=n&wX%G=5-9r3Q`K-_V#!{$! z8CPRhjC8iH{8UI;jAF;ZwiPpcooHcaMLKADHK80M7)2kHh;HK7`q!`Ze*P9a9~Qs4 z{QQPa$sY37XaNPY5i6mv8`QeU#ay_vFp~Plsl_|*i3_DsfYbYdGIIkMc?JnFm+KuS zs=kXKS2K%~xC{2=M#%aMg{ohDNb~VpJyvbfX0{_8aLe8?(Sd|*BN&>ix@Ug~)yO^G o=gbJ)62?Uw#Q*od)VM#W9GMvkwS}hz$Ujz9(o%dYZxQ-`0A7PA#Q*>R literal 0 HcmV?d00001 diff --git a/tutorials/files/server_config/from_sdf_no_plugins.gif b/tutorials/files/server_config/from_sdf_no_plugins.gif new file mode 100644 index 0000000000000000000000000000000000000000..1e631bdb5a3d43fc72433bcfeee58a1311fd9af7 GIT binary patch literal 78768 zcmWh!XH*l+5=|$C5~`sZiUXk78pxRRrBrNp=!VV4SyU&{YK;&PA2<(;^cbK+87_@(Sq7tmn%_Y!XiKDAPt0$jCnly;O{eBmq*mTfZJJN7980g9%%~jA zsGP{G9Lc6$&#oL|mh>5Yx23&nH+x=}H4WeDSuO8=Uf#V@{?F)NtLS=E z*}YiRy-+>)xh9of)BU7o=u^$mms(Xot+8Y+_d)I0R^8D1hQZejL+={KzBf#Z8W|al zLvI=T0-rIw(Z%=LiAJcztPj5F5t~L+8XrB7jJoV=v zS_YrD@PD^V{owp}k#oC|GquH;`qg^tMl1hE>(sZ_sqd}R-`WPAwvD}M<9}`Ae`}li z+@7A)KJ~R@_*n=4a|i!R$JD2esf~`Q&v*DA@9;m};cwiT`gmvRQ)eoz^Zut!{`*e; zhpzkYx%c07CtvTLT3Lk&Nq z6F-LR`xs~YaiIH4kkQv*oo~(g-)~*q3c_yPt^FH-{VSZ>_LJW}q_TZTWBah$_J0oB z^b_0M%x&(i?Xj-y$?EM_E22Y6qM{3;+i{}DZKCBN(W*dQgz|Lo_p`I{b}-tD0|Nm7 zfcj4e6!~w~|2F{t4-)`f1Xx6K6wbZ$_Vk8}79JMswS~-@D zwM$cRX{(yZ)A4HvnP{uNe*<@7vec!$W~u~#VQp!my>{jnArYzS+EF)K>71t*I@wYG zpw_$6^``5chDVKo?NQGr?=(JXAr7Ufx^*@!v`0Q@2)*BVd$Ei3V)CY2SM#%8^4GOz z_q$r2-=lz0YVKUl%20~zo}+wj>x(gFLWQ516HU@0$2fYK-`y@alM7FIJdjfgnXU6{ zR4|~H_T{Wkr}lPEDfe7bo1I-W|D<|$hL?!iS=PR|7YNZ8O_L2MU*8BS4?cJNqGEk@ z``5~1*R@J+!uIRiqIJ){zMo&;S{_}jwx!T5T1<2OIve}{{@%K*tGQc7)qG=Xqg~2! z`{4_T_#L5NGc8xuS<8uNN1bxQSA=GUQCFZ?AxWe~y%86{td8-#wW)FyoUe;YVWhJe@&9{5u-?EKo4*Z6* zBnw^+e?MmZO>lut`Q*!?s;!w8rAHL>vmf5K8o6_^Q?L5sFnTc5$9wWw? z2Y=9qj%QC=$wpZG_;X>#dRyq1bt!fG#dOu*{6xu$w37id`yXD*o3Z}5rKxw&W$tTs zMR~64n}(*&p2y)A-ik;;r)zJY+!NiLAU9*NWO9XQ8JXsndFBnpJd5#Sb4beKjZS3- zRM)=cxY*H2bl^035q?4HfY_IXFAI^i9_uy)O;w ztWInE6;F>!-uvtA?((l0?MrO%p`oQek-8SE-kR=$75dP$^*rS&_rKqNDm_h!Zhxm3 zGqzI(iNPoMGsf@rvr6z&96PhORRQPzep9%uIc>Jsr~Alsr>4cx)r|8)9tVG*Ewe3Q zXF+?@?NbiDY;vj)?XFUBou zax|`GfR%sqJgo<3dw!%&>=g0FOgYls=Q2*HfcA))iJuxcUst(vQ|Q?Bt6b91VOn{H z2eZs)*boqDS5V>=XpxK9p8Lenqg$>O{RCRgY0Sr+KbiTXeL(9AgwH$qa3!<1IoW&5 zCRP7p#vraRD~pEG|MDFFYT$?WKb1bpwwdA^8Qm&*rhiI3cHXR% zk!h=dBs)|l8J+*pbgI-YZg`JBzE54*wy@Is?FP)W#%3Iwu-EJfwyOO=y%hf0=lr^+ zoLFY1O84w-yAQZsPAahbaeXJP8f2Y^U~T2J;TP_NKg^ z^{{DU_9|K)L3&?{=S#gAdxx82u6!*Kh9I-D6sOM@e=U9MUc3Lv#B^NG*P9y|wN`Ij zX0AN_TDHZnJ@8{fG;{se*INLII)a$1fTpy`hI`c6?wAxL?cXd%XV%#}tv00vZ&qNY z>Kx4{XS1$sR$?XUot<3ga*H>sbUf-^119GRdp4_anf30cTptua-K@b+)q7r^d{B1f zA*KruWlVE@SPnW=XYa7)b1v**g?2%`*O><2n?3&Zws#tQrt}VXxjt(4{MH!oEh=yz z>QP(Np{A3s^nzx34&TZ8cKfu$o+B&!pKv=5HJ`n+C-iIZlm0K?TF4UbL&bUn1{4Z8 zS3H`INi+uXG~!ybFTD@jy%;!ZTiABvc1*azo}j7Yo$W;u29Zwp{oTUDq>kZkpY~}C ze%SLJbrok26Sn8b6Vc_eaF1YhO{vwmhj5wlUND!m+Xo6YkfIa!aftboVSw`uCsD?-GBtH=yYLvF~k#Bc-p5 zPW5-CCH}^u-D3K3XM4%Fj5pR#e$HH!yjWIAST%?NqLPvZ zF*0W&?N0!aS<9d*WeJ9z-_yC|W|Ioz%y&+ggCE>j?x=N;i1N()^`P#+od&z9D8H^N z4_o${Hideu2Q3Ca=6YUgx)iz|($e#!um2J!;qLk|)Z+Xw%&aYW>V1S|@4Vn}Tt~L` zhj70mPv`qPJ8w^YI2o|GxbX3N`;f%PGdGSbJy+}Mew2CkeEaXEjq6=~m1o|W%>Q0K zjRyCB&HRKD9(gWWHs^h^CSBc8`W)zmAAnAi7|MMssLS|4P0!ECZhwTBWbVkG1D`Xm z_PxN)Y>k+zozG1#eX(04B2T&<_)=K8^b&Wud-BBg`J(o|*Z5oAQvuT#ir1~)n2Wjv ziJqHfpO)S@IQ7g@`!~zYt=~Ci?|)F>d8yv=?ixNh@$sEySaa9P`mr~^9@si zziUTCzvgH9zjw|2{diUMTPSr;v^D0n{iQ_o=dIVhUr%PXznhDsHnQ*idE+JewJ6%& znz^_AV@9<7TObPn8R#Dv+rd7FCH$Rhg%% zZBelpng*Vx6-d)2({xxgJuVH3f$!a-;V_9t_(YSyL^EGpwiM>5@+MR(=W-RJ3^TXb&>!xzu+4`duBGt61=U@jwMo^f=GLBu2-$0vmcCY>ZF zMY58jxJfbdNoTi`NSNgF_~eU$$#LXlGAsECH~HFp^7XA`3MPeyPoW2YPt6ZZEhMM1SgFO_)YAFXvaM7$CanUWRu!05Lr$w>r8RKVn* zx6(M6^fr8YM__sHCH#yBfulAFPw&zRoI5MVOr z@R<(-Gar*P=UJIgxtUAznaf+5LQK{wKI>&*)@yRsTUOQ@H|za;*2k@^4NUeIeD-Ew z_IGmj7AyM~H~Y_g_V!jbK#>WuU_yeJuy`iCh>7fGiZ3uFe=^aEIWiVGazQx?@i~~H z9Hs6Ym4zI&pE+2?Tn&p{t)N`(_*|W$T)pmG{e|4UKXY-4c}5m_CP8^-@p*VrQQrRU zJgbGg13&W!iutw{`SwBij`8`P5XcjDb5GyI3l~Tk?>tl9L170i;|9@lFs-NZc#~3cS+wuN&n9ho?_{sMd@%* z>1cfEcv0zOcPW3NboythK=J0B#m$F7Hy_8}oG-fhwEO1L!p-HMH-(C2t0IfCmqBH( zcq*y2ywlE2t!rE;15<#NI03RlW8#pOyp3aqQDzbghrByVa6m7ln6YqA8dn$Mxv1{0-`_w&!kk~iYxT@!|aF< z10FzK0CFKg&k<3b8}KwX)Pf1##{noYLB;^+akQ9gPZdV5GSj=#JWVVT4Y8qsU?c#7 zP#sM{HV}~Iq{?zZZMhIpPC#;qs3T87Vnl%T6_7C@GD5^e+#ptEQs60+8i~n@STw{= z079Wb%1nq0K`fjAvju=PI6xCz&2a%E1uaHGL!36Mu^ZsS1Tiif9?gbY2|xyH;0{tl z`2PBQBs&FHSwKQ0q=^M^AW2aGMFQ9cS7o1uFh`;qImmjR*fj#wlms^50hI_~XA)Qp zP~%8}oWvn-@sJ!QGNBm3+Gu7`#Kx~ct%N`^CQye{7fBRjkr1Xz^#iWAGSOn5SHSz2 z02KgO763FOz@iDr8vsNYzUc-l)CgY@wJx0j$FWDlmbjBxt|}he3ikGeOpA5Cz#uU`DkRlH@te0>&AgZd&92_pjI0olf_2+ z`z<-%l}ut&6;I5W1Thc-cM9)Sa(d%9UB-mY)SkMNoLWaD0*3|8<2V25yc-*xTunVa=v;;A*r;gqOGwf}|P#TzMF>hwQPSfB; z0IGMrrD?r~cpv8A-tN>C=`7${@nJ0ly-*P@GsXY=2LiVNU?_!#E}WoSps2x1GF~4!4#NNa1vM< za^w#{lLPhzG^qUss1v~V_9uaRhYi>OO>E;uHfqET=Gxe2{+nSgUX2n04+ta3CH;RP)AQOCvm;-D#{+QhvgT6rc)j5Jw!Agx|d zjJV~EeBB5&XMz-&Kx4q2=l9zWMBf<`SwT*6kQ@Mttb{6B7rTarD#ZZ376)$d#ZD3- zHqpS{8%-np?{Uc9njT0VWM7Y|00%$7*nY~o&pfrC3-sj&0&-hb)mVaBBc{hLut0?Wk@)v%T zAg}XaZX}Lh!yWD~knbcoy73=TcPB5-76=iQynod4T;~0~I-yv)pno8vCH-lgZ%Fs> z8p84RjJg04!$fLrBRltZy4Z4&r$W>vZR^YhON z&EHRDx>bjgsyngBi$cggUZXK(iAWx@^9E zC==FHmH{!$&Z^Se&ITQhxT@N-%lV|&8*9yET&J#JG&tekO*grDKogdl?;feNy1E|k z0X?e6Hw9Fyvw^R#bk&}%%8lx_LQN!0ighXRp=@AkA5cnSq)K@A$883(|NWfnzi8?V zF*3K|=R3#WiLdj>fq zq?p<}#F=|TzhU9Trxl9;q;Tei$LIX}Q>dfxi^A3}OOO-*$ent68s8Mhfq98IVBsI| zL1wEa3H&Z2DH9+T$%NntAhQh!+ZA>Y09Im-cpgYXszO`@08PSX4|e7v>Fv3`O)p8Y zBYXhP`(q^0eUM(gJ*b(P5mLc1glj$2U9>2o`4UO2STWtC$SZpV(uUV_0nuy3- z6l9w>Txa^bZBK3fk$V?!R@#t23hc3H-13^zBfr~E0uuO&o?I0FnVqn5HxW`xL=OIk zY+xg=uGN}LK7`&|9Xp8J_p#EB_&!{<@57ZREFt31?LVo%I-*4su{RQfamT)!EmS#@ z?us)9-Mn9R0#M>=sN%+^9lTe8GYqYmh4n?~Mb3O?Xys62H(-`AMn##hQ(W@B%ggaL zX?;YFx{Hiii+e=F!@8Vu*L=r`v}$L!ECnTRKBa==Q)=iKtS`jnWbX03p`;!>ZkVUb z)VR0x-Wcezp6+J_@J?N!!$ z`*JF1D05Hc)`p_*@9!DvCvByZJ&>~1u1qX+uiBDif%3(3-nzM3463+I!?CeVWxuM7 z6f`i&zTW)1H~I0!(^RaIFP_cN-25V8`SE=olHy`v#Cg9 zTsOV9gyatA+`(Bu6_7WGSi0tW{MjT$Z|(=WVujE^cK5At0}s&hN}pywwCJRyRJDMb>fJ95dDc3x|}`W)Lb4vh{YP}FJC zT>TVZ0-wsqyLk5_TW5l~08ZJLLf`U^3Pf`Djf2+w@K51$mN z4#AXqLka?8q)#K%Oq^qMjz2JZybEd@IXJYwRN>PBuGl8iY!k&jTxlDl+6gaDO+q+!0z& z!$GEzVF&|ckY;Kw8IYJ+j9m%1{pU)1q8ZNA`8dMN+akh&8myy}X2jZw}Pe1I%v z1fD23=->*(L8!^m!$h{+XiD{VqwT-SP>x z;{+UM0H<|%AE4hh|M|;KGi_h3vaE!$Zn;(-H&bmeMJnON#{uE0>^|hn*WZ07mbdU4 zU{nUr?p&R7lRfUP@q}b{|0(=HBr39Q;JmT1(l_G5soJ}7i|59yFIxmCX{IRgo??>^ zo~Xym9a2zy2a;o_456)p<}$q`&tu#aF84n8w6*s-7G6Du`GO>`XgZ8I_Ji(MoqpM6 ztDb@rtUlYt3OCv%=X%_0*v9ub;&fH6++u*n;o}gYK^VeB`p~iM<2p?n!lQ#Uuv``( zZx_i~-aC~aY_w9i?Gh~lZ#4jYhX<4Vh*d_^a)@?_4ax!Qg|bFdK?DIn%w$0P2I*+T zwhTtD9weVm$d{GFf`&^W$gq^ekNI4CZL`@_FSj=T>Rxf53vb6&r=z&NVUltsNQ>GWkBoS`9jBSkS0!G zC4UcZbJ1X-qgwu?gMJuT8E>oVRl6TWPIa$(=q&fB+cU27!Oc%qvY%8yebxS-u54Y% z@C^A3-@i!&@7Qt)w0#Ucg5D=bYw+Lo-6?q|o>wmE4XDyOG)Z5jO88=_V0&UB9M3~U zbM5`{U<6(t2$RB4<*JBK|1&%+eAd0Ee~ywrXS1VkZ2+8zP0|Y14s~=M1aiN@1IJOp z!Ayla8Th6Nz^J5)Ges!7CU z?{a157||iG_6J<@b%-YO?BqBss`y=sL<4vFoK^Ca%4wz?8E2>k+L%Cy+85)E)X^66t7X5MGdInxR4MdPs~}$^(j50etJ=BWd$&HSur?EQ00b zsFr8SYL!NK1VQ(>x8AqK$Xw!<+bjw?m`|{e;a!F_>A|G5Lp;!_yXp*8Hj&= zOc6JDsaUI`{DV2Cs<-4Fn-r3qIdN$;Mlsa1FHG|C{16+s6S#w8u;wtSP{IL;o1p2h z59vvI&->j92kFRP$~(1ODQ-8qAy0LcQxKB~)%I7!&s0I68BhZqLTd!q$1QE})yY&(gsf43E;I(pygtLH`q-J>7;=dUi&gT`4$2St? zN!4PRS8NPiUSYj5R+~r@15!%7!_C*{AGIW1YFgJb%9dRb@7J4J(IXfF99vwbnstK0@8JB^%>5f?m#u!iBn8TxM6 zk<()kZMjnkc2c;iay5*}@-vH?allPCVNG#Zha9O%_>N{yVaOnhWhbS)2u)gn9o2zg z&owG^9`HI)W>AK(X(*``2?S%xpCv*axU`pbxLuz+0sd^&R&cg1K-`%|GlKdP82)&D zJ)yZ_D#((o`sHeuBL!{6X%Q!Y{BR{c7zTt|)bCSrUWv9-+}75Ih0&*ovqA48b0gR9 z%)ga6uasv5u)VdI@`ne}90$nFn~Ki48Em2TaTzqkdb6SakRZN${lSp+OFM}p2#gyL zhNe2iQ=NYrYM<_Xm=4CnX)WA>o!+`K80s#7(c*8lLIRBnr=m$999K6M~VrhFTA@|tEhnNh~Eb^%`GSg>A+`GbBj((?*{rswa-uS4_X^15kC>cpB zv_x5{oBE*;{>n}(>4~nmLZVV8>n(Lxlaqdy%IX?4vyKTpBk zD>u7Up8W}L@*v1n3BT_favuzMGd!`BR>?6G*IZ3ePCh-^yC9hpg>GQsYh(85T*Sz6 z&5hsIpa`64_3CGOIe)Q|UM#nJHb5|!qC8HOz*Drw2fR}tzwX!AthPL7xqX2%QSsEh z#6(-p&UtBqARfI>Lv>&kd=ReZjLb7M1Y?IW>h|ML=u`9V67j!OXM@xBvcW+*C>!9- z-zO3kcoY$qG*wS-#q{nsz~1V#pLE@T9MYlhA#44Z;1rOu73LL+2n=m|9cTmOMXTWm zW`w~T2Fdgl0BHfpWL$k3(C*v#uSp3c#sLNx-aUN6o5!Xf zVkb&tfktd_WY3MxIe{aVu?s-m&4Dr_`*#@0oTr1{(0e;sGjg&7WKdpJwZ&5aG{986XCH}%)lJob#I>Uj0CcNgu zu8XDezVzbL2XiS1H7;!z5YOjH$vvAcse((#+F)sII2LuoVJD!vg`%jQDh0 z%NUt7SEJW26Yb|{0YqqDD$ayG^w4VeAqVZ$p+s?K;6JTnj9R*Tv!qR2T6K^xq9v-KHwa7FChPv}#c^5<7furH-9*g)Cy6OvnG@7=XTYq$= z=)3wj%QY}15-9nZ88{D-(@I5+-(ZG5s+DQjMY%0_H!XIlAFMxCv)@S?SsN#ZHK}^| zO>wMRY0j0CC?}9^N)*e>n7*Bfltd zBt3kc1qhRB_MgMs4_m27pP?~*gj(l%nBaMeB0}Hh?t_W(17VglRclao4r?6LCRUZ9 zvskP?4xqOe^}nEA_5d04;5$miH+^o`$Fnq<&~#2Nw~^Yw?@g0eLT8k8*Jt?=8U7gP zA)?Z0Fs|m0;|Z@Ce^ZRPyR?L)eM;V4 zhW?K}%XEU^|GWrdT;KFQ(eC^CmV3IjI)PJ95I5a8;Mdms)-(BnYn(ah!ymud^v)i5 z)w=VpT}>vUQmj%FQOSAaBC`&+omE{FL4{At_Y>QCR7jvbWXkRo#+G%U{`$>iczVIr z#1Nsp@;pFuCGK@jdCuWasdUr`Co z%$G3JcyMs-jt_}($QgQoxcqM9P{(-x3u5I6S@Y-b3W2@bYlr`5GlxBIvw~dr%SS+e zN{X%I47ELbWH<@v2wA+l@6TijK5^$S8ty^sgqGpNPYtC?!yi55%7sAL$17sNVp~K&;wF)1|Bz%O?eO$F5Be429m%fzE|3vtXqrK zIh=L&Wx>gJ55{GG2$~v|)$m{*g9`~1fF#&dg>?s3XActyW=Il-=2hJ!PWsAzd{ zfymNn4P*u^>leBS%9M{pt;QhU)fbuT1pc)4`u)3HLl$||-}ptoj`H5V8?$O3-yye4 zZ`C-z;0Izsf7H!%#CyopGp9ktb#(C$;+GFsdqmcWVc+u?t!4r3m2os_4(+Iq;eqtv z=|+fEaC7Ka-WNA@g#VB@0jynr$7th#{-J%7#p0>= zmBTE#nmUjJqKa?*`awq&yQS-&K!XHP&~nKEi())fW`uyQ01`O!}G! z2*cU$5n<`sy!0_7M;jj&7)Uo4(3Hu}#*+qJXBu#pG!&PjMP!8LKKWp(wDXT*ftqjl zAv-N+#!1Ey@g@iG_2^@(k1FwKlR#B$CH+^XRQd4p{qFC6YCC$>QN?lT^abf>3iryj z+>hT@`o)f2(Eif;cgXrDB}GVG0qWO#)_D`wgn#UAY#b(MGM>GEGU!+51W1(PJ=v8$ zbLYaBsT#-uqK+sz3LtV{`5>NIKsLb;=XX)hS;cIe6IE z`2nEB&>+g)O;N3OW_Z#njsE%QvJ2F1jXvSW?T_mfxL*xg#&zRS3!&Rw%)2Bzinx2^QZ1>h;Cx9k$}bKkD&> zMD`p-+nc!iEc1w#k>*#Qn(Z)`UTjy>K}POo4xa1Ka?fgW6ou??n|6-oy z%&(=wBPg-@|Mvg-d}B{IfI>s<;l0N24RgBO%Wb3~XUg5~p3Fse0(j zX57tCejrzT;dkuQ$-A_qZy*;(OP9o|Y%qjHMy;xY$IA{aaYNv@2en zAs>t>SC1ux*`p974p7RiPaUOSSqe>cDPa1h!0b#0iAk{#Lwh8GF0hr=EF>R~N%CF| zkx_*BU@vD58#HZVsp$TC|k&sCpUHo#>9=An>Fukbzk~O2!Q$_VnR~BrN}s7<%zt zOx1{u%eMB${FjHd%ecE9Mr)g{7P%?T1J?<9pEu=|L^cBUa)!y@h}mPdrvn78MP#}y z%*T7Rk$~`d?;EH938O0-iy{K*N~V+)<#jMOpItjPg?WIm)0$E_Nw^^9a>&3T))wa6 zwJG!1PVg{iI$u1Fc)l}s)90Ld2z3~$*jJS^t!_CVG**?-Hm+=?LfV3P?beK}9(jdyMY4#gE#%9%p?U7PM-@^#;0sHM1L?lmT?LfF_*Q&(wP-(-tNZqoR z3OoEVEDBxL#kJ)om7v(qa$_c+`dOb$3^Tu+oIXC74D_cop(A$$?FyFj#vQaf5dp}S z-3*BsbOJ{DpKtMbZgA#MWaRL-w*TITIrXoL(ChaOivIo<9R!%?scX%S+mU-f$}zxn zZ?3_AHjVZ=#U$X~DMvdM8QC&>`*c4D%mZaKyo*@QkYHmai(TxKXaH?k3>M)+9NObP zpb0-TDBBQdFNwp^4KoJdxz@YA znTI~niJ`cWc zUAS1J|5lhp=+*!b>41apf*@4tZtnJkH)*E5k&cOcf;8EvanKtNiW5@dd_l*@jc{f< zr?6LnbDOM~Llz56yc>Q(PIMvFNxFJa=fr@gsZZ{$?Y3_15l_D(z{}%U`)Ux9gxz-i*l3RKwAj_eN?%knz4k zEFl-9kR3>aon_MH?86<8tizpx1BUbJv}79y47T`X?v5sEV$Ohj@XJRERw`i#-h_?J zd4Pri_p|nw81JPopj=cRTA}*Epu}D#NN*l!0KVzb9|Dp_Vbta8DA4>6LnOEAEIeB= zZG-qjx~5LTuq-zHW3ZzcO28HeDeXE>yo}TgWXCAQmNZ#a8o&CySNpwmuJ@iEL*S-$?9@&#PisD&X z>35q^1HdD%kmWU2JMj}zmuoL=eOa#9p=Q^Yt3mFMWub2(-c&xeGKlhPeEMh90LWto1c2#Qd*g#FREjWfvfK@niPXO{*#X`vbm_ekb zfKV!VvPzxb?B|gJ-E-a?Z_tPRm+ZcvXKXG_8m#nI>3C`aiV%MO$Q;&{(>CHcb<3MP zginS2bzuBn2hKkMX+As=YnY^EB7_E~te*TMhYYYBb^xG(@|Z zO*L)WXS)>~lSImiMCd)bqc*p1(ZWF`jU;-#>EesPNM2f5Bdn) zfM^m$u5PMTsFjNUt!0>YH^^Go*>*=U4|tHJqq!niBOQ>t^U`;}=o;LJp4=>0Dw0Y~ zdF^@hE=Ylu5)sX|(9v^udMMmGjysiDB%KfQ%H0^2?LoPr-vb_k5mQlDXO)!zLmeIC zQR)dd-Q8)pq!N37ir4Sd+4CP1x&}5aty{tJCz-9cDk3eDK2M-Ea@X#0J?BB-Gc&SA7kLO5`tnuclO*^QXzHs=pszH$JA~t4C{>4!$Lx1kcp%!1Q zCyAlP{1bb>K58(Bo4!S-lxiVE18pGe3U17ClS-vnteA$ztWMu*+MW=e!{rX_bUgNm z(Cl(}C3zTTgoClgJ~$tMRG`5RmOfI>N?W0Gi|)ybY0`CLJyS+>tbmXH*lr|Q%pZ<> zU=o7$yf1&v^?|3eboxZK&_hpwt(pr^k5-*2UJQYOYy$!riN!n5%Qjbvg5 zWkxi|?*kyu*Jb|ItYKNgG1=ph%{BI~R1%3v@BDww;fiDPuVO)BRzj%Hcxzm@Ra#)o zs+i^$P#kpfC4FUGrV;=aC;8l#`5Fj*ZSa+$m-DaGL>R{3JRn8pxNBZWc>Vg|!Cw(U zC4U0Nr;QA0d<|n{z_13wluIwnu59~*x3_j|{CW%kimwA$)iPgMqmQt_rx;a$|1yo^;-y( z=Q}70hY>}^;iRYHTTuU$(CvwW3hT#cK4V4*8R@gP&wvu)qERWC(L07tz5>9)L!LYn zv{TLohLMO4fwWsY9}OGy%ZG+Mq;xXX;gJJ6DWQz;M@MJpHB@X~;Q(SAJb5+{9+wpy zKhl5EW>|Mno>KTJWri}Zwp7R09UeqAQCxCtBkcz!7iNgDs{M43K8B}6au44+^2sDy z)yhk@!d|nKrobokzdv-U)m=`IZErFfzM`mJvr~UmgRgF@GCmGHLx8a6E8t9ZK6!w)7w0nu63eFvKZgZAZ>tKWnb_() zBrH!%c+x?77LglaaBQ5(D1^fwcJMMRU=JG!O_fU%}zWU5ZJ4fpHNRzi3{9AO6&9^1Dn_7l$5 zx0TiBq51@jM*w;DKz{yCSC!#iLf~>F?{z&$f5Rq#F*A(Vjnt*93IHBK5Y3~Ivzy08 z@uRz}URz!nl$RqkbdUZTDDl!sx-vh5mCO&U=0&`FH3G#>@kWltKZ=Yke{Mh1^iS#X z23^A)9%Jpc%O9BhD>fdlp;JbK@u=Ij_vfeHag{bZ`Z zW|hTrEStk5bVWH}Iso+wZmFiLv@jse10d!p=oEldip)i&*{5d+PIFWPD-h-n4-`UB zjjdDHT3(&7eeo_VVb`2jPUpag^+$AkMXD%zII@R*7l69p30*#idE z8!Hbrn3$YYt?%;m@2UjtaW}IMZudIezD4ZvI;+Eht*^WDDKML3p2O$%D@-jxlG>tl z!Vy8Z;n^lXu>)_938ge`)S{z!(i?flV8WZGja5yM%&-$uTD+AdilWtsn5PN@?RR#I znHeealrc%wKqqt4(%!59OADry`e-gio=9P^mY_y@3aQ4j=~T>A#c6!OY3yX#NNnaE zhG>Ri2D@X6WrFF%;WvI-4qgQV*z0JZFVLIoaJ{X3TIhHI2E2oKJ>q%_t)lJpGP=e3 z?MJ@YNk?MsS7d8tt`wQ-`6r~9i zqZ)2K{7(OJ?J*rz=+J>W8LxgK!EfxXr*Boo6*eH0ZL_;)wGg@I+2IEOiBQlrK-u`? z+9gQ7t8;NbRZO@Fq7zcyI?vsyzR-FTltGa&;mHaIv$j7xunt&s*>TCm29BkUsEJCS zR1+Ff;7d@Lu6vduV_@mZ#6gATym{Jl7oUq|>1-0kEbgq}jH@JW_H`(T11RS>tCeFW zv)?^=cPUNd8f*K*2`coHUk!q-Z38M*fAg;7T2XF=kzbmH4gHqa&6X6!lg*sAes2m)s!8d*HENN|W&ArnF*F=73Tp?-y*Rn|s8e zqbTu|30M{3RqWfce*&o9pfUvr_J98EOvJO38$}Vpk!T4dvxW)4E@G6*5T`(cQ1b{t z8HT0zGHZ-fGjI|MG^5|&8bf;z=;VX+`UX%YHhO*R9sA$b$P-}UnYB5hL7RHePGJO^ z&FKGP?@JQ8TVbtM>>Cs8gMNy?(r`ld*n6!|=g9t(!@{$;Lvmy>{-oom(TF$(_=N~t zFDGJc!U9u<#~Ysi!~icT$UAkE{IZ^Euhx(@FK}XDu%S|G(zkL zBsu`3hrEOyCvhiMB8+(9S`iFO)l+)=D9T7v^o2fPi)@M>;d{+5*FIm)fCaRR1QpTM z6wpTD!@EFn!2pP%skCrB*-GZQMyo~@A+x6W#-_KV3LsBQL{;D)ma87$j08x`H*Y62 zCqtxF-J4(4r)YFg9wSaAKSu0LQhi9PNE?>6kxJcYx@p}8+!GkAGQ^gUrzu!<+!`G# zZQG$-XM14K`Ppa9cMgFnDmLIv1$t}Cwemsjr3WfuBv*gX>(c}o^0_yFT&(n*k`}N5 zqh|Zk2c%E+JOZyy0_`EDQcwFz$OWhmf6;Xl&s6nOSpYyy2$uvVUn6Aq&hw<0EY<)j z;M6g_DiyZ(tH!mernrm$^u19XF)wUv5B+E=BelNgj_D^;_rl%BzKi)yL3Yx^v@>i= z##N1+J{$=aCtmgQARP%?wTXD!ZiALp6H;5hXGvp4HgjZKu2Qmq*s2=STB=iwq}lsL zLL$8n2R{}B9$J9D_PR}lMwt^a=FBc3d$-W0CvyZ5H@1tQ93?eChUH5r9G?g~q5yMv zfN?mkufH?EFrw1Cu1#NgN4flONK~(3*Wd4A9+Q0D$iD`9c?Bvk93UTle&3jrW=qTw zRbWFT510Z-C4)}4w|M%Gz&%+SFDbxHfOrgQ&e_~@eIC50R@hJ7lXCe=)?>fhm;DWf zm11~%9bvlmbs^#9S1Mi=CRHd106@^!Cv9i`;_>aaTjOL}YkyLRtU(`j^h=D!7M^V7 zVSels&Oif^HTgA#mFm>0wo48KYiigLC2|HnL*z^!POX5ze*$5I7vmG~Ou1%Mfs0a_ zvAE;^C^{E^rvLYi?`%hAhB>x5&Uxe@e} zgjA@c^GIiv&QjlxpWnamem@@f>%Oo1x}O)e^u>WKFIzINxl}R#a690(b3MQ0A5{>Z z>zZQK&wpvIx$I!|=kQ)BY9-*Am(AHup(*~Z*S^|C(p%lDpYhfGolJmMGw{v+*iAsf z%@Xf+>4ux01Lq8psT))4to}4l*`9+JaWQ&QgYveUvKiD>sg4vx+dqUe-SNlPM?Vs{ zVdoB3*mQxJbY_d1PZ(#d&f*t(Q$TcA$cLYotmD2{;2@jW-4!oecZ1X$0n13yhLrX@ z9JNy;TvNDK`u)Pl)zMRa9WmR8hjkz>9dKj`uvV@#GG;jLMt<(JbWFIudch!zSpIN= zZT2hkV5HC9RN?&_e*kd1$!z=-esr=y|Ecv=caMi_Ntq} z=QGhaA^=FIv7O!GDJlEIhl^<5XH4c9;B@^gWdVOj4%Z6O_&2t&0?^2JDAz^Ps-ELC zX z@K=HBs@^Gp@E|5eO+CBYZ2yylgUmCEMr8ivgvG&6!^-FX_uw_#U?k$jKgxcyfg@0^ z)iIWX!k_ucdx!6$|0{V>I)r^7g)#oj{8=AZG#Gbb4&x#LFHe_L zDQT7Kv|52a>x(^LQkN77`Mt%^wnyL3t&(9siVpkbw3>3w#Gstr)`7=jR2#$OC8q}$!zReONb5=%Q;U|jBPIkx`J$Bkay#f!@*uhDZc#A}&E# zeovryR7YU+^VNbvZvijv%mf#&dlc<(*1j^v^^ryNFSjlc^^2LksY`oNP|odl+ZWF| z>wydO_U-nHQ`EMml8|HAaLhJ=WD=sZrSUcs9_Sk|syyq|+qxOWB7p0>a3GAOX!DCAR^k zn-|uKE{*{9DX?))6s6xBw0DU}U-`;WTmibi|2-KD}TxiF% zyf~J1ju#_T!4q7NB#(8rPSv45dppYQOJob2+?OJOa*&Ewi`f3IkG&#&j2g|w){xt_ z#?}VMm77P9;mtc=`YkRPq^Q02ED%K`mFoxEvgSNw6doT_LyU`G?%VO&Ks&u4T7!R$tqPAea^fu!5dn0nu;?5pOp7zoFc``&d*ubCUtd>D1Ev99oL)8>{-3@3+f>&K9jx9@eo%N|1OT0bnk6nMmE z?^EcJbEQSPw(Is(uzHH8=>f-^k&M}TYt0r8DsZ6YsHzI7bg((uJ;?%-VX}bZThaHLXTr!4BurANL>@{oETC0 zS=iq-v;woQ9nV)YXCqV$u%@Z#poXlt4y9*Q)Ez6OzBh#0mr-BKZl?t+Fqs@b_hz&t zX&sGu`)#nEXn}8CaYeB>Mt)}nq#~9JY)t0U^9RKw?sPSoxrFU<2B9}?c(PPt;YZq;U}rYX)Pv+{ z860g?#2%)vgsUDpj$;*J)s=N!8U4FRa!?*kbCHJ7V^P81Cfvr}(QF#X(Fl_|?^ldj zb!(Os97@zZEb3D%iaKkUmm&0C7V%Uy(JhpRa8GTnl6DG5FE1m~fBhI6QTnh{S9|Cg zG?fE!_WGPrb!K9RbcGM2P{EtoPe06NB6p><0Bdi%Yqx)1;0yo_K9tohPYzv2tROi73?!e}D)%4Vqf zY4njC|9$?ii_BTF>Mb{CHW&qu--!%tB&cX?lYOI$ZB5qT`_iaS8TEAqJY+H7HAP9N zi*dMh@r_Tw7q_-8#?tY_QXB6y?FZYQ_7yscsFiDx`JF>m+ylE4NA&%pAi9DvZ#jJ1 zny=uf4x+&B)(4{y6#~gv@01hq=Pq3`_omV;r|=^!LCOUNOx!woe5aIy?G9`_>fsgggwG`|&yx!` zR6bj(@6G|x?5;oF29cIxGz8eXFXxeB+X3_7bCdC?`rx zS6^959oyZ^)&(Z_4**N*eNPTvEVL6+RsHWgeerGWvPUBgwV7Qpcmkw6`U!*FdpTIw z;{cDMr9!I8vI}7EvIAvy4PJhKjcb!*99xjG8HL2ge63Ri3 zk5f)Nnm!=W7*0R#$?x8N@7FT%ikb4*dfrl@q4&zcLbOZRu!2!krp>6v_E?<*FqJlM z&He-OX{s#~ab>?X3BxxBF6~V6E|Jp`is`RaY0J*gMDjKh#ok1^hB1>o{MV(s_1dH0 zB*jeywIB?e3AD)marKWtcFkH%#nt%?OeM77d+*khbTz2i3kk<={IZ41G+xzW#>eL- zbbIT7RGs3sX1(>KUD)+2AN|Y0B2a;~OC5X`FY3aYCRAeUS6 z)&OO;gyCCxi;Tj=vL!mBp=5 z6Q)HmaN!q!PGNIkB4(-k;k#ihc>#~)%6&$B8ALp?79*yi(-FSm$JvU!LqbPBYc!LqTR^ z7s72($>gqC|53a(Kt9mez&6@+cUemo@693+AMR=}ErZm2(sxX?*lNDCoB0OavNYI& z^JvEUQxm($29)Nc^`#G;9Ux?qIp}o3@QT>N>Gl!$Z9r%8|A?}(F)hJG| zqu!Pj921ba3RcojWgyd45T-!PrRu&n*4JL3ePW2w)AAPSWe!4=HPy#4+iPNx$6Jk_ zn|}Mn)^!kHaXqZfQ3Zn2iL&60gO&l|>No9I9IJ3W!o)Yt0D>!)iO;$Px%pf+CdlPJBaQYA>xgdI;BNxKaTetraqBD%P z1x#*bpO1FIYd52I1D+YACD4YVS2$MOHv7P#^mNeKo|(lDEjF|vlbj!?tb3E3T2RLU zu(oLWuCHc6ybSaX^YQr1lz>I6ql>~HdJ>v)w4yW3(}?J=IJwxpY&TnKk>9H(|FgxrzFEyis0st;QXP*0(Q>o7Q2L{;_$Dl=V_>G`fL z;w$Of^(ovC6cN76Tp^QeOf8hmeV0=Vd92qa=24$AZ$|RJegVYo;@{g^Vx#EMcVzzC z-+y{HraT?z_ES2f=pPSfOR8X2%mNON-LmX54cM{RRxZt7zpjH%C8qN>>wn|@AXI2= z15=KfI8UDPsR-(2wf>9LE1kY)bLOV7&NRqP@UKF+Vij9x|9$d@zcO+NG$xMGy=k=& zV7VzcxFm%#80$Z`oh7h@oJ3U1Om`MNJRN^D;5oETWiQy2ayKt_&;R6c%QBF0jO}Rw zkn<*DcT{cegpnl)5eSgSo5`J?2oqQD8L>qimIBxDQbZ$FF>rzTS>@iK5p?UuUu7yC zCPMNlw03)|R@b05bRXc+a z=Y)p2-@blwXQgjpJyN(S@sM1?p;4Y`KNHcyQ+`#e`Y_;wlZ_o!S2N&yp7n}{IjNH1 zYUH>do>WYEVR-;K6}(rFv|Egt>$$l8Ofd&dIdA^Ce?n7b_6WVEn5q?a282@#udXE}#Mt11_y-KE1N;AC{ zajrro3LGe=7bU=^A$2^l{rY{Coq);e)r=7MBsKQ*2JT|7kvaD%42PJZwSn%H^^v! z$frDN9dti6`vVkT+MY0jCdlBsyH+RPr2He&7asW!!W4E(19$-^^!4%RTZEkGvlMfL zzpU;3a93k=4?NbGCFazJpVQGXz1WXhEd|OR`MqZ!ii+x1r=rrM4IeC?c_+d}FDOO; z5Ya9wu?q%0GXM3l0SllFMek?UNZPlcu=8`4$PtktgXlEHsp#_Qx)R-6(sM{e{4*!} zFf|f*K`!`O!gAT$AjX2CtrYz&y|WQ=!TR+PdGL=QH(i>GCl9doOLX9peeY16|45ht ztNRE~y!U;)P;Q+2M$hu@w@;I&j<1LrRI=^qwJY=?bP2?3zO6K1xWM?GyUKR=Wgmj! z=#l-d2fn4RE&t4C>Qz4b`6+(bp#-3SL|1WXzu(=K|6wVRpMxmg<4-dyc3K$qy!#fb zw#M9{INBlir~MV>eqiP=NQrcVO$4NoP6$@Fn>)BpbC9`GtOKIja_0{?#nN@*7FvAl zZ1-EXL+yHd+Lkq8@WPczg5)h{zLz^JZU_L2#6=j%?dvHs^GZfX_4lkCl(q`&m1N*_ zG2)#J_*w15t~|trkg2=jTgqe?)FO~43R4eEr;_+$-ncxVZtY$Dj8v(qPl7--AHJA3 z`1^fB1ptxb4I9lnX_gCpxFh$tOfl?J$HImTwHL-akmL~o6k(L7+IFVE65{u65%k94 zsE~eX7|p)@?>p@GR$R&@xeB8zGuZ2cpH3g70tb!V6@f~oU*Y-YlNK#6@*L?F0PA6n zf-MJWKUk0!izj>J9Xku_`>jyP!)Hc8q|z=M0M|>4Y&?XIjv_iY8>B3#%tUu9hqWJ&QBF6SY3!-dXZp%un~eV1zha>(qH$g|8}b72fb}SPHdwE z>idvC6D^$lb#=A!VjQiMAXA`8*~9&3>{YG*YVwoh-6lJ+n;k|vK+r<`)9oHi-r`GLBp$t9T?PWVCSgGA4PpAlRFzr0&vt! z-HUGeq)<=Jo-HisbK;Qw3e_$JVz(;_pURPo z)6Qh? z`EAz}5AQ;G-jTb%H5O-;5zUzF)r^7RC`Ft^jbHN7f22*dhr9hz#LNc zE>w5SgIl(Y6ykN&liU*VTJYF;)5J93DB4nJeB7zfO0mT|Sw+;fzLbbJb=TgbH$VX+ zC#syb_gqcqN8R+Oh71;6V3n$9tJB^*d%XF>qz}uVS}_l=poaB{`erIx1qJBsuiTu& z3#+=+EWJancGy%IhhMDNJrT9zX5r}sl6ngyxm-ZRxC(~xUDLq8di9^qkA?5r8QIfl zM0yKHpyo177^_00b@)^p+oby>`W1N}GmJl*PuPy1I=&tKHP8OXg15+jM_W}J?BiUa zPU!Iz!*S7*OPHfN`|BzaFBy_{4fCVv`X7w;B=p6o3Eq(6<&PMA`fI9FQneXUzdP;P zoKIH4^z<_|>qXyFg|6LIh&WfYfz|;GDf$FQ1zi9$XxRl?FXaB`5PO1^Jw>V0dP?fU z8T>pUl_gX~+B9!3jZOC^zjOyiXJiusHoEAI;~D+;)pfJEx89G*Y53`}sUSb8RT0B} zYrHU|ZR*D`EP~Vi7#$~4Y0mc?lS3G#=&ckO$>*}vgeucis6ly3c3d8)nK>rha`;c9 zR=^Zs5fS?&?M-Q-4jrLvjShX5Tx(BIH)!J6C7jsoW*L{5dvVNg69KR$Dg$W4BATDn;`zy|d^HW&o?sKbjGagq zjo^;Cp`v=6)zT+))FA<%-JX;!^uRQ%zj~N<#p0rl7s{@TV+^HH`_i5!iCvWZN32qZ zk=xvY$i;eG7c7ou1;e59C2k}&&#S!^o02Jkv8)xg6cwTQ?8_KVEwC`M$aKgBjJTxA$tGfrA4qJfN;)@wfT`u3p8wz7DN0y4DR^ zOYIs7tbG+#8m#iXE_88HS!K0${SP(su^<$bi%G@Z>sl=bVT@e@VX)Q?jq0>p2z$s` z7Y5h!jPRk*#Jidp1^FU!0qrDbRk=JpedkctzmAyDgGgiyD{>}T_)zZE=@U_#wDOdO z^W|W1MD6ke>GA;yhg+g}FMcHeS6iU!gZgUkXU1%^Rz`9j)LLtezJaLK;SMctZVFMR zAMsq=;k$c|2W9~f(~8Q+Km4lknMy_AeLxDfQn0b8z?GPXN}1*WF)W~pgdqU9xbey2 z(}L=x5&cyW4_)Qy$X}~C+Cl|udH{3qd1#)w3lv?qfHRFG1dszd-pYpLgI4hMR^_J+ z*4#`sJdIk*`sC2{LXX_Si0PI|vGck$&0IwY{x@9f5qkLpgT>PAkiF|L=y6jvBitMe ztJZj)f-LOMZI#QYfzzGdLUeTfW5ss$Zbb$m=ezE-IJvg}SX~KnCEwNe=M;?fzu7bC z6#~zecXCb;eN6zQ-Y#Y^QnbsFKKN>xrHYHb`UiZY_ctqNMGj_a9y< zqyF76bdi1gC<}%3z=ok}q_B_@Sf1Ix+vGW{)h(6@+9&+uN^IfBgS6=!aY2e`?ipkFR-hon`8gaofT%FVv zHq~L)kk@7<*6mTgn#JC(Ft8Gn!q419z8#V=lU2t8Xx_eVt|Z+$Lzso+TlfSZq_-yh zI;RpDWxouXzp`j!G1i~m?Do|Smr8-?k&ETLvcaZpHt*i{eS}l8rR#9@X=sq|>gE6X zZYo+6Zif-|5ud+)&cFcW4p@G~oPKvNm$G0Ncn{E{b|Mo@ofg#A4caHZS65gH@pqkX zhJx?!U(PN-glq@`+o)3a|CuPdF=?o<`-xu;dt&2Jsi{iGy^#^3!qj9zG9BoHTrvpi zl*9tF=sTX!fT##EuO;d-K>z;U3Wpc6wxFBFul~s##+}`1dv>`ZR(wM)v&;4;YORK% z0zf6^)_Z}+lXvy7q1qef;ok9~lh|8^*GCr>Qz#2470&kK>9&bg^PEj?7Y00?TEe3* za};?L7^}66+$9F1$;^{p2G zpAq06B`aLr@yh#dB*E1S*EuK%cTQdF7i>;e=;3?q<(^TfRt*P$r$(L5qVizb64+Vg zLpoIhYdYyN?UZjzEcU7i^6~WSE?vZ)Q!8Kv?`xAs7J|TDVSFQXaB$1OqN16ELpt|B zI9B|+A(@`B-EpKyrIC{aPs+mxPw-8;7w}8SO;$f#pZ=m}$Qwp4Mt$=jIjo-@bImo8}%XAoMh71G?5J_B~vVkcgohEW@H(uFE_K z5&&|=A*&=iYMDp@n@^A&2y#UnzLhhZZe45`*tKF)SZg*M0#TPh#%yzL4cTm}1lcR* zIlJIJC4pwu23j|5Q>0)sK#Ef@E=vS*5+jCdgSb(t@7^5DuH;qfhPO!__6P4HW5NIC zVmjG?1&=Iuk}CJB^2th|wdj!4E?ZQ=j-0VcpN)wh^wkgo`V>0 zZUolD@HtfguNNZ)luVgjUJ(1>OOSsLHb-k%4hE2GWVxqp(DMLx^S@zzVyMeP8GJq= zNSp>72S2`a=nuc*kULVq1O&0o+U7yyrw_q8j@hRJHaL!I6v!R!w!faX!u~Lj+qUCT z5Kjr9cX~ZA@O|ubhSOaxv)+>6%8~1YBCuBmP+WoBIlp!=z)9!ed8u*=lSpvZ>*AI`aIrtV95RiF#r z1f)~kqVdX23qEYp%7#G247i*|Hb?HqccTE2w|qJx43BJOz@Y$Wt=Cch@P>szt?@f3 zlv&@%(ggCNwe&MbS~rOmJ!5OxT_T7B6>5Jm3R7Y9?R~Ys0X9?wY7%+fzrXI$-~#P$ z_xM)tgyd()5VS5bs-;e~uS0jEI@AK1k>68$#hDS0d{5PxR87Zwjy6luiti3soEPG% z7!Wl|md1Tc?KK-xfY+h&8Y7X7hC1Wc0y66@qtLF>IRL?igCZn}^hLzx1xU(jkd?Ze z2Zy!~i_B5mw&y3@PXeraq$T2@ZUNBa9JCaG##*&?+CfI%K#H;X%JJ}~X&XNV;Ga%n z=>f3%3TPJ-_4Pr0i)XG1yW&IQ!L_Q&9->mO6b5JKI;%ybF<{RYfwnS`4gduk?^rKK z7IA;RD@$nLM+-BHA&y@KCRZjH*)!6le49flmyTfMTRTH<6BHJ>| zj9AgTx*;g+xC{7>i~4=8Vn$zs@w*y%n%aV;wg(w|Qn|?1;b&j_Fff0jbJqc>9WBKlZ zzjUA?EhRVmN(aaWlF=tf_rdVyWh3X?z4do)DaFg7#S*!LGSm5dAgw<&5XrA1}8zCx?s*_P*W*i#ECy zBW5O_IEz#N_w{70aq|XQv-O>$4K;Hi1L3lwedUQO*|GWSVyCNWX@Co&!m7(YTC<6g zyKhDD-gwIy>lC_ZfDTgf_y~~`XT9hc2v`FOR?Zm>Z7%q&X#3&PlLrUFgmQk#iizC) zexj^QZ&n%=8eJ~%ONQ5PknR954Xo8!7nF1wb%~8S$hdk?3hAG&zvYob(n@`ijcY<*E1lfs8+LMYaqo5 zaBdRvvrlCk8*0h8K1PEcD5CZ1t)os8&zc1xPKklV>U)=GubxS&+M;%8jR~fr4lvEMnFM z(wd_i+V53b7?zEV?6hypqJo8SgmZDE+r1LqS@p|o^g%3UREEmADo2wciN!;gazLs8 z|M?3Lm~>j5xdIp@EhYDT-NQpeHu}av;k_@nMr+}U=kLZN_Rlrf&@z#y09qD(W0%V3oF8u%NFd`EAld+nG`YQ{qK$hu^r(1-U;^0( zxaZWY+$6E}5dqBD;A7d7#yYpUoXKq*NJfM@$H@TQfOvfQY9|3vQ0~Sz+Qt&OAz_dI z#N2bW#O5ZnEb^oKG*4bA(RH*!!T|ASFW)w4dGt4@(WP$wVYQBO|} z{aY`sEY~tHt}o(G$*p;%emptdi0}?pBIVvmq#=66z(B)B&g~)}%D^;y&g?iy6o=cM zxxa{dM}wHT?8~aAKs4CMQ?{*}kPgXqZT~_cs?xwQE+Q=9lIwwMTL|qIE06{WV&_}! zg-@Hz?}JfN&Mt{?uwO>0}g6? zrI@jAKs6t^MdYY3UVT`Q28bR$QXLYQ4^}has=Mt}Npp7W^tiK?)4j&8_g{iNMyAJ2kuW#E^aXe0Q1D6F7Le)*Iw+FmH?Pz*> zPy`KRyk8n`3V25CsTn)|NB_AXaBD09{H;-i>lJu~INhal|9>vV^a&%8-BYFX2HFWj z<_Qn{;By0P9s{uT`IfqV9eb6Fg7gdR>CZE)-s;W0ygPXEhPmv|#S{Cj%W8&i2mXDD zP>*Xhs;2z-3k42YN*=n15Hb($aFSmenC?!C@>r3MU;Rnh*7*-@{pfIO% z-xC|XA6FDC^X#i30zfWZ=jtWr*BX9b0%gI?lwfsc?pUlGp za)VE_YGnvRc9E0YnV9DlT-2t4n+(grSdPts{x=a!Bt0=5qxjN~dQfFG% zfzrvGLp{^#|1J3|I%hz97@c<)YKJFBEVgIy|5s_70WqRVe9_oi<8>EW)ws+hAE9g> zJI{#v|NDGDv|vmK#5h@#b%Hy~T}32!^9}9rzS|ZT|1d)I(OIf@wtp;@Ux*tjci6A9 zA+ELm)uZ_d}9si4z-9MGEKZtB|x`!qDbE8I0M%LD{U8@ zVDGrsCCBTmf@%1Wx8p*?df1ScvW|h1QRr+(y-}rf@POL4A8p?8qLCs6b@he`|Eg*g z-UGBda);hvmgl#&Oz+!;;}xT{B9_BsNwr}Cek|XM`SLcVXSJB3kuba?6*R6C;qBGBg?tAcGjLziN80Uz7 zJuehSy#RvH-T%LJH{;7Z*dTGzO*vfKD;fc_rE|Bf1FEKpLZq5Yt!E8uk%RhG%%&lX z&gA36HjI-;Vd}D>lHb(EX_2@3!M4Ip@=}0R)AXuL*x;7&)!fxQO<%<@dqA;Bfadax zN>&&jZ8ATNR|Ms>3DBaT zDXjicdK6y|Ike=esyH!%-xg>eHN4@$1l`b_qrApZ5An@w{Lq|eEcue@O`-F_4LIly z;!jJxcNC)~j-@zAXl38h0lcA75$3AA9!M^%(hJ5L0d@py(I6H2d!94-n*B^Zo~t7m zFTrN(@N>lz$D3fxDeKLPRVKDF*J}l? zJV^96$ZZ)!cf)w^=wwA0UMf@aMn)GNo&K%Q#&{g9?a^`&9>gOif~h^YB)< z@$qBouZz?ovIbIoFY21VQ!BwL?Bkjnxq-di_MlsqeZPF(Vmu{uFISzjZ+Chdd&7c@ zDdAAqj~Do4d>FeNRA4AP!bUGu+Pw?)WtO{_8!(wvzV7Y;m-LSsR+MU7t@sxRt}wWP zn#wiZL~uaA20wG&KI(Vp2XG{0H~d(qYC3Ztjg&Ub)G)d0@={$Q>tZ zTlPVD9R($Wymb?&uWgOKMe;B#A7J?7jQ$1Y1{rQxokqfnq~pp=`v?EXN^-??ONjG^ zZj=P=@DMG+vX1Yeg}Dn7gH7Z@>#7Z%fW_d*mQvz^muA~f9#qJL=!*HK{q1(a?Zp{G zCY!E~<9Z7*KqxGXs!$|77whmfd<94F*6Xy;jhs;ujC1}yVG)a}{2kY<_`_R+5L>1> zuzIRqRnIF#$H_@t1YBD3RHMa{r2`iTt7($%s<{=|Cm8l61cpNS+bV-Z|~2L+2yJQ^XWfV*|IQ52w3A!YA*1vg_MA zZR1LwiT+=n%JYGk4V4e5fVX^2J6v73WA!ZhGyeHGc!Heuw9G7sIGX;=R@rSeUja&g zXhcd6C~ho<1&zm<2Q&k>EcYf}c;%l`vH~M?17j~mox0Lfd4jRhjMBCTd=Bw!s(lc6 zYVT$&58n@Y4~;_C4h$*3GuojTx9{MGSJT*zw|%~i08I4v=&S#aS2cA3tBQd&qDMDW z2;3O0oiFmN`vI6p$!TC87*>WY@`&9LY+12GDR#bLeMJvBV(ez{>-eb8hQjMFQN(L& zRKSup0y0WY(3}>E{KCNMPwYLc#9xauaWvGYstTQSw*KHS34xJGm6P@duWyx~RM2=A z{Vi#n56KrJ_6?l<^Z%#IvEsrozaV_Jn1fy6V0y4`4ywx)D^0OGQ=e66^-#}ZR>Y{@ z=@&q&-d$TkCP+GG2<*h@4j1ss-yI5Nm`Swkd6&ZG9hc(XAH@1!{IUB_w3pT2{RqGy zBU7qKFamw|sv#RzdUm>PI2`6{cHPpeU&-fxZ|}2O3DT3ean)Gi4DiIL)yb+mTXk18 z!mQluEmR`6+a}~MqDe@MvSudRHvf?PcXOx9Zk`kR+jR%@gzJyr#Kq$v+gCDhJsXr3_`hdo_5|zTFN*mvu{Z$L z$ZTg=PT3&_Z{3iE5vLaJUY2GAow)P+21Zfw`^6{u9c3h8)jXAie`cvz9=$b1_5oTV zxl#UOJNVS9jb%(w3-r+TuKzx5l3SI;0?ZVi7}-}~O)T>A>I?iRm=*`gv3?yR zAHC$@nr$08GU#eP!!wyuc2g*>GYpVhIu>#o7c>sIsvqPVQxv{A(dbGWFR?-y!LJqG(U}kU5^HV%pfH8dW?Q_=%85schE$+)aH?fY+UX82R_scm_L@tJoul2M^)@*v@ z@1+w4`=9;2rq@cJ=B4k=Y2tvhQl1Fzhd5-f=q2FsPIw7i)(ZFWWJnN7$^AVJUZ z<71pI{G8o1^xl2gUVBoqJuI4d&5H;&mrm)izo;tnY;ezC>c{uj!{)0O!79es8V8WWXmXn`T%a_4;c+3~QVh~& zVOOJ}vCWnzi^|nIxIH_o)r(qJ)++{1?bvqiFACT|06kUhdwPA38W_IRUieXzwt!pDn&Bcjo(l&d6i8S_K?k-}ay z<5U>L>#+IYnxW`FAkdlVu~vz*H6*QE`pmroiA&W@lmT?X?crWi>$4Yk{=Koz5pL(>pZ~2h%E>nm1IdR;Uws|)rk_x{FV0RghUPbx z{ZkB^1n6aZcM%j-Q@AKjW8s6s%U3uDu3XxPnKGAg!327_nC>S0qaF?N;{m zL7m>-5A;v#C2Fy2{@Rr%nk4+joUIMbkh(O=PEFo`>$zjVt7r;%JE#7x7!;d(wc!vpSJk?4 z{GWVPn=tt57Gd+%xk!w+=!Twi87aGnLA?6E28HzuY$wvcoR#kb=Z!bpwk!q09&^+O zi2Ih6z3ITs0vXb$Lj==^P#xc< zbukai;?n9A48t}w*d2%a1%70E9X(hAm66|&Z_c^Z&{|^BPh8C&a2_Jfm3aD61@86$ z-*&8fxsE1MnX>DOkO2)+!!R#{F8mwVVc!xNjCn^9IDNzTh2t^V!1tidMfb0H%fJ}X zj=;hi@&M2%m%Cu4`x}BKq>8aKTj0sJu*ezQLQ$8DbVTz7V({Z|*1fsogH zPVLj*dVUg%8RtU6cn>?IcXKZNafg5_^^#yhuXt3k!<+|8@xhJ$^8 zGn>&P_Teps@W3!|!LnmSz;#@RAVS=QXO; zZQ?YfZm|s_9}-9hw)vPo>1@2sp)3he1ubqzsXO)RxVf)M^?IrW9X6kaJR|RO-oJnJ zQxb3iGdm%ygan*~lC@34jW@myS~&Vk*o}Ly4WnFqZFTu~Cs!NzU@e;q$;OVjTewR3 zST@g((yc)X8qQZBl|v23PioF{ZWKY9&l(0w1Qrs=-qou$?u^;LP@ilNb$r*Tur^E# zhH%gk$q=V79+-N?*mUl)QJ)Q!Q#e~lLO#}M(O){G8niCvqr((J(v){T1ckAJeN74< z5hK4B^8Ipv?{F63(qOF1&I><{?pL*_U@c_N&UkFBEI50@HSZo&+(K*!P|Js6ID9CL zned<%3Y)eqQpFR_{349LmUjF>>t{dj32AHjX{HtQpx4CsxovtwAp>eQ&v}0h^y~RB zr?)lTh=Ue_F12&fOrz;W8v;q;JQ3(4QfIF|zoGfU_A+>HXE^ir*sT$c6}63cYT^{5 z>`?UG0&bbJHQ!EYVm6bWLu=UY7p3m^IAFEmq^ZUufW{pvfB)XHf61D`b->$e=l7CS zcVu25OK$k(b${0IJGthl@FwPNozURyj4!45>iV6RW{0}gQF}z=kZ^m>p|(w=e-pu zZ@4#QnV;jmar^UMDQ)&CE=_&<=Uj62r1+aS3yj0p~^9*ua- zF<9Y$6KT0+KQzI1r0lHFnCCob=Ldv2pNrAHGll>2(|-FO-@RiF!9pmi100A^b*sCh z$$F*<;M)-dSXiMqMPNe)&Lx}g)vD2c2ij&o@}UzF$^u?mQ!SZvBmRB$sVG0p9`NL# z-r|VnAtUhJ#|b+lw6_6(t`S9QEB-6%`PUD&!>#Q>Fgiy&%(r%|e|U%fq25xT0f;q~ zTU{SkR6QYHy+?2M&=p~}2$8$8S}TZm6J{5@?O}VEu=o|ZWTAQn2Nq8)*v$r$*gQRZ z`L7b$k(u-7dI4coXv}$VvxI~4yGQ+6xDjD<>II_dPRFhy`t^_yWwXm4oH~acG;OY& zm(Jk=sZfW1wI_`yj$Xa~l^(0;2;C+D7{1W69V6ci2>i+{i!7!_{`$9r}qjU zg%yI|-|%|@I5(ISBY?!d$lvG-u+s{&dAnAH-k&=ae@)mWZ+=t272fMQ7Fsqm+|S<# z(UK^KG%1K*#rSzmuIraabl9ft(Tv<@C@_K^vqMFnwT1uS?03y{1A0R5{1 zvLOoW#XQw%0HrYH%t-!*g96OnZLk9u`e$HqxSt^usFQ&d*dw>E_94{?UZf}Ju$}*v zwitD_nCLtkyUZi7TEFjoD|!eriC`fS&|nGYjvw8zk(C_959qkJ=W@OYtL8}kHL;4$ zn6|(!n@gjBtK$(hW7Ajkw2H!tyl_A)Ise@il` zz>PDf)LwlX4$|B%KHvVI^zTxX9^7hKTRaCSO3*wmlnLU<1x^YD(PY@3jxTFjd{ZW9 zyYNP9;kCxR8sfUVacaZjGbP3ILnUy2k@(t{lk}%bqV%529bJc(M-%;h3DB-?^2vpn zSF(=Rj5L6*K(j8mE(WvFS`0i-@c~PmmtEh?jcQ$3WbDuie0tYi8sKM`dcaEb=`ep2 zfjf3*Z}bg$m2<~1??s))5HQDm^LE=*uap1kZ4Y928dAx+{-d!Qzr;vL0#5?f%7D%Ua(OlZ)@qw z-c+{PYJB?hQ62VMy^a^P|HsjNxFy;C?*nHD0*V46Dvm%waqm%S0WRFQXN7wkmYLZC z#67}2vL4(cGc_%n515*nnVOl}LesLcva<#n$xEoSfGR-b3O88BZw5J~m?_mtdc< zjj1T42xW0$D_RO^%s3-iN<9{{2J;^sC(sSeaW>WxA^QG%snNqteulSD2>=wB)NvYl2dxd40 zgv(i40K#3~&ca8KOt*u?2d%}~%{9>it(o&UsqU&Kg?;n&r~s!IXK zJEL@?dW1y#^n#=fVK%mq2#c*)Y> zd5?Qj&EqM}dwBm&Ts$TCs7bg(@v_h*;uSYnEo80+;h%4~G#-u&yj}tKrT8>&FjXSN zL-~Ygvwd~z-$yH5s}2+<_nTqgFf(|{Te>W5dOmN4>|V3JGKpH9NuRH& z4h5*6K8%bROS%H-J$sOH4K$&FG<+m59${GAHxP2l9C3wdQDxlfc^U)(jNpZk^MpUj zx#vEYf}rV4+yVEyKxLu&bbNKAOHTMQVh4nZZYp9xzTx65*Q})QR4PFN2}=Xfu^O#)d{QYH`#oZx_ch z2jtm9nPo}mZR+@iG%8J*92mxtCP&M`;p8UU}|G?B0 z4h@xRn;1h*Z4nUI!4ux5Ami?$~1%D}o)4?=l-#*Lj5f-r)=Hkn2 z80#Ab+V}r{bW2s}h#@`q$H=Hl=cOizDM$Fq7}b>CV%RVY7g`ArHKO%ln@9fcbv0I;7#^6Y}ecC`f%az&8DQf z@MU<${VimJD$>cIw(g;nV;^@%*I(O#$ARY6B>bmuKYYn2q6Cp*-=nzm>hO;NPGp&x z$_11XL;Ex9?t^@%6w12vj-zuAI3SHb@bg&GH*V~394$_Ipwid36o^c}`Qw}W<&#xU zQT~qSVTSi?*WCE>J1wRSE{>grDA(P1r_Zqv(p2A>-K&D@o)8MS>QT=7P<0jju~k_& z-j66+&OZ7$Ub@IT`iq%j@XP06Us4VnYAB-LksUjD;9OD#MG1n0@;9=8l1hflxwqiw zW8_|o)U2fk!Bl2H&`Wz=XV;&R*O(I`fZE0;ZgHMy6xJt_ZRg}-^1XITTa+JlTB0!2 zw}gIAT=&t;N;yF=?F8ufFlGEP9~{PlEvOb{Zs$1n4ZO4OY=@}tXBZ@nyuoyqg`S9N zsyw7l0Jr(fh8Kx|dnhGQ)jtar-%&?2x0$Ed@9=XLw)Wy1p* zjs`DSKxbS#Ci^E>+Gc}C-dH(WlXg~jj>&VVn2=-m;^nVP5I)qD3hjhgUYZ; zsxnwHL%?aV%Teq}dMbe3Rq^33r(9boM!(CYV0=CSTB$DuRn~2jk_L}0994`mS+c}L zv|zlcG|E_9ZO6i!J@!HxaPidx3NAL3LIr7C&38yzzNX;Vu?eD`gTI7C@Pqz;Qh7KH z+X)fKsRv9ex88XYPux{m^U6tMt@fF61NX0mgHgt3VZ_Z8x?(}K>a&fk?C0gjUXi@l zrXmTG{V<5hmp2b(OSS)C0jXzoy<>M(+tq2Z4c2A65f-8>WKDyWLj~D`uvGBZal;F! z=C|uyl$TV%5cbp{NiVB<0@ZuCbARWKmm6(+ZG}SF1H-M(6? zvC;))i10>;BY6C}@<<6^69>{#_Kl5D(0e9oPXhQW7@%_Bfef()8Di*m^w-EX0_zX_ zwB{$yqV$u4Z$-6?ns^7a#wg+-C>ht$MpuoVFQ#`Yx{74&^DU)v7`gCiq?L$^Ggw0Q za#mj;ev1}K=E=YU%F}MV!UB~G{iDY|9~b!#3`%tIUMtQOW9sKnHq~pkF;@2u*R|+% zVlu`!Do(Oh_ZIG2IVn%0##y4x=Wf;b_l}2m zJ$m^)f=(!Yej_D3Y~?ku#g#T4x~UsYPlaAIYtcUb)XdVhejRKAB)5EJo;Iop^$Z8txXX{F2gwOv*Lm(e(}%9#No)DN`&D~M47AE~k}NwIcU|f_ z)Ldv5P<6Go9mJfCGbzbTzmPYoO$F21XFIGx%PQF>ALCUR##MP?Z)fx5(c1G(} zi+A2y8M&PEmOfRoK+`E zLy%6KL`qg;p=!kmh3xjjVIVG1A@Mhi!K z<=>@hoAK13$OZBW{)=*I1GHlDsHx0Qzr-Q~`uHG?Y3?!VQ&qnrL6FZx&*~91WYX}D zbK_l+J^{_2t@1i@q@rbwH|Tpf1{gX3;{KiqTsiT90lj{Q1sL$icGqC&VZ02-CF*R5;uI@mZ>ywnN3A zT2?D&GvB4O@jsaNEy<-DF(>!EFauLK&y5bMjA*`?;!6!Pd+wD#kS&tDYG&@eZ2a^4 zg!BQG1t~F74fn&*Ej}5L@avx<3vU<|eMA{;P;uYw#FNp6;VWq}sx@?SJQaE(Y!F~? z;$UxLB30`T6D!uMo)F_Q=+V?_gALC9BoTU33i7@B;b)r61i(4$3Bj@EUj7T+Aj}U7 z&?#A;p=PLW{Gx9C4i9xF6$c-A4vkX!a?_hmOcIg9?s;s}Cm9$@2Tv#Ixxf#k-weR= z_XpVsVv=%_l_%lt9$Sx|D?P~`s&Nnh^Z{!X{|Ij2mtgDrrN~i5Ip7uias4xA6#E{k zOZj1VS-40%byGT1xh9qXJLVn?DyvzH1}J6>k(rZ}u6-PeCK5j!T0>W2i@b@C(IGjZ z0DEJCy+vNFgR(t5B2P7FNXeb1Q#1#@w{U^%hmvp~Gvp!HN62~7i28><&#=d(@^mWl z$|WY*+v&u9(gwjP z{j*3hN!HG+G(eUXsMhRZldW@YCd9qvX%XE3D(701bA^&gm)X|YZnDs}azTGfEf+@fWXGSw{0`PHt;K_a-Xw_UCD%gU1Q~CCV+BB!dfspDUAsmOWd!<_a=tq5^^R-VIs!TokbfnApA=Vq z--3qlP`v@&@{%5as6^7DPX0K}Wz zjho`A5FXW|Uhee298Hf*%-*BKDawfOaG4(zd zHpm#8xu$e6|6*YD)J#PXg=TxVtftPut`$g-e?BEY*Iv9&++lE03Nhs`AdbPKI2yOh z8$4gmZmZ@7TDa5r(4T4 z45SCsv9Y;RnUH0vmSvvw)^r18%6UsdfmCeiK68;VdCuLV2}%7b$hGGtpW`mv%>ITI ztxku0T;Sdw_irrL!$c3YvxBvNb#I+8RPpRqfbTZp zc}h`%)Zi``CwsT6CA5eKtT1dFBj0bx*30m|O%` zu0_w3Oe)TD{zs6`IJDkS3EZK*KD@av77N;f*@7_b9&SW^!O48|+Itj}M%>0&rJfc| zO0UiaaSSStP->gaD!KbSc&y0>t{!D?&-H6NQszM_%@-}ZK3r?OP~G?5cmqU4@$gch z@7Ex)LK*=1>O~CH)9%bCj&YMmBqc0(s&v9^xf5OET)uvAvGn0T7>(0Tz@HAlazRX3 zhzinX{nYOlRcZMb4{3R(kHQ5}vn;2NsLNi^K^{|^;On@yPX2-M!WZANGZl~7y|wd zkUKI+r1B|QOTrcPa{_(3&qYBDlxc9OjaPl~b=`FIyvz11jP+oap;`)Yl;O;p@tjBWX60?dAsa;i1i$ zpu;@K{yHYBddQgQ&cjdPcCCK;HDSi=ugvT5+pD7Y@rV;*jJ?M#szD{`lYkCHry*Tk zfSZTrU3zZI6(0kzw~CHMzMx-rX%7ES(6mt-`QXQVRx4T*MS9V1FQ|&CZI~Tp*p?{HpPCp9NC55*) z?(Z$%zWBT8qm%7X?+&w|EqfmLXS>|5Y(x>DOzZ{fRv!qxP4kVCy3h`1D%ZZ?^Fwr9z$hDv%TmwVh-~CRm@HJl`k$sH~B(KHfXbW6SBN z-uSF~Fh1npPsU^BDl4=`;TYh}rP)%WB!h<^Cv>z!Bl1@V&@%qo5*0~{FYGi#)1V7o zFCzWd-K@K|TI8P@Abn~Ska6)0E$iXLavAaF?hozp27)H39nP7 z;%Qt~SpO7Hq)aQkljBU_LM^y{tx^Vj{iByIT9NKl{RP<;>edbc2}%5L!I090x6ed0 zblS`oV`3xl&wWiHAXxk1J`3e$9|-3a=@kwz(f$R6z$`Dezz)!4m3RIn7luDlQv2;5 zAnwkMwHjY{Jiv6+4&y?@zCUDYYg`ZKJX3C*$b}YpxJ=gU>Q&e))@8$-Tl5i2LJuH| z^S_J7nsx7^)b#)U9G_ppF2`LuXLjbr>aHaftnLcbMDtnW_k*9)kiVmTq_h{f06zi??e_}B)@rU^O{trbMps2H_>Ix<@m%h{9zU;0tx{)!@d z#o!vg1;T_#Q+A!FHx@J=eI|YDK7LadzyG6YyYb7qmGG?bA)S-FeYM9~UZp!&YjnJL zOZFIytOn2%UY}siHK~P8v=)R1Jh?y>mW;<`&WqtSw9Aq++~%l(u+PiGG~Cw3{jXLW zoDc|;YnOb*GlCB;vqShc^UGJiR?%-w)c4d zB}<|$S8q*Tw}___b^M0cMDF_JVnv;fYL0(57nnC8Y?8X(#1$t*0vE0Yb;SaQxof-o zq;zKCK`68Ex}$_G{!zoKn~ScHe6^v{<50d~-G$cN!9GEm|4 zY#5q$-2yS!sBNMg2Qzb$4Dpb6g&VVsNJgoaqt!&S-f|fPpHrm5Fe8%Ob*B6>;R>;y z4#j3-pZ;b@4k4WSTFvDxBFD|D*vf9Z21-94${S97H!Dy_I@7(cAM<}T$-Gi`Vhr_K zfBr)8G67yn@@sJ@)&pKnldZQ(J~puP{ridFz5~N0|NCv(@kB{~a7(Xaadv1(d7xYo zpAgkHmaUd}-70ylz!PX1uUqXo50k6Jsb+K${qIc;K*eScV2G{Hmhu*`hBS1OZ>w}s{;F$Q;G~;YUHoRP2 z&mOTIq$T;ay3X0pWYb@jt@PZ9Z*w)eCsoeesJV2TxFL$#`;FD8kHFH=Y-+X|&lu~| zE^Ocs8iNYenCz4m)hhC(jFBI%^1Ur+!2sEQyB zmqrNEr+wTj`_EaTDCiDvg|xRSgUF2z95&QPx(EA)Y-b_k(Uk^^R(HBWY&5-bZ#7rZ zI=DdqB3{0cbXngl9;ah(%UwmvO)dw{x^)9+FnS-ev659o8?Dn9Ph(7s{&i@r-v5l< zgdm(y=F0lW=0Dh9uSe6$MwSq=F=dvGTkk8343sZMjpto%g3k4`RD5`Nm(^0xJ5=-Q z_jul`YsgHYeYMOo?8@4=MSE_6en28{kl9$gXmQ=PqXEh;=dbM6keip}8iif>+6gj0 zW=ylqv1t&SnGs7RS!xJPSkMRL?A%YDAT^Kp<*Vw|ZMYTmS#|;J^AY;hzIsH}oT{nN zu5-BkPUzdiCZe0wi6qQ!rpRmXUO}NMM5YntnT8`aNa6OajYUWkDh5ZYSv=aPT3i?U zMcq;Z4XP3|B$fTD zSPfWWeSO-k|Mv`}KAWdRH`!uMx_?Z$d5T4xBo}f1p*eD)ADTeAFTe(ysSg}aNFI40 z(%?T=I`^38(Vw=jDp(m1fvP6-?OFxw;)#Moy_wa$RYI;z{|a~Ky+c+rN+5k0lE~{db zS@1IgM}q=3s2AO5QB26jg$TOT!f1*OSy4~dB69G!C~H577(}1KUu!aT4;M0M zh-+v$q=nw%Ju{B9>N|%M=QkWy%uE^&&J`J@o6xNX@)dHUBI^17MdRWl3q4>!*ss}h zN<(Xf0h^Du`QCG?@NwJM{@h57uVOma#MzKzTxnR>x+@n8`MI9!v(tgArS-1D1@3wd zngLXn+YmZ9npYMpL*%N^_9fQPO~;HTp`S=eBUE^kUBe6I~v-p!`dbwUKIE%zfc!ew@C z<$d!Fw0z*%xV?xTIYtc|aCtsP`dZy%7|~|v)bAs3e=JX0g%GZ1Pm|IAN&V;g1s>_| zLP0QKv#&B4Lb1BhTkPL}aLv=Q=K``0V=$JTw3S2(7ankvC9w3DN!^&rhVlv0F{}lX z=-p+bNg_Ez&9f906iDZ0IF|q616^;a02~$((s7LoO=~R}+^7;PmJ-xNU#6wRcYRhb zpIOQ)P+wFLc8nj>(Y~3RD~^^({al)UN$}1IsZ`WXxvW@%5CFBPup6iCrN{y*7&cp`AXk9r1-y=`>K(z4D{YV4Co))LhAhOQnj@W zIk`wc{zM9&u2aFXq;Pb>b|t* zrGu8setT;|=tWWFzmU0JBdf|Ndtg{p*Hy!+_W(=k{W68pO077K{C|hc$?o2HB+8ZP zFnfr)O}!U+kcJU%wB_B&h)_6qwMH*o3Yfd(dV0hzIspY3J4GkPoO?41j6raEd!NbY}7H`WH7HLs47tg zw}13o!<^cm9@mU|Lk}a&JLygx-OZOi_Oxx{o97O43F?Y8{i)q~LdEH$voYN*3Sg(2 zgN%T?`?n_ndu|W2^$N?Iwjy?;_Z~WP{Ho4I$q)}^mDd&ZoEmYO_w%vN9@DSPKMPX@ z>8mX*^xM`haof#YfSn=^#Oj+~Z0@RaQ_V}Ks6Il`jZZhU4;<1G?#d$HPD;bTlG%PbDIhu7RW4}Ld(l6~RPs1|t-apz5&o{VAXUtwSe=Zly`2JK-|RZ3)hI9%~F zk)*pMEz3Daw536ULZ|E-4X)LynA{fuu`!w2@n)AJ_J?FkTM zu4<%%W267R3%p@EavpLK!@hk;sX2cpZ^OZ0jsy5V16ns!rQ*yfJi&L#8xD^iuM*|F z-*v;Zw+DcQHk`fRKDxO3XKNTy6wdo1U)I@Cr)RZvHfG{ur7ITVVp3N z554}@?zhK_9O1bteH;wx z!`WdIj`9Oj`!~qoK6YCGT&Z3H&Ww{UJYxuQLr2ii^&CA{<3hh}v$7N6>haBILMj~j z-A@oH8G~>|ko3vBD58RU!;f)^g#-W(ibU@jLPciVFlhhNCdo~)t_QutTDV*xbyUtq zST{BjqHPvPWxZc?`>DJaW)+|AE@8L;AAFbRVIgN!m5>T91ISl3>bMZ4d)h4wwB*)>I7{K5^g@$TBZVRW zB*`bp=RK5OF5S;kWR!c%7swk>^|!jVkyf(OG;jFcEh>MB;b5do`^38IxNEpBM|fn+ zfcOhjVHA$G62e(PxEbqsMwzWw(?F-o3noCG-F)`@^a2GaUn7DDo&TXu-$9Kd`&f~E zEP0fk%r2;zzqi>Ls)B5|b!=f>g6Kq)ffv02kt>p3I#`~kl{+gBvx`h$2K#c}jn^Hf zrh8w=qo_mPw1tdNT1Fgg;Wjt)DX*I7W+Q>mB0n^m>c(@RjlNeX;a~*uNk6!AoE*&D zl6-tojzNe4!VcnMfn1#gzy$cc*yd$Q<(!1T*E;miCD;ft+(IHHk&t2QpfZ5Mkl#)z znnE`f_UAC|tM1WVP%lHXzWq~>Lj>frv@45x5KpRt{s*(xMEHitv*6v&vV&HajH5&B z6{toDplo?r;awk#D!;;(H1jY$U|T|3_dEz$)+#L`*f7&b{aL$jb}1S!0hqwBndylx zmzz8QQJ?7s=UJt&;LIhvpE5)5NSHI-yY0j4<0PO=A;YwRS$+RGJ^b7p@+sr4+`4_D zpW-J?uDnRNSN^i+9shqw<#34*Sy);J9SG6~AJ1V0o{0WnRQ@i9DSLkFad6*c+aDSE zKW!l35iN>XVUL5KBeuD~Ju4-?6?XW3Qd3j{ym=2Pi?8S8k!95_q=%O3L>%$ZKxvLc zOv2*=y|g|#u@vg4VE)klwh}9i2DlZKG8+Y3*NaXpAiku6=a_WuY4A_hKCJ?UQ&g{S z7GcB-4GtW{r2iEI@O~x%8iU(3YJzPmPwCs+geaxssZ;~7e3b-%i&Y*_ytLgT5(7Xy z+l*@`NN+bfUZ0uc1T;3j^BHe71kF%qyL zfng=!BH_{>OCKvz(B53oQfeJyUDRJ;_spI#_u+k1WZm2roVesY&xpo4aAlnUnR33g zM0vBLRI_mE_KQ-keI`|Bh1i4Hxsq_QonZTx@0{?25Ywmq93p$5z+VF1?U?;8ObqIx zJ7rKnJ9CqjB3uv{b+{V(RL)!449A)Dvi}=@Glj)XyP6wYf1~pD)GLBqF<(pF~ zBf?A9t#m6gITco~Y%|k|{!6eJg2U=JXT}yyv8xp}^oY&+a`MfxM)ClFDFWMVGtV6R zUq1h0NwpLC76dsW`jUNY>`KU+BMF;M+axI|=~_WP_St~!l_CYcB=lRywpsw&3_7#* z=*V%Q_A}D)KkwNFhYzX(6~e+{<>SukJZ9P#(Vxfm*OKywHc!Duj&!@{J=sR#B|5Q# ze}#STwF8cLiscO?c?wfS?+?G{Ae^rC?&V`3^A~j%#)Hliq#R&!P4fhSMJFsZ^b}uv zZ2rVIL|40}k*+6FM?OP0GF{RF!RqH2ARk$HTrm=3|FFOj`YwHqGJc+Mfs;ofC8bVK z`LbxFnONY~N@Q{6W3O=1$AgSbjU988chnuIom;Tdv(dP0I znTCXzx>{<^g`C1i*I_>viV~0(lI$nryrdRC8Odk}2LUQ;a3;TZDp6OL+I#Z#2}4q| zTcp*C80=iU)7+7|Mh?(==kd2g%Nad~#f>(Nte{-R{sW}#XQ!Q6J7pt=CyDmnq8#=4 z!8>Z?$6h1Fi{xy>z4afrCv5w}qp7F8i?YU*a zzxtQ4M!PsK95r8$aEiBh63le(be$EBd)o4oQ_8y5TyXyq1Prr0L*OF$fO=o0Od}iV zVUhU{3OoqPBP?xC?7+*xN<`X#t$c3up~@aBj!1s{1!;JD4s;alTOMFj+be@ux{jKl zenDL>jIkCyD4V~Mh1NtqK?X`8-0-f#^9d_OqM>mEjACwTz@l!! zE4HazTHT`^K!@AGD?yjr?4DlVn?iC9G4D?%H9bEfTN2u6#8v2*NSoEeQ#kM%39OZM zpk&w)mVMJ9Q0dr^J$o)SequGh#4lZeM3{|vuDU_R$=Cglb-UPfwOxRMa4s%akleQGi}Cn4|Orz;qTPf=$# z^=2KR|2_+ze}}FjdM}bDkdyhs3-XbHd*esADHg7`}z9jozrl>X37C zr^fof-F4^6Pqusa-LUJlX=nMz1U4Ry^f}ZHEwH`Z8yoUw1tWYOQ;=2WTPrYH*!Q97 z_~xtbjxA3`PnNLZTWa4M$N#lGdl-LTfF4;kYpRvS4jA&rFb z*J7fql#Q03ITWoyn1sqIuV~WAZcqB?g?&l~SD>S35-dMwH82s^YLYrXKyCKfGq~Z$ zf(N(NU-!2uwm|r6`Gvr{rx)cz8)}v}OV*|ho9tpI@J7+9L$}|Vc7O6t8BMa~!k;Qy zHlOhar;hqOjeY7zBw@zqUEf-H{UThq#6`UwWN_~GB2v?;lasgc?#-C>a8 z#MbY5k5k=G-<$;fyLZ>I+?QX=4x1tVkZo`j?AKBd#s~e!id- zZENga$WWY<0CE6j6DsE(|JnsZ9&IbZ1!p1GuO*kM9#`xW)*eK!{JWRFgopqTP-Hx# zM<~vMDd>fb^)%2N1nbQB24ZfNe}kSSKIq%mVu$&k+i<#!jf_+ zJg=zs)<79r>$=$ZqMGaDMzYLs^|O?UpIl(j?|eTM-9n305yYDW-S417NX_TJ+^Ohl z;9(SihO;zD7 zyOt%08d#O-=Q{Ek21Rczda8ua9LXD2?$4599H!z0|F>*36GOE(DrslUQ=Sz9gfn5U? z$%zD}lQ`mBlr#E6-Md$l5i2_FIqQNo_Y3=WxN@m<_?TT+c+Gs| z0k>uP?P!dmZiaGc9Lg_D^PmX-(>tm9;7CC^Iz!Go?5^ZibS@Md`llkjYqi#TIk6Kz z0!e4?Kd5a}8?KJ;`|u~~;l&TXj@Ao{&G1oeS3Ly2wHYNm^%}m>%(k=eK9jYe=?YHz z91zy0kDIuhyc9vC9MS!FIabp!tOAAp-$Aq=(* zd${P))6Vyx+5H+?4yt>W33q077%m9Em4{DxfA0aIc${W)bOc-}ZZ2g}s?eHEjc&B} zCkfbGttd?%6o@ofV{-^t<_Ux;|9;ICDOTT+)AR+!*0*m@Plvp*+I?k2S7oZ= zm*aAZt2y~&hJ{91jl*~!)(tNg=K$KE>OZ4%=J<)#fC!iKij|7lRy>nXiV1z9(WWfu zGZ8XiCIu}GsC8RUfc0(>chKoas-D5T3#3zBNk&aw#Edgu)v)Y0LwPPF7ioD96c?By zfq(jNvBI~@fhZ?L$9cp;w+HX&4HUwCBffMSAc_3b!&hoIhSmLtbu}@uH>Pcu+!I=% z%23V2-i;_|o~+3yP__4;y8z_V7+%;M=uh5dLe3yxANLs~Ya?Bi&yi9~*Z|pD@C0%l z!3OA^N0MsVusyRk*yuk!(;90zPsRM?RQe7Nfjkba1ywa=A=gLOuH;qV!RBLJu_f&o+HE{65c9oOLrk@p#YY)qM~*foqYbG;NIJ z5tR*f2qy3DUeVP~{+vg4KMecYtLIw}%HCbjZuaIqucpYvZu!8n+E$l>zHV|EJ@cGsV+lRuFVt;t-yweWThS zvYWCPh6jv(%)E*YS@zLvV&D{46veC?Fc*uqWYWT;0#K{d z+lX@2=nFvZPn4t$T^L}|Ehsfy=8Arqq8$&cI|k5CtPa;s^Yg6czoPq;`hGsKHrF=ZYhL|Jd>qRW_Q4+5v z&xRDHqC>tfRuirQP(HISoiDSo#DkeS(5nTP%`T(J444@Gu9~NOGq~rWX43q+0F12Y zF}KZG^c4kksi(01tz&gN>3@dr38I#z?Y6uYTA0?ozKurf zdd_>>Fek=1`EHm&_bC^#%GlXU;T?n6{)ENy3RN~rksp0u$>O578yS%?HytH1Zn$k6 zwlM{gzZnkXUhgl`BD%VLH!@FseD-GUeBP8SG3l203(Avy&XN0YzVh-tc!1N{!T1Zi zC_<3&aoyFle@6G~j2v+>s_Ic1j+KQyITP(E^muU$gexGV*r+_cEUN}oD2|Y50u18{ zt#MH<8^d-A4PqVYlh;Tt!+<}<$?U|hy?l;x8fdg=eNIhoCcQnxBHqfaES?76@EJ2q zhkMntGJT826o;`q?H)0Mu@^~ZH2`hakDGd$x>2S$I(Wv`)BD|r3x@0P=RVIG8v5HE zd}svNm2@UIW$5jd(a(Cy4j%QkdHvuQ_UE+Yx|aZfJ*p&gP-1i98gv#>xW9?Ri~A2V zYkNKuxJ-bNyc>&V#aGh>t{>V~EZ(i!n`o?^vYybe{Sa}DZy+aJ`Alm(^+W$b$i7yt zuS1~y)=nytnsV5+1_;)4i`Qm;iz$n3wK`V}Fe_yK|k9>hv@HQhED<0Uu+QbMzgU;qI6$jcz4;-vcFGb1pZ~7gg zJHzf- zn6Y%AOdiSIhFv>t_Y#ank3~X2IYBUw83&L5Is4RZKoRZQZ~2GIH^QrI- zg3R+LCcA5r+u5PkHR$YlY^4z4AtD_CqKzxSCs1(44})%r6orcUGP~cFonHPUZsN0N zXoHV88!Vrf?z0l4<7nk#LGsvi2#1}h?155xIGuDqrzsa;RZjO;QwZ~rl&P+`Dx=jr zJ8i|>1t8PKMhuzm-bcwg?x%P9DrM{PV1Rikyom`OpF1Y}!nk!P4XFR?VVIuLv!XHZ+}d+699Cl zLa1-B=2Lo?4w+sNnyO_L-Hn8uFah}xAaD+d%_)7{uI4uUh%;oEz&534>QI(vTQNtIf9(r3U30>}e!q@gC| zJ9h{BtBujm151>$K@d8c1H@*rq8${caT$fM-OU_?r!FXw#fn|vWpF?`oJ`v{jGI0I z=eGe$4(RF{t`k$e#UAht>)4@GE~PVdYW zJJ4FUX&Nyc9lNFD+OV`rCfJX?>kl^uWL5*YyceAwV{T1l1qjr*@a_%hc1gDjTeIYs zmoOaR(UV*2r>VoMP5gG&m<^gphX+nsjMmz3#zG;4isS|hXLdr!k>b&r|5Lxr0gx}& zoZr#pS94bCOVT)0ZoUGV(c`d_P}vo4c$#iuH=^VMqPky@<9o`%MB}hF(uKJtL9Q(Ai-ZVp8xO zrX`V*#}NC2QC_sHYw+_2eBkzM@bT{_N%3XBHqG2y&h5m8Wp5a_)Hsl^r`1E?waVr8 zx+FtZ1#6L9Y=Y=z0X?(a)A`a~eA|x7S$UyVZGJJ1|Bq z_p$BsECrtKfocJuPh!_CFp-at()sQ65QBhU-j41{{i<#$gc%e}fx>pVWQEg4^)wsG z5NF!Ue{EwXX>l(q;k`@?=WQK>omI(5wyrJr9ozpYyE@st&9vo zEaeO=`eLTzjfK7DY29TBD(ynR6_Io*DN2=b);?PS7qhDneCaG=x7NHuT(eqMEcD0P zK4FBTr?xq|Un7nX#kBDCLK}#KF1}K*9D3~{F1ODj8#H z%ICfq(B59LU5NKT)YlaZZ)XE$kJ%msO2=`e@Kln?<2Fc>-XSf0h5#fz1xoDk?O#ax z;iBlbnwXGQsQ$E}C(_pr-7gbHsm9R29O|I@KnU6%#lOeu4uW`YFf>Ez7@v-Kw36S-MY;y&@%uv#VrjGJ1v} z#H+Xe!jtT-_}yA323bbZngarI#?S={w&zl#Z!fBE{qhm6;+A9`5{e+d`kq)!4GfqwY3VpQnm$`pLW-kl2E z9FBCT)_w8txpslDyby0xE|v5B+T%#Gr;cM=?3h+X?1gbU>N-ggwgeL#mBvF)wW%wU;NlfP73p*;&icbe3_i6HXbETHrN2u{N@3Sp> zw9w~PT-97_+CTzvJqPu1uD#-&3gWu@=sC`>|MvO* zC!{BmQrgs?b3Hvdckae?(nD>vXOAwExk=-#lj#OVpleFi^n2bn^boESjI0PN;<+g8 zGTstCv1y^Q4Uzgw^Vjd{+m}_kLw26$AiS!kRSq5e_j2Wzt7;EYx4U-F>_Y50sI%Rc zDz#JAOGXxNHDDLLVYhV_?uFbj{suMVe8M^ID&;O%Nf)POJtTL;bU-2{D*%PqsT|8` zsk@kBkBqxFQ9GQk>Hi?9n1eXW0W5@B3a*@EQYy0oGEuWuP+2z zF($PyG0^R!w<>$Dlxidl?Y3r6BW|^0ojxlTk#A;|p@D@)*2ZtyQI9;taI|GM>M73Xb=fQ(CIYIdcI~ zV{o9kJ{l5x=HJP~+La zeX#hy#rxh_Bjqov1!XP*c>6N82>>;ApN#1Q3MOAwiKV3ppSGgTb<|83vk*%D(idY> zFWi=b_gLmWM|Cj@zRI2YS3DB(>)t7zRDjDZ%hHEcJl#(zB7(hv#1qFPy3PSRAAZz% zbp4jQod&&oakR|vi75kDZW~h%B-U=myk_hsGU!d3cRcVHPkml4!M$q_`qG+tZqNNo zKiGY5zAqd{I8#TqtPfu3adp4AE-oCzJEyr?=hfL`!qT?z#nDZbi^rmlPAYD6m%L8EKzGwbb^)7c`k6Cck)zL z!sNeaZ)t=d_$udbJuRYmzHT@N+P+E_5xn3xHRUS@KahW!p{0I==R17snW2Pgo6($V&Lf8r4s#rQrZQlw%8=(-0YGEz|+7=^4E zdWwS1Hi5nG$2!(Xv{4xM}n_rb=+n+TdlXR%Tx^KPC3Ftf>~azl&Mp zHWFL5vHFc*`ukr6ug+dYJqi_=$+B=6Av|!loW`tgh^tX%uJ^Yjr>W#wS*W;@ARh&m zHeK2c=x`gJ~Ec4-T&zwRim^#kXsydM)PBa|ZD6e`kD} zl#OJUx4knIo{WJ>5z7x2i(O|y+q5TQ^|yHyb`5o+d5ut|Va})84{Np(lx1lpJj*z6 znj=40!VnF+)lh-`oBvutF!otfoMaL`?9(*@fBDOUCJP=`#hyPv-DaQAb7a_gNeVFA zp|WaX?KRB&WUZSWR7-u&8iC}_rARY7v>PBw@>q0ekOU^PFOs2M(C+pvvkT0gZb*S)WbjCCquQ!5i19L&?O^nj@?j%K__ zWn!kun#Y}}0oi6trrp83S`+SE#2JM;Mkk44NeZZ>&?2+J=#x*${YzwevYx}!hRe=A zK(MfE%kQ6Xg&b++LNcyvK2K8;e|)itT-PL2I02Xg7q^+ErGWSneh%chy%GXvHYh7o zc&nP(N?4Y4XTOrPID#_>K?R%iMho(n812qo@V0Mf6z#oW??&TAqv;24#>M{1$g@FE z=XMWnT#xhmN&oT(Pl>kTWIR~^lCyamj`E^`;$tG(^KC|Av{S0CW-E)2vMx*|o~33r zf7F~#oVd&`fzvA68#)ay%WckTN!3c;9K^y7w+mKsBzZZm7lfe;4tll{dQ7pIWuyXR z48K0)ab${$+||D?s`2KhG~I@aSEs1(#_3vybvHJREXDtNS0d{Uf|{>Mk;KY7P_MU# z|H;bB`BL&{%_RpJ407W#wHU>sZPu9>$Nfs^8adTZN#X{bW-%=nf~1OAlcB~FLI`K; zuB6XhJ@Oe`(_)i!gxW$7bk{1)Isy+)TxO8eQgr_|u~L7?>s%auY~&wBaQAOjG%jEX z5W!I}nB7>dbggndZ47{z`l94y!9zGLPlIfUTKa2T-ss3ODUa2+s>r>E2$@A_+J>>c zzKdindXcdaaIcW~W*M=5pMMR4bbjhQX*nzuDQk|Nnm6!BLE4>jp%XZ=0_(gMw~xj& z*G-X-t2Q)c-b$tMF|Sn5DlP|IG0?(c*Agb~o&67oR1l*zMoZ*WZsW8OOMo3SG@^<# z6KGJ=(aUr=5}#rB7UWAQ-dJ&oWGwG=IKJlopFV?aUkDY8Zx>7x-!>g}mQt0dEO^|T zma^0uf#DwxFu7#MCXf*qS`nY>&KbJ6E`a|Z(`WjD{kyP9j3Nu1<yek3^$zK>(pF8o$`K8p91 z{jQsZf`d1=hC}xh@FI7r`ed^G$s8NO(aA@pL*=_d6e=+HtEM4ds>TZxLYb_1p4Qy# z{+@VJH)LcHp^gI`AA93x;bn^5@Lur~Sy@638h~pCzSx^i9B=u4)=58*5Bs#>pA<}# zx0!C((U_aIISvo@`*~TGrstKgeTZwv1$#z@MxA?s@*6Y;yJPk$--A85w7$Jkf5M2C z_BXrWrthsly|)`%?Fapw)57!kkbD7J!wBn@@OdZMQ-pMXQf5pLPLC!U+I+t%^9iNT zSkC@dw#_Kv?|u3>ZJXORM9ejws_mDP?I^`45jH~EaE%K(cKpY!eD1ksF&=5h;at$# z%Zv=7+4l>wysV`?`b5vE5zqk2aIIjUL3+vwC!qabK{LZB`|A0_m%^^c^W{i;Lwv%z z9ieYsV7okDAQ`-&KYUm0pSMp6)he<>)j~#=rqwEmReP(Z7>JC#h*S%h%&_kQPfFN! z8>^HnMNXiX+E$q-+C~!2oYUPTtrq>sK!ofDX|<-lweg!pNIlmxI`KBe4_Uy$*eeCogmX@zC+k5dA5?z+mH>3>dxu7Nq#g|_M$ zOy$~Cq+N(pE5KlNvR;QJhUD^g8fn;eH7s7)OX2`Lw4I?k7<|eh#}?(?qX1Gt9(Wh! z)>9Wa-;u%;V%wo+pDr1hpH9U*kPzf>1GI?V{f7!4Pa`}=5uAPAPh8)m+~Wx9H97y3 z3H7R*QxnYJm~kKypV&o@Zu72y#@e3#SE7k?xbhedx#U3UJJKVT5AeF)e0;SH z#x7dgMo&8d$1fPPq2OT(Ejtg{3~6cry$k|*%be@a@(d;#b#WHkD=awb~Qko zyZEJ|Tk{g>z`L03iHKA>d>e}o*=3Qf(7s-&UVr&ZA&+2p=?k-y)P7_1mOzhbF|KuW zb30dKs$=Cs@k$J6`AeE~x6xJtRDq?#qLA{^aVii!%Ag=|rQY_qwIcziVO`?72H{EU zuEbkk{fYG8NKeoOZZh_@2|2p{!bf})z(hZd3`VV8Xzn3D8)&N7)6s0f#|;SN!^mBB zjUVgn^fVzEpSk>JUpnsQ89UgvV0vOHnu8 zUmv&Sp)5cSaHs;0uFp?%XVQz8?h zwt+3)W|5}g%LP_@UNd>Rp5u9{eKVdcS}T$?=kA!$2dDjS(A?kLi?kJ_Rg=B`5Pp{} zFpG)GU%msG;>xe~{UhXBwgW&hx0UQ{G+b-Ki9I8$3ey@HEaj###E$ewdJ0jX?H2qh zw;ct)@m^FQc8wHnspf6j`6q{VWjAe1UhLxtj(o&;o|;zgB{8WKA9JX5c6VMK&n0N^ zm3*p>r`|fzY%*>%5EXsl2BB8jQ27IabaYOWYs)OV0??C2t~!Mj9*4=V(T z@@ft2f_sE@gWr3u`xquqOSj1k+6{Jhd^P)$3$>Ih%ncUH+8jiYn$2qzy9H*CdR$+1 zw8od7p8Z#PoL{)sr6K&hs%EL+F~kjGQ0bTHDm#Y%b!nE)6v3Mt(MhzuJ!I7vspH1C9d{dn zX94zO$j0dOoq-*$AFBVGC~Tu9-<#$c573x=hhHw2r7i{@8nE9gbva*NoX$20}Ib1u7+Lf%8R7_MYg>1N$KVlR0^H(X1P@E&H14|I}j=HKc}%(DJthw=~%vaY+oE?o0t;O z={H!Lv9I!>2O&>^4W1@lh-8>%WfW;mbJfJ7XR*0mCxPB@XpHB&;*LL446>p!sNp(Y z;4U&wc}&`L)Vp6hov_R-ZNu~eC|A*#aAV2naP6cf z7gPnh18I8oaj~d`>7Q(m+&^H=f6lxqqsIa_uHEANewNIV$IbAFMH;U`jcpOW>@hx= zIT+@G&`a_XQ6Qf{MtC1H?v8>Rpx>Yb~mS#xAn%{n8 zN_+mMxS@RZ&d+3}C zf#~V7;*Uifdh&*!*v2h<=mJo7-Z){>O21JwV#&H9(I(Xt zY#rG{qCui#)lHn!o!&hAbu!#C;FcO^=bb$9<23sx{L(GoG<#!Hwb6w}9jV6ndC4;k z|K&o31Fd&xPs8>+W{=gNeVKYwTo!xodGtEOe+mLY+kcRPQDcK%-Q-ZrWT?$n%e^{Z zyKxrvg4)(0|4kyY6W{R7gP(O*9Swt$4Hcg?WnO%)Fu4%XQ@rKi((Kg879E4(VNd_J z;D@L>-i`A4ZTshJEVz_4w=V;aP`0}w3~X#mX5ucTPL^Z!@JjJ&uULi6&wy4%zk6=2 zKs?%V+Ad7|`-^wLQ`{AxKcweyG;X$o2-v&N|5t=c$A;UQo!zmWZcOOL_Uuf7CrRup z;v;+|VDNOOV}sy>QI|%<;;Yjt_OU<(cCuT|obJzSeEkcTR?@3S7J}1qbX7Ofic}QI z^D|ocUdLHd3c#2A{vk-gYq>w%ZhfvJ=uSeS{-*p(4QI?WoWO0C4^b4?%_By(gZP!P z2iw|0L)2b=M%~2Un$Gmia*fSJ{DZ| zw%Kj$kk>pF{|2<}gNE=#$x^PZiM`387Q@}X?e7*Z6l}Xb1;6y+TMhoF8(Vh5s)3jwwjZ`P z$hLbZvaPXDn3aUp@2sLUzH&}yl3h;tWlU64|3xcRMFFRTM}`UM>f+_?9Z#2Xv>7#v zVbO(HcO|aeU{mlNb-Ir zquzO|y0>}7Zw0&F`fLc3_rRpWds%<)v39p93iNA>d%b{M0~{BS-9q>;)3PydlYQ4k zk4+$3=FS&)fpy-vO(uRc56yO#xRkz)P6Jxg9!2Q~`_-EwvajubS*q^7yv6?OXz}!f z+2hCZU5ej!x9Pm=@F?$w{U@&P0VAovpDAcpTN3!X&aXdh`;Hd{oh1G`+Lp!^fHXd@ z4UXQtgVnrCzPhKbuGb4sK`~Q{vYC*f?pXJ0w+&{OVuk{&UxUoFzZI{qF~DhO5LG>XmMH zjlBF`wF#d@zakQ_r>?uc>z}=!kak(#l||?Zoqm8OAZ>Y575N@6JSFcR!uax$4(|r} z(%x*;OFy5JXZA-Z4F})VVcJ4_T5AVQ&-Z&AtX$6FiT-@Hm9pU%4BgUoc<#*=@Lgm< zU-~b`SS5;idc!?|C!3ENK%uWEqip%^QGW%Ti?CQ(FCt;h5D{#)h?1E+>H-(%)TsJLPUr@%-=X(hlpwTPUcA z0g}U*tVb>5y9Edpo4Sa1Ae?Kyn%9-66=IibA>Fgt0*2`q6L%=aMcre<9P)4k;$jPt zn0eWYdOZ5erGb>9;RxpOT8vwXx-zXI;u1i=-1U44V`4d{l%N(RkB05$qkWlanp%%ekbJlIY%9MTSEeUG>Mj zNipvRQdDCtXvKdhZ>tG3uP>KQ8hY2T$fl5=wHFTP>p2&0zWUO_ZbR*3W6gtE3tsC; zt0%XRr*Vi(p(f`3HUB9xCLh_m_+%H`5Nl`?aXsWevn@wuF-R0|a2M20HBA@VOXKkN z+b~>w)KJO@gZY&kK6>Rf6fjoTucml^BI6K01?A`U;!viB5Oi$gs|Y_8`5-h@IQ5w7 zl(~uGOi-Wa!(>rQ#76SdNT(EyaJj%! zL9=*Lc`F)HBxu{aLs83w=fXN|6YgrF)~menWQq@e2NI_}BY&PGA1H#k0N-O2aL>X@ zWAb0bJBiPQ&rkeUJ{`sYA{)O(=$}GG=}SbtSe;YWR|N0#70bB{gX1~tKXnbm=#)#B z;PS#H_>%|d3|#8`t#8rus>hcxU#In4OfH!frA#Y>FcvWFAw6=hwEoV4nL}Ne zvZlya0#ppnf5T?_Bd`yktP4S$N2$|3dAFR3jNlboZpf1%{(5 zyIkYVg}R-YDxMmyZDH;BoE%4wSbGCK1EcR)VLD35`jc|}vvt#XefeJE>NH3>I$Z@- z)#P_|Ukp0!^{$YdG~IuGTiU(%3Zy%xvbMY#GJsE%+B#)Qc?|e9-$rcorScTJ=i0io zu6|zHjJMTCP=3GgZk5<@#a_W56y6CaZeSKQLQNq)1|738zD-(In7RT(| z3wB^THnIciQ?9_DsF3oeZQfikbi>5aBng-4qX=Mk7A$96V@5nt7} z-qaRhV{NILL+|<+@b@ImrXF9o_mw>ghe_z+u@pP&yCotKjFz-VPvs#TgnI}&^*r=A zjwkPx<1 z*RUAt@y3xHu{h+QqRCEUioVL30$BrVaUuJ3);Z~ zXk>e$2aZudLx&DNy=HI{$KSqdKIe2jCbVXq*yZu8hyjkCA2G19MC4h(F2?RD*0IJS zT-^^FM%}7%JYA#WV22F+6WePT9%g!MTYRo^t7BEla)WxLkbK_45%J9BVVX5jg*4>f z1F=by5f~Y%RuFA3ZpxXr7L0Qug2nB^ULU22THxO~{qH!8Utq@M`Ag?55-5ARRQz-y+pKhB7-TD!t7h!m{( zME+MDj*mIW?>zkSn=79viZ?O)FLA)eOx2|ES8%9!cHJBTm5BGm_QiNWfpSOQZJq@Uggs zQepmKf_sUxV^x!rikW73Mi5<1P7){mmwf&uZpwK_J+SQ8Bea*pER?cTC#Ao&&B>|P!6L&NNK&m=FKkRfREyTE9zxJeHE|T}>eTE~Guu!ZSEU(5-sLXe~&qjBlKm1XqiQZh0NPxUuw^sxyU(zJ8kVI(&Mh?&+a( zR?8vCM`PhVTIPg6$$XNjqUs`N3?Htab|SzfTj)4FN8i_WqxntUnjUb~o-7O#Pht<#&Rpn1|OR zcTOM-)pkwZIoKgb^LpUfr@9mQ1JZZ|e#RkK=yZ3Zd1jY-++d^p+d_&4>Cm$0;WgwLrb-$^rA zcbmECxa%ARQTU(UZ;kdXyB{b@5--O->^bhTne>8IIrla86Iz5d9Ul)ceLNE~z$qsj zlUvVLHq`j|8|f&7sV~q!0PdXOTMLxbnIq1!Y^&PwiSE2H!1%X&|4I2OBmhE6`#z4! zwM{MibMIZLbm-%AFPnTf4&P*gTR0p_d$9{)!n4+dtx382DeL3_z+{SMqA+3=#9Zc%GKO{^Qf`#&9&rB~m*!5>BrzCr0 z7>JyW^~?YY%EOs)P{YnH*b>v=S?2s$z)4#UQUb%-jTN;@Sqc}fE>B&!GPe(yjn2N8 z8Y!jt?infMn`B@K`9sJ!?yc!PB;qbYoH+E9FLGFNePk|`tE?a@CDQoLNv_uzJgs2d zkFP4Pu;mUTuO(~%bW({J!8gXzfy;2`93L4`M>m6STt&@Ue>}g>!!2N3_u^5ALK0#7 z86B=eNoa|W>uF^4ab=B$hlDfth^C-$u;0nyCE-#eKg5F-s{A&sIeTym z#?;k`u@)h>UjZYbR=GT@`Z*3nRF#9b#_+nK@QjKS+H*D_^C4+;Vt12lHR+E8?6k{UN3?j#q1jz z)q;whe{F_5feQH@Q|}W z?r6sRFJJ+uD-HCx0=o1hMKQ-Ei2H@cKbS>Vh>)87ipt_YQ209UM;hQWr;er!h}N(k zG#~4SrKfAFj9RHDJZm=<5O6^+l-9ow6(kx43?nCbgu!g`U17IY6kuwqmP+!}3I;vt zlpf)|4@#Ndjltvw19WYlUc^;-89kR^T^$==8zhDYv&L0@A{JLJ-C@xQFD|MC*R%`M zx*ykI-<&TtVt8`8FGo=E4Te^RYH{uK2oJTkn<}b-VabMmP1?`mPdsh)aeH`MrCPb# zbGE{WQ^}5ZedMEEbs)APGcfL7Q1u4+DD-?L@Gb4dq^>2tt_8M1Dpl#EDvTN5pm!Tu z14;bp9_=oD$-*BYb5L9E9=9Sm>%)`sZX#RSQSn$Z&z-OtckJqW_7i28_i`*g!eXe% z9-;SZd~bx}5*00$!9+ppNnFm9361-}lceYPRm<&6Ic%rf=jx~!SG@xv&;F~S12sS; z*)u*##ZRK$6N8NIfTDqu)N_|2T{f`Keq;?8F4-PZsFZ|3&V zlfhib&}{hSjd^48r#~Lu8{?+|y3!2Hfi#{7<{SSRAAb4_#&{>i6=}vlbpm+8tE6Zi z;V^!reN;ZT<&$K+V?y=HyO=`A;LhNxNx56?NOuceoad)wd>z#wq2-B85z z&l#+}598x%wg@*$`Dbn`qADOn{e>Zgf6v5E487DfI>C zwl>_T_n}GKXT&oUu9a(St^G8n?wm8iOFh})7eh^BvuyjP+0rk*#I}&?$ zU>O%S)SLtD7aHJv*wUE2wIB2A1=iD#BDhezSLx2@MT&yq*N4DD;C9c$&Hy+JS8G(ky8!y|EC17C zc#d1SK-v1^9glQ1ct}{Q0?DZ`yG(TzGMYN|;QH5K^(^w2)!iDNpZ2SEBcrHKaYtNi z%{45jm<4~$(0At-T%98L;is;_0Oix}fgN-3za(l_7{rhbhrPk5(=L)Os^$p%4n| zUnNw-($UizX(s7Fp>@pPv$c`~y!lVBBuBOdcXO@_B!cdYzH1ID&-8n{hiqN!FCE!_ zqMKMH?Ivq&=md=V&ME$gPwMDbZm%0V5#TNcegD+o@`n2*x=k#A8wPB=m!G?gcYXd4 zO5)Iioy42>!aF{?>RmIm_+UOB;WVYVG?}1)V19G*88La(R?rd-EObkJ4+@?G3mjDgLWg4Z_xYFLojHzO!Rdp`keGUqZ-OKjx0&g%^kt*RIu@jx zap81%yv<%Smp$AsnsR&WuKg(6aSI37cN3yt^~&h-@_&Vmp60qY7z@=xQP0tAXT1>C zk3$Ae&uNY^uS)9)PYs4z3*mnNZ@O-rBbu88*$A=kOn=pQXMl9@fRNR#dlY5tyC$C6wR!iE@a*)xC(pUa zTZYYt$s5Z4lv6(SmQNNo9dymAKmG1l0x;h;PhqaT&}OJL=FB_U{@XIQG3(35 z0{~2+u2t!iivEI~F9LvL0NqaDuU8!>-26`Z_kse~-go#YKU}fg3fX)5c#Wp!hKR)L z+z)Erc1hn7G-dmPkyF6(9}|Gl%KNGT?er{dj-zC$R0VS-+SYl^4_5Mh`lXgqNgX?a zlGPo&(LQ+K1p4?Z7g5`{-S=EP0-o0Fd&s!(_~;R*Z_5%T(93?$RpCND-*gi)1+-1? z=iovwnas|8uBAVJR;SP|>Gavf{@`O&0)k1nqcVQ?uB>YKIwSaPOEDit*c_w2TSY+4 z-{m~{HmRm)4ii)@Roai0-A*IL;YIw~?xOA6e-BnB8Pu$K_H=zLjB8joRKqUX2KwK) z`r*FXOH13j@Pt+(PE>0Xl6KGP)p;WgQ~S4$y-SFPD%aW(CA<&L-!~T>={SFFP@iS> zGclj*cC1A^Xa~WTmWi36>kb!LoWnzIanc@y+XgQ6c~~cs6whna7w(zZQ}pRVc`{Gw zIUMbB;s>$9c&hu#_x8-WHRaoT6O}L!)7$%Te_`+4A6iX$FZjYr0B>>`nBY&{R%Vd< z5m>5y-gNe%JAW#pAR9EK)&3$E3yTWgU&AI~=8vSP{O?aHv-tnnUEuFB*CbyRS=7Y{ zj0ByBo(isA_$S$7{xzgbs&S+5*yHDS=n=+CZWP0k+`PWxjGrv!`1LXTRzJFbcb(GX z%ONZI#jk6DHQjIaJ=rnKgG!`iHBAEvV6SkS80HnIWWx4hx3u6ZT+c5>SYV8ZF6Yg|{Nfl!a(RWD4-xqZ@=9qa z9}8blYHrjxBi~0;5|J1ED6Q;2=@-A*c57ffUy9Z?I2+hAJ1qk&s)~(eIq$4k?%&*QW-sa`riQHw`63 zIwBn$EqjCvqrSp1-qo_Nf_*7M{CPp3&>9B4|LDf9gPpDG&${JZ#Q>H45j&ELZnS5s zGzbi_`KTyJ%AMjxSmx`&X7f0KylNUD=-S2?QTGNMT_rvDJ#^}%55JmwR9J_HiAvqa zU*Bb%ATiHW+F2QrQfupmqV&j7?en(l8WT#no;gxZ#&qFLlDwW;9IJ;<;k^-|rX{Qv z*Ci@2)ooMnh}hX#mVm^{Iw3RA86t)Lb$EJs3hH1tQC9w#XPC>{%jMsr-yjVi$ii8V(R1zEu8{I=Of&@JLUigLI5-Ed zuQH`pS~G+XF+Td}&nCny$cnz@9IJxt2^Grw_nCTNy+q$e#x^0U(a2de=}DIvEsUx6 zn_9$2AljK==uPA^-q@NhcTt0s?>l02~4U zLLmSD!T;lx^ZQ+F|U%?<+ z<00>4i%I67_&hZfv>S+C9bi4EMc2dhYJ3MquX1$!`T|YrrDoB_UZ}VAjpnQa00()^ z8(|MZ=pXo?NEf5mca+yx>HSyy&E3uoLg<2a4$<+Zh;YO?Lxbyb_v`m)pCWvfo75rJ z9=3m)WSnS}zk!{KB>)Dl0BsX9{G%wlDI;o0gQV6yx6aMMIBzm*X8`o^U)3Yms8Qum zelv8dni*hH?6~fhh;ugpTaEMwXNCl4c-OAu?i?*GVQt#2ZVvz} z0;X*%C9x3>n1T4_xWgHzrU@Iz_8)}XY7quWdg#OR#}hB$#uirzw1EIQfCiuCQ>5xu zOGY0DEK^cde)I{u;DD%H9n1RTf&m0SdALJ``XWKezMf=Wi*)djOIZOn9abec1JmMdjr!1BH5d`k?)uIFcAJ z=C`{`8v!7*<$DDi%`OR*Pe9vz$CMfw2){!BlSh*jkm{aAlcdNMp>fE!{Bcq#4#BmA zMz8w{(L!p)qL*s`=sh)4QSiv`g3n%z1Zw)ocqcPkA8B5o2#MW&?d#2ZN_YZnssp0>Xu%|15#pkE z;~&GH_5cA{rqZiC$>FJiIMchRxs|52Q2iKG&DpFvRlxCJ%Z>fMl-!(}z8A#08x1e! zQ?&d5T$e7r#~t#NF$=xCyNL?U8ezlZD=vYTm1i?-{O@RH=>Hcu+nRZ>l(?v$pk0_@ z^ZU&eP0B%>k85CF&BHlrfS0W(LH=G zVl$eUyG|n6rv0dqh|j6?{_<(+&D=tBM^xF-qPhQ6jzPN0+QnJwjC(p6e*`R3k#5wf zCG>t}mk(-$y!#|MBAN9AvT_*pE+S#ZMX!>bKrbm1QxFyfB=GOo|6K^4Tf6&*;$j}k z&UQ12C36dzkI=3x8rT8dcS{xujXNIPv;o{{XhY$c_82$CemyHJ^M@_iJ_wAG zRLz1lo^er)1CUVkIDD6ssD1&>r*f&?^>BTU(>E~}Pn27^&G#uhiXo!8P2g+2L@d14 z+k~+qGyqBETx&o#PL=07%D*|6&^37V(qpmC6aWPugqRF8f%(>+m|(%AZ|kg8=P4Ax zm&KulTavl1y}qB?TQyI$-YkF=1mIZS-9eo%dJ5N*vEFXtoJ){EdM2swOY|BzE>V>2Q{e*mZZ0b~G} zWm+l=3~o+OjCp;lt9WdL{c4f#8o=S#Uhps>Xxay=w@c*qv? zQ_JN7{zrg&fMA*01pdF(CKY2E6DK+}(|-=EjH5tmy{ervv3!VOi>JQVc_W%v$KgHt zyV|)xz3VFM;bfc5Cn}Db;K-qXG>^dfm3kuu$5eth>fl?DEutmBN zfUx`4iPMFmg$<$cr(X_*?@{(|i&ePpbp0~BdH0>~OM{0~Vnebr53j7gQ8)7?M4&t! zw8zChcl)%J3W!CAyBNVIq3K9O-USmcbnt4>7XPbHy7&R0NJFHiM8HC03WRA|deg6l4bK^7%kMF0TF!`u^ z-MY!&?>lJPWTOrJtEX_*yiovm*u3+UW#7i~g z>!{!@0a$p7;fLeS-K0rd@J{X+8azwd)l?A#BcfN+H;r$ZbEn_~cfd3YBf5(xTq(>t-+D0oh_*a=o4hLB_t5&OdJ7@ zb;Du_5lF(Qc5>C(!DZ$&NrtComK=ZTBHE-B({uUa-BUCeQU8QcY}UCfB3arQc)vC; zZ~%(VL>SCIx9p8dUdSq*+?T2vU4@PIkO0?JP?Ul8N(IV4{T?Kxlf4SXS!G8TS&l>Y zC|VD*kC<2uL*`P@{yzM%Ff--3`;x32H;@;b%&XW5$d6jbAGcc!4zaSjN|+#t_pvS34i`4~hv$+BLY3 z5PiYc_p)&-n{PqugU=($fQalqy$x=-e0|lcAJQ#M=p9@15g+rI@^qA9p|YvY_e!RHyV*qo z7Vn&3Jv{14R;9B1WJs(9&gMPFo8G<29v76 z$5c)A>a5h<)83n=eulB<_W&T>l{%y+S0wt%mEC+5B3w>PjA!8&iPqm|k)cx%{k?n_ zp}<0=Rw^X7Os9lU!MG&%ay=U-l$Ua)dfOJHCblch-Fh|$qlq;#f zblj;h`JBm--QZe2wSCaz)Fzrz3LI*Ba|imIYlSMaXm^nNrW<}!D8RPAYJj?F&jPOm zx$SF?M7k$Zz3>R$wT7>CqR#tfKwBu=si+?^JH8(Sfr+WTh6$G9%SK`Gk3A}Bp{L>{66kYN5a^TNwd z_-!tP)hCaYyzZuin?LGd@ z!#z%JfsYET+UlWHXeU1P2JVJ+>r2P|)$gJDEc}ga7W)!{Env(6pO(7QF$auepMFA& zhL+?Tg?FUw#%LdvGm!~C{O!cc*~x1!7)#Sjep7E^j#QMH9^6xj7rRExD$}JK51f_= zUYrm3M&MSB;NHiW`R6y`KR4 z0za+hoEtmqdZikZ$m!1L$k_XpKBF{|2Fc&gd2@L7%edPoAdWtO!y`2xh9m+}QSk%- zqX>J3O;;~yl6Ab7BmLV!`gW$`?ABppAn^azTREBDhWwA-PD^FeodHD#KI}P>A@u5xR1`03tyB+8ND5Df%7XFTxhw9xL02^V4vg_!)v2PUC+0>|4{1}tV9?2qU?_r5YU z=NHgY(_ErXC42ehQO#gQ2h=Fr+`v&7zMz^@deG^WcORnGt;I?L>^Ih!Z<3h!D$6{R zI7aH>mDxTMwuRfE=~iBHgkv-#fa>V(8!8@8#c#Ni$MnCz29IQXe>tG5aglo2k61q4oxbT_ zlsDmwuQEM_XsReg8@8iCJ1Nt)dY7_u+2!zaTeAdW!<&DI)p63X((nevpJodifaSsFFBPck?#c%S6fo}fZ+LFZ&xoiWfOm*1V&5LIt8 z2uBir{5|eoa<|nk6>Ai{UMw=poqqSOPXBscnd)(X@Uk-;_(-O_Yc3g^V5?sF`k_@o zmx5~0oSXSLdrpx;r}v;Jx7!K5YUlr?c@d=m?rw{5M$hogI{-kMRzTcLYP+hXue?RS ziIp0yi~DfsR)7g@DD3=(zWWpa)(Ra9ctJr*x3_~nx}+{AEK?BXD5^0yvWpS+^`Vcv zp`6Nmy5+}h-#;C$Ks!7-*XZ7Y>ei5P*r?k3fYiv8AXkLxZB9m0x8{E^SJi-ou&Mhe zK-bQWbu50kZ=#gkvO|qSeR!nS>yRI+zfa@Q(}`@I;3vJh1kz)6=pF~P2%q&2{fFI! zDCLe`2h+rTCv(?LZ`|1abVU5D?L#FdeUuIvmX@9gBZ zlqX25D>|dN7n05o{pvol-A3mb4?c=rD%`s1arLdPE1J^VkkX_{{GQT7=k?B)>f6PJ zxf+-QtKImw^}Jv1e-c1EeFA9~hBQvQf*m4D+vT}3Nv<@d%pWn<`%l0QOV@;6>FrXv zOVShDJUeAxN!7sA;Q=yNqf0|?MqbyC%Kzmeuf3)s;<3IWq2sCY8O!-Q(1+!{*+A{- zCK%xTzDzKX!+W0j0@;S!n4^bj~e961JH&b5T|g!P8zi zMJa(OtlN8u#qp^qjrqKbV*N|MCFB$&5loagGI#=khmp_h#S$QSWB7otUpPe7DJREA zRKa!&3YYZep+ZnYzJGaOd`x#XdyJr&^^hnrnrG;(?879i?Q)@ZXO}MU(OIr@YCos? zH~$-Vy$sjZF@7u0Ve>UK+~?IUOfgv=73!e_-Fn28D}@@f7}@SM`Hn=e!m-HZz7MCI zu_V(y_(=irvJKB>naGA`s9Oq*4%6VeWFVkmVbWNA&>5@Xx)sanwghs(6ln$Kju)In zE>8;-(cvIZx+;JRb}LM#egf#OnJ`eR-zwA#;**sCR1g3VCbtRTXhNS^mk3yV>{*fs zLk0js*&A^Kw(msF^P?eYJzX`AGt868yZcx&l?4`DLi8dx zjx6puVP`YQgk8R*@}Bi>3mUODE%)i?WmPWg5zhyBIj1NlqQ=knqS=8%A?UiTr>XuG zejLcbF$Os<42oe~Yjl;y1RgK;uD=s|h^AVHDR%YKwSEl6$vnU2k`?K~FWJI_YwF3=y24kgI@XAZ|8@J^hb-3pb zmj?iFPb;y887IeD_C%<9iNr%Z&m=RJaYe&-RB4kzsDjG2r3=n(*dmw{TL}3%y2x`y zhHEl_LIX0`q*5l6CCJZWh7J`hoL8jtMX0Lxq%-=}kh;$iV-P3WM)qK_=L|>uPJdY? zf(mv=#+WoLEv02nytTV?gQyhyqbUSAHK%&B|0XH-YsG1x@!~Y)`nuM*-&DE7>PQdRA^0A1${xi+f%{#nQz%U6KV9cm6 zKeQOzI4odT1;+(Z%uCEe%yL9z9?3*Z+h%WhperKpB7LZp$0T0SyprO(=2+ySNY+x;;kpn;vyA|cyHed@Q|>MT)@&6Jn|pZ(WmwFQ29sSz zwe>!vGEfxOc$xaR(VNyIP0a{0!aq%dv5FXu?dKZ#+5&h2>o<;fuT*^U?%66y{mao; z9y#?LO6<)+TDjB143Vw{yF2z28^PAQ9Q$K=jj`YI11Br~u%tc4uD>fJX?ARTxd-yf z@U`;q(n_@&w^uK;nzscH&;x4T_x!PTRW?RHxJ)QUkjpg`u%^LVagS2-ZV zAvmZ=>^iP9{hU06jfUBjGbnkOL|a-7XD~>i(B?Mv0Rmt$J0;FMgKI$nR2L+9FvB_9m^*wd22Y52YG^CT zki((}kA~d?4VZ`FLKB`goevZw<(KWk^-LLC$1O~fx1+yK7_k!lE>(r&czIT71`Wy; zIp&_ZnEb8hqVaXi*21Q2<0Je_yx3*aMmHQQ-cj8_5+7+&}2!hK^%d8m^4LNI8!baiy5Q@XwoR*$cp1((l8`C z$#x2?kWbXy$KjcSVCA(*vQC5u*gxlSX>X1|M6$k@`f2LxHDu#XKB^o@g67O1{y&Xm7fGcchDU zwv;c<2&!mXeU-2%q!Z@cW;c>f{62Z~b~6y{b>0*uH6l(je#iA6}$e ztj`5xuNx!ZKGJ458-~>-JKTvvS=;fG-N-L@wf6ryf5Mtqd514KcjC#)(x+A+c_k0W z8!FKJ`gz-H!5+CT4q$L#v3L`(#aS`7yMv&4^UL2xhw%zJj&qoNx|>!>?G&*MsG{>m zRj1cigP4H@TMTp2>*lg(cRv_-Umd)BUah_u$c}~@d6uJSkQ!9}@_{9+T9JooC=R@l z0org+90)tPYUyhAkxmq|)z*EAVD7_+9r^w8MIKNAy+L8a(~-x`X=(iMj03(rELdM2 zS*q5?L4PUAr%`Ay1}_TAGNh|?V_fN*8*RZ{WkGlHg5FhAp$CeKOlKDB=O=O;J|*E&2f)VeWH5pcMAxw)xLSuR_G__4yG3}N zUz8rN861>`g!q7C;M?P6U>GdRvJEh5XWX@;pe?GD(c>8=$tutd$_#Os_ON9w1vK!Z z^f)c;Ay4ytkLB`c+1W7jAON5-4Xo&sC|Us+o|9nTXdD-dBOQ~K1N<07C>;7lD zA+pD%u=FLb6i&g6c^{{D?E22t)<113u3BGvF?u!O*it4HTCXOU0i#;6!Q&yC8Z*j? zhi>SFKYHAwB>n4?%8x4{6Q?l!fVby9Zauh1Hu4A}gRl=PKbJj9>g~S%EMboX5unu< zLC|#rn}jlVjRy*Ezx}i!%Pjuoo8pR5>srtpm179>H183f`ev5;ak7g((Z2P{V@pYIg0mlumuvFE zt1%-x&i@Ia-mL)~(oqFezT{O#4;Z>1JG+?q!{(rJI&p=7e-Pl}pk z4EvS!M(gb=+-H1jHL8UWp1W)&Mi;z>r%saY9J-bHeg3Z20qT6Q>((jIq`@>`n7?_F z8m&@Z-iPC9RzTwYtwoES4Dy8gf){C&J?~W!Oqzp*>Mz5GpYDHEj05aRU;mkDkrK{= zlFaAB7}>XaX5avQkae$D=9S!DLGFFZ#Js-K$P4CH<(fLde#7=Z$^%%PcTed%AM)!j zy?F9Re)$oJgSO9(K}VxurqkwZo!%}&4x_f_pjh8I8Acp^q`R2 z$TYoP38qvo_dofTa580f1t~` z7>zL(Xn%avxbnJH0#1Q>`$yKjCL9oxI<5# z6|_#-;5#$so>aS$kt*5(rseSfO7aVFk*Ql!SP=z}gVtp`&(O6>V)1v=-n*80`|^2G zPy>zQW|dr2xR-HPPuUe}RymKpfQJD-kYHBrzIu`lH;r#;$Xz-gnXE(z02Hj|!UAay zV8N&$u`8dDTy&yZWOS=T0cRPdQ6^S%MXD8eX9$%%WsSJAb4WU+E4O|UgkodC6hS>& z^#GmV=8K3}jHvK@pJmtkh91K0D)R5)Ss(iV!fmBt*er3BL7x{^YN9q~Tpk~O)T6rDYh`JwOgk03WO%(GXjx&AE zZLa5*`ApCGk6jwLV%TXLYcIXVJdK+@v8s7IwY5VD0gZj#C<~F@HImPU{vB zp%^GCHS>$iac1Ob3nl{ddw5vwlb-f(*Vw5F6^eh_ziK(#@@&^gnAV?}K0o|148Vx( zGxH$k`!7ASUW?xA0}5IXYcDIbh)ibkADOSmANK0IU>OvE2+kY-3 zH}#Hz(TQg-vN0EEcFl5`R&hX^hpzr1^u+CP?1*~YD~+*=9+jcUNh2_O(&uoyJ&sHJ zBCod{I;6UY&Asm+ud)SXrXOQwefrz(vLK)ZF>VCShuUa74LHo!8uWTK4Y<1T0N9{L z7XCLy`?58gqsENN^_0~iK71phMl4=lNDvSzhBHyU1wP+Ffz8%w^3)R0Mki8T-_7`I zS$d0HgGOMbQzTD+)nY!O*IvoS7>+kj%HILSiAD>%l#``OSi`I>)e$3zcz}ZTuUe%| zxty{Jiic`Nu0|siV(io1T=;K;(*U$H@G{VdAggc-IHW_$bErz zo>`4lfhWcV-AE_!lpRUdB66u|kvJdjGU~S)DOB2BV~+Ftkz7v?I3H3?+C{%p%q&Fp zFFqw{m>C*a_ztjg+~myElzgb!{rz}3Os{IW<546BR~E#5;Q`zEG&^y4yzI|%+(`eC z{&o?QO>jb7#F2u_yrMxVAH#D(%4we5Qcj!|9<%guJ*<8SVM+m)-^$rCZRalqA+L(|zD=QO5ycC>!y}H$SfxX1Eia{wxuVkrL?$cE>8fJi0 z0JEqP{slne`cHa`%5^!AonHl=v6=k^0<_7AC=c8D6e`P>21WlyytabALfHPA+?c0v zJtfbA2foAanv8={iLw_-Pq-09G%w;uanJ-j17FWhViBK!AFwDI^sy2wj;t3UF9o zy#B-s;h%*$AWb_)sE`VgHYZPnejD38ad1>W+vS3XWfHAhU#!5z3kbC(Nm<6nOwjq3 zNgr28Sf_4Z8**NEV+Dp z$VQU#r-U9-0+e&z*YRacg)N@ z{XRN?6s^hWP#`sPv0mC7)KQYiCNNS{7_s~F(d*my_ndVVQuZi!n~L;FIJ831sFpbu zL;yI$e5xU)Jxy(4g#uTxxKK~yfZJwI0k#*#RduIwZ1(wWyA`2$v)I)n7He2)K-q(_ z3?8=}U@I$3LDb8JJ&A+UPNUFlTg|b_z2JuU2L1y6AQY@6?|%h(#HgR70*U_4tnV-r zQ^zOW9OX9n&BlG29!!o^h8kd`@sf^(46@0xaKGBbyPWTv*FD3=)uC(s~M3P2MZogw4e zvsN)DSoK?Xz@}9TOE03o#VVUoLBz#j2&q|NXGA3A%sqd!XD!?K4;|lV3I>*SY7V zt%x9jB2`<2D*XZ0jwgvm?5El^q;Ke2Pd#x1GNl6!_0C`%)H_9}nDXl#J~&UBX%ZOh6s0|B!esJtDXnah5tmlak)%qh!&)ckF^6jXkyh$yi`Kl&| z2`qa|>eubN6OK&ElO-f68DWK*oOBICx+0(vo2l$x3pAESz+Kq1BZdob-^O8Ros?&c z_jP{dXoUTj`DY9m3^W1k`7dx1MATv{|= zLTvf;`kyfm_Vk6Qf)*Z46li(KEvt?jZm?)B2Tr2*wmkXrTq`enGfd#?FSd43j}+W?G2fff&55$i;1jTzLSO$9>8MM30s|h_M zkFN;6wztGMc%8g!Th9(&WAd`68&a1X6?Z#+if+G|w!8mSaOPY7Oy`e?3_LXX2~J}o zYSuxa@WkM+6^IT9?e0rcT1n>H!3`AHnSqIv+EjJjK93XHv?Gkn5`oa|mJLwBE>Gs%ESJX3D!QS0caV@3jXb9AG|5N2szmF<0NAVAAyAba@` zEQULd(d2g);mTqU0!byczdl$^t$d`Y2N?T#nAS-nfI}v}$q<+)>B#R_2g)Z7-wyv( zw8ymTVIru`BI!B|P+iB62Lb{k@-z;_qTyy{)d1Lx32y#8q2$MKaQhpT_5B{2<$|P9 z^DdG14cbO$n#6c8C^}EIcopPHipz|Gr8!s&VQ`yC@5gRC)RX!4#%mFhH?O=`CWxER zQKN9@Nu6`9*}N!(&OP=5-)`)6A)h;l>RvMnXGkFrz%&-rd^n>{*+CN9@Ef^Yu;fL# z4gG=z=olWZah8|M6_|#zmIrO7cdmP3!dW{fjp9xN0XkPgEsAiR@he%X;p~Pj4%1t* zZO+UoU{}w8)6RqcVJ}WI*RZj0h!wq)N?^=q03Nzg2IzdEU^r#Y7mGR?AxDdObhfFx zA=bAbd=UV3>Zn~$HW^ZOyrc8T1&bT$rfPp?BU^(Csq3F@;h}=LEGmlfkNfl_mGRfE(`VjBiUbYiZ&TkprdBT8EYmF3qa+EK~5 zK+Bh=$+>eE_KG@-Qda8_4@pqZ5Om4uc-I#0)CKdPsO^X-H)8FA;wDoLSc6Fe9+QDc zP@YC#A4|1N>J{vxqG8?vwz&wszg<6y{U#}#=&lmcD=^I?4Nf}79m z@AoP3p*q=~4_XDn%w=G2X0ax%d1PBjGZ;QeE5AI4xz_$u%E&&VWQgKW&wN*~YER-A z->`2)z2p{)@g<@d0UW;YSq#xRZcLopmo;;aN&Yi7*zq2%~hvK@w+_M#h$*1XrARR#?yHHk!snoU;W?X+yUGKv_+9wue=x8)@ESKByj*M%(&Mf({e$99 z$Zcm!Ac_YL(W-P7S?LEgwTWKk(5d7Yal3!1zqQeFsj2m~ZGu0b?FTCfMxIA4k+3pE z(6w#F*watxn~Ul^gZ?7`f;*zixyP5gOuQ-vE-7bu7B){c;SIYMVT#zGL&l|MMe`+V z5p&*vQugeFxSeIhba=^ZDTrz)z$gRPyZvMAO*aMbsPLv%Cdaf8#mO->=+J^+eIA64 z%F(<4j>0Afd7{3(4JL~F<}%SG8B?QrN~J})Y!hKA)36MXiKNJ(0|E2QSRRE$GSjqN zjQ?4o={bHy*s=qdLcOxezA3747;U^jD&M@>mauSA^)dkg?Q2{_L*O1$<;-HtA4tta zYS&2!hdWbCJzM0*4R&KeE_}4pFA7X2#WIPrv0{UVy5%sc{x|aM4}gd`h+2VYpVKaK zMxD^Pgz~-yu*tI*`4^3n2W3A;)${zLcECMYenE6w2~A8C0mu^anC#~hbv6larfe$n zHOg|&mwQu7nCntReVzTeEYxvQz3xF=a~$gmCZJf7rU71HoxQy}!q=lcuRD0Sw6=(& zcB1Hd(~c_9NCEs7_zu$c73F~!X>xB-OhQ_0B5#k`KFYYRhPxjlX&M|&1pLE))GLir z&gr|nE|XkG#c=aAag1ayGIGBjRkD0wpFw^gyv&AGc;fsI9PGV%u38iqJFpA=2m-hP|oOkuw_ z+0A0_AZ=>F3XboG7!(-JrxLx<arwHyKV+B#ug#fx0ZDT}+*yUEhN|~X z^M;Qjbhj_6+1@R?=4wBEX8X)<)I_O-FZq@4|GWs-HV;VmMN!D=oBVsNz0_gT>e2 z?+%RK!Mff1>aMb_`=LxF6vg|36lpM|do>$_vhIIdsd>or7{KW*BX8If_2DFN>s!>JG#Z3rOAil-T|lzI1iEzGx%7pdxnqJwEpSwIi!zlekc zSO_!(?EIfZ0wJ$+PQ;GnC>vU5xG&d=3IOJTBJE{AL%Ob2a_D<`KZzS|2gSBn=zgh0 zFTlE|d(OStQzM4b#>#2Z_Y|OUv{Ff#Pi8jqsWVrIB-9l$^;6TN%qFi`CQ_)8|4^5c zdnT}rr=*}7e3+D5b*^YWz{!i2Mp9^*dYE5mUKEGdf<5b1(sLfS%~#B4rcvUD3Q%Z5 z0Eubj8D|0mI7O+y`Hc>Tw$2?O8@~0Qs{2t3<*I*q$Y|Eo&qez+ z`douZMdJ`;-#yZ{wG5wA1c#Wl9 zB9GtMJ9lSK2v5jX8VR*{T-^y`(c2q?D=dx+QX&|xzOb&2vbtc4_942T|DnRyu@V?%U5IbF#e%Y zhHgq6FoP&v%$+nE3Yr5OyX^I68SbFT9g))2kqIpy9y-QFb@O)wMI4mLNRhuEBC~c* zo>Y!XF8pdKKyV3@{~kDlQ znrTd*3jaqOyUhsspcRO0YNp}>VkNb+JWn%XIcZ%@QbYb$4z=#UD=0T7$K^%oN}jf= zojyUj!>YfOQD>(AiNgE$ z`tgbLYxu)?&;CYD9RC;>2qWDX)cZ1M9EcO?{k-J?C;oNj;N&16zA{VK1H+IAZ&)g@ z`~F&+&Zh>mrd&lov*k;Vg}<*P4Zk~g?wVPDhH$d)mSqOT6d;%#2T?y z%7?~mzfYN}**B@#=Gg#g|L;`O&bWoaEzyNGEzk4^33pTv|4{Xq+c)|y+rl?X?=gGV zsV|o|9+~`D-sAJ@PtxltvDpCo)gU^dXBzQk>U_=Q+OcjrrW7y$8o{c3y|VE~2I*EX zxPc*)zF5Ux9@y(Y$Gu@;utD2-`=5C`(N~vTNk`wbz}gS*0Bwj+#s6X9=<2gwiVJ~K)IIYkHRAh-YYVD@H|`_ zE}OxsS2p9Y+n;d|wOCg@|GHfA2ww9+T0O9a%(srs#9Gh6<(F8gb62=|UC;(}YLbh# z?Q<1TEEv#nMJ+{}g&CGxE908;OyU;wARoBe{vgXjXqIkh;*KX_9r-5n^Vu8R2Iu>0 zVW*)RoE^wwlQYEPqCuHafk~zluL)b_&(q&#I$_RoF5jsUt-3axD>s^{(>h+MSA1~P z>HsLC$zWr_Q_mR6E4tRn##$CvwRZy%)3xKVJ~mad^G(=eg5SJaMW`(IOPkIg zb0d9bLw0HNe2_)*#XiZo=yv=IY-9x3lQD`aT)J#G8pPZFE9+u4AX7O4prAF(hS-Wl z;o#!Ztvxv91I;e__8};qeZ3mg+h7L>^xtN239wH7tVaFoS#6S=#s4!#5A#s!o2&bl zBIvmqHlV&V-v#;^wQY{z7ADK380}p{Zz;x&ms-JY@i#N)8RzuENBAvA_D|G64}2F@ z?K1JHb#ldH;H4j=7rpB21M+$rr(69x_g+1>YWSqx@OJvIe6r!wE{prwDJ@5@PWED7 zjeH79u^t;Z`t{?Bi5u5m-DWEw5_Esey~;YF*04&q&>}@tnA_oX$_=d|2J269kP_63 zajhfEv)yB8oru%O<8Hs(;X7gjT1ziIIG)NZRKta(e;S>rv1B-Q-!1Gwo9(UTa=Lon zhJozOC6COn7A1IF5((i`a(>tpRN?m5@zMFG!0w5TL(D!&zvb6lbj_lnay z*SkdOa=CelCLfeh4+>8CRIY5aF4^G1w-akS~2tJJ|wyO)Lgt0Ak;IDK@(gfA}fEVBF_ zLXG+|<}wMB!@+Maz7AgRx})M3OEYuH#nL>jc#8nAVE-D$t12NvD_oPhh^3pAQKtn> zz40JXPl@f*nvN&I@&|1Br=Sg0^W0H@tDB*X^*EU>7uZQ{btXCGt1A<|t?5_daldJ@ z+|Swy(cuJewrx@3}|qlYvY!-L2%M7Fy>+iEo!)BoNCZF4HkD+XoepX{gfid77%S zr$tQ7fwk%cQ|Gj~>WhO8U1?g+;I*emLKZJ4-Tz2aD}qv(gbGrp!Xnkb=*41#f~Ub} z^Di<`!7bH?P(t-DEFF`kcRFlkVl4aQ%(mevCgG9lwXWqG#QPat=P#@MMLV912QNHr zxEK~M$|-a;w05Kqp|<>Z*)v!H0s2fFcX{vPcFAOWID{F4imySOk>(i2@X%=}+E+Z( zS?f6#eQZVC=n$z8uG4XROOUf}byKmI2KUqkFjrZwJ0o;Iq6<#Q{@4dmF!#sv$S{b$ z2`Klrxx-o4)fS$~dnWDOA#0_g_Zxl8)$&78^Z6{f(G4C+$^SP6p8!q)u>i_{y&cT| zqwOX}{xgy}W>hlkT>%;vds&sf3wQJM)la_G_IoYn$}8hGR3;OI<<`pOd@~!P-%8DQ z&eQvnP43ogIg)@hU&Z^@I;9%OIsE0ROK`%`wiHQ#bx4JIs$3*BC+$s%E#j6IvBrYJ z|H#0-h8NdeCAz$wFN--l>z(k*kFST;W}EMAU92m4VtluFIOE$&)Nbh0DgrJHqzL!# z*p|T4jstII1?&}?-;^MCT=}iIF;*>VAFPz%72X{BF++34h$Xi4KDXNBVLGdG;Ays7 zn^xD}aB(BZ$JdS+D>}QgD_IHU&uh)oKa#zuO?(+vxqW@o&f}&{l+<{6ZG|rVz|YkM zPH_2^*Tcusm%COQ(C;o4`p;J+{h{Ar0H8HS&hFLsmAfvx+yq}ZIbRSPJR?95&bns#;RVckFU^D>_$aas zmlA>rfO2vUsNuL`)BX$~z|yMVO4js041>ecf1kC&*w z1Us(!jjv?Y#Rih|Y@P*YzC3>WSJx|}v0EQ$deNROVil=5?$fnvXyoX`a#`&CxpheM5_e*@H_|7){wM z)qJ!yu&8%34x@(O-5(kdC;C>q+b5-m&tc`pQ2!e@p8$a%C_sK|07U@QVH+x;0B7#M MfARm1IFc>@3;WP2Qvd(} literal 0 HcmV?d00001 diff --git a/tutorials/files/server_config/modified_default_config.gif b/tutorials/files/server_config/modified_default_config.gif new file mode 100644 index 0000000000000000000000000000000000000000..da620c130eb24eb028f38a0994ec9ea2e52dd453 GIT binary patch literal 145290 zcmV)IK)k<4Nk%w1VY>qZ0`~+l00000g}eZ&>;Sap0RI34fwTn9?FJDl2MG)aAw&sm zw+pe|4TZ-Q9Viz(UKkJ!8*iT%)>ArufLZIC8Wb|)$?DIpv%KvXdZ05LT@ zG&empH9Iv)T{bT;Hw^IgOh-gaPEbuzR!vb^O<8MBPEJlwQ%_S_Pg7Y>pT|(( z{ZUR^QB+z|H7-(bic?cqRV^e{N=8*tPgPY_R{#K4f}>d4_F7q4T4;A&U0q&YUtV;I zUu0!pWNKhwVPRocVq#)rV`F1wVPwSFWo2b$+3#j$XJ=(&Xjf5aWMXP!U2S!OZKAwx z69sNU3S$jHdL zv&r7?%gfBo&dtuQn$OP8(9qD()78;aD$&u=(z&V9^ZnC>ZPTQS)6B=z)z#G6-`3XF z*T}%v+}YRP;MiwF+2ifn!?fDk+S}61+wb_?+}z#W-QZv~;NallP9EXf*Wu#g;qv_A z;^N}#?&Rd;<>%_==H}<;=jZeL=;-L^>FDV0@agB~>gwt0?eFUK`|IoL?CtOD@bm5M z?CtjZ?&aO??dtCC?(bVF@AUWZ@bU4@z4G18^78WYQyuf{ zoJq5$&6_xL>fFh*r_Y~2g9;r=w5ZXeNRujE%CxD|r%fOt?uiw9b0}CEZxUk{Fh!ZPb%($`R z$B-jSo=my2Ww#+NTnKTwv**vCLwnS$d1QkNryF2Mje0fe)+u+0tPx^`=-aq+>&8g> z!pPRFRR?$7U`R<98%T$^@o~ik6T72JpFTbFW|2FL3mn3IAb0IRz>EJJVnTBW6Uig! z=s3j1a~9O&%b!pGXpRdTYz!>FoMZdvILKDtfCLt3;7UVeW}84q=&->CEeN#33LI<@ zf(!!55W#Qdg8d7%Nb+?_a z;f*wes~8U9qh_$$u;P$T4wOT3bpmnUgB) zSllT{&<-}X@vV{Rwnm2;m9{Ft*R$P+kiHgZuExEVoS65YNKO9S1kwP;rL- z0@6t29#S-LV55CEB6XRE)4bFeAEATu1JbbEj6PaaR*{=%dtCb zg*Uc9qx z{rBL9FaG%Cmv8?0=%=s#`s}yw{`>I9FaP}X*Khy*_~)1yrB+r$U_{mkW%ytq7eUwNW>x<(F84;loFT7#3nlNiBOE9 z6sJhVDq8W1Sj?gpx5&jVdhv^345Jvw7{v#fQA}ps02%=FOt8ydp2w72TIU_8uXwD6{ri|sY_lu zw4uLjqeLf4(TZC1q8QDnMmNgQj(YT?APuQVM@rI?n)IY7O{q#(n$a4x;GHmisZ3)^ z)0x_|rVOn?40OuVo%*z=K>evugG$t)8nviMJ*rZZ%G9MgwW&~js#K#&)u~#ws#v|M zRTk~qyzVh|2 zcn$1c1xwe#8n&>A)oWt?N?64@ma&I@EMOxG*~L!QvW=~*WHWo&%~H0rnhh;zN6XpL ze%7>@J#A#o7}nOh_O-B$t!%?u0~7zK&Ud)Yt!{VA+ur*2x4;dqaED9W;u`n3$W5+t zm&@GdI`_HIRj%;JDnyoA_qy24u6DP}-R^q#yWkD4M5F85vC6;(=uNMB*UR4ay7#^C zjjw#?OW*q1_rCbeuYUK--~RgdzW@&Ke%)2YXc_px2u`qq7tG)WJNUs6j@u!c9x;SPKF!ypc^h!HH{_qwgbC{D48SIpuTyZFU0jxm6ZRA38Jbi_E$v5t4l z;~x9?$3PCUkTVQp6WBm@NKUenm(1iQJNd~_jTuK=$i*k=t3L% z(1=d-gyY=jMmze^kdCyZCr#-n|C!7X2C1Sq&FM~i`qQAUaFHub>QbBf)TmB1q%S?i zOoueou#UB?XHDxMk6P8Z&b6+0&FfUNT8a-QDUZ*?A~uJh*0bhNrHRmv2Xyae)j zn8-_JBU{L~?zOhJ&FyY`+seO=qJvGk;~3HW;NjZnwRIydfsO zl;8=E0YPLyCL`&GAR_-CNDMkW?RU?X-|GIbZDUK$aUv1NEg)_TVxDjuFC5A@U_l02 z;DLZm{OCwey3(6m@h4u~LN^yFj%QwPX}9~PGUd6CIW*#wXQ<@pEr{3S)!~=E{N*6$ zu*+WyPjQO#<{?g7aa+)HIKS8gQ@()*PT+yQ7u`}z5B$+x=WxMqyXj73FtkEo&S+~o z#O{18+;?nSnF6s=Fl8vmnay<&kDcTM2|LPB-r*Iv?(DOryN7M7TejoQ?Ff&%aaUe< z9siukEI6CrcVF}q6yET_-?i{s`}^SM8u3k3ycwzfPI^^H&>@zs)c^h|N(ROB?#{nBydNHLnA81p! z^ns=4I=KaJ?<8>9N2kxSYh86df^8&Y$6k>&4hK5R{ zhHb=rvV}{>c4Hh?DF-Hp>^6BH=1wiJhtZ-n+~{uxW^Ld&VSP9dq9=YTSAwm#g7f5v zThn2zmtF*TdNMeJZwF$gXM*r2gYtKYBX)Z|=!u-jdl?V{|JP)%_=`Ovh1tQ1vJqvj zBZU$oJFl1lvM6|5h-dAhj7p@6suGgCr~~L>F-N9^ks=`3!5!$)EwUpJqqveQxn!tl zAYblkOCQEx5olP=Kw;;d!5L84iEwn5Q{d6Fw1cS zHDDnjkR79lWI#lUlCpF2W|4n(9?SBJ8>w_1d1oIk~xf5)*#2Gin22)Zc`~c zpaZ!ig)1N_pcw+9$(fNdlCG!&F<=8XkdtC2DXo@Z6~%_L6_nO^VG0>=4pk|sGdK8l zb?3O0I2d8J)sz|*0tuM`8;}7929?n=oDr6en(~M7VwD+Ydhck6hsc5)7FNEqUI71B zi1OE!8rF~Rhl1$`d&Rbv9@ds4kO2?cEN}!2c?2hEk{tjd zH$Wa^q9P%3B5<;NtQaZi!6Ik%myPL|X82|80-BSui%2$-T4R}3b_5BsG)uN37IIc5 zpduA=9>l036Iv-2IRq^LHm-4F+31|mqjcX@w&j*LPiFz+Lj@cP|5O$p1m;v%h zpAnFd(Ybxc)_osFhwlV}mM4N#TAYG-TUn`sTUm1*)>`4|e(;u-`q%>Psdi_np6fY} z?)hOmcmnddq`YSVK**nX8Unt@kVY_yMsOZ103m<695#R+G0-kAS*RaShOYlS zL(rERS)tzcg;3;??m~lrmt>l%nN)_EA|gaKkRTm!sKyckI)I=NvI8d20i%i>Er5!D ziJ&_|h3Ey5%_y6|Mw@W>a@A;27$%KE>RLqVl}7qtNXl{%(4_Rqq^4Pp9g>IMH5nLArsnjfaGHrp#scvPm(2>7_gR+?z@H&7uPkt6 zHR*~nDuv5pDT--@4)Tjth<7I`JFJMHBsZ|0N~yaxMaWoZ8LC8+$vYAYqE*%)=mD*+ zxgjly9;1pLEZ{D!I;x}Sk{cic36eOrdZS*plgN2d!b+?^DwG&zn@j)nlQ$c1(g|VW zxRglQVapl;%__7D`kc{{0ZqEI4Mv?NXRSa}c3k>?_9Tyv7^W}Rrevw5B}lFTmx5WF zrszs!>Kc=7NvG~ApSxGD{JEd@YKBK}10DA&tjYn%;d=o~A~}$X9vhKTcr~xW9gB&V z49jZ{3z?ZplAMaTm#L!6F_E&fA){)N`GKGzTc}bZiV%`6Gr9tOIkDMstF4%$n1)~% z)qu0Lj5M2w^LByS7>*1Dwj0Kj682KXYGHO6v_jjY5ukO-X_vLjht#T$);V^x7rQ3d zrDw{O-Wj{oD1+xjmdKf%YudHs>84@3VLt~1?25MYS+5?Tq#pl3ukwngZTn=#A|fGh zWG>JFFX=4J87VNMxA|cMM{uym#sYu~i}^aZx>mS$7O@*Dk`OtN6JBbmv}H!!L(08UJnF0UE7TIRCQ2#1QCu|0~q z&>~{3D`Xw$ji{W6xa$B(dtl6|q-InhEvR0h9G0z#Ho>ViluTh*DYe|Wf>m33Hbu4J zN`sNewK0XYx~yT@TeeVKpCRCP^qP?4Yp+LOhVlOkGTh;}q=={uy{daV1W`De`>IB! ziKE$^Yj51malEONskkAkpb#`7kozkI>&zB1w+DL7^sAr?OV1W8y0fXl8%&hYa>A0= z&>)s??ncWahSuL0ox%xXA+jOM+MG(dAqm->W-XNi0eZqKDU1h1An1;(T)oQ6tz}o( zA#F~P++gS#gD;iD7k$zXmeTDS#U9Yoeb>@eyxIKe0#jhjY|I_C6CUZp0*z~R(Un0)*tpD9-NSz{N2$pO1^|rwB#5W&s9C)7;JIM_fZ_k z+|W(k0XJkI7)01@V-V=UCJxXc7=l+ff*%*z6gG1j&7D;HfZaI6`Uv9K>ew-0u5{kx z42IwN4VRex=TA14j_>-R_nZkn7=Fm%6U&;(o8=e(nYz@*$^cEKJkpiGL z?*b%H%;f&@Owa4a%=1z|^)ZR?iHBj0O!Qj6^<1xD5%2Qq_3ygwmQQc)yPm~VpY}TM z^IhNeZvXZT_VqPM@#b#!A8+?~ul9N`@@xsinzxRr-?tKsV zj{o>6FZhw7y*q&OAOG3@?w0hM^NZj42HyCPANr!->VjYOS*%|FN$5!K`K<5jpg;Ps zAN%N9`i`q)Gra?t&vdQ7`$hfwvj6+Q-*dG8WUH@alh6CeKe)ah{LJ6{ur~Z8U-ij9 z{aCpC&VT*bk7z|!5rqGL`5(Uo4wMyEpM2S0{^s9l+bdgW zxTHl06DI}Q2+>00R<2#Wegzv=ELe~>E`;!?qr-&;8>~M3*x~|IATeURRhY8nUX@P$ z{skOZ@LdIKAP@=3s#6AgpY=ZVFL#*(8`9jE;QkW1|4i+hmYLTiop$Zz-}%ZEW9uT?hx|s zyA{x*u|^wj#4$%4)wAxm6GGVFh9QW{pt%)HSRn@YTx>1`4md#a$q+(tVM!oNG@;7> z6y&l?FOfT9x(!xn5Un9xaL@$z9@JrlwbX1uh7LkdX@dr0IBhx>nv?DV8?b9&g&`h$ z(1a68BPjpI?{s9eQAZzzG}54WBeBj7L32y#f#1Oc}TX(2^lleAiE zuf;ao+$fF6$Oupb@&-+fL8|IBU&XuFfqC2ciO z-RdI)a!}JQK&oGPhKLw|4De%;0I|0Np;j%kjmV^E^iEC9`#6(3H=}j+&RgFZXkmeuz)*94A4hx@JGBHaU{XI zfgC?F5YQcDT6`&ECN;T9NS$$yp9JO5CfSu2fkb_#9GmDkxk^^Hl02RaWh`Ym%duQ? zFRsL8E_I0*Skls$zXT>q!njLf7SotV>18mLxlCq)QI*GpW;CUVlVmp2n%DmXr7dAI zO>TBGn$^T+IK>%2ZF=E2SsQ?6}nJ{Hq@aHg=j=2I#G&N)S?%~Xht6vpC1Kj=>ob@l9tq@ zCq-#WRk~7^wp67Z?N~@;Nmc;%Z#w zI#;@G)vMGJYhLyG%7&gbBnG9>2GSZx$8|`mf}0{->$+IRHrBBjy(|AF_c~e1)<&ra zRg(<>s{<09WS}&Q0SAr*nS=4{Kcun2Sv4yn51Bv*E!d9^c=jYUwN;?1eQa)ZyW6@( z_Lh|eZg35A*@OBOutxX~3kq7f$#8&9P$g56mXtM4wIFLcz|>S%(55M=BuoHif%h_BMsM2F)yB*%iOP>L4c46D(PF&64eaB z*y)sJrzFt2jA;k5by0+Mykj0Kbi(nxaFB(plMD~2wnsKD*j)ddW4G3z1|%{9#m;diqio>#pUo~ zg#&MUnHGmI8Bn#Zx}>3@!KUV)5Y^h+*VgK-bG_~M?s`C*2J8)9MysD$cab($atlV> z0aPnFwWk#kmqjF>`Y0JyOvZM;^^M+rR+`)YuB^8i%3uG3jUoL>L}M=VzBRt_l4={^AK$CMBRUX-3h1u_F=(_18j`^6G|?TfILBo^^QHD1 zH&KL>h4J&tpt(^ThmtpQXc9(1NReYrL-demiV&wN(h>d1k*)V1zU zs$bpfU$5mbw?6iCb{*_zM|(!HPIk6;)9h)7d)yzg_O{m@ns1kT-t|sLvD@A6#KimF z1uu8H|K0HF9DL#xACbZz-tn6Z{FmJN#kNU}A&<7CW*5Ks#y{TkW9<5%rsS|Icb7BL z4$xyNnUEn(smfFlQM(Q@=*o;pY@1Jf=Rd#u5>o%Y)9qq#sxm|S)T`^1#Fr^*U~Xb$r; z2&`a?1Ps6uA-~}Ok`FkS_H)0ygFpE*LA0U2?XwiB=!m8ovp+d27f_Nd!IC4{pB)I3 zCs_g5Y9R`-njHj{GwH4t5ET3&KoBHC5Go~=0WS))9J-fflxglh@Jn;p`R84f>9F@C$Wk|laO?gB-LBCcB#E1 zSdkv;lp%o<0!%A`_<<=wKOwolExNNU)VnVH!br@Ppiz@b>@YD55XXoBgXw@e5wrcf z3Ug_;RS6I+!@>G70_S4G$Y22*&;ibJi*(6E)q}-7Q9;ijB>P~8PlH-6R<`+MlMXoW#mU|p+EkDK1(?QRB0hCyMZ>; zGTtf0YfQu|L9QaP8PZ52yn&APxikMz!$)?MJ%=m~O;IcLo3U?XFfGhSu!F>YM9CaU z!7+r8w+SIRXHKKK#Hz zV{E;QEXlJw$&{o@8d*t$kVb=eL0lw_`3Vs_`yUgak1az*4nWGs$N(Jxf*)uBXSv5< z(?lG+f&J;q-l@Qint0h$IA z5dY`^R7th^(H||+9mt>+Ez-dMU?J}C5YB9{VA-LK6hy|5Aq$BN+5-t0Ity+bOq1Nl z!?exw2t6Q>zBCL8j(DTDKqUX&@jmEVN>M8f$GMWF%qfW^PQh_P;FOg|O3p)49?R3s z*+jd-yv^;jECZnshY77h#7gWW&*acf?nF<;h&+;DA)kQ^!7R`CJdX2B&-yHk^<>Z2 zY5~TS&;Fdx+O*FARZssU&}*Vk0Yy;vD$oU8rUOmT2SpzSmC#>uPzbe944cplm8A;3 z&<^zp{M678O%M+C&=SpwqjS0xRnf*8IumtK^jXmul~MC*(HFH*44cs$)ln8D(Hp%{ z6g{XKm@N>ZvmG_kBNe(H_0bmv(hqCTO8gHbmC`9is2W|;D$oXl0eO(kl8{sJB)!5Q@VMBQ!vHTGZRxX<QXrunf)X)y zBf=1n8g>yaGKnz;WH&_(kv;50N6pho)v-P8Q$97*JX_7kC=or|sgRft&GV2Dkg-J_ zH5uaoQB^cbW!3Vs)Jq-HOjWWQQ&ga_fu5|6GhG={Ew}+ov;}*socfQPG8j{7)nnzY zSB2FpmDQEo0U3&cqjXXO1jG%vi@cc{=Q_7)?HgqE*2hxTW%bc!6;zDeE&w}IQHu;2 zfC-DkR;8H|bu|HYt+<%`)_bL^a1~b@CD#uVun2Gg>1f1RwE=B4sCS)9QY~0gr7?VU z*nCyeeGO1qUCaLhbj8O=tEp-$8CU^i`wxyNmtI5IDbcLG1lc2b*p#)ah?Us-l+~x? zOz=~#{sKg)X;0P^*&KscTq&2H>CB8%*`VzyeQntieOW~+xQ_5FMS3lrx)QfS7|2O5 zl1n(K}WGJ80+O%ycuI*Y2?N_yhTQp`uLB+9dl z#}JO#b-(}FrCk$zyB&%c@eGNk>fPhe8Q=Zg)eTSYGDEJ>Y%b z>xpu!N#8>P!1}cc_oX)p zNeKzOUhNGg?(JUQi(ce{3RA(q`S7kCK$S)X5+_lKW^_3-jKq6!zD&ds$BVcAS-~;}==uJp08()~SihFz7Ak;1(SdofskI;lZ z6ZnAUOEj@r0T8^BQSAs)q)D;C$rNkC8gtzkZj~9P;m34&yxDj>tv_ziKo;b|jg{b| zl_(-LMb=}hsGmocvZqC`%JCn;%9=t;y%t*D0qFqEGT1tdV$IWIi9}9QKILahWdZfQ zdhCeR;^i`2$eG+3M{dns4G%!e@zK%M-{%gMtY{4cv!Y=F(J#56jImKS=3~g-3{y4~vYzdug%KkUYzU&3f zY|Y*_&hBgi{cO<2HPIgJ{w!_NwlvgE?f6`6)^0P`er@uMZP^|&+OF-{ylwy74l>=| z?WpW+-?lK|4(@y$ZsP8?+&}5oI~%mR`2x=EAejc!FzA`Mk@K9@Aso_`|j)f-s$@0Z=>^XiU#li zpSl5G=K?oykiu^ShdTxDiGv}+7I1+Hukanba0<8Z4aaZ}*YFMp@eddA3@33851$i9 z@f26_6=(4lckvg8aTI^X8K?0YxA7at@f^2tdi6&KH)ROl2~5#(D9uG3|BoTBEhy3P zm7pOM?=BRNj1<4Z6Q_z4uW~3)@w2k>=Q{ByKk+7~axN#ELPe4h_wfGtch@iRrGo7iASGwgbDOS5Ar|XbWtaCG6D1;R})Y_bUNwrJC9)?zX|z} zpg=ctoJhc0zloK>b(=^)Ro96S@b#P^b)KN~N$2sM=$lISiIwq*MZffA$8O7dPVnl zotSs1pZb>1`Ig6aufO{8_<5kuC!x>fqLj1@;{H8LOA$O9-FMPvyk|NLX$v6D}P{*nEa3|7H(? zcBgilCo=F)p-7kd@}~)Xm-e4flC7VKHQNb~Cv+qM2pa+i5-cb%Mu-ZQ{aq6Wi= zD;`E%7-M3LiUws&l%eq>$dDolngC+*B+8U3SF&vB@+HieGH24PY4aw|oH}>%?CJC8 z&K)a;5-nPEB+{fKS8z}`G6shhI-YLGNY$#y7*&zV*ou^cN2D9VjvSkGgHp6-lOjy& zkZeeYSmTD63sNrEgh&xO6*;kQ$iGSl6J}TvDB}ObiWf6(?D#R{$dH8^tvs|a=D`j_ zzy*mBX^Xmhy^8E=7bNGTdO@2=+M@N^*ho{)?hMid?2(~ehhR&)^lIRM?*^y)J2Uc- zhb1#_?)*9Q=+dXdq-@z}^6VO0bQu28p^2#@O;Eh5I)-hHD@>%X*!Fx<6H-~HRchk& z$K83|-cP!oH+~g4#3~Fe@W)MBqlxpFP z7GOoV`6k{-#|6foY91~{;74jD2%~_#o!4GO?~NoEjtouYR&jSBxKxneh0x!I3_4gL zlTAALB$N_fh#`$hDg{-QK8m)Zi6e%HVqE{EiKO3bV2UK;crDb&n^G!*q+^O%E`(Qt zHttyDM?(sCAf8qdwq%rn3OXpEh0Zi3hJI$o(FO_O_9�l1E;nlOB1grJ07%L8X{_ zswsIKgzzb;ns!hss^pEDDypY~%Bl&j!s_X&uiComteT4YDz3e5>MO9oo*FE%qc&P> zu)`t??6J%C%Bi!yLK`iv%~Bh}2G&xWEsKg`2B@LoiaRd35F&b=w}ff6LJKamz^=RS zzT57+F08P@3Nh%rFTefn%Tx<7)Zj0{|Ayd#33 z!8zYMG|wFMneJ`nI{h@%Q7d+?Wla0GC6OdbgmqS2hlG%eS&8{|2ZNzmmf2~i)ni0s z6Q?ypblwT~oJ&V!U|w==WOv+rTiu}4feSu3;VMyG+23^K2AqgUk*8E>bQ`3Vi zQeA8}xcHcy)1|g*nlI${La#w?=bfS#^cIkMuU_O0vEN`r4m#+tgX|n}V1y2`3#0?@ zaSJB<>^1;DRqV7Q@4NBAF9>eo(Mvx)l!s%NxO$g=gk_tJ6B%}xl@~<1L7|x$l3DT1 zN8g(9xn2;Qzzvr9)k?{|C!hat-M~T=i(F$4C%UjdCMaVb^Ed}ChQI;>8gL%mSVE0f zFu(#D@PRhipBRKuhzl-|f)0e>^Qb4n5t1-M);kLJ`sO{qXs28tI4v35`=yAO!zu@WBWpNJBr+kb*M2V+%Vl9t%bQgkJtmAbU)MIoNOmAcUe6 zV8d?Di#vf+j!^zj{a7y%ik zp#~#xG?-s_g%~&*yx6he54?y%9^TP~AqXS|BlyBEHpR{`L5l$_X{N8d>a_*M^aYPggKgg}a3 z6al|NphPcdaH$MTpbXn(HM_}y{E;u_no}nLU4xxt=t!Sr#_-`FrqElr+ z$*A7bA}p>dQpt1{7n5XtJ`APfJpB|D3rJ+A9E_&t#%YHZbR;(jO&OVB3{#|W(6=;n z^3L23FGw(UX#fTpM$rom8GIopdgBW{VfyFlKqNUP^&zkGwFj5yH39++_p zFW3MFbC5$C<{*q;G{N8qSNJcuKpw!};t@X(!!iUh1mrn9;S1-&L{6~U4OVy#bvOgW zr%-Kdv%KXdq!J3#wV6mC3DqsEDwple?kHD!bA-8fL~>{!QKM}z@k`Op9YUB?k=-`oIh=aQy3A4uAc>1|6!)aSsq$YVhWXi#M}=^*aL9)0V@vp=RVQuNKM zeb2}9_u&&iGTKg((wzF#n`^|L^UHbjpzg)=s$n{fq+N(N5a12iZB29Bj)%T(y|im2i0%~|Haa$cjqadZxlxNp$`ET2GG@$ z_GzEwy^w!I-Qj75p6tj3mWG1(2|3Z925w+F1>QPs2vfO62M`@yNS^a8k-8Y(^xcq1 z&=2H5V2-RGK@?z%5yl4&l)NQfLIhOa*q{swL_9lVIJmTLhNC@_~9JdOCRdt9~R;qj*1}?A|Beh>hda+8av{$CcN-OdTEPhIQ z)uO84BBmV6ESAbGu7{)qBW{ceFbbnF;sysCqcT#;G9F{26k{_&3bsUJFh(LYQX_dt z-Xv`zHyU9lVg`6z*^^Bnl~LJ5K!iBvSVE-Zk2PL73Ym?01UsV0CC>jK_T8Z4FcM*K zKw;Ft4+=y*wiDvJpa4c$0#qz%xZkrc+!jRy?Yll5^P_$8p0BwYn|jpX59c4S~g=A^YvWFr+M`<>vH zz2r*bQ%i;p0>Ym|uHaD~AX9$dOBP1>i68cP-V)s-Om4(X#zj{CiB5K9-|^&9z|%V& zB)I9{Q2N}T{G$yp-BOqvSD0jsUlCPMGG{xL<&}733_|ED zQ7DT}CwjJ^cb*A2VkU>E~LwP3rxy)vIXgfitk$C?ob&@EP5{`*Flz?t0ak{8m zY=D}8AB@ILmf};6k`iWUCww#|VbEY(rPUS&jaY3VLZHW)K2)1_;T8(Unf^r@B1A%@ zVQ5_9k~S%yMvaL^qA6lapbBcBrs61q;&dgdqAn_Yat*J zrs|@l{7NtK%6x8PpN{JEU?)Pb2g!t?&(tY-xImq1MI5H#of3`3cm!XrSZ1K8L1^Rv zGU%7G&62IhJn9&S^v1Bt7}&gHIhx3^&X~+7E0QH^vx*&gDovNBScq!Go{}oJ8p>;0 zBv(YK;|So3lH~GXh8BM5UBXbVnyZ5vanAqGx^`xL{$>4WDEK{2e(I~Jb}PX8 zsRw4sW?%-mUZjkcr@4{`OCg}S^4PaXXJ#6##2RUqVP^KBE5?#%v8E`#$wQi4umQIb@sLZykLn-K|`Q}S{EM}6Jyh*3X zc3I03t;wP+(|YT`s!+lzZ9GXQW5#FAZU@GGY!GFJeC+Ji(xt{`Mvsn3*5>TY?x?(S zEJOAy_^s?yH7(p0N+*^qXl$vaJ*?eMPTsB#x$+pHVMhC_}6%*GeqJ{%U5d$LW4;MUd`-QtYB& z>{ChX^YVwpQf1MCeVx>Biln(I?F@aR}@-+Cr; zz;BvJFz9ZuKV|Uz$}n>Nu)nGc?7IK0aY$MUFR^nR75a*+CO>0T=vWyuSv`!f? z^Rki!bB;BcELX8o=z!+-An&e#%vvk|@@yZYvNgBFlM)2s?W;0hjRfl^0$Q;7AP3=o z67%8^78jWe*DrF6EpV)J>aPDK{UW4zTCfPa2YFWWHSaS@WHS&>@rNSEv+n3Rvv2XX zaL}c5Gyg0tudfCBFcC8@*JAPF7O`JCu6^*cM(ad2hvVLdHTCj| zC%QD6axXMPH}rCoGkBwQMSpN|@Q7Bww{(l_bz`>xPvmD` z9&4AiW<2o43ib>)c3W4dIX5*m#SL-7)7Z}6-mt*=|XXhf8`vw5i9#qb3h4-EP4-5SL2U-*skT>{ipcm-mG?Bv`( zSayAIxGzR?sr43e?jR1$y?*{h*fFyHb!L;1V`Nk!s@+Sp_2;nP+X;6sW#di(F%1mA zxb;0?u1mZ7U!7aMPQNx=HgA_qkDe|DvE?rOmzBXaqOQ-3lIEMtzgfA>w9fZAB z1p4>YyL4W+8*NEMMZ!8OUbqq5i&fyX5&!7X>i&G7#^%O;+{B1VDhk}@ovD@HR@;!<=#2b7i=N98tPs@&~w1mJA14+ z#nmR0`m`c^+^dWnrTxJ8>|&&&f$%Y$;-)M~}k4(`hp zw%&PQP@HAQ!i2<3BJt__%Vp>5$QnWS)PRj;KgVYyYnfUa-*=f zF5lmUxc(aO>}uVA*Aggp!rG;KZV>DCxTA4G`dmF*v_dgMGTY61B9qT{DX+spe@6ec z+jFPa&70{_2aS_l{LZn-UiSMf4YFR}7An6f4#s;89e2>Z4N{jhF5eyEVRY8->_T zm?=`CU%PeJPZ5lEChf}Mb0+Q@bF0gz?Ko?rzFZ4*lq)p(6MdO;qS@;0a={Y+Wom}6 z!vlpv$J6dZ&n&6$tdRlthXwC*PVrzCzjf4rUx^p`mf@|8vSbRziPU{aqp3?%qWS z5{or9xRK#u&$?=e%cq)Pf%{t}``zBzFy9#W{G>qU_-`4?6{mR(5k~*l)54aO^V1S% zPDNajwj4D7-7oRGgL|5rWI>~D_v7v>qDDlNN z3+gIA-jwQ!Xm~DYGg^Zd_4K69U(?#BrY~ z{N*k4L1O+lv zEpnr!eJU?$OIl_wXB}60QMDg_wmoT{oyVC)5~%G_yXSx2l>NDRLL%Vw_U3X{D~NxG zkh_L!RZ_R0cX;qNnSe|=~k&V?!VUG0KJbiQFSQpi^C z{bW%0GclPHDE$K`VEI6~y>_lng-GXa5f1@RLFXe{i(4 z4DCWrUq?6VGJmm^Gcb)$aN>GWafAL%vtX6NmfSBzMd$br^G;f=1f zp|3gL$2dSu9N6nT_zt7sYjPfUh-%{GBLlk}y`ED&_P3-Kg1_8KHGGjlA6TPg&_{+> z*}dw7bvUSRS0&4Zh4Z;qWOudi6vktsKj;5F(eZ*B&n9FvR~e#po3dm0*Zpu55Vsm*yZMR%oafGU9M3ZbBW zWe#~^IOyd|sbQC~V-SsH!>PYoW&F^XWi+lwTcTH}X|WssOLYWDwe-2*U*h$wrEgeh zIXOAcij}zoQ_brlHJ!U2Ru((1SAWq_oA-m;(rCg&aXGC<5)s6~ZfYTX**h+|FK{qn z?AU7XFS5WJWv({uZkm;U-bEZLLRI4Y1 zG=5_Q)l9|0#MhE$`YS1OOGoAX4}TS>W>X; z2`p_w_}Z$+;**zmyf-VatXb7MPuuX_Q{!z4AO1`^$D^jdWn$+Jp|hW2Y_%0unuvry88Z}8`e#ld*VDyvuDMabHU&1nm`5)U+aZM?LY@l2qa*cHZAxZ06zDMDuN?Q{Nf- z<3kM2{X8->H>&Jq_fJA{-vxQAojQ86%NLdY>#KCvi=UHEeFQytpTDn*_3nfkeIEX5 z>sCmp)qM-9_wOWrb+xHR^S6#3g>L>W;JB^-I``hMneM4}LEuq-W%q_mYv1Pd0buvr zV(PI}t9$P=dQbQh*dqC&>S%)t(f*lXjo=|Lo+Ux~ciP!GPSO|2pXa3?f08A+(ePrU z+ORRswC+vEo}T0yLS`_hG|@gF(IyC*%(PGUPqDZNu=RLx+&>?)&0wP^0PVTXs}E5$ zA#LUHDEt?TE{LG%_=gZotYiX@Bj$Wz!ku2?9J&;U-GA_!94l2wVKv46;NvFAzR zAxmtTyhj&BgcgQEC4{ROg98g4cSe4C3Z%r@i{J&Txm3xW z9dNq!uI={cgffi}D3pwg9QEQ!TU=cOi3)ea(F zvw_$^=a-!e_|lF#$g$|=oO1IwLum2tPQ%fDGUjE&K7s>GNf=*@pvR1%uR8~i=#c(O z$Ra~B5c0G56z{hFTd&4tWJ3>UBa2owwTdn4B_FdZ2=`Wp_7e{nWQmrmz~Vzx@eog+ zth4=QmPzU-aW` zHY+Q_&WRG>c$Jo<_Ws?_f#-*$R$8N^HahBWsTr2#73a@#% zesE8?y>Y-3vg96yeHJnjuyN=cBn#n^QfF~;*AYKqu`m8MPIh0CYZQLND%*P!J2r%rTUxI)s20ufhJN{Jhw({N`Rx_@<=!- zj#F2XlZXQ1%zDcwp~XiZ-MFVoDDh!VBH>i>v59?do>x4nDldgOWbT^Njfq27nv3Xa z1tAsbMqr;n4|J1yx|Ab!BhGY`W=siQ5@0>$E0rc$;Y^VpA&@}HYp)ika@O$EbG?b; z6;$+Nl6j9{noVkGoo6Ev6mnZ|He7hcfq0ck$UMpCT`V9cAy{JNq2eB*c*a4$>8=p& zAx*#|-axEugil=rRH!4W4og!TNf65x#K~`7);D`a9HuJY%uf7ADY^cnm{$_J`IP`N z`JIO{N63YumAZAadgxDL_gz&2!OWOC>F{PH9XsiNKg6nn3NLZwel@Ler)lvmXdM8x zzbLDn0W^{!($-&Jf1Q#h|4Z+zO|9nf(mGzVNK>7o1^s!;s*I;R!QVF~b0}4k-xSTV zj*HQpb2@rBSR4&#%m3oQLQkfP5V1uWg>=bp78>SUMtpLbsG=~<&kF|0?6Q#;Pn~aY zaT5$b7}f) z{U7PoW?59a$;9)wKM*>!9?Z@yni>envqi~EAx;G$0I8ShO!~WAM+1!t9Z2i@{ymGJ zKMFyMYjmw*%vWpxvO6~@1MaxVe0nPhso8RZC8?fVy0b;y+*>u_Gp1H|r#G*Kh~%6} z4Y(R5L{ya((tm6IeRs5o;jE{d?qSO)@IIjK6|nx5?fK0cVG6YcyXEsYs71^9BYh1f z8@`N48a0OsefhE&r|a~W(|UlVL;Y_agfpIRXp=1?y|hu`DNaTMy9sGliy6-n^_)`A z^-G#%&z6iRr%f!ET(lsr5Hg;pMH|Zm^BOxBzYD$N=ik5W&xFxvmz^WY+^-WY zQ!|XHTbBhhT~_tKY_(?EWGX`lOAqxeBNxT5XFURz9iEYUzO8UeZD#Pe@)VlZk|5Hw zZSgSia!w_4cIU9MzPf!7wt4O?hkF1^_Wt(J470R1Kf6-=`dh!}$}#!M1GNb7TCiso zvCmxg?!0E0_~SI>Zl~bvjN78|+uNK*6-kYDR04cUBJyWnk#H81(D<*SUzHMx`=TG?*}6(TIE}?BA{9tMmPTyGm^#3P|mL6J3#BjCy}B zWJIYjN!$d+gT4tdPm3^Vv|pDu2XVC9v)+VMWk${XK6Rj=ntvU^NMhWx5OzkkSxDgt zYx9n5jqHjHaa~bkfQ+?mRNxX)2i=XOwu?m~S3E3A5 z$zMKKnIHM1Zn=;5Ui6YjZPoCpY>M4I{WAOo_GNk`_9T^i#z@(i-EGDMwn?E=rcXy^ zz-?xbQOYx)c5!?o;mfot>=&unJohK50h59#AvU2GKlFKxa*T$s5tzaP*`l{t*5ce^ zLUC;ElzFHy4dFiQ-t4?|fpY&>`2<6G!Sm9XVyE1%vLaWT4ikg@gyKJ3Cy9wx;jao+ zi&k#6$7(rX_nn46YY+OoLV^9Y;4J$y;U^7}PM!EW0m!-w#-~BNTsaww}7Uy{u39BHa6z1;q zjsKNIN&Q$TQaE$>`PioM$G`KLx5Y8H>Kuk2JAA{G!fK-R!)bFHX_)|UVdwkI8tT;- zC&p^L5=~7X_|+t;KEN?keCuT~Y7OMeRYc)Gs2V0ZJxkZB3?+)K*7YpOi3q9vzk^-e zy$eHsTCY|&cldr*scs_dYAIoFP4&yx)K8A+bf)b}`s$mYu-+U#)w-DL9@F*3(6@y4 zuq)oP!&0;6)7qyWxowb+R@(b8R-y*a_2c^Wj>z=h7rPQ8#5)EZz zgVrhWq&dybIYVlOU&<)5!~I92yGP?6Mw2DS(*4H-=DRHepb7(fRpuh|d{2?_K}yTIZ@?(DhYM*~s8J_5MeyFM2yuM&qqbnd#kcCqLsn z6Mt9lMBVahquZJ}yku?a!~NiI;!#?^c4uAJzcgnz4`acvrgx(TX^+PPRvHATCaM+( z+uq@7NPb11nWZ;5X4;(0_8!;pZw`VDmykA`?I7K|DP|=H%}o{}g=W-DLNuk8>9PhA zJHd_*#q$0uM-QY1k1Kj}Q>*^rC}r(sZ`u%FlUXvtrLHxk>&BXGzV(pnZ2TjV>p}jf zHcPR|L3z)p#mD%djT(c10)eH)%mbuRz{sbiwN2V`(=N&JfZgeyz6ZXc$K2J_%{fYq zt#lI(jy$u(b7Ve6)RoEZ9c|A!%@#*-KeO}V!KOdo(>7#aL}GJLVI$xJ?RUC@Z%kW# zR{o2NCT0dwd*meRuKo?6oq1WQg-a>w-`#uHzxLuCZ8RRXR4nJ0G3R|q_hSPVzvfHm z=kMd{gT_n_KF1%BPgO{o9D0-QhCXf}e0G22AMMf})jhIB&@Kyr*NW(1rKZcB>)W}T zEqj|kzHzPokUCQ6T_QGZMu7%)LdQ;K=-lT5*B2soxB|O>k?k_RGr)e|hM?O$+Dd-0 zaSr-@bpM2WdinPMM8!_fJ<`9y{}uxu3YUm(tmet{(_uOn*uk9P`}N-T+Mqgwn-`X(_KTlPcI2> zBGqr?@$XE&;bTk9CKep?6_Mw)ZMoQ{L%=m}>m)j00P3s`v zgRRFARHmEMBhcv)eITMQ7z>w5(0rh9ARLdH6OZw0(O@*bh<10Bj#+FNrG&WP>_EwA zI8-TzhJtx;ESvS!)=)DBP zk7KM!#`xLH2^JAm7Kv5~(KcB>7)daI&w4?&c}yAX2f0*R(Y6J?r_qd&v<~TJVYnX$ z`-32KG4#b;>~`-Vzr=F30QmS>Ht*ANah zwY?7Vs`b-%oOP{BF*P-eaf&rIJa`#28rggXTgt>2(N2xyJQKCLfltxNnnF&<5KZy8 z%uS6U%}5lD$DC~2p@(o5ualcuFg3BqfaY~(Cu6B2nby>_nsd*U>5Wq)U5^CP`)9y` zuEzY(`E&PjIbceArNc0}#{s{0M&~Ag%cc9;G|qLH>V5i|3vGJEyw~Li@3~f-uec4y z8};X813%c>c+DUJB268AY|9@NM?Oxv&q$*-_^c^g5dAHyL)!BAVk8Y7go-5ng7c~+ znRQB;$yCNB;6yLZrGg!9B5k6SJ6z%K5OKL#>`njBg-HI0AMxAgcwT+GZYY?P?I zYA(6Z`E>X9>He2^X@9*JUjG}}`jSu@7VTiLAeHfGi^MQ1&>zXTZW2;K1=fuVDB}CJ z3%!=Ui*^ZPd5C^&mm_TYzzKZ3|Ac$37)qlZ4+k@@AR3!wDrKi|ROb`aC1E+g%bdKS zSf+PxFbA)Kp*AtE-w&}gHW8`1#uP|=zubD3J5O2^{^H^Nv6ZMy?e7V|${6Fe?nv7b zN>&4y-8rqg!NfEA;e$6>w;JttHzC(qD;Rk<^V=)YWOiNGq_Dkg(w2~y`0s3e-<|B> z2B8h3FP)27z1p6m8WS&9nPW*K$;6r=SHh1NPIUTC*Orkb`=&sVH#qD)<9pDAFKweW z9-|>{qhaWCakorAu7NKbE0m8WqOvyP`tHWkfZgF}=)Adbop2L)YZ<>xzlUQ;moZCsEMsrkc$F5>(pt zpJ##xDX-=pQr*x=M}-N%^I0D&eWpvwWQ_|)6_}=qs7yA&$n5D;?l-Ygzt+WUvyz`_ zj%3$3S-8d6y|T&S_V;zNw=4IB8jO3?ywg*cgIG*(Gd(X+2(Ne%#DQ5HEtF{u2?0(2 z9FB#nmySy&NLBq*vC$WZ(*LWzw(;XlrbA0j*z?*qy~au2M;^5wep%o#iOCFUCWgnC z1>*+Fw6rg5m%12nD0h&lrpB~Z-&tkp+Iy`9cP}9RJ*)#=&kK);X*}n41PZFm9+uhK z$N!>M;9v^XjH$t#EY-9Zl2>h&@f3ehXBF6t6!5QKYFViJsAWdYHJNqlk$^gZzx7)a zzjE2m==yQQBM)EyKBnXE$qISx>iw=y@LG@qGG(gLBwbbP*17cSvv~tGMhmwvK%CbZ zC=K5}JB`nL$?(G0fux!>P4gD-%LUdD`U+uP%BB+jI* zF?FTBZrbY%W@wn?G6)|7TMVkO@rYylJz)3x7Xpvpb;=NRKPAxGS5of|d@k1&(O9Kt z*Q~kJ+&D3Man_+sUiIrgPH_p%A(oEzbUE(Z4$@{PwJKS3+chkEnEo$50j;7${}4+|wm%h`z-qK;M=r zG*a-)`5gh1=e1l9cXyzTtEE|i$FWrP(2zr_^Jg2Y#86lBIm3y-lwV~?$^+zUl;&c6wre}N|ws0=?K%sDDTy%H7NFThL zm!**$8M;1M6;1)K%?k{CQN>Vqy?6cQ6usjB2FA&u}3%43%}kAkXryP=Ye{nR{TvrWPU=GetFU;MU3S)goZ80pYrp zk(VKGP?UehvLPve_$3m3FGQbLB$&^DPFCAIel+SMHn9TS`#J9ic6KQDazp{PcD8Z| zPjEoVLNpiOdrhnmb6L1wRE+mrBnF>7aeGueX*3rSg`Q5K2!_!g&SFHT_+v&wW8H!o zX6c%e!@e#?q+dsrDMz{+lBwECGF8O!xW-hm$CEY2q+7)r-o!{8zQn8ulwLvafJLpD zfB0!0QIP4bupOETi>0)KDz1?Kjg*)N#<;CSd^$AnjuLZ$(fEkQKSpW4seA#MjUi}d z7e7??KJby^4|=)?x7SbT9Syt*4nDE7z7e&)jpU_R70pvlq`mc>fl)uPr;O^xFWrP6 z1t&CC`a2DWCPsO0wI`8!ioA!ZJ$?@*x()r(3`Hs_(H;gLk;QPChpS)wD3^4?exvA8keO-=|gk0S9z`7#oRwuuIBADZP1K+oB=Pyf|7-MWsp z$Ej3NVko-}4F!B&O7px;4-woMCRB zak?1MJs(lBqD2FOsVN6M*k$G(rJ)`15zSg3eK&(1g<2nm+C-(IN9bF<2^6sBu(N~8 z;iP@I$y!*>5;0HIQp#oEAilVg%>(6q`JGl96}6YeE^3r86-h7DpYCTKzkJAH+r*_X zrjo3ZU4M`~w;a(s1{HC^g#6CO=r{jf1>N&;#VN_|uPTV(%bTH0x3EtY&5n&$;U%n; zD&$Bwk>!U3M>pFilT&8jQE)qm!MZt6#NA|K{M-5aW1Nmfh2O>$o&FSJB^PduWi5ad zjyejc#Yul16*y(mM^hG`7tuMAztLyr-@;V*xav&>;>*E=$@_$?kEJ^G7s7(IoL=!} zD?Z<^!emRbCx>D{sW4<6FvzM)s9n$(8p+7SeE`0aG@NCoKeFZA3F|=)*L=nHilz>p z#Tn?lmtjTBgt{5gVQpd|$v$cPv!xltSml;f=)HBXqDqkH&*rLldo%jwQOOyO+Gi6q9dD=OPlE< zI8-T3#>W>^9DzZo&BLfo?kbLA=I%qENtO}V$#+U)3NR*K_!pS=NlXCO>Z4bI*sHFB zIj%vvmYhVfsv6qhcsowwtRo(Gof_&s43+Q@ad^cuXhpH{bIkA6wM-S%E|>yL^$p{k z@(k5%+DuY%)h=S>YLvB?V63m=KDS2nWVP?|L+2@5-SWN4xwPnyYNNFI=P!|Emq310&KvG^ z!rVJ4#&y@^qcF@UGFRhL`OX)${fOF~f6co@n2Zgs5$8tEZ=_!&-tg!T1VIiHTz?v^QV^J%J3o7r3MdH}N z>534SfI6D92{gKY9IvG(Z_$0`OL-gO~h)FD^5sK`Ts&d&X%;$(wf7R+A z6>lnhOXbZl2n&h79aR$+VYV7KW5~98trxap1-m+8EIU9qj@sb3UHv*`9`1Hn3!i=t z(9&wht_*bb+|#awe=cU~J~J2jO3eN0M$8+nR%I%)6iS1?YnV0C{kn35F?OCnq zS;u7}>0VUGEm8k0|_3t=G>i6aILZ|?`D(u-p@RR=b1{@xP@7Bx4v zYd<#BI_m{h7c~{i$Hama7}p2#?~}V=HQDJSIH`Vx(MO!eCbGjun#cU3rvIR(pQ^iO z)v<@3dw{vS2ZM=XJazziPcO8MalX#L8OQLP=4m*a}D53{!5{dEpAWA1zd=hPrqN61iH@sQEvkfZs(CdGnwIX`r8 z9shTX-pqXS2C_xn4(Do7ewXJTxuDRWg(CklKYUpBKT2_nS|;w=G`Y({atYT+v)@T1 zhSMN0BoOh(?ZV>3SX^oRj(l+Su@Ha405v6RZenv>^6VU~__s~7L!|m8sW(_x?qc3N!&_v{YYMjIb&pKhV zKapp9zP@ct<;g@JXtJ(6qLBOD2jzDqwUf`OCsN|7wrMoFx*e0$o#$z~7V~VStJ--u z#rE=C<7i;@+|wPyqxHvH!`%Po&!(BHre$$voXjW2e@ripOtm{rXXuo~P$S1~Iv?@c zQT{Tx0kDgAP|!bFs8YMSn< zT_@gev2ZeuadjbBZH}D;t`gsRaS}lmFh7$sEB~P>4(~Jdqs-jK;?vDSUh?eoDYBRO zLRR^6td`4q&t`5Wk>l9Qu2S(5J&TwENUZ#JdX*)rUrS@$Gq4ZFvSSNj&%=o}$2~Qc zNTwo;J}ks=2rGgTrnKZ&Ftm*SLHeco* zRgyb~8vO3A>$C0ET9i#_dO^=C66wOK`BK@4*Bb(BuNA&S8b54b9)Ei&{_gihkJ&bc zz-peQCL_?_JYMFLCm_KNLiUG24AM%RV|S^;8!5D)G0Gr??>qV}iY3EtN9C#=eSrRY zHkCl+Ijk>MX7kP55Rv^M#*z-&Bp`!;oIcMYUg%&&UQ4(r|EmTeNtW3wOu|CB=@+#AGJU`tp~C1~ zr9sL8Op)_B`~Ws66ayXSRS}-(RaP-2gkBPg&C3*0byS|WlwpMFRBB1%HX3flAR?I6 zhnJpDXhp!b`T=D*!;U5SJwAtFE_91xbZ=J?Gbw3)nh`RIj$d4XoY$a)V5P)M#H^)g zhe3R=-W+abZw87sMdy7gHBd+np#{z3!(d^QOrBK0NAMXncNh88wVkTdU&W5aU|=G{Xo4SQWF zOGXI&5ReUms}B-=`t$#JG^|YZy3uZ> zVCe^Rq9nV)7k4_KYr$f&=sq;!Mp=5tcsW9f8<}UV!7YHKB9asajKx!dKDs-k+NYh# zN)$MYCOK<_E}3EhlMWs%cy6I|rY(;Nl?mqOHpgr!#0JnI(Rkck39d#*n1$hJJO#lj z)qQZ9v>S9yC^!ASs606#G(;osDCp&630+re&iA+z&Iz4$!LXvZ_3zV?E-V0k;r;j? z4mIjUoDqQ}od*9EX39<(!1i2P;>WyQicZ)t+kCUITntg7pL!Xm1~bi$6{`jV(@3az zbDp6z4()e4?Ha4-F4`)UjP*jz=hRpUX8i0L2X-T8d2Qo1;+On8{b)W|?)W-VmpLmZ z@j;DaQy+aVbGPv-L`PJn-EuDT4%I8fm&c~PIxqA8FFYEJN;&d>Zjbn%qQ4%&{}&$3 z_*_QkpE43DEGDb}?$L<$RB5{VM#)EgCyc|X){azND5m;bsjN}0n>oHvF8;SlJHGl& zh3aCp@!x90scQWyDp1A#c8wXN#&AS+sWInot(``V@$&dmYv+nvy-@wRvDGWcM|>Jpi{FpPxt*lJQ`cI^)=MmRqOxOqge^u=|INUdsL`x{*?BH zl#c$-9t~_nZR;ZE`d>%T|KicCcg1LLeE;XsI0t6-{ijERfCJUHF{uAH9!=2e{{Ql5 z#JD33vTpuYkES8cR(+Rh{bu-o@@T~IhdCc)_L!(wM>UlHPaX|^Q`U(3K7X#ySc~$1 zdNjAFsg`yHT7N=3ap3O%@Mxs(Z)f26&4vHv(KHv6PaXb;M*7X{k1t`l;V_xA>nPjq&>3(m#);g89)_l4W4dxB8Iw5sg!~-206~&9=_vsZ+16 z`_1!&w(bLsGvD?5t()n#-s`Ee!2A1ed(&49*GN2Diid3+t@Z)(>GKGQhyUtKcXPQQSxUi_DpaeF@YpGO_nh zh1TQGx2U_7ncl0mna5K<)crQWOVqW|nQz~C&q=cuYHX3`;i?Puc%Jy>;Xn(uEx-G8 zGxO!?dIt3*Z%H+B0KpK2V;RB$FgQ*Y9NZ4aTY=->z@ZeuM54hYhQVa8V2Z3@s`g+~ zQG#Xdz#vj@o#H?in46eRDw-84-X1Es5-NQY zDsvc0hZDkp<;`pu!U_xN7y&qG2RUg2UW|HMXag*G!}XNI^`pX#Vc~j}*j*ywj@rP$ zJ{(U5fNFbKlo_ZB4ldIMXSm?lBd~iau&w(5mN=jcq+Yl-&~7_iXEa2BB1*t8lpqSS z=n}O84U1`yid%{LR{|cDL=h&h9OmpDrkoYlVE`!62HT+p8J|ZRpX21g0k$`h?iJV> zF1Xb&+`J^PYkAD7C$7C0ZfzgPVK^qF0$YzFBK#cZlQy{KJf?9Jo&T)Ajah+)E`QWU-+WDWt!g+`y= zB%D(uUWg`&ibgXWdL4R4v$A8iU%#Fh1z9loTe|=w&_Jm!No7gkA_Sm-Js~&~`~*#Y z+Q!{uNPaSdk&WTEnI*TJdwXi*B=vzR8RBXTQ)&!xGoX=S1~@egvG!Ns$-}s!^LOEJ zKWj6PH>x#Wyd$+g3Ct;$uxFPb7aeri4j)CsgQEcr&~TiQpc$D&ZOU|AvGg~fuq(sB zkI($vw1L(Pes`jNt!*haec%Zkkd0`hJsJqaVNuBd{8fQ%*9Wk5@q=S%EVz@DR1hhKAg5loYnT!jH=W!w6s4WX?aFz zpeRTM8qlZ^OLZI5=o}dAf~VJ!Q+pIO>w?#h#H$m_C4!~bFMBCP0ZQTE)NP>aO}d>y zOyDzMl}v_J2RMQ^(hm-%(FdoR;e?>2(6)lh`jWl?Gwrnj9$A2Z!z6!$OhTVbB2;!J zVMiv>YH}bs*qbdYxXNZcD;sWr#MVX2GY7#epy1(-xJekW`v6FD1+u2_iYQD<(vH{?i???He2T*U1OwRfmiht< zh>enWSMex2k`GoheQZ)3ZAzvM!P7V}YnOPGk!@o;*l{J|?iLil4vT`vqm8Hb!oirF zLD-yWKvno?A;>@`N4gM08V!>dtq9*2JGc-OUkO<-3kAR+QB=iosF>hosBMfYUhOts z{CFj^s^N!7ugc1}VU_aaZD4+7VuvBXx({SE1}ddW>dXYtkb$bHyu8oDPDNPk&plT< zN`rwQIz>?Fws{^hhIT)K&IY8PW815Z%NYZ9YOj5_R%>$SotBi^uWvi*`^kpNB#9Rm zmxQ-+^C`o~whk@cl`6>Hp%7ge{*wZ?!UY>*oC5_H1>IE;`R2GFL8~rBz)Hxb3~p*6 z?kW;;uL>G3{JaJQr}g1QSHdfZ@kGsVuqq+@y!hI@z||x~x^DwC3$GRpf>8-+f#Qi| z`C~*u$haD}WE#nEgDWiYOQ0a0)01a?MY+#uLXPYq_w3*x$~c76s}<%sMy zsPW7KG{)4x4@!IC_%Mz#UzIY#=z@TX0^ecqO-Gx5S6fgd;B!*^7y|FQ4R6q;)+*+c zZA^7YTOFb*D=8PZgCVvS4!#qsKR2lV0V|wC!z;cm{JmCDd|z=!Ra8NVGl!@oaKtZ9 z!i+utyx#{xxIc*3Sr{Q)RR}=}vT7lg1;%k`ESI0Jt*1$*Z5TZDU`SYyR zAv|Fm1Tx8_NCrHS)QHdCecK1%L3=BMf@2OB_dwSnMccrBG=v)ib|>PqpBZjv4Pvto zl30lS3;|q|2!6$7=tSOPV~e9k-S?LiutOn5ka;%9&C7HXpmVb zWZDHU>Nv~x4n#u(OW^uf#!xOzW0G|rn8OuS5DjVI#gQt+5@6^o!TtQksng&bE8hkG z)&YM9f#sY8+3$mxA~1rrAw98};o6Wp-^Pfns8JxovKIHtF$C=xvW65DJqPq9bq99C z=_f)3B_Mg*jlft)=p+b;@X-oY7QQ6C68Xw{AxaC`gj7>2-W!W(uxz(?~nh#Vy3 z|8*7(GQofsx*GRymwJvhTP_bTQLTfIa>h1i@U(3(cxA9b21vw<^jGaHqV6o_LWgRj zS1>??-ogj&@vV6QlSqPgGpzT#fY~I1yd;cVIHZCY(z5O+PZJbIj)~} zJYg=#>bxty5Rw7M8P*2*^kKO3g7VC82G9^waGbQlE^#UFTpw;--j|l!;51RMpU;4* zeiOB3I4q-yzL|heG8vze-Um#9gW}(pcY;5irv^phR6#-N;$GoNV7v`)<321oGXOLR zixmx^4#obo5^b7QZfsUcU_Y?#pS)Q+@Qr5LPh=W)HSlAyEoeE#+Y4_3i8q0kyI9@+ z@&Od@IP@IHbf!qH{GU|X6zK90)VnD}5ZZK_E==%>zGoYhuqu~aC2~6NV5BT2a z7=tJzK};cb@HxgXk|6LLqtgt3m;oSOnE!kmh@THsLSVgy13jE@oS1=vh1d>#*b*}H z!nE5Mqu_z0d6^I3c-{q=zqoAOHjy3vV;{ur9Ag~bI9&rUMq*i;VRIEOeq;b}oMQ*N zKzxwc!w7%{65~A_Sl)*b-zQwTy`w%QypM!*L$Td?n_U7D-SPw9oKJXZOj;nZSSr1} zwZXCld+9a6U|{Q*n78=&df;`mWzxR_Ycz~LG$=2?@;ur)Dc@MT#tv;iKEOLU32fB~ z?#|ig8V5Oxyh>kc~os1`=$U2YBBHxkUo=;_x<;fcgl$TLus}67*sK z%c}6y8IIX$*1%PRtFt{$jx({pynFNvP-(VYqYZ4z3sfvPSN*tLi2w#Gfol3bxm~X$ z_jv2{Vc~0|8_-=q&oR`u!(GJo;R{W|YZ3C|?{V^HF0P(k*_gvL?&$D{103V}W}Y~<1F_h_t$A(IV)HaKP^1O96n zP#tATRiV>b&^-eW%rzr+NsyeKSyr)56IU z?pf08-1gavfu+FhB|_zMM!WMPZ=h@e*w>}mwqn`m8L(6)qf+MID+x+N`~8LfAq~Fg zdz=wm5uwH7-I-GtNRBPHjfP){#`qZxjE4T4AjTGj{H@}$YITmSz3sh*cj?Y`=~>Vw zbk-I~9@lo0qDZr`fc@u7{!Faq9|e@3QsSSHfJQX*@q{pRYzU7bgT*i&2%UxuhEs%9 zX}85~`lo#AU9YwJ-W#`KwH$h(9xLvjZ1^}dR+|?+!~%-ObR3No^p6hkP! zabXb#0~n2oOYQJgj(eKmPp+@cNz4%IZp!djNx0|`jW--tQdU^VTaqJLh#V?==kfC( zfqZS;mgd>oA8u_~AZs&Hre>TIHCu-#1g^7Ra0nx^p1%7z+rn<|Sl#wBX(HFDn&Twr z#q?psi!beC6$B(W0(gAxEVD(#?vq9Pu|g!lJ83+&i>xtHJk%u3a}l&tBAjmWWRN#@ zZ^Ml=k%rIPIDH2(AZqL?Qz^R$g%8|G3WNW+Bm71MY>A*s5l7 z;HxEO=3ct6!q2^QzvmNQqR=MKs5J3828l2p`FJ<5$loAjLC?HgHl=LRJ}6Q-;<>&e zR$H(%SKw-lLT1!AM9 z8qRa=Hrv6qHs#y}nKh49pfYJNd?MI#FFM>S6cv$!tVK~4%})P3np}=o#6u3VO|v`0 zDUK7xf^}*F=|AiE#QzRYI8KXNQoTljoe%@~YEBKBm3$SssuAq+`1aNP>;e`p=a`1F z;jCVU->PNEj9w;KVw1iUEvow?A>%!@K{td$DYP4L*@n+&S`LNi>IM&fqbq^#n7}5Q z3cs;u!3N^UQ(z(A*iXx@QWbUQC*fvb`eGyX#`Q_PjJUSe+p;jf99H(Y?98N#IuJKumBJMnl!o*4y3pQ7dc2l zE3okrIe1_W*|^ChSa1ho{6hZ>QQ(D~s8FYV=mH0Y$cHhcAO=<#gAXQXlg-jLLmJj_ zDr;k#R?_AuQ$!+ClX8?=*y5Ia^dl~sm{BTHkqc%3ZW=E+RX!TQ0!+1P8Tl|p3j(o> zulxcCC)k8EWSALVaHde4>zrwP6S~}JK{%}N!wMPEtlA(#3{7Ya?zF`UZt2fAVh{rw z1c@3gupv98a9_CEGlmI-hj=}BUVF??f)ezA2~mio$T+c#V{oz*zUX8pTfvHB96~g8 zkc0LRQHoIbZb#r_(D)`MGDegF6}N;?$JkdQ6txU~CYxW%aO6i~7Be;dLuQfwcM+U9 zNq_?&V3i6O00ai@9F+e%3f0`91*uW(9grBoB4(8jb3DQbG%&#zI^h*PRDl=f;D#`8 zV2D}aVhJmtff|?)LmT$fpZ{!B4%@cFN^xQ=n94{&??yzpv|t4;aKQ>zPzPR|Aq|4- z3loUZ4`D>%1ZluV9<*@9aeTo8U%)6C_H>lY^eS_NLSq_5^P6L_u{CU11teHkg*z;( zHid}RZdi5)N^rubs3>X~im8P|6g4}jNP`x{AcsewVil#31Ix5d?RyIh>yjcLB3C*5K6Cwzth|rLtk$hAG8J5||HIPxa!gNCz z%&3c!x^WE!n!_8P~sNXY&guJ+m2f)OH5)cX7NflEJYTx zOeHhgP{uX1dktksBOBK^%dDiK42^iB8plw^Wx{I?Y4AcB8{x(m=FpN|bpsop8m?zz zD%0Pv&ZbVFf*-^XE!Loc6Lbtk8Je&f*R4womY`$C3L)7#C{c;1n8YW}r$kOP$7PsY zUJ``RRZ1oS0!c`MTGtw`w(h4taBYS!Ai)S?3}_y6odjQdR0@dw6|fHy?79p|3J@I@ zv21wRFXjJ-vic2kvQK`QWu=T+Z!~kWoSi0>5ZH-xECn0+&4>(_1m>dvi_FGFbD9OE zjY$a9Dz_jgtzdKuTQCC~(KW{{U{q&pGV09C{Ig3;fdfrQLn&YWb5!=5#^==ZzXW!T z7!W}tHaKB5LTwou-Y6qTluNROu&@$4R0>Pn;dU=$PrF_qgjI_;321HCir3ZRx8?^x zx0o?I2IP-Vh(^aessoS1_hTTp%nzRs(fSZeqC4QO5S(mmFq=%GNI==zEt9fksqBqd z3_=16*laX?HYJIOM9t?$ceY#+?`@L5yfK z8L}jTgvYNvbslBAvQ)+fGC)BGggjH+51CRD0HGy;tJ~~nM|;}Uj+uOLgA#?dOg{-u zEa>d3_UGk^h#L1h2o z+dJ#*0V@CqP)Oq$qFsCPmA`!Eqb)Ppc!s|HId{+1{qA`8qaK=lZ8S*Tm?5{9$VDD< z+83e}YdDS4N#S9ap@9*pummGUzXoz){$*&;10yUUqWJ3}k;E(mHt>T&KmE|zzMITFu)FJ%mIXvXt+7}Uc)^us??Krr;52c!z)5E#&lH2b=;h8Y({c~$9R;-d2|_bq#1N%$9&Ys zeKZPLq{n{*$bb|`-mu3Zxki3O$b?Kre;mk$bjXK{#)1@*gH*_hw8;NQWJrkA$c^O4 zUzA87p~#CA$&oa|jO@shM9Gv~z>fq;d?d-2gvm*CNB&aDnzYHAq%4*^5;%ekb>y0pu?#LK)KMI;H!r(B12Xoqz`hrv{b zzibC~00(qn%f)2O#&pcbgv_8c%y7_!WGKpZpa*(rhicFTUQkS>#LRZchB{+Px75qi zM9tJx&DCVh)^yF+1k0#ghs@-JGmryiK!?9H1~h1dZHUa@1kV596wcu!O3b8(V<3Pt z_)MW}2YYyjDL?=ONP%on2hg+!dMJehFa&i-hYd-Gqcly}6wmP_&+;_S^F&XUpq72XU)X)v(&<^#`53S4fgvxcWhkmF89dHlavJUhkQ6r0cB92Y)(FCfK%{IrlbeHfKWrAhj93T7N~{`9m)&^(I$1$Cxy}|1yK=w z${KY~8xV{>PzQT(haG@}ZJ>u=V1p&d0U)3#cAy7)kOTiY-~=qF0T${8K{x^#AOmSo z2h8k-LTG{|o z<<(yG)vu(|rz}xPU;$02gD5x#dJu;rfP-|vA~q$3KEQ!5sD=_ngXducN?-yg;Da?V zg+54uIlzYYTmvHzglJ8HI-t%%W!H9n(b>!gJ^%nHh=eqVfCeCg_JoB82!TU*1P?d> zQ!r66z<@pI10E}aJfMU?$bbW&gna0W1h9o5&4>RlhyYZ9P({dxN>~9CD1<=x18~65 znM|W!HQAFz*_2gTgXBrsETTwA0al=e9q5B|a0eUsQq2U+c9@4!xB*QFQZ$I5bZCcB zaDg(=5^y+HUZ4k9$N^3OhjmDYM!11an1>v7*R0jr#ynJGzmak2R_J^V>kw5=!GHpgCE`6-Q``iY|sCEpo9Ymgx~Fi13&|NxP=BdgIu_UUmylC zAOL2d2OiahZJ14Zu!J>m12@P34}e%R=v%&cf(QVN;w4feZGk^E%3PJ)_I2O)gHlWN1#6_yhm^q=!m40@&q)EszFsNQc4P25Zn=560s>Zc2&` z;YP4hTWA0`$cI%pfI0vNa3BY3c!q6Ihv}7Dh>hD+aMpbA01rSF@SRxkCEt87-y%KI zBQ8qzed19j{^!f(%fG_WXqgm;k=$ zg9Ffn5`6~`0AdL31I@grYG#L9U0iPz4O6z~d&XyzMP;R2hbdm==IjSWZ~+g1gCG?H zA+QC-@PZg9U^FOW1uorZ=w<&j;bJX#0ZllEZZL*D&;`X!=8ryR%*=;&hyv~G2UysE z14x536$Auef(UK~M394XaO7Mtl>_hta}b9jXaGy*Edl?dQgJ~ z=z~_U1$ovrQO@V7rs}FL&wWUV7k$8~^|ScmOgG&~vZ{dnkkk000C40OO@; zIUs;sXisKf0mnuFFGv9o=myQK1IGq{B4C1bJ^)0(Ok*el1OV#27D}nM>eq(t*uG1w zMoLFThec)w<7@|TSkV8>JWgI9hjjo4{Imyjuwyi}hvD|k%p?cv^=)(T1zlL=#O>?q zM&{}H4C#_c6d;$e~P0VnVRhfCT%%Dk&dmN+2L?~v>xFR{p9gv{X5-Yg6$fy7 zh6Do#@*o%T21M`?H}WIrYjuEX@C@+M81g5F@+iN@zC`jWxAH3w3zIJUdH}n59FJ&+v^EGGl4lZ*vhx0gpUo~&@I=6FneRDb2^F2>lI=}Nj2lW2T zb3P~ZLYGoM5A;M=^xqtGLwEE?=g^Rh$w{YlbZc}-$Mj4WPf4%zPWSZb)AG^K^id~u z^yGB4X)XJ@FX{*H62^AN<*;_G`QY?Yno} zzy1GRt-M0vBa)KmCuWsOmU-$(-NP$uS zh<>ebG^*CEn>kBGmZ)))CPgEJxP}Cx2CIc8YW+5)*ksPxmo(L|A$(VcjKvs#o@w*u z@+HieGH24PY4aw|oH}>%?CJ9-(4azx66HDX8l7XU<5gMm=9JCvt$yc_uA3{`~s)^Y8D!=4`dmHXMNk8h9Xr2`acCgKQO-6LKLEbA!N=qk1Sz=2{h24#UlT94b+G> z2z4_`6I~i%2tn6WXO0{zkf97V+l4Ztb!EiRLLF}AgNqDg08=EPg&KM&qBb3gWKvN& z`Y5E4N;+wzQx5fJH{7&xi!#q-{pfwWo9?tV3SQY)fi+>HPpIPra94KBTcoZ zm5I=__mNwzH)eX1?S#{yAqFt_2|F*n_1a4lu}CtzFTefz`|pCz2H7i2*bq$9LEN~Z z0}GpsdN0HgOKfPq0s?$7#u;n8u~z~^e2_V#gi_kU6PtW8%CA*i8^`}GyZkcD%f7V^ zJ2l&UGtN2dyfe=|`;7BC>$FodI_Ug-G}1{cy)@HJJN-1&QA<5F)m8Jn@_;dGy*1Ze zBRI3wVIv(h%|)vtHri>cy*ArzyZv_3STp4{-F4f2_gP@Wy*J-|`~5fIfeY@l+)3hn zIO2&buJ_=LJN`K2kxRaJ;kGG$Ip&$e%=qM;d;U4-p+8=Eqnew3I_k`FE;{S2yZ$=t zNRtjp>b2W`JCv)(zB})|``-BMxC=i#@dWCww9xIeQ#3edD?cYxKoJMAXnyr6UT@AcdNcJTkj>%Tw$#0k>9)7C)` zdT?Sry5L^`d!AIQNCDZC+lIh&vy zo{){3wZk41v>*oWC&L+1Er0#HAr5nxmE$Rm9{G@j3s?|{ZLGr{`A~!oTCj))woQQf zI0G4;Q9gT2f(*wnVFu}84`U2L3mrtm7y950ZmeO5J8NM+Ququ2q7e}<&;efH=_C5AwTCm^GU@9@GIPOu1T(2s5H@XHy-P{;vBkBK}hVm^cc zggvBh8`~%!JGOyE7Um<3gd}A?5PMj6w{HIEOvtAcs(3p$1T(1QF@cjt%BO z2W3D7I`Y8>Bcy-{V#q^28u0~QOz{y=sKF7+(252+Q5ZPjWc7+h4{nrUh~?Yh5o#cY zQf%Xoau9+P>0yjAssnLzzES9wVC`dDBOPk?RXMdCg3pDYCIg~FCZZL%s z!EwYojDi$>NI@O4;X^*Szz?O+LlgF2vs6LnZ(%`iy}9L)dWefD?<6y5+1di;V5TbL>tSWt>T z*5L`y7$_H}5D89*;R_k%C}Lgd(U3B>v2`11%}NTiQlhjIjOao#h~b1sT*R2qTV5c5 zz>B9Ep%39qL<{~vkA9#bH0c;85Z>^}4l08k?J$QJ$lyaXL=hc6ROK=3F^U`@!kLwH zA3HE9j33BA2Rax65L)rpxTYf?YhVI1gl3K}kinrs2uD5+aRXMQW4eb;EP83USjV!r zy)M(^9^$))xyZMVHv3~FM$igz7{L;acmX$h;eth~W1NzhZys#W33{kP2A!}*5qqJM z)uMrrhSY)?=;4mo@*)}I7)Kq1z>R*KAqoFdETt-m(GNeYG97-*$92}gh(|Oc5WJYK zY~9fWGjwFCkeHCVtiyTJtK|Bv*S$`DvcKRfU;4_|X6qr?YKxY5ti;0nfK7=EEEqn(F&*6^JT7%lwZm21V`~|sE=<(%s=-HU`u#hIwfeRx90^9aT#0r>A zXFKEh9bJgx_1fXdKc<1+Moe)&IHAazwL^UA!=x_QN=mrC;T-)CgJ07Tw2}8C#NNoq z9ad>*G2naOM&~zD7-cztGrj3f61aVHM(b9bqaE{bW-tfb>n4mr7rShNgICLj5fp+J zitqvuTq7S9~bUy!Tk%BZN;~j~>L8VX4w_4#lTp*aUT zipCCw*I*GXoCFJ2K!YwI0?kG2MjdQG12qi$nok_V8sF;n7Se+}T{3|U`rtxhoPh-~ zSVKM-@d9Fqa~Wt@f$n9n3B(W3pMEgmx#Ox1d#r;KX>!2|VlW3I_B9;#Xa^^3pnEm! zq0})XJpek6>7^b47GPVz+9hd`Iv|53&7M7kL%Z1nJ)8qE$WJ?f10xL(J*>kv&;u+e z*rcU{HAs&Zk%Od75j`Y>FEE2OSc7kg6FSrxJ)pxggp&kzgD>#HGmKzb4Ujt2APZ?x z4B8+)EJF@@QVR{C1KR&XFeF1dYy%JmpcIZy(kUJ77$6pAA#NaG27!_&;Y|5N5B9{K z?2S(g(Sk9YLpt1o7BB%aq{9q;p%)rW`9M!4*_QH%VI0z-I1!B}u~0jtgX~$^9NJbN z#@-k1p&@pUI)K9$P9Y=;&H!p5C03$Va3R__(IdEkpRE8B*n%^OUL=kpDfY}HS|Tc@ zB2-|a*a(m~O~Wdbf-ThG{FI_C-r~-jqAKoUC9+~BDi0Zs5-twoE$SjK9-{&JVkXjz z_zP4WVk0<)qtZlUHKne;)Gqe0~QDh zHk1jqTnjPe!4c@d63BrrAcO)LK@MnvCKyCF$N?LCLKoyf6Ep%#RL5B6fEb+RQr;zA z;zv_HC0~k^PXYx{qQM9>!l;}ELKuS=a6utxLL-oYEp!7eZ~+ty78#s?N0`GJc!3ub zf+c*x2yFiXb?BKGK!Q?r1XAWDYNqBrYGbkVrEBU?RNlmd^aCy6zzVp47R-SyRKs@Y z!4RN=X~fEeticu#gF!IE7nDIXU}g@G0z%lrKOqEh9z&TR=NZt6YG$W)8U<_W%WHmT z|HS4^vN@@h(U|GheCFPHl%@aB1ANlfsFR)pGph0 zJWQHCDqgN>n@%dgylHX})EuOOhh>5d2!Sy411jLa7qkL27y~2ZLQAf|7z6_~Bm*Z1 z0yXew8D!~4a0Wt{f~pDwH7o-q6oPv|DzGl4q*5xe?u(^Lh+)Wq5v)L$(0~|p0(Eo) zDL4W6t$-8kXF@E&ZJK}#)Im2~LmHfcGav*rlmQ#?X11CD{Kqri3vCjW1 zvK(tnuw->4!!OtZFJxt@n1e9zt9@Jvz_x-eAOlfKi@_WOHY_B;3WLES!!sBRyjHA8 z$}7EQtfbg0OmGWdFzP~jESY9Qd+cdKW@SQ(OE(ydVPYtwg3D=Itjy9Q#%iq1MhVBx ztj_N2P1Nko{w$N^EYA)t(Rzc=0xi-8%>S$-(>5*B9BtA@t%0DU(^joDLao$hZE#Sn z)pji|Vy)JOEpKqG*Ou)lg00x5?QM{)*|u!}qOID-ZCbFc+t#ho!L8ipEm_d5-S+L0 z;jP{VZnG@y)Fcl(I1|oTk0?4&J9I-bWW(b6t>iv!cUp|#Uapd`tlFoUYmkP$h^Ka-}Ztj$`Gr zOzRf!)DkY#I1yCU!3bzV(3H>ZwvX7jn9l?aJ(TV?P;c;VFX0St))+7NZY}aY4JP4% z6P!YT)>)V>K@LO#6P&>{n1UE^0vi~?5Qq^ih(QiGfhKT|7I8uq;FBDnk2rC{7UX~p zM1dbRa z`LyQ}Fv2LfaUTd!8gIcIEP^E*5e=}xC^P~SV3#nuFgU_+47V=TS}!c*fUf;Q4tVYW zMXx7$APvlcI-El{=t(GG(}y&|KuG}_FfcuA!U-@!Dmeiwc@jFnAx||zfrY~tM1eHW zLnhEbAE*O8WJ7XR13f6h5wt>q#TpJQgDty&Y5CST96?*zRxJR585y!VB61>Q?jpC) zWB|h-l|jzYL-cZwJv6c=U>iNi0Tlp)4>bc06hc0%0t+;PZ{`03G%!JzazYBofi0{M z_VB^^c3?Y5f)2DoJ7mHRv>835!yRZrG@OGPlmRas12Gr_t}R$5)W9hOTR7KVkBI{l zm_Y+dGd5ClH482}PLMGe!5x&sDD=V{kbp3^gCaOV`xMa!K9~UI0lfGSGcbW5g7hJK@7#>ETp!^0G7Tmv0{FRrm#n}9^ualJvrM~>2P)Vn zwSydpfiyTCGvI(CE@)*56(I*>!rAR%eHnJVPKK9K{>c+y9^^)rg}T+3}q|50v9LpYp+Igo=KM1eBE zbZ3)bO&2y!E5iUeg97KnTGauz<->;*!e`L~J5a(6P#qs&gf1I)XQu;cPg^_W!4^cr z!!3bl$DSi9H!plrFi{*MDGzSzb~y5OZ>udjK9aJnL~@mnDQF!mxIiG-f-u;_L>Km9 z*K$56!#WR;9<)FpaDzAyoh{Gj|J6U+z_Kof|zJrsft=-vt}!T5o(7VLpun}8g=;q?N6 zE)Y=zD|GqXf*7dl3beo(Fhe^WLT3xMJ#@nyz@J_N0Rs_vNE`XmCAp*z?*Apt^R|Nt zzMK|;!!vv~Jy=_?(E~YH1NRV(E`PcUP7pn41HXa4faT2FyJ~XJNh;9_oPcL)dFMlq*WM_U^}cs^w`$nn$Y~bmbLRC zFp84@R=c%(l9q3QHi%EMLp%Kpjq`|8*@*v=1li$$*CDz`&yXv7DKdMrCoSIsPCL-L z7)UR^JG#E_JJ9y~=nBm%lma-k^}xGz!5jR|BD~*F4;kw2!vk-`OT5NXeBjIv#%Db0 zZal}+tH+Bx%Ht2DmrlvI{3_OU%E!Fuki5%N>dDJI&W8=n*L<7ae9r&8)a*RZ2dU2k zz0o&~&=38D7X8sTz3i;~6)HW)GriMS{nbFd)R#QfTRqoz6xL_G#BY7qcYV@>y=#j7 z*js(sn>}BmecC(y+Oxe=y8YW9eca3aPSSnd1O46O{YmQm-sgPZ`~5@$e&Eae;1m8p z8vfy@eBvv9J~Dpei~Qq5zB@|(Fams zqdqdK{^~>g>AQaT!hY;abL-RoF53R>yKwI7zBj^r?+^d)OGPlSLMSA^@-IL0H^1{g zKlDex^eg`)RKN9KKlW$8_HRG;cfa?4Klq2g_>VvNm%sU+|M(k%`maCxx4-+pKm5nP z{LlaV2SdN`{_qEH@k0eGGyy;u5;%}xL4i%s7*t3Q;lhP?nm8;ti6TUb7cpkMh~|z) zj~F9<6xl@N$2%QMYD}0?BT1GR4WW67k>kvZA#ECRY4eWEnV~{)1Ui&xQJ|AZ8dW+} z=TfI=&^T2(NhUO_SFvW*x|RQHSFc~eTAe0n9XqpU(WX_qmTgRHl-C;b*5Mx7` z7o(xPxC!H6pBJ+dy_huPJE#-C=A0YN?yyu>hYbcivY|V{!M>i({Yo*S?*5cEN|i7k)mTJXg=9BUeqoJaQA3+opVsJP&SJ##r7fu zt0UXkTM)eyXG|=V8WaEXkG00`sLw?ozq-vd9Ko7owiE9|5<#wliZLwNoJ>wV5~)lG&8`GuOt!{!RIJC* z;w&@3-2SXA$|461>%hxitnAF>Oe9m%tgiIZ(n~STRMRcN43n@)LA5GU_ySEZ$=p`- z^HH!^sdF(Q)m#;<`Do;`F^UGX6Es=NEL29&Xoc_4G8ufb(NHC=bkk*-ZPwXm=jzl` zWXY6lC!3l;iKlC4%GM@|bo#a;ZLt;CNOHS1_at+<{iqy7vF^R z6)4|+1%ek~i1`2QSKxjLUXt4Jl!eyeharwQOKHPgm`bGB^(iNuwpCYSY|(wGU6#TX zcU^H;5_e>cih@uorHp%7sXI=SxhVH+Cd%cUfr5(Xp(6S@6pV#N181J88rEV8$&%RV zr=gB|I*LPFT0+T=W3*JR+*G=&R_`<~)x z?i`sLUCPE@`#ket;oJNw-2lwH@+lKbdNkS{Z_IGTdGFnKW*HYTchu9Qjdifryqr$g zukzJT*|q<=u`%gwtzOsb7rQ&w=@Wf&a4Dh3YVXT%Pp+bEtJgb~$dUbmnbDU=*|8Wg~Uy+Oep-~%PsZM;y;!XHoSFGQZ zPkvodpZh=}FFrE@m2OZcG0k#T*&0FAB^!F+Q&JKYP3=MPe_Z8|f#&kt$p;cak zK>m59Z1o$WsfhQ(;pEU%N<0Y#(f7d-PLYaL{7?x^2niGtk$$%mpk!v4l^CiDbz@Ut z4NJ!y0$Oi-Jc3{mVT3v+Cg_D)k<1SxI7hv4kXU@&B6ON&ML`adkZ6IQnEog}q|gju zJ<0#pNgx?XNk*~>kDTNsDajE`ZqjI*^dwX~xk-eC5|frBWh6m)N=c?tm5?;$Dxnff zSt3N1wY23dZ<)(l(o&bX`6|UfYrB$^m@UUn?ZN4Uq6|AFHV#1u{DX%d%4blX5Wh#GD%P5+JmfZ>6zh3vnWj3>2Vr(^QRg%qZcJrIz9A`Ptna*{# z^PTaWXFba~nak|6GnEPGT?!hPgg&OB4~^(%CKHvfY-J}~DM?4Sa+HyVWQeQ8;xljh z#c8&fm+LC#%-OFo#)&VcUuQ-?LH5E@{cYSdi^kcyTE}qwaO_BI-zES0H;?2Mv8bt} zX-*G&z@A2yWKb=t8gs43VKFslRUOyn@V0ckzOb(wYhh@#*S*-rihLj29PI(CIhd)d z1Zm9cJCZor^HY%Oe8gqM5S zdIPwcfc?6d@EXM@C3CznUgmjMONF7fuwxfnZn%?MqayzlW?2&F~U!@xO6febQf>DO7&*%zZ$m|`qQPfQ#SUzJAN^{ji$9+BR*gJ)Xp20_krwVHf;mG^ZuhEZ_SB%Sdx`uC zZt_|CH7p0>&gHcFU$c7h43B+S8eeY8W1Y3&nvQT z`zX+Nx-Y*F&1n4W&oa%1<1XYQZT95@%@Ra~2 zCK#y(2V!1uFkp0W2eV}dc@PK>;s$Y$>=I)FD=-NW=K>k!_ZG~Hs7~AVZQ5WivSN>@ zYDMatkGP&g`Ci4Zj!LYgFDsx=Q0(sY1jVnKr0|k1eP&My;ZTH_uy%}4*@UkO^@`!_ zZVEN*IaF@to}=`5%KN&o3Q=!=_)ZW7MeoqCO&ZauoI~s;1PSA?5+P;|QwZh~EY}iI z+ahZVtwIsKLKM5A4YvaC^3M32!}G*v3|sLz`c6;qZc+FR?;g?NP;S>I@eM7p7q5xC zDyBSU4BEi(3AH8=JyGs<#Sg2{O~!*2TW&l^kt_eEQRzVO!aT9x8cg*VF)CC~4a@Kd zdC?ci@o+FvZ_bCt>@L0VCJ?L8)~YQKukjCAr3&{h5bZ94JP{smEs35(8`I7Ez_1SQ z>lP(&9Lq5wSqd1d#t)6rQT)&pN9`H`a(SL(>LL*uAmqj>=9QI zF&}%9Hau}9xkn`p^0{KK;uxbUuW~P6YbO7Nhf%`vzPz$B;&S((%`KbKDmHK7E>b8_ zaVSG=JiJg%IuavAF81)tIY2HT*-$0ZQ5?;VFGX`%Fwy9K5;M0_I1ICl@{tdlBQUMv zF=bQltO6)&vrH%|$-r;PSYbCkqc_3NGeW^P)lbPFWH*!M{(9oe_-{G$5+O%3IyuEJ z<7YuckOM!k0~0MfGjPwm^E<&aJjHW7^$a_^^E#PHJ3UZ4(Q}yE(>+zN(c<&c5)b>J zQ#$dpLoV<JYW+WCDR@uQ`R&SK@;=778E6oXFS3X z>|n7jSx?OLGCx7oFS;-HRP*|9EF=H(amOSR3tvSj7jwPLQbB1mg03$XKT9$vwD}$< zM+x%2Fs~Ld6S_V$M2R#os1uPGXe}3XFgwHPa?(K;^etPIJZzIj$>T96^How*N}mTq zAM@dOkMB5ix;C__hO|i0lrGecM9l{k!DvNO6t|?YBkwLn6EsE}^GatlOBW;pmvVJx z)bK77L&MQ4##E8qbg9lXO&RqqHf|HGZ$*WY9c6JwU-VY!)H1bDPdODN$%9MJ=yB+@ zQ1^>auWt?iu}9gCD;Bj;T~#gS4KI%lPHD9ZofK8Z)C$StD3OOw9~6gr^-sw#0=-p- zCiK4^Geb2LBx_VB*|0vG6y$juQZ35^SO->59Mnc{ z^l=xM;758YiK7kaFLNjNz_AUymBkg#Rmw7!YUW`Tv34(Q9w{;7vKaZoM zx*;H7BF@nQ) zEMe3r5g1rgZiN5SS7lcg_rO)*&T@r;^-ZbPfa4c5F}Q|d^+>Y`B0n`-6XQgsae;Le zE+yn+Q|^4PZHUvCfwi?foK}e4)__y)h4b)Xn|4eu*oI@WGzGVN!`Fx1Q9_J1)zWu> ziBDjmIDrXKfJ;_<-n@Yc$#}r?J^lf!FY`U*!R5Im=Tzm#j2l4xSY$QmlXwp(fJ?odH7UMnVb3b;#r<6 zk?3qWB25{e3EHM6gnZjpfcu$k%Zi+p*vEvKoXPlQ+qi>;8JOw#Djpi5;c(-u87$yc z8rPVOoA#n{YC^UKq0;N@EUuTNRgQ{Jmrd@d%)p;;PuUD}B+Hp}NK>xZxLF#`-gorEbt3%nRIeNLtS)ko^M3z}GYdUHN^_j_ef~z=5 z)cUt+54O09tO+@?`uR7l+PSA&qv1=Z`*c0`UDB+q-1bF!cNn=`*Vzb65}1N`h@_q_k* zy0)DA!oL~tM&!Z2!lT_ty7PNPgu0-uyQg(jnCqLr&syTp;IczJI`tPFHGGu?d8*Gl zV723hvHx~KJV#i1N3yOp`s6_`Ps%Q4Q&Z}Pm&ZK`WpT}dRxrxd)O)?j6f$=y7rDP_ym9gi{Hup%eI^ZC}p{oRA=$W0x%^nKzJ zW63T4njb#g>0B_w{knljzhB1))BWH(E#Va`-XWgZB);6UBH7Cq&Zz{=Gae~*ox)4q zzR8W%*Usff9*;`iMqfD2}9NV4X z@ADV?^Y`h>Waem6*C=8p^=GDLSidM_q5<9IW6Z@QLZt=+2K_an_thUJXutMVKLKB#D0*W4VPF33KPd3uDVpE;0fL>tfdmU0Jcux%!i5YQ zI(!K6;k;{*Dq6gF5t_!09HE6m!>Xgmkt8>=Y7(-f%91Bju6+N=u_erz8iO?nMw8~v zoHKXwe2E6<&y_)k5*2Ecx+?!uSv51-U$%$=9jV*^IUnRb@3rX7J*@#p_ob*4cWmU$zk7hi@NZpdMW z9g(*>qkV3i?gVpbAj_ab)y8ugWBldPDPao*in)l)S_ z^^u7fe#m5#PCf}`Y$1x+kxYtxwBu08?RR8UE%s-bfss9TAbI{>nPZC3g(YNv4o3CY zXcSI(-I7t>iD#aA;yERK9AP=6k7;H#$)Hs+IOdw%DcTj0Hon=EO_uejT$pEWW+TP}Ywvi!@B6(?ktz!3TRwr2o&5V@M>JxR4HWj0emi4NpoL!1H zXOM^%R_I2cmdb3i&OYnVseEa)rDAc0_GMw&!pQ$wNFX;!xC`fHX$B^X+!k;clY zxjY#;+K=%TwJfyu-ixoO((ZNNg6tNzEqB8PsBTlaI@fJg*_CPSz($D%-h$yq1+ke9 z|5V<@O_^73z8-%J@`n3jRHDC=2HaJ$%(=^xn31iDq{dCbys^wYqFkWOL$ztG&KRQ@ zq{{tGa#qMjAC2^SBVWXFPKFem)Ex;^d~k(6{{(b_<2rZoP&6mC@P1RTyDPzy78~T( zJ6~&N(Mi7zcieL=-Pf2<8`bH`CzoxMfMH(E6PXOBMr+uLeaj}WX*W&NM|@+O*bK=D)?c-c-d`!k$#*o6-JL$CvNU zd(xRhl9}f`35{mqxDPceuC&&=yy~BuK9k~zk)D(xq7M&vPQ>4?nC`uQ5B|Ns!zg@C z-<=FSOwu2Ez4_Va#CllH^R&LE#?wmLq*qOfc!l$?0U^1kcq6cfYMD$D!igc`F6sP#Y2bIx2!RRAn z`UuEC3UZKy9ApzhQOHCpQjjNEq$3sinMAT;l9a5ZB`--y;9zo-oa7{9Itj{9UL};B z423CAiORpAa+R!Xr7KVQv{%YU;gYx(P8F88ySux) zyG!Bj?u8a5EMNCbcW>|P?3q9NJI~3J&zm>mM#K~Ey`>uHOpa$0)xm)rU6;iyUlFDZ z2?`LFkxJNN=@dAzFw>`Cs0muWDa_PaW-Pw1yw!#)ZUWI`;p_r=dJ$%vB3!c$8B6(c z!$YX^T(d9jN(FY(l{_b0b1pP!gl>K)`Sf7&{<F%>H3R)CdlDajC_8fC~?NaR;0T8Qw?5QF2bh>ZA{U3NktQTjf4d8$O-$R^d^ z<({C+=0L6joF|l06qc-K_-o+%f^;;Sw{@4bs%C=}{Q4pbKUMgZ1CIuX6TL*E+NQ}e zqOXjpnNnGQo1olvaYuzkRG$i=7=%5V3bgkUX`nU}iaX_rz=pXLIg8#Jmj}~UrIm<4T+cqb znZKrz#?q@!2GGU}40~>^y+25zH{$emXJam7wb44!Oz*#sU?_%UU>D&YakI{}#Jmv? z?_%rK>|HHq8p(Rhtwm+jjOw~Wo3mkhQ!V>OgmLhNaPwB&xy?)CO7AX|<5Gi(Uy%yI zZ4hHbQg)@Citoa%*|z5?rl?tr-J$4L=2l67b{C8inO8Y);=(CTJMnnNFT5#qIHb=# zSjYSN3!S{z;;Zz8A%NK^_(Vut&!Js`Iw%v<#G!qrW==Y$Kpc79-!X@E`=-|xr#~}M zS)_+g0_%b6`~t_QfKjzIqcDN@RngkHAzeS&h+2k&7zkZ`$&ce+To-25tDYUeqdR5L z#WL)>wN=JZgKnpfI3-aN^mb zCNTARagkSH$j+hZrtbCl)ig~-^&0-oy`LJCG4!l8*2Q#lWq?X(WV>% z$+Mn7doRuCB67p|oQ}TRnMTvHZ4PWA_=ZHN#w*yUf>Nb{~ z0V{+uY@r!9Ut=OF@R81i9rPnd@og*eU4RLBQMhcH_Q)zklDRS4w*O=1c zQV(}1#JoD}d@qmC^;Cc~9a>3mSoi7j*}7ajC_uPa#*6a1z8s%iM6CX;7V;v;v*Xd!x=$d||4@^)xPq2umK z9|iv#_U%C?2g0A(G7-HVH(wcl4i;vso2v?4#MU;A*$UktHvUXqk^gwgApMFlU-yCmRz4YO<-RaLbyd;{7rQYkQa zOkrYC9vCLyF%%}@35?~HPY$LM28E{$5u}!dCqKw$>d3~L`}N@@ih*F0ogP}&}T7(`Co}1zTB=xlW_*U z&}vqU#bSp?#icl+hR5Bu#l#lGFqK7uIpUUHFx3I3;iHj|>6Wjcc&0U+174wCylA22 znAnG#KjXl=(YIJz~}&;pc!6I zVWk}L62 zuoe@c`C=Q`6Dtp*V9Ha_feF{zapvjtr0uS9l2KS*sUGR6Oqi)!qbWyt*Z?mo(jQSl zXZ|yw1Z3+Vy7073EiLySX##lZD4eM;CsC2I_;%sxm)L2QXNe}#X}727(AKe5jhZE1 z8Dwc0)SfZ9&zSo|DHSzV)I&c3hmyll)J|nNHHIF<%y#zOH z2Z1`^N2%?e7ge`eI7%pi~M0e$*U*X1iEWWRDdo6#(6>dcp+T`m)*D*%6e8_ zxjRNg038L0%cjsJv~ZI;k1Z``pROptEM>Mh-5x;<+Phe(u~-SAh=JY{Y9d36uVit*_)mKd>u7?tcLr~SWBq8M2*00XMy}d;Vda^L z7eOqTK413v^Pp#J&(XU=aY{{^F$ENibIhzig4wc}g#+)DMxu$6E*# z@m7x2n%B7|h{2!VXk8gKQ4EqQYJJU%w@I(XEJw33qz6>i^E)Exf=q?2-`^1KAwa6@oR%aOXnwY7jUcd zQE;w%g0N+v8sm{Tj&cD={YFm z8{}}(FJuB@GBQ8P*K=kTN_L`m&{q>z){EK}ut?WUyO#_2WM|N01lfRI5k*?)-|Eh7 z{N^K?=r>IDkXmTDTPBvPC=W~3E)q;+i-XsypeGt|H)YnRRY~8 z`72vswH#|;h!VnrD_rEmPUTh0+DO5GC^E3`i^5l6y8*Br8?1r^4$X`V$;=G7!wSvU zSAM1J$d~V!HCHOH?5LdVsNU#MC2T_^@WP-{Nu3N$nN*FQ#HT3koOTOS4hxO}wMpQ~ z4^GPEamwYCbyeNsPF{rjxdF>)y8|?67i_!p;eoLDbqN{Xb%dRya?OjTr5{6@qd9s| z5v!f`Tjx9KO$S>=8Srmxn+WQ4f4p@6;*H^7FL1o5)FP<96KHyiY+_@0%f$NG;y39s zZzJIE)7vNI!6Q(9GFcHi*vpJWq1V}*!q!>=+Y56^|Ay30Y14}mm6TCY9dK3-!%#|K z*BaPf#uU}$Az%Hb-_imcg!5%YRv5@R@;>t6$E&KlEA5%@=*N>ByqC{-^J$P`@8i0B zuXefxs!AqSS{y2eZZ~>ocq3_}hS{=Ofv=Ts0{w@e)`R>(wJhyNcTk>pkM6Jdx6J+( z`aY)39-@o%lSt3oh*5dx5s-nV$5^i>QNPpW5R2*%$KCMwc#nP7Sb0D{nH@;XE>HDx zw1L3O-e8QOen5z8NYJLAx`OFj z-vpy)f(wW_$oKU{#W`5}Ik@OKgz7n@={c0ExeqAw=uGpNiu2g^^SIIT_)PPcb2HND z^`Pe2ExXxWwb?y`(dnv+m#p#Gqq4WEc@~rfHl_s*#RV?=1)k^y&guC<>s1*!!*B5X3aJP4nz13zSx=nVT6xj{Sd&k8l<=i zwqFg6UJb8ajhtSMzFLh%S$k)vM8&ma`?b{Qwe;$>M3hy*X{txNGGoN`Muo*(t(BL{ zLhfsV>yJd! z-;hUpHq+|5H|CkP78JLZ?6+2;x5BqJ{?M9dR`JX!th@S6HFr&&aWD2O^7>X!M+T(T zW^dh~?A$T!+$-*U>)yg^x3~}*$pUQmZH=sIZ_8xAZ3h!=dqwx@?rlF-?;_3YqFnEO z_uJ7ab|zP>aq8O1(Jmmj-)#84!`{_8{%PtuZTExHK9$2hP0W4_@g4_N&2aRLAo`4( z?j{uKgs;#6LC?45l$H811B#q|5!6F5=EK|W{V!m{i|WOml1&2PS+1C=VZRk`?aj&T zI*GFbiI^kZn)emNH7Q}e;p6>_tG!72W44~XFtTGlL!*{WqYJ-XS?41I<`Y+?6W8mb zp=MIznORYdOurt~ZnjGnj3j(cj)aGriu-(!5%`zP>@d+4yMfxpflCJUa3Fs@7qBSZMRZ%86_Y zW&O;#1sVJm>J41%Z8!7H!ZNMt^@w@TC3^1Jl<;xf`pGOaHl8DipJFy_?k&lO?}a_L z2`eRjU-pIvXc|?)RUT?U^WOPGtJ?+PQaUOoj zp6kpUb9s^T{^s+&;>`nX&Hc2@UB`Ag{nt139p>%PPg8=*XPnO8%h?_+XwH?DpDajr zRAY%y9UqqNufBY|KD^!$Ct2U5dN6VfAa=a9tbO(|+5**Ty4>74e5ep*nZevSIj&)? zH!KPjx$^w2XEysB&+?<`>Upg3;Gyybn&eZ>_LJrHG*;|OEyaVJa+xCJkHmL6HCju4 zWByc&i6!!&x%ZfD}07&?`>0`L6(aJV9; z!{O@uflM5kR1D=A`oVAnjb@E+8vDLj8k+@%Iq$;pbWn&JLC1pmiE^G87?p}((Mq)_ z@M+3yeeq1aOto04Sa0cEvr4zw;b?v7Lc7jnIEG4p`Qn?c^-_%m;lve9oAc2OSRWpR zrpt>@cVE)lai`Z?KA${_era#85{tz$E27?%Gxwu%iGde3!&Ew#WOi_R4nzU z^@p=>An|<5Ednmi)q0aqcFOl{jLr7X7k|1o-e1C>)7e5W-1NNM9!>s?hucJscN z?l(X83>JZqzqgo#MEDge0#mL)ErD|4gBGpHn)O|nYtjxN_v}uoI=Zh^#K9{e+J(uB z{k*8iFY=X;S!KtK{9*RPhw17Ol6Lj)sz8clH#Ir1dBb>fUO?jj*OdSuf&Ukh3MaE) z`;mr*Jn@x045oq8lm%x~UHTgkF}^{a%_Lh>f;XCDNJh$Wl0#=Rglf4(I2H_uHcpC0 zQL!=!;$Fuo%$^=T@UL>ycj$b4+K^=#=44XjJ4~7|lhYj#Rg3;1MdW-K?_ub@$2F41 z9AvVjNsm7?mrCv1&$aT!V+*ZkKLfO^XIcHpeGilN)=~4qn;x)u}oWdjlU8l*mRP`M*P#-1H z7~pk;#w$=5&A-l9-K?W(R_q?5XIGevYHCruz`<)T%l*@?X(46NTp>S6%>w4aIC#-$ zBtG@nr02)6rRPgKT+W+gNOpA(@`vYCrvv;!n zB-7LL59|)}n?Q)jM4}jU^3NQWIe9I7kB-5u689Dp+ivZra|yW5X};pq&ji0kCGfX+ zmW)!retEr!_3K^}kW$&wGj!KJ_CBn3?ECo%5~(fL?-!Gkz&(CXuw~vbIve@)}VtnT>m_pk|1Xmo=YT+rJ@w#O1~N1Y*(#QrBps!O?g+^;M~!34+)}U74v8H z55C)4-6!MuSSx`zo5Obwy2WVg-?gL%UlxEs>v2kx2vzM|lA-VjSG?Cc^~! zO`E5T7_W3GK2W(USk(M=;OZ35sdv78mN5pXr|lvf>g`H&nv;fMS)c)?zL3RAJu!vH z6_r3;kbN*Wur3gKftw z{>xoZcQRq^9MWCh&(SW(HwB0ahO^R-V%*&vN-guN1ZQ;0Iu&(b54V)pF78n?wsSY3 zZwF%0-Wo;x#c4KPAK1|;;gsyoG}sq1Z&|&UdQr?0YF|#FA%_q)!N-Q*%SNZalzvO* zW{<$%w1m0BtmLUy<8ECvVDLd)3_n}U6d@kV9|<@V>ERiF4Tnz1Pu z>wRBG-tYiVrtX?41b)_oLjdizd;Lo;0{w0^)^`C*>`}%i>Ger=XOdgI5yqiCRpxMM zyf3$dE`DS&5U3w22N%vigO9azhOu+JnsAh!&sWwFwOS)yPk!uI(&Dt#<<_%ZI{p4> zlz_b=G*%^r39R27Pk1D>ioVt?r2U|`S%6cDp-7uTy5u2tPpH*hb=y-PnX|T^bPBFC zP}J`D{qZ81ubWQjUVgOtjw42JpTX`G$(ZOQO&`h~z+RoyS-x+Ei)3gTRBpZgX%`x| zOwJy3XpDdy+Z0AJICWUBF`}3nzP&M*Gw$GoL_OGoJ(WUBSS@8;h)wGcPkq(4x!+f4BW zLFS>=QIVQX*qRnEk_EQ$R?<8fBuiXbDQ0qK*bB~!Lld0#XZYuMBQK@Qf0|;>CyjP% z^fnJrWBsi|LsAfc1GT48oFsgolu5~ugCUByz5UGl#JsVCb6ClL`B&&Q6)Zy+Iph)( zw^gvKdJe`7e-5IKVxp*8?~iz@caT5E?C|W-sjMI7QKJ30hP`x1?KR$RdY!ZciShPF z^|@-e9!ZGjj__{T9}p($XlShG%0pA@#Q6)YQT*5W=vnAHiKpYDSW|QjN?*{sd z1kU%geYzjRq%XdiCYi#^cGbkAk&Q1?55XhHGsrFRnFd$3sfZJacj5dhtR6it?Yy4Z zmryfA2n3#@(p@@MO%%W541e>O2cQLuVRf!P zLIm(2s~Yf3zB$wQnlfy}Vj^x>d=wCppY}HB_~K@5<#V-WXh2t8fUtN`P=4Nn1enY^ z_WLTj<2ds}x@K{{^K{t4us@ug@eg(-aCmaktBch??^x1lhd24$k&@()Rl_Hwfs-?pEA((qlMsl#cM#j4(QYm0&nS^2+x6X>Dn z$&d)-rUjHSkh;FII*WoQjiHrvy7Yjs&{3f#brmKrJsHrDa8o_#ZhbEPp)h*fx~E_< z0TFK9kmplwVzI`Xy^bz&0fMf0;;i_O2I$;AWQ6k~e;C9yIa>M4f?hpyQZjo|eV8ZJ z`e3X0P(%ae>zYNNKlWLR4g14z&-I}gfDOyad|pBw(Zo>3y5wJadekL^HsC@A!MIHw zcy6%>WS!{!gA14fKIcsmxtB2Zs#1LvArZQPbN+npc5A2P{ zE+_ag!?uq>L5zmJ8nyte*#<2HF?cp9?TZFJc@5zP1~R4fDW* zL1Ler0oIodycN8W3*4)&X>~}19T61O6p{{^!Ir+#5t3E=9YH`+N*T&N%{*95f5CKD zu;!FxH$socPk^dFtU+Bc1+O5h2C`lstS&3RCv8ZD3uk6ibL87At8O3cRNwHB7sIO) zKq3q#&@C-QlFj5{@Ieg7Dj@xeloV=^KMUU)(IrRJ2{bq5gEEKJLxa7&l5F^!Xf zw<~hc;0?KeH82j6ags$b2Wyfd>+A|vdXwM1!U0Xil95{&7gF(j6N|cfZ7+CV7I*~> z#_m+5P4OAUB%v#ZHw!sx9=cy1iuNcl5oMxa$~Hzs*(r2cIXWcq+&?HAHZ`s=Q&ce(V%jc~ zB+r%v?&HX78lpWgma^U>0IUEn|NTKBXDZl` z7Cfnf%1 z@f}n$&ZWOEph3&;@*plG+!&0u6M^56tnLr{ zuJNJHtEN`h2l_27gMzGJZ<_ZqC zFH|aSE3u!qe@t|;pDII6in^+<=thsj)~(s9chl59a6$Xcx0W9?lg23}JxwTmo{3tm ztr`c`HI^UXg;GOn=|zrXL`O5S5R{Mtt2r&JIxY7buTovnL+djAP{CvE7Guv|ukBnd zrd;^ll;MbyRDGp4^(nJfbA^^}&3ykuH`7M@uQd}zeV+pkncpgwpS1=c77K}m#^=|% zVOQswkVjRbu6^6`x;`MNt`9f!;%FxAJ~owYVMc!Lc7Eh#mm;=m-<O+oWs911!R&o&zI){GrtR9q{OcAvo5^#XTc5V= z0ne05Y{cs0Oxprt3!Kpg2b)I3&W5K##^if!D605#nymt`T59lM<=tRKf21z>b!GTX zD+?Xuth%hvIgoxj7i*N`WxAp{NbnHK*{Hvk!~)-muZ% z1wlzHxz2>rXY2t0cYL!8-QnH7UM6sUbR@jxryq~v9}JDqzT}8wBtvp?vuc>snwqqo z5AO_fvV%kHmX?pE^+X_dIVYp7(*O=>0FVm6GVK6VSI?6Juv7t9_yc$x4g|N&2rmu< zEkibGl`PKoNR-S?5lt1|=u%;|&=~8tb)j`oA2xbFFIy3BZoK<|Jt$o@6coRYtp`lI z6`M5ph(3Hb{V}Iumu(^*p!(`ozo$sTxt+MO4=^|enC!v|QJb%h9a+@D8t=kdLRgxl z92m`5e1ZU&k3^3*Z~oCRw~jHaqe>;CHU+vXi9gN{^CAz>!YXc?4=z9p-5%b%FyKhz zsxe#4PJDdwjVmBB)48551+TNUi0Nl2Uw{s*L6*CxS`MCYdLT&TK7Z^}7-N4k5d5hi zsXw3(f)66Z5)Y1(6atylUmPNY4;7@x8-T_Oso`lB-4b0XwFJtsOj0tIc1WOces>N` z0HS{SB4IiSoE>~)08^Y+xN4=JmXCa1u3_<7EeNO_TC!5?v?}~!For$it%Yh3WA^n= z^g%R=gA*JbX@FiF93dK%=^qPqQh&Z(fWnKvhzdaJ#b1;ZAp8QM2m!DvI~T-*HZ%_6 z@`Mxf3@l?7&}K%LRI={9j@Y+}W$(vk95I6Y{qq6O|*>4^CeW)Ge9^mWPgl>2PgDh%hlQmPQuAwsSWVuI0$bJ zTrmUL&J0bb18_hKMe~GiMLp$8gEpLle)nv`pMw!iK^a9(>G@-OJ`&OAaMmAUtx9(^ zNZq0Ray|GKG^w8kBMD8H=FRXUtRIOi?GLZxlU)Xftj!bQL4xoUWXX+QNbd5nKQ1rq z5_8P&Lx9eUzf>5&BM$~{6~+>DU~y}2=n3ah2UYVYfWsI7UmCy`2Fr6CBIg7tHWncK z63BmhwDF=Ll74-zbXVSXO@nVYU}(i`(!ivY%&vnn6kwO{i}rAw6mo9;IAizY)K1FT zKyAZLcin`)evc3}-k%#lOX@G>dA*A#`L3Y~@`O_&g;3OSa?k;=%>|m3*|2#+8X5<1 z);W3b22wiN@)(B5>IBJ&!VuMg`DQNS60Z}roP|h`a2%a=`>`jMb;%>{)Q>TwPnp>< z&OP4TF>z(6OUN({>C`Dp6LqPv$V&G(KAM5z=Fk0|_<#`XX=X>j6nYjXkC$K=tB_Vh z0Mi^4=M5A!FPMba6`m)MD;Mw#GJ99gCHD;8aCV@pZTj_RRdC1EOe8YdFm}T!@nh}C z1zEHlVzjn@v&Kgop1XT#BS$XC?*Mdn#oh;P2O9;N1-aIBliBDB?m&1Dj1a2Xrf0XB zc8Et^F#KGwOFDqd3CghSoaw!#p@p_sy<&5^Fh2(H(FXCe1`4tU(6ZoA&^!t8yN8En zn|mZ!I6fHA*@>~Bn8ZOVx;W+^y05iax^KBVXj2`cJv*&Dcxjy%;}~N(o2kD*;J@+0 zS~xv#zz^(xxnd9rMm~k%HFOeo3h?uQqacMgL<^!{^>Ahl;MoPgp`NPp1}M!zNqNF? zu?7Xtc=;}`o924f)kX-XqF6e*lSXW!Xi;WX zeR^(udT)G|UVM5<^afab2St2`JaT1$z9Wvm24d02VtvPReK}u}$9sLJW__nue&vD! z1w;|w4ay``f+bX-5sd?d;eY3;gypKhNaY2ftwIa0`XiSG38KBrzd|p>2J)i?0bT+H zZlRFTg7}>R0l*-ByfDGtAhfVRfjmf-u^?>Yz(bL+jK1(RL9HPId>nK`(Am9VJ zLYfoCU(o<9bu9TmJchRetn>b&pR2Ad+3}0`W_^m>YMsK=e$)>Kxus0Be8Z_J0 zU^!c$Sn1BR(c-W(5Y6Dhyw%};vp-$w!Lrlyjia{Actj5 zE=}XoM{b7gDSKtYpB^G_fBw8d}EWd(=F44aQ4g;ixSc;QCyCv z{93@KV<99VA=0*_4y$D0Bmj?nzbc|qa#y;JuuYddDfPmT{G}JY==osx13%1RTD>pk z*g8e=GUVw+3G(b~%K-@Fw1h!;-1nqr7~EQ6WU0Ec797F=1OkEqFrNXY1*#Q!Mo)hm zwF5^-c&4-S@iKLG{S~)qoCNn;Y3^4jg0ehmVFW6ZRz=z36~&Bb4}@^ORNA4iHpU`QzA>8Mmh&Q&~katB=xT zp4qHtdn|^~TMxa9nWm4299uWc5Fpu?_X8Qu9VR=*PO3IsHmX~9W;83SdyXn>gK{@b zu2U0h#^uVULY|nr=E8VcKuZx3Ro%#INQ%YxA*M!A>w)@p?`o32O4~v(JTf{!RpJ&l zSq_M|755WJEIqm3Z5{o78*bG0thHp+jnfonxfmfyc#+tkNSgw!%J4JU8nFj`D#ljX zEAPAd>y}x>NRg_@`{^mNo4(06X5~ecKoTQ&mQ}2?bbG%IRF-rTy1v$r4gWFV?2<@S zIQ(W+nElkMD04<0_j}pak(Qfg<8E1yM&4$I$pMACi;VD7!+H>=p=Yig?s372ixINp zlK9VRw(ao|;+CaI=qa9X8N%)MliZ)7FZuK?)7EF{G1i~Y1@!$oifcXy@Kr2I_mG|B z9prRgyM)*5hQC=laB;e+$21>m9b9@IOhM%~uC^fcbUrMo@BFN$0sL-W(%X>tZE8># z3SaW(Kx*qY5Aqavyl8Z6dtAu^g}spa#M*opvK3~zbbIxEewsX~cA4YQ|A`0^ZR(Dd zyvE4+6`U$Gg5dbonS5vZ*s500p5^P5>JH?)rczKhGz%#N1lbQ5Sj2ZpaYlIv1PCGs zEC>krRtN<6hxdz({vdcv>Ib;Iyn#?OeC}W%dj3#2HiO|%+TEUX3^5ZFp6oZ1u^J}g+L%l_-LRmc{&^O@_p|UrbiAMC?foo7z`8s! zmqTQFgR#2&!9aLS;VfXisbn}dhYh7C`oTynrhqq$tQr|_Je4|uV7OYbye<6fI3?V5 z(PY9$PqIs`^2r3wj=t>9A8dsD`I`|ctR_WbFd7u$!jeG$EFlG~SGz_Y`T8QZ zV6+IsqKq3hp!@L!W$@eYPv#2cbCtR~9xqlKZFgq6JD+cM2P5A|lzX~N5#5l&7F zjAx2ghX|R3ChH#t*#RW;gQ+7&^D})(%ah}!4kPzV0a_#Y#l6(;f8qXOP6ZiT^}X0f zRq4!-5=Kbg4}P)U9~a9-*|YSh1{Dk~EdY=c;%h z_tWD%H%xV?pb5p%;#WPEfp0joXcXGUV(|NHE*ICVNLhKQ*t;AG77r8!E;d~!o6My_ z_V8EugA51?{Db9|?ETm<=FS5qUn6#j1^4yWy5=fUSyUkag1dcG1iuX3G~;|&2Vl9g z^5Zl`eYfBJ>8kEVh&(RuMoB{%zmHL-+I=6VEv@=K!Pt8FeUf#Q@qUVP#qNHZ_oV86 zM)3LaepVEY>0wS1*ZyH1NK^grO@Zg?VL|2KGFD{w2QlpKWRtx7O5^vs+di8oQg9jf`k`AU(e#tax~Qg^u|w`Y(~r2f+bx2{HDM z=x`#%ri01iB_jpP^@pNS$h}8L!EhuVht1|#eW6SsTyYqYY{TAYBCUFb!FYqk2)%~s zM3!u#9Cj+N>-pyRz1eiGhz}yMToXtx4`@yBX`+d4p-5x7C?I^Xe5q0=mYPbm0*e4j zzcGSX{)tTE-CRqHX|ly$y}}m3rathYWTVsbvuVI;bb{`x_Go420PO{vVtxvK&kIPSTe4oxva{U4Hr+L9RHmCVv)D@=%QQYUJg>lmK zXGKX`HfP0YmKA3uS?=d&rFkLr=Ve7HHs|GKB^BotRW0Y|m31S#^cPi4%QhF)ZO0WC zHC<2V7qxu=hReDk9NWwKG3v_8hAHlg%f>lrhO4GUE!(T+Rm;k&mQDAI>dZOOM*FsX zOL>R(m7GY2=JOf>`_5}=B*(7V8F|OXr|nL=o|_h1rgoUDNr!f*OeEG8ScUL>+28vchHZ< zl1gAyCDav-Cw!3l3-ra4sjOzERpN~$)0uP@@1Soioz2Cp-zDP5LYgZCCenY>Q=y$N z<&I|0mTRt9idM>PFp+?*SgbT2jL^(TrVUVm>Jg(&pfXPri4`+x$Ii)}yWGW(3)4>^YRiLG}B6tI|GuA!p$0aMwS3W*)O-!D3n zzYa+d@;=?`q1NRmPIz6X(WQ@_dRP10br@zTXz%CdgpWF(B1R3tze!q#QX=o zq&l%4%*#%od&%MzpDxK5Iz1)qW`EQJ8=3$Z=(w1@G`e5)i03KNIMi7Kep#v!U&)^7pt#^OkEpb#j?DR1jcBpCl#P0VHoH9*4LK;f&sbv|7NbCzp_u6ii-fsqx`n8Rw&BC<_K%N}Lg6d>IY}apcHa(_!4l{%Oyx@}yQE46G0dTZa&kX9Q(QW5Bs^LFd4PF&)qk1CS` zK$y*ut;yEfonH1wsE-P5b$f#dN2G>~T+=iiUWAD6E?bNTlM3@_d7SZ$*i(7w=guJQ zcOk8^VjP9(j^>M%Ihi+`1@5!ML=|beqa=<0DsfoCpm193yHRIYFE>$V+D|-C zXF2z9(qw;baHGlbDrut0^~-pm$qR_#q|FBhx`7I4uExu9tuStn3!@wO=!)q-MOYWd zJ4C3JLPGxY|L1_@c#j0Je^g6#q{%@Vi1Y?+brFN1Xk_eJw5$cgVOZFPo3w0ZQZb~& zmR-PIG)N6-8hmo&;eE+e7`>$e_(o&J*e|R$m#5C8xPef^nGyyUFAviuZ|xo5&2kx0 zpYPS7q&|Sa*1RByCoHsof0_*cc$zAt*fj8&oMNZJf7PCFTJZyQ1yXdHr4KhJz-Jmml;&4nzjVF+4R6(NW=jcS7?9LIh(c(2|Rh<>;7((rc}1 z{A)7*JAnU6<{5u)hK(@;;E?{7z$8L7KmN1ax5INT{Eq~NQ7G~iw_N1`4x(6!22;0% zQC9R=A%WXbE|?G9Upbdq<`0aXOPNx|K}etzlSajMEF0zR<|okua-sYMh=d62OEi2ym)jh{B2y zlmANHMG4LnlCc!(A&k}uc@wGR`X7nfN6?D@3TC-PwPPSu68xemY`o%N9HGDnWk)WD(0({=N!fk`W6SA& zBVp{qb;NtMl3Hd;rj zMPLIeOOJ`LDU7w@-!F%0LOL(2$oY0&UitA~sr~QxnEod|^7`mu%4iLM5c%);K+#GE z*6$C6;Zf;r>adwfGNSNBbisc+5M`uLS7SUwKa%DSWz1&>Sx`*I5+XR+U^}agMeva6 zF*Z#cl;+}c=yB>gSxc5GAc!xeaoUKbqLynl)1!UU2+%=aMjX+k9}Xp+b&47Ee*5Z1$O}tuPrY|HC6hfs!?_@L(+kTF1V41YeuCZDWJ>|xJ z*sFTu$&Iv5kvUJ}n$fhDKmj=fi|&dXp>83!jwiN06YleP-QlD8 z*+chSv6;tq-2iGldjS+KX?boR5?=Dd=?rP}BbjX4$RlBrfF>c_4QXT%WPxpk{{I`b zQ>ypFnBlqg3qtiJsjJ<=>rTna9;HC&v~Lm^gdp@$j2DxYq-DXhOr)Etq2s05g`}70 zl@HM!6HJv2hi98~l&6sRhJ;gT`vW?T^0csRPLmw2+G!!av|&#bLQIw8WCgs^ofRl^ z6O0~ zlDaAMjf*-f^31G;#+mc1nneP6+vdUjh%2`Zf==6-8S#JTH%f@Ze?aOVm9rBW4kHSJ za1`(^|9!T?qGp~}Z#Ei@Ar!F)|DA#ysvMxlFKH}463v3J=&gxvHk3vRyN@i(UMear z@cHS1t}ae72NMCFLeJ?`wFF3pN`&~iLaGu6Mbq9}6SPvTlPC-;zk8}vXIbu`_%oSt zqsV+RVW^F!#-Pokc;s_M%Gqk8N@dey$8(KD9~C+rIDGYDH#2%rI3@!3`&hgrOJs0` zSN-gaJ6-5U#g3-4g);R@!~dujCvy}#Tdp?RTrak#J6msd`ht*1l)C<()#ATG>Z4H8 zbJ@;h?gx9$-#;G@_D7Z7-~Lqp`K_(#4}~F>_f>&-%qS3X`yEpELhvSE07~$=!Dy(w zWd4LMWqDuVLZpqYQ7yHB#4d}@dSr1By9JRNDtACof8E`FG|L2VnV$FQrGP~L?(`r| zlmKrk4hY3ss2l={KaA7B8o&U8;U9`(OIJAxe>8C%;$PKz~`wA>6-`Lb6OiCae|<5R~jbQCL6^%tZn{(=+=7Clmxka$~&awGX4Q6dz-&Os_kEs6fYzv1Rccoeh%z7hej6IB$om|C*ayCRc z`ak=RMw_jP=J)>NeQ-f6-%_>K2wJH4H2K%y!s%clTfVhstMh$u@%R429~$ZJ{YMxk zgW*(L{lRD)g?x@ed&ALW8i(!nRD0vetTRn`4(9?|(?XeQWAOWZ+xbeVR6!3W;*)J$ zx&B5^H~JH?R;Rinr)1X)G3Rh115FHD(*4QI4PKzqZ?BQ9dk z!KTQK&!IBC*-x)`8@lZw#8rQOM1sCw?8KIge_<0tkp$zI>S*i)z%Sz>5>&qQqd}lS zIR%iED_|M2TJU0-1ZxPInmA>F+Q>pbN@H!(lgEsaMNofBEr=ijP@vn{a>7tVq0Z25 zit}s(rKBE@fTFRIP!Qo#xLD5^OP%SU z@n3B?sJ>8?vkL3I^~A^+jhGY1ryo~491lSZ%D0xiKkAPUp`N$1ZrlZ?3+O&6@P1b+ z%cBfM+{9zVA}CSeqR*zSM_8)VPHsT{40kq`&-AVcbhc!!oRO%N0!!#_soThHeQfZP zb+w{Xc;lOp&gd)wgg>A7vjxB;$dGt-ID4hegeTl@G|qklpkBX?()U3=JvHGD!M~*Z1dHIo>5n`{$a*vX`mLhGSTWvpY(sx_7-kYw*9;BfWRaros!Z> zOFMMK&`1eL3Me5R4&B{d(g;H+jdV*05(-FngOnh9p67jj`+e8i>-g<;9DD6QVdlQ? z>pHLV{9NbvCNyTY#f!Q68mR>YldG6yXzZoHJd&bZq%1L* z_${ZDv-DNUFdsQ()$_*4#fXoL2JtVaI(kKiCg$T_ttIyE{^Bxj_I#2nXy0hH^ciow zWS@f&wGv|U;i2Rxxj72`0Rvx#$k%NQ#_$u#_B7Yqj7dL>I;?6w|AEl|ojP{=se18S z)z4E2sF=`PSA+dif0gTxulwI*dHVkTjdCdMje4M-{k`$D&CI0IAFqA?cxU=V($R;^ z!M!t;?b-cf&ucNaueo11o~SNYd+#3pB#V1;|Md6Gf2a)BWh54)!ZpzgP14f`Go$*A}Ce*B*+My3XNNW*Z}G^Uwj zw7;dwQUkC5Z!W-Gq!A)qI(KiJak4@T!IOPeyA!qL&GAO=dbhPk=C666(il*29%*bU zUni+MJ)?teP?{}wFXZ_iJ_eDt??ex|N)@jR#XIWSZU%nelgR&Ea5@1p7_0!+f4{19 z4MD&ldT|5vf)f^c=(~Dut0u*6PwNLE*)13d44r7Y5I)1 zep3z8A?^s?JbgT-%lAyWe*27`B%ijRnC*tw1`#BY;r;$JIbW@usp#wbz!b}|K*Lta za~V{HL6L??j;>bgzC+O5>N|uIpmUGk-~{=%hS>xuS7wT)iwi_`iLNE`S&Y zH=4EkccR>77DxLb022vG5%d?PKxbyFaCLitEjlwR$kQQ}Q8$(=E*gr}35+nl-hQtV zt3&&tO7XP#ON@>+rGQI)X@9mTHtDI-v<3pxF#KVP$W)wGp^n~%V9UB??O1y~|B0s4 ziiG$|0JZM0)SN)%L^LhQ_F4CQ#6&)ZiArawPLT7_S1X?+wyvfLrbC*!MmjTFf8eZN zbLf0$j~xk-Z^kAU#^5XFCz2TyE|y<>)!h4GqHh&Sa?z69(YwfOyr82_viy{99pPs1 zW@&CtXkDzTZfx`FyDO0`UDz96-yZ}GX5B$IXHOG~UW|uI_mObs0Ng5{-Ak{^6TzI$ zGk$(1nlVrmUq*~!0JB=P+Hd-}A$8wB-{U#`sq+202;arX50U!AJSQ6n+YB|8nx+8F znhz8Uz3{`iPD=Ng=u9&-21UGm6hMNJx)_Eux10=jsAVNEQ%epj^o6JitiGKp_-5|Q zFHJhio{cp$#J&SwFEnSlC}VQ_11DNZh)XD4PgD~vCro~zE4-1ahl$*XGJd@?p283! zQk?LD&t@|$=)+Eisy4Sx5;&4$Mt4X}E$f-0%GGUOWxsvuvrgUumZwp>0()8JwK_}G8%;bm!885A_ z9Tq#SXRL0b%#caOujS$e-j+%Ld!@K+p4WYbf~%_e>KgLFIB(6q3XZ~Xg7iK)&gQ5< z3j=UI6qz)NK`HrqXOCV41b_?8b+353GO-E-S5#(sms7mJ!F+F7lDD!_32Q9*CkQgd zf^hF(T;A`qWw5SN33Me4os4@?KQrw-&$+R}kOi%==aF1O! zZA4oYoRln)i2#}&6u9MVj_H3`i^{-OXL+-5ab1YrSYNX(>}R*SUzr8m4f`OqdHsv@ zp}ORW+k_3p7BidX#JtAxxyed|Boa;YD<@ zSP899lGk+MyISW)3S};N`Nfz=8)Yxwgf90E|84%p<50}c(EM%wdQeZVzhJK3AdhII zNj6KhuN`2HnhqiT4})=Q0aH3oR1se-4nYw zczWb+Jk7q3NIpe*SNqOJ#C7>ZJsn8tMEkdu2$V|uN`(CEn^gLG4MrPNPSiEVoGL?odI)e}tQpMZdH3 zKmXiW%+!Cc8*~BxdJF&BNdH%9^M8d#3OGIuI1pqSpsdQPfxY;z(CDAE86E_o$>d9a zl&+YhCV@Ne-3RXO>y6MLv~iHe}4Yg zq0M}$Jv@W-pF^87rIacK{O91m4sFh;;pB3rebv8hfP&Z9F`l^f)2Nqd8{oGE`%KE` znZIm+H)EB~M{akmf7t+A5d56KL!&GgL-pq#=YIi6Tb{``rhPyD29RD-*q>?^y7ME!;hGVluN;X+EJ{C2qvPN7 zh-7Fv3XNElVD~6FIb*_+87kn2t^8o?zcwOq%u@It_ye_qc=^cr!f5H9$oJ{iqU6QV zp%&pK`Jtj@rP1oAWo2b0?4;!>xfN){Li)aMR|Tty5{+2g$d>0>-@LT0?!<|js&*DK zuS5+#rg~T$B~*b%EL_$(ik=91J2cE$b702F4aQPDnOf%|$rS^xF*M!HS)^=7um;q_L2828Qg`?S|LJ7uNZH{%tJhc|nu z0q)=X4YRL*?^pe-{(abXdHDON6By@pSW)?4OlS~^smwX(@F4bhLgC5X`LzBx-bs07 zkT~meIHL2>7o#VCuGZ7u{MnoK&Clf8(#Pd0qAp^%h5LF-Sp}lc>%T~2Odw+ovS#xA04PupgC|WBu z`mu=S+>=4{Q!TFhL=esP@iOsb0Ui~EF-%|F^g#iu+?G`>4K#R_bSPYo{qQ)E{vy*jWKAjcA)@Qmf_TF^oI>g|4QtYbqDEml5*@b+Y!nE)K`!VE}K4wCbcb@tP_ zEn>nK8G2@#5IIv;NUfkW{1ZFD#l1J1FbN0|GcEuInJo$32scx1_K*vE0x&6^Fpbw= z5>p=sk&O70Q$Ep;V>eYF~o!?Q^ww*Y!*HTZ6^GTvcaqy%8(Ocint37`$u>I=P z@4&0A@fAc*e#C$&_K2 z)O?&8^)kU7q8EcaA!_Cm!vpQXFs_HkA+GmxjE@$sIv)lmKwn_V;NhBCn1-nsj~tMo z-eFf+g2f(y$>G=&G1XX1$6;?3Q)y@$fLzkYiO{xygc4j?n={QA82L)5h;f*Xk>)r5 zg%!XzrpLZ%6Zl2~W_Vk4mAsUQFIR_JM6+Dg$Rls-5vE=B z`dw{2ut@Jy-RvRbmj@Dm(G12r4!n<2EiR7R%2ub7Q6JndGdufaZprk-69bCmk*Ff< z82pByex)e)bW}=Lw&IPUtj8^GhBvw0&$fvKJ=r5@y+-ss zFr0{VVtq;YB0kh)N7Y{Idj<`V)Qq+UfU{vDg{l0f9;3u4kaN8j=oBtTv=ab@(JeEB z%mPKSGee4u^z3?^f#A#_DWQ_+*fuOg?7oVb@#ci6ACpdb0fE zT#O_*@-4Y{=#};x$!@AaagWzD2ZQxyRuGZjUkIX}jJM#wRBz5uK_ZVBrJCxcT;FA_ zkX^^)uwHyQVlrNIv1FF({iuG~@**y$P#egXxZIr;wdmOyF2@2Wh-UfHiE(Y=m8s3nyrSm z{hes9p%16Ts#rjv%$pnfH$f9QW`%n;8n<==08H;l2aw>f@vTkmoM|Dj2ZPw1@gJ@Pn%VzfWdmrE_pfZ=v86t*GKVX} z-z4w9*(9};oOOo=CY1W8tiNQY@?UI{ViJzpuRS1!_o_RbNr?^^@akaVi{`(xff+hp z4z;Mp{KssA=6!I!RWKh#21%+~O2=uJ&or(Il_nzAWpxR6>P4z*@n& z_Zg6eVV?Ls7B9r-D3iq*K6bzUy@Hh`)yHmF8+qPZNZL4vcIe(mnZeco8Qb08SK|CF zdtZ>ZhW87$B*b8O7Eyl$^{`_)yI;z@{IfYIhk2S1=YP9Kz1Jv5)35ID9i2z_TX9gX zBLR@$w9dH3+E37Z>~^B^{x{S7fT9au^zYx6Tt-*$E%|oin{imVQ*(*Dl1#0RgL@|4#TN2>qd#K-y zc6P_|)>99!5r)L-+`v&5$@?M1>lt$rTt{0Pv@@eG+LQW+e^KE2Y8)*M3-7CB=;1dS zZ>p1$22@|-C^Sw!z2T?eQIn^UB%I3peqJK{#ZGmnbSn3TxD;P4^ch)%CPv*`5=FHN zt+bYD4dGwqh?rM2pw5Ug!(SB!U)W*Lf^XH{zsf_F^Ys~}X6iD3RoQY?!oLpB+_hKZ zX@_uNEK|<3JnXD?CsCw7_MYuH{Z-?S>tKqZV$elNiV72SFe0;``N&85p%A(z95VbR zPr49K`mWsC$9sPC^+ml97ZwxTXiU)MIFjYom~04aNFI3cQBVyV!%W3!{{Cxf-6~d* z*oXA*V|LDUC^>8lgtO7al0{P=wj+&jZS?voX?EKJ*DL;A5f03!O@nUL)_XjL2Y-@@ z(jBYa2kiPxU)45dRu&3J`53Qy&z9!+)o9dn{9F)vnQkKcWHZy*d>H!rvGi!gr+iZ?pEo9vZ~($fLtit2TVX`}0p#VCf- z{OXcR_t&)uki%j#)k*>T@r&oGMT=0~OmxS~ut8$Bt08;WSO)yWM?O*$@07^$s|<8BCTxEnhHxPU7AzkhyCeZY3XwdJPLRN@8?@pLsj zkp5FMBWyJw{#gAaQbU|_64liIbnGNnU!0oavT0D^wX;ib_B!kRPhqjL1lY=}Pb*U? zPdA*rqZ91c*4f6J`{rw5IlmWHyW_9M-Nx`TTrBE&whnr>OtisK)ax>jyeEndT^((M zc13}_wq4s>!}D*uX}3gX+-PH*q9r!=3Hs-?JM_Q0m~1B6w**H_o-{!H4m1Wtmc(dr zUH1Lf=_UJZcn_SKWbjH{ZQc%){<&h zOue*XCl}D=kDv2yY{UOtSde`dx?S2kCwh4mk|v#e=6L!P|N7FGoW;c(g@nx^@ve{r zO-L+)0Ahmxylv;W*>^j$-V%NO%D`u70?6x4d!hl?OQ63*De@00kaI4O`znxU8~+S_ z``RFgs|-kE<3_Y)Pc;}IDu_7PlA&i6VMI?RGDAjR`YO#idz%HRZwK;U1#5W*(WC`# zp>u-9my(K(@T-8?-e(L~_8m^aDrG+FTh402Awt5=ugXG&o1E7>eLIfrCAPIqwnNC} zM6%7msc^9GU>LaqUZ8Mzut9jJXLz_l_;(a6LNR>h-U-M-9+F5Nk<1#D!WzLZ9Ff`- zkvSKUwvF#WfLACSS=a=#Vu_57kF2-?Re`|OSCOc2gTggngF%$P6V`~0TT4?^+gwz~ zRa6@}?g${d?J7KPFk+xA;$d3!Xn6FPFupfDvMAj7eOctpU}PL1>brsN3vAu^b)96! z&<;AF3!VRjN1*Clr~rA$E}EVV_wiS7ZsZB=ObtmJaGKTkoqem4ux9^q8|dN$-SiA) zObb1j3*7gNSHFrSA@e)qi91&evn~lSGSK!2_mgu|O98q})O?n)zrE1d4;JkYTPT6wexQ)N4LLx9DUaA@5frRV>g4jgx z@vh^!DH14!6TCv>cp9Z{K_Xqt&;lo{yyFDA9iOtNi7af%2jqBV2%rO<)5>um8$}qU zK2&Wd*^V^D*wc^9O6@87BivYq;dEdk*b zSDP9a&xDMxhq&;7y_?fowtOXl>91JRStx>FL#d8K=`V%D46f3jv1ZJ?Pe2Fl;me7} z*AP}4HohiYN&Qf^tqg5YW}zx)k2O;A8Ynd~?Srh@p3}~Y zvYO&SniIf&GZ+E^jO@ftK89K3W4m$#ic#tXq$es@8XU6-0@>tc1_%~%i)B})S zaG@4EjFB=U*dy=i{#y8VbDCmb;n^|NBL0CD3cMHrRn3RF83LQUK(+vw#RO=j6OY>( z&w>to)(P`BgDO@8`n9}QYe^<)gdiyM1}J<=S>;&XuQ&iSL%Ff`K)HanNk(JGnWv#=N z#xv4~Va3L5IX%11=Wu8$5|2n9qQ-+)M1VbLhW~1!q6PtN&WCAsf{6w|R%UEl2#6g4 zcH41=VNDA0By~1&&*&SCLk67@R<{yB@b|I8M_>XJC~2038*Idov|AZdBpQk%_-iy zGh<7+i~*X2P%6A6QD7eto}8~^Qb3P^{$L2e3WwtlEn^wRL#F6(v=BHdbfAIb5(^}@ zCLDH<4^lwjXgcA{(-olDLr8D33g^90<2!7G;Bg`4q?4$3!b&L%WYj0O-eWD2P@5J$lhw*p{ZO z^&P`e9wW1!(^2u~(4ZkFU^hX~Ewm$=qk}OkzS=TNTJwwGZaJ!d;pt~%Q@ zk{|hWAzozIX{@wZ}qbvO8 zohyZ&sR8<`Mi0HOdpFqYu|xYG9s+#vAlZdh1T)v7JaJ&=b0 zX~6oT&vKtuwfSdftu?z(x7MoL5`4BpUpyY9x6gFrOiCEiO;{+Sb?8a=84}q_d)GMh z%9Fr+C@@UbSsqr$Wjw&_GjN+ctnbaQhe4jaFs#XvSfWs1Fd7KbOx*VzAxax5qAosF z%9H*zn8`9^!O^$>dq6LJlvp@`bQ=lg9V7Mx;<64@A$tiZ3S(3q%V49gi4Z_IfMku( zcHxWUR_&%R{;jwR!(l)vyj{RU(EhO3>^S_=6?jkRrkm~hC#s9i@ylHH zmkR2>s_agYtt37_XU=lh2fX-LCj)IN6H^Px#zq~yg4$Aw8D{*tdvF$xfHoyL_lznZ zWVQW^=%WHXzClQQ}!8!?OVO1oo>% zw~*s@JK>HlE{xqRjK?^Cl~|lMS)BQ>Fq^aZy?yaJ7p&x7c=1m#!~%h{Cb4AYw6tx4 zgO$Iu-@bJCVd*_TIEes^GI$xL7&#jc``YyLRw8nz6AwVUj48Q{CAl1JunfvwhIA|g z@LaHBUA{X(-*+~bnGK2D_7%bMo>L;S=|sCCd&)YS-xEOcI>Fh?VR6fth1lRYvzTZk zD9jARhn`mhSQCl`3CFH+cdT(8u2!W-deGsBNv_Mr#>o4xD=tNT2Z1f}fhcltQfFAQ z+3Es0gg6%RwQ5SsdtOM;sJdM$F{yAb3PNuRVKiNRY>Go9_p^F#ts;HRsT$oBzpi4s z6~Bz-k6KrFz2&>KN_reJ2qn=k>fB+Y;Yn1oRSZzCph>jd62QZAAP(wUl!va_|uwX zI~u9ywxo9|arn;QaMS_8vaAC}VT4Q_r^`XD; zY5ifCkLPD?)4flB4kKufTJieZsK4^w{~A;xTVQ41d^BHYIo6yWi{pU`^JfL4%#MTe zk8#J36_3Ed$m9Ba$XNBkDGiwZJ}eZ0y=|&jW1y$~WMh9R4E|>OBkhHc!Jcj>NT=ge zedCDh-HOPE6?;Ex7YgkV0`L$4vSv}Z^m@MBX~zeN!~7>~oEuub46a6=hrEELA+Dg~ z#}NFJL^|+u{0*Zg$GT>qP02%p7kcZlhmY|ua^GF#AH8;2K3up0qf6Pvk4_zrF3fM! zN!SoCXh-9cF3&P`$~&9mvWsm)O zcXg#+1DSpSE>k?vuE20(l5S<$lW_#YI;k3HY0A->G-Xu`sgS_M=TE~ z9`zf=18qeehsRy@YTWiA?*Yz3NtG&vmR*U&c8ScPsjSYcmS786^>`Oqm%;dlGTIg5 zt6730jNPGlZ0gxp5lO=uTqYe3*NRai2toTq_LO>J_S|y4JIh}cGZRK~el)nL0_i*@ z-Qk2{?ws>F6?qUrqZ!pbJsXpDQAPs2eSKzs}!5hh6HZMNi?kkn4bdu7`chH)MZb4siR*K zifq7)LQ<}C`ISYBGwamZ_sbZNVn77*%V+a@Xe`XWRj zqhDXUv4ttn24kxX2g(`rm=94~6=x+%s3YWeZBr+taiiQ(cJ}91qPrD7IzKEy$Hhj< zK>|;$QuM8xH(XLqnRV2A6^j?OovyKt&WX9Lw(vF=TsFZGqRS? zFPfSWTIrU&EN(P4@Zok+)s}~CBv2c!zUTdu8*0plNi6=UPb$x3BSDaRNwj~{`hCJ0 zs?U9T-?FNEci?Cyw$*L+McAU7`6hP-sSwOOgr(g^gxsl%H%R-Kt0x#Hs~qhJ#yuc6 z5_K623n@Mg=MCeHQ4k#vW}T1$`kc!tnV_%(j(6p6ab+aAQrJ5@CBzc)_$$D&sT=XLcp4Y zeGJ#VZ~Q9Wcb!>S^2hOD7Fl!1z?tOL!YYvhYahpM8j;pIr+Eq?$nq4(Qi?7`E=2ap zye`I8Y?8IBn=8N!kwX$>u(AYoFR>p2z&!$6t|n*SXN9(F<5mXWj=*!S$86Y0QYWKr zWEl+&KzV#l7Lvd0$=Fsm8gt!P@hs@EEE{?Y^084b8X&U!YUj|bOc6kvd{%Bpc zM80qxOD3`2UX5&97Nh!nk`R|*3Ui*Q7kjj1t=q|a;n89Xlq-#2o0RoFx%l-WGpGr8 zi77VKV!^7bOoGQqAQB1iiY9s#v=PxG5=|tMAFO7G8HMF9BjbE5`|b}v40D^uAod=M zfm<>mDaxuYDRd&Jzc)h)5t)OVYoh5vTC5zPFd2IAJ^3XHxsp4-jZxfeRxYPCkJzEUGS6DYEK*>pI# z0s~W=uILUrV?{npm9f0VoQ=SiqoD{h@fLv5<#!sO?`6`Zp39b%G2k%P0-aN}qj*S| zMGLf)wYiH3p6b$w`?ctIT*R!1*{ zOBXYZ?jrJL8$4ou!>F>$y&qG_H_x%cnen=&URbk_L`dh;7Y^$voegWoCJ3d}Djv%! zJhPv$5Y|pG=aqY{MpxL{96SqyMkg7xmOd#8}7-vuJyMOu7@h z>ZUaVUkYHEyhlNy@B)hqaz0D(Jp69{wMSpwoLFFIez@QpFNp-Oc66aIOUfiit`4z~ zY5|SH>Ffp?>W%kK|7qpkcpFbL4vM=c`l3A< zSF>D+r4#DG+P3w|na7DveVXut>qt@e1We@0FMsx&mpvAsO#X(q`ZUKr#?g0JV_UCO zvfnlL+AvH(-0C%g{S})NZ`8Wz^+PO!V|acRs*gRKP{gUwS+U@ec5pG;L&mWgiJDUh z@@k!y<;rkgC89`}BJ+pKW?6A4Q@rFD`_z6A(^L48Z+CvCG1Z1ELS-r#VR#jt6i>{Dr~Kbg?`- zWKLJ0y?Y~748jXivm!Gsd{LMg4kMjNp5xar>n09^KdAR8B)Y#9fRU!7T$sw+k6q|e z0qNUv%t{H=n@&F-`iI*!DeSPi^oY(#GQe}(_FpHa-3AW{%eRGbE>kQ;zv*9U43*Tj zV30(y2=S-*6C6g`UAAqJl3+i^+3wwN8YiOcxp4eY&O<(&Cg_sK*zdm$vq)NLSru zxYYaR^X%Qt%iYT^+&@YF-9%dHg%3-=FmF_r4JW}IsIV33keWT|>Vbq=UTMJc;3-Dr zlqi>KJQm2AA<_uD(6im__<=I~+4o9`i>!J=<);;upNVy(n7Z(8jYPWZD10hQOeP36 z7~vr&1PY)8O*()g;zL7W@ii*{j!{^7gguS`O2}J#{5t}++sO=)(%1f6N8jc4uxKIb zGs$!}mqQ#WRux$lHp5#obx>4aVVnIbL2X&ECOP)~GvOdmMN_Ib_Ra{E2RJ0cGyEHp z;CSuv2|uLvBuE;N!N%0vTp@kpTxtz!=3MWVe=B>sj8}2h4S3Md-I8&h2|o}cx6vY( ze~2v&7pmtA)Hse9=l%FLqi3hS=T3Ls! zxU5ogqbXG+Lw!bSJe>a)zf~q)l?k8@c!oL)a&*OueV+V1BTlDR4@BsK?u=$-wVqD_v9!uajM&*oGu>u9(G=9X<>!@&M9x*C2XyNBHM=nS2kHrp;x9Vgqs@p`ez2s?pO);ARxuDe>D?9w2 zI*Q7^D?T`{i#0mrZJJVRg^e#bOD04?F$hW$}f9GA_^l`Z510B04n)}xyj|l`AQuQk!XeVM-%!>1HiWDRa*5X&;5Dy{1Q6iipuQhFd1i)n5I$X?XU13a~I|T2y)bn#; z{yT;biUWeWQ!MTEPjz)j_8}rM0}nq;afYw~7?BEB2!a&;BjkjPK!%)v&Z+FQtjV;d zm5u^UM(y0VsMSXls`T1LG@+|pE#zYn-8aLJx@QKMn1kO;zUi9&`euYZW2T#k`%tTn zb&{HJvbOBW2~1bk?W?uPQ`?joI}%;Wy%0tM>M?qM0|ix}#XL&LLmz1@&9n zIAjGTvKjPUxQ5-iW?fTe7onhk-@E|;USPBV(*6fx2rHlM?=HuXDiF#W-R0P)1m=46 zJ{{_ELG)-(>y)zJ(W8>I+pdkBpo&*OkB$#?3? zH~fs+QRG<2)+D+?TfPL&GmXjbyzv`TE8PYN-{aypmwniV0P8a$%=o{6rf8D4Kz}FaSyB@0deNxXnGSN7) z*$p=Px#TNydDPp^av#c_wy_hloa3c|?=RtVcoI|)z2jai2Wf-WyZd=4?Pru=t-YiARj9!=&Nm| zDAGqT<9LM8^U?wte5kzKmsPn^JuPDT7RlG*9=hm$k7cYaTu;o1xdPkaP+&4kY4HgS zr5Kp9A<)HL5t>PiON5)zSc-Pm8Mb=QH!~bccC53UTF_Ll^Ndm{+&x!`D9y-wr!b%)Q ziYw4XobUAqbRF&fr#UcmzqvyXT2rrv#s7wXkwiKB6OG{0 zs`Sh5o7bJ6$CRC1WDlv*6ozOxHu(Olt&X=hfxrpf?i&Py?vEQqO}j63${-VJr`Y{EY(%!rBgL2-*tQQVkF4kUTrzdo`ARC*O;7dah7^3 zRHi9-BPwP+8PO>9$e%&RkAE{RQ>Ku^cHk4=gO5CXwt*#O~fW~czgDhH%LLUXLbT1yD!diaQ6WrTxg*AL35ZfX$ z?|aMANk3B^p`LBRCS2Ra>RseXELJ#n!4ee05u!J0*4MBtQ2v(J z`NjLig9>uF2e~{k52%YU+7qG$`A{+R)9Jl)n_?Hm31QyTOXTfc5&FlqanElVT^3js z$3Hl_-y5wT1YSm}d!Hud!-`qOo`)l%Pm{}TEsyZ76rU-76{ZUK0>@EOd}E29pf_rH zWJ(xodUKlA2`k|VIRTqfo~3ucT|eAp5&I-}n$kCvz{#;AWTZY3J-bfxBw^@_8EGNK zBFu&-g+i9((?LcF=6V3$S$|`OQ^FFGfu)aPOy_-I?iCCu5}|Pa**e$N!XdagAzB)# zL4KZ(({93LT00TScV2)O!z#tI$mHo-W}_DUUu5 z(njMhT292p26wjfdI{gEOB#wf+f7t#l=ZSR1s`gNDzeTD&wQ%3{_w!dh-P;pMy>-t zt^0?yWRTKm`>JbR{Rkb+@5i-Bc2${Q&PMdR1OvRouAbh%DxZk4Ja@*Np*pHGS%lad zT#L)f?K@-*bBoAB4WHB{e(00npc)%-2_(*BcIXw|W5vBs2m?5%U{m@^eHX36h#8PM zFfG>%w?}e1hVu=4(TnH{Nvmy@h{J!R2NII~w#-Udm`6M{(KC(Uz z6XR59qrB?eQ!9nf7t;5i9(1)QIXx{2fT;VflFTBU1=y+0AqwfSamy=7&tdb!q))Sl zKq1TqD(WVoAkIZc( zv_)zX@2Z8f2&0Xhyxe0JXqE^#H+yJtw5J4l|e|(n*fM)a3R6_?NEvG0y_uUB9Z~br>c|r z*|++78DmzBtrWONyf5Tr5@|0EZ>wVL6n#h*@9C@sTX-Wis=jSZZrkO)k%G9c2ND&P zVe>OdI^!1oSWR?W5A&Hlj2Rc|+OGBoHi-Bm(%_M60*<-E zF==srs7SR`Gy{JTrEY(z#NDgCD4(LvW)9KVxau|ArAYcNNt~&OMckL!M(!oKIK0wb zus64b#NQ_5`O&p)N>_zc-&y52N_Zg_W@~~igE%xFBQ#bM8S{oZ6QeJOC-~}&4tI-v z2BH{`Le~9`81-u#W``q;-WE}Cv-I0bNSJ65qLw_%xoL zTSLG(srkf$Vn#wdzF(|80^|2GA(Fg1U;aL?l+gc;j`vvfwmhq+O7!{&9%ZjV=&8@x zmt=|iv_{a?J6zmR#CoPjFWiq|=DEVE_m5e>nKR2eB6FMu*e)6D3@Euls!HYlZUyk_ zUKct+pcurZOZoD34Y%jg}VFwh>7JP;c(tLm0l}jfo&BbbWZiw{Lx&H{8NkBOL|J@KzT*D zj;E9gIbPsJ@Cq@wj7J=U6=@b45>rC^y*9)_JD9CWg1cWzMbX}JPOY23(bhIZ|4Lcp zL6~fKAQrI|cSG=2YS`l2*J;IKcK76g&x8Z#HI0?~jKEX?<77|0q`>x{f1P@zcX`{$V@UYQO~nH9~MgD5SH?rYk@=i*MUdfqWob=QU7T!00YgfG zH2eDw6hy%(Z)vCC5j%{Yz0khLIYuPTLWG9(RRlX_?$77YFghUauNT6vip+G2%FHw- zca&JrRS0g-a1;=pSt4VYr$|}qj|3@Z=Bf<)nTSM+;-rC;5Go$UUCTL*$6$pCO$;)p z1|+n70(yE+hktck7E4(k6$x!XLMC_eaY?kKBOwY%2r&fhKb02VjXULDZfcKtaw`odGb6Y58_&d8Pr(<{Dy!(9CIK zv#uzojjC2Mz%Rn)^kS>u?iIbHi)0-sov@*tcMoXxsp$&1{~wiAqRUR#EBg^u9EOA- z=LU`+&>Yg7^{v`^8hmUD;p&t8EA%xl(}<9pn+RHv%e)$*(oC&tQ=}#GO5# z1XN+&SY@WcM)$THS8Uzawju;wed1OcyJRt_xM?&XC}1Vq^`ubc6xJC)!hJ);oz-j* z-Js{&(7xVm`X$fRSF;>jZgT@|Lc%t&WeF=~$xu_6d_HwsHL)txs;+*kyrq1sW$hrf zkGV$45Y7!PbL}blhu3yl2kQs4Ch@io@OE(9)uw)_wXoB)4*-kZz_h+pHmujQuh%p< zSDmgmjJG#BAJlE_6C~fQw~@fwecLPMFBGYw*>rfCnCNnVUo>g~otFq`Z&U*aMa&)D zJ($;ho7FvFNZ5YTjB|lv4{ZyUtUDQpb|afXaFR6?@d=8UjF9Bygs9)SY7+_jGM=q$ zTe{s2+OBNz;%WC+Ef_N^sOQ1RdljdizJ?9ffJ|$-D!UU^`}J=y{i=Yqb!Y>E1cR-W z{Gnlw@`d4b-iIgqPkP8Y22>9*7Y7Y4StS*fMXCn`p@Lm?Px@q^G_hU>pNd<{$iT~% zx_S`=setZU1aX&Szqk?cz<77x!O+F{P@hllGr|F8Q3z9I&7lFwTHb&feJ?3r?}cga zpY?tsywdeM?i}XZd{q=|`$-?^_~7R=NAX9=v!U(5UW7;EV51cc>=zjNM|aWTkf>BY zhj0J+kN(>+oiDy1#S%7uDMB@=-oS|gDmB1q-Y16n&e{ikU7URe9fSA9qVI3gwle!v zcKF(n>^-y} zCzm2@M3B&Z9cQ4=i8aD6?kP%?8Xf#P$Z^}El+|P|g_-!8TU!UpN9Nb|)HDQ)U1Uv) z8jacCV!urESH%oB_uRka%FNNQn970Rj?V{1<2&n^%e>xNWNx(mR3E*&d)?H)*D0j; zgxQ^UJx%2(=x@Gj4;Zkbp*fCu=QsJ!uAd}!vXpO_E1KjcGmvl)9}UPByzOCrI&*aR znf(Z}Y1#((k{$DP#y!vBwqvmPc@qUM3z6n?f@!g)Yp^T4jG_(Ni6W7df;+}^yGqqk z`1gD8!}aXO&fDgQ+ED0|`tXBkNxu2xj?Y2%Yz_sT^ClAR>oB&q4iSo3^mXXI$y#)jB5c6IoEK`V5csiYCN9|nhaF3u zf4@Y%ChpCe=bp^&u9{*txVH{AS-keIz8)M^E5@()2dxJ^&8{p*j1m9EUi(6D@0g(= zLBeyN6&ItqKDwUjTWBcia~s{_AY#7tc378T?Gi=;GF^kycXYyA5@H8mtOTd5e*Lyo zkqD+IXl23wWs&-tK;!#@bSJd-__oMn@Yn9aZiaIaWd9jJKSjab?^RkM@s{ocjh4=9Rphe`lm z@pM`}t^r34YN2xPsi_n(fEK9rf}BbE;rNI=9E2d;#d!l1xRg^fZVFp|EWIn=67MNJ zO96`;8)1@>UM(Tt`{%uSUAp=;c8}}H0l_qWg~K8-Llp=MOOAuuBO!!snq2>gE)ZXf z1>k+^fWG%f6n-Qd{II%{{f8a?+1}3k2|DIXjU58PA?*w#&A8!j0 z?r8o4kO;!ldRBDfy3Z>P%X+|Xd-5s)N8$b?Im8DgjQDAAf>?Ecw!qPj;1N)xZE*Eq zD~C|t@tA6hN6dUSdzEw)4aE#joT%^NYD{(;6XpmWlsF!g-0^SF3w!~70HvCqI8!a2 zjUTCh{0<8EUP|11aa7Y-SA}}8>#Isw(hu=`FNAm|9EMaTAT^Q5KE>f2YX|H{NFUs& z1O9$qwf9>QQUhR+_tmO-*Wq~>1f1J=M5eZ%;`TSU562`4 zd;1M$E*#cQC-=YRTv$)-Fw7rJyauCtwooRQBQBm}YNvjUeZlI+4$nF* zy@x6Q85BqGA9d0(UBmo1^aiFIBIqHQAA>F~vGnB02tJDhM9UPVnJ% z36?pq)%_6ONt5U)!HqRgE$tg@Zc4N<G$VL;v*qRz_m=6IRr+u=PZy7RR3|QdS;=PD}3@LxZQb=b%>?o0e>I6}q+9_wQA* zj>>|MsZa4yEDO$%!H3s?t&zfQbsr+hea4tL$*h_rzU0HEACXUvMcy43S)@Y0r%nyA zhL+7K@p4qoo~_7J0TuKM;n#<_YI3AgLAI2q3be5Rjc+TVJnI4Ec;tFM+=3~%q-POz zNt$mr*}$bA)n!MxVhA&{1t(DbZR7 zua;tv5;Hr6R)}i?K%Z=MfI>@_8SjpgT|Zx_Hy)~5f__<4q$$bEIUrn0*g7{e{_yoC z;lKkK@`zMMd6&Vb`5h`k^3^?w#bib{%mIn)c4zF1B?_Uo2yGSG9dh6d{i_r+6F$^* z10ChWXi|Y&-3-seN$rLlzU`UWW2C$a&4*h^g4&}G4D4LmTK43;y45Nv0nb#`Ec9dL zCQ{0cevP~2X{zieCB3}eVWW_{F-RWjiGjT>QXP6U=B!j4VBfI&-Y-Kqmnn~OZXvsfE%Nn zwRV2k==W#U(?mYSDA711mLn1{nVgD#%g1Z6(y~s|E4T3P=#L1i{kaGL_Tqb1fOaB&2S@LtdEzhqq}>y=<)sSc zF2l@BwRY0aWOB&W!Fr5WFE81|DaF)1U+ZQmGZ7A$9{U@yzMAU;e_As7@LERcC7FkT zty8U-;VX~b&a$lcB#eNYql;aa%|F{MFJYm7XbY64sc~h3h^i6fI0vFM+g$Q&L`KjE zOn7bM5|`WX#sfF-Nu*WX)Lrn4@r8lSa9W#*moA*7jQ`GbIZpPuxTMJSxXvjlI#NQt zWw_T0>BJKWIOMrkW>aEE2--5uQ0)Br^5ivVG92GRw6NG!aI2Q=+Gr6wt!h5BUAIIc zHrx)Bo_|OPdhiq-X&gs}PeQ$&-^Ui}=G3mcSF>A{%q2kf!hVzd(EvHOdP0;)@8(~S zgj6-9fM1icJdy5nt1fsarWesuC?yxO%eEC541s

g)N<|2?X=XN%wuxLcZPkW=U5 zsIcZ`wG%hiUB+95HIz&`zmA_P!E2RcR&R8`NZ7ZVO%4CSrx+y~mgJTP#V`4^Ri6Dz z;Lr`WW`meMJne0eUc0-=;WsJo0VyW|>f2d7wOPmt+=OZ60+ms55*SPA*bKUB2#-~R z&<8fwOs0(Q=NQgp12)u$vlV4U7VenAVm7X*CpO}teX7C4p+W~nrOhj?*`9rma;DCP zt@HMu`$0u?;|B6k(vp*b_@RkJ#hMy9TFFDE;Q&(iO*!6I8qt3TgcJiy*gsqeYw5GIfpRRNhlnyF^9H?{UB<3)Lj#XGzbuODYCTRM1JCetkrVpiq#Kx{ur+ zQP!N(qS4?oaxMN}aurVgEIJvG*ve0?`Su_VL2Ay4Fo`hL-<7LsARgU5s)f4rw?G`S zcD+I2h5GPNdpS$?Cw(o&TE+Gu$*7W&FW z`Bl3leS?*uDY(Mh2@4}$!wiq(=4Mg*|J@4@0NCL)0OJ3j#TpobG#o)8{=1_HgHDl+ zqItyeUl^$S@Hn}(y_ZXoaui4}+lW?3dlY?N$@F!EY^5ksRG%z8`OzDd$Vb6Y(WT${ zg9Us}EU(MmcCe-NX~Ioqnzjnj;?+QRJ@N|O8iR7%c|G^Tfo#=od{Nj7Q~giy-agUH z<}!nHXGloqgI`>07^mWIM;o{D>8s4T`$FA@3o)=GZi_{uH$5JijcUPXv zcTYuT^*)on(Ga}J_k8W|GDty%1D5twG_8Fxv*!JCnIKVTY{w&<`34VnYw7e1($xkj%VO+ipC9wtZY(fRh~d+gWVbvrSRG8Ppk4T{Noutn=OgOB)s zz!u9z?4Br#dm@e`txD?aFy&%LX>SqIw1@!i@0prii3%bH4cxnl+8x5BA7T6RNf~4g zkyal)Yq-_21IHr4ETIkMjPV+O^oz5cIe5M^qyl*MQ)^K!<>}GFJc)%`*0#GPM*oy~ z(mc_wJZafEbJH1G#CP`|L~Uyx!fKuOZ@Ft;gaOSBL;_ce1mAWv@YbqQ`SLZ4vG7{a zDIT1?mDAcZi)_?1h^|gbMYQoJ<*(=K)XhnHhqtUL6xy{-6Z-JBm&b|n%Y9cEttmTH zc)s7zVNDm?0q$)pDnD5OPIfw-M)R`d-@*hn@?4Q9eQPZ zaDpM|y&j`$e9v2-@)^bYKajMdJ(qh(+S;L7O1MCz$(aA(S=5)? zM=5VRo`?*PGH3tnQdT4qWsULT7ZcS|rG>T~Q?k(}XEd*hvAm55%3ycXGLKyKTC4W_ z=J)f?A(HC-1;5vN$d?xv8xf^u{HqnB-}IHj;P9*MD+b&D=_txrtH<9>XL1zZyzeM# zql(#cxDSsfNlWf~eHCikihZeY_T2Mpf>V1)SoztK*e;>p+@g_|M^d?1hOW$g7-H?% z=tjC@(ymF^e{T4pL|M`}`5F4%6&c^(Kf+pMVpnQ!n21;wd2-K@ZSr0ZDSt*?-JJEA zG80}K{Of4EKHDv}Z5gOOCZ(BP#GmW&%dq_tUoHW-FBEa!t*q7Tp0>`D8UxM4& zzF9ALf?oWojSV3kxxHrN*9&PdZ$&L!>GTcF5KCO zKUF=%2}eEo#z4qX%-Ho)mV?kdEpIx;im#BCAQ~U1t!aRd%*E?E*g&L0sjH!LLRr1T z;FbAE@qOQF)SW>Xb-8vu(qGV)kZt3BxKQ9=HmA^5+3H{58swLG9w%!U_NXF4o?omm z0q!=$gT)rfOIpNHJun6<(uh(R*V=PrB_f#4;fXH$X!I>L>)NG~yn+R77rKwfNPkeC zr9suxGLx~2Q|zU>ldTMFo2wf54AC%+9#48 zkz(fYp^3*ezY__)@#q>x)L^gba|-Amu)^~dYxm#TKQqkdy7O)hV0@G{p1j3O@(LBM zfn%xav#pf2tzs0#|Dh*ZLD;%2#w3hab5m{)8*??yqmz*R>sa$$InwKz%!B9PH1@VoRC~Y4b(8%@0N|Qdn+rnIiypV;Mp*&Y(hR}tYd$4E2 zJk195RqaM&m2k8r$iV}wqhD1G+8i5FpRckt=BW~S#AN)oL>ID91;v2)#sq|yUTm0! zhld*cJ8xOakU;|;|9E9tsG`=J`CIdm6s5UU>hNb-2cq5{ZbRjEim!L5^QK6;0^5vF z%C_2b&Ak?&*WO(Ey>h!%Kz?m%m*$n%K;5+F0P7ibCAAc;5Q{{W*#T&%o}+Zyo4yCf ziDF_kQp_!-_L8jC@E=V-&(%oOC~J-1ej(reD%R>cbL8WTFLrTCSYr9$NZjB2eE{(Vs?Recc*;r#K{l6W9^I&zbX4cztj3LbTkU$d$kQ#|5W{~IxkwT+skkh@?K$R zlj?r=6yD>cPH>oft*58X_a!??q{4zRIKAsNGn?Zg+Y<&8NaI!8zQ?rE>!QQ&J?4EU z$6u{1Iryoom_I8Asz_`Lj5d#5S5Tz?-Rb4?v{FKSXCbfj+gug0zf*tlX%xiHxo@wR2GqqG(y9-w?=qoLH|}%`XnYaWmzDXh^JYi@zN4=pfAm!dX1F@tCCl(@ zC^8r$(R=LCezSV4fXAaL^HXQ(=G%oBVVAB;x^kHL8h}LHocMQC(1Y7`up);2H0Hz< z^qi*8%WHsHz$N_o$Og?6W=JRpo@VNh5Kq`j`9|e5J>X%ESNSw`S#hTw1BRFKd zPFLejy?+clzV6VbNlZEjoaGhbP+Gn89gTDxENbth?X~G+&1P&^X&COICYP9UQIAoa zWBx(B=Cf!gb7|nV`oq){GvV-_uz5;^EOg0NnC7K-bK~Em7oK6vEHW2urJ*v!qk6pT z&t@&)g%qlJUhA>HU@j5Q5vLJPakhng7o&s!M4Ctl*$BAJ+!R2%$|QFltlfC9tnR-6 zE9^c|*uZzFijrJ=Dg;K|C-Q=RRDXDivq?$<^ed!aTbI5&gqRZ6+yJ*8t^M7Oe0V15 zZ2mJQ?cXsilUpHU?qIIqz^MdBiU!H{)pU!m>j^l}6E?K&bBZEqxEIjZ{qJR0;4dOj zPe238w`JFTuf?|y=^+z-58?HTA@Cw=38cq(45fLq1mhzbKctk9KTPBV<_kU3ahV0deE8EC>_Hg`Sl#g1Ok5H+vx{@m= zjVo)?2R@oN9xk57>^|C$wc5jdYT<+uT<|}2Fj<drhPn5mdDp+4wl3<_%#hflKs~hXS>55=CUb z2id=i4>XU0Eit~Jb%HERFbDz5rHR6VqmbZ0U~kx_X#kCQ&}oaW`w6&$I$}$gL~+Ew zM9FvS{x{`$_0>h|&PCH(fO7#cl7GCDm13y-)!B646$6+ThkZ`rB!egZGUDhtJv2}Q zy?#M-uk3eY-7B~V)%3z_PMiZD!%M&4_myLg&#$6^X~<-bIG&q{T(0MYy7%;$8uu0FtMegp(c;MQ;+N(S%*Fa?)GcSZOcxAT}W2tye_2%lmZ#!F?F6OR{2lS{ZlttuqM- zodygf2`G$T_=QIeW&NLQN4{ z&PWC76Zg}G*ed}-!@cf%0+M>%o9lxA2onB-;?u=vJn6X|_pV8eT(d6^oDeOF^V) zgaMir8b}rat1>MM^91|Wm4zr)G}I+n(`C~{W>{3DxhVl?MhZpb(?745uqGi^>q(VT z2=7@|Jh}nR0ryUdA_M|1hXmwc1KuB0Xz~=0EoE@ac$Fgo zrIc1buWUaTIE@w{NPyb9CFFgWAYc;&2SbEjK2-#a!m9-oy(;tkAGDRuMSwsj06HXK znFksynG_(2wzqMrLc#2v!J)da`wiwwc;?Lskqfql90PL+0LiUGjw=#oM@c@E7lQA6 z-icVb!8bzzh6ws!S`JYj6fMQg$WmwV*!9wU@(1;}fjFR^ur=L`Z=A)ry-u|~5G!~? zZ5`BYCHSI_gqRCX{sY|pAMu$22@r}-!}F;P^K7&m%ex||qjMo;_@xC3fR3_NL}%8l zELK0b*N;^Js=RO|IKChBJ(v~^?5#JZZD>YAE9?9PGqdsPn_N&B%gAigClRkCtI{i! zsI}PKe5n@ZNhjFgqn181nKch=GvvyefXwyyLb?$&L9YR%tPVx;GCT5mKw$K>^SgB3ax0cQ~ z+@ElJF`~-NS)&%Ed$FL!e(oH3(Q8vh<^AS>J*CM?Ei49rS*Y-6)uJXfRf!HukR-)@TZi zds4-*L^wr1{_g?#r>4Q;$4wtG&G8dOr`}D+e5pWYuqS+Yyd!5)ZTN>8z%)9WRjs?i z-UiQOV0G0$hL>Sr&*@jW#_ZQeL;J&c%dwD)5wMfH%cK|wA$lHul)$#4OUnm+~& zQOz8~XNF~9VZ}X8RWW%rMpY`iIuVEE2pm_#J3e@l=eXb~c8Y%NvHhrYc29p^f9W1o zcxG(Y(!~B)b5qawB&HuPABuqw-BMvED%B_2o3Jin*WuQfM@kzdAd{40nN%N3~d6qY`CE>G9 zM{NpUN=g6D*7$q`=0m-Iq>N3tKL`(VitW5mC@loQN{|4$s@@XBLea^@hrgeQ39?=h zeGZ9b4qH{hH5+GXSZ~MbK&K$I2~|_nv#{(n&dUkU zbokX+T(COO{+^|+SQ0{&8Z5)>;$G=*59Hoa&P(nng9RxwF-18IN1*&bAZ5bKD>O%ohfpfns}oUpG3 zFE(vD6oY?6ID!z53FB6b^{2d)g03@{DhN`YU(;|;*K2%TfT*}~=OC8`hOBm2y{zp$GxY*)MEb$s#7J$vz!^6pDaUBO?y+G4(zwKA|W$2h6 ze<8TpRh+~wXF*4^BmG|Ql?%XYRKJ1%2{mdS&0oDlAN#|p_Y;kCfkOLf@5eh@_H~c< zWqjy7jmHZ=y9zO;5-qtzJ0Xnk z#DCKR5`wrQ;XRwjV}0LtAK7c;yTr^8tg}r;yi)GDIczK;;*aLu7UL@CpD+(Kd+na zu8MO{D@|_Nn64YTZ@Rj#I`3}!n66r$-44aW|93Sz4j=?48Q}4MWlt`6W^XWrEONi0)%{Pbb~aOdf5A;6y^hZR`a1I(W|>2tH%5IrlpVz8$couh?VI;P ze~+>EsJz?3e2_6-@Dbdz3?qF|$w=e%=O98^@sX&Ffr~?i_Vd-q^Z7?2*$w^*UFDcc z?TUf=YmYBWmzHZ}g)Fj`3y*NRGp0XzOlEH}i{!sDykimUlDhi+eYTKu-Lmug;&?0m zBGTH|0)1KgV`}O{_uW4LnW<*LUx=B}$>RbbeMW&gLi*JCcT4OxPg}9gS@&R%`d?(s-kzv7GeC zS@NB=nSF^!>GP)spxuPx*UKB}biLfz9MFjJw1voO1}cH}C}U41+2N!=w( zyR10#Guv)<)H(N#OFSJ#R{D$1xBJCGjt6Cr#3=7<(Ro48j2VX7^wC|XhLY5Zj10ym za*?>PYwr4Vo~DC*F0(Sba&N|{?PQnFl6D`1)Lk|6gBk69C>fs*yh)dP!7Ct}OMJ7B z%(hzMt$Y{OmY3~!-I~zKQk_{-5(b^isdF`utO}*eh|qilCb8!z*a?F=H=nS4;raB} z{6Vdfr_%MuA$^9(>82M)mNg~21_LUYdezajvZc`dIweuE%DLO;|oky3n z#)K)vZtCp=3X3@ki7c@&eJyuGCyEqh_o3+Ny9e_NUe85df5FlmIqVMlgVR59_ssx8F!SDCWYh*j2qFSe?|L?ePY^X9NxY1+*Xv&5<9Zj zA0j^%PWk(1)ucOn@37*7f4Hv0BgZ!jJzA6P`aMVgZe;>KIQXsoTLEu5UuPK+L?aM*67Qu%R&T zd}I(QArOlV6Ya=<#r2&qgx`Ypp$s0*U4)FB8I8t0&S8Tno{Nx$Y>Q@CDU702DS(NC z&`i%B|0Dbpoax_5wCSxm75UKfPo(T`HXncoJ4O;L=Qc>?*aAr3l*ySaO;f8F6_7@P z2f0=1qs-~IgzJ<7bV5iYKoZ+D&3Z#Qem~h=%vojPa3Yyqi^4#4g-FNVQNypK@jia$ zOyyuXUUQ8Y;M*Z;$olXrpfFm`ep{0xpH=A`l@dXrBpfFMH}8?7w-E{>g0PHPx(!5` z(JKkKFRNH^kfmA2n+u-dBo&^bH}OEq5q}CB|HN z-l6rk^X2=VzevA5$s8`jWwqYBi#CaQ&PacyAk-xj;FKH;=yx7e^%H`#$tKWf`*Fgb z?x{T!bBmjB+eHp>O+9CJQn4A`5trD6nUQVh4I+AE@Depspdoo6GaDiXm4OHkxri#M zu!oJKqz=SFQNuB%BCN76M_Tc-KxLswHA!?J)mGk)4YxJ{nNHxG1)>FG^MciOB8u3h zRGPg<9AEgA1hlAxA(DMi^S1`N;(I=*$CLvi98=mhSEEB&h8&Z@RzT(GbLhY8GfS!z zS-VHjSREh%ZF8oFLUEDWyaV(zPg}&SKf1$1kTfgW!DN8i+?^lVxGFP-rl*x4Q%*77 zeLBB&3k0FVrg{puzT%w@Bo?+s%ssL4vfArYIf1B+if)^p5lwJb>fBpf@3#xZJm-wK z8{x=f8Ka;Pv22}~5{HMI^`A#m8hwjxO$_Ob+rKrp>9PlKN<_;!$S!d1+!wk)oJsZ; zT3C-mZ7gXemWkaLgVaLb>JU_Ew#PlL;Hq|1s~*>CT)-Bcq#yeg+nHP&=pnY&`3xq@ zUw?A=`I3r0f^US^D6OlhZ3p2PWES+bZUNo_%y;&GV{dk&l2%pXz=D#PSj(Xljb(n% zZ5$3WIc;caTSM(}9F;wH$PsG;t=~U*HH$r!i=ju!h3_XNMw(|v8)P^lkd#seQ#Ec) z4=G0kL8q`{YyCT3;gX;J<$fl7umP%0HBPB;Xe`sN*aWWrqYOhjGtj$`4v3iRtHuhs z(>dPt-GTJcy>l$%TPA&@$f+(Yw)#hQ$=Rr-8LEow zBPZ|L^gOz|0Oi;BdymMZG)i~oo}i^r=#XtO5ds{{CBV3K!{gf+r^6Y}|D7hWcBniT z@3;q25J&(I1mx(oMooT6*OsGaJi$Dc*~FeDlLzermoa?cfN1Lnt9x2R;wlh8P+CA9 zk;;49p4Q-5?{`HkhiwqR5EL0}oDf$yg-Lyxjbx{A^ z_coZD#Izk*v`T72(zOOkIWS)Q>d{58LP;QSK0YlREvjq8Yeq9N06B#jc>VirMm4;o z)8^4fO^?Z)=QU|%{ZZ9zdA=5K9P0AWD>V3T`GAfvCX&~bwK9wfV>&iqX0Q=gb#gw@ zVtTg@$-{0i(RSq*`^Z#Jg((UaANS`8$`tu|)AfghSd)A}dnRaNd8GHd7BzwF&~zjq zz79V&!M{DvzE%;QUh-js02a<+4WKc?<1nbOwroPc6L-no!(HGsK|GI*wscT6b*=yc z5&*SBTlIDYpO|zKq1CUn+N<*v@dpHKr@}1{m#?MJp7=y@a!03my$mSQAdHMOrATOqkmr!QzbVPnT-p8a zQ5SMQ>V^aC{_m*!AATs9oaJND|4@k7Ol=AVgRug(_67A8vSEz;u7upv==>Nqtpc?x zIGbuXtBFSp_iu}P3K8DSguXN9R4$!9jwqKKS8ss=9t-=P@Y~t^BpwbOF82zZY~4nd zGsvHV&!q-QH6jKn>q~Wb`Q`tOj zq_H+04pT1(SHE>W zaJQ``<2R(Jp=q3q7+^i9hFt!d8u3$Bz+2IMY_N-;)NlE=^`S@3ID_q-lla??zGiS` zVJKrKX0v@cl8%W{_;xMGs``CeRYJaZ{9R=DH*FlUCKDruY@Kx^SWJ8_s4O--Pl0zw zktrBNn7*Mx3lUuiA(2UE4vgzedligpJvU$kYz{R-y~<}>@@4uIp=m^Wl|~x=(3q_t zUe9HBJ?umXQy9i(mreqjJ9E~i+`g^S)ny;z? zvdWfmZ%Z<^{Wh)eX5y`1$Z;w-lFD1Fu&%bU%jpC4*kq`Pb&_+9Bt;mKtW#}t@{b)9 zS7p(CTg$!}%rb288=W`CCF zU-r$9CAvp$4&LLIYn(!Lx$IVU4jUaqUC9z3r`T4wEU1Jp7ZgCBW4^*3(zCqiS3dfUY1myj`6h|o{kF+^Zn0;UwpUf ze#3up_A0T)9Gc<+)>L@FA~1eLoh{8yJ!zlF z!3x&+HJ;D6Ol^g+#(^!N0>xFb0PZf>_LxAy((iyL1x*$$&-}pJDrflRL6LlMms?^? zE4b_N$oxDOG`m&D<`eFGwD1_`qg>0K@^{+#dt?Dm3VS(G3BB4jdFf@&7v?P^Qd40vHdUR~@P^6#io_Pzh;1 z7)j3jenqK%OI96(j3U&BQx0l_P_k;FiN(kiyzEhXg{1Edmf|k5Y93X)LgvUw$O9D- zuKFBc5~*SOquqwmmkt7zmu~rLK+&vK`!+ZkPA)Psis1=G*_4GOOl%P1&NEl^79!bi z@Xk)X8P^xePFHmgl9a!?xU7g)jH@~sU1I8rg9TT7j92$a9D54*|@yz5W z--#5Xoo#k`p;h%D!&F@abPoMtr?ydNJ{aas^~U~iz1?XVMK%TC72x#Q>35jO&&4{UN@m>T`w8w4w*Jv8wV`f)UTW$-Yj z{pBxjW*rr)XOKqptAujvbYv}IC@s$Eh_IU5pTRdwj(=o0qosg>tuA-vf$S!OPsX{oe~!1jwXwF2s)F1OI^Uv-q;5k`@nE6 z#jmzw>}T{$Lgz@GVI`cIcM@p!&&}~E;l+|3LPO$_Cnz?fPcZ{g<;WZ(r5cQFgZ^s&e1_q6*l1a;}d zG4?dC2GCG{)dP-6{2 z^rsog@a*WsEiL^uoLN09v%)LwiW3+|i)~b)D zq)bGXbVrw#Z_qezEg|t!oT{&#&}P$bI#Ii~LF&kd1r&6@-E5vy46&nzltg)Fr-=XZ zcslv#(2qJh*$wMQvqHyd4BoWeFEy3uK{Fiktw2`;3;3Cy##3PWwgt;3n(r#iRN1pdIbkiv#A**g9AZ8 zsXT@=L8Gj@j^c;!Hi9TUdvI@z6Z&+jupUPhxNJU~5_BGf?|~4L0XZc=<0LNN%z0qU zJo#ZiX-J?=$QqAkAXL-7npo<-{p_LMQv*0MdP0i=rw@VlfCFNplV~0hp835-TT$GRS$R!hIVJG~!O13dPq_Lz< zu~tTf-Q1JVFnbZ2Kay9mupNm2Ix`j|XK*4OLxFm-2~{Ho3p8c2Ky(3h`cmi!+rB_C zxHzb*>;W%BtGIB@SP~G&3ZbA5xwX|6rs``i&34jU*>8g~40U=bcyk>$+ zMBZ>)vOa&@3sD9Ulq?No%0Adv0Y&|( z97gFts?Mmgjykbfg)np05`KzZk)YqZK58}0x~Kso|H6SGNdO` zy4hP(`xz5FTOvz}kYnTcW%}WAtBX!Sj?OxIWaZmI_lLI$CLpQtu2F@7ZL7l9w1=iD z9hbeyBXw@iHK43|1yxV2?E`T7se3NRt?j1AtsZ1qep2yZ&9$jx&*aqD|xGf%0NG%LVfG%&4J)R^Q`jxD#5%rP=XMEK1(BZFUa@~E=qa3NWQNQmCw%^{d z_WXF&Bl!U<+hBM(;6>+sHA)ynN&GnX#Vz)bp~n3 zgzNp}uY~GLwcok5egvZWQRPkAD+83@GxJ+HDrm$LtoZL%_*7^;7LS1sS@SuRH;J4b z$(MJH(t_AectaTH_Sg7p3AhOUi8)8HI@v8~w)5!xaMX=(yiC{x7o+J7R{uJh&l!H( zRz_)=#!gyQx)s}Mv)(M3Mre}zJs~g|H;kH%@!>Qa*;MD1%}AHUSBNJ!zw23X2sApG z@oSeFEmLVfk^B8*^({o)q>t3C<~Qr*?Jkm}ZOXgr_s89j099n$tt88_gcy~btm9?Q z@9ajUIi^8J4mBf!XNI4cy#Bm1x}2HvVn8w9UCrJdol}z^E>ayYQse>@g)V&dcKz-H z?YK$-$EBRR1c7zK0Yo(9*zgY&dSG+_9mVB`#0y{Qh`>WmN(Yz6OyK*lhZif&{b9p= z1;T>@Kmfk~-wc-b-!s@=ctCC#jFk-YPLX9Wl9E?}a8RRQI5ZWEVu8C_Dg_m@)v(kF zZ&su{#QVett}bcJ63-U3`(&>#_n#Szhfhz?L?MZcQbBFK-U8-(JlEQIFqutW&r_w0 z*wx9Arj%wuxY^7UbbP@ zRqU=&mvj~c^dJ=>QmcJKCY7p5gVO|hA4$#?Z@NEoj|E3orMt+KyNZ&Rb-*7jO}-q5 zbJ>aIj?A)upY zu5yvMQ{DdhM^`x*lO~YuqdtbaA)Tlt;$U;!m+~Ab0U{Ph1cJyE1H^}mQ_|lcC#hfi zm#L*q2)*ELN^_r_ch$B5t!qsQY%p*kg20S=F`j?cS+V?fL~}WzA}U}CQ@Twz!}lPD zopGnt3@?_zLBcoY0l;P@KuiQ=E(baD)LoUl1&LwA8Cvp8v7dl!v!X#Ex`-%TeDUv* z>-QA$hb>j-w5UGhAiXx)XkSC!OTwLy8+gTmk^+Hs*)q9_xj&+NM_EV&_ODK@KSs-h z4msx1CRxczx-NhG(48!%CJ{{hxCAX5Bx(Ef^!B@nARZ38BDcKRojyw979OINv*_TX zn)=62x2!xAU-BR$FY`hrD{hku&e=|D#qEhZFNsafe0{0J@RpPV%_pBK!InQz0JhHr ztq0jRBtx~M;$aGgS?cp*7cA(3zmnU5mpL}3`D+*!I9jOWhPlmCGO5(p-`3C|;SZH~ z3~xI|HYWopP5*1aB2y8`ugdWlOXir!fo}S_sk6qK!!LpMv`l>z!x=Jg2=N9&ccBwP zs<#e8?aAZyX$lF+4vGC=p9f4guf8&2sOnn!uZe1wKdJ_S6NIl6!pv8;W(4e8R2q)_Q?e@);X#!8sq$CHSeHcV*xj83;G0GC)dd*e-?)~FGQ-DY z?MnY@=(^6Q)r{4G=T6W$Mt>jUJjz;W-UxqbWZeSdQ%5s}ZaADHUF>KiaL`~;R8|$Z zs5Zm@jsZUs{Qh6hT14*hC-Jhn#B&}8$J;3J_8#0RMf`_J6P%}`>R6SU!&uYrVFbq8 z7ooWELJ4b!Gvho}+5*_A<~ie)$83tA1)dk$;;qQCvzd4O1h4*H;F|4yb@nR_#O|mf zzdz5tw(YGq&=#Pq@c!z6VtzU$5(`MNU@QP{L)hHn<<@CGv)^)by`+pVdRV?XL^IMe ztTD{#j%Ey#?&l!C(HpM+kuW)qu!AS^D~^d*@>>j`nfo^o=DSF%_qi?jo;j)d1z=lyBG zRInsZ@53dgi&my+ghTMDM|;w+eWB!$AKgMUl?fX*A2;;q2Hftp2%fnh3J{>Z5igeC z*dU@xOLpE@fzVl^!dEXo66)roJh$^NpANf@eK7vYmY;Vi-sGaMRW|!D zMB~Z462R+okkm;8M@NAdbK~}JN};Q*CB9vT(}+Gs5KfO2{q&1W(l<1_d>~alrS#_J zB=(Z_S&{v%>Gn?Zj9R|<^swg9P;6mVxG))xk5CkINT1iCl-d?@Y(jILg*<)p-okOf znkzs~T?Zx`gk#`~`6*cP320oOL=T`Xz(L$B-&<~_sUbI1Jy8TpX0#>$#=K97Hh1%@PX&Xav|iq|3&?}zo43mo~nZT9em zu^`Z7K>^I(lMRtXN80|6uc3?@gGE-NyVhAV^1=StSPgASGgRFSctauqyYYVmrcW-+ zlVOb!2V)L2b2xwyvERzqE!Qeq(lHdAPCBP7RZ;-yW5q+CZgD+c+f&~G>QEmB)~qta z2~{nXj&DdR=F{GWf&NGI`63S(;I zs6Y3usg7Y?P}2%T7|_0Qt}TzNa+Al8eAkx#MCVH@&Z1sFq9q=Pqob{o)kev{Nodh) zunUiKGB_$%cPF-qab#Jdv|uSLn28caXWCj%!RBTfBbl=|dE|?m{NssSU~e+~YHu#` zdwJGP!1eKa9+m>Hg)GThMOD3Bsfteq=dvtJOG5N3MUX}M83NFDTjEs^ma_*}_ zx-ygS^B7a}6~m;c((IMLmsYLVfg3OTI_pgda3i@IP7}|~<FZs1F=fbC*8%OAlxS94*^ z{j|6$>Q16^b^#RfAzYgI(ae<(a*BPmas2O7N9*4!J0@|$@3@n(^rEL<)mp;1vY{#q z{TnK=(-WE8KSr#&Zr>cYv19ZuG8WO^nx?k!Qop|scShZ|VsQ>3rr00fygg*w{&UQK z^=t91&ux;hU+<}h_lls@ea*4L`A4q%$~UFBxt>#dP6<9sibW4WTz+Kc~w^CCL2(QS7f?!oyloMae`P9f{R1+=#Ry?T?1 zq?9KpDl@~HWLZ#c_-ZIiPn8eyt7uM(NK1}BL%~l*Hr4!z1 zDt5MBZ#QZs4p*yEv+s;0vb{v8=Q;Om*YOzM*|y)GuQW0$mGR`OgtjTbSn&)AI2dVc7B4M?V31P?e! z=+`rU6u_%2-#j;tM}egvzadifxv}R?D02xjl5gIb7YA*EnJz902!BS$HzPg|<3qv= z5izh?Io$}x3hScK4f^qD&aR<{0`U$Q0Lm*4{*H?_&fbVfnlWTiO2QRoA&r-LVRK~8 zu2P7IM!!8_l-=m!jRcXJP>--Iz^KPDNnml9@ChMaq>wSpxgUeH$R(Ov(ZpE-Qay%E z&qM?BAM`>FS(Bt&Sw|14)OLqUzt>)`f^?}~CyoGl{FM6t_N*Pom3I{dDm%4TX7ELd%R!y)+1 z@CFM$4ZFd8p$HR~qTAXVKK1)4U*)FbLas545ha&#D>M6NZy3uj?M{V?&PuY6@iv7U zjSF})rp!g^95;yd(z*bGVb^voR@}fb)h7bLe7&yGQoYABs7RR9=^#UNhsQ$^Gz_1uZiji8I}DFR{67j{s|iQ zCdrmGW4-Y0osgd~M1ohO_!4y7M`^chgvvotl&;RZBOM*iAEw9+Z`3fmxz5H45WqZ% zz^`FSG$S;WP=qg;YaR^-1)H0?&K&UO>h~Y1X6p$oo-Bfs+cCuh1eeq9h)@a~(^$Gt zX5%3Qv}ICg1Hi?zB^|rR7LTS^ro#~u!c2Zn8$ksFpy(m~MCjZcg%XI*%t_-kL@ucN zpg+iu+MmW!PD;xB00xYEMq%w7AWUi&;-fo=)#B=jC4AsaZPpe<4)=eCz9WHa7cTKE z!4oUg7bOlm5eEw2g!GMZg_t15nUzezY|_-BK3 zLhCI=8^GreP+J+|0=fne0}F^<$*|dUZ$a9B0`bt%&|h?W7QprA7_bgxdGygrM)c^F zb7@G?_)h68>sZKup6Wcd_zVIZgGpaLVmCh@fc6=EOEDS3kA2=S8Bk|UO@6*DSztOD z@_#?yo1;mhCH&9xeI3fB4b1*8GOlC*F6t;7Q{7>WBxR!gKaR47|G2cVET>2#`X*8d zK!(Bc8oR8icp7IL<0zMQt~kw7k>^Ki<$T%q69}@V^7&HLLPjM8HmsRqkg^`;89s`XZ9`5divB<*He{FSVG$$%l~i}7@a$;r4|=D6dM>wnpw&vTTi z=dQND=+@%d%#q) z?fdJNSF(2vgM(iB0LuK{_&F%`Oi?UAS?;~ zrI>_tEDCNb{MI_y2@|QN-3zBrvEE~1E-BlKbhmEVi-M0Z)9HjvS?@=)Jl`vbj{knL zA1jV|S|~0VXkGMPgi+o<2A$>fAVF1(#Ue>l#l`|f#!Y8P0)kG9Q>6pF4$`Rkr8jx3 zOUfBD;uq?VGMz_Qm@*w_Y>u;So)ds_CRLB)EbZc1PGljc<8 zWf!MD7X9S+wR0wSdcuqHhAUaS>K5DzgPORCj>x)hN%f2Rg#rct@@_^ugD^7w^9y^= zoJZT1>JmvnN42CncFX40_&V!!A3bM!!{+!|?L~tEfc0-qMFmR7J-+DfunD1UIx?nk zF8(71Xdww7i)n>JKyPc?RMnQ!qc>rHw+6)T%bCsH&lm zdE51_@af9FDuch|SA!1s&z~iA%*%Tp3*7---wWv9WHX}mlnJ}#$=J0r&M6B0b>nd- z`o>?-%AS9>JSnX%$7^SNX|pt1&SJl6{3cp~jQBU@?TY5$lh?X}vsD;lb1UEU33oVC z&BGo-aK@7Zn3RCnPtq~=VgbTFc>;m`YSEo?p<&!FYZ}02kq`lvF^}qLCe_ts5JoSB1BNs6} z)apPnHRiKac3o?d`}Yp%?E3jW_NM3GU2)$8^U3xHDlzl@W6r<7zxvFJJstR90DO+$ z$Pr&V{pfsY^39|3J5HQejgQH*moyR^-Fw9GA|`*gO8R=?s-KV#?=dV|d+{e~J~1Y3 z(skjpRno)-Q3X$8nI6CSS?ugi^L+&8y+=3IH&y?XZ(Ep8Pef99Jhq>0}<+cg+zZ# z2jK-b2rV}~N9k7CdP>eu(-1mg$u?=mKyCz0(+l$Z2TArHv$5fllotxtqmnf<1WA2G zjJ)IH%H9o$d5GYb;=jh#6TT&-DPdh0o4#70;f(cL+rNDQ8XxMO2?&H9T(EP;{%v@?BD@;kfBs@<2SQe%P+%gkrb2Q%psFd@7O zu5#MH7YP3KQnD5gDtP*{dqzIdPOZS34~_;i$=ZTcsv5mA70VUye}WSoXGjojp-NT? zDEsq5NpoAdipRvf9ejX99EX)jpG5Qh>%Fo#x&PRoH5oz{xI>tOssE^kL&Wx?Nv0~a zTPINVXZOnDogtl8@O(~&dr7nZh~9F=eD3pRFByz8wU_-19jwG}*}Pdb!)KA92~w%1 z!PZybB4*!5HrA098?k9E>zGj4Rc~vzo`3LU1<7&L9X`^LjGeFKAXC2tc|li3!GhfrVD8<$@683f6Sgt&2d2t!M8gb+55xC)L24&YNEmlt&O?eH-c#1 z2ms_^kP_#%a4t$bJS&aK)pN)*gst-X#Twx&HKFBGt{}>Z7;PmTgQF@PCQ?)@xM3q(lhT&WvxurRg#xa5Q#yN#~e{7+V5x zB?^PSUV3s1p`RYS`TBq)ZFUk4iI05e|0Am^D?2T~aEIsX_1ryrQU<>=fr^j5JJ-<& zmE-N19d;mL%FQ!6f!Sl7*JcDhDxoa8_#kPx*~nJjFdeN6)NW@jm$<~5d^F8mCdNm{BSAC{iO}kkeB4~k@RP#M6qelc-!K`B%RT5T*pHAnQ6k+ z#LaNKJX^)0Sgzl{zxgEoli2N`)wO!4|%tAzBl9TPE*<>v*yI{P;%p zrGSKsQPLhsxV5wZm>cYE7(`gT!z;$(y^`RuM6k=STQ`2bVs`$!aKiY4 zd3eYRFg}jW_W+_F55rUi`r*Q=1Ek*8IigClVOB}Bc!3YWJXJLJ>&imu!at6?UO_-F zdpQqL0>FuB=ns|X?$vC}im9*h2m{ak;rSIQ7Ih=A_a8I7>M|J)dwggl?*RGt9UyIv z3+~4vbo`GG?sE+?2WtfQvjX&piWnHhj$0|-)zkpD_JPEuIoVPS-!kq@< zIp;=J_H0t-J7#7xKk<=FevQvQp!9$U7|3S_Ya$LO*4aVc4aj=w4K8r$p-{?ruhyGTydlthAC70955Uc{-_5|_L2;`NEKdvu0+jAX zP*AFfC&8fjG!|_snq=z;?0|?2Y;h-P++8HjDqOtaL2;46w|GUdR1Q1~P%1i!tbG>6 zlje)QBI;*G-5MT+nIA=L{sE5<(NknM`k*}EY&6p*f_w;{X!TvwdSScbv|PS% zve=vt0nJUN0u6KwK4a$DNYHtgRvTqbsG;@P-Z-c{-c>N z`qUKI6P$36mjDp*Lid7K9LB&|U_8IXzUxX1p7;o{D1B>9gr9_yfFfwM>9D1eWW18j z2~GLEluTBV28*llK&)L9!&*UNIneIE5 z&XQK1aw!b^CofJ*pRLD~h2AWN5gE_tnORnz2T=eZ-)7hH=FX8B0>GI)A9Is!GNT$| zu$wc5Pw@Wv!#=|bKi6SZsTK-&7xF967WZK@&J~KTy%r}gk`yVD?kJS;E|SYAl6%CK zA}*r4FH$8hR@KMU)Gr3AV(MfR>vo_Rk3b4m7;3u2WedwN2PHZ~qCObguIW~agOV3@ zv!0g%Rz&BM@EK)Do+p=jca-|Fiu#`6_>-3fij?_-amwSs{Ey(~yt3w}xQLj?GM8f3 zs^&aX){<3hztKFLazfm!weoBQ97G*-SG>%>0;j~gqUa1Kr=ue0EUGe6BufEW)K}4@ zUy0}TcC`>^92P|_5dEyZz|J}%*|vP^G^;hw8?|br4FpR>V*2FKzB`jofmi1QJE&I# zdlu8`13;_fbon>cJLENcA~ib`AYpOvi9!+TtChoPtNO~K&k_OUsVp728(wjP3RUR+ zW+RbRwbZobbv4C1C=N0>A5gs{Qk`B@H*Z`0PK0hRvgQO_Q?!HSYErkuO1IBiPq|*N z04^$0wJL%Yo$EJTp4E(z*Phtqf6piY>BoIxsRFlT>~R} z?XA8ht6(%+Vm^F5{+E8^707uutV)=?u8bNp-oJi*7$j8*zNdzu5S*xa_b{NXQyg$F z-c$l;UWugLQD~Nn#6-Y~DA}4(dr5KfmNXR03(1$}Q^xqMhUGkVcB~=AvbLP8(SD`H zk)ky4w05EcTpow{8D5`j0+x!xYp8>uD!Mh|fIzmk8dYe{4ycnFqPX6q(AGv|&@KfA znZX-0qiT2>no(1j^vrfM6A+_MLvCl;7;8t?lR!{?0aG7&Rk>p030q0kdD)lcW20YQ%Ri>f&v`lQ-qRaBY!vUcF^v6_eptopL>_VDEq@E zus!;^#U5+SAw8oJEh7ajc2Tvb=LMV{J?YG?s9ECMKG2(2;BEi}1vco)?CtIB{pr)& zW!I(r3Y-N8M@JQXj>E)4)D*&dIh2|>?7?j}pu)Z`DTP)7`+mj&%#@u%TJ^%M-`!&E z3CtpI&c}1Fb<0g&!-OiM7`rf&`l^ch1{&)iJg)~GH%59hdr`<4sNH%X^ znzvpW3VDEy$wDCACZmc|eW{Z*IZuki^pYSm=YCS(;fmujM*U2zid?_b)H0tQF7gq< zs78=iRmD%Ry)%|I0>aq^31Az2P#koy?|sG%3F+#3yB6S=HG)D+2e3oh*}y|=;09H^ zMsYx$KO}79wcBJ3Vx!Ol0AdL2k5p($R0@469Zp5$DPpTXh?L}Pr~*cNns>&~em8c* zr)pGjYYm|%7oF#nqbHQ3!*vj8#d>;3OBozw252bsp8)1f+*Hj3zJj`KK-yqnEXsaO z1nL9jn%=e{B(x86 zQUOv{HSs=smBpd=(s1yj5wu%zEY}2y#a<^12l-V^!vEm7P%T||&Aa<8PgP9O6O6yj zZlD!fkyjqKq$su2vyaFwc;Ooju{Hj47HW7~i{i$zBVbkRqW}lkZ1oI^I5McZlnZY_ zQq+|@W4S*88fd3ig+-TZs%H*ScxD8oNPInlbv(!jGb?XBwqhal?>do#<#U|H_bBAd z&2)L(zyx_6EeDw02p4M?JXp8Lqzu5`>g--$>^`5v%p6NJ0XiDZ*c)zD>9qGQazm)-_fYtO-%<#IhN!B_0skxV?b8`+mK$^)S zBd}X0X8ii=Hfp?vzO_T-!I8t3$mW4s%*?Vfa*2(WE@t?S1ItQ(CEj)=Y`UR8yI`^| z8$q?tqq5)Mhs_kTUm3TEuC{}jj|Sw1UMRubRA7MVIg98e+vz1;oMY(KL9p1NFxBDk zQ{P;LKg6dSTm_iL{|kD1bC|?gY8tbGmAw6ua-a8Vx*rC98wVcm*w8b=tD4%!s_$I< ziyx8GTX$29W#6i+4CcH5E5)1y;~u`dIzX2|p4$%BQcv7ne)$XsC2`L7Oz#8RuB?&O~B#6{B22Kf5QR63NL0}IhNI|)9% zalXRby+nZ^u;Pzha(dUV=FutN0Q*L#3BjCQ*XNX2Iq(x#CF~xb^I$P(!PCxlWnbBy zktSjXD_-Howc-NnYrnZz9B2Ct6fbSuWFv_hD_dZq3O@6#Z)88_3c7W<9do^yeFD6> zr0hN0Rhg1`tto1uy3DTd9yBVvj_(IMOl;& z2Qz)WcF98{a{f^O!_<5C>vrpa=X&7$@5*U*c?#&*R%Rd>biT~ulL4INNe%=9K6R6wnL!*BYOX>)>H0r<(I9Ys;wun z=_il+ruR2KcpG(m{ND#wDr~+Fi341Brd={0yr_OIu{U@c9dUKiR7or_Xr*oFT3{k%`r8CWPnrh?W46SqR8l&#d7!(2*+?v4f zOXyMMAzN~poR>8AS61vepa_BV$*sg#*I^_M9e|CfoHCv^B||q-lUcXn6Y)BB8UQ<% ziiM6w2mOBKwObDq0?+QkVK{w!(b}x{v)`X&>ER9_vAofH1R!AqfFB;3gd<0 zgY({S?UsJvnffVzW|@dPE?o)f1Q9#>pn~_p z!=*u{0G+(+6?WzBNpi{ik?#y?Iw@@|0?$mJ*)r!let@TMqCJ19zAL*M}Bu8MU$q)s-PKW|bz4nH_2!>YJiB!E9m!Q@Bq*Rrpwn7Ks2@+YG z%Im$NljqTpBjX^}{-fx?_=Xg8B+h1~;oOhu-~(d~^lq$U#T}(@RN6nI#+1&P)1Mqt zcOFLo$nG-i^8!Bois=}~E~`v?zE0Oiq%kKBAYX8V9sB%pW$mEN{ktHJ@|&;oB&MP z$xMLt)x_Reav#R=D#*()Sn0?!(5lOFhXB-gXyr$Qn>X*fzj~8la3}K(M&}oGiRtdBe z7>LzN_%R5(I+BUh$-?kuQWWJS7&I2#X!D3n7c9IqIo92ESUl<6Y>lHqYp+Nq+XMwix^hjfXx@ z8sfMtUKWbqXG%2+C9^ECbgYofbRT);RF9bRnEw1XI)!?aFX8;OXrDYS&j*-;5C7}> zVE%T_m?fH{nivv77;WSdYv73XksjGktA8k;Dj?%==Dr>C>dNDEYx*ejzNGt8Rg8X& z@O!1oV(C_PS`(7!1kSA6fliJd%06?oLyk8JoSSZ2^(DI82v9|nozBfv4z+F?kq0p| z#IT*HQO-fsPvf}6KyuX~?9JyQ>*!M}>rL7|wZNTO?VY_R5{hhD8W4wEja!!#^*s?W zzAU~t0T5&aeDeXM;k##sZ=-FaB1o76D|~`wd8R)ucvPgUZIoL4Q}Nv2wz>4j#r=b4{2t_wh+2{Yh#%Z!Aj~r?!@-5+8m9{z!L+zF`Hgqbar@SUnIMEKmkJxlsJVNAoT7T z;qnbzN>|WPj9V~svfMid^{fKb3+AsJvx$zM?r=y3hu)w;AFl+p6wf|d|GjjaHg93%&j74J!0L=_>kt3S|l@OYS z>D-kg2t?{7Zv@o- zyFH)qB-q%vpDG~v8>?pVY^9JW5YU9-?PXMyyn(*ba_PQ|O7ljIS}h#s{vE^Rt^Cu}vRoZar@CRb+G{h4aj=lbx{*szPw)p$Dc#Y?dzZ9c$z6S09V&;DV+^cExl6wBp-3k!FRa`|4NWe+^>8udQnyN~YpNxH6;~ zjux+O8GyGKXyW?E-w%ZqJvePNv~R7rupWbhF`Kp7rQh*7J+SMd!O&i0+x}}AphIg> zP&-*Q9^As5*YQi$yg9Wo#u8cRy#i~=8QJc*uF&=Cx)sGL1KQ?(k=Cc&2aQphkBv+f zF}uI7ZN{-Q@#sX(kO~xpRdJc=VlZjD9BVn#UBcU!M-=7nl)FToysa!i%55H($T}y! zh4pPC448VI+2Lz9Lg|gx7=g~-4I4kl_4%jJhnb6ui6y0b?(2a=<-sz~Uced2khTAD%4F#NnUopfS)ps4gO`7QTwq%ubix`&PJ+mDeI&JU!M7Yb zDG}UD-_7@sb}bKZi?Jow$|?~t%}ykUw4yIIeo_DwmE;tcSG4`pDJ?Fn**mKYMcC$f zsvp``eM*jGy{H;cA)jjaLF{wU)XlLn)x5mrg4MF|>HM;F=M#l(+d&HCiYhm4-65c> zhJ>*BrlVxLHPpWHs{3Fd^15gHae}M$1oY_G1(cF~*_I2txgMB)Acqb<&46#44>ngf z`Y^06mc4dGUf=e3RDI*_d5qam3j8V(RzJet$^W9gl8>fg{AkM*d-@1-erQn0iL}bC zwT1n={!V=5-IS0ALU!&jX41`zif$TBF%Xu1M7nKQ}#(m6d67Po6G+Zu>to9%Bt4actWPc_5hHMPT77cj9g_ z{5*Keviz_WYFN|0l}qG0eUzt>7mkl{(me^fQ){BA(=L@OaRJ6sby@qrrWu5^$}`(4Nz^L)&ZG-2|I zcfmh1O`)Tuoz9{za5Y1k)|6er-yCW#{*X}eWmIO>aT{$bEkostHY&1KAN?grn)Rv$ z%9Vo^Y1&2I(pJ)XMO+WlQYsXDK0YQZ@-05@J0^WF{}ozpRW@xbIdUvtK<9#Wm|)rnt#bj(tx{1}|Ep;$wEo0?>kS`z^Y z!|X@wciLDCYu{2-fbpCj5#6<$9BE;}rn}+kQ*y3>gqxZrTl8tIwK5tRxkZ*YV*M(g zO7^nDeM?^-%YXG=yUV!`mZrK9e){@Ow}1$MQznk3pc*)lpNFknCaGu|@u{T|*Y~3} zJ)^>Gq`q5$n))#(PJkS`G&+F=eCSSAVJ-os8fE6Up*f42OL+X4563B^6vCg+pl!;> zl_`>1^_tDm{!W*VZL7-fEow*G5WdiNwA)6eBHPhWzBfccc#A1uSa8QAZLzs*!ZgKh z`>|Zr!JHX01H5IvK;fqnov9%P~_j-^Ebgg%zlS__wM*cLqEOF1lbw0m-Or z!w(jrnznH_u1U&_^a}ktPEX==q&;~bc*T4KT_Zm=9htKs^XfAfCLB;u>U7=@Wil(F zTBIRm)q=tC>l-7V(rc&Jt>q~;+!+Mq%lNO5zG`9b5CU!;ow7Pqp3=vX?p1RZhwOg8 z4R*YzD;z??Ju64%EV6Vyp8YlSU$zr0R(W1g>}laU%__yWl-l`I#{R&!VY?#!M{n3i zSq|-bur_l%8IrUvTqaA%HoVQHKIG8Cv>lc}$d|o6tF@_)5}( z?C&k$=V>lhJu+G8F3~nXsp+9SS-37f!k}(XztU5NW2i6UgXSPfEs~cl&D5;!)5nCs z(Azs`ngz$QrwA|Dsc@gza>OVI&@6|+7F^$Ey%0EUZkbmfGFxX!6iC?maLdL+h9mM* zZ+_F)wrY?Zfi&~#j8NHj>$o^HBCJ{t)8OJ4pg6OErB9FR%5X?egN14X2}9svT>3OP zrosB8Nj*Pu*+AP4Qj4MEmCe<|)6}w=zc*sV40%Z(gtK6sWAaAB*0C-KOZFf_*Sbt@ z{roK(*oVQ%CzvNsFPTcO?O>zwrO7}))s@S-!ZO~Q=N*Zykx3dsQzTY*Jlbfw!fy-7 zjLJebZPAXknd`?`V~Z^Y+o77e*~H4#Auo%nb193rIZ8gq=na?l6SzGr$4nGV;r;WdT zkqg(|z5AY%c3sCVbczB4o;?PV#vDj<%y?T5geebjMT%-$#a6Bf)&|YP()}F-Z)DHh z9}r5mPmU3na>AZLzk)nIPvdj>WodlTSlZr%&9B>DHO@7pVLZ_$vO>{?zWqM=X~K8x zekj2{|NV0o!Iy?asoi3TgURf^f57vA z6itYaR=`^E=ZKNdm&XAW1^)SoLQx;YaIx(eb>)T10zE$lm_75OD0_j09TY_ylsTyN zbKY+)B`B^b__e39n4JF$GfFAB;Lm2kjZ!-Dp7NtZ!SM$ki0{D|&qHcTtsMwCPR&Df zumg+f0&%S6*^fhF`P@y%yp421-&;{Wr}MML{$ei_6!cCEBC9B1xITeUNXed5g_5LyDjFS*6!a@_?l*Cc2ZXvE73rkiT$JQLjRwqmTs)4QF zo@}_9Z2T+P;wITlIK^OG&9XhoDm}$o4-@8|;(n9jOqS{jO0`x^{Ui^t_D}UrPxZBd zDaR#c&Z%r`g0*$hLLH$AtgvwO0Kka8O=w&aKztO-Dncaa->BY7Fpu|p(Z+jA^C24aR zqJ|D2WqbNC!{gGEe}Qk(=_p4`U(u%LvSc)!%C@XJv+=DV&Ffc%DEjAMdgq;_ zXHm9h9m*$ddBu=KMDGdb5bnJX9(5T@&#^mzAgHlsWz%oR!FR$1cjA%`@ zorbV0+wz}mjL;+V_#*Q@-(d5zLdVOqAZvNJ`tjtR3GH(E#NPR%UOD8E2Kmmwmm=x4 zC@L*A?jAMXH-9`W1;97|;&0Tr-8YaX=Yr(&f?vO6tLlJRvYAD~CDmz#{2jp2(7aa@ zg_OsIZ&2W4mqaOrA~e?kQtv$50|@Fl`$`XD{T8ATiFYp!xV^zaJU!yv!ca23Vw4|} z>QliLO9{`Ttg8vAB&;O!G}nEoq+kN|%g=LRE&Zra`hy|lYkUk>S?K}F0F_bX>W@uL zUaY5&*KmV^qL-m;liPr*ZB%ObpS-ZR?FN$nykr(LkNpgiuZsB(l#vLkaH6l^SAbfp zf=eSSL@O#P^%Evs5^BMfgl0t=p*eQJ*sji%s1PB7yz20#@=&$*hkor%Us)V0?s(*< zq+gcP8RaN;W&TZRSwwn1OUZIZ;buqS!>0-edHs$;6rOjC2YC*mZOs);C1!=JC5=<_ z4MdF<*4bC~U|aj$yY^n83gtjGQh;RqvMdcVXj{y0e`3g>ovc-_XzYzk&png1U#lC_ z!`dLPm(8poR75nRkgKSFGu*RhjBOF9bQcIFlPV{Wn5%PZD@UZ_w$Z+cfrr506W zM~~&x*RltP-2m`_fOeBtwMmNYz2sHHA}y|!mWv{pO)OZ5oBY(RQaT%+qHt8B3r#WfpP|&Ek2!?UX+vhot>Ff!C`Hw zE#xc;-RKfsu@vnk47I)|VrV7KH|Pi*aX6O|*Z#ao@Z zn2}ksik|v5Jz|f(iWK<-8TFS@RM(X?{dMK@>urNKZNolzH+=&p6zz|b&Ho@(_#39F z<8C}Ykd!`5``-|~vr70z^9TfQFs@8Avml+khlJ8n(HTN+nDd6&uzj+J<`2cS56Uf@ z|MC%{3oifZgEzcB(0ev;xHABRjr_~(y??}M=<5=gY6toP^LL8G4Dp5|Yk4>NQeIWv z_tmm?$PyzeOhcXC`SzS-_6P{KX+8aUX_}HXpo)^(*3m=_nE2vZ`HpjR4X_)IWKxb~ z{Aqg>2QJb0oMNDkd15^oBCkM z;iwIYXx|(lIaoRJKiP5W#>CIQ${~@i{{We)~jus_AcuUr2k{uNK}g>@M~ z+D$eFvNi^+d}r_|`@TSXMD%-5N&K{Vez&iHq7P+_e$8MNm0_b187o$-e}+oM6bc;9 zZa;1U?Fa6FYLJyRN`PTFEC*S+oribE-qKcA#X|024+FVfw4ED{ocoSsO-ip~a)O!TEpRjy>!&P`PwK_>yP%Q+mDtg@lDe~0q2zj|ZSMX0T< z_Rpil1Ye%ca;m5|qV&gWsMhhs8@~AUQr`d?L}9<<#(%CuX!R$`!~w;~mCCr{_{y17 z_`3K8viq^k%y(vz9j^&F_sOn*7U$KEKdp-#h7#fNa^;(OreD7!hJk;YX?WEc9LMGJ`5=7-kHhZwO}( zbE|#FuHQ5iv&W&UN(siHbCq7GA}V7Jo5U9Wq_C1xFq=86?}Z~E1Fi{U}Jhz?0hf3We% z>AHYQ&U_y(*(CMGm*kp?Zc}em)5dY(`0|j{XwP)3^0)I0jPkt98JI+!yWx1&=#1om z_RGOx!}_e(pD;CvuXd(h8i@rk$-P<6E>Zr-JVQ zD9vuF>i#)&uU-X!@c+ak_M_ZCtqw5zQtY&5^ZOt*q(U50=Ktwy^uzihu&3{Va_Sru z82X&(7xC7P#`E!)tOZSZQ)oSh&(v-mc7FI?{(9>N8id#S#dZ{`f^44ZsuH{k?)1Pu zPs@|W|E9zsZOC=MoSpV8c+d93(lo8m^!?B^=~I`{==)!kpMG^lA^|S%r~?Fmaltg= zJDFmhKMBO73;x5IYrW*N=wt?!OoryEnw4_4SjZV)KCiV_wXt8?{{*VqC}*j~bdF4>_N9J{ zL$iRvNFs_pH4yl#Lnd#D6}^lgCHSq$PF>0%LCyh*Zoa8!05Rc-Ox{cdf|6s|teMqP zdxS}cl^xX1Ws%YE2!7SVyILwD9@Qhzp(!wjDwNp~=6P!g^0jvRJz@Sofol5z1GV5P zcc;hwXw=4^0mF1d@J`W;>r}FGi3aoch1;BV}VKvM?dxXm5(*E z?HkUQ8~-vjbM%!GtSJlb<4VINFi6Z{5^X8+jx`-u6P3?ToX0D;&jqB*>r=4(F$N`1 z3dczZhu2S%wfOGXc$9=79DJ9O5fMEGj_vQ5+SO^O%bq@GDT~u&(@-a&*W1G78B)y~ zrHb{ee)@?xS_w?p!8+cO?`kx!V!1R1K>@TLmcFoqW059{81 z1BcE$(GxnpwEjfuO$y~}%C&!^02)OcL!}eg)botgVVF`X_;=FV4{2C{hOvkADvN0gJKCBq$cFpw|%`zc8hrb2v#``+5=FV=Rm29#|gU=$uLJ7tA&JV8WD2 z&dw?JRR1`ofBcD@FKzAFgoV=uoSMDHKaHNWi*!<$@n(#_7U2YQt#i9&8X$}G z1xao2iyz|(z3O`LfTmNeb=T}Gtu@QyJ-RxE`LXwyY(Mp>R(-!Pg z0V~Ry?m{UC3s}twmkVG7M*PLw-C4XSJ3u`2@LAv@VT)sj$-at`YUS zUnbd3&re$aJ2Z`PJjrFFrk$#iR7~X{BZqB0{Nv1BSagwrA0ya!a7r^j%;CVoynu2& zDG@Fb|243`A~Rs6RRUKa{7G;MV9JL*MBykcMb<~#$A{e)9Sq;6L0W^=U6&KjY+}>{ z&nGL=LK{@m*lF?-Q*VIQgp>It{;!0ojS$*{7-Dsrc8Ph0fdi?Qx^?dT72pfL6$#Ey z^+JXkp*)5{1H>wHh$;V2aC<++28=mWK4Q+bZ9u%ky@u^Im|%<9HS)OsY6&p9CZ-wXVvAgV2o!8 zB8f$qY!ULd+VkvtPk8|_N3Yg@_T9lNmwpEF z3>YAGm4Y$$Nf3>dN8+)glUkXN@Kw=H>WR^l%_k<68@C9@)(w=9kr|1KTDAx0&BPm# zS=u(y@`_o6Fl(4v|DufSi4a&U$MXsi3Pf>CNu|J&J0aLQ54if~d3b8b0iL$qP!{Gu zsMC%NcI}=D*#Iw%x4ywqTub}Wy_!QllKehNMk@bxQLP@0rHReSa-kSOg5vO=2J!iV zR@XiZ-&x`brjG=f6sd*m!=4d(=7-cV20^Ic0VHC1LGP|YtEDJd4G(Q--#cE@R3&TT zZ;MO?_gOL<;Iq?3DwiKv1tr6r(l z?Gl7;x462#0Nl3KY4y+K3?0sgAAly8UbzG+ZF=DOM zPq*GCuesibZ&g+AbkkOZKazwdQl9k;84O)y<@ZM8F&$Ze$kD5Cn%M!y+}S`up-MuH zvnN^jw@{}|Ks+!ikdW>qT9cuRQsUtpS*iA@xJ4n5I#GcSB$b{(sXrOaQEl$cPq7N< zD59C#j1AF1>3i$M?HMZbJGl*rwQGm+T^@=>&cVzSjRZOv;R#TUqaW3NRmNfx_f2}8 z1eFzP%(J+Fxz4$Kj>AYOr&m)7}8;@5mu%U=lF+zxhUggI}S}$@1ZU zEbwluL28tu4y~DuzrnA+E%1MQqrcmn$?ud=wM>1v(sQiSIi$|=PJj7Eac#~Ca_+&* z+Su(_-us7>LHDB6^VHjLZBDMd>x$KBTtTG|3#@vg+Gh|jIC(79luYBS?6w~JnXO8#r=6Ty^$@X19O8R7fwn;=V zH`nsb(TyvsPxQUr-USP9t*!|A7+;@!W_VF!Ztnj5^mA{={f&U!-pe11Zyh(*{h$6k zQQP9)3`8dxto!c_>#h495*=)Mhw%Dr8WMcuE(jyKU0LKBsCKa7zED)bphTaJqBloe z-<^uS)_#EVjrK`t$BN;~a`dv}h);h-o|xg>%!>bGw+;YbID^NnU#GPTKCAC@Qfy(%v(RHr1Zh(3}# zs){nU;;XJzzCTf2mw$D{Wm>dMw^*4Y0&=X)U2awu17p?ssIp*_RZJ|lkB*yfZ5dZp zkGS(8sOq%I>&jw<-0R8~xN5GoY?kj{EA0by3zWs=YuF1IR%+O{8;9{feu~taaB2G} z19R?+SD$DoF@!EG^?*afTuK(Getar=4{H%BZn%wTY7eJ$YLY`r<5dYcwz8cRF+O)f zjj^eaH;Yo5_tf6`#WFM-op>atHXc1=D#H0Xok19g8|-$k`~{d584*yYwhFaA!LomcI(~JF=xV7k{Zl zZ#+q5s&P}GujP|VH%-2V;ImJW^{i7n_Xc@>VlAr8{3l~oQm}6lMU8nsEI^J_!|wW#BYE7ziDLhzT!ltm;SH zq)Lmn-NQ9WdD>#nY>2&IHJUQ;OR6|5p2WLPu`>!p^vX*U`ACbX(>$eUP1kWoU7x3< zqb%#wYI+%$W<4mt(%F6cZjFwF?gWe0kVp_ivO3rhXKnl5^vvxj$z>PU(e#zJ6Jw{# zIc8_4BOH_6ew1?Wf+Ggpd@Ec0{ewy;X5k@OguXs8o&OW%Yb2CHnlQB#^ls^PxuSYf zQtX5N)_i6upoTt~h0DZlUeUpRB`2XscCI2vzE8MvRuf-NcMU#$tdVrzcwOA~wMB7K zrK{2>#S1F^XuQv;bg>8h_q~%#D?a+E%(!Q#T)X-@$H-=>oRs$|FL77#BZWivdgpY} z%N`rWrydczMliZ@7Km{2$wUQdp?lf|kMdhp&9~C*Wwi`>?{m**@5Qw$zBAbnp=w50 zY3}5lX;O$60=vgfjtYz3*h)GQ#My3=CzmLId09L;l74w8$c0hhj&|MBaxq$kIAzi8 z@+SL6G1@AmP0?~TBCg-%*-47skL;ucRBKGlW$1x{IK}cRC%fV3H9n1!rr2KbbijgP zm0)FHw2cr|UBWG!pE4bYY_+YI#NZ;a0 zAcQu%jp^g|sDV0HNmk(p-a_Rch4ayEO```I&N)raKYkmgS@m8Ynwn z+USd*2k2I|kAcRE^Xi?SooA(#MfE4wY|$OGGno*+fZ>(hW~xr~aQ)Zy{gHKf_k#G~ z#|9;A>nF{XJ$Y6icjmj-U&|=;hK7uYRbr#%Z%NWUYICJOt?9OoWDS@>hDR2`y7F|? zF-1$N&tS34pWW4)#(i8GwiA7J+i3?|J*WJnNInMRb*?p3<^Ssb@XvA-kEUK};N7R)WW%sld?es7fdGmD;_n znUta)w(rXD@`*tZFxIb*#pG_cT|L7?``AvE)Pd$Szb}E8rHRsSxF^n!GDRa#tS!&8 z=&BK4-z}=|WSD&%bSB0oD^%CMkjkE^PjzqgLA`T6_stw$Y<;)r@NmjTW-(4zEME zTMI-#=t;g@YTI#Ym#g?_!(P2w%0+58a(OIMBcmU^OC9Ci{qf~V_nW9+UU8dNjD9K= zYdx>4x>YrM1D?B#J@NQnv`OR=T{^Z&(Ba*h@BJz)B>n~QtK0}dZZ`!T|4pr{>rx|8 zAy|Fi59S09pNzd7)w=CRKNFfXJ~3YBW|>8{N5cJiO4Q(f4gteH`T4?((fSudUegV4 zco@?!<Fg~lwMxTJFKG8r<>6d1(eLaH`(y)*ZXz)x;6KKp!p*)SFZ1F z+11(h-t9_0i(Va)jCyy>cju2jsxmZCo;W>0c&e-OM>wj6K~=evQb-*!AQY zao+E|!x$GFqxbI9_p*&g0TPcBs=TSIBJ?-&Y@e6)U<6(!-of3*Yt(La2Aukps>RzD zq}`ftvG!YQ85u6!mfE_U5F2o8_^w`0)^P6Pzr=E77%sSaE#p)5Qh~#_(&z10E)e=y zPZ?+g$P&!9{PNc~_HE=Rl_ADzi^z*tFOcDw7r(x|eEwrYj^v6u5I`dhHVgzA1}5Fd zhoS=!D}lskf#67d{s)2fjSxzoAgatD8pEI^6(kB9#QB-900}GA4(3#)W#b7BPlWKU z1m|Ldg=j(qB4JgHFbSWK8Z1piV~7koqyYo77lI`ShbkU~D5FE#urM`rsQOB%=2&R; zJnSA1Vn{Yj-!RP3CyY%$z;q?d6iRki!g$e}S!YC4FvZ~;g=C*LekIa+)D^*3rfV`5 z#zqxUd5R-2BBCKg{Vi;|c8@<%Mh4N`BSsn?0-YY|ITn^!d1G%$9FdN2c~X3 z2pree>;T^93eWX{w_&5&W}`X^qs$Bg*u0{>BO^S%n7V~PDzV{>&YxdYr^5| zoTT0uiuZHz_RyFLRX`aMaXA)sh5FrCAvl3AAHY|xP+<>N5@+-Xa)pv8Xj3c464wqS z84hgL8 z@+vY>iWXrK8SOe2Hxvll;E1R&jFwglQ#4BTdXfrmglVp(ezM`@kZ0Yd(jk+hiy&mw zCyXC;jh;G4&Q%3mMUvo5Jy;x@6+@Dnm1Q%Y_1!i7jD^HeI@I`1(~{P@62zP{#1Y1`l_%69<51EFaAMYXWZt}V z-aH|R^~tXEmqqkmD{{ z8bT-bm^5-MQ`blhHpPoP)g}hZ=7Eh1vyBoZd2{4>5p6gQaAMR$H6)Oi7-)|uUk#(m zir7cPI%x}-?77q=1BPrE;iQPKDCP?_NjFtM0JZ>UXTy^zgvgYLssZfn6P>cMtJIQk zihCt3Vw*P+1S~;Ck)*2u4x&=nsAAd)3;Iydg3Y22&|>po*6m?Zgj=!Rq1lF*B%dA( zj6|fI!-3~Sv(hCfKazLa#JDcr3yYKzRJ07ARcRo^xid=cqPVCt>$^p|qk5^T9~_ny z{bVry!wOjUDCU{2U;LF%*{pUl4_y?9755k68k+?KgoQ78OYGH4KzvA7x(c(Eg6oGk zs3pl@V+HskcLPaMq6U~XjJRoE8D#i8>L_)dy7=_`5nPTgsmm;dPLhuknM_;MEriU@ zs?9Sl6!R_3J4iMgBXkGE`SKz2{Iaa=6A!bpy$vhxUYKbi5gjsqEQi!_#ulBVRm+sM zt~6OWs#&-;$_6rTxwY0DDG&0KI)Fk3`BS@@HK%qA*6iX?EisvK_kz%SvxxMKD5d4oj_)m1q^%GA5JPlv zZ5D~6>gkO9$YNQfI9>Lu)ecMgk{RE`w!pS*9)gtFDC3w~rsFnFjRu06wuqWi#9U`s3-Tm(G1Ao_u9E>s8b zK27YfAaoZ(dQY|`Yc!ACXj$>it_S~YZ!~rUbXWPksVJx#xT-8|qrn)-JEFC;8$86_LMazF`k_rE z-}#YLQ%#Ido3|5TwTaC*KJa}_fZ7>GvAPe;0t<^l9{uQbAgq~2_k5>_OtOGVFa&Ht za%Ey^jNOsRzQf?ej`}wh6g@+DN!^Ucgp_NeMm<@0ti&GU6cMiIg0qZw;}zg5RvhE@ zHw!q}q$D@1&e1+vlp)eGdn6QvVOt#`yoSVe?mRkgUAG@@kOh2}9X;3RhZK#1T?rc< zkq_Stf%=PTF@)hcp|v;^@L}%;lA!%*|1)|B3(n@%IQ+1uqI)vxm=H7lR3W=(T-qCx z?@#?oBO^f#*@l7X-R!Hmh8*?pyU;+gxDxIh4}dL02Hu1=V2T7~5Z`YgoRO1wz$p@o zJ_h($+|!BRu9PQV%>3ms&TLFePS1}042QIlZ))4D&T~&4hX}U1z}kI2Hxazo=J4d; z#^aE?nW0BhZJqEbklf2>n(5~?(^l_ax|6pqAgA-+a4nk7I&AfTuPp8nK19~aW}FHQ z*_>y2{{(!!IkTzp0-Tgyi7CpRo%`^9hHQ*<*Bly-0{5A53*?Pg{UCz zK;GKR$?n?5E(F(FFIoG6zn_y`gE4OlUKyE8u?suJfR=nK^meaxs8AmmB^3$d#@L3nt83;}SyDPPj zQ)jE;PDt$gE|L#THgzw-05}>`R3m_>6=%Zh$(ul^JT-K|mV+QK)J<%026aN!&;f915#Tk*@+5)6V54&QF{ zrluH&RUSuy<|bW;MxMT10L?+bfF-7)P(0G2!Vl}2+UWB)8%jMLIN0w|Y@$n5^osLl zq%+OqnoXZAbu)=7j~|0QKjt)@@~A%aet(*G%M3Z%)dd>fDyAu_ct7(~X7sc1Q06UU zGj;>i|FYcS?W^AU9pRae|))e+0*!J(B1N&Dkz*lt0UcP;|Kv4?9Ouh zxND!k@2i3Q9M|R(TyO^s6OV+IVhNL3kj`&@1PVdve)Qb@!6BklW) zwd+TpPLGI*Yh)QdkUl%!y}Q+Y9hr)GnMGG_8O=@q6wRy!tI;_AdKZvu7VI%zbkuiu zGUn~FQoW!6^P75_MCcwZ{V`k%K=x~mSuQ151MVLm%2%KG;a75(Q^?R=*l0f?`kWB{ z0H$(D8Npxu0D2()7J+xIm+dnb-aTxj%MP*G#Oam5M-8*rf$ul)g5VZ@;4QmG)t(e!2y*6Ro$^jr&>f`mV_LkEQ&Jb?uh;3|D`3p@yURBU6IQYFV7YcHmy5b*pR*mq zeG0x$y%@x2jhG`Dsz6LQHym=&Y{AX1$nT5*2aiKJ=%uhU!k~drQmArZpkP!7 zhi>Q!mbJ+m!bxVhjGN1~o7K!$%+h_Qp3ZxxFO>HFo@TbV^ZHQM{e7Ho^w}>k-J+d{ z)esW|t~|#UWKes%Ts;hyrdS2mefH?IdRwuSD27h+jEr?9jLy>P=RqPsC4np>jKV%r zR-?<)2sWH!@X4(2+2yZGjYXcJ(!TU%hYR zD^wh&Nn{`L%i)Hn4$E~9Uzk07;H+3imc!aI@PS5hw=9K6*#mXH)13KunE0CUS8Mn7 z;*De`Y3fst)W$mV(fo%`k0Y4pUfW)%-`vee+4V8w$8xT1y^I@F95XFMb-Ywsm(*fB z_4;*rc}0M%Fd=3yOgDz4R^52F%syTBV{K==_s2)LlFX$s?6+@pcUF8nwfSH$OE%=N zj_{s8av*yxRbGW`!Y^xt~55zdyA```6ya=!l=*-Ci!C8O!T>(%jJ z2?9$dGK8!ra@AVOr*pWC+K2v2ul`W=WPi3qHHGit1cjYWiB`#Py_#>SLc8v-$ks%| zmH1`nN3y69Q+x+k-yY z!9}+Iw&i@m{WOh&yS-h%BU>FeW_r87f7%?xMdaV>>pA~&&?#^7vak2YckD(B8O@8n z%O7CFrF$>Uw=b^%^%>@Y;AKfdAoyFwrtI-_g?SLNUBx_! z!~e@A4MR{kPiN`V+QOjC)KAj=?CHmEw{}wiRO4k&`%%)iPs3^4xt`ht5HbYnnRRl- zIZ7NT<{g(E?mfP0va-#y+Kyt+pOqq=%I|w?u$OLnL5s*&BcqGXj{IECL)UoWqX#S+FgwEWRx!- zRwQ)yh2of&_pozNy9KON_rEKjq3OU+&64fv5S zs<7U_m53ei-VbK^`E&d3U{p1sv4xRUkV-X zt)gqZXl?}_coS<)vR8jHJac4Y+WMhrcH5@+bG2FU`_W98j)puCR`^5q(M^CFzY-Qk z6A49S;?Gx@eM-6CtvvMNLi6z*!Qc#ZsEXVG4OWkaBJtVSs2r>*Q5)Mu9ixtthuv~@ zC(vN+$ki#=Q*^w==yVTxwZSg9L8!i42dOcuBs4enh3Y!j^QkLz`}M8{P%#^Q@u=dYm4#oFiMJdG?E zI!_13FQcOU7I*fYR)&Vp9|s2_N?BUk6u8xe$*^6ltdgrThfN6&3k-ER4%u!}$~4_l zqFcd&X_!Tux0B-BgP91V)H}eF+ATL}gMRvOxxFKkZS$YZk~p2zha7k+KYE!L9aUhF z9Bo)_WkY#I-t&kpCF`5po@j-K5 z#2-b*{|!0ziu&ueq*fzqO;M>s-8l7;|eAwVS}}T_ZG%+7~rh3RLUeGky>TQ-FwaBkMh+ zEeS!|!GNV+7tab4*aIJG$|~q%9|O7d&)Jfcdz^xFx0BYtb$#!xu?X|WHHI&iJ5;|> z<_3JHM{f_nB3HBZMYEe?Z8$<$I#BYwP}x`re5Zc^kShoQNkQQy{X zq~YL=^^<6$o>(Ng1tp(^YjVldHfeXJY=rLH*c@GJhqqFrH*P~Xj<7pW0++EqbXfMQ zSlj+vQdfhj`R)-p3|179>||gT*PxUsJI0#KVFP01Bkt~Zr5;&Bevp=UNzFib!72?w z(x_alC4$Z1Y`|@=B|`6}rMYV7%ffFhc}j=}86Q5@hM7&Ykulm5!H1^$koXHr|bef$}Gj8qb)=$z+xkny6~1>$YTswx_@}5jS^r z68sPfENH5+TLX2+MlmJx=>d)5Q9uU@Zgxujqn5CJMh8YbI@7aG{`A5+2f-4WDNKN8 z?K9wE5N3x7yh$)XUhnFbVZDVX_q{A(ZqtvMhSKu-mylD(EksAoqLt#jQpM2YvK2H2 z?@BGahEO}kkh+KEr>d0vx26O&gNu1elGDtTAWJBD;pPrZLB|NE$l zWbWY&DWRl#bZX7VCIidDVHsHm9XBa<|9nnTGpu^|O2(L5JclKhxU+7{k zE%&Rk$av)g&o1r4>!%Lzfg`+gWpu~K#HVXJ^zWFOKl=YXwth@Q7RLmgBhqylPY4;K z&i@gVR_8&~=~3l(2iEpW07;ZmJl7oVyUYnnc#M=~Ld$-a4bVIp5j^Yfdg?2;*`Khi z;Lk!n5v611rz|LSinkT^3+764 zg7xx{WcNFWM0tip^C#7tOFbWE-Ooyb0`ugUrQA%cEcPVsapnv5hQMd!RNhqS0UO?q zTlxW4-T}!fk8ZbHf3UOpB*`}>`CP8af2zVAH;{SZ?FH%ZqdoBgL8X+udGrXLfq=n; zz~CKMxZA$ldjo%R8rX?}HkD5h%ZUGX6-#_pA3j6UP;O)gi(?2o0z~S#Lj4Sm4u<>i zP(y;4mVNQ&JtWcIGqQf~RbU}ILEGuB-({bOW(04mAh(o}?aFYxt>6eUm`30;Q=V`V z%K#TUc)zy?h&3czF~nCdOg}R07L_IWw{T+>fVtt5dRZt=JQB7GD3*nSudvSO_DFCe z+`iKG(uQz$-`UWPRN*XG`yinDtFP~9gltlXjsddC3#VXv^;EcqsUmT+%Ah$9Ge4!0*6AHb^uysg}L6SbPF?7906GCPvXu70ViuR6D22`@RLW5kxsYCJQV)#)= zbR!J)Jse{Qk5-LbMEPt>#qXUxPxRvPq6s2U1Qd_OP8&vlQ?b0D4n!En5z0N`s|3zP zc(R~jn>@%!SL6N_7=*xOaMMqO;K?2ec|l<74UMkw;5wmkE+z0)$+QLXhVP={27Hj{ zy#(ZFT+dis&1Mj;0kGW&PeR4ns75_R`7Bi?s`>ErdqrqnDGLyMcA{J*=Xqs%(=Jqv zCUHam8PqNgP4i4-GyyCZ09QlSS|mgQ(kfZ(e^q#jsR4?G5Z$v7+z4?oAjK@wb%QIk zpCIXjiU2vt?-nfu{z#lOl`m@4y++n?cO?lwDYZp45?bVXhb9e|(g(~+1}DN=sa&Ac z5cF6=d?Oqe;6s8*2nD35oD((60?@8r7v3rF4-k&y>CS`{I(8PczFrN;xDGBC6=`H* zRfa`oLVz@K8yTlH;C{^jUWJSYon(TNQlrNc)QpIY3EX-cW7K?}3!@PW10JSi*{VU- z6csn@l>y%>Q_r9=c);*Gnb|q2$Tg_%rc`F z%AMKdq);nRvn;qUfV)b^ES_c89TvbyLkG1*;y-l)|_EoExFy0wpj;LU)PALE7Y z)qZ@aDzK~H=0QvzRqPTkGRvZ3DLSB%&fMT4wEu|nf}`G64&G={(UtAl<(J{_i~L3t zdnukFHxbtwSdHJGW}}9DpUn(9N&LiHD`Tt)cuK|W=Sh%LBQl<06A6E{RIcC?ifdei zcET#PVQ^a*%*_vcMVgo&9cv7$XZX?-;8xFGQ$=V=*s~JTB`S5zq+~T3Rw4vz#4%Tc z;3bK5ZGO2-)JX#qEkAZ!9+NiH_Cu`rNas{xC9|d^ z3s@*bfD1cu8fywa5>r^Rh9!;xoDMZX| z_PpG^(HSL+7m)~gVgaA(?pgy7Jwbx%3K1oEeY0+z4p<<=EIzXZC{Me$brWBD78nOW zRPw)=Wv!i@#g|Tmud$G@T0k%uqE-y#^ap+qPO_e2m`&_mo5eTAzt_Ac+2Aqe)j|=QVv-D!HoxE!dzMBvl0N9%aLW9Kj!~$7a z2s~ZE)QON=%Y##H!1ExuZy=Cp7GTa&nuY}H_5hz?Vd3!Mk$xijJw!$hqD{MhL&Lwi z5-}AxV0DeLkc?<9Q2>wh-)uYxzz8S|wEcg$_>(JW4UGNg;;&oGs-UI*R~|=(5Wakf zSA^bFj?|N*H6!=EJndPZ-+3Gdvso!z(_$090S7d8&0V6RJd3zI4zslA@@l<09N-{K zTGY^>!5Wvx@urC{+rsQc^Y4p)f3^6|>$j5`&Uy;6@4hi=(m3jY)HA5erdBGgs-x*O z@~6lJaD!?Ojc2AhpNx&=E5!U^wft|n_&4aej;HS4FA?myeM|An(>L9Ae9yfv&j~*j zj6Qz7r*U;1xRM(vMIAhQ?LX1mBp-;7$DXUW3HQd>}ZLTQI>k#{HD61%y_9vn*5g1 zzBEpXb{m;;yI%2~*WKHMX~_z(B~A|`2cuURu&gs9Idv}T@=RC~VQKV6-T0oi{XEoK z!+j~rG@U*EATYU2y+)uSIgn5 zJPI&&=;oeKeBXlRD-&oPkSMKJ-`=hvYr{)fR2+biq>>FFo8H_XWY0S$9b~}AHU4b>rYVZmwY~I??f04TGSA;X(GfD? zFrR}^-6}%UNPO@J)jSq&RUpfFAg*R`udXdf?(tjQR}MiRJZr5JxZC?xGqhf@@J*XZCfL;Lzp$w|OnIF*qvlb@$556cCs#qxU znEmgFnt!yg-&^9pv@qP3sGR#t3;T=t@%QZJ?}(Z|_#)hv_^pNgp56QtQG;WC>`eTP zFZ%LVM9qu9Klq}?E!^xTKTZq7Mb!Mk7j-uOncZBU!ZANy;Rr02*WtSii*Vk(%tz_=ds#T<$6mHm`{5tv$9}HIGLHG-vsbmB z@Bi&^zaS98cTgBg^?P=ctNOo~AIf}(xYcjF}ucO0?!f?K$%F=X)qpHgC z>Z9t~_M@Yk#*r(&LJ9Z?g`{}C5aihZa_|ppj z!8I%fOznj2hjQ0q2N06)v4cpJYbQe#22Ll#G4#>^!mq9msiUdgA9)7NWRCN>KX#2*i}uOvR=f&8f0npakA63Lhf&A;p*4V@1Jlh5b^iy zCN>bNSqP#Y!$4%PLCDxbFt=(y%orO?GgSzY9P20c!-lXRil8d017z+FbZaaau}nFD z4Mk{}#f~y8!xA3UC=@nSx%H}CF3_!T3q*qsWWGw>LInF4l03|TkWiik$s$8Ym{-7p zuG(ZEbP-S@H?wyXAD&aK1!c23DUzv31r6gcBRxER^%C){8(8 zDU0xQ1p#MV39egg!rc=U7>|S^>g$TBtynPlY>5z1EE|+&))whD8~vci%F!g$njeZJ zqF_>>8Nf|j`t-wTipdkfJZv|De8D%2@xlKz3A*q=ARqvUs};Zi!hchejDVKF5J2jG ziip{QJHh`xF;fpnF#S<9zfVjzE2S95-_!28TPlg1xD)db%b}hwWS#DDu8Zp)FaZzN zd`WSXBrb2*2g26Md)YVR_phZm&5DDM+w+Nx+7Ku zmu&P05C|z)c|})06q2hG9SY|u=4HIL%`GgG3oN-I9ShVH%|0O`lH8Oi))ZqDVYd>s zlX8pgUGpdkYu?Ee3Kz*`bRQ$-T0Eg+1}*gy&=Uy-ML7EU$jMT8`^;ge!JA1&JfK_d za*VBW#gVcNo4O-}Wvv4+;ET;>2!zNqF?_PcQo^{PEL(qD1W#aavXIqXlt{P^QTNbR zLsGFpwnXU(gZ#gdhWfY_P7M&kt?>9iHGwOO7z&@9Pt3=)NFkhv`T9*&onrZDN&&K= zOdWP$JflD`;@p*EJc^4n8hof@p%g2?KH$`OQaX|)_ON>Df7S%ozwUpkxC797dOM7d zGH|I@e8y3vpe;H zLBKG8$Dd7DB*!lMKgt#f3MuX4;TYT|?7`s|<)8nO_`L}qsU$!zfl#C0)J1}O#bTB2 zoVZF}64%RXET7Jm4Y|9PMHV<$AfLkbmKR%iujE>q`t&%3u~4>3f^yzOn~h%Ty*4jK zjbzkZt<`w-uxgU*Xp6C&%R`MSVDRO>?K+}QX2U}m zHD+jhn{A^0wDA7_FI(;^1d8Ccl%|-Ln*v5`il+o2w!nicWyW|#Sta|i+bp8KZVIsi z7>cpDU}mx*P4`cRWCOUf&@Ebo`#MUKng+Mwm?p%&#E^;y%tnNa3bPXv$*+OnNtj$I zD_SlmD+Du*(*T_KPODWcJ)_5fhS<=!T%bU&KXz2?Q=uG4a7ytYhS1%W_b$Pc*5)AA z8CUD*OfcQ|Xeqg=rdVNJXg?e{gKX6lCEcFyXPaPHKu9jC&IfUs(sfMSh)~>=M+$h5 zZObt!1H-OU#iI~#I~qe?x4NDZWeCcriI!5l=Rf(f1 z?)BUs1-CyCV*~m+X|sfCWEYNyc$0Q$av3F8sn)~EFw-}}6dT9Hw0hZ9AUP~!tnS*% zI#6a-MeT?T@Y)tWM01Q)h0zm@I21+6Yc`ZQx1}7A9GCRBkb z`f78ICo&tAoAT<|PKJv+^G#KK*_+5`GY9=Is&Kmbf)}N~0H(LH_4o|{79C_C=-PQ! zn-yLbf2i`Rn{Ib8s%~>gb6!C|?)9RqX}KQMs|uv2yy@d8`_JAR0qz4S0mT3L044&& zP++tYJEoSU{}Gsk%XGzcQ_f{)))XU)ArZ2jMfc`Vuxg3hfr_+p$`2G+f|#j*IU`!R z@z6*0(h8NyIrQv3<(F*OJvvDjCnq1FsCkP4ML8Mal2+ED8~15JO^JA9tibG@9w*lm zIbuPFo%q5nC6+jms2S8ZT$cwB$Jv$n)=ekIFh*>iubyL53Eq&+b>sx=SJp0~(gZQm zkHuxii%tnqv0C#G#4%i#35~R>*`f+kx?b4H4pB&z@y715Hg1jN-T(oF+r1AZ#B&*EQC<|(ig$O#a~ zJ(+@ky+*FTUL*APYt$*iy+%>8o=6>brFh0$GGJQWM~cZ@%*hm)^V<{YaOnYtaoz2y zOnTb&P}GwOjr7|OA^(fl_{RvRe0gqiM1ol^eb^g}FZ<0=zu6`sT*=Yvz_?v$W56?} zy?&+8z0INQSlrpP$@0y`ng&aw?w~3u_b)o+KW{SX4)f`l#f z55E?|X@!G6vIC z>Wg-&iAquVirKBa3+3wK@&a^E{>~`nYcvwE>JL7L(Z?D#+nP!TP#)LRnRM8sl+~d% zSKf5{JR>!ccx5Tl?u(a@_Qt?cq(Aa4+4Y-P*X_|5_>BMrZONVIH#30cu~IbVF~0y7 zefAlmHdfRMG5OM~9@`d4%++Qek~1A=D*0#1D5d@liY+u2=*lNa0>hFe-+?jRl522pYAp*W2w4D;{UkTo@9(W*@@ch^G6CeY)kdsvM zBZ?GAKJCg*Oz`-c6(M&Wi-D!Zi&$$YF?j8>p%7EB&+5&ukte}{Q&ppJEL@w&Fp;&d zWJAm=mJz1UUSQ;9VR_mR4y8AMz(9vzE1% z*QbgQ;)`m@3dGlUXMqIQN(UhH+FdO}v;JbJIWs9~hu5Pxw;t{v#MZUKm>< z2Qv~g#8o$otAgqp2PXJxuCe0tw{FhkLx{w%N_-8_(vMvuJ)l$TFEV0lTw`(uRwA?S zeffd@!sOFp%e@8!(;f@R`|#2+!q$g&oj(s4)ipjmSdz7S;%(sa#GXsqEMM45%DYk6 z_UxUr=g0H?2)6sx6j8IK8sYrb6R9ho z-%Z+xKAEYt|583vaP28fE1aA|3?*xw%_2aMCJ*>9> zw7?%op9x+V;3e-P5hQlcdi` zOL?qSZK5Log^!X=D{^XHnOrK4KFEFw%ELdVnI(ckHYE2}c|H>AoY;o#?nz_`Sm3=S zyTL$X^(qIPE^G~x*cAt*%R|BL(Sa6!KK-u!B!UhjJxCl)BIzM0!JKO+U9)~}f^~Qf z=?-817_?B%dx0FIDIkeSeRqh7%FIFLr7ETHA?IVpl#RY!VC`Pt5aaNny~g`LCV3l93wVrp`ZTi zB}bw#-f&u;dQHz0Rq%E2oIE#XQ#_HH9*qrR7~M_oXL!|9l0(bs!V@7osx7Gt`MaX* zXB1*edIbk+HOdWAbb2HQF}p>DFasBdMv_dxiYyu7_nS&#?thh*vg8bsW~hF+r0#N2 z4B->mL0jl!uXbQ9b-QLeTT zB+fe9I0mAh&~&nB%qEQM!JW?F#(53WQYCF=K9C!$HaMVlAX?Vj?3~)myiSoxa_`zg zv_RY(gkEwEybygoD2aYbz&$H1DM0r$Oh*j=uA-|F0ri9HM(D8NB{OdEorXdFL;MpF z(0zvF;YT(&WschVXOlLk<-55tHG#FcAs+s+&*K7*J+<)h5TVkH#$AB|*lIDzs;Gy^YLsahz<{b~=NX3mi`A-ygS+7{cm5^ROBCuXCZ3&g2% ztIg(9>_ntUEx*=71+X^BwdvQbs9AP}@qDeP-*|%b!OQCc^xsr7=E_M`m({6FH|Qz? zlxK9#Rra#-a75IH7aB+5W!BtPd0ls&uT{7xd?x_h><^*MaG_T1`|11j@L4_g?0T=x z*|^*cx8X*>*rmkje!dc5nZv@Dni9GY1PE0s4CWP%#7WE19Gl)>pZ)u}cHv5IegMON z4u(ctvG%9*o?;QRok*q3Rc+et4_)AZ`Tt$P*w?BiZ_BxSQdc^2k9{LW2gYrg`*o#S z!30HaPbxS;DYk1vZaytzWEJ{T$o1B!M0!a%E>}gJkvfCKJEZIqrd?kd>k!Y1BP~aW zmI>tS*Ri_oX^zA8c*8^Ly#oX}5 zE(%)~6XS666KkXkf#Zzp_`*okaP$(cIaAt5wxVPaB3Na%>icz{*+u}q_yNmfX&sKO(A0Ng ztFna2D(gXXE~>K6Ij-{S&7jHiP3IZr_Zv*|G-U-3wc}{sa(E#pqPWF`m!` zO-bm2RsGC579Dk);=zcM@pv*faO#G#Y?dras;HNPwxw7!xYqsSPiSGK&U5gm-9>2% ztCz*9`0Ipxt-J#j+W6tRU5gI#CEAqAMB(8MdJTAT)dJAz#G*2(xpJaTFBY+8ToXl) zr}3i}%3J#ju{pv7b$*;6(8u!uB^jm#PIi1!*<#{Ck{%3yQ>evA^ ze=RM|9SLVTAPP#zV-1M|NZL*iOK`|G;S`lM5qFajH(H>@1j0Q8GQT<$!^2Npy0kTb zk6;$+ks6scWFmi@%BeXn`nvT|M*#kZH0$_gahhPKK)flAmlX?0;@xl_#R~g0*C-QM z?do_152^c86@&_1)!NWAiz7-W!_e6g<%vSIqZ@9Fo7m#^6e~K=Q=fsjW8#>^a;qf~ zPj%AlJI`y~{r%u|ERy#bsSY)JytZb-0YAs3cfjw&Z1HlEZjUs&zb1YhsPyAKiR=M| z#d&EbW;gyZ$on(8A6q)Z7~}nuwDCg&Vge2}+~V6QqTtt`GrANxwY*z%OlibxZq7uv zBOFBUE1V-Rx78GB&S>yxCe}*q$K1zmq8s^aUoHVmiv`c$;X~8?sW0scE%3;&nIUiy z)g*U7E48IMRHl40?5DW0We9_W1gU%*B~5WCSN<7QB%j$LHSpg;+yAA;JPLe;(*yn~ z6dMcgJjW?;rYIx;m#D&efww7CJRC~Sd%MR+xCEyM@J6pe-HS$(IB9Vf0kV>@3`!F+ zQ(tW1R2JQx_5Y*2GjWIdU;FqNgTYLVZH$RR*2rF#N;CEuMq_7^EMcgGh}5sfzRk$K zlYJ*4BxKK8L$)MYN+^;&ZO>P~&hPxrxz2g6b3NPjT+j9V3*Y7Qx$pP=df)F$VRDCi zGLEzEOcoo94~EF!L4UPEpq0RrPy>eo*iwy)VFo9$i<)a*)NzTyp^Nsis@j<$L}f} zs!3mZFY^Rd%XrT-*X)96Ybhiho9497B2>M%o={fWk~j&1A|~+YFT4MBCZPKj3fT6|oZ< zMDsC%gOT~5R(qbYmDy(=BXiPq(?m13lzd~b{0q^9Y#M7pj7cVrlHz)c=T8@4Bp~RR zfi3`l(=zDW=fBk_1HXe{H-C23(8KtSJ<=cmt$d3g7i*^%BWhA`GTb=7FG~7sb2?7G zz#vtHXQDBsS{$1QX4>U)^7l{Rk6tGd#j(pMC-;ZRLZpMnPx!@J>{I6a0NpcLs9Zgmhocley$fWY zBrH7tX|kAAay1253*u?uoZ4Fo#9D0J2|R(J9B`eVfc|mkC)JM6OPJIum-`>M&oyxG z)D})Y@-@pD=&O_MYP!Y9eoN2if7M`lhg*pb_2u?wLZi3?SdSEO1;W*Qxq>+GP_AGe z(l}=bpKB4P6u;j>tPuY-i5xvLgljhZ2%m;YUKL zJDUGfgXR75fWAyuaS$$qxGN3-`f_`5IBrP;B-ekT9)|5D|JdE9+%XP@F_h=9i5!FI zRWV>)CYL0!b6HqA)2$9yDlbHdjy>FaGF+eK!cJ@t%N1@VI77rugdR3kqFsk29W|%J zl5sMHwPCXUa2I?-xHLtzmBzZ4-1JZ#Vp%`XcYO`h8}Wkd302{hu?@j((lZ0Qm(wO#GxKch|napl)&L<*x2t86moxZ`!CAT1h<%)DCB zA#qIV=?2BAZZBaB?k0y}WfSv5Y_i|iR$!Xf4~gXc?HmWB1Bw8B{-?j-28(T0$KH@+ zvO5OU8S!&c>G^9?$@=N%q_X1oNhR84bkFC617QMJHgLm*hFQqSBX4mgSuOd*D|?g5 z5<&zcFsUqAE7r}kZm$|XQd_21<@DTbqonpfJgNLIWINJ+`JDa}lgfY2cKFaS)n};+ z^T@fwpz$3jR&~lL2zzQ2DRQS4juW}8b5QbZEWXVtk667a;TQvXqaqq>p}^-Dr{O7i z;m)7S0acJ9D2Ji#4;IH=kVg{AWh~jfxAyes9<{v^?C1OXg{K8s=J&P+NpKiTs_qT7 z{^CoE7Aszu?1>ZaOZy`(3WDFV?yX@PDkSdt(l#9p3oL(AEC2n{@VDt~5E~fJJl+12 z#X0NmoD?A>O2m(rU)f`E#+C8zeE6syU~&AamoAt@ z^DqpA$O9}6+QlJb|9gteK*NLgDTNjhLbi(uEiWKY<=+5b+7+5rr?qIeiOT3}z?XJt zhquomGZ8{U8)EvLYx=4$Ity4#mn@!OwfRBQ0>ygVeF?m;n@D)8nm4rL5cIq{R>?v0 z-s@+#m&ZS&UwI_l`o=?^Hg)jMWAS4FSR51Q`$oN(L}D8;7yRw}32%rWut!bsn;G-v;X&UVQO6*0I$jQ7ada)MSOl(~=!r>-IxSXwLFc{@ z>y(GSj-;qV>Y$TQFjC_+ zk<8S2mnnNBVML(BsOw!8|8B9B-BHexg9lTe*e(Dy#_jRpb`Qz7h zx~}ZEjbV!`-!{jc?|s{v^!fO0dpcD1`_7yH9u_BcHAuoBo6VxT4cV|7EJw|TIqS8f zCsspL`m^`>bhrPpM=eyZLm2%jOwS;PGpV~nOzl%Rk($F@sMiVXQH!wb&q3C8cgpyE zinN90q8#$6gB-a+ZS>%G1wsf1F9t?lLD0cQ2Z)O2G(L5XSvl2+nd?#;3ewUd=F1U$ zs3rj9D%UCrou>953j{UG`Sa%pMeplxMG_=BlnRW5!9>oh^e|?n#QRhicSc?T%MOK& zZaBGL2ol=Qub73^CojaHj3{mLIjwM#uMmp>8N!epqv|?56u)At$*eX5GZ_kiyY95` zLbIqk0Yiy?{q4-iR+yVXAm6ZUuB1#Q)Dd&|DqV2?1RICHc5>{2Vql<(4v*Xq0i!N` z;OBbNf_W$&w?Qnm-**tWA?-6NsY_|oG)w$>PXMa0O z&J=Fi(B;kZ{UqVab0>U)^b**U@@N)*mtVc`0d_R_ZHR0_=z*Q5eq^058qw{$mw{Sx z*>vgDeQj+iGHheq>8(t^Mu-kI;j!cN+f6v4=(h$HGqK?=?hnj13xif5X}v-NiRoH2)-J(b;~ehj0+`4G@8#B^J3>qV&y znwr9pFXFf)ap$yD{wzW;gBU?03~PVffJEE+ztIf=ee3UTKz^KHc2C@l-d_OiJ!ke+ z;odap;rX&Z$dg?};a~>5DZwK#wg_k%fE#dWy=bHWR?JZ336mPRw@0I%*jyS383YmO zp476RY}GP(RJy&U?O^<(+MY9;(ms0XkzDy>(tdgk{3nfil;!2oYs^neqHmy@5HS zGy^!ZLsk7MFJG=V`VzR&@@#!^&zb$qvZ-R3-1Fdz=0*#B`_t-NpR#4Ufm>>9Ddl-JN#r6xqpBe?8n#j|#y2ycE%k3h>c1yCJb;N*HbK%;g}uG1A5FMAQROz!KTHNM>3crGJK07>R&VL^jLXM*vN zCHKZBIw^G7=(!ad&@vdwsp^`YuU)`TNe+bJ^o>6`mh# z!t|S@f3KOZ&35q@3Qm3rdeC)xokzsWL)7MAonkUiSAS&nn(`_ zO#Bq(+n;-IyZedy?x#C@9&8p|w+4DGI?NzXnDG)z0;NLSfGcS|b-cgecwNtco8NlcG^|kN2@co@x}LsZP^dQ6 z^YmK7dd4dCkHEy8{zCQbo*&O{?XKVbJus0TfZq5Sn8@2p4^i95M$n41#P6e{iG*UjMek5z!$!Uwt=PaB|2%bKqd;Y#*wClv#CEhKbDz-+@w_?cTBG-OYOxc$qDW{&*XDt1^sGX3yI<-lev6 zKblr{L0tbuFKMePd7#Wmx$nhOzpd&lcsW^De_|+gtEPxh?rPCDG1{>8ppsU8$yxv9 z#E*$z&g{OIQ@dMrE$}^O_T(&jyS|$MIJ5gE=he0!(rFc5h5E0SNZSqL0~Ocm`d$$= z0zv)Ik2l!bU~T|TO4pNBO3sEkaVw!9M4cM~#x`K-x#n$Aklg&2XE-Zi2$-QwvPB;u zYYk!)kbo#kc=$6rOf#Z<+c2G2MxjYCk_XwX1njC;L}YPy2)3}OVJW1qv&hE_+E6f- z@)2CaduRuMlKq)ES7#d`2p!(F)pMjvf{0!+vvU0)Rc#W(dz5)Ws)Hj)Rk|Hzi~!5# z%)rP74&9SkI){%VUc(>HArB_EAG7}Y?ANCBpNrD#cb0p*5Skq7a-rYU0uOv#4P-Ht zhdYCm7|VS_(Fzo1*$xzHfG(#@Z4FhpiD54!GAq^3MDbIzn-<|kN7O5!R~vKpaa9H< z6b?E|r2$3ULZCvuJPq%j#noTriAjnH-{)oD710d}4^5Ahpd=lbg|;3r&w%mA3pFmm zB@W3Uf;Co!ARI-3m~jjRagze~S8oi>KJP^W*o2c5cZIeC3tF3bB(&p)-eh%cq$XGuvqwRyBq$Fq4(K&PHF@ ze_@zI{BNqYy$Zk#Wc;gIS2^LX43d^E@C~H(r@Xnu_Q3b@+o!n$=`PjK_<4FEI8rzx z)l0Io0GqvU(>ac)5?w39JJ<& ziTHQ?C@B^^5F)Td*jNPzio;K4nLZa6-U&cLSQ)N|gp<=evlNVS{Ht6B1umQK z7Gl!NjL8M6$Jw0tZn1SlV9amgmQpAaWU*|MTgg_@W#I6V+>~m+6sfqv3by(3C{C{@ z0uaOrdSxePyiUpES=0xjZ%0XK^?>?jS?SnB{AHT`%F;51wi5OpQxkilyk=xdq9n=Q zmQ;Z`KbqayFw5pA(`ch`LZ&j*yk?~d2v%6C_%?c04*Mg@WwmwT+82kmZH>vLD1;)e zEJMRwdZEL2B2wxJ*6*uZ?3TF|J#Eqc&*Rv?|5%B(DwoHKB=fEfoUIS|CD>>OuoP>* z1lYM_m-ov86tZW|ahiaM->`XAzJ8>HS??RY<@|xPDf_3BxPg}gcMo4(;m1E0r{{8c zbG{9)alz*6``BDvGCez7I%o+@GWQ)ZPdQfiy(YCPAD?S~UgKDr!ljACndV#Y&xs;d z4~+&#d9K4hjuhX}1&;2a%eKi1FKSOo50%>Ap~~(PgQW*@V8_lEYe0z;hvrPH1I<1%ImA`yHmpZXHg9tWW32)5tZ0t`v z+rj^}-Yc%fWvf|cO?CXmq;|-U^+b0&&G$3^SYUe?@#Dw$_Z;ag{BBx6c@ZlTPnfFFO=~|Tp&MrA3FZ*JrO_dpN(gDo3o|{~Ff9Us zFBK$SHGd(POGfa`=LQ~6UP!l6!xvF)#mIn{3dt&gEsP?)^XC0->6EKbC95_o!Q{RB zhQ?LUT9{K;5ITo(sr>xj58dmcT_#eXaw)XeFV(I(&%8+bc9Y@Xe?y~xYI)p&mS?I_ z0A}$|ML!@sL8R54)uhCrho1LW(JxKqXpVJ{iDMr?vj5767v$KoPF)rJCHg%m!4_Cr zk$xHQ&NvB_%KdJ@gFlSBGKvoZ?ZMiwUv~5pU#9~Gyr?Nw=Be8d+hQGax=ELa9_d?JO&+E!6uG|5H(^d%*R~|5AMH=k1lIQ z?>hc&z%$MH#9E!>ij}Up=qJf?1WeGsoH60Hml6Me#(?+#qTjzJ`u)o-&(|~sp#5|+ za6tDHy98NZG+cmc@%2lHD2Lgx+af4@blbc|1sug=Is(Ky9;lH1iT$wcG#CQZi>53z z%_Fmn{&FE06)XT9W%G2oYqF@dMv}8C5+>aPIeg{e)?Qiri^nNKsjYAmAdU!<+$GDN z5+>*+jBdz*$i=qyyXfUGriO*c8Y#np037xM?hFh|h)6x;5K3BwQ88KG@VRPkdeZ`i zYaA0CC`C{1{r@Lf` elements inside an SDF file. +2. File path defined by the `IGN_GAZEBO_SERVER_CONFIG_PATH` environment variable. +3. The default configuration file at `$HOME/.ignition/gazebo/server.config` \* + +Each of the items above takes precedence over the ones below it. For example, +if a the SDF file has any `` elements, then the +`IGN_GAZEBO_SERVER_CONFIG_PATH` variable is ignored. And the default configuration +file is only loaded if no plugins are passed through the SDF file or the +environment variable. + +> \* For log-playback, the default file is +> `$HOME/.ignition/gazebo/playback_gui.config` + +## Try it out + +### Default configuration + +Let's try this in practice. First, let's open Ignition Gazebo without passing +any arguments: + +`ign gazebo` + +You should see an empty world with several systems loaded by default, such as +physics, the scene broadcaster (which keeps the GUI updated), and the system that +handles user commands like translating models. Try for example inserting a simple +shape into simulation and pressing "play": + +* the shape is inserted correctly because the user commands system is loaded; +* the shape falls due to gravity because the physics system is loaded; +* and you can see the shape falling through the GUI because the scene +broadcaster is loaded. + +@image html files/server_config/default_server.gif + +By default, you're loading this file: + +`$HOME/.ignition/gazebo/server.config` + +That file is created the first time you load Ignition Gazebo. Once it is +created, Ignition will never write to it again unless you delete it. This +means that you can customize it with your preferences and they will be applied +every time Ignition is started! + +Let's try customizing it: + +1. Open this file with your favorite editor: + + `$HOME/.ignition/gazebo/server.config` + +2. Remove the `` block for the physics system + +3. Reload Gazebo: + + `ign gazebo` + +Now insert a shape and press play: it shouldn't fall because physics wasn't +loaded. + +@image html files/server_config/modified_default_config.gif + +You'll often want to restore default settings or to use the latest default +provided by Ignition (when you update to a newer version for example). In +that case, just delete that file, and the next time Gazebo is started a new file +will be created with default values: + +`rm $HOME/.ignition/gazebo/server.config` + +### SDF + +Let's try overriding the default configuration from an SDF file. Open your +favorite editor and save this file as `fuel_preview.sdf`: + +``` + + + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 1.0 1.0 1.0 + 0.4 0.6 1.0 + 8.3 7 7.8 0 0.5 -2.4 + + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + + + + +``` + +Now let's load this world: + +`ign gazebo -r /fuel_preview.sdf` + +Notice how the application has only one system plugin loaded, the scene +broadcaster, as defined on the SDF file above. Physics is not loaded, so even +though the simulation is running (started with `-r`), the cone doesn't fall +with gravity. + +@image html files/server_config/from_sdf.png + +If you delete the `` element from the file above and reload it, you'll +see the same model loaded with the default plugins, so it will fall. + +@image html files/server_config/from_sdf_no_plugins.gif + +### Environment variable + +It's often inconvenient to embed your plugins directly into every SDF file. +But you also don't want to be editing the default config file every time you +want to start with a different set of plugins. That's why Gazebo also supports +loading configuration files from an environment variable. + +Let's start by saving this simple world with a camera sensor as +`simple_camera.sdf`: + +``` + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 1.0 1.0 1.0 + 0.4 0.6 1.0 + 8.3 7 7.8 0 0.5 -2.4 + + + + + floating + + + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + + + + 0 0 1 0 0 0 + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo + + + + true + 20 0 1.0 0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + + + 30 + + + + + + +``` + +Then load the `simple_camera.sdf` world: + +`ign gazebo -r /simple_camera.sdf` + +You'll see a world with a camera and a cone. If you refresh the image display +plugin, it won't show any image topics. That's because the default server +configuration doesn't include the sensors system, which is necessary for +rendering-based sensors to generate data. + +@image html files/server_config/camera_no_env.gif + +Now let's create a custom configuration file in +`$HOME/.ignition/gazebo/rendering_sensors_server.config` that has the sensors +system: + +``` + + + + + + ogre + + + +``` + +And point the environment variable to that file: + +`export IGN_GAZEBO_SERVER_CONFIG_PATH=$HOME/.ignition/gazebo/rendering_sensors_server.config` + +Now when we launch the simulation again, refreshing the image display will +show the camera topic, and we can see the camera data. +One interesting thing to notice is that on the camera view, there's no grid and +the background color is the default grey, instead of the blue color set on the +GUI `GzScene` plugin. + +@image html files/server_config/camera_env.gif + From 69e190c8e6ba73aece511eb10a44bbc388c2d46b Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 11 Jan 2021 11:58:45 -0800 Subject: [PATCH 05/55] Added missing version namespace (#541) * Added missing version namespace Signed-off-by: Nate Koenig * Fix codecheck Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/ignition/gazebo/detail/EntityComponentManager.hh | 3 +++ 1 file changed, 3 insertions(+) diff --git a/include/ignition/gazebo/detail/EntityComponentManager.hh b/include/ignition/gazebo/detail/EntityComponentManager.hh index 027baf355c..880dba745c 100644 --- a/include/ignition/gazebo/detail/EntityComponentManager.hh +++ b/include/ignition/gazebo/detail/EntityComponentManager.hh @@ -32,6 +32,8 @@ namespace ignition { namespace gazebo { +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { ////////////////////////////////////////////////// namespace traits { @@ -547,5 +549,6 @@ bool EntityComponentManager::RemoveComponent(Entity _entity) } } } +} #endif From 6544c780dd0bffae892740283b2a8965d23d5cd8 Mon Sep 17 00:00:00 2001 From: Nick Lamprianidis Date: Tue, 12 Jan 2021 12:08:37 +0100 Subject: [PATCH 06/55] Fix examples in migration plugins tutorial (#543) Signed-off-by: Nick Lamprianidis --- tutorials/migration_plugins.md | 70 ++++++++++++++++++++-------------- 1 file changed, 42 insertions(+), 28 deletions(-) diff --git a/tutorials/migration_plugins.md b/tutorials/migration_plugins.md index c9825bbac2..7f972d5f21 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -1,6 +1,6 @@ \page migrationplugins -# Migration from Gazebo-classic: Plugins +# Migration from Gazebo Classic: Plugins Classic Gazebo supports [6 different C++ plugin types](http://gazebosim.org/tutorials?tut=plugins_hello_world&cat=write_plugin), @@ -75,7 +75,7 @@ class MyPlugin : public ModelPlugin this->link = _model->GetLink(linkName); // Register callback to be called at every iteration - this->connection = event::Events::ConnectWorldUpdateBegin( + this->updateConnection = event::Events::ConnectWorldUpdateBegin( std::bind(&MyPlugin::OnUpdate, this)); } @@ -103,6 +103,11 @@ On Ignition Gazebo, that would be implemented as follows: #include #include #include +#include + +using namespace ignition; +using namespace gazebo; +using namespace systems; // Inherit from System and 2 extra interfaces: // ISystemConfigure and ISystemPostUpdate @@ -113,25 +118,25 @@ class MyPlugin { // Implement Configure callback, provided by ISystemConfigure // and called once at startup. - void MyPlugin::Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &/*_eventMgr*/) + virtual void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &/*_eventMgr*/) override { // Read property from SDF auto linkName = _sdf->Get("link_name"); - // Create model object, to access convenient functions + // Create model object to access convenient functions auto model = Model(_entity); // Get link entity - auto linkEntity = model->LinkByName(_ecm, linkName); + this->linkEntity = model.LinkByName(_ecm, linkName); } // Implement PostUpdate callback, provided by ISystemPostUpdate // and called at every iteration, after physics is done - void MyPlugin::PostUpdate(const UpdateInfo &/*_info*/, - const EntityComponentManager &_ecm) + virtual void PostUpdate(const UpdateInfo &/*_info*/, + const EntityComponentManager &_ecm) override { // Get link pose and print it std::cout << worldPose(this->linkEntity, _ecm) << std::endl; @@ -149,7 +154,7 @@ IGNITION_ADD_PLUGIN(MyPlugin, // Add plugin alias so that we can refer to the plugin without the version // namespace -IGNITION_ADD_PLUGIN_ALIAS(MyPlugin,"ignition::gazebo::systems::MyPlugin") +IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "ignition::gazebo::systems::MyPlugin") ``` The example above uses headers like `Model.hh` and `Util.hh`, which offer @@ -161,6 +166,15 @@ the ECM's API: ```cpp #include #include +#include +#include +#include +#include +#include + +using namespace ignition; +using namespace gazebo; +using namespace systems; // Inherit from System and 2 extra interfaces: // ISystemConfigure and ISystemPostUpdate @@ -169,43 +183,43 @@ class MyPlugin public ISystemConfigure, public ISystemPostUpdate { - void MyPlugin::Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &/*_eventMgr*/) + virtual void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &/*_eventMgr*/) override { + // Read property from SDF auto linkName = _sdf->Get("link_name"); - // Create link entity by querying for an entity that has a specific set of + // Get link entity by querying for an entity that has a specific set of // components this->linkEntity = _ecm.EntityByComponents( - components::ParentEntity(this->dataPtr->id), - components::Name(_name), - components::Link()); + components::ParentEntity(_entity), + components::Name(linkName), components::Link()); } - void MyPlugin::PostUpdate(const UpdateInfo &/*_info*/, - const EntityComponentManager &_ecm) + virtual void PostUpdate(const UpdateInfo &/*_info*/, + const EntityComponentManager &_ecm) override { // Get link's local pose auto pose = _ecm.Component(this->linkEntity)->Data(); // Get link's parent entity - auto p = _ecm.Component(this->linkEntity); + auto parent = _ecm.Component(this->linkEntity); // Iterate over parents until world is reached - while (p) + while (parent) { // Get parent entity's pose - auto parentPose = _ecm.Component(p->Data()); + auto parentPose = _ecm.Component(parent->Data()); if (!parentPose) break; // Add pose - pose = pose + parentPose->Data(); + pose = parentPose->Data() * pose; // keep going up the tree - p = _ecm.Component(p->Data()); + parent = _ecm.Component(parent->Data()); } std::cout << pose << std::endl; @@ -220,7 +234,7 @@ IGNITION_ADD_PLUGIN(MyPlugin, MyPlugin::ISystemConfigure, MyPlugin::ISystemPostUpdate) -IGNITION_ADD_PLUGIN_ALIAS(MyPlugin,"ignition::gazebo::systems::MyPlugin") +IGNITION_ADD_PLUGIN_ALIAS(MyPlugin, "ignition::gazebo::systems::MyPlugin") ``` In summary, the key differences between classic and Igntion Gazebo are: @@ -234,7 +248,7 @@ In summary, the key differences between classic and Igntion Gazebo are: * Plugins don't have direct access to physics objects such as `physics::Model`. Instead, they can either deal directly with entities and their components by - calling functions in the ECM, or use convenient objects such as + calling functions of the ECM, or use convenient objects such as `ignition::gazebo::Model` which wrap the ECM interface. All these changes are meant to give plugin developers more flexibility to From d5e65d9c485a94785703fd67f7b15efb63ecf8f3 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 13 Jan 2021 09:22:38 -0800 Subject: [PATCH 07/55] Prepare for 3.7.0 release (#552) Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- CMakeLists.txt | 2 +- Changelog.md | 20 +++++++++++++++++++- 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2927065688..9d4b9575c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo3 VERSION 3.6.0) +project(ignition-gazebo3 VERSION 3.7.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index e9ee76d1a7..9bfa6d1b67 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,24 @@ ## Ignition Gazebo 3.x -### Ignition Gazebo 3.X.X (20XX-XX-XX) +### Ignition Gazebo 3.7.0 (2021-01-13) + +1. Fix examples in migration plugins tutorial. + * [Pull Request 543](https://github.com/ignitionrobotics/ign-gazebo/pull/543) + +1. Added missing namespace in `detail/EntityComponentManager.hh`. + * [Pull Request 541](https://github.com/ignitionrobotics/ign-gazebo/pull/541) + +1. Automatically load a subset of world plugins. + * [Pull Request 281](https://github.com/ignitionrobotics/ign-gazebo/pull/281) + +1. Update gtest to 1.10.0 for Windows compilation. + * [Pull Request 506](https://github.com/ignitionrobotics/ign-gazebo/pull/506) + +1. Updates to ardupilot migration tutorial. + * [Pull Request 525](https://github.com/ignitionrobotics/ign-gazebo/pull/525) + +1. Don't make docs on macOS. + * [Pull Request 528](https://github.com/ignitionrobotics/ign-gazebo/pull/528) ### Ignition Gazebo 3.6.0 (2020-12-30) From 4124deadabfa5c58dd821055ee521d072d220760 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 14 Jan 2021 10:19:04 -0800 Subject: [PATCH 08/55] Non-blocking paths request (#555) Signed-off-by: Louise Poubel --- src/ServerPrivate.cc | 2 +- src/gui/PathManager.cc | 29 +++++++++++++++++++---------- 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 7792222754..67fa6df18c 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -401,7 +401,7 @@ void ServerPrivate::SetupTransport() if (this->node.Advertise(getPathService, &ServerPrivate::ResourcePathsService, this)) { - ignmsg << "Resource path get service on [" << addPathService << "]." + ignmsg << "Resource path get service on [" << getPathService << "]." << std::endl; } else diff --git a/src/gui/PathManager.cc b/src/gui/PathManager.cc index 575e8de6ec..a1f920519a 100644 --- a/src/gui/PathManager.cc +++ b/src/gui/PathManager.cc @@ -44,21 +44,30 @@ void onAddResourcePaths(const msgs::StringMsg_V &_msg) addResourcePaths(paths); } +////////////////////////////////////////////////// +void onAddResourcePaths(const msgs::StringMsg_V &_res, const bool _result) +{ + if (!_result) + { + ignerr << "Failed to get resource paths through service" << std::endl; + return; + } + igndbg << "Received resource paths." << std::endl; + + onAddResourcePaths(_res); +} + ///////////////////////////////////////////////// PathManager::PathManager() { - // Get resource paths + // Trigger an initial request to get all paths from server std::string service{"/gazebo/resource_paths/get"}; - msgs::StringMsg_V res; - bool result{false}; - auto executed = this->node.Request(service, 5000, res, result); - if (!executed) - ignerr << "Service call timed out for [" << service << "]" << std::endl; - else if (!result) - ignerr << "Service call failed for [" << service << "]" << std::endl; - - onAddResourcePaths(res); + igndbg << "Requesting resource paths through [" << service << "]" + << std::endl; + this->node.Request(service, onAddResourcePaths); + // Get path updates through this topic this->node.Subscribe("/gazebo/resource_paths", onAddResourcePaths); } + From ddd7fcda563b1f8c47c92610181a2d5f797c80bc Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Fri, 15 Jan 2021 09:26:48 -0800 Subject: [PATCH 09/55] Parallelize State call in ECM (#451) Signed-off-by: John Shepherd Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- src/EntityComponentManager.cc | 112 ++++++++++++++++++++++++++++++++-- 1 file changed, 108 insertions(+), 4 deletions(-) diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 9946ccbaf8..3c4992b49d 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -50,6 +50,10 @@ class ignition::gazebo::EntityComponentManagerPrivate /// \return True if created successfully. public: bool CreateComponentStorage(const ComponentTypeId _typeId); + /// \brief Allots the work for multiple threads prior to running + /// `AddEntityToMessage`. + public: void CalculateStateThreadLoad(); + /// \brief Map of component storage classes. The key is a component /// type id, and the value is a pointer to the component storage. public: std::unordered_map> entityComponents; + /// \brief A vector of iterators to evenly distributed spots in the + /// `entityComponents` map. Threads in the `State` function use this + /// vector for easy access of their pre-allocated work. This vector + /// is recalculated if `entityComponents` is changed (when + /// `entityComponentsDirty` == true). + public: std::vector>::iterator> + entityComponentIterators; + /// \brief A mutex to protect newly created entityes. public: std::mutex entityCreatedMutex; @@ -222,6 +242,7 @@ void EntityComponentManager::ProcessRemoveEntityRequests() this->dataPtr->entities = EntityGraph(); this->dataPtr->entityComponents.clear(); this->dataPtr->toRemoveEntities.clear(); + this->dataPtr->entityComponentsDirty = true; for (std::pair> &comp: this->dataPtr->components) @@ -257,6 +278,7 @@ void EntityComponentManager::ProcessRemoveEntityRequests() // Remove the entry in the entityComponent map this->dataPtr->entityComponents.erase(entity); + this->dataPtr->entityComponentsDirty = true; } // Remove the entity from views. @@ -295,6 +317,7 @@ bool EntityComponentManager::RemoveComponent( this->dataPtr->entityComponents[_entity].erase(_key.first); this->dataPtr->oneTimeChangedComponents.erase(_key); this->dataPtr->periodicChangedComponents.erase(_key); + this->dataPtr->entityComponentsDirty = true; this->UpdateViews(_entity); return true; @@ -463,6 +486,7 @@ ComponentKey EntityComponentManager::CreateComponentImplementation( this->dataPtr->entityComponents[_entity].insert( {_componentTypeId, componentKey}); this->dataPtr->oneTimeChangedComponents.insert(componentKey); + this->dataPtr->entityComponentsDirty = true; if (componentIdPair.second) this->RebuildViews(); @@ -894,6 +918,51 @@ void EntityComponentManager::ChangedState( // TODO(anyone) New / removed / changed components } +////////////////////////////////////////////////// +void EntityComponentManagerPrivate::CalculateStateThreadLoad() +{ + // If the entity component vector is dirty, we need to recalculate the + // threads and each threads work load + if (!this->entityComponentsDirty) + return; + + this->entityComponentsDirty = false; + this->entityComponentIterators.clear(); + auto startIt = this->entityComponents.begin(); + int numComponents = this->entityComponents.size(); + + // Set the number of threads to spawn to the min of the calculated thread + // count or max threads that the hardware supports + int maxThreads = std::thread::hardware_concurrency(); + uint64_t numThreads = std::min(numComponents, maxThreads); + + int componentsPerThread = std::ceil(static_cast(numComponents) / + numThreads); + + igndbg << "Updated state thread iterators: " << numThreads + << " threads processing around " << componentsPerThread + << " components each." << std::endl; + + // Push back the starting iterator + this->entityComponentIterators.push_back(startIt); + for (uint64_t i = 0; i < numThreads; ++i) + { + // If we have added all of the components to the iterator vector, we are + // done so push back the end iterator + numComponents -= componentsPerThread; + if (numComponents <= 0) + { + this->entityComponentIterators.push_back( + this->entityComponents.end()); + break; + } + + // Get the iterator to the next starting group of components + auto nextIt = std::next(startIt, componentsPerThread); + this->entityComponentIterators.push_back(nextIt); + startIt = nextIt; + } +} ////////////////////////////////////////////////// ignition::msgs::SerializedState EntityComponentManager::State( @@ -922,11 +991,46 @@ void EntityComponentManager::State( const std::unordered_set &_types, bool _full) const { - for (const auto &it : this->dataPtr->entityComponents) + std::mutex stateMapMutex; + std::vector workers; + + this->dataPtr->CalculateStateThreadLoad(); + + auto functor = [&](auto itStart, auto itEnd) { - if (_entities.empty() || _entities.find(it.first) != _entities.end()) - this->AddEntityToMessage(_state, it.first, _types, _full); + msgs::SerializedStateMap threadMap; + while (itStart != itEnd) + { + auto entity = (*itStart).first; + if (_entities.empty() || _entities.find(entity) != _entities.end()) + { + this->AddEntityToMessage(threadMap, entity, _types, _full); + } + itStart++; + } + std::lock_guard lock(stateMapMutex); + + for (const auto &entity : threadMap.entities()) + { + (*_state.mutable_entities())[static_cast(entity.first)] = + entity.second; + } + }; + + // Spawn workers + uint64_t numThreads = this->dataPtr->entityComponentIterators.size() - 1; + for (uint64_t i = 0; i < numThreads; i++) + { + workers.push_back(std::thread(functor, + this->dataPtr->entityComponentIterators[i], + this->dataPtr->entityComponentIterators[i+1])); } + + // Wait for each thread to finish processing its components + std::for_each(workers.begin(), workers.end(), [](std::thread &_t) + { + _t.join(); + }); } ////////////////////////////////////////////////// From 89987404180f38dafe5542d677ba97c8f4ce23d9 Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Wed, 20 Jan 2021 18:29:19 -0800 Subject: [PATCH 10/55] added size to ground_plane in examples (#573) Signed-off-by: Jenn Nguyen --- examples/scripts/distributed/secondary.sdf | 1 + examples/scripts/distributed/standalone.sdf | 1 + examples/worlds/3k_shapes.sdf | 2003 +++++++++-------- examples/worlds/actor.sdf | 1 + examples/worlds/actors_population.sdf.erb | 1 + examples/worlds/apply_joint_force.sdf | 1 + examples/worlds/breadcrumbs.sdf | 2 +- examples/worlds/camera_sensor.sdf | 1 + .../camera_video_record_dbl_pendulum.sdf | 2 +- examples/worlds/contact_sensor.sdf | 1 + examples/worlds/debug_shapes.sdf | 1 + examples/worlds/default.sdf | 1 + examples/worlds/depth_camera_sensor.sdf | 1 + examples/worlds/detachable_joint.sdf | 2 +- examples/worlds/diff_drive.sdf | 2 +- examples/worlds/diff_drive_skid.sdf | 2 +- examples/worlds/empty.sdf | 1 + examples/worlds/fuel.sdf | 1 + examples/worlds/fuel_textured_mesh.sdf | 1 + examples/worlds/gpu_lidar_sensor.sdf | 1 + examples/worlds/grid.sdf | 1 + examples/worlds/import_mesh.sdf | 1 + examples/worlds/lift_drag.sdf | 1 + examples/worlds/lift_drag_battery.sdf | 1 + examples/worlds/lights.sdf | 1 + examples/worlds/log_record_dbl_pendulum.sdf | 2 +- examples/worlds/log_record_resources.sdf | 1 + examples/worlds/log_record_shapes.sdf | 1 + .../worlds/logical_audio_sensor_plugin.sdf | 1 + examples/worlds/logical_camera_sensor.sdf | 1 + .../worlds/multicopter_velocity_control.sdf | 2 +- examples/worlds/nested_model.sdf | 1 + examples/worlds/performer_detector.sdf | 2 +- examples/worlds/plane_propeller_demo.sdf | 1 + examples/worlds/pose_publisher.sdf | 2 +- examples/worlds/quadcopter.sdf | 2 +- examples/worlds/rolling_shapes.sdf | 1 + examples/worlds/sensors.sdf | 1 + examples/worlds/sensors_demo.sdf | 1 + examples/worlds/shapes.sdf | 1 + examples/worlds/shapes_bitmask.sdf | 1 + examples/worlds/shapes_population.sdf.erb | 1 + examples/worlds/thermal_camera.sdf | 1 + examples/worlds/touch_plugin.sdf | 2 +- examples/worlds/track_drive.sdf | 2 +- examples/worlds/triggered_publisher.sdf | 2 +- .../worlds/trisphere_cycle_wheel_slip.sdf | 1 + examples/worlds/velocity_control.sdf | 1 + examples/worlds/video_record_dbl_pendulum.sdf | 2 +- examples/worlds/wind.sdf | 1 + test/worlds/altimeter.sdf | 1 + test/worlds/apply_joint_force.sdf | 1 + test/worlds/breadcrumbs.sdf | 3 +- test/worlds/camera_video_record.sdf | 2 +- test/worlds/depth_camera_sensor.sdf | 1 + test/worlds/detachable_joint.sdf | 1 + test/worlds/diff_drive.sdf | 2 +- test/worlds/diff_drive_custom_frame_id.sdf | 2 +- test/worlds/diff_drive_custom_topics.sdf | 2 +- test/worlds/diff_drive_limited_joint_pub.sdf | 2 +- test/worlds/diff_drive_skid.sdf | 2 +- test/worlds/falling.sdf | 1 + test/worlds/friction.sdf | 2 +- test/worlds/gpu_lidar_sensor.sdf | 1 + test/worlds/imu.sdf | 1 + test/worlds/joint_controller.sdf | 1 + test/worlds/joint_position_controller.sdf | 1 + test/worlds/lift_drag.sdf | 2 +- test/worlds/log_record_dbl_pendulum.sdf | 2 +- test/worlds/log_record_resources.sdf | 1 + test/worlds/logical_camera_sensor.sdf | 1 + test/worlds/magnetometer.sdf | 1 + test/worlds/mesh.sdf | 1 + test/worlds/nondefault_canonical.sdf | 1 + test/worlds/performer_detector.sdf | 2 +- test/worlds/pose_publisher.sdf | 2 +- test/worlds/quadcopter.sdf | 2 +- test/worlds/quadcopter_velocity_control.sdf | 2 +- test/worlds/revolute_joint.sdf | 1 + test/worlds/rgbd_camera_sensor.sdf | 1 + test/worlds/thermal.sdf | 1 + test/worlds/touch_plugin.sdf | 2 +- test/worlds/triball_drift.sdf | 1 + test/worlds/trisphere_cycle_wheel_slip.sdf | 1 + test/worlds/velocity_control.sdf | 1 + 85 files changed, 1086 insertions(+), 1031 deletions(-) diff --git a/examples/scripts/distributed/secondary.sdf b/examples/scripts/distributed/secondary.sdf index f9dc09ed5c..13312dc93f 100644 --- a/examples/scripts/distributed/secondary.sdf +++ b/examples/scripts/distributed/secondary.sdf @@ -28,6 +28,7 @@ 0 0 1 + 100 100 diff --git a/examples/scripts/distributed/standalone.sdf b/examples/scripts/distributed/standalone.sdf index 94a6d74396..1b95237900 100644 --- a/examples/scripts/distributed/standalone.sdf +++ b/examples/scripts/distributed/standalone.sdf @@ -108,6 +108,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/3k_shapes.sdf b/examples/worlds/3k_shapes.sdf index d53292a574..ba5ea9298c 100644 --- a/examples/worlds/3k_shapes.sdf +++ b/examples/worlds/3k_shapes.sdf @@ -130,6 +130,7 @@ 0 0 1 + 100 100 @@ -149,7 +150,7 @@ - + -750.0 0 0.5 0 0 0 @@ -262,7 +263,7 @@ - + -748.5 0 0.5 0 0 0 @@ -375,7 +376,7 @@ - + -747.0 0 0.5 0 0 0 @@ -488,7 +489,7 @@ - + -745.5 0 0.5 0 0 0 @@ -601,7 +602,7 @@ - + -744.0 0 0.5 0 0 0 @@ -714,7 +715,7 @@ - + -742.5 0 0.5 0 0 0 @@ -827,7 +828,7 @@ - + -741.0 0 0.5 0 0 0 @@ -940,7 +941,7 @@ - + -739.5 0 0.5 0 0 0 @@ -1053,7 +1054,7 @@ - + -738.0 0 0.5 0 0 0 @@ -1166,7 +1167,7 @@ - + -736.5 0 0.5 0 0 0 @@ -1279,7 +1280,7 @@ - + -735.0 0 0.5 0 0 0 @@ -1392,7 +1393,7 @@ - + -733.5 0 0.5 0 0 0 @@ -1505,7 +1506,7 @@ - + -732.0 0 0.5 0 0 0 @@ -1618,7 +1619,7 @@ - + -730.5 0 0.5 0 0 0 @@ -1731,7 +1732,7 @@ - + -729.0 0 0.5 0 0 0 @@ -1844,7 +1845,7 @@ - + -727.5 0 0.5 0 0 0 @@ -1957,7 +1958,7 @@ - + -726.0 0 0.5 0 0 0 @@ -2070,7 +2071,7 @@ - + -724.5 0 0.5 0 0 0 @@ -2183,7 +2184,7 @@ - + -723.0 0 0.5 0 0 0 @@ -2296,7 +2297,7 @@ - + -721.5 0 0.5 0 0 0 @@ -2409,7 +2410,7 @@ - + -720.0 0 0.5 0 0 0 @@ -2522,7 +2523,7 @@ - + -718.5 0 0.5 0 0 0 @@ -2635,7 +2636,7 @@ - + -717.0 0 0.5 0 0 0 @@ -2748,7 +2749,7 @@ - + -715.5 0 0.5 0 0 0 @@ -2861,7 +2862,7 @@ - + -714.0 0 0.5 0 0 0 @@ -2974,7 +2975,7 @@ - + -712.5 0 0.5 0 0 0 @@ -3087,7 +3088,7 @@ - + -711.0 0 0.5 0 0 0 @@ -3200,7 +3201,7 @@ - + -709.5 0 0.5 0 0 0 @@ -3313,7 +3314,7 @@ - + -708.0 0 0.5 0 0 0 @@ -3426,7 +3427,7 @@ - + -706.5 0 0.5 0 0 0 @@ -3539,7 +3540,7 @@ - + -705.0 0 0.5 0 0 0 @@ -3652,7 +3653,7 @@ - + -703.5 0 0.5 0 0 0 @@ -3765,7 +3766,7 @@ - + -702.0 0 0.5 0 0 0 @@ -3878,7 +3879,7 @@ - + -700.5 0 0.5 0 0 0 @@ -3991,7 +3992,7 @@ - + -699.0 0 0.5 0 0 0 @@ -4104,7 +4105,7 @@ - + -697.5 0 0.5 0 0 0 @@ -4217,7 +4218,7 @@ - + -696.0 0 0.5 0 0 0 @@ -4330,7 +4331,7 @@ - + -694.5 0 0.5 0 0 0 @@ -4443,7 +4444,7 @@ - + -693.0 0 0.5 0 0 0 @@ -4556,7 +4557,7 @@ - + -691.5 0 0.5 0 0 0 @@ -4669,7 +4670,7 @@ - + -690.0 0 0.5 0 0 0 @@ -4782,7 +4783,7 @@ - + -688.5 0 0.5 0 0 0 @@ -4895,7 +4896,7 @@ - + -687.0 0 0.5 0 0 0 @@ -5008,7 +5009,7 @@ - + -685.5 0 0.5 0 0 0 @@ -5121,7 +5122,7 @@ - + -684.0 0 0.5 0 0 0 @@ -5234,7 +5235,7 @@ - + -682.5 0 0.5 0 0 0 @@ -5347,7 +5348,7 @@ - + -681.0 0 0.5 0 0 0 @@ -5460,7 +5461,7 @@ - + -679.5 0 0.5 0 0 0 @@ -5573,7 +5574,7 @@ - + -678.0 0 0.5 0 0 0 @@ -5686,7 +5687,7 @@ - + -676.5 0 0.5 0 0 0 @@ -5799,7 +5800,7 @@ - + -675.0 0 0.5 0 0 0 @@ -5912,7 +5913,7 @@ - + -673.5 0 0.5 0 0 0 @@ -6025,7 +6026,7 @@ - + -672.0 0 0.5 0 0 0 @@ -6138,7 +6139,7 @@ - + -670.5 0 0.5 0 0 0 @@ -6251,7 +6252,7 @@ - + -669.0 0 0.5 0 0 0 @@ -6364,7 +6365,7 @@ - + -667.5 0 0.5 0 0 0 @@ -6477,7 +6478,7 @@ - + -666.0 0 0.5 0 0 0 @@ -6590,7 +6591,7 @@ - + -664.5 0 0.5 0 0 0 @@ -6703,7 +6704,7 @@ - + -663.0 0 0.5 0 0 0 @@ -6816,7 +6817,7 @@ - + -661.5 0 0.5 0 0 0 @@ -6929,7 +6930,7 @@ - + -660.0 0 0.5 0 0 0 @@ -7042,7 +7043,7 @@ - + -658.5 0 0.5 0 0 0 @@ -7155,7 +7156,7 @@ - + -657.0 0 0.5 0 0 0 @@ -7268,7 +7269,7 @@ - + -655.5 0 0.5 0 0 0 @@ -7381,7 +7382,7 @@ - + -654.0 0 0.5 0 0 0 @@ -7494,7 +7495,7 @@ - + -652.5 0 0.5 0 0 0 @@ -7607,7 +7608,7 @@ - + -651.0 0 0.5 0 0 0 @@ -7720,7 +7721,7 @@ - + -649.5 0 0.5 0 0 0 @@ -7833,7 +7834,7 @@ - + -648.0 0 0.5 0 0 0 @@ -7946,7 +7947,7 @@ - + -646.5 0 0.5 0 0 0 @@ -8059,7 +8060,7 @@ - + -645.0 0 0.5 0 0 0 @@ -8172,7 +8173,7 @@ - + -643.5 0 0.5 0 0 0 @@ -8285,7 +8286,7 @@ - + -642.0 0 0.5 0 0 0 @@ -8398,7 +8399,7 @@ - + -640.5 0 0.5 0 0 0 @@ -8511,7 +8512,7 @@ - + -639.0 0 0.5 0 0 0 @@ -8624,7 +8625,7 @@ - + -637.5 0 0.5 0 0 0 @@ -8737,7 +8738,7 @@ - + -636.0 0 0.5 0 0 0 @@ -8850,7 +8851,7 @@ - + -634.5 0 0.5 0 0 0 @@ -8963,7 +8964,7 @@ - + -633.0 0 0.5 0 0 0 @@ -9076,7 +9077,7 @@ - + -631.5 0 0.5 0 0 0 @@ -9189,7 +9190,7 @@ - + -630.0 0 0.5 0 0 0 @@ -9302,7 +9303,7 @@ - + -628.5 0 0.5 0 0 0 @@ -9415,7 +9416,7 @@ - + -627.0 0 0.5 0 0 0 @@ -9528,7 +9529,7 @@ - + -625.5 0 0.5 0 0 0 @@ -9641,7 +9642,7 @@ - + -624.0 0 0.5 0 0 0 @@ -9754,7 +9755,7 @@ - + -622.5 0 0.5 0 0 0 @@ -9867,7 +9868,7 @@ - + -621.0 0 0.5 0 0 0 @@ -9980,7 +9981,7 @@ - + -619.5 0 0.5 0 0 0 @@ -10093,7 +10094,7 @@ - + -618.0 0 0.5 0 0 0 @@ -10206,7 +10207,7 @@ - + -616.5 0 0.5 0 0 0 @@ -10319,7 +10320,7 @@ - + -615.0 0 0.5 0 0 0 @@ -10432,7 +10433,7 @@ - + -613.5 0 0.5 0 0 0 @@ -10545,7 +10546,7 @@ - + -612.0 0 0.5 0 0 0 @@ -10658,7 +10659,7 @@ - + -610.5 0 0.5 0 0 0 @@ -10771,7 +10772,7 @@ - + -609.0 0 0.5 0 0 0 @@ -10884,7 +10885,7 @@ - + -607.5 0 0.5 0 0 0 @@ -10997,7 +10998,7 @@ - + -606.0 0 0.5 0 0 0 @@ -11110,7 +11111,7 @@ - + -604.5 0 0.5 0 0 0 @@ -11223,7 +11224,7 @@ - + -603.0 0 0.5 0 0 0 @@ -11336,7 +11337,7 @@ - + -601.5 0 0.5 0 0 0 @@ -11449,7 +11450,7 @@ - + -600.0 0 0.5 0 0 0 @@ -11562,7 +11563,7 @@ - + -598.5 0 0.5 0 0 0 @@ -11675,7 +11676,7 @@ - + -597.0 0 0.5 0 0 0 @@ -11788,7 +11789,7 @@ - + -595.5 0 0.5 0 0 0 @@ -11901,7 +11902,7 @@ - + -594.0 0 0.5 0 0 0 @@ -12014,7 +12015,7 @@ - + -592.5 0 0.5 0 0 0 @@ -12127,7 +12128,7 @@ - + -591.0 0 0.5 0 0 0 @@ -12240,7 +12241,7 @@ - + -589.5 0 0.5 0 0 0 @@ -12353,7 +12354,7 @@ - + -588.0 0 0.5 0 0 0 @@ -12466,7 +12467,7 @@ - + -586.5 0 0.5 0 0 0 @@ -12579,7 +12580,7 @@ - + -585.0 0 0.5 0 0 0 @@ -12692,7 +12693,7 @@ - + -583.5 0 0.5 0 0 0 @@ -12805,7 +12806,7 @@ - + -582.0 0 0.5 0 0 0 @@ -12918,7 +12919,7 @@ - + -580.5 0 0.5 0 0 0 @@ -13031,7 +13032,7 @@ - + -579.0 0 0.5 0 0 0 @@ -13144,7 +13145,7 @@ - + -577.5 0 0.5 0 0 0 @@ -13257,7 +13258,7 @@ - + -576.0 0 0.5 0 0 0 @@ -13370,7 +13371,7 @@ - + -574.5 0 0.5 0 0 0 @@ -13483,7 +13484,7 @@ - + -573.0 0 0.5 0 0 0 @@ -13596,7 +13597,7 @@ - + -571.5 0 0.5 0 0 0 @@ -13709,7 +13710,7 @@ - + -570.0 0 0.5 0 0 0 @@ -13822,7 +13823,7 @@ - + -568.5 0 0.5 0 0 0 @@ -13935,7 +13936,7 @@ - + -567.0 0 0.5 0 0 0 @@ -14048,7 +14049,7 @@ - + -565.5 0 0.5 0 0 0 @@ -14161,7 +14162,7 @@ - + -564.0 0 0.5 0 0 0 @@ -14274,7 +14275,7 @@ - + -562.5 0 0.5 0 0 0 @@ -14387,7 +14388,7 @@ - + -561.0 0 0.5 0 0 0 @@ -14500,7 +14501,7 @@ - + -559.5 0 0.5 0 0 0 @@ -14613,7 +14614,7 @@ - + -558.0 0 0.5 0 0 0 @@ -14726,7 +14727,7 @@ - + -556.5 0 0.5 0 0 0 @@ -14839,7 +14840,7 @@ - + -555.0 0 0.5 0 0 0 @@ -14952,7 +14953,7 @@ - + -553.5 0 0.5 0 0 0 @@ -15065,7 +15066,7 @@ - + -552.0 0 0.5 0 0 0 @@ -15178,7 +15179,7 @@ - + -550.5 0 0.5 0 0 0 @@ -15291,7 +15292,7 @@ - + -549.0 0 0.5 0 0 0 @@ -15404,7 +15405,7 @@ - + -547.5 0 0.5 0 0 0 @@ -15517,7 +15518,7 @@ - + -546.0 0 0.5 0 0 0 @@ -15630,7 +15631,7 @@ - + -544.5 0 0.5 0 0 0 @@ -15743,7 +15744,7 @@ - + -543.0 0 0.5 0 0 0 @@ -15856,7 +15857,7 @@ - + -541.5 0 0.5 0 0 0 @@ -15969,7 +15970,7 @@ - + -540.0 0 0.5 0 0 0 @@ -16082,7 +16083,7 @@ - + -538.5 0 0.5 0 0 0 @@ -16195,7 +16196,7 @@ - + -537.0 0 0.5 0 0 0 @@ -16308,7 +16309,7 @@ - + -535.5 0 0.5 0 0 0 @@ -16421,7 +16422,7 @@ - + -534.0 0 0.5 0 0 0 @@ -16534,7 +16535,7 @@ - + -532.5 0 0.5 0 0 0 @@ -16647,7 +16648,7 @@ - + -531.0 0 0.5 0 0 0 @@ -16760,7 +16761,7 @@ - + -529.5 0 0.5 0 0 0 @@ -16873,7 +16874,7 @@ - + -528.0 0 0.5 0 0 0 @@ -16986,7 +16987,7 @@ - + -526.5 0 0.5 0 0 0 @@ -17099,7 +17100,7 @@ - + -525.0 0 0.5 0 0 0 @@ -17212,7 +17213,7 @@ - + -523.5 0 0.5 0 0 0 @@ -17325,7 +17326,7 @@ - + -522.0 0 0.5 0 0 0 @@ -17438,7 +17439,7 @@ - + -520.5 0 0.5 0 0 0 @@ -17551,7 +17552,7 @@ - + -519.0 0 0.5 0 0 0 @@ -17664,7 +17665,7 @@ - + -517.5 0 0.5 0 0 0 @@ -17777,7 +17778,7 @@ - + -516.0 0 0.5 0 0 0 @@ -17890,7 +17891,7 @@ - + -514.5 0 0.5 0 0 0 @@ -18003,7 +18004,7 @@ - + -513.0 0 0.5 0 0 0 @@ -18116,7 +18117,7 @@ - + -511.5 0 0.5 0 0 0 @@ -18229,7 +18230,7 @@ - + -510.0 0 0.5 0 0 0 @@ -18342,7 +18343,7 @@ - + -508.5 0 0.5 0 0 0 @@ -18455,7 +18456,7 @@ - + -507.0 0 0.5 0 0 0 @@ -18568,7 +18569,7 @@ - + -505.5 0 0.5 0 0 0 @@ -18681,7 +18682,7 @@ - + -504.0 0 0.5 0 0 0 @@ -18794,7 +18795,7 @@ - + -502.5 0 0.5 0 0 0 @@ -18907,7 +18908,7 @@ - + -501.0 0 0.5 0 0 0 @@ -19020,7 +19021,7 @@ - + -499.5 0 0.5 0 0 0 @@ -19133,7 +19134,7 @@ - + -498.0 0 0.5 0 0 0 @@ -19246,7 +19247,7 @@ - + -496.5 0 0.5 0 0 0 @@ -19359,7 +19360,7 @@ - + -495.0 0 0.5 0 0 0 @@ -19472,7 +19473,7 @@ - + -493.5 0 0.5 0 0 0 @@ -19585,7 +19586,7 @@ - + -492.0 0 0.5 0 0 0 @@ -19698,7 +19699,7 @@ - + -490.5 0 0.5 0 0 0 @@ -19811,7 +19812,7 @@ - + -489.0 0 0.5 0 0 0 @@ -19924,7 +19925,7 @@ - + -487.5 0 0.5 0 0 0 @@ -20037,7 +20038,7 @@ - + -486.0 0 0.5 0 0 0 @@ -20150,7 +20151,7 @@ - + -484.5 0 0.5 0 0 0 @@ -20263,7 +20264,7 @@ - + -483.0 0 0.5 0 0 0 @@ -20376,7 +20377,7 @@ - + -481.5 0 0.5 0 0 0 @@ -20489,7 +20490,7 @@ - + -480.0 0 0.5 0 0 0 @@ -20602,7 +20603,7 @@ - + -478.5 0 0.5 0 0 0 @@ -20715,7 +20716,7 @@ - + -477.0 0 0.5 0 0 0 @@ -20828,7 +20829,7 @@ - + -475.5 0 0.5 0 0 0 @@ -20941,7 +20942,7 @@ - + -474.0 0 0.5 0 0 0 @@ -21054,7 +21055,7 @@ - + -472.5 0 0.5 0 0 0 @@ -21167,7 +21168,7 @@ - + -471.0 0 0.5 0 0 0 @@ -21280,7 +21281,7 @@ - + -469.5 0 0.5 0 0 0 @@ -21393,7 +21394,7 @@ - + -468.0 0 0.5 0 0 0 @@ -21506,7 +21507,7 @@ - + -466.5 0 0.5 0 0 0 @@ -21619,7 +21620,7 @@ - + -465.0 0 0.5 0 0 0 @@ -21732,7 +21733,7 @@ - + -463.5 0 0.5 0 0 0 @@ -21845,7 +21846,7 @@ - + -462.0 0 0.5 0 0 0 @@ -21958,7 +21959,7 @@ - + -460.5 0 0.5 0 0 0 @@ -22071,7 +22072,7 @@ - + -459.0 0 0.5 0 0 0 @@ -22184,7 +22185,7 @@ - + -457.5 0 0.5 0 0 0 @@ -22297,7 +22298,7 @@ - + -456.0 0 0.5 0 0 0 @@ -22410,7 +22411,7 @@ - + -454.5 0 0.5 0 0 0 @@ -22523,7 +22524,7 @@ - + -453.0 0 0.5 0 0 0 @@ -22636,7 +22637,7 @@ - + -451.5 0 0.5 0 0 0 @@ -22749,7 +22750,7 @@ - + -450.0 0 0.5 0 0 0 @@ -22862,7 +22863,7 @@ - + -448.5 0 0.5 0 0 0 @@ -22975,7 +22976,7 @@ - + -447.0 0 0.5 0 0 0 @@ -23088,7 +23089,7 @@ - + -445.5 0 0.5 0 0 0 @@ -23201,7 +23202,7 @@ - + -444.0 0 0.5 0 0 0 @@ -23314,7 +23315,7 @@ - + -442.5 0 0.5 0 0 0 @@ -23427,7 +23428,7 @@ - + -441.0 0 0.5 0 0 0 @@ -23540,7 +23541,7 @@ - + -439.5 0 0.5 0 0 0 @@ -23653,7 +23654,7 @@ - + -438.0 0 0.5 0 0 0 @@ -23766,7 +23767,7 @@ - + -436.5 0 0.5 0 0 0 @@ -23879,7 +23880,7 @@ - + -435.0 0 0.5 0 0 0 @@ -23992,7 +23993,7 @@ - + -433.5 0 0.5 0 0 0 @@ -24105,7 +24106,7 @@ - + -432.0 0 0.5 0 0 0 @@ -24218,7 +24219,7 @@ - + -430.5 0 0.5 0 0 0 @@ -24331,7 +24332,7 @@ - + -429.0 0 0.5 0 0 0 @@ -24444,7 +24445,7 @@ - + -427.5 0 0.5 0 0 0 @@ -24557,7 +24558,7 @@ - + -426.0 0 0.5 0 0 0 @@ -24670,7 +24671,7 @@ - + -424.5 0 0.5 0 0 0 @@ -24783,7 +24784,7 @@ - + -423.0 0 0.5 0 0 0 @@ -24896,7 +24897,7 @@ - + -421.5 0 0.5 0 0 0 @@ -25009,7 +25010,7 @@ - + -420.0 0 0.5 0 0 0 @@ -25122,7 +25123,7 @@ - + -418.5 0 0.5 0 0 0 @@ -25235,7 +25236,7 @@ - + -417.0 0 0.5 0 0 0 @@ -25348,7 +25349,7 @@ - + -415.5 0 0.5 0 0 0 @@ -25461,7 +25462,7 @@ - + -414.0 0 0.5 0 0 0 @@ -25574,7 +25575,7 @@ - + -412.5 0 0.5 0 0 0 @@ -25687,7 +25688,7 @@ - + -411.0 0 0.5 0 0 0 @@ -25800,7 +25801,7 @@ - + -409.5 0 0.5 0 0 0 @@ -25913,7 +25914,7 @@ - + -408.0 0 0.5 0 0 0 @@ -26026,7 +26027,7 @@ - + -406.5 0 0.5 0 0 0 @@ -26139,7 +26140,7 @@ - + -405.0 0 0.5 0 0 0 @@ -26252,7 +26253,7 @@ - + -403.5 0 0.5 0 0 0 @@ -26365,7 +26366,7 @@ - + -402.0 0 0.5 0 0 0 @@ -26478,7 +26479,7 @@ - + -400.5 0 0.5 0 0 0 @@ -26591,7 +26592,7 @@ - + -399.0 0 0.5 0 0 0 @@ -26704,7 +26705,7 @@ - + -397.5 0 0.5 0 0 0 @@ -26817,7 +26818,7 @@ - + -396.0 0 0.5 0 0 0 @@ -26930,7 +26931,7 @@ - + -394.5 0 0.5 0 0 0 @@ -27043,7 +27044,7 @@ - + -393.0 0 0.5 0 0 0 @@ -27156,7 +27157,7 @@ - + -391.5 0 0.5 0 0 0 @@ -27269,7 +27270,7 @@ - + -390.0 0 0.5 0 0 0 @@ -27382,7 +27383,7 @@ - + -388.5 0 0.5 0 0 0 @@ -27495,7 +27496,7 @@ - + -387.0 0 0.5 0 0 0 @@ -27608,7 +27609,7 @@ - + -385.5 0 0.5 0 0 0 @@ -27721,7 +27722,7 @@ - + -384.0 0 0.5 0 0 0 @@ -27834,7 +27835,7 @@ - + -382.5 0 0.5 0 0 0 @@ -27947,7 +27948,7 @@ - + -381.0 0 0.5 0 0 0 @@ -28060,7 +28061,7 @@ - + -379.5 0 0.5 0 0 0 @@ -28173,7 +28174,7 @@ - + -378.0 0 0.5 0 0 0 @@ -28286,7 +28287,7 @@ - + -376.5 0 0.5 0 0 0 @@ -28399,7 +28400,7 @@ - + -375.0 0 0.5 0 0 0 @@ -28512,7 +28513,7 @@ - + -373.5 0 0.5 0 0 0 @@ -28625,7 +28626,7 @@ - + -372.0 0 0.5 0 0 0 @@ -28738,7 +28739,7 @@ - + -370.5 0 0.5 0 0 0 @@ -28851,7 +28852,7 @@ - + -369.0 0 0.5 0 0 0 @@ -28964,7 +28965,7 @@ - + -367.5 0 0.5 0 0 0 @@ -29077,7 +29078,7 @@ - + -366.0 0 0.5 0 0 0 @@ -29190,7 +29191,7 @@ - + -364.5 0 0.5 0 0 0 @@ -29303,7 +29304,7 @@ - + -363.0 0 0.5 0 0 0 @@ -29416,7 +29417,7 @@ - + -361.5 0 0.5 0 0 0 @@ -29529,7 +29530,7 @@ - + -360.0 0 0.5 0 0 0 @@ -29642,7 +29643,7 @@ - + -358.5 0 0.5 0 0 0 @@ -29755,7 +29756,7 @@ - + -357.0 0 0.5 0 0 0 @@ -29868,7 +29869,7 @@ - + -355.5 0 0.5 0 0 0 @@ -29981,7 +29982,7 @@ - + -354.0 0 0.5 0 0 0 @@ -30094,7 +30095,7 @@ - + -352.5 0 0.5 0 0 0 @@ -30207,7 +30208,7 @@ - + -351.0 0 0.5 0 0 0 @@ -30320,7 +30321,7 @@ - + -349.5 0 0.5 0 0 0 @@ -30433,7 +30434,7 @@ - + -348.0 0 0.5 0 0 0 @@ -30546,7 +30547,7 @@ - + -346.5 0 0.5 0 0 0 @@ -30659,7 +30660,7 @@ - + -345.0 0 0.5 0 0 0 @@ -30772,7 +30773,7 @@ - + -343.5 0 0.5 0 0 0 @@ -30885,7 +30886,7 @@ - + -342.0 0 0.5 0 0 0 @@ -30998,7 +30999,7 @@ - + -340.5 0 0.5 0 0 0 @@ -31111,7 +31112,7 @@ - + -339.0 0 0.5 0 0 0 @@ -31224,7 +31225,7 @@ - + -337.5 0 0.5 0 0 0 @@ -31337,7 +31338,7 @@ - + -336.0 0 0.5 0 0 0 @@ -31450,7 +31451,7 @@ - + -334.5 0 0.5 0 0 0 @@ -31563,7 +31564,7 @@ - + -333.0 0 0.5 0 0 0 @@ -31676,7 +31677,7 @@ - + -331.5 0 0.5 0 0 0 @@ -31789,7 +31790,7 @@ - + -330.0 0 0.5 0 0 0 @@ -31902,7 +31903,7 @@ - + -328.5 0 0.5 0 0 0 @@ -32015,7 +32016,7 @@ - + -327.0 0 0.5 0 0 0 @@ -32128,7 +32129,7 @@ - + -325.5 0 0.5 0 0 0 @@ -32241,7 +32242,7 @@ - + -324.0 0 0.5 0 0 0 @@ -32354,7 +32355,7 @@ - + -322.5 0 0.5 0 0 0 @@ -32467,7 +32468,7 @@ - + -321.0 0 0.5 0 0 0 @@ -32580,7 +32581,7 @@ - + -319.5 0 0.5 0 0 0 @@ -32693,7 +32694,7 @@ - + -318.0 0 0.5 0 0 0 @@ -32806,7 +32807,7 @@ - + -316.5 0 0.5 0 0 0 @@ -32919,7 +32920,7 @@ - + -315.0 0 0.5 0 0 0 @@ -33032,7 +33033,7 @@ - + -313.5 0 0.5 0 0 0 @@ -33145,7 +33146,7 @@ - + -312.0 0 0.5 0 0 0 @@ -33258,7 +33259,7 @@ - + -310.5 0 0.5 0 0 0 @@ -33371,7 +33372,7 @@ - + -309.0 0 0.5 0 0 0 @@ -33484,7 +33485,7 @@ - + -307.5 0 0.5 0 0 0 @@ -33597,7 +33598,7 @@ - + -306.0 0 0.5 0 0 0 @@ -33710,7 +33711,7 @@ - + -304.5 0 0.5 0 0 0 @@ -33823,7 +33824,7 @@ - + -303.0 0 0.5 0 0 0 @@ -33936,7 +33937,7 @@ - + -301.5 0 0.5 0 0 0 @@ -34049,7 +34050,7 @@ - + -300.0 0 0.5 0 0 0 @@ -34162,7 +34163,7 @@ - + -298.5 0 0.5 0 0 0 @@ -34275,7 +34276,7 @@ - + -297.0 0 0.5 0 0 0 @@ -34388,7 +34389,7 @@ - + -295.5 0 0.5 0 0 0 @@ -34501,7 +34502,7 @@ - + -294.0 0 0.5 0 0 0 @@ -34614,7 +34615,7 @@ - + -292.5 0 0.5 0 0 0 @@ -34727,7 +34728,7 @@ - + -291.0 0 0.5 0 0 0 @@ -34840,7 +34841,7 @@ - + -289.5 0 0.5 0 0 0 @@ -34953,7 +34954,7 @@ - + -288.0 0 0.5 0 0 0 @@ -35066,7 +35067,7 @@ - + -286.5 0 0.5 0 0 0 @@ -35179,7 +35180,7 @@ - + -285.0 0 0.5 0 0 0 @@ -35292,7 +35293,7 @@ - + -283.5 0 0.5 0 0 0 @@ -35405,7 +35406,7 @@ - + -282.0 0 0.5 0 0 0 @@ -35518,7 +35519,7 @@ - + -280.5 0 0.5 0 0 0 @@ -35631,7 +35632,7 @@ - + -279.0 0 0.5 0 0 0 @@ -35744,7 +35745,7 @@ - + -277.5 0 0.5 0 0 0 @@ -35857,7 +35858,7 @@ - + -276.0 0 0.5 0 0 0 @@ -35970,7 +35971,7 @@ - + -274.5 0 0.5 0 0 0 @@ -36083,7 +36084,7 @@ - + -273.0 0 0.5 0 0 0 @@ -36196,7 +36197,7 @@ - + -271.5 0 0.5 0 0 0 @@ -36309,7 +36310,7 @@ - + -270.0 0 0.5 0 0 0 @@ -36422,7 +36423,7 @@ - + -268.5 0 0.5 0 0 0 @@ -36535,7 +36536,7 @@ - + -267.0 0 0.5 0 0 0 @@ -36648,7 +36649,7 @@ - + -265.5 0 0.5 0 0 0 @@ -36761,7 +36762,7 @@ - + -264.0 0 0.5 0 0 0 @@ -36874,7 +36875,7 @@ - + -262.5 0 0.5 0 0 0 @@ -36987,7 +36988,7 @@ - + -261.0 0 0.5 0 0 0 @@ -37100,7 +37101,7 @@ - + -259.5 0 0.5 0 0 0 @@ -37213,7 +37214,7 @@ - + -258.0 0 0.5 0 0 0 @@ -37326,7 +37327,7 @@ - + -256.5 0 0.5 0 0 0 @@ -37439,7 +37440,7 @@ - + -255.0 0 0.5 0 0 0 @@ -37552,7 +37553,7 @@ - + -253.5 0 0.5 0 0 0 @@ -37665,7 +37666,7 @@ - + -252.0 0 0.5 0 0 0 @@ -37778,7 +37779,7 @@ - + -250.5 0 0.5 0 0 0 @@ -37891,7 +37892,7 @@ - + -249.0 0 0.5 0 0 0 @@ -38004,7 +38005,7 @@ - + -247.5 0 0.5 0 0 0 @@ -38117,7 +38118,7 @@ - + -246.0 0 0.5 0 0 0 @@ -38230,7 +38231,7 @@ - + -244.5 0 0.5 0 0 0 @@ -38343,7 +38344,7 @@ - + -243.0 0 0.5 0 0 0 @@ -38456,7 +38457,7 @@ - + -241.5 0 0.5 0 0 0 @@ -38569,7 +38570,7 @@ - + -240.0 0 0.5 0 0 0 @@ -38682,7 +38683,7 @@ - + -238.5 0 0.5 0 0 0 @@ -38795,7 +38796,7 @@ - + -237.0 0 0.5 0 0 0 @@ -38908,7 +38909,7 @@ - + -235.5 0 0.5 0 0 0 @@ -39021,7 +39022,7 @@ - + -234.0 0 0.5 0 0 0 @@ -39134,7 +39135,7 @@ - + -232.5 0 0.5 0 0 0 @@ -39247,7 +39248,7 @@ - + -231.0 0 0.5 0 0 0 @@ -39360,7 +39361,7 @@ - + -229.5 0 0.5 0 0 0 @@ -39473,7 +39474,7 @@ - + -228.0 0 0.5 0 0 0 @@ -39586,7 +39587,7 @@ - + -226.5 0 0.5 0 0 0 @@ -39699,7 +39700,7 @@ - + -225.0 0 0.5 0 0 0 @@ -39812,7 +39813,7 @@ - + -223.5 0 0.5 0 0 0 @@ -39925,7 +39926,7 @@ - + -222.0 0 0.5 0 0 0 @@ -40038,7 +40039,7 @@ - + -220.5 0 0.5 0 0 0 @@ -40151,7 +40152,7 @@ - + -219.0 0 0.5 0 0 0 @@ -40264,7 +40265,7 @@ - + -217.5 0 0.5 0 0 0 @@ -40377,7 +40378,7 @@ - + -216.0 0 0.5 0 0 0 @@ -40490,7 +40491,7 @@ - + -214.5 0 0.5 0 0 0 @@ -40603,7 +40604,7 @@ - + -213.0 0 0.5 0 0 0 @@ -40716,7 +40717,7 @@ - + -211.5 0 0.5 0 0 0 @@ -40829,7 +40830,7 @@ - + -210.0 0 0.5 0 0 0 @@ -40942,7 +40943,7 @@ - + -208.5 0 0.5 0 0 0 @@ -41055,7 +41056,7 @@ - + -207.0 0 0.5 0 0 0 @@ -41168,7 +41169,7 @@ - + -205.5 0 0.5 0 0 0 @@ -41281,7 +41282,7 @@ - + -204.0 0 0.5 0 0 0 @@ -41394,7 +41395,7 @@ - + -202.5 0 0.5 0 0 0 @@ -41507,7 +41508,7 @@ - + -201.0 0 0.5 0 0 0 @@ -41620,7 +41621,7 @@ - + -199.5 0 0.5 0 0 0 @@ -41733,7 +41734,7 @@ - + -198.0 0 0.5 0 0 0 @@ -41846,7 +41847,7 @@ - + -196.5 0 0.5 0 0 0 @@ -41959,7 +41960,7 @@ - + -195.0 0 0.5 0 0 0 @@ -42072,7 +42073,7 @@ - + -193.5 0 0.5 0 0 0 @@ -42185,7 +42186,7 @@ - + -192.0 0 0.5 0 0 0 @@ -42298,7 +42299,7 @@ - + -190.5 0 0.5 0 0 0 @@ -42411,7 +42412,7 @@ - + -189.0 0 0.5 0 0 0 @@ -42524,7 +42525,7 @@ - + -187.5 0 0.5 0 0 0 @@ -42637,7 +42638,7 @@ - + -186.0 0 0.5 0 0 0 @@ -42750,7 +42751,7 @@ - + -184.5 0 0.5 0 0 0 @@ -42863,7 +42864,7 @@ - + -183.0 0 0.5 0 0 0 @@ -42976,7 +42977,7 @@ - + -181.5 0 0.5 0 0 0 @@ -43089,7 +43090,7 @@ - + -180.0 0 0.5 0 0 0 @@ -43202,7 +43203,7 @@ - + -178.5 0 0.5 0 0 0 @@ -43315,7 +43316,7 @@ - + -177.0 0 0.5 0 0 0 @@ -43428,7 +43429,7 @@ - + -175.5 0 0.5 0 0 0 @@ -43541,7 +43542,7 @@ - + -174.0 0 0.5 0 0 0 @@ -43654,7 +43655,7 @@ - + -172.5 0 0.5 0 0 0 @@ -43767,7 +43768,7 @@ - + -171.0 0 0.5 0 0 0 @@ -43880,7 +43881,7 @@ - + -169.5 0 0.5 0 0 0 @@ -43993,7 +43994,7 @@ - + -168.0 0 0.5 0 0 0 @@ -44106,7 +44107,7 @@ - + -166.5 0 0.5 0 0 0 @@ -44219,7 +44220,7 @@ - + -165.0 0 0.5 0 0 0 @@ -44332,7 +44333,7 @@ - + -163.5 0 0.5 0 0 0 @@ -44445,7 +44446,7 @@ - + -162.0 0 0.5 0 0 0 @@ -44558,7 +44559,7 @@ - + -160.5 0 0.5 0 0 0 @@ -44671,7 +44672,7 @@ - + -159.0 0 0.5 0 0 0 @@ -44784,7 +44785,7 @@ - + -157.5 0 0.5 0 0 0 @@ -44897,7 +44898,7 @@ - + -156.0 0 0.5 0 0 0 @@ -45010,7 +45011,7 @@ - + -154.5 0 0.5 0 0 0 @@ -45123,7 +45124,7 @@ - + -153.0 0 0.5 0 0 0 @@ -45236,7 +45237,7 @@ - + -151.5 0 0.5 0 0 0 @@ -45349,7 +45350,7 @@ - + -150.0 0 0.5 0 0 0 @@ -45462,7 +45463,7 @@ - + -148.5 0 0.5 0 0 0 @@ -45575,7 +45576,7 @@ - + -147.0 0 0.5 0 0 0 @@ -45688,7 +45689,7 @@ - + -145.5 0 0.5 0 0 0 @@ -45801,7 +45802,7 @@ - + -144.0 0 0.5 0 0 0 @@ -45914,7 +45915,7 @@ - + -142.5 0 0.5 0 0 0 @@ -46027,7 +46028,7 @@ - + -141.0 0 0.5 0 0 0 @@ -46140,7 +46141,7 @@ - + -139.5 0 0.5 0 0 0 @@ -46253,7 +46254,7 @@ - + -138.0 0 0.5 0 0 0 @@ -46366,7 +46367,7 @@ - + -136.5 0 0.5 0 0 0 @@ -46479,7 +46480,7 @@ - + -135.0 0 0.5 0 0 0 @@ -46592,7 +46593,7 @@ - + -133.5 0 0.5 0 0 0 @@ -46705,7 +46706,7 @@ - + -132.0 0 0.5 0 0 0 @@ -46818,7 +46819,7 @@ - + -130.5 0 0.5 0 0 0 @@ -46931,7 +46932,7 @@ - + -129.0 0 0.5 0 0 0 @@ -47044,7 +47045,7 @@ - + -127.5 0 0.5 0 0 0 @@ -47157,7 +47158,7 @@ - + -126.0 0 0.5 0 0 0 @@ -47270,7 +47271,7 @@ - + -124.5 0 0.5 0 0 0 @@ -47383,7 +47384,7 @@ - + -123.0 0 0.5 0 0 0 @@ -47496,7 +47497,7 @@ - + -121.5 0 0.5 0 0 0 @@ -47609,7 +47610,7 @@ - + -120.0 0 0.5 0 0 0 @@ -47722,7 +47723,7 @@ - + -118.5 0 0.5 0 0 0 @@ -47835,7 +47836,7 @@ - + -117.0 0 0.5 0 0 0 @@ -47948,7 +47949,7 @@ - + -115.5 0 0.5 0 0 0 @@ -48061,7 +48062,7 @@ - + -114.0 0 0.5 0 0 0 @@ -48174,7 +48175,7 @@ - + -112.5 0 0.5 0 0 0 @@ -48287,7 +48288,7 @@ - + -111.0 0 0.5 0 0 0 @@ -48400,7 +48401,7 @@ - + -109.5 0 0.5 0 0 0 @@ -48513,7 +48514,7 @@ - + -108.0 0 0.5 0 0 0 @@ -48626,7 +48627,7 @@ - + -106.5 0 0.5 0 0 0 @@ -48739,7 +48740,7 @@ - + -105.0 0 0.5 0 0 0 @@ -48852,7 +48853,7 @@ - + -103.5 0 0.5 0 0 0 @@ -48965,7 +48966,7 @@ - + -102.0 0 0.5 0 0 0 @@ -49078,7 +49079,7 @@ - + -100.5 0 0.5 0 0 0 @@ -49191,7 +49192,7 @@ - + -99.0 0 0.5 0 0 0 @@ -49304,7 +49305,7 @@ - + -97.5 0 0.5 0 0 0 @@ -49417,7 +49418,7 @@ - + -96.0 0 0.5 0 0 0 @@ -49530,7 +49531,7 @@ - + -94.5 0 0.5 0 0 0 @@ -49643,7 +49644,7 @@ - + -93.0 0 0.5 0 0 0 @@ -49756,7 +49757,7 @@ - + -91.5 0 0.5 0 0 0 @@ -49869,7 +49870,7 @@ - + -90.0 0 0.5 0 0 0 @@ -49982,7 +49983,7 @@ - + -88.5 0 0.5 0 0 0 @@ -50095,7 +50096,7 @@ - + -87.0 0 0.5 0 0 0 @@ -50208,7 +50209,7 @@ - + -85.5 0 0.5 0 0 0 @@ -50321,7 +50322,7 @@ - + -84.0 0 0.5 0 0 0 @@ -50434,7 +50435,7 @@ - + -82.5 0 0.5 0 0 0 @@ -50547,7 +50548,7 @@ - + -81.0 0 0.5 0 0 0 @@ -50660,7 +50661,7 @@ - + -79.5 0 0.5 0 0 0 @@ -50773,7 +50774,7 @@ - + -78.0 0 0.5 0 0 0 @@ -50886,7 +50887,7 @@ - + -76.5 0 0.5 0 0 0 @@ -50999,7 +51000,7 @@ - + -75.0 0 0.5 0 0 0 @@ -51112,7 +51113,7 @@ - + -73.5 0 0.5 0 0 0 @@ -51225,7 +51226,7 @@ - + -72.0 0 0.5 0 0 0 @@ -51338,7 +51339,7 @@ - + -70.5 0 0.5 0 0 0 @@ -51451,7 +51452,7 @@ - + -69.0 0 0.5 0 0 0 @@ -51564,7 +51565,7 @@ - + -67.5 0 0.5 0 0 0 @@ -51677,7 +51678,7 @@ - + -66.0 0 0.5 0 0 0 @@ -51790,7 +51791,7 @@ - + -64.5 0 0.5 0 0 0 @@ -51903,7 +51904,7 @@ - + -63.0 0 0.5 0 0 0 @@ -52016,7 +52017,7 @@ - + -61.5 0 0.5 0 0 0 @@ -52129,7 +52130,7 @@ - + -60.0 0 0.5 0 0 0 @@ -52242,7 +52243,7 @@ - + -58.5 0 0.5 0 0 0 @@ -52355,7 +52356,7 @@ - + -57.0 0 0.5 0 0 0 @@ -52468,7 +52469,7 @@ - + -55.5 0 0.5 0 0 0 @@ -52581,7 +52582,7 @@ - + -54.0 0 0.5 0 0 0 @@ -52694,7 +52695,7 @@ - + -52.5 0 0.5 0 0 0 @@ -52807,7 +52808,7 @@ - + -51.0 0 0.5 0 0 0 @@ -52920,7 +52921,7 @@ - + -49.5 0 0.5 0 0 0 @@ -53033,7 +53034,7 @@ - + -48.0 0 0.5 0 0 0 @@ -53146,7 +53147,7 @@ - + -46.5 0 0.5 0 0 0 @@ -53259,7 +53260,7 @@ - + -45.0 0 0.5 0 0 0 @@ -53372,7 +53373,7 @@ - + -43.5 0 0.5 0 0 0 @@ -53485,7 +53486,7 @@ - + -42.0 0 0.5 0 0 0 @@ -53598,7 +53599,7 @@ - + -40.5 0 0.5 0 0 0 @@ -53711,7 +53712,7 @@ - + -39.0 0 0.5 0 0 0 @@ -53824,7 +53825,7 @@ - + -37.5 0 0.5 0 0 0 @@ -53937,7 +53938,7 @@ - + -36.0 0 0.5 0 0 0 @@ -54050,7 +54051,7 @@ - + -34.5 0 0.5 0 0 0 @@ -54163,7 +54164,7 @@ - + -33.0 0 0.5 0 0 0 @@ -54276,7 +54277,7 @@ - + -31.5 0 0.5 0 0 0 @@ -54389,7 +54390,7 @@ - + -30.0 0 0.5 0 0 0 @@ -54502,7 +54503,7 @@ - + -28.5 0 0.5 0 0 0 @@ -54615,7 +54616,7 @@ - + -27.0 0 0.5 0 0 0 @@ -54728,7 +54729,7 @@ - + -25.5 0 0.5 0 0 0 @@ -54841,7 +54842,7 @@ - + -24.0 0 0.5 0 0 0 @@ -54954,7 +54955,7 @@ - + -22.5 0 0.5 0 0 0 @@ -55067,7 +55068,7 @@ - + -21.0 0 0.5 0 0 0 @@ -55180,7 +55181,7 @@ - + -19.5 0 0.5 0 0 0 @@ -55293,7 +55294,7 @@ - + -18.0 0 0.5 0 0 0 @@ -55406,7 +55407,7 @@ - + -16.5 0 0.5 0 0 0 @@ -55519,7 +55520,7 @@ - + -15.0 0 0.5 0 0 0 @@ -55632,7 +55633,7 @@ - + -13.5 0 0.5 0 0 0 @@ -55745,7 +55746,7 @@ - + -12.0 0 0.5 0 0 0 @@ -55858,7 +55859,7 @@ - + -10.5 0 0.5 0 0 0 @@ -55971,7 +55972,7 @@ - + -9.0 0 0.5 0 0 0 @@ -56084,7 +56085,7 @@ - + -7.5 0 0.5 0 0 0 @@ -56197,7 +56198,7 @@ - + -6.0 0 0.5 0 0 0 @@ -56310,7 +56311,7 @@ - + -4.5 0 0.5 0 0 0 @@ -56423,7 +56424,7 @@ - + -3.0 0 0.5 0 0 0 @@ -56536,7 +56537,7 @@ - + -1.5 0 0.5 0 0 0 @@ -56649,7 +56650,7 @@ - + 0.0 0 0.5 0 0 0 @@ -56762,7 +56763,7 @@ - + 1.5 0 0.5 0 0 0 @@ -56875,7 +56876,7 @@ - + 3.0 0 0.5 0 0 0 @@ -56988,7 +56989,7 @@ - + 4.5 0 0.5 0 0 0 @@ -57101,7 +57102,7 @@ - + 6.0 0 0.5 0 0 0 @@ -57214,7 +57215,7 @@ - + 7.5 0 0.5 0 0 0 @@ -57327,7 +57328,7 @@ - + 9.0 0 0.5 0 0 0 @@ -57440,7 +57441,7 @@ - + 10.5 0 0.5 0 0 0 @@ -57553,7 +57554,7 @@ - + 12.0 0 0.5 0 0 0 @@ -57666,7 +57667,7 @@ - + 13.5 0 0.5 0 0 0 @@ -57779,7 +57780,7 @@ - + 15.0 0 0.5 0 0 0 @@ -57892,7 +57893,7 @@ - + 16.5 0 0.5 0 0 0 @@ -58005,7 +58006,7 @@ - + 18.0 0 0.5 0 0 0 @@ -58118,7 +58119,7 @@ - + 19.5 0 0.5 0 0 0 @@ -58231,7 +58232,7 @@ - + 21.0 0 0.5 0 0 0 @@ -58344,7 +58345,7 @@ - + 22.5 0 0.5 0 0 0 @@ -58457,7 +58458,7 @@ - + 24.0 0 0.5 0 0 0 @@ -58570,7 +58571,7 @@ - + 25.5 0 0.5 0 0 0 @@ -58683,7 +58684,7 @@ - + 27.0 0 0.5 0 0 0 @@ -58796,7 +58797,7 @@ - + 28.5 0 0.5 0 0 0 @@ -58909,7 +58910,7 @@ - + 30.0 0 0.5 0 0 0 @@ -59022,7 +59023,7 @@ - + 31.5 0 0.5 0 0 0 @@ -59135,7 +59136,7 @@ - + 33.0 0 0.5 0 0 0 @@ -59248,7 +59249,7 @@ - + 34.5 0 0.5 0 0 0 @@ -59361,7 +59362,7 @@ - + 36.0 0 0.5 0 0 0 @@ -59474,7 +59475,7 @@ - + 37.5 0 0.5 0 0 0 @@ -59587,7 +59588,7 @@ - + 39.0 0 0.5 0 0 0 @@ -59700,7 +59701,7 @@ - + 40.5 0 0.5 0 0 0 @@ -59813,7 +59814,7 @@ - + 42.0 0 0.5 0 0 0 @@ -59926,7 +59927,7 @@ - + 43.5 0 0.5 0 0 0 @@ -60039,7 +60040,7 @@ - + 45.0 0 0.5 0 0 0 @@ -60152,7 +60153,7 @@ - + 46.5 0 0.5 0 0 0 @@ -60265,7 +60266,7 @@ - + 48.0 0 0.5 0 0 0 @@ -60378,7 +60379,7 @@ - + 49.5 0 0.5 0 0 0 @@ -60491,7 +60492,7 @@ - + 51.0 0 0.5 0 0 0 @@ -60604,7 +60605,7 @@ - + 52.5 0 0.5 0 0 0 @@ -60717,7 +60718,7 @@ - + 54.0 0 0.5 0 0 0 @@ -60830,7 +60831,7 @@ - + 55.5 0 0.5 0 0 0 @@ -60943,7 +60944,7 @@ - + 57.0 0 0.5 0 0 0 @@ -61056,7 +61057,7 @@ - + 58.5 0 0.5 0 0 0 @@ -61169,7 +61170,7 @@ - + 60.0 0 0.5 0 0 0 @@ -61282,7 +61283,7 @@ - + 61.5 0 0.5 0 0 0 @@ -61395,7 +61396,7 @@ - + 63.0 0 0.5 0 0 0 @@ -61508,7 +61509,7 @@ - + 64.5 0 0.5 0 0 0 @@ -61621,7 +61622,7 @@ - + 66.0 0 0.5 0 0 0 @@ -61734,7 +61735,7 @@ - + 67.5 0 0.5 0 0 0 @@ -61847,7 +61848,7 @@ - + 69.0 0 0.5 0 0 0 @@ -61960,7 +61961,7 @@ - + 70.5 0 0.5 0 0 0 @@ -62073,7 +62074,7 @@ - + 72.0 0 0.5 0 0 0 @@ -62186,7 +62187,7 @@ - + 73.5 0 0.5 0 0 0 @@ -62299,7 +62300,7 @@ - + 75.0 0 0.5 0 0 0 @@ -62412,7 +62413,7 @@ - + 76.5 0 0.5 0 0 0 @@ -62525,7 +62526,7 @@ - + 78.0 0 0.5 0 0 0 @@ -62638,7 +62639,7 @@ - + 79.5 0 0.5 0 0 0 @@ -62751,7 +62752,7 @@ - + 81.0 0 0.5 0 0 0 @@ -62864,7 +62865,7 @@ - + 82.5 0 0.5 0 0 0 @@ -62977,7 +62978,7 @@ - + 84.0 0 0.5 0 0 0 @@ -63090,7 +63091,7 @@ - + 85.5 0 0.5 0 0 0 @@ -63203,7 +63204,7 @@ - + 87.0 0 0.5 0 0 0 @@ -63316,7 +63317,7 @@ - + 88.5 0 0.5 0 0 0 @@ -63429,7 +63430,7 @@ - + 90.0 0 0.5 0 0 0 @@ -63542,7 +63543,7 @@ - + 91.5 0 0.5 0 0 0 @@ -63655,7 +63656,7 @@ - + 93.0 0 0.5 0 0 0 @@ -63768,7 +63769,7 @@ - + 94.5 0 0.5 0 0 0 @@ -63881,7 +63882,7 @@ - + 96.0 0 0.5 0 0 0 @@ -63994,7 +63995,7 @@ - + 97.5 0 0.5 0 0 0 @@ -64107,7 +64108,7 @@ - + 99.0 0 0.5 0 0 0 @@ -64220,7 +64221,7 @@ - + 100.5 0 0.5 0 0 0 @@ -64333,7 +64334,7 @@ - + 102.0 0 0.5 0 0 0 @@ -64446,7 +64447,7 @@ - + 103.5 0 0.5 0 0 0 @@ -64559,7 +64560,7 @@ - + 105.0 0 0.5 0 0 0 @@ -64672,7 +64673,7 @@ - + 106.5 0 0.5 0 0 0 @@ -64785,7 +64786,7 @@ - + 108.0 0 0.5 0 0 0 @@ -64898,7 +64899,7 @@ - + 109.5 0 0.5 0 0 0 @@ -65011,7 +65012,7 @@ - + 111.0 0 0.5 0 0 0 @@ -65124,7 +65125,7 @@ - + 112.5 0 0.5 0 0 0 @@ -65237,7 +65238,7 @@ - + 114.0 0 0.5 0 0 0 @@ -65350,7 +65351,7 @@ - + 115.5 0 0.5 0 0 0 @@ -65463,7 +65464,7 @@ - + 117.0 0 0.5 0 0 0 @@ -65576,7 +65577,7 @@ - + 118.5 0 0.5 0 0 0 @@ -65689,7 +65690,7 @@ - + 120.0 0 0.5 0 0 0 @@ -65802,7 +65803,7 @@ - + 121.5 0 0.5 0 0 0 @@ -65915,7 +65916,7 @@ - + 123.0 0 0.5 0 0 0 @@ -66028,7 +66029,7 @@ - + 124.5 0 0.5 0 0 0 @@ -66141,7 +66142,7 @@ - + 126.0 0 0.5 0 0 0 @@ -66254,7 +66255,7 @@ - + 127.5 0 0.5 0 0 0 @@ -66367,7 +66368,7 @@ - + 129.0 0 0.5 0 0 0 @@ -66480,7 +66481,7 @@ - + 130.5 0 0.5 0 0 0 @@ -66593,7 +66594,7 @@ - + 132.0 0 0.5 0 0 0 @@ -66706,7 +66707,7 @@ - + 133.5 0 0.5 0 0 0 @@ -66819,7 +66820,7 @@ - + 135.0 0 0.5 0 0 0 @@ -66932,7 +66933,7 @@ - + 136.5 0 0.5 0 0 0 @@ -67045,7 +67046,7 @@ - + 138.0 0 0.5 0 0 0 @@ -67158,7 +67159,7 @@ - + 139.5 0 0.5 0 0 0 @@ -67271,7 +67272,7 @@ - + 141.0 0 0.5 0 0 0 @@ -67384,7 +67385,7 @@ - + 142.5 0 0.5 0 0 0 @@ -67497,7 +67498,7 @@ - + 144.0 0 0.5 0 0 0 @@ -67610,7 +67611,7 @@ - + 145.5 0 0.5 0 0 0 @@ -67723,7 +67724,7 @@ - + 147.0 0 0.5 0 0 0 @@ -67836,7 +67837,7 @@ - + 148.5 0 0.5 0 0 0 @@ -67949,7 +67950,7 @@ - + 150.0 0 0.5 0 0 0 @@ -68062,7 +68063,7 @@ - + 151.5 0 0.5 0 0 0 @@ -68175,7 +68176,7 @@ - + 153.0 0 0.5 0 0 0 @@ -68288,7 +68289,7 @@ - + 154.5 0 0.5 0 0 0 @@ -68401,7 +68402,7 @@ - + 156.0 0 0.5 0 0 0 @@ -68514,7 +68515,7 @@ - + 157.5 0 0.5 0 0 0 @@ -68627,7 +68628,7 @@ - + 159.0 0 0.5 0 0 0 @@ -68740,7 +68741,7 @@ - + 160.5 0 0.5 0 0 0 @@ -68853,7 +68854,7 @@ - + 162.0 0 0.5 0 0 0 @@ -68966,7 +68967,7 @@ - + 163.5 0 0.5 0 0 0 @@ -69079,7 +69080,7 @@ - + 165.0 0 0.5 0 0 0 @@ -69192,7 +69193,7 @@ - + 166.5 0 0.5 0 0 0 @@ -69305,7 +69306,7 @@ - + 168.0 0 0.5 0 0 0 @@ -69418,7 +69419,7 @@ - + 169.5 0 0.5 0 0 0 @@ -69531,7 +69532,7 @@ - + 171.0 0 0.5 0 0 0 @@ -69644,7 +69645,7 @@ - + 172.5 0 0.5 0 0 0 @@ -69757,7 +69758,7 @@ - + 174.0 0 0.5 0 0 0 @@ -69870,7 +69871,7 @@ - + 175.5 0 0.5 0 0 0 @@ -69983,7 +69984,7 @@ - + 177.0 0 0.5 0 0 0 @@ -70096,7 +70097,7 @@ - + 178.5 0 0.5 0 0 0 @@ -70209,7 +70210,7 @@ - + 180.0 0 0.5 0 0 0 @@ -70322,7 +70323,7 @@ - + 181.5 0 0.5 0 0 0 @@ -70435,7 +70436,7 @@ - + 183.0 0 0.5 0 0 0 @@ -70548,7 +70549,7 @@ - + 184.5 0 0.5 0 0 0 @@ -70661,7 +70662,7 @@ - + 186.0 0 0.5 0 0 0 @@ -70774,7 +70775,7 @@ - + 187.5 0 0.5 0 0 0 @@ -70887,7 +70888,7 @@ - + 189.0 0 0.5 0 0 0 @@ -71000,7 +71001,7 @@ - + 190.5 0 0.5 0 0 0 @@ -71113,7 +71114,7 @@ - + 192.0 0 0.5 0 0 0 @@ -71226,7 +71227,7 @@ - + 193.5 0 0.5 0 0 0 @@ -71339,7 +71340,7 @@ - + 195.0 0 0.5 0 0 0 @@ -71452,7 +71453,7 @@ - + 196.5 0 0.5 0 0 0 @@ -71565,7 +71566,7 @@ - + 198.0 0 0.5 0 0 0 @@ -71678,7 +71679,7 @@ - + 199.5 0 0.5 0 0 0 @@ -71791,7 +71792,7 @@ - + 201.0 0 0.5 0 0 0 @@ -71904,7 +71905,7 @@ - + 202.5 0 0.5 0 0 0 @@ -72017,7 +72018,7 @@ - + 204.0 0 0.5 0 0 0 @@ -72130,7 +72131,7 @@ - + 205.5 0 0.5 0 0 0 @@ -72243,7 +72244,7 @@ - + 207.0 0 0.5 0 0 0 @@ -72356,7 +72357,7 @@ - + 208.5 0 0.5 0 0 0 @@ -72469,7 +72470,7 @@ - + 210.0 0 0.5 0 0 0 @@ -72582,7 +72583,7 @@ - + 211.5 0 0.5 0 0 0 @@ -72695,7 +72696,7 @@ - + 213.0 0 0.5 0 0 0 @@ -72808,7 +72809,7 @@ - + 214.5 0 0.5 0 0 0 @@ -72921,7 +72922,7 @@ - + 216.0 0 0.5 0 0 0 @@ -73034,7 +73035,7 @@ - + 217.5 0 0.5 0 0 0 @@ -73147,7 +73148,7 @@ - + 219.0 0 0.5 0 0 0 @@ -73260,7 +73261,7 @@ - + 220.5 0 0.5 0 0 0 @@ -73373,7 +73374,7 @@ - + 222.0 0 0.5 0 0 0 @@ -73486,7 +73487,7 @@ - + 223.5 0 0.5 0 0 0 @@ -73599,7 +73600,7 @@ - + 225.0 0 0.5 0 0 0 @@ -73712,7 +73713,7 @@ - + 226.5 0 0.5 0 0 0 @@ -73825,7 +73826,7 @@ - + 228.0 0 0.5 0 0 0 @@ -73938,7 +73939,7 @@ - + 229.5 0 0.5 0 0 0 @@ -74051,7 +74052,7 @@ - + 231.0 0 0.5 0 0 0 @@ -74164,7 +74165,7 @@ - + 232.5 0 0.5 0 0 0 @@ -74277,7 +74278,7 @@ - + 234.0 0 0.5 0 0 0 @@ -74390,7 +74391,7 @@ - + 235.5 0 0.5 0 0 0 @@ -74503,7 +74504,7 @@ - + 237.0 0 0.5 0 0 0 @@ -74616,7 +74617,7 @@ - + 238.5 0 0.5 0 0 0 @@ -74729,7 +74730,7 @@ - + 240.0 0 0.5 0 0 0 @@ -74842,7 +74843,7 @@ - + 241.5 0 0.5 0 0 0 @@ -74955,7 +74956,7 @@ - + 243.0 0 0.5 0 0 0 @@ -75068,7 +75069,7 @@ - + 244.5 0 0.5 0 0 0 @@ -75181,7 +75182,7 @@ - + 246.0 0 0.5 0 0 0 @@ -75294,7 +75295,7 @@ - + 247.5 0 0.5 0 0 0 @@ -75407,7 +75408,7 @@ - + 249.0 0 0.5 0 0 0 @@ -75520,7 +75521,7 @@ - + 250.5 0 0.5 0 0 0 @@ -75633,7 +75634,7 @@ - + 252.0 0 0.5 0 0 0 @@ -75746,7 +75747,7 @@ - + 253.5 0 0.5 0 0 0 @@ -75859,7 +75860,7 @@ - + 255.0 0 0.5 0 0 0 @@ -75972,7 +75973,7 @@ - + 256.5 0 0.5 0 0 0 @@ -76085,7 +76086,7 @@ - + 258.0 0 0.5 0 0 0 @@ -76198,7 +76199,7 @@ - + 259.5 0 0.5 0 0 0 @@ -76311,7 +76312,7 @@ - + 261.0 0 0.5 0 0 0 @@ -76424,7 +76425,7 @@ - + 262.5 0 0.5 0 0 0 @@ -76537,7 +76538,7 @@ - + 264.0 0 0.5 0 0 0 @@ -76650,7 +76651,7 @@ - + 265.5 0 0.5 0 0 0 @@ -76763,7 +76764,7 @@ - + 267.0 0 0.5 0 0 0 @@ -76876,7 +76877,7 @@ - + 268.5 0 0.5 0 0 0 @@ -76989,7 +76990,7 @@ - + 270.0 0 0.5 0 0 0 @@ -77102,7 +77103,7 @@ - + 271.5 0 0.5 0 0 0 @@ -77215,7 +77216,7 @@ - + 273.0 0 0.5 0 0 0 @@ -77328,7 +77329,7 @@ - + 274.5 0 0.5 0 0 0 @@ -77441,7 +77442,7 @@ - + 276.0 0 0.5 0 0 0 @@ -77554,7 +77555,7 @@ - + 277.5 0 0.5 0 0 0 @@ -77667,7 +77668,7 @@ - + 279.0 0 0.5 0 0 0 @@ -77780,7 +77781,7 @@ - + 280.5 0 0.5 0 0 0 @@ -77893,7 +77894,7 @@ - + 282.0 0 0.5 0 0 0 @@ -78006,7 +78007,7 @@ - + 283.5 0 0.5 0 0 0 @@ -78119,7 +78120,7 @@ - + 285.0 0 0.5 0 0 0 @@ -78232,7 +78233,7 @@ - + 286.5 0 0.5 0 0 0 @@ -78345,7 +78346,7 @@ - + 288.0 0 0.5 0 0 0 @@ -78458,7 +78459,7 @@ - + 289.5 0 0.5 0 0 0 @@ -78571,7 +78572,7 @@ - + 291.0 0 0.5 0 0 0 @@ -78684,7 +78685,7 @@ - + 292.5 0 0.5 0 0 0 @@ -78797,7 +78798,7 @@ - + 294.0 0 0.5 0 0 0 @@ -78910,7 +78911,7 @@ - + 295.5 0 0.5 0 0 0 @@ -79023,7 +79024,7 @@ - + 297.0 0 0.5 0 0 0 @@ -79136,7 +79137,7 @@ - + 298.5 0 0.5 0 0 0 @@ -79249,7 +79250,7 @@ - + 300.0 0 0.5 0 0 0 @@ -79362,7 +79363,7 @@ - + 301.5 0 0.5 0 0 0 @@ -79475,7 +79476,7 @@ - + 303.0 0 0.5 0 0 0 @@ -79588,7 +79589,7 @@ - + 304.5 0 0.5 0 0 0 @@ -79701,7 +79702,7 @@ - + 306.0 0 0.5 0 0 0 @@ -79814,7 +79815,7 @@ - + 307.5 0 0.5 0 0 0 @@ -79927,7 +79928,7 @@ - + 309.0 0 0.5 0 0 0 @@ -80040,7 +80041,7 @@ - + 310.5 0 0.5 0 0 0 @@ -80153,7 +80154,7 @@ - + 312.0 0 0.5 0 0 0 @@ -80266,7 +80267,7 @@ - + 313.5 0 0.5 0 0 0 @@ -80379,7 +80380,7 @@ - + 315.0 0 0.5 0 0 0 @@ -80492,7 +80493,7 @@ - + 316.5 0 0.5 0 0 0 @@ -80605,7 +80606,7 @@ - + 318.0 0 0.5 0 0 0 @@ -80718,7 +80719,7 @@ - + 319.5 0 0.5 0 0 0 @@ -80831,7 +80832,7 @@ - + 321.0 0 0.5 0 0 0 @@ -80944,7 +80945,7 @@ - + 322.5 0 0.5 0 0 0 @@ -81057,7 +81058,7 @@ - + 324.0 0 0.5 0 0 0 @@ -81170,7 +81171,7 @@ - + 325.5 0 0.5 0 0 0 @@ -81283,7 +81284,7 @@ - + 327.0 0 0.5 0 0 0 @@ -81396,7 +81397,7 @@ - + 328.5 0 0.5 0 0 0 @@ -81509,7 +81510,7 @@ - + 330.0 0 0.5 0 0 0 @@ -81622,7 +81623,7 @@ - + 331.5 0 0.5 0 0 0 @@ -81735,7 +81736,7 @@ - + 333.0 0 0.5 0 0 0 @@ -81848,7 +81849,7 @@ - + 334.5 0 0.5 0 0 0 @@ -81961,7 +81962,7 @@ - + 336.0 0 0.5 0 0 0 @@ -82074,7 +82075,7 @@ - + 337.5 0 0.5 0 0 0 @@ -82187,7 +82188,7 @@ - + 339.0 0 0.5 0 0 0 @@ -82300,7 +82301,7 @@ - + 340.5 0 0.5 0 0 0 @@ -82413,7 +82414,7 @@ - + 342.0 0 0.5 0 0 0 @@ -82526,7 +82527,7 @@ - + 343.5 0 0.5 0 0 0 @@ -82639,7 +82640,7 @@ - + 345.0 0 0.5 0 0 0 @@ -82752,7 +82753,7 @@ - + 346.5 0 0.5 0 0 0 @@ -82865,7 +82866,7 @@ - + 348.0 0 0.5 0 0 0 @@ -82978,7 +82979,7 @@ - + 349.5 0 0.5 0 0 0 @@ -83091,7 +83092,7 @@ - + 351.0 0 0.5 0 0 0 @@ -83204,7 +83205,7 @@ - + 352.5 0 0.5 0 0 0 @@ -83317,7 +83318,7 @@ - + 354.0 0 0.5 0 0 0 @@ -83430,7 +83431,7 @@ - + 355.5 0 0.5 0 0 0 @@ -83543,7 +83544,7 @@ - + 357.0 0 0.5 0 0 0 @@ -83656,7 +83657,7 @@ - + 358.5 0 0.5 0 0 0 @@ -83769,7 +83770,7 @@ - + 360.0 0 0.5 0 0 0 @@ -83882,7 +83883,7 @@ - + 361.5 0 0.5 0 0 0 @@ -83995,7 +83996,7 @@ - + 363.0 0 0.5 0 0 0 @@ -84108,7 +84109,7 @@ - + 364.5 0 0.5 0 0 0 @@ -84221,7 +84222,7 @@ - + 366.0 0 0.5 0 0 0 @@ -84334,7 +84335,7 @@ - + 367.5 0 0.5 0 0 0 @@ -84447,7 +84448,7 @@ - + 369.0 0 0.5 0 0 0 @@ -84560,7 +84561,7 @@ - + 370.5 0 0.5 0 0 0 @@ -84673,7 +84674,7 @@ - + 372.0 0 0.5 0 0 0 @@ -84786,7 +84787,7 @@ - + 373.5 0 0.5 0 0 0 @@ -84899,7 +84900,7 @@ - + 375.0 0 0.5 0 0 0 @@ -85012,7 +85013,7 @@ - + 376.5 0 0.5 0 0 0 @@ -85125,7 +85126,7 @@ - + 378.0 0 0.5 0 0 0 @@ -85238,7 +85239,7 @@ - + 379.5 0 0.5 0 0 0 @@ -85351,7 +85352,7 @@ - + 381.0 0 0.5 0 0 0 @@ -85464,7 +85465,7 @@ - + 382.5 0 0.5 0 0 0 @@ -85577,7 +85578,7 @@ - + 384.0 0 0.5 0 0 0 @@ -85690,7 +85691,7 @@ - + 385.5 0 0.5 0 0 0 @@ -85803,7 +85804,7 @@ - + 387.0 0 0.5 0 0 0 @@ -85916,7 +85917,7 @@ - + 388.5 0 0.5 0 0 0 @@ -86029,7 +86030,7 @@ - + 390.0 0 0.5 0 0 0 @@ -86142,7 +86143,7 @@ - + 391.5 0 0.5 0 0 0 @@ -86255,7 +86256,7 @@ - + 393.0 0 0.5 0 0 0 @@ -86368,7 +86369,7 @@ - + 394.5 0 0.5 0 0 0 @@ -86481,7 +86482,7 @@ - + 396.0 0 0.5 0 0 0 @@ -86594,7 +86595,7 @@ - + 397.5 0 0.5 0 0 0 @@ -86707,7 +86708,7 @@ - + 399.0 0 0.5 0 0 0 @@ -86820,7 +86821,7 @@ - + 400.5 0 0.5 0 0 0 @@ -86933,7 +86934,7 @@ - + 402.0 0 0.5 0 0 0 @@ -87046,7 +87047,7 @@ - + 403.5 0 0.5 0 0 0 @@ -87159,7 +87160,7 @@ - + 405.0 0 0.5 0 0 0 @@ -87272,7 +87273,7 @@ - + 406.5 0 0.5 0 0 0 @@ -87385,7 +87386,7 @@ - + 408.0 0 0.5 0 0 0 @@ -87498,7 +87499,7 @@ - + 409.5 0 0.5 0 0 0 @@ -87611,7 +87612,7 @@ - + 411.0 0 0.5 0 0 0 @@ -87724,7 +87725,7 @@ - + 412.5 0 0.5 0 0 0 @@ -87837,7 +87838,7 @@ - + 414.0 0 0.5 0 0 0 @@ -87950,7 +87951,7 @@ - + 415.5 0 0.5 0 0 0 @@ -88063,7 +88064,7 @@ - + 417.0 0 0.5 0 0 0 @@ -88176,7 +88177,7 @@ - + 418.5 0 0.5 0 0 0 @@ -88289,7 +88290,7 @@ - + 420.0 0 0.5 0 0 0 @@ -88402,7 +88403,7 @@ - + 421.5 0 0.5 0 0 0 @@ -88515,7 +88516,7 @@ - + 423.0 0 0.5 0 0 0 @@ -88628,7 +88629,7 @@ - + 424.5 0 0.5 0 0 0 @@ -88741,7 +88742,7 @@ - + 426.0 0 0.5 0 0 0 @@ -88854,7 +88855,7 @@ - + 427.5 0 0.5 0 0 0 @@ -88967,7 +88968,7 @@ - + 429.0 0 0.5 0 0 0 @@ -89080,7 +89081,7 @@ - + 430.5 0 0.5 0 0 0 @@ -89193,7 +89194,7 @@ - + 432.0 0 0.5 0 0 0 @@ -89306,7 +89307,7 @@ - + 433.5 0 0.5 0 0 0 @@ -89419,7 +89420,7 @@ - + 435.0 0 0.5 0 0 0 @@ -89532,7 +89533,7 @@ - + 436.5 0 0.5 0 0 0 @@ -89645,7 +89646,7 @@ - + 438.0 0 0.5 0 0 0 @@ -89758,7 +89759,7 @@ - + 439.5 0 0.5 0 0 0 @@ -89871,7 +89872,7 @@ - + 441.0 0 0.5 0 0 0 @@ -89984,7 +89985,7 @@ - + 442.5 0 0.5 0 0 0 @@ -90097,7 +90098,7 @@ - + 444.0 0 0.5 0 0 0 @@ -90210,7 +90211,7 @@ - + 445.5 0 0.5 0 0 0 @@ -90323,7 +90324,7 @@ - + 447.0 0 0.5 0 0 0 @@ -90436,7 +90437,7 @@ - + 448.5 0 0.5 0 0 0 @@ -90549,7 +90550,7 @@ - + 450.0 0 0.5 0 0 0 @@ -90662,7 +90663,7 @@ - + 451.5 0 0.5 0 0 0 @@ -90775,7 +90776,7 @@ - + 453.0 0 0.5 0 0 0 @@ -90888,7 +90889,7 @@ - + 454.5 0 0.5 0 0 0 @@ -91001,7 +91002,7 @@ - + 456.0 0 0.5 0 0 0 @@ -91114,7 +91115,7 @@ - + 457.5 0 0.5 0 0 0 @@ -91227,7 +91228,7 @@ - + 459.0 0 0.5 0 0 0 @@ -91340,7 +91341,7 @@ - + 460.5 0 0.5 0 0 0 @@ -91453,7 +91454,7 @@ - + 462.0 0 0.5 0 0 0 @@ -91566,7 +91567,7 @@ - + 463.5 0 0.5 0 0 0 @@ -91679,7 +91680,7 @@ - + 465.0 0 0.5 0 0 0 @@ -91792,7 +91793,7 @@ - + 466.5 0 0.5 0 0 0 @@ -91905,7 +91906,7 @@ - + 468.0 0 0.5 0 0 0 @@ -92018,7 +92019,7 @@ - + 469.5 0 0.5 0 0 0 @@ -92131,7 +92132,7 @@ - + 471.0 0 0.5 0 0 0 @@ -92244,7 +92245,7 @@ - + 472.5 0 0.5 0 0 0 @@ -92357,7 +92358,7 @@ - + 474.0 0 0.5 0 0 0 @@ -92470,7 +92471,7 @@ - + 475.5 0 0.5 0 0 0 @@ -92583,7 +92584,7 @@ - + 477.0 0 0.5 0 0 0 @@ -92696,7 +92697,7 @@ - + 478.5 0 0.5 0 0 0 @@ -92809,7 +92810,7 @@ - + 480.0 0 0.5 0 0 0 @@ -92922,7 +92923,7 @@ - + 481.5 0 0.5 0 0 0 @@ -93035,7 +93036,7 @@ - + 483.0 0 0.5 0 0 0 @@ -93148,7 +93149,7 @@ - + 484.5 0 0.5 0 0 0 @@ -93261,7 +93262,7 @@ - + 486.0 0 0.5 0 0 0 @@ -93374,7 +93375,7 @@ - + 487.5 0 0.5 0 0 0 @@ -93487,7 +93488,7 @@ - + 489.0 0 0.5 0 0 0 @@ -93600,7 +93601,7 @@ - + 490.5 0 0.5 0 0 0 @@ -93713,7 +93714,7 @@ - + 492.0 0 0.5 0 0 0 @@ -93826,7 +93827,7 @@ - + 493.5 0 0.5 0 0 0 @@ -93939,7 +93940,7 @@ - + 495.0 0 0.5 0 0 0 @@ -94052,7 +94053,7 @@ - + 496.5 0 0.5 0 0 0 @@ -94165,7 +94166,7 @@ - + 498.0 0 0.5 0 0 0 @@ -94278,7 +94279,7 @@ - + 499.5 0 0.5 0 0 0 @@ -94391,7 +94392,7 @@ - + 501.0 0 0.5 0 0 0 @@ -94504,7 +94505,7 @@ - + 502.5 0 0.5 0 0 0 @@ -94617,7 +94618,7 @@ - + 504.0 0 0.5 0 0 0 @@ -94730,7 +94731,7 @@ - + 505.5 0 0.5 0 0 0 @@ -94843,7 +94844,7 @@ - + 507.0 0 0.5 0 0 0 @@ -94956,7 +94957,7 @@ - + 508.5 0 0.5 0 0 0 @@ -95069,7 +95070,7 @@ - + 510.0 0 0.5 0 0 0 @@ -95182,7 +95183,7 @@ - + 511.5 0 0.5 0 0 0 @@ -95295,7 +95296,7 @@ - + 513.0 0 0.5 0 0 0 @@ -95408,7 +95409,7 @@ - + 514.5 0 0.5 0 0 0 @@ -95521,7 +95522,7 @@ - + 516.0 0 0.5 0 0 0 @@ -95634,7 +95635,7 @@ - + 517.5 0 0.5 0 0 0 @@ -95747,7 +95748,7 @@ - + 519.0 0 0.5 0 0 0 @@ -95860,7 +95861,7 @@ - + 520.5 0 0.5 0 0 0 @@ -95973,7 +95974,7 @@ - + 522.0 0 0.5 0 0 0 @@ -96086,7 +96087,7 @@ - + 523.5 0 0.5 0 0 0 @@ -96199,7 +96200,7 @@ - + 525.0 0 0.5 0 0 0 @@ -96312,7 +96313,7 @@ - + 526.5 0 0.5 0 0 0 @@ -96425,7 +96426,7 @@ - + 528.0 0 0.5 0 0 0 @@ -96538,7 +96539,7 @@ - + 529.5 0 0.5 0 0 0 @@ -96651,7 +96652,7 @@ - + 531.0 0 0.5 0 0 0 @@ -96764,7 +96765,7 @@ - + 532.5 0 0.5 0 0 0 @@ -96877,7 +96878,7 @@ - + 534.0 0 0.5 0 0 0 @@ -96990,7 +96991,7 @@ - + 535.5 0 0.5 0 0 0 @@ -97103,7 +97104,7 @@ - + 537.0 0 0.5 0 0 0 @@ -97216,7 +97217,7 @@ - + 538.5 0 0.5 0 0 0 @@ -97329,7 +97330,7 @@ - + 540.0 0 0.5 0 0 0 @@ -97442,7 +97443,7 @@ - + 541.5 0 0.5 0 0 0 @@ -97555,7 +97556,7 @@ - + 543.0 0 0.5 0 0 0 @@ -97668,7 +97669,7 @@ - + 544.5 0 0.5 0 0 0 @@ -97781,7 +97782,7 @@ - + 546.0 0 0.5 0 0 0 @@ -97894,7 +97895,7 @@ - + 547.5 0 0.5 0 0 0 @@ -98007,7 +98008,7 @@ - + 549.0 0 0.5 0 0 0 @@ -98120,7 +98121,7 @@ - + 550.5 0 0.5 0 0 0 @@ -98233,7 +98234,7 @@ - + 552.0 0 0.5 0 0 0 @@ -98346,7 +98347,7 @@ - + 553.5 0 0.5 0 0 0 @@ -98459,7 +98460,7 @@ - + 555.0 0 0.5 0 0 0 @@ -98572,7 +98573,7 @@ - + 556.5 0 0.5 0 0 0 @@ -98685,7 +98686,7 @@ - + 558.0 0 0.5 0 0 0 @@ -98798,7 +98799,7 @@ - + 559.5 0 0.5 0 0 0 @@ -98911,7 +98912,7 @@ - + 561.0 0 0.5 0 0 0 @@ -99024,7 +99025,7 @@ - + 562.5 0 0.5 0 0 0 @@ -99137,7 +99138,7 @@ - + 564.0 0 0.5 0 0 0 @@ -99250,7 +99251,7 @@ - + 565.5 0 0.5 0 0 0 @@ -99363,7 +99364,7 @@ - + 567.0 0 0.5 0 0 0 @@ -99476,7 +99477,7 @@ - + 568.5 0 0.5 0 0 0 @@ -99589,7 +99590,7 @@ - + 570.0 0 0.5 0 0 0 @@ -99702,7 +99703,7 @@ - + 571.5 0 0.5 0 0 0 @@ -99815,7 +99816,7 @@ - + 573.0 0 0.5 0 0 0 @@ -99928,7 +99929,7 @@ - + 574.5 0 0.5 0 0 0 @@ -100041,7 +100042,7 @@ - + 576.0 0 0.5 0 0 0 @@ -100154,7 +100155,7 @@ - + 577.5 0 0.5 0 0 0 @@ -100267,7 +100268,7 @@ - + 579.0 0 0.5 0 0 0 @@ -100380,7 +100381,7 @@ - + 580.5 0 0.5 0 0 0 @@ -100493,7 +100494,7 @@ - + 582.0 0 0.5 0 0 0 @@ -100606,7 +100607,7 @@ - + 583.5 0 0.5 0 0 0 @@ -100719,7 +100720,7 @@ - + 585.0 0 0.5 0 0 0 @@ -100832,7 +100833,7 @@ - + 586.5 0 0.5 0 0 0 @@ -100945,7 +100946,7 @@ - + 588.0 0 0.5 0 0 0 @@ -101058,7 +101059,7 @@ - + 589.5 0 0.5 0 0 0 @@ -101171,7 +101172,7 @@ - + 591.0 0 0.5 0 0 0 @@ -101284,7 +101285,7 @@ - + 592.5 0 0.5 0 0 0 @@ -101397,7 +101398,7 @@ - + 594.0 0 0.5 0 0 0 @@ -101510,7 +101511,7 @@ - + 595.5 0 0.5 0 0 0 @@ -101623,7 +101624,7 @@ - + 597.0 0 0.5 0 0 0 @@ -101736,7 +101737,7 @@ - + 598.5 0 0.5 0 0 0 @@ -101849,7 +101850,7 @@ - + 600.0 0 0.5 0 0 0 @@ -101962,7 +101963,7 @@ - + 601.5 0 0.5 0 0 0 @@ -102075,7 +102076,7 @@ - + 603.0 0 0.5 0 0 0 @@ -102188,7 +102189,7 @@ - + 604.5 0 0.5 0 0 0 @@ -102301,7 +102302,7 @@ - + 606.0 0 0.5 0 0 0 @@ -102414,7 +102415,7 @@ - + 607.5 0 0.5 0 0 0 @@ -102527,7 +102528,7 @@ - + 609.0 0 0.5 0 0 0 @@ -102640,7 +102641,7 @@ - + 610.5 0 0.5 0 0 0 @@ -102753,7 +102754,7 @@ - + 612.0 0 0.5 0 0 0 @@ -102866,7 +102867,7 @@ - + 613.5 0 0.5 0 0 0 @@ -102979,7 +102980,7 @@ - + 615.0 0 0.5 0 0 0 @@ -103092,7 +103093,7 @@ - + 616.5 0 0.5 0 0 0 @@ -103205,7 +103206,7 @@ - + 618.0 0 0.5 0 0 0 @@ -103318,7 +103319,7 @@ - + 619.5 0 0.5 0 0 0 @@ -103431,7 +103432,7 @@ - + 621.0 0 0.5 0 0 0 @@ -103544,7 +103545,7 @@ - + 622.5 0 0.5 0 0 0 @@ -103657,7 +103658,7 @@ - + 624.0 0 0.5 0 0 0 @@ -103770,7 +103771,7 @@ - + 625.5 0 0.5 0 0 0 @@ -103883,7 +103884,7 @@ - + 627.0 0 0.5 0 0 0 @@ -103996,7 +103997,7 @@ - + 628.5 0 0.5 0 0 0 @@ -104109,7 +104110,7 @@ - + 630.0 0 0.5 0 0 0 @@ -104222,7 +104223,7 @@ - + 631.5 0 0.5 0 0 0 @@ -104335,7 +104336,7 @@ - + 633.0 0 0.5 0 0 0 @@ -104448,7 +104449,7 @@ - + 634.5 0 0.5 0 0 0 @@ -104561,7 +104562,7 @@ - + 636.0 0 0.5 0 0 0 @@ -104674,7 +104675,7 @@ - + 637.5 0 0.5 0 0 0 @@ -104787,7 +104788,7 @@ - + 639.0 0 0.5 0 0 0 @@ -104900,7 +104901,7 @@ - + 640.5 0 0.5 0 0 0 @@ -105013,7 +105014,7 @@ - + 642.0 0 0.5 0 0 0 @@ -105126,7 +105127,7 @@ - + 643.5 0 0.5 0 0 0 @@ -105239,7 +105240,7 @@ - + 645.0 0 0.5 0 0 0 @@ -105352,7 +105353,7 @@ - + 646.5 0 0.5 0 0 0 @@ -105465,7 +105466,7 @@ - + 648.0 0 0.5 0 0 0 @@ -105578,7 +105579,7 @@ - + 649.5 0 0.5 0 0 0 @@ -105691,7 +105692,7 @@ - + 651.0 0 0.5 0 0 0 @@ -105804,7 +105805,7 @@ - + 652.5 0 0.5 0 0 0 @@ -105917,7 +105918,7 @@ - + 654.0 0 0.5 0 0 0 @@ -106030,7 +106031,7 @@ - + 655.5 0 0.5 0 0 0 @@ -106143,7 +106144,7 @@ - + 657.0 0 0.5 0 0 0 @@ -106256,7 +106257,7 @@ - + 658.5 0 0.5 0 0 0 @@ -106369,7 +106370,7 @@ - + 660.0 0 0.5 0 0 0 @@ -106482,7 +106483,7 @@ - + 661.5 0 0.5 0 0 0 @@ -106595,7 +106596,7 @@ - + 663.0 0 0.5 0 0 0 @@ -106708,7 +106709,7 @@ - + 664.5 0 0.5 0 0 0 @@ -106821,7 +106822,7 @@ - + 666.0 0 0.5 0 0 0 @@ -106934,7 +106935,7 @@ - + 667.5 0 0.5 0 0 0 @@ -107047,7 +107048,7 @@ - + 669.0 0 0.5 0 0 0 @@ -107160,7 +107161,7 @@ - + 670.5 0 0.5 0 0 0 @@ -107273,7 +107274,7 @@ - + 672.0 0 0.5 0 0 0 @@ -107386,7 +107387,7 @@ - + 673.5 0 0.5 0 0 0 @@ -107499,7 +107500,7 @@ - + 675.0 0 0.5 0 0 0 @@ -107612,7 +107613,7 @@ - + 676.5 0 0.5 0 0 0 @@ -107725,7 +107726,7 @@ - + 678.0 0 0.5 0 0 0 @@ -107838,7 +107839,7 @@ - + 679.5 0 0.5 0 0 0 @@ -107951,7 +107952,7 @@ - + 681.0 0 0.5 0 0 0 @@ -108064,7 +108065,7 @@ - + 682.5 0 0.5 0 0 0 @@ -108177,7 +108178,7 @@ - + 684.0 0 0.5 0 0 0 @@ -108290,7 +108291,7 @@ - + 685.5 0 0.5 0 0 0 @@ -108403,7 +108404,7 @@ - + 687.0 0 0.5 0 0 0 @@ -108516,7 +108517,7 @@ - + 688.5 0 0.5 0 0 0 @@ -108629,7 +108630,7 @@ - + 690.0 0 0.5 0 0 0 @@ -108742,7 +108743,7 @@ - + 691.5 0 0.5 0 0 0 @@ -108855,7 +108856,7 @@ - + 693.0 0 0.5 0 0 0 @@ -108968,7 +108969,7 @@ - + 694.5 0 0.5 0 0 0 @@ -109081,7 +109082,7 @@ - + 696.0 0 0.5 0 0 0 @@ -109194,7 +109195,7 @@ - + 697.5 0 0.5 0 0 0 @@ -109307,7 +109308,7 @@ - + 699.0 0 0.5 0 0 0 @@ -109420,7 +109421,7 @@ - + 700.5 0 0.5 0 0 0 @@ -109533,7 +109534,7 @@ - + 702.0 0 0.5 0 0 0 @@ -109646,7 +109647,7 @@ - + 703.5 0 0.5 0 0 0 @@ -109759,7 +109760,7 @@ - + 705.0 0 0.5 0 0 0 @@ -109872,7 +109873,7 @@ - + 706.5 0 0.5 0 0 0 @@ -109985,7 +109986,7 @@ - + 708.0 0 0.5 0 0 0 @@ -110098,7 +110099,7 @@ - + 709.5 0 0.5 0 0 0 @@ -110211,7 +110212,7 @@ - + 711.0 0 0.5 0 0 0 @@ -110324,7 +110325,7 @@ - + 712.5 0 0.5 0 0 0 @@ -110437,7 +110438,7 @@ - + 714.0 0 0.5 0 0 0 @@ -110550,7 +110551,7 @@ - + 715.5 0 0.5 0 0 0 @@ -110663,7 +110664,7 @@ - + 717.0 0 0.5 0 0 0 @@ -110776,7 +110777,7 @@ - + 718.5 0 0.5 0 0 0 @@ -110889,7 +110890,7 @@ - + 720.0 0 0.5 0 0 0 @@ -111002,7 +111003,7 @@ - + 721.5 0 0.5 0 0 0 @@ -111115,7 +111116,7 @@ - + 723.0 0 0.5 0 0 0 @@ -111228,7 +111229,7 @@ - + 724.5 0 0.5 0 0 0 @@ -111341,7 +111342,7 @@ - + 726.0 0 0.5 0 0 0 @@ -111454,7 +111455,7 @@ - + 727.5 0 0.5 0 0 0 @@ -111567,7 +111568,7 @@ - + 729.0 0 0.5 0 0 0 @@ -111680,7 +111681,7 @@ - + 730.5 0 0.5 0 0 0 @@ -111793,7 +111794,7 @@ - + 732.0 0 0.5 0 0 0 @@ -111906,7 +111907,7 @@ - + 733.5 0 0.5 0 0 0 @@ -112019,7 +112020,7 @@ - + 735.0 0 0.5 0 0 0 @@ -112132,7 +112133,7 @@ - + 736.5 0 0.5 0 0 0 @@ -112245,7 +112246,7 @@ - + 738.0 0 0.5 0 0 0 @@ -112358,7 +112359,7 @@ - + 739.5 0 0.5 0 0 0 @@ -112471,7 +112472,7 @@ - + 741.0 0 0.5 0 0 0 @@ -112584,7 +112585,7 @@ - + 742.5 0 0.5 0 0 0 @@ -112697,7 +112698,7 @@ - + 744.0 0 0.5 0 0 0 @@ -112810,7 +112811,7 @@ - + 745.5 0 0.5 0 0 0 @@ -112923,7 +112924,7 @@ - + 747.0 0 0.5 0 0 0 @@ -113036,7 +113037,7 @@ - + 748.5 0 0.5 0 0 0 @@ -113149,7 +113150,7 @@ - + 750.0 0 0.5 0 0 0 diff --git a/examples/worlds/actor.sdf b/examples/worlds/actor.sdf index df9a84c3db..e69a66513f 100644 --- a/examples/worlds/actor.sdf +++ b/examples/worlds/actor.sdf @@ -126,6 +126,7 @@ 0.0 0.0 1 + 100 100 diff --git a/examples/worlds/actors_population.sdf.erb b/examples/worlds/actors_population.sdf.erb index 855d89f2ba..f2bd07ece1 100644 --- a/examples/worlds/actors_population.sdf.erb +++ b/examples/worlds/actors_population.sdf.erb @@ -118,6 +118,7 @@ 0.0 0.0 1 + 100 100 diff --git a/examples/worlds/apply_joint_force.sdf b/examples/worlds/apply_joint_force.sdf index 2fc15ab1f3..1825eb7a4b 100644 --- a/examples/worlds/apply_joint_force.sdf +++ b/examples/worlds/apply_joint_force.sdf @@ -41,6 +41,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/breadcrumbs.sdf b/examples/worlds/breadcrumbs.sdf index 69033f1ee7..b3ade84636 100644 --- a/examples/worlds/breadcrumbs.sdf +++ b/examples/worlds/breadcrumbs.sdf @@ -55,6 +55,7 @@ 0 0 1 + 100 100 @@ -413,4 +414,3 @@ - diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index 608fa57f7e..b79e76b81b 100644 --- a/examples/worlds/camera_sensor.sdf +++ b/examples/worlds/camera_sensor.sdf @@ -123,6 +123,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/camera_video_record_dbl_pendulum.sdf b/examples/worlds/camera_video_record_dbl_pendulum.sdf index 8e22fc4d18..21ba632227 100644 --- a/examples/worlds/camera_video_record_dbl_pendulum.sdf +++ b/examples/worlds/camera_video_record_dbl_pendulum.sdf @@ -54,6 +54,7 @@ 0 0 1 + 100 100 @@ -320,4 +321,3 @@ - diff --git a/examples/worlds/contact_sensor.sdf b/examples/worlds/contact_sensor.sdf index e9baaaad1e..6e84f1c29c 100644 --- a/examples/worlds/contact_sensor.sdf +++ b/examples/worlds/contact_sensor.sdf @@ -52,6 +52,7 @@ Run the following to print out contacts, 0 0 1 + 100 100 diff --git a/examples/worlds/debug_shapes.sdf b/examples/worlds/debug_shapes.sdf index 1e83a2eb19..10ed07430f 100644 --- a/examples/worlds/debug_shapes.sdf +++ b/examples/worlds/debug_shapes.sdf @@ -43,6 +43,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/default.sdf b/examples/worlds/default.sdf index f359666e1f..a963e7e709 100644 --- a/examples/worlds/default.sdf +++ b/examples/worlds/default.sdf @@ -39,6 +39,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index 687a3faa13..ce693fe1b0 100644 --- a/examples/worlds/depth_camera_sensor.sdf +++ b/examples/worlds/depth_camera_sensor.sdf @@ -113,6 +113,7 @@ 20 20 0.1 diff --git a/examples/worlds/detachable_joint.sdf b/examples/worlds/detachable_joint.sdf index b5cb606e1e..c88799cda7 100644 --- a/examples/worlds/detachable_joint.sdf +++ b/examples/worlds/detachable_joint.sdf @@ -56,6 +56,7 @@ 0 0 1 + 100 100 @@ -482,4 +483,3 @@ - diff --git a/examples/worlds/diff_drive.sdf b/examples/worlds/diff_drive.sdf index e1e711ec77..647509944d 100644 --- a/examples/worlds/diff_drive.sdf +++ b/examples/worlds/diff_drive.sdf @@ -56,6 +56,7 @@ 0 0 1 + 100 100 @@ -436,4 +437,3 @@ - diff --git a/examples/worlds/diff_drive_skid.sdf b/examples/worlds/diff_drive_skid.sdf index dad1d68639..4edf93497d 100644 --- a/examples/worlds/diff_drive_skid.sdf +++ b/examples/worlds/diff_drive_skid.sdf @@ -52,6 +52,7 @@ 0 0 1 + 100 100 @@ -351,4 +352,3 @@ - diff --git a/examples/worlds/empty.sdf b/examples/worlds/empty.sdf index a0ea893bfa..74fa85eca9 100644 --- a/examples/worlds/empty.sdf +++ b/examples/worlds/empty.sdf @@ -95,6 +95,7 @@ ign service -s /world/empty/remove \ 0 0 1 + 100 100 diff --git a/examples/worlds/fuel.sdf b/examples/worlds/fuel.sdf index f9e9459b7d..9331c70837 100644 --- a/examples/worlds/fuel.sdf +++ b/examples/worlds/fuel.sdf @@ -34,6 +34,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/fuel_textured_mesh.sdf b/examples/worlds/fuel_textured_mesh.sdf index 2818448d44..7c2a39f95a 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -203,6 +203,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/gpu_lidar_sensor.sdf b/examples/worlds/gpu_lidar_sensor.sdf index 286a150752..07020dda9b 100644 --- a/examples/worlds/gpu_lidar_sensor.sdf +++ b/examples/worlds/gpu_lidar_sensor.sdf @@ -44,6 +44,7 @@ 20 20 0.1 diff --git a/examples/worlds/grid.sdf b/examples/worlds/grid.sdf index 1a383a0cc9..b775544573 100644 --- a/examples/worlds/grid.sdf +++ b/examples/worlds/grid.sdf @@ -123,6 +123,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/import_mesh.sdf b/examples/worlds/import_mesh.sdf index 0015bd15a7..1309625e2d 100644 --- a/examples/worlds/import_mesh.sdf +++ b/examples/worlds/import_mesh.sdf @@ -116,6 +116,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/lift_drag.sdf b/examples/worlds/lift_drag.sdf index 3589ce701a..d9c1f73bec 100644 --- a/examples/worlds/lift_drag.sdf +++ b/examples/worlds/lift_drag.sdf @@ -49,6 +49,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/lift_drag_battery.sdf b/examples/worlds/lift_drag_battery.sdf index 813a8a38be..afe4f8dbb9 100644 --- a/examples/worlds/lift_drag_battery.sdf +++ b/examples/worlds/lift_drag_battery.sdf @@ -52,6 +52,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/lights.sdf b/examples/worlds/lights.sdf index 46b4d6a657..f1910f0ac7 100644 --- a/examples/worlds/lights.sdf +++ b/examples/worlds/lights.sdf @@ -81,6 +81,7 @@ 0.0 0.0 1 + 100 100 diff --git a/examples/worlds/log_record_dbl_pendulum.sdf b/examples/worlds/log_record_dbl_pendulum.sdf index 0a964ee416..c7d4d208df 100644 --- a/examples/worlds/log_record_dbl_pendulum.sdf +++ b/examples/worlds/log_record_dbl_pendulum.sdf @@ -57,6 +57,7 @@ 0 0 1 + 100 100 @@ -278,4 +279,3 @@ - diff --git a/examples/worlds/log_record_resources.sdf b/examples/worlds/log_record_resources.sdf index 254c1e4f09..6bf9adb87c 100644 --- a/examples/worlds/log_record_resources.sdf +++ b/examples/worlds/log_record_resources.sdf @@ -63,6 +63,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/log_record_shapes.sdf b/examples/worlds/log_record_shapes.sdf index 60f9254254..39fb8797ba 100644 --- a/examples/worlds/log_record_shapes.sdf +++ b/examples/worlds/log_record_shapes.sdf @@ -54,6 +54,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/logical_audio_sensor_plugin.sdf b/examples/worlds/logical_audio_sensor_plugin.sdf index 9b93d11f99..a86a0656b0 100644 --- a/examples/worlds/logical_audio_sensor_plugin.sdf +++ b/examples/worlds/logical_audio_sensor_plugin.sdf @@ -71,6 +71,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/logical_camera_sensor.sdf b/examples/worlds/logical_camera_sensor.sdf index 3952828079..14d596c8e2 100644 --- a/examples/worlds/logical_camera_sensor.sdf +++ b/examples/worlds/logical_camera_sensor.sdf @@ -51,6 +51,7 @@ 20 20 0.1 diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index bdb0b83514..57e5bed01f 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -67,6 +67,7 @@ You can use the velocity controller and command linear velocity and yaw angular 0 0 1 + 100 100 @@ -402,4 +403,3 @@ You can use the velocity controller and command linear velocity and yaw angular - diff --git a/examples/worlds/nested_model.sdf b/examples/worlds/nested_model.sdf index ca705c7825..34310a6361 100644 --- a/examples/worlds/nested_model.sdf +++ b/examples/worlds/nested_model.sdf @@ -45,6 +45,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/performer_detector.sdf b/examples/worlds/performer_detector.sdf index bee3525430..5350526c03 100644 --- a/examples/worlds/performer_detector.sdf +++ b/examples/worlds/performer_detector.sdf @@ -53,6 +53,7 @@ 0 0 1 + 100 100 @@ -426,4 +427,3 @@ - diff --git a/examples/worlds/plane_propeller_demo.sdf b/examples/worlds/plane_propeller_demo.sdf index 1827a0c2c4..6de0ef7e92 100644 --- a/examples/worlds/plane_propeller_demo.sdf +++ b/examples/worlds/plane_propeller_demo.sdf @@ -109,6 +109,7 @@ 0 0 1 + 100000 100 diff --git a/examples/worlds/pose_publisher.sdf b/examples/worlds/pose_publisher.sdf index a3a927c68d..2c9947512e 100644 --- a/examples/worlds/pose_publisher.sdf +++ b/examples/worlds/pose_publisher.sdf @@ -47,6 +47,7 @@ 0 0 1 + 100 100 @@ -277,4 +278,3 @@ - diff --git a/examples/worlds/quadcopter.sdf b/examples/worlds/quadcopter.sdf index 7126135016..224a11cda9 100644 --- a/examples/worlds/quadcopter.sdf +++ b/examples/worlds/quadcopter.sdf @@ -56,6 +56,7 @@ 0 0 1 + 100 100 @@ -162,4 +163,3 @@ - diff --git a/examples/worlds/rolling_shapes.sdf b/examples/worlds/rolling_shapes.sdf index ac35e266ab..6c7d287631 100644 --- a/examples/worlds/rolling_shapes.sdf +++ b/examples/worlds/rolling_shapes.sdf @@ -43,6 +43,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/sensors.sdf b/examples/worlds/sensors.sdf index 967511ebe0..48af629339 100644 --- a/examples/worlds/sensors.sdf +++ b/examples/worlds/sensors.sdf @@ -65,6 +65,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf index c40ac364a7..71a2e973bc 100644 --- a/examples/worlds/sensors_demo.sdf +++ b/examples/worlds/sensors_demo.sdf @@ -152,6 +152,7 @@ 20 20 0.1 diff --git a/examples/worlds/shapes.sdf b/examples/worlds/shapes.sdf index 5dec565b81..b43dbab638 100644 --- a/examples/worlds/shapes.sdf +++ b/examples/worlds/shapes.sdf @@ -34,6 +34,7 @@ Try moving a model: 0 0 1 + 100 100 diff --git a/examples/worlds/shapes_bitmask.sdf b/examples/worlds/shapes_bitmask.sdf index 4aca31166c..342ccb99aa 100644 --- a/examples/worlds/shapes_bitmask.sdf +++ b/examples/worlds/shapes_bitmask.sdf @@ -55,6 +55,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/shapes_population.sdf.erb b/examples/worlds/shapes_population.sdf.erb index 92122ffbbe..4c91b1206b 100644 --- a/examples/worlds/shapes_population.sdf.erb +++ b/examples/worlds/shapes_population.sdf.erb @@ -130,6 +130,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index c8498d3cc2..325139a1c0 100644 --- a/examples/worlds/thermal_camera.sdf +++ b/examples/worlds/thermal_camera.sdf @@ -131,6 +131,7 @@ 20 20 0.1 diff --git a/examples/worlds/touch_plugin.sdf b/examples/worlds/touch_plugin.sdf index eed0d28593..7497a15984 100644 --- a/examples/worlds/touch_plugin.sdf +++ b/examples/worlds/touch_plugin.sdf @@ -55,6 +55,7 @@ The output of the plugin is via 0 0 1 + 100 100 @@ -136,4 +137,3 @@ The output of the plugin is via - diff --git a/examples/worlds/track_drive.sdf b/examples/worlds/track_drive.sdf index ed4c852a82..9680cd01e5 100644 --- a/examples/worlds/track_drive.sdf +++ b/examples/worlds/track_drive.sdf @@ -60,6 +60,7 @@ 0 0 1 + 100 100 @@ -2096,4 +2097,3 @@ - diff --git a/examples/worlds/triggered_publisher.sdf b/examples/worlds/triggered_publisher.sdf index 110f10f0e1..e9812361c1 100644 --- a/examples/worlds/triggered_publisher.sdf +++ b/examples/worlds/triggered_publisher.sdf @@ -125,6 +125,7 @@ moment the box hits the ground, the second box should start falling. 0 0 1 + 100 100 @@ -532,4 +533,3 @@ moment the box hits the ground, the second box should start falling. - diff --git a/examples/worlds/trisphere_cycle_wheel_slip.sdf b/examples/worlds/trisphere_cycle_wheel_slip.sdf index bd7a23b219..7738361315 100644 --- a/examples/worlds/trisphere_cycle_wheel_slip.sdf +++ b/examples/worlds/trisphere_cycle_wheel_slip.sdf @@ -102,6 +102,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/velocity_control.sdf b/examples/worlds/velocity_control.sdf index fcfabd8c12..2e104e5f08 100644 --- a/examples/worlds/velocity_control.sdf +++ b/examples/worlds/velocity_control.sdf @@ -119,6 +119,7 @@ 0 0 1 + 100 100 diff --git a/examples/worlds/video_record_dbl_pendulum.sdf b/examples/worlds/video_record_dbl_pendulum.sdf index 2894e0f7dd..ddbe423ff3 100644 --- a/examples/worlds/video_record_dbl_pendulum.sdf +++ b/examples/worlds/video_record_dbl_pendulum.sdf @@ -113,6 +113,7 @@ 0 0 1 + 100 100 @@ -334,4 +335,3 @@ - diff --git a/examples/worlds/wind.sdf b/examples/worlds/wind.sdf index f260d17f07..d5d58b73b7 100644 --- a/examples/worlds/wind.sdf +++ b/examples/worlds/wind.sdf @@ -109,6 +109,7 @@ Example: 0 0 1 + 100 100 diff --git a/test/worlds/altimeter.sdf b/test/worlds/altimeter.sdf index 4aaa125fc4..95aa5ac43f 100644 --- a/test/worlds/altimeter.sdf +++ b/test/worlds/altimeter.sdf @@ -21,6 +21,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/apply_joint_force.sdf b/test/worlds/apply_joint_force.sdf index d89570e396..bdc7e56f92 100644 --- a/test/worlds/apply_joint_force.sdf +++ b/test/worlds/apply_joint_force.sdf @@ -13,6 +13,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index 855614c1f6..fae8d86898 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -40,6 +40,7 @@ 0 0 1 + 100 100 @@ -661,5 +662,3 @@ - - diff --git a/test/worlds/camera_video_record.sdf b/test/worlds/camera_video_record.sdf index d8fdf8f1e3..3a08ef9fa9 100644 --- a/test/worlds/camera_video_record.sdf +++ b/test/worlds/camera_video_record.sdf @@ -41,6 +41,7 @@ 0 0 1 + 100 100 @@ -307,4 +308,3 @@ - diff --git a/test/worlds/depth_camera_sensor.sdf b/test/worlds/depth_camera_sensor.sdf index bd8c1a23b8..f6fd16a163 100644 --- a/test/worlds/depth_camera_sensor.sdf +++ b/test/worlds/depth_camera_sensor.sdf @@ -40,6 +40,7 @@ 20 20 0.1 diff --git a/test/worlds/detachable_joint.sdf b/test/worlds/detachable_joint.sdf index 89aa2fd68c..821d5a1a0f 100644 --- a/test/worlds/detachable_joint.sdf +++ b/test/worlds/detachable_joint.sdf @@ -11,6 +11,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/diff_drive.sdf b/test/worlds/diff_drive.sdf index 3a95bb1e92..b2b00bb0c4 100644 --- a/test/worlds/diff_drive.sdf +++ b/test/worlds/diff_drive.sdf @@ -32,6 +32,7 @@ 0 0 1 + 100 100 @@ -240,4 +241,3 @@ - diff --git a/test/worlds/diff_drive_custom_frame_id.sdf b/test/worlds/diff_drive_custom_frame_id.sdf index 073bfc41b8..41d9f1b4b9 100644 --- a/test/worlds/diff_drive_custom_frame_id.sdf +++ b/test/worlds/diff_drive_custom_frame_id.sdf @@ -32,6 +32,7 @@ 0 0 1 + 100 100 @@ -242,4 +243,3 @@ - diff --git a/test/worlds/diff_drive_custom_topics.sdf b/test/worlds/diff_drive_custom_topics.sdf index 312b28e872..075c1c6744 100644 --- a/test/worlds/diff_drive_custom_topics.sdf +++ b/test/worlds/diff_drive_custom_topics.sdf @@ -32,6 +32,7 @@ 0 0 1 + 100 100 @@ -237,4 +238,3 @@ - diff --git a/test/worlds/diff_drive_limited_joint_pub.sdf b/test/worlds/diff_drive_limited_joint_pub.sdf index a32638a281..33baaea880 100644 --- a/test/worlds/diff_drive_limited_joint_pub.sdf +++ b/test/worlds/diff_drive_limited_joint_pub.sdf @@ -32,6 +32,7 @@ 0 0 1 + 100 100 @@ -244,4 +245,3 @@ - diff --git a/test/worlds/diff_drive_skid.sdf b/test/worlds/diff_drive_skid.sdf index 2b314d83d2..1adff231cf 100644 --- a/test/worlds/diff_drive_skid.sdf +++ b/test/worlds/diff_drive_skid.sdf @@ -32,6 +32,7 @@ 0 0 1 + 100 100 @@ -325,4 +326,3 @@ - diff --git a/test/worlds/falling.sdf b/test/worlds/falling.sdf index 18f780bba4..9e69c968e6 100644 --- a/test/worlds/falling.sdf +++ b/test/worlds/falling.sdf @@ -61,6 +61,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/friction.sdf b/test/worlds/friction.sdf index f78c10dcbb..f4ce49cf4d 100644 --- a/test/worlds/friction.sdf +++ b/test/worlds/friction.sdf @@ -164,6 +164,7 @@ 0 0 1 + 100 100 @@ -186,4 +187,3 @@ - diff --git a/test/worlds/gpu_lidar_sensor.sdf b/test/worlds/gpu_lidar_sensor.sdf index e72ef9c32a..a8748e419b 100644 --- a/test/worlds/gpu_lidar_sensor.sdf +++ b/test/worlds/gpu_lidar_sensor.sdf @@ -40,6 +40,7 @@ 20 20 0.1 diff --git a/test/worlds/imu.sdf b/test/worlds/imu.sdf index 1cf77984f9..4bd476afa6 100644 --- a/test/worlds/imu.sdf +++ b/test/worlds/imu.sdf @@ -22,6 +22,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/joint_controller.sdf b/test/worlds/joint_controller.sdf index f2509c1ad6..06b9dd566b 100644 --- a/test/worlds/joint_controller.sdf +++ b/test/worlds/joint_controller.sdf @@ -58,6 +58,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/joint_position_controller.sdf b/test/worlds/joint_position_controller.sdf index 9394c1ad6a..906521db60 100644 --- a/test/worlds/joint_position_controller.sdf +++ b/test/worlds/joint_position_controller.sdf @@ -58,6 +58,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/lift_drag.sdf b/test/worlds/lift_drag.sdf index b3c4021254..4926c4d9a8 100644 --- a/test/worlds/lift_drag.sdf +++ b/test/worlds/lift_drag.sdf @@ -15,6 +15,7 @@ 0 0 1 + 100 100 @@ -204,4 +205,3 @@ - diff --git a/test/worlds/log_record_dbl_pendulum.sdf b/test/worlds/log_record_dbl_pendulum.sdf index b93844b5fc..6b79cc1a43 100644 --- a/test/worlds/log_record_dbl_pendulum.sdf +++ b/test/worlds/log_record_dbl_pendulum.sdf @@ -50,6 +50,7 @@ 0 0 1 + 100 100 @@ -294,4 +295,3 @@ - diff --git a/test/worlds/log_record_resources.sdf b/test/worlds/log_record_resources.sdf index 254c1e4f09..6bf9adb87c 100644 --- a/test/worlds/log_record_resources.sdf +++ b/test/worlds/log_record_resources.sdf @@ -63,6 +63,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/logical_camera_sensor.sdf b/test/worlds/logical_camera_sensor.sdf index 6ca45a21d0..74b6fc448f 100644 --- a/test/worlds/logical_camera_sensor.sdf +++ b/test/worlds/logical_camera_sensor.sdf @@ -37,6 +37,7 @@ 20 20 0.1 diff --git a/test/worlds/magnetometer.sdf b/test/worlds/magnetometer.sdf index c34dfc87b1..9fb5bda4ca 100644 --- a/test/worlds/magnetometer.sdf +++ b/test/worlds/magnetometer.sdf @@ -22,6 +22,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/mesh.sdf b/test/worlds/mesh.sdf index 9dcc8ae815..dd2d47ce04 100644 --- a/test/worlds/mesh.sdf +++ b/test/worlds/mesh.sdf @@ -42,6 +42,7 @@ 20 20 0.1 diff --git a/test/worlds/nondefault_canonical.sdf b/test/worlds/nondefault_canonical.sdf index a03d8c88e5..56c303542d 100644 --- a/test/worlds/nondefault_canonical.sdf +++ b/test/worlds/nondefault_canonical.sdf @@ -61,6 +61,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/performer_detector.sdf b/test/worlds/performer_detector.sdf index 2a093d0176..faa7cef57d 100644 --- a/test/worlds/performer_detector.sdf +++ b/test/worlds/performer_detector.sdf @@ -17,6 +17,7 @@ 0 0 1 + 100 100 @@ -387,4 +388,3 @@ - diff --git a/test/worlds/pose_publisher.sdf b/test/worlds/pose_publisher.sdf index a4d88b0517..fadf485754 100644 --- a/test/worlds/pose_publisher.sdf +++ b/test/worlds/pose_publisher.sdf @@ -35,6 +35,7 @@ 0 0 1 + 100 100 @@ -515,4 +516,3 @@ - diff --git a/test/worlds/quadcopter.sdf b/test/worlds/quadcopter.sdf index 06b0ad57c9..e6c7aa5a7b 100644 --- a/test/worlds/quadcopter.sdf +++ b/test/worlds/quadcopter.sdf @@ -17,6 +17,7 @@ 0 0 1 + 100 100 @@ -327,4 +328,3 @@ - diff --git a/test/worlds/quadcopter_velocity_control.sdf b/test/worlds/quadcopter_velocity_control.sdf index 9583a1fc8f..fc8adea119 100644 --- a/test/worlds/quadcopter_velocity_control.sdf +++ b/test/worlds/quadcopter_velocity_control.sdf @@ -17,6 +17,7 @@ 0 0 1 + 100 100 @@ -366,4 +367,3 @@ - diff --git a/test/worlds/revolute_joint.sdf b/test/worlds/revolute_joint.sdf index 3821ff0eee..fd9632f5cd 100644 --- a/test/worlds/revolute_joint.sdf +++ b/test/worlds/revolute_joint.sdf @@ -58,6 +58,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/rgbd_camera_sensor.sdf b/test/worlds/rgbd_camera_sensor.sdf index d7d1bcc66a..5759741e11 100644 --- a/test/worlds/rgbd_camera_sensor.sdf +++ b/test/worlds/rgbd_camera_sensor.sdf @@ -36,6 +36,7 @@ 20 20 0.1 diff --git a/test/worlds/thermal.sdf b/test/worlds/thermal.sdf index 223b04ba51..15b2ff13b4 100644 --- a/test/worlds/thermal.sdf +++ b/test/worlds/thermal.sdf @@ -49,6 +49,7 @@ 20 20 0.1 diff --git a/test/worlds/touch_plugin.sdf b/test/worlds/touch_plugin.sdf index 90a802f623..4ff260b7f3 100644 --- a/test/worlds/touch_plugin.sdf +++ b/test/worlds/touch_plugin.sdf @@ -17,6 +17,7 @@ 0 0 1 + 100 100 @@ -212,4 +213,3 @@ - diff --git a/test/worlds/triball_drift.sdf b/test/worlds/triball_drift.sdf index bba019b21b..d574e2a2b6 100644 --- a/test/worlds/triball_drift.sdf +++ b/test/worlds/triball_drift.sdf @@ -92,6 +92,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/trisphere_cycle_wheel_slip.sdf b/test/worlds/trisphere_cycle_wheel_slip.sdf index cf0af7d524..b086b05a0f 100644 --- a/test/worlds/trisphere_cycle_wheel_slip.sdf +++ b/test/worlds/trisphere_cycle_wheel_slip.sdf @@ -92,6 +92,7 @@ 0 0 1 + 100 100 diff --git a/test/worlds/velocity_control.sdf b/test/worlds/velocity_control.sdf index fcfabd8c12..2e104e5f08 100644 --- a/test/worlds/velocity_control.sdf +++ b/test/worlds/velocity_control.sdf @@ -119,6 +119,7 @@ 0 0 1 + 100 100 From afb228d6582341c9813986b73c0994c16ee0dde4 Mon Sep 17 00:00:00 2001 From: Luca Della Vedova Date: Tue, 26 Jan 2021 04:03:31 +0800 Subject: [PATCH 11/55] Publish all periodic change components in Scene Broadcaster (#544) Signed-off-by: Luca Della Vedova --- .../ignition/gazebo/EntityComponentManager.hh | 6 +++++ src/EntityComponentManager.cc | 12 +++++++++ src/EntityComponentManager_TEST.cc | 25 +++++++++++++++++++ .../scene_broadcaster/SceneBroadcaster.cc | 5 ++-- 4 files changed, 46 insertions(+), 2 deletions(-) diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index bc99cf7eb1..326cdb1b8d 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -487,6 +487,12 @@ namespace ignition /// \return True if there are any components with one-time changes. public: bool HasOneTimeComponentChanges() const; + /// \brief Get the components types that are marked as periodic changes. + /// \return All the components that at least one entity marked as + /// periodic changes. + public: std::unordered_set + ComponentTypesWithPeriodicChanges() const; + /// \brief Set the absolute state of the ECM from a serialized message. /// Entities / components that are in the new state but not in the old /// one will be created. diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 3c4992b49d..3590fb0bec 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -419,6 +419,18 @@ bool EntityComponentManager::HasOneTimeComponentChanges() const return !this->dataPtr->oneTimeChangedComponents.empty(); } +///////////////////////////////////////////////// +std::unordered_set + EntityComponentManager::ComponentTypesWithPeriodicChanges() const +{ + std::unordered_set periodicComponents; + for (const auto& compPair : this->dataPtr->periodicChangedComponents) + { + periodicComponents.insert(compPair.first); + } + return periodicComponents; +} + ///////////////////////////////////////////////// bool EntityComponentManager::HasEntity(const Entity _entity) const { diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index a58a056e63..0ef3587247 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -2082,6 +2082,7 @@ TEST_P(EntityComponentManagerFixture, SetChanged) auto c2 = manager.CreateComponent(e2, IntComponent(456)); EXPECT_TRUE(manager.HasOneTimeComponentChanges()); + EXPECT_EQ(0u, manager.ComponentTypesWithPeriodicChanges().size()); EXPECT_EQ(ComponentState::OneTimeChange, manager.ComponentState(e1, c1.first)); EXPECT_EQ(ComponentState::OneTimeChange, @@ -2093,6 +2094,7 @@ TEST_P(EntityComponentManagerFixture, SetChanged) // updated manager.RunSetAllComponentsUnchanged(); EXPECT_FALSE(manager.HasOneTimeComponentChanges()); + EXPECT_EQ(0u, manager.ComponentTypesWithPeriodicChanges().size()); EXPECT_EQ(ComponentState::NoChange, manager.ComponentState(e1, c1.first)); EXPECT_EQ(ComponentState::NoChange, @@ -2100,9 +2102,31 @@ TEST_P(EntityComponentManagerFixture, SetChanged) // Mark as changed manager.SetChanged(e1, c1.first, ComponentState::PeriodicChange); + + // check that only e1 c1 is serialized into a message + msgs::SerializedStateMap stateMsg; + manager.State(stateMsg); + { + ASSERT_EQ(1, stateMsg.entities_size()); + + auto iter = stateMsg.entities().find(e1); + const auto &e1Msg = iter->second; + EXPECT_EQ(e1, e1Msg.id()); + ASSERT_EQ(1, e1Msg.components_size()); + + auto compIter = e1Msg.components().begin(); + const auto &e1c1Msg = compIter->second; + EXPECT_EQ(IntComponent::typeId, e1c1Msg.type()); + EXPECT_EQ(123, std::stoi(e1c1Msg.component())); + } + manager.SetChanged(e2, c2.first, ComponentState::OneTimeChange); EXPECT_TRUE(manager.HasOneTimeComponentChanges()); + // Expect a single component type to be marked as PeriodicChange + ASSERT_EQ(1u, manager.ComponentTypesWithPeriodicChanges().size()); + EXPECT_EQ(IntComponent().TypeId(), + *manager.ComponentTypesWithPeriodicChanges().begin()); EXPECT_EQ(ComponentState::PeriodicChange, manager.ComponentState(e1, c1.first)); EXPECT_EQ(ComponentState::OneTimeChange, @@ -2112,6 +2136,7 @@ TEST_P(EntityComponentManagerFixture, SetChanged) EXPECT_TRUE(manager.RemoveComponent(e1, c1.first)); EXPECT_TRUE(manager.HasOneTimeComponentChanges()); + EXPECT_EQ(0u, manager.ComponentTypesWithPeriodicChanges().size()); EXPECT_EQ(ComponentState::NoChange, manager.ComponentState(e1, c1.first)); diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index 9dde20341b..722d8f58ac 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -293,12 +293,13 @@ void SceneBroadcaster::PostUpdate(const UpdateInfo &_info, { _manager.State(*this->dataPtr->stepMsg.mutable_state(), {}, {}, true); } - // Otherwise publish just selected components + // Otherwise publish just periodic change components else { IGN_PROFILE("SceneBroadcast::PostUpdate UpdateState"); + auto periodicComponents = _manager.ComponentTypesWithPeriodicChanges(); _manager.State(*this->dataPtr->stepMsg.mutable_state(), - {}, {components::Pose::typeId}); + {}, periodicComponents); } // Full state on demand From 347fd5129108fe72b8c9ebf56b221d42b3ec7540 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 26 Jan 2021 18:24:18 -0800 Subject: [PATCH 12/55] Backport state update changes from pull request #486 (#583) Signed-off-by: Ian Chen --- src/EntityComponentManager.cc | 18 ++++++++++++++++-- src/network/NetworkManagerSecondary.cc | 6 ++++++ 2 files changed, 22 insertions(+), 2 deletions(-) diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 3590fb0bec..b7aa6e0a6a 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -1236,8 +1236,22 @@ void EntityComponentManager::SetState( { std::istringstream istr(compMsg.component()); comp->Deserialize(istr); - this->SetChanged(entity, compIter.first, - ComponentState::OneTimeChange); + // Note on merging forward: + // `has_one_time_component_changes` field is available in Edifice so + // this workaround can be removed + auto flag = ComponentState::PeriodicChange; + for (int i = 0; i < _stateMsg.header().data_size(); ++i) + { + if (_stateMsg.header().data(i).key() == + "has_one_time_component_changes") + { + int v = stoi(_stateMsg.header().data(i).value(0)); + if (v) + flag = ComponentState::OneTimeChange; + break; + } + } + this->SetChanged(entity, compIter.first, flag); } } } diff --git a/src/network/NetworkManagerSecondary.cc b/src/network/NetworkManagerSecondary.cc index eaf4f0c28b..46b979fa70 100644 --- a/src/network/NetworkManagerSecondary.cc +++ b/src/network/NetworkManagerSecondary.cc @@ -167,6 +167,12 @@ void NetworkManagerSecondary::OnStep( msgs::SerializedStateMap stateMsg; if (!entities.empty()) this->dataPtr->ecm->State(stateMsg, entities); + // Note on merging forward: + // `has_one_time_component_changes` field is available in Edifice so this + // workaround can be removed + auto data = stateMsg.mutable_header()->add_data(); + data->set_key("has_one_time_component_changes"); + data->add_value(this->dataPtr->ecm->HasOneTimeComponentChanges() ? "1" : "0"); this->stepAckPub.Publish(stateMsg); From 8fd9b2647a5c37b1dde5509b5a741c6c955ee10f Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Tue, 26 Jan 2021 22:18:09 -0800 Subject: [PATCH 13/55] Fix code_check errors (#582) Signed-off-by: Stephen Brawner --- src/SimulationRunner.cc | 6 +++--- test/integration/logical_camera_system.cc | 1 - 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index fd39d17a95..bdd21a1cb8 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -872,18 +872,18 @@ void SimulationRunner::LoadLoggingPlugins(const ServerConfig &_config) { std::list plugins; - if(_config.UseLogRecord() && !_config.LogPlaybackPath().empty()) + if (_config.UseLogRecord() && !_config.LogPlaybackPath().empty()) { ignwarn << "Both recording and playback are specified, defaulting to playback\n"; } - if(!_config.LogPlaybackPath().empty()) + if (!_config.LogPlaybackPath().empty()) { auto playbackPlugin = _config.LogPlaybackPlugin(); plugins.push_back(playbackPlugin); } - else if(_config.UseLogRecord()) + else if (_config.UseLogRecord()) { auto recordPlugin = _config.LogRecordPlugin(); plugins.push_back(recordPlugin); diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index 94e4763bb6..4c4454a9b8 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -190,5 +190,4 @@ TEST_F(LogicalCameraTest, LogicalCameraBox) ignition::math::Pose3d boxPoseCamera2Frame = boxPose - sensor2Pose; EXPECT_EQ(boxPoseCamera2Frame, ignition::msgs::Convert(img2.model(0).pose())); mutex.unlock(); - } From ebd09d4ce75d9a793d4d887a40f4575fe706b7ef Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Wed, 27 Jan 2021 20:05:41 -0800 Subject: [PATCH 14/55] Visualize collisions (#531) Signed-off-by: Jenn Nguyen Co-authored-by: Nate Koenig --- .../ignition/gazebo/rendering/RenderUtil.hh | 4 + .../ignition/gazebo/rendering/SceneManager.hh | 13 ++ src/gui/plugins/modules/EntityContextMenu.cc | 12 + src/gui/plugins/modules/EntityContextMenu.qml | 42 +++- src/gui/plugins/scene3d/Scene3D.cc | 63 ++++++ src/gui/plugins/scene3d/Scene3D.hh | 15 ++ src/rendering/RenderUtil.cc | 213 ++++++++++++++++++ src/rendering/SceneManager.cc | 31 +++ 8 files changed, 391 insertions(+), 2 deletions(-) diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index aa66219bb3..f3c9a31248 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -111,6 +111,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { std::string(const sdf::Sensor &, const std::string &)> _createSensorCb = {}); + /// \brief View collisions of specified entity which are shown in orange + /// \param[in] _entity Entity to view collisions + public: void ViewCollisions(const Entity &_entity); + /// \brief Get the scene manager /// Returns reference to the scene manager. public: class SceneManager &SceneManager(); diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index cf195f86b3..2099ef7b0f 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -96,6 +96,19 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: rendering::VisualPtr CreateVisual(Entity _id, const sdf::Visual &_visual, Entity _parentId = 0); + /// \brief Create a collision visual + /// \param[in] _id Unique visual id + /// \param[in] _collision Collision sdf dom + /// \param[in] _parentId Parent id + /// \return Visual (collision) object created from the sdf dom + public: rendering::VisualPtr CreateCollision(Entity _id, + const sdf::Collision &_collision, Entity _parentId = 0); + + /// \brief Retrieve visual + /// \param[in] _id Unique visual (entity) id + /// \return Pointer to requested visual + public: rendering::VisualPtr VisualById(Entity _id); + /// \brief Create an actor /// \param[in] _id Unique actor id /// \param[in] _visual Actor sdf dom diff --git a/src/gui/plugins/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index 5bd42b2510..e76cbd8cf1 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -47,6 +47,9 @@ namespace ignition::gazebo /// \brief Remove service name public: std::string removeService; + /// \brief View collisions service name + public: std::string viewCollisionsService; + /// \brief Name of world. public: std::string worldName; }; @@ -75,6 +78,9 @@ EntityContextMenu::EntityContextMenu() // For remove service requests this->dataPtr->removeService = "/world/default/remove"; + + // For view collisions service requests + this->dataPtr->viewCollisionsService = "/gui/view/collisions"; } ///////////////////////////////////////////////// @@ -146,6 +152,12 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->followService, req, cb); } + else if (request == "view_collisions") + { + ignition::msgs::StringMsg req; + req.set_data(_data.toStdString()); + this->dataPtr->node.Request(this->dataPtr->viewCollisionsService, req, cb); + } else { ignwarn << "Unknown request [" << request << "]" << std::endl; diff --git a/src/gui/plugins/modules/EntityContextMenu.qml b/src/gui/plugins/modules/EntityContextMenu.qml index 9e927e2356..bb2f4e02be 100644 --- a/src/gui/plugins/modules/EntityContextMenu.qml +++ b/src/gui/plugins/modules/EntityContextMenu.qml @@ -37,6 +37,40 @@ Item { text: "Remove" onTriggered: context.OnRemove(context.entity, context.type) } + // // cascading submenu only works in Qt 5.10+ on focal + // Menu { + // id: viewSubmenu + // title: "View" + // MenuItem { + // id: viewCollisionsMenu + // text: "Collisions" + // onTriggered: context.OnRequest("view_collisions", context.entity) + // } + // } + // workaround for getting submenu's to work on bionic (< Qt 5.10) + MenuItem { + id: viewSubmenu + text: "View >" + MouseArea { + id: viewSubMouseArea + anchors.fill: parent + hoverEnabled: true + onEntered: secondMenu.open() + } + } + } + Menu { + id: secondMenu + x: menu.x + menu.width + y: menu.y + viewSubmenu.y + MenuItem { + id: viewCollisionsMenu + text: "Collisions" + onTriggered: { + menu.close() + context.OnRequest("view_collisions", context.entity) + } + } } function open(_entity, _type, _x, _y) { @@ -47,6 +81,7 @@ Item { moveToMenu.enabled = false followMenu.enabled = false removeMenu.enabled = false + viewCollisionsMenu.enabled = false; // enable / disable menu items if (context.type == "model" || context.type == "link" || @@ -62,6 +97,11 @@ Item { removeMenu.enabled = true } + if (context.type == "model" || context.type == "link") + { + viewCollisionsMenu.enabled = true; + } + menu.open() } @@ -71,5 +111,3 @@ Item { property string type } } - - diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b6e3dc9af1..af6c3ef967 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -231,6 +231,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Helper object to move user camera public: MoveToHelper moveToHelper; + /// \brief Target to view collisions + public: std::string viewCollisionsTarget; + /// \brief Helper object to select entities. Only the latest selection /// request is kept. public: SelectionHelper selectionHelper; @@ -429,6 +432,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief mutex to protect the render condition variable /// Used when recording in lockstep mode. public: std::mutex renderMutex; + + /// \brief View collisions service + public: std::string viewCollisionsService; }; } } @@ -803,6 +809,31 @@ void IgnRenderer::Render() } } + // View collisions + { + IGN_PROFILE("IgnRenderer::Render ViewCollisions"); + if (!this->dataPtr->viewCollisionsTarget.empty()) + { + rendering::NodePtr targetNode = + scene->NodeByName(this->dataPtr->viewCollisionsTarget); + + if (targetNode) + { + Entity targetEntity = + this->dataPtr->renderUtil.SceneManager().EntityFromNode(targetNode); + this->dataPtr->renderUtil.ViewCollisions(targetEntity); + } + else + { + ignerr << "Unable to find node name [" + << this->dataPtr->viewCollisionsTarget + << "] to view collisions" << std::endl; + } + + this->dataPtr->viewCollisionsTarget.clear(); + } + } + if (ignition::gui::App()) { gui::events::Render event; @@ -1914,6 +1945,13 @@ void IgnRenderer::SetMoveToPose(const math::Pose3d &_pose) this->dataPtr->moveToPoseValue = _pose; } +///////////////////////////////////////////////// +void IgnRenderer::SetViewCollisionsTarget(const std::string &_target) +{ + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->viewCollisionsTarget = _target; +} + ///////////////////////////////////////////////// void IgnRenderer::SetFollowPGain(double _gain) { @@ -2618,6 +2656,13 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem) ignmsg << "Camera pose topic advertised on [" << this->dataPtr->cameraPoseTopic << "]" << std::endl; + // view collisions service + this->dataPtr->viewCollisionsService = "/gui/view/collisions"; + this->dataPtr->node.Advertise(this->dataPtr->viewCollisionsService, + &Scene3D::OnViewCollisions, this); + ignmsg << "View collisions service on [" + << this->dataPtr->viewCollisionsService << "]" << std::endl; + ignition::gui::App()->findChild< ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this); ignition::gui::App()->findChild< @@ -2770,6 +2815,18 @@ bool Scene3D::OnMoveToPose(const msgs::GUICamera &_msg, msgs::Boolean &_res) return true; } +///////////////////////////////////////////////// +bool Scene3D::OnViewCollisions(const msgs::StringMsg &_msg, + msgs::Boolean &_res) +{ + auto renderWindow = this->PluginItem()->findChild(); + + renderWindow->SetViewCollisionsTarget(_msg.data()); + + _res.set_data(true); + return true; +} + ///////////////////////////////////////////////// void Scene3D::OnHovered(int _mouseX, int _mouseY) { @@ -3025,6 +3082,12 @@ void RenderWindowItem::SetMoveToPose(const math::Pose3d &_pose) this->dataPtr->renderThread->ignRenderer.SetMoveToPose(_pose); } +///////////////////////////////////////////////// +void RenderWindowItem::SetViewCollisionsTarget(const std::string &_target) +{ + this->dataPtr->renderThread->ignRenderer.SetViewCollisionsTarget(_target); +} + ///////////////////////////////////////////////// void RenderWindowItem::SetFollowPGain(double _gain) { diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index cf966a4efe..97289bd412 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -154,6 +154,13 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { private: bool OnMoveToPose(const msgs::GUICamera &_msg, msgs::Boolean &_res); + /// \brief Callback for view collisions request + /// \param[in] _msg Request message to set the target to view collisions + /// \param[in] _res Response data + /// \return True if the request is received + private: bool OnViewCollisions(const msgs::StringMsg &_msg, + msgs::Boolean &_res); + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; @@ -245,6 +252,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _pose The world pose to set the camera to. public: void SetMoveToPose(const math::Pose3d &_pose); + /// \brief View collisions of the specified target + /// \param[in] _target Target to view collisions + public: void SetViewCollisionsTarget(const std::string &_target); + /// \brief Set the p gain for the camera follow movement /// \param[in] _gain Camera follow p gain. public: void SetFollowPGain(double _gain); @@ -580,6 +591,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _pose The new camera pose in the world frame. public: void SetMoveToPose(const math::Pose3d &_pose); + /// \brief View collisions of the specified target + /// \param[in] _target Target to view collisions + public: void SetViewCollisionsTarget(const std::string &_target); + /// \brief Set the p gain for the camera follow movement /// \param[in] _gain Camera follow p gain. public: void SetFollowPGain(double _gain); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 01bcd7644f..1dde5ba785 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -43,6 +44,7 @@ #include "ignition/gazebo/components/Actor.hh" #include "ignition/gazebo/components/Camera.hh" #include "ignition/gazebo/components/CastShadows.hh" +#include "ignition/gazebo/components/Collision.hh" #include "ignition/gazebo/components/DepthCamera.hh" #include "ignition/gazebo/components/GpuLidar.hh" #include "ignition/gazebo/components/Geometry.hh" @@ -197,6 +199,30 @@ class ignition::gazebo::RenderUtilPrivate /// \param[in] _node Node to be restored. /// TODO(anyone) On future versions, use a bounding box instead public: void LowlightNode(const rendering::NodePtr &_node); + + /// \brief New collisions to be created + public: std::vector newCollisions; + + /// \brief Finds the links (collision parent) that are used to create child + /// collision visuals in RenderUtil::Update + /// \param[in] _ecm The entity-component manager + public: void FindCollisionLinks(const EntityComponentManager &_ecm); + + /// \brief A list of links used to create new collision visuals + public: std::vector newCollisionLinks; + + /// \brief A map of collision entity ids and their SDF DOM + public: std::map entityCollisions; + + /// \brief A map of model entities and their corresponding children links + public: std::map> modelToLinkEntities; + + /// \brief A map of link entities and their corresponding children collisions + public: std::map> linkToCollisionEntities; + + /// \brief A map of created collision entities and if they are currently + /// visible + public: std::map viewingCollisions; }; ////////////////////////////////////////////////// @@ -225,6 +251,42 @@ void RenderUtil::UpdateFromECM(const UpdateInfo &_info, this->dataPtr->UpdateRenderingEntities(_ecm); this->dataPtr->RemoveRenderingEntities(_ecm, _info); this->dataPtr->markerManager.SetSimTime(_info.simTime); + this->dataPtr->FindCollisionLinks(_ecm); +} + +////////////////////////////////////////////////// +void RenderUtilPrivate::FindCollisionLinks(const EntityComponentManager &_ecm) +{ + if (this->newCollisions.empty()) + return; + + for (const auto &entity : this->newCollisions) + { + std::vector links; + if (_ecm.EntityMatches(entity, + std::set{components::Model::typeId})) + { + links = _ecm.EntitiesByComponents(components::ParentEntity(entity), + components::Link()); + } + else if (_ecm.EntityMatches(entity, + std::set{components::Link::typeId})) + { + links.push_back(entity); + } + else + { + ignerr << "Entity [" << entity + << "] for viewing collision must be a model or link" + << std::endl; + continue; + } + + this->newCollisionLinks.insert(this->newCollisionLinks.end(), + links.begin(), + links.end()); + } + this->newCollisions.clear(); } ////////////////////////////////////////////////// @@ -263,6 +325,7 @@ void RenderUtil::Update() auto entityPoses = std::move(this->dataPtr->entityPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); auto entityTemp = std::move(this->dataPtr->entityTemp); + auto newCollisionLinks = std::move(this->dataPtr->newCollisionLinks); this->dataPtr->newScenes.clear(); this->dataPtr->newModels.clear(); @@ -274,6 +337,7 @@ void RenderUtil::Update() this->dataPtr->entityPoses.clear(); this->dataPtr->actorTransforms.clear(); this->dataPtr->entityTemp.clear(); + this->dataPtr->newCollisionLinks.clear(); this->dataPtr->markerManager.Update(); @@ -457,6 +521,43 @@ void RenderUtil::Update() visual->SetUserData("temperature", temp.second); } } + + // create new collision visuals + { + for (const auto &link : newCollisionLinks) + { + std::vector colEntities = + this->dataPtr->linkToCollisionEntities[link]; + + for (const auto &colEntity : colEntities) + { + if (!this->dataPtr->sceneManager.HasEntity(colEntity)) + { + auto vis = this->dataPtr->sceneManager.CreateCollision(colEntity, + this->dataPtr->entityCollisions[colEntity], link); + this->dataPtr->viewingCollisions[colEntity] = true; + + // add geometry material to originalEmissive map + for (auto g = 0u; g < vis->GeometryCount(); ++g) + { + auto geom = vis->GeometryByIndex(g); + + // Geometry material + auto geomMat = geom->Material(); + if (nullptr == geomMat) + continue; + + if (this->dataPtr->originalEmissive.find(geom->Name()) == + this->dataPtr->originalEmissive.end()) + { + this->dataPtr->originalEmissive[geom->Name()] = + geomMat->Emissive(); + } + } + } + } + } + } } ////////////////////////////////////////////////// @@ -536,6 +637,8 @@ void RenderUtilPrivate::CreateRenderingEntities( link.SetRawPose(_pose->Data()); this->newLinks.push_back( std::make_tuple(_entity, link, _parent->Data())); + // used for collsions + this->modelToLinkEntities[_parent->Data()].push_back(_entity); return true; }); @@ -604,6 +707,23 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // collisions + _ecm.Each( + [&](const Entity &_entity, + const components::Collision *, + const components::Name *, + const components::Pose *, + const components::Geometry *, + const components::CollisionElement *_collElement, + const components::ParentEntity *_parent) -> bool + { + this->entityCollisions[_entity] = _collElement->Data(); + this->linkToCollisionEntities[_parent->Data()].push_back(_entity); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -709,6 +829,8 @@ void RenderUtilPrivate::CreateRenderingEntities( link.SetRawPose(_pose->Data()); this->newLinks.push_back( std::make_tuple(_entity, link, _parent->Data())); + // used for collsions + this->modelToLinkEntities[_parent->Data()].push_back(_entity); return true; }); @@ -768,6 +890,23 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // collisions + _ecm.EachNew( + [&](const Entity &_entity, + const components::Collision *, + const components::Name *, + const components::Pose *, + const components::Geometry *, + const components::CollisionElement *_collElement, + const components::ParentEntity *_parent) -> bool + { + this->entityCollisions[_entity] = _collElement->Data(); + this->linkToCollisionEntities[_parent->Data()].push_back(_entity); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -944,6 +1083,7 @@ void RenderUtilPrivate::RemoveRenderingEntities( [&](const Entity &_entity, const components::Model *)->bool { this->removeEntities[_entity] = _info.iterations; + this->modelToLinkEntities.erase(_entity); return true; }); @@ -951,6 +1091,7 @@ void RenderUtilPrivate::RemoveRenderingEntities( [&](const Entity &_entity, const components::Link *)->bool { this->removeEntities[_entity] = _info.iterations; + this->linkToCollisionEntities.erase(_entity); return true; }); @@ -1009,6 +1150,16 @@ void RenderUtilPrivate::RemoveRenderingEntities( this->removeEntities[_entity] = _info.iterations; return true; }); + + // collisions + _ecm.EachRemoved( + [&](const Entity &_entity, const components::Collision *)->bool + { + this->removeEntities[_entity] = _info.iterations; + this->viewingCollisions.erase(_entity); + this->entityCollisions.erase(_entity); + return true; + }); } ///////////////////////////////////////////////// @@ -1312,3 +1463,65 @@ void RenderUtilPrivate::LowlightNode(const rendering::NodePtr &_node) } } } + +///////////////////////////////////////////////// +void RenderUtil::ViewCollisions(const Entity &_entity) +{ + std::vector colEntities; + if (this->dataPtr->linkToCollisionEntities.find(_entity) != + this->dataPtr->linkToCollisionEntities.end()) + { + colEntities = this->dataPtr->linkToCollisionEntities[_entity]; + } + else if (this->dataPtr->modelToLinkEntities.find(_entity) != + this->dataPtr->modelToLinkEntities.end()) + { + std::vector links = this->dataPtr->modelToLinkEntities[_entity]; + for (const auto &link : links) + colEntities.insert(colEntities.end(), + this->dataPtr->linkToCollisionEntities[link].begin(), + this->dataPtr->linkToCollisionEntities[link].end()); + } + + // create and/or toggle collision visuals + + bool showCol, showColInit = false; + // first loop looks for new collisions + for (const auto &colEntity : colEntities) + { + if (this->dataPtr->viewingCollisions.find(colEntity) == + this->dataPtr->viewingCollisions.end()) + { + this->dataPtr->newCollisions.push_back(_entity); + showColInit = showCol = true; + } + } + + // second loop toggles already created collisions + for (const auto &colEntity : colEntities) + { + if (this->dataPtr->viewingCollisions.find(colEntity) == + this->dataPtr->viewingCollisions.end()) + continue; + + // when viewing multiple collisions (e.g. _entity is a model), + // boolean for view collisions is based on first colEntity in list + if (!showColInit) + { + showCol = !this->dataPtr->viewingCollisions[colEntity]; + showColInit = true; + } + + rendering::VisualPtr colVisual = + this->dataPtr->sceneManager.VisualById(colEntity); + if (colVisual == nullptr) + { + ignerr << "Could not find collision visual for entity [" << colEntity + << "]" << std::endl; + continue; + } + + this->dataPtr->viewingCollisions[colEntity] = showCol; + colVisual->SetVisible(showCol); + } +} diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 7e0beb34b4..0be6da0be2 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -341,6 +342,36 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, return visualVis; } +///////////////////////////////////////////////// +rendering::VisualPtr SceneManager::VisualById(Entity _id) +{ + if (this->dataPtr->visuals.find(_id) == this->dataPtr->visuals.end()) + { + ignerr << "Could not find visual for entity: " << _id << std::endl; + return nullptr; + } + return this->dataPtr->visuals[_id]; +} + +///////////////////////////////////////////////// +rendering::VisualPtr SceneManager::CreateCollision(Entity _id, + const sdf::Collision &_collision, Entity _parentId) +{ + sdf::Material material; + material.SetAmbient(math::Color(1, 0.5088, 0.0468, 0.7)); + material.SetDiffuse(math::Color(1, 0.5088, 0.0468, 0.7)); + + sdf::Visual visual; + visual.SetGeom(*_collision.Geom()); + visual.SetMaterial(material); + visual.SetCastShadows(false); + + visual.SetRawPose(_collision.RawPose()); + visual.SetName(_collision.Name()); + + rendering::VisualPtr collisionVis = CreateVisual(_id, visual, _parentId); + return collisionVis; +} ///////////////////////////////////////////////// rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, math::Vector3d &_scale, math::Pose3d &_localPose) From 59ea1c6cb92dbdfa5e64d1b1b53ed3c0dd303e89 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Thu, 28 Jan 2021 23:19:25 -0500 Subject: [PATCH 15/55] Remove playback SDF param in Dome (#570) * change system injected playback path tag; update documentation * Remove SDF param for LogPlayback Signed-off-by: Mabel Zhang Co-authored-by: John Shepherd --- Migration.md | 3 ++ src/ServerConfig.cc | 4 +- src/systems/log/LogPlayback.cc | 2 +- test/integration/log_system.cc | 85 ++++++++++++---------------------- test/worlds/log_playback.sdf | 2 - tutorials/log.md | 5 ++ 6 files changed, 41 insertions(+), 60 deletions(-) diff --git a/Migration.md b/Migration.md index ab87e91c01..30fded54d3 100644 --- a/Migration.md +++ b/Migration.md @@ -24,6 +24,9 @@ in SDF by setting the `` SDF element. std::string(const gazebo::Entity &, const sdf::Sensor &, const std::string &)>)` +* Log playback using `` SDF parameter is removed. Use --playback command + line argument instead. + ## Ignition Gazebo 2.x to 3.x * Use ign-rendering3, ign-sensors3 and ign-gui3. diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index beee1e2ba4..b7dd413cb6 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -572,9 +572,9 @@ ServerConfig::LogPlaybackPlugin() const if (!this->LogPlaybackPath().empty()) { sdf::ElementPtr pathElem = std::make_shared(); - pathElem->SetName("path"); + pathElem->SetName("playback_path"); playbackElem->AddElementDescription(pathElem); - pathElem = playbackElem->GetElement("path"); + pathElem = playbackElem->GetElement("playback_path"); pathElem->AddValue("string", "", false, ""); pathElem->Set(this->LogPlaybackPath()); } diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index c061bbe997..e7b557e44d 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -183,7 +183,7 @@ void LogPlayback::Configure(const Entity &, EntityComponentManager &_ecm, EventManager &_eventMgr) { // Get directory paths from SDF - this->dataPtr->logPath = _sdf->Get("path"); + this->dataPtr->logPath = _sdf->Get("playback_path"); this->dataPtr->eventManager = &_eventMgr; diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 06dc2b62e7..205ff31a16 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -165,7 +165,6 @@ class LogSystemTest : public ::testing::Test common::removeAll(this->logsDir); } common::createDirectories(this->logsDir); - common::createDirectories(this->logPlaybackDir); } // Append extension to the end of a path, removing the separator at @@ -266,10 +265,6 @@ class LogSystemTest : public ::testing::Test /// \brief Path to recorded log file public: std::string logDir = common::joinPaths(logsDir, "test_logs_record"); - - /// \brief Path to log file for playback - public: std::string logPlaybackDir = - common::joinPaths(this->logsDir, "test_logs_playback"); }; ///////////////////////////////////////////////// @@ -341,16 +336,16 @@ TEST_F(LogSystemTest, LogDefaults) EXPECT_EQ(setenv(IGN_HOMEDIR, homeFake.c_str(), 1), 0); // Test case 1: - // No path specified, on both command line and SDF. This does not go through + // No path specified on command line. This does not go through // ign.cc, so ignLogDirectory() is not initialized (empty string). Recording // should not take place. { - // Change log path in SDF to empty + // Load SDF sdf::Root recordSdfRoot; - this->ChangeLogPath(recordSdfRoot, recordSdfPath, "LogRecord", - " "); + EXPECT_EQ(recordSdfRoot.Load(recordSdfPath).size(), 0lu); + EXPECT_GT(recordSdfRoot.WorldCount(), 0lu); - // Pass changed SDF to server + // Pass SDF to server ServerConfig recordServerConfig; recordServerConfig.SetSdfString(recordSdfRoot.Element()->ToString("")); @@ -743,25 +738,17 @@ TEST_F(LogSystemTest, RecordAndPlayback) auto logFile = common::joinPaths(this->logDir, "state.tlog"); EXPECT_TRUE(common::exists(logFile)); - // move the log file to the playback directory - auto logPlaybackFile = common::joinPaths(this->logPlaybackDir, "state.tlog"); + // Path to log file for playback + std::string logPlaybackDir = + common::joinPaths(this->logsDir, "test_logs_playback"); + common::createDirectories(logPlaybackDir); + + // Move the log file to the playback directory + auto logPlaybackFile = common::joinPaths(logPlaybackDir, "state.tlog"); common::moveFile(logFile, logPlaybackFile); EXPECT_TRUE(common::exists(logPlaybackFile)); - // World file to load - const auto playSdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), - "test", "worlds", "log_playback.sdf"); - - // Change log path in world SDF to build directory - sdf::Root playSdfRoot; - this->ChangeLogPath(playSdfRoot, playSdfPath, "LogPlayback", - this->logPlaybackDir); - ASSERT_EQ(1u, playSdfRoot.WorldCount()); - - const auto sdfWorld = playSdfRoot.WorldByIndex(0); - EXPECT_EQ("default", sdfWorld->Name()); - - // Load log file recorded above + // Load log file recorded above for validation transport::log::Log log; log.Open(logPlaybackFile); @@ -794,10 +781,6 @@ TEST_F(LogSystemTest, RecordAndPlayback) EXPECT_EQ(32, stateMsg.entities_size()); EXPECT_EQ(batch.end(), ++recordedIter); - // Pass changed SDF to server - ServerConfig playServerConfig; - playServerConfig.SetSdfString(playSdfRoot.Element()->ToString("")); - // Keep track of total number of pose comparisons int nTotal{0}; @@ -818,6 +801,10 @@ TEST_F(LogSystemTest, RecordAndPlayback) EXPECT_EQ(0, recordedMsg.header().stamp().sec()); EXPECT_EQ(1000000, recordedMsg.header().stamp().nsec()); + // Playback config + ServerConfig playServerConfig; + playServerConfig.SetLogPlaybackPath(logPlaybackDir); + // Start server Server playServer(playServerConfig); @@ -1026,7 +1013,7 @@ TEST_F(LogSystemTest, LogOverwrite) // Create temp directory to store log this->CreateLogsDir(); #ifndef __APPLE__ - EXPECT_EQ(1, entryCount(this->logsDir)); + EXPECT_EQ(0, entryCount(this->logsDir)); EXPECT_EQ(0, entryCount(this->logDir)); #endif @@ -1062,7 +1049,7 @@ TEST_F(LogSystemTest, LogOverwrite) #ifndef __APPLE__ // Log files were created - EXPECT_EQ(2, entryCount(this->logsDir)); + EXPECT_EQ(1, entryCount(this->logsDir)); EXPECT_EQ(2, entryCount(this->logDir)); std::filesystem::path tlogStdPath = tlogPath; auto tlogPrevTime = std::filesystem::last_write_time(tlogStdPath); @@ -1088,7 +1075,7 @@ TEST_F(LogSystemTest, LogOverwrite) #ifndef __APPLE__ // No new files were created - EXPECT_EQ(2, entryCount(this->logsDir)); + EXPECT_EQ(1, entryCount(this->logsDir)); EXPECT_EQ(2, entryCount(this->logDir)); // Test timestamp is newer @@ -1116,7 +1103,7 @@ TEST_F(LogSystemTest, LogOverwrite) EXPECT_TRUE(common::exists(clogPath)); // No new files were created - EXPECT_EQ(2, entryCount(this->logsDir)); + EXPECT_EQ(1, entryCount(this->logsDir)); EXPECT_EQ(2, entryCount(this->logDir)); // Test timestamp is newer @@ -1158,7 +1145,7 @@ TEST_F(LogSystemTest, LogOverwrite) "server_console.log"))); // New files were created - EXPECT_EQ(3, entryCount(this->logsDir)); + EXPECT_EQ(2, entryCount(this->logsDir)); EXPECT_EQ(2, entryCount(this->logDir)); EXPECT_EQ(2, entryCount(this->logDir + "(1)")); @@ -1175,16 +1162,8 @@ TEST_F(LogSystemTest, LogControlLevels) auto logPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "media", "levels_log"); - const auto playSdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), - "test", "worlds", "log_playback.sdf"); - - // Change log path in world SDF to build directory - sdf::Root playSdfRoot; - this->ChangeLogPath(playSdfRoot, playSdfPath, "LogPlayback", - logPath); - ServerConfig config; - config.SetSdfString(playSdfRoot.Element()->ToString("")); + config.SetLogPlaybackPath(logPath); Server server(config); @@ -1390,29 +1369,25 @@ TEST_F(LogSystemTest, LogCompress) // Test compressed file exists EXPECT_TRUE(common::exists(customCmpPath)); + // Path to log file for playback + std::string logPlaybackDir = + common::joinPaths(this->logsDir, "test_logs_playback"); + common::createDirectories(logPlaybackDir); + // Move recorded file to playback directory // Prefix the zip by the name of the original recorded folder. Playback will // extract and assume subdirectory to take on the name of the zip file // without extension. - auto newCmpPath = common::joinPaths(this->logPlaybackDir, + auto newCmpPath = common::joinPaths(logPlaybackDir, common::basename(defaultCmpPath)); common::moveFile(customCmpPath, newCmpPath); EXPECT_TRUE(common::exists(newCmpPath)); // Play back compressed file { - // World with playback plugin - const auto playSdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), - "test", "worlds", "log_playback.sdf"); - - // Change log path in world SDF to build directory - sdf::Root playSdfRoot; - this->ChangeLogPath(playSdfRoot, playSdfPath, "LogPlayback", - newCmpPath); - // Pass changed SDF to server ServerConfig playServerConfig; - playServerConfig.SetSdfString(playSdfRoot.Element()->ToString("")); + playServerConfig.SetLogPlaybackPath(newCmpPath); // Run server Server playServer(playServerConfig); diff --git a/test/worlds/log_playback.sdf b/test/worlds/log_playback.sdf index 4ad6985c1a..b46b04d357 100644 --- a/test/worlds/log_playback.sdf +++ b/test/worlds/log_playback.sdf @@ -7,8 +7,6 @@ - - /tmp/log diff --git a/tutorials/log.md b/tutorials/log.md index 4a69e41eef..09423fa8a7 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -96,6 +96,11 @@ directory specified to record: `ign gazebo -r -v 4 --playback ` +### From plugin in SDF + +Playing back via the SDF tag `` has been removed. +Please use the command line argument. + ## Known issues * When using command-line playback there is currently a small caveat. From 4cbc9dd9f7805265c51b717d2ad7af4396feeb54 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 29 Jan 2021 17:21:10 +0100 Subject: [PATCH 16/55] Simplify particle emitter component. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- .../gazebo/components/ParticleEmitter.hh | 83 +------------ test/integration/components.cc | 113 +++++++++--------- 2 files changed, 58 insertions(+), 138 deletions(-) diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index 6385171838..a6ec2a242c 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -18,12 +18,9 @@ #define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_ #include - -#include -#include - #include #include +#include #include namespace ignition @@ -32,84 +29,12 @@ namespace gazebo { // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace particles -{ - /// \brief Properties of a particle emitter. - class Emitter - { - /// \brief Equality operator. This function checks if the given - /// emitter has identical id than this object. - /// \param[in] _emitter The emitter to compare against. - /// \return True if this object matches the provided object. - public: bool operator==(const Emitter &_emitter) const - { - return this->data.id() == _emitter.data.id(); - } - - /// \brief Inequality operator. This function checks if the given - /// emitter has identical id than this object. - /// \param[in] _emitter The emitter to compare against. - /// \return True if this object doesn't match the provided object. - public: bool operator!=(const Emitter &_emitter) const - { - return !(*this == _emitter); - } - - /// \brief The particle emitter internal data. - public: ignition::msgs::ParticleEmitter data; - }; -} - -namespace serializers -{ - /// \brief Serializer for components::ParticleEmitter object - class ParticleEmitterSerializer - { - /// \brief Serialization for particles::Emitter - /// \param[out] _out Output stream - /// \param[in] _emitter Object for the stream - /// \return The stream - public: static std::ostream &Serialize(std::ostream &_out, - const particles::Emitter &_emitter) - { - if (!_emitter.data.SerializeToOstream(&_out)) - { - ignerr << "Error serializing particle emitter: " << std::endl; - ignerr << _emitter.data.DebugString() << std::endl; - } - - return _out; - } - - /// \brief Deserialization for particles::Emitter - /// \param[in] _in Input stream - /// \param[out] _emitter The object to populate - /// \return The stream - public: static std::istream &Deserialize(std::istream &_in, - particles::Emitter &_emitter) - { - if (!_emitter.data.ParseFromIstream(&_in)) - { - ignerr << "Error deserializing particle emitter: " << std::endl; - ignerr << _emitter.data.DebugString() << std::endl; - } - - return _in; - } - }; -} - -// using separate namespace blocks so all components appear in Doxygen -// (appears as if Doxygen can't parse multiple components in a single -// namespace block since IGN_GAZEBO_REGISTER_COMPONENT doesn't have a -// trailing semicolon) namespace components { - /// \brief A component that contains a particle emitter, which is - /// represented by particles::Emitter - using ParticleEmitter = Component; + serializers::MsgSerializer>; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", ParticleEmitter) } diff --git a/test/integration/components.cc b/test/integration/components.cc index 3412d6010f..f5efe59e0d 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -1473,69 +1473,64 @@ TEST_F(ComponentsTest, Scene) ////////////////////////////////////////////////// TEST_F(ComponentsTest, ParticleEmitter) { - particles::Emitter emitter1; - emitter1.data.set_name("emitter1"); - emitter1.data.set_id(0); - emitter1.data.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); - emitter1.data.mutable_size()->set_x(1); - emitter1.data.mutable_size()->set_y(2); - emitter1.data.mutable_size()->set_z(3); - emitter1.data.set_rate(4.0); - emitter1.data.set_duration(5.0); - emitter1.data.set_emitting(false); - emitter1.data.mutable_particle_size()->set_x(0.1); - emitter1.data.mutable_particle_size()->set_y(0.2); - emitter1.data.mutable_particle_size()->set_z(0.3); - emitter1.data.set_lifetime(6.0); - emitter1.data.set_min_velocity(7.0); - emitter1.data.set_max_velocity(8.0); - emitter1.data.mutable_color_start()->set_r(1.0); - emitter1.data.mutable_color_start()->set_g(0); - emitter1.data.mutable_color_start()->set_b(0); - emitter1.data.mutable_color_start()->set_a(0); - emitter1.data.mutable_color_end()->set_r(1.0); - emitter1.data.mutable_color_end()->set_g(1.0); - emitter1.data.mutable_color_end()->set_b(1.0); - emitter1.data.mutable_color_end()->set_a(0); - emitter1.data.set_scale_rate(9.0); - emitter1.data.set_color_range_image("path_to_texture"); - - particles::Emitter emitter2; - emitter2.data.set_name("emitter2"); - emitter2.data.set_id(1); - emitter2.data.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); - emitter2.data.mutable_size()->set_x(1); - emitter2.data.mutable_size()->set_y(2); - emitter2.data.mutable_size()->set_z(3); - emitter2.data.set_rate(4.0); - emitter2.data.set_duration(5.0); - emitter2.data.set_emitting(false); - emitter2.data.mutable_particle_size()->set_x(0.1); - emitter2.data.mutable_particle_size()->set_y(0.2); - emitter2.data.mutable_particle_size()->set_z(0.3); - emitter2.data.set_lifetime(6.0); - emitter2.data.set_min_velocity(7.0); - emitter2.data.set_max_velocity(8.0); - emitter2.data.mutable_color_start()->set_r(1.0); - emitter2.data.mutable_color_start()->set_g(0); - emitter2.data.mutable_color_start()->set_b(0); - emitter2.data.mutable_color_start()->set_a(0); - emitter2.data.mutable_color_end()->set_r(1.0); - emitter2.data.mutable_color_end()->set_g(1.0); - emitter2.data.mutable_color_end()->set_b(1.0); - emitter2.data.mutable_color_end()->set_a(0); - emitter2.data.set_scale_rate(9.0); - emitter2.data.set_color_range_image("path_to_texture"); + msgs::ParticleEmitter emitter1; + emitter1.set_name("emitter1"); + emitter1.set_id(0); + emitter1.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); + emitter1.mutable_size()->set_x(1); + emitter1.mutable_size()->set_y(2); + emitter1.mutable_size()->set_z(3); + emitter1.set_rate(4.0); + emitter1.set_duration(5.0); + emitter1.set_emitting(false); + emitter1.mutable_particle_size()->set_x(0.1); + emitter1.mutable_particle_size()->set_y(0.2); + emitter1.mutable_particle_size()->set_z(0.3); + emitter1.set_lifetime(6.0); + emitter1.set_min_velocity(7.0); + emitter1.set_max_velocity(8.0); + emitter1.mutable_color_start()->set_r(1.0); + emitter1.mutable_color_start()->set_g(0); + emitter1.mutable_color_start()->set_b(0); + emitter1.mutable_color_start()->set_a(0); + emitter1.mutable_color_end()->set_r(1.0); + emitter1.mutable_color_end()->set_g(1.0); + emitter1.mutable_color_end()->set_b(1.0); + emitter1.mutable_color_end()->set_a(0); + emitter1.set_scale_rate(9.0); + emitter1.set_color_range_image("path_to_texture"); + + msgs::ParticleEmitter emitter2; + emitter2.set_name("emitter2"); + emitter2.set_id(1); + emitter2.set_type(ignition::msgs::ParticleEmitter_EmitterType_BOX); + emitter2.mutable_size()->set_x(1); + emitter2.mutable_size()->set_y(2); + emitter2.mutable_size()->set_z(3); + emitter2.set_rate(4.0); + emitter2.set_duration(5.0); + emitter2.set_emitting(false); + emitter2.mutable_particle_size()->set_x(0.1); + emitter2.mutable_particle_size()->set_y(0.2); + emitter2.mutable_particle_size()->set_z(0.3); + emitter2.set_lifetime(6.0); + emitter2.set_min_velocity(7.0); + emitter2.set_max_velocity(8.0); + emitter2.mutable_color_start()->set_r(1.0); + emitter2.mutable_color_start()->set_g(0); + emitter2.mutable_color_start()->set_b(0); + emitter2.mutable_color_start()->set_a(0); + emitter2.mutable_color_end()->set_r(1.0); + emitter2.mutable_color_end()->set_g(1.0); + emitter2.mutable_color_end()->set_b(1.0); + emitter2.mutable_color_end()->set_a(0); + emitter2.set_scale_rate(9.0); + emitter2.set_color_range_image("path_to_texture"); // Create components. auto comp1 = components::ParticleEmitter(emitter1); auto comp2 = components::ParticleEmitter(emitter2); - // Equality operators. - EXPECT_NE(comp1, comp2); - EXPECT_FALSE(comp1 == comp2); - EXPECT_TRUE(comp1 != comp2); - // Stream operators. std::ostringstream ostr; comp1.Serialize(ostr); @@ -1543,5 +1538,5 @@ TEST_F(ComponentsTest, ParticleEmitter) std::istringstream istr(ostr.str()); components::ParticleEmitter comp3; comp3.Deserialize(istr); - EXPECT_EQ(comp1, comp3); + EXPECT_EQ(comp1.Data().id(), comp3.Data().id()); } From 39e98e1164844fb80842b90fb9f29610adfb0295 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 29 Jan 2021 09:49:33 -0800 Subject: [PATCH 17/55] Tutorial on migrating SDF files from Gazebo classic (#400) Signed-off-by: Louise Poubel Co-authored-by: Michael Carroll --- tutorials.md.in | 1 + tutorials/migration_sdf.md | 341 +++++++++++++++++++++++++++++++++++++ 2 files changed, 342 insertions(+) create mode 100644 tutorials/migration_sdf.md diff --git a/tutorials.md.in b/tutorials.md.in index 6930c6c746..0219b39c81 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -28,6 +28,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. **Migration from Gazebo classic** * \subpage migrationplugins "Plugins": Walk through the differences between writing plugins for Gazebo classic and Ignition Gazebo +* \subpage migrationsdf "SDF": Migrating SDF files from Gazebo classic to Ignition Gazebo * \subpage migrationworldapi "World API": Guide on what World C++ functions to call in Ignition Gazebo when migrating from Gazebo classic * \subpage migrationmodelapi "Model API": Guide on what Model C++ functions to call in Ignition Gazebo when migrating from Gazebo classic * \subpage migrationlinkapi "Link API": Guide on what Link C++ functions to call in Ignition Gazebo when migrating from Gazebo classic diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md new file mode 100644 index 0000000000..52e3716bb1 --- /dev/null +++ b/tutorials/migration_sdf.md @@ -0,0 +1,341 @@ +\page migrationsdf + +# Migration from Gazebo classic: SDF + +Both Gazebo classic and Ignition Gazebo support [SDF](http://sdformat.org/) +files to describe the simulation to be loaded. An SDF file defines the world +environment, the robot's characteristics and what plugins to load. + +Despite using the same description format, users will note that the same SDF +file may behave differently for each simulator. This tutorial will +explain how to write SDF files in a way that they're as reusable by both +simulators as possible. It will also explain when you'll need to use separate +files for each simulator. + +The minimum required versions to use this guide are: + +* Gazebo 11.2.0 +* Igniton Citadel + +## URIs + +SDF files use URIs to refer to resources from other files, such as meshes and +nested models. These are some of the SDF tags that take URIs: + +* `` +* `` +* `<...><*_map>` (only on Ignition) +* `` +* `` + +Here are the recommended ways to use URIs from most recommended to least: + +### Ignition Fuel URL + +It's possible to use URLs of resources on +[Ignition Fuel](https://app.ignitionrobotics.org) within any of the tags +above and both simulators will be able to load it. + +For example, this world can be loaded into both simulators: + +``` + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Ground Plane + + + + 3 -1.5 0 0 0 0 + true + + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + + + + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + + + + + + + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/actor - relative paths/tip/files/meshes/talk_b.dae + 1.0 + + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/actor - relative paths/tip/files/meshes/talk_b.dae + 1.0 + + + + + + +``` + +\note The actor's vertical pose will be different on both simulators. + That's because a hardcoded offset was removed on Ignition and + maintained on Gazebo classic for backwards compatibility. + +### Path relative to the SDF file + +It's possible to use relative paths within SDF files to refer to other files +in the same directory. This is recommended when creating files that work +together and need to be relocatable. + +For example, consider the following directory structure: + +``` +/home/username/ +├── world.sdf +└── models + └── model1 + ├── model.sdf + └── meshes + └── mesh.dae +``` + +The world `world.sdf` can include `model1` as follows: + +`models/model1` + +And `model.sdf` can refer to `mesh.dae` as: + +`meshes/mesh.dae` + +### Path relative to an environment variable + +This method is useful if you don't know where the files will be located +with respect to each other, and you have some control over the simulation's +runtime environment. On either simulator, you can refer to resources relative +to paths set on an environment variable. + +Each simulator uses a different environment variable: + +* Gazebo classic: + * `GAZEBO_MODEL_PATH` for models + * `GAZEBO_RESOURCE_PATH` for worlds and some rendering resources +* Ignition Gazebo: + * `IGN_GAZEBO_RESOURCE_PATH` for worlds, models and other resources + +For example, if you have the file structure above, you can set the environment +variable to `/home/username/models`: + +``` +export GAZEBO_MODEL_PATH=/home/username/models +export GAZEBO_RESOURCE_PATH=/home/username/models +export IGN_GAZEBO_RESOURCE_PATH=/home/username/models +``` + +And inside `world.sdf` include the model with: + +`model://model1` + +Also, `model.sdf` can refer to `mesh.dae` as: + +`model://model1/meshes/mesh.dae` + +On both situations, the `model://` prefix will be substituted by +`/home/username/models`. + +You can also set several lookup paths separating them with `:`, for example: + +`export IGN_GAZEBO_RESOURCE_PATH=/home/username/models:/home/username/another_project/models` + +### Absolute paths + +Finally, both simulators will accept absolute paths, for example: + +`/home/username/models/model1` + +This method is not recommended, because the file most likely won't work if +copied to a different computer. It also becomes inconvenient to move files to +different directories. + +## Plugins + +Plugins are binary files compiled to use with a specific simulator. Plugins +for Gazebo classic and Ignition Gazebo aren't usually compatible, so plugins +will need to be specified for each simulator separately. + +It's important to note that for both simulators, plugins compiled against +a major version of the simulator can't be loaded by other major versions. +The shared libraries will usually have the same name, so it's important to make +sure you're loading the correct plugins. + +### Official plugins + +Both simulators are installed with several built-in plugins. +[Gazebo classic's plugins](https://github.com/osrf/gazebo/tree/gazebo11/plugins) +and +[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo3/src/systems) +have different file names. For example, to use Gazebo classic's differential drive +plugin, the user can refer to it as follows: + +``` + + + ... + + +``` + +On Ignition, that would be: + +``` + + + ... + + +``` + +Note that besides the different file name, Ignition also requires the C++ class +to be defined in the `name` attribute. + +Also keep in mind that plugins that offer similar functionality may accept +different parameters for each simulator. Be sure to check the documentation of +each plugin before using it. + +### Custom plugins + +To load custom plugins, users need to set environment variables to the directory +where that plugin is located. The variables are different for each simulator: + +* Gazebo classic: + * `GAZEBO_PLUGIN_PATH` for all plugin types. +* Ignition Gazebo: + * `IGN_GAZEBO_SYSTEM_PLUGIN_PATH` for Ignition Gazebo systems (world, model, + sensor and visual plugins). + * `IGN_GUI_PLUGIN_PATH` for GUI plugins. + +### Keeping plugins separate + +Trying to load a plugin from one simulator into the other will: + +* Print an error message if the simulator can't find the plugin +* Potentially crash if the simulator can find the plugin and tries to load it + +That's why it's recommended not to specify plugins for both simulators +side-by-side on the same file. Instead, keep separate files and inject the plugins as +needed. + +There isn't a built-in mechanism on SDFormat to inject plugins into files yet, +but users can make use of templating tools like [ERB](erb_template.html) +and [xacro](http://wiki.ros.org/xacro) to generate SDF files with the correct plugins. + +### Default plugins + +Ignition Gazebo is more modular than Gazebo classic, so most features are optional. +For example, by default, Ignition will load all the system plugins defined on +the `~/.ignition/gazebo/server.config` file and all GUI plugins defined on the +`~/.ignition/gazebo/gui.config` file. But the user can always remove plugins from +those files, or choose different ones by adding `` tags to the SDF file. +(For more details, see the [Server configuration tutorial](server_config.html) +and the [GUI configuration tutorial](gui_config.html)). + +This is important to keep in mind when migrating your SDF files, because files +that worked on Gazebo classic may need more plugins on Ignition. + +## Materials + +Ignition does not support Ogre material files like Classic does, because Ignition +Gazebo can be used with multiple rendering engines. Therefore, materials defined +within a ` + +``` + +To make your models compatible with both simulators, you can use these alternatives: + +### Plain colors + +If the material defines plain colors, use the ``, ``, +`` and `` tags as needed. + +For example, this material from +[gazebo.material](https://github.com/osrf/gazebo/blob/gazebo11/media/materials/scripts/gazebo.material): + +``` + + + +``` + +Can be changed to: + +``` + + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + + +``` + +### Textures + +If an Ogre material script is being used to define a texture, there are a +couple alternatives. + +If using mesh files, the texture can be embedded into it. The advantage is that +this works for both simulators. Some examples: + +* [OBJ + MTL](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/DeskChair) +* [COLLADA](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/Lamp%20Post) + +For primitive shapes or even meshes, you can pass the texture as the albedo map. If you +want the model to be compatible with both Classic and Ignition, you can specify both +the script and the albedo map. + +``` + + + + texture.png + + + +``` + From f6a7329ad7a283034a54647d44c4c061666cfeb8 Mon Sep 17 00:00:00 2001 From: Gonzo <42421541+gonzodepedro@users.noreply.github.com> Date: Fri, 29 Jan 2021 15:15:41 -0300 Subject: [PATCH 18/55] World exporter (#474) * Added world exporter Signed-off-by: Gonzalo de Pedro * Fixed CMake Signed-off-by: Gonzalo de Pedro * Changes based on review Signed-off-by: Gonzalo de Pedro * Added example world Signed-off-by: Nate Koenig * bump required ign-common version Signed-off-by: Louise Poubel * PR updates Signed-off-by: Nate Koenig * Update documentation to have simulation self terminate Signed-off-by: Nate Koenig * Rename world_export to collada_world_exporter Signed-off-by: Nate Koenig * Finish world exporter renaming Signed-off-by: Nate Koenig * Revert change Signed-off-by: Nate Koenig * Added a tutorial Signed-off-by: Nate Koenig * Update transform Signed-off-by: Nate Koenig * Added message Signed-off-by: Nate Koenig * Added a test Signed-off-by: Nate Koenig * Added more shapes Signed-off-by: Nate Koenig * Cleanup in two locations Signed-off-by: Nate Koenig * Fix build Signed-off-by: Nate Koenig * Apply scale, and fix codecheck Signed-off-by: Nate Koenig Co-authored-by: Louise Poubel Co-authored-by: Nate Koenig --- CMakeLists.txt | 2 +- examples/worlds/collada_world_exporter.sdf | 180 ++++++++++++ src/ServerPrivate.cc | 4 +- src/systems/CMakeLists.txt | 1 + .../collada_world_exporter/CMakeLists.txt | 4 + .../ColladaWorldExporter.cc | 266 ++++++++++++++++++ .../ColladaWorldExporter.hh | 59 ++++ test/integration/CMakeLists.txt | 1 + test/integration/collada_world_exporter.cc | 83 ++++++ test/integration/diff_drive_system.cc | 4 +- test/worlds/collada_world_exporter.sdf | 150 ++++++++++ tutorials.md.in | 2 + tutorials/collada_world_exporter.md | 25 ++ 13 files changed, 777 insertions(+), 4 deletions(-) create mode 100644 examples/worlds/collada_world_exporter.sdf create mode 100644 src/systems/collada_world_exporter/CMakeLists.txt create mode 100644 src/systems/collada_world_exporter/ColladaWorldExporter.cc create mode 100644 src/systems/collada_world_exporter/ColladaWorldExporter.hh create mode 100644 test/integration/collada_world_exporter.cc create mode 100644 test/worlds/collada_world_exporter.sdf create mode 100644 tutorials/collada_world_exporter.md diff --git a/CMakeLists.txt b/CMakeLists.txt index 9218eed0f7..274e168a10 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -59,7 +59,7 @@ set(IGN_MSGS_VER ${ignition-msgs6_VERSION_MAJOR}) #-------------------------------------- # Find ignition-common # Always use the profiler component to get the headers, regardless of status. -ign_find_package(ignition-common3 VERSION 3.5 +ign_find_package(ignition-common3 VERSION 3.8 COMPONENTS profiler events diff --git a/examples/worlds/collada_world_exporter.sdf b/examples/worlds/collada_world_exporter.sdf new file mode 100644 index 0000000000..cd4b089ddd --- /dev/null +++ b/examples/worlds/collada_world_exporter.sdf @@ -0,0 +1,180 @@ + + + + + + + + + + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + + + + + + + 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.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 -1.5 0.5 0 0 0 + + + + 2 + 0 + 0 + 2 + 0 + 2 + + 2.0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index d082232740..cd1bdf7cde 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -227,15 +227,15 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) bool sdfUseLogRecord = (recordPluginElem != nullptr); bool hasRecordResources {false}; - bool hasCompress {false}; bool hasRecordTopics {false}; bool sdfRecordResources; - bool sdfCompress; std::vector sdfRecordTopics; if (sdfUseLogRecord) { + bool hasCompress {false}; + bool sdfCompress; std::tie(sdfRecordResources, hasRecordResources) = recordPluginElem->Get("record_resources", false); std::tie(sdfCompress, hasCompress) = diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index c5eeabe6e7..d8b61a4056 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -76,6 +76,7 @@ add_subdirectory(apply_joint_force) add_subdirectory(battery_plugin) add_subdirectory(breadcrumbs) add_subdirectory(buoyancy) +add_subdirectory(collada_world_exporter) add_subdirectory(contact) add_subdirectory(camera_video_recorder) add_subdirectory(detachable_joint) diff --git a/src/systems/collada_world_exporter/CMakeLists.txt b/src/systems/collada_world_exporter/CMakeLists.txt new file mode 100644 index 0000000000..a4bae60924 --- /dev/null +++ b/src/systems/collada_world_exporter/CMakeLists.txt @@ -0,0 +1,4 @@ +gz_add_system(collada-world-exporter + SOURCES + ColladaWorldExporter.cc +) diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc new file mode 100644 index 0000000000..0ab619f899 --- /dev/null +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -0,0 +1,266 @@ +/* + * Copyright (C) 2020 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 +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include + +#include "ColladaWorldExporter.hh" + +using namespace ignition; +using namespace gazebo; +using namespace systems; + + +class ignition::gazebo::systems::ColladaWorldExporterPrivate +{ + // Default constructor + public: ColladaWorldExporterPrivate() = default; + + /// \brief Has the world already been exported?. + private: bool exported{false}; + + /// \brief Exports the world to a mesh. + /// \param[_ecm] _ecm Mutable reference to the EntityComponentManager. + public: void Export(const EntityComponentManager &_ecm) + { + if (this->exported) return; + + common::Mesh worldMesh; + std::vector subMeshMatrix; + + _ecm.Each( + [&](const Entity /*& _entity*/, + const components::World *, + const components::Name * _name)->bool + { + worldMesh.SetName(_name->Data()); + return true; + }); + + _ecm.Each( + [&](const ignition::gazebo::Entity &_entity, + const components::Visual *, + const components::Name *_name, + const components::Geometry *_geom, + const components::Transparency *_transparency)->bool + { + std::string name = _name->Data().empty() ? std::to_string(_entity) : + _name->Data(); + + math::Pose3d worldPose = gazebo::worldPose(_entity, _ecm); + + common::MaterialPtr mat = std::make_shared(); + auto material = _ecm.Component(_entity); + if (material != nullptr) + { + mat->SetDiffuse(material->Data().Diffuse()); + mat->SetAmbient(material->Data().Ambient()); + mat->SetEmissive(material->Data().Emissive()); + mat->SetSpecular(material->Data().Specular()); + } + mat->SetTransparency(_transparency->Data()); + + const ignition::common::Mesh *mesh; + std::weak_ptr subm; + math::Vector3d scale; + math::Matrix4d matrix(worldPose); + ignition::common::MeshManager *meshManager = + ignition::common::MeshManager::Instance(); + + auto addSubmeshFunc = [&](int i) { + subm = worldMesh.AddSubMesh( + *mesh->SubMeshByIndex(0).lock().get()); + subm.lock()->SetMaterialIndex(i); + subm.lock()->Scale(scale); + subMeshMatrix.push_back(matrix); + }; + + if (_geom->Data().Type() == sdf::GeometryType::BOX) + { + if (meshManager->HasMesh("unit_box")) + { + mesh = meshManager->MeshByName("unit_box"); + scale = _geom->Data().BoxShape()->Size(); + int i = worldMesh.AddMaterial(mat); + + addSubmeshFunc(i); + } + } + else if (_geom->Data().Type() == sdf::GeometryType::CYLINDER) + { + if (meshManager->HasMesh("unit_cylinder")) + { + mesh = meshManager->MeshByName("unit_cylinder"); + scale.X() = _geom->Data().CylinderShape()->Radius() * 2; + scale.Y() = scale.X(); + scale.Z() = _geom->Data().CylinderShape()->Length(); + + int i = worldMesh.AddMaterial(mat); + + addSubmeshFunc(i); + } + } + else if (_geom->Data().Type() == sdf::GeometryType::PLANE) + { + if (meshManager->HasMesh("unit_plane")) + { + // Create a rotation for the plane mesh to account + // for the normal vector. + mesh = meshManager->MeshByName("unit_plane"); + + scale.X() = _geom->Data().PlaneShape()->Size().X(); + scale.Y() = _geom->Data().PlaneShape()->Size().Y(); + + // // The rotation is the angle between the +z(0,0,1) vector and the + // // normal, which are both expressed in the local (Visual) frame. + math::Vector3d normal = _geom->Data().PlaneShape()->Normal(); + math::Quaterniond normalRot; + normalRot.From2Axes(math::Vector3d::UnitZ, normal.Normalized()); + worldPose.Rot() = worldPose.Rot() * normalRot; + + matrix = math::Matrix4d(worldPose); + + int i = worldMesh.AddMaterial(mat); + addSubmeshFunc(i); + } + } + else if (_geom->Data().Type() == sdf::GeometryType::SPHERE) + { + if (meshManager->HasMesh("unit_sphere")) + { + mesh = meshManager->MeshByName("unit_sphere"); + + scale.X() = _geom->Data().SphereShape()->Radius() * 2; + scale.Y() = scale.X(); + scale.Z() = scale.X(); + + int i = worldMesh.AddMaterial(mat); + + addSubmeshFunc(i); + } + } + else if (_geom->Data().Type() == sdf::GeometryType::MESH) + { + auto fullPath = asFullPath(_geom->Data().MeshShape()->Uri(), + _geom->Data().MeshShape()->FilePath()); + + if (fullPath.empty()) + { + ignerr << "Mesh geometry missing uri" << std::endl; + return true; + } + mesh = meshManager->Load(fullPath); + + if (!mesh) { + ignerr << "mesh not found!" << std::endl; + return true; + } + + for (unsigned int k = 0; k < mesh->SubMeshCount(); k++) + { + auto subMeshLock = mesh->SubMeshByIndex(k).lock(); + int j = subMeshLock->MaterialIndex(); + + int i = 0; + if (j != -1) + { + i = worldMesh.IndexOfMaterial(mesh->MaterialByIndex(j).get()); + if (i < 0) + { + i = worldMesh.AddMaterial(mesh->MaterialByIndex(j)); + } + } + else + { + i = worldMesh.AddMaterial(mat); + } + + scale = _geom->Data().MeshShape()->Scale(); + + addSubmeshFunc(i); + } + } + else + { + ignwarn << "Unsupported geometry type" << std::endl; + } + + return true; + }); + + common::ColladaExporter exporter; + exporter.Export(&worldMesh, "./" + worldMesh.Name(), true, + subMeshMatrix); + ignmsg << "The world has been exported into the " + << "./" + worldMesh.Name() << " directory." << std::endl; + this->exported = true; + } +}; + +///////////////////////////////////////////////// +ColladaWorldExporter::ColladaWorldExporter() : System(), + dataPtr(std::make_unique()) +{ +} + +///////////////////////////////////////////////// +ColladaWorldExporter::~ColladaWorldExporter() = default; + +///////////////////////////////////////////////// +void ColladaWorldExporter::PostUpdate(const UpdateInfo & /*_info*/, + const EntityComponentManager &_ecm) +{ + this->dataPtr->Export(_ecm); +} + +IGNITION_ADD_PLUGIN(ColladaWorldExporter, + System, + ColladaWorldExporter::ISystemPostUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(ColladaWorldExporter, + "ignition::gazebo::systems::ColladaWorldExporter") diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.hh b/src/systems/collada_world_exporter/ColladaWorldExporter.hh new file mode 100644 index 0000000000..c31a175b0a --- /dev/null +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.hh @@ -0,0 +1,59 @@ +/* + * Copyright (C) 2020 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_SYSTEMS_COLLADAWORLDEXPORTER_HH_ +#define IGNITION_GAZEBO_SYSTEMS_COLLADAWORLDEXPORTER_HH_ + +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems +{ + // Forward declarations. + class ColladaWorldExporterPrivate; + + /// \brief A plugin that exports a world to a mesh. + /// When loaded the plugin will dump a mesh containing all the models in + /// the world to the current directory. + class IGNITION_GAZEBO_VISIBLE ColladaWorldExporter: + public System, + public ISystemPostUpdate + { + /// \brief Constructor + public: ColladaWorldExporter(); + + /// \brief Destructor + public: ~ColladaWorldExporter() final; + + // Documentation inherited + public: void PostUpdate(const UpdateInfo &_info, + const EntityComponentManager &_ecm); + + /// \brief Private data pointer. + private: std::unique_ptr dataPtr; + }; +} +} +} +} +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index b3c33508fc..1f228c1f88 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -7,6 +7,7 @@ set(tests battery_plugin.cc breadcrumbs.cc buoyancy.cc + collada_world_exporter.cc components.cc contact_system.cc detachable_joint.cc diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc new file mode 100644 index 0000000000..ae677413c0 --- /dev/null +++ b/test/integration/collada_world_exporter.cc @@ -0,0 +1,83 @@ +/* + * 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/Server.hh" +#include "ignition/gazebo/test_config.hh" + +#include "helpers/UniqueTestDirectoryEnv.hh" + +using namespace ignition; +using namespace gazebo; + +///////////////////////////////////////////////// +class ColladaWorldExporterFixture : public ::testing::Test +{ + public: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + } + + public: void LoadWorld(const std::string &_path) + { + ServerConfig serverConfig; + serverConfig.SetResourceCache(test::UniqueTestDirectoryEnv::Path()); + serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, _path)); + + std::cout << "Loading: " << serverConfig.SdfFile() << std::endl; + this->server = std::make_unique(serverConfig); + EXPECT_FALSE(server->Running()); + } + + public: std::unique_ptr server; +}; + +///////////////////////////////////////////////// +TEST_F(ColladaWorldExporterFixture, ExportWorld) +{ + this->LoadWorld(common::joinPaths("test", "worlds", + "collada_world_exporter.sdf")); + + // Cleanup + common::removeAll("./collada_world_exporter_box_test"); + + // The export directory shouldn't exist. + EXPECT_FALSE(common::exists("./collada_world_exporter_box_test")); + + // Run one iteration which should export the world. + server->Run(true, 1, false); + + // The export directory should now exist. + EXPECT_TRUE(common::exists("./collada_world_exporter_box_test")); + + // Cleanup + common::removeAll("./collada_world_exporter_box_test"); +} + +///////////////////////////////////////////////// +/// Main +int main(int _argc, char **_argv) +{ + ::testing::InitGoogleTest(&_argc, _argv); + ::testing::AddGlobalTestEnvironment( + new test::UniqueTestDirectoryEnv("save_world_test_cache")); + return RUN_ALL_TESTS(); +} diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 1d55d2b576..50279bd99a 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -358,7 +358,8 @@ TEST_P(DiffDriveTest, OdomFrameId) int sleep = 0; int maxSleep = 30; - for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) + // cppcheck-suppress knownConditionTrueFalse + for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) // NOLINT { std::this_thread::sleep_for(std::chrono::milliseconds(100)); } @@ -408,6 +409,7 @@ TEST_P(DiffDriveTest, OdomCustomFrameId) int sleep = 0; int maxSleep = 30; + // cppcheck-suppress knownConditionTrueFalse for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); diff --git a/test/worlds/collada_world_exporter.sdf b/test/worlds/collada_world_exporter.sdf new file mode 100644 index 0000000000..b65709b628 --- /dev/null +++ b/test/worlds/collada_world_exporter.sdf @@ -0,0 +1,150 @@ + + + + + + + + + true + + + + + 0 0 1 + + + + + + + 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.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 -1.5 0.5 0 0 0 + + + + 2 + 0 + 0 + 2 + 0 + 2 + + 2.0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + diff --git a/tutorials.md.in b/tutorials.md.in index 6930c6c746..bacb32edb2 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -24,6 +24,8 @@ 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. **Migration from Gazebo classic** diff --git a/tutorials/collada_world_exporter.md b/tutorials/collada_world_exporter.md new file mode 100644 index 0000000000..e1bdd4e60a --- /dev/null +++ b/tutorials/collada_world_exporter.md @@ -0,0 +1,25 @@ +\page collada_world_exporter Collada World Exporter + +The Collada world exporter is a world plugin that automatically generates +a Collada mesh consisting of the models within a world SDF file. This plugin +can be useful if you'd like to share an SDF world without requiring an SDF +loader. + +## Using the Collada World Exporter + +1. Add the following lines as a child to the `` tag in an SDF file. +``` + + +``` + +2. Run the world using +``` +ign gazebo -v 4 -s -r --iterations 1 WORLD_FILE_NAME +``` + +3. A subdirectory, named after the world, has been created in the current working directory. Within this subdirectory is the mesh and materials for the world. + +Refer to the [collada_world_exporter.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo4/examples/worlds/collada_world_exporter.sdf) example. From 4c87e1d9c6cea8ede46463defa436daca6780c35 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Mon, 1 Feb 2021 18:28:21 +0100 Subject: [PATCH 19/55] Model creation tutorial using services (#530) * Model creation tutorial using services Signed-off-by: ahcorde * Updated tutorial Signed-off-by: ahcorde * Tweaks to tutorial and example Signed-off-by: Louise Poubel * Move files Signed-off-by: Louise Poubel * example only needs ign-transport Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- .../standalone/entity_creation/CMakeLists.txt | 8 + examples/standalone/entity_creation/README.md | 25 +++ .../entity_creation/entity_creation.cc | 186 ++++++++++++++++++ tutorials.md.in | 1 + tutorials/entity_creation.md | 111 +++++++++++ 5 files changed, 331 insertions(+) create mode 100644 examples/standalone/entity_creation/CMakeLists.txt create mode 100644 examples/standalone/entity_creation/README.md create mode 100644 examples/standalone/entity_creation/entity_creation.cc create mode 100644 tutorials/entity_creation.md diff --git a/examples/standalone/entity_creation/CMakeLists.txt b/examples/standalone/entity_creation/CMakeLists.txt new file mode 100644 index 0000000000..99a0c16f7c --- /dev/null +++ b/examples/standalone/entity_creation/CMakeLists.txt @@ -0,0 +1,8 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +find_package(ignition-transport9 QUIET REQUIRED OPTIONAL_COMPONENTS log) +set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR}) + +add_executable(entity_creation entity_creation.cc) +target_link_libraries(entity_creation + ignition-transport${IGN_TRANSPORT_VER}::core) diff --git a/examples/standalone/entity_creation/README.md b/examples/standalone/entity_creation/README.md new file mode 100644 index 0000000000..e9a4ffcc18 --- /dev/null +++ b/examples/standalone/entity_creation/README.md @@ -0,0 +1,25 @@ +# Examples using the create service + +## Build + +``` +mkdir build +cd build +cmake .. +make +``` + +## Run + +This example only works if the world is called `empty`. Start an empty world with: + +``` +ign gazebo empty.sdf +``` + +Then run the create program to spawn entities into the world: + +``` +cd build +./entity_creation +``` diff --git a/examples/standalone/entity_creation/entity_creation.cc b/examples/standalone/entity_creation/entity_creation.cc new file mode 100644 index 0000000000..6184f1beef --- /dev/null +++ b/examples/standalone/entity_creation/entity_creation.cc @@ -0,0 +1,186 @@ +/* + * 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 + +// Create a transport node. +ignition::transport::Node node; + +// timeout used for services +constexpr unsigned int timeout = 5000; + +void createLight() +{ + bool result; + ignition::msgs::Boolean rep; +//! [create light] + ignition::msgs::EntityFactory entityFactoryRequest; + + entityFactoryRequest.mutable_light()->set_name("point"); + entityFactoryRequest.mutable_light()->set_range(4); + entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5); + entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); + entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); + entityFactoryRequest.mutable_light()->set_cast_shadows(false); + entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT); + ignition::msgs::Set( + entityFactoryRequest.mutable_light()->mutable_direction(), + ignition::math::Vector3d(0.5, 0.2, -0.9)); + ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), + ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); +//! [create light] + +//! [call service create] + bool executedEntityFactory = node.Request("/world/empty/create", + entityFactoryRequest, timeout, rep, result); + if (executedEntityFactory) + { + if (result) + std::cout << "Light was created : [" << rep.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +//! [call service create] +} + +void createEntityFromStr(const std::string modelStr) +{ +//! [call service create sphere] + bool result; + ignition::msgs::EntityFactory req; + ignition::msgs::Boolean res; + req.set_sdf(modelStr); + + bool executed = node.Request("/world/empty/create", + req, timeout, res, result); + if (executed) + { + if (result) + std::cout << "Sphere was created : [" << res.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +//! [call service create sphere] +} + +////////////////////////////////////////////////// +std::string generateLightStr( + const std::string light_type, const std::string name, + const bool cast_shadows, const ignition::math::Pose3d pose, + const ignition::math::Color diffuse, + const ignition::math::Color specular, + const double attRange, const double attConstant, + const double attLinear, const double attQuadratic, + const ignition::math::Vector3d direction, + const double spot_inner_angle, + const double spot_outer_angle, + const double spot_falloff +) +{ +//! [create light str] + std::string lightStr = std::string("") + + " " + + "" + std::to_string(cast_shadows) + "" + + "" + + std::to_string(pose.Pos().X()) + " " + + std::to_string(pose.Pos().Y()) + " " + + std::to_string(pose.Pos().Z()) + " " + + std::to_string(pose.Rot().Roll()) + " " + + std::to_string(pose.Rot().Pitch()) + " " + + std::to_string(pose.Rot().Yaw()) + + "" + + "" + + std::to_string(diffuse.R()) + " " + + std::to_string(diffuse.G()) + " " + + std::to_string(diffuse.B()) + " " + + std::to_string(diffuse.A()) + + "" + + "" + + std::to_string(specular.R()) + " " + + std::to_string(specular.G()) + " " + + std::to_string(specular.B()) + " " + + std::to_string(specular.A()) + + "" + + "" + + "" + std::to_string(attRange) + "" + + "" + std::to_string(attConstant) + "" + + "" + std::to_string(attLinear) + "" + + "" + std::to_string(attQuadratic) + "" + + "" + + "" + + std::to_string(direction.X()) + " " + + std::to_string(direction.Y()) + " " + + std::to_string(direction.Z()) + + "" + + "" + + "" + std::to_string(spot_inner_angle) + "" + + "" + std::to_string(spot_outer_angle) + "" + + "" + std::to_string(spot_falloff) + "" + + "" + + ""; +//! [create light str] + return lightStr; +} + +////////////////////////////////////////////////// +int main(int argc, char **argv) +{ +//! [create sphere] + auto sphereStr = R"( + + + + + 0 0 0.5 0 0 0 + + 1 + + + 1 + + + + )"; +//! [create sphere] + + createEntityFromStr(sphereStr); + + createEntityFromStr( + generateLightStr("spot", "spot_light", false, + ignition::math::Pose3d(0, 0, 4, 0, 0, 0), + ignition::math::Color(0, 0, 1.0, 1.0), + ignition::math::Color(0, 0, 1.0, 1.0), + 1.0, 0.2, 0.2, 0.001, + ignition::math::Vector3d(0.5, 0.2, -0.9), + 0.15, 0.45, 1.0)); + + createLight(); +} diff --git a/tutorials.md.in b/tutorials.md.in index bacb32edb2..5bf1018f1c 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -12,6 +12,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \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. +* \subpage entity_creation "Entity creation": Insert models or lights using services. * \subpage log "Logging": Record and play back time series of world state. * \subpage physics "Physics engines": Loading different physics engines. * \subpage battery "Battery": Keep track of battery charge on robot models. diff --git a/tutorials/entity_creation.md b/tutorials/entity_creation.md new file mode 100644 index 0000000000..0bbd34df56 --- /dev/null +++ b/tutorials/entity_creation.md @@ -0,0 +1,111 @@ +\page entity_creation Entity creation + +This tutorial gives an introduction to Ignition Gazebo's service `/world//create`. +This service allows creating entities in the scene such us spheres, lights, etc. + +Ignition Gazebo creates many services depending on the plugins that are specified in the SDF. +In this case we need to load the `UserCommands` plugin, which will offer the `create` service. +You can include the `UserCommands` system plugin including these lines in your SDF: + +```xml + + +``` + +You can check if this service is available typing: + +In one terminal + +```bash +ign gazebo -r -v 4 .sdf +``` + +In another terminal, see if the create service is listed: + +```bash +ign service --list +/gazebo/resource_paths/add +/gazebo/resource_paths/get +/gazebo/worlds +/gui/follow +/gui/move_to +/gui/move_to/pose +/gui/record_video +/gui/transform_mode +/gui/view_angle +/marker +/marker/list +/marker_array +/server_control +/world/world_name/control +/world/world_name/create +/world/world_name/create_multiple +/world/world_name/generate_world_sdf +/world/world_name/gui/info +/world/world_name/level/set_performer +/world/world_name/light_config +/world/world_name/playback/control +/world/world_name/remove +/world/world_name/scene/graph +/world/world_name/scene/info +/world/world_name/set_pose +/world/world_name/state +/world/world_name/state_async +``` + +# Factory message + +To create new entities in the world we need to use the +[ignition::msgs::EntityFactory](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1EntityFactory__V.html) +message to send a request to the create service. +This message allows us to create entities from strings, files, +[Models](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Model.html), +[Lights](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html) or even clone models. +This tutorial introduces how to create entities from SDF strings and light messages. + +## Insert an entity based on a string + +We will open an empty Ignition Gazebo world, let's start creating a sphere in the world. +In the next snippet you can see how to create models based on strings. + +\snippet examples/standalone/model_creation/model_creation.cc create sphere + +The variable `sphereStr` contains the SDF of the model that we want to create in the world. +In this case we are creating a sphere of 1 meter of radius in the position: `x: 0 y: 0 z: 0.5 roll: 0 pitch: 0 yaw: 0`. + +**NOTE**: You can insert here all kinds of models that can be described using an SDF string. + +Then we need to call the service `/world//create`: + +\snippet examples/standalone/model_creation/model_creation.cc call service create sphere + +**NOTE**: By default, if the entity name does not exist then the entity will be created +in the world. On the other hand, if that entity name already exists, then nothing will +happen. You may see some traces in the console showing this information. +There is an option to create a new entity every time that the message is sent by setting +`allow_renaming` to true (you can use the method `set_allow_renaming()`). + +## Insert a light + +To insert a light in the world we have two options: + + - Fill the string inside the `ignition::msgs::EntityFactory` message like in the section above. + - Fill the field `light` inside the `ignition::msgs::EntityFactory` message. + +In the following snippet you can see how the light's field is filled. + +\snippet examples/standalone/model_creation/model_creation.cc create light + +Or we can create an SDF string: + +\snippet examples/standalone/model_creation/model_creation.cc create light str + +Please check the API to know which fields are available in the +[Light message](https://ignitionrobotics.org/api/msgs/6.2/classignition_1_1msgs_1_1Light.html). +There are three types of lights: Point, Directional and Spot. + +Finally we should call the same service `/world//create`: + +\snippet examples/standalone/model_creation/model_creation.cc call service create From d8b9d0c3a328b6def406d411db5345c8799254b4 Mon Sep 17 00:00:00 2001 From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> Date: Mon, 1 Feb 2021 12:58:34 -0500 Subject: [PATCH 20/55] Fix topLevelModel method (#600) Signed-off-by: Ashton Larkin --- include/ignition/gazebo/Util.hh | 3 ++- src/Util.cc | 27 ++++++++++++++------------- src/Util_TEST.cc | 16 ++++++++++++++-- 3 files changed, 30 insertions(+), 16 deletions(-) diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index 3ec9ebd54d..cfa49e98d3 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -134,7 +134,8 @@ namespace ignition /// \brief Get the top level model of an entity /// \param[in] _entity Input entity /// \param[in] _ecm Constant reference to ECM. - /// \return Entity of top level model + /// \return Entity of top level model. If _entity has no top level model, + /// kNullEntity is returned. ignition::gazebo::Entity IGNITION_GAZEBO_VISIBLE topLevelModel( const Entity &_entity, const EntityComponentManager &_ecm); diff --git a/src/Util.cc b/src/Util.cc index 828483d0f0..ce00fd6ea0 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -400,22 +400,23 @@ ignition::gazebo::Entity topLevelModel(const Entity &_entity, { auto entity = _entity; - // check if parent is a model - auto parentComp = _ecm.Component(entity); - while (parentComp) - { - // check if parent is a model - auto parentEntity = parentComp->Data(); - auto modelComp = _ecm.Component( - parentEntity); - if (!modelComp) + // search up the entity tree and find the model with no parent models + // (there is the possibility of nested models) + Entity modelEntity = kNullEntity; + while (entity) + { + if (_ecm.Component(entity)) + modelEntity = entity; + + // stop searching if we are at the root of the tree + auto parentComp = _ecm.Component(entity); + if (!parentComp) break; - // set current model entity - entity = parentEntity; - parentComp = _ecm.Component(entity); + entity = parentComp->Data(); } - return entity; + + return modelEntity; } ////////////////////////////////////////////////// diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index d699b3dc3b..f9edf2543b 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -428,6 +428,7 @@ TEST_F(UtilTest, TopLevelModel) // - linkA // - modelB // - linkB + // - visualB // - modelC // World @@ -459,20 +460,31 @@ TEST_F(UtilTest, TopLevelModel) ecm.CreateComponent(linkBEntity, components::Name("linkB_name")); ecm.CreateComponent(linkBEntity, components::ParentEntity(modelBEntity)); + // Visual B - child of Link B + auto visualBEntity = ecm.CreateEntity(); + ecm.CreateComponent(visualBEntity, components::Visual()); + ecm.CreateComponent(visualBEntity, components::Name("visualB_name")); + ecm.CreateComponent(visualBEntity, components::ParentEntity(linkBEntity)); + // Model C auto modelCEntity = ecm.CreateEntity(); ecm.CreateComponent(modelCEntity, components::Model()); ecm.CreateComponent(modelCEntity, components::Name("modelC_name")); ecm.CreateComponent(modelCEntity, components::ParentEntity(worldEntity)); - // model A, link A, model B and link B should have model A as top level entity + // model A, link A, model B, link B and visual B should have + // model A as the top level model EXPECT_EQ(modelAEntity, topLevelModel(modelAEntity, ecm)); EXPECT_EQ(modelAEntity, topLevelModel(linkAEntity, ecm)); EXPECT_EQ(modelAEntity, topLevelModel(modelBEntity, ecm)); EXPECT_EQ(modelAEntity, topLevelModel(linkBEntity, ecm)); + EXPECT_EQ(modelAEntity, topLevelModel(visualBEntity, ecm)); - // model C should have itself as the top level entity + // model C should have itself as the top level model EXPECT_EQ(modelCEntity, topLevelModel(modelCEntity, ecm)); + + // the world should have no top level model + EXPECT_EQ(kNullEntity, topLevelModel(worldEntity, ecm)); } ///////////////////////////////////////////////// From b4e152d5940944a908192f4d43c5610445e64e42 Mon Sep 17 00:00:00 2001 From: Ashton Larkin Date: Thu, 17 Dec 2020 17:59:29 -0500 Subject: [PATCH 21/55] add heat signature option to thermal system (#498) Signed-off-by: Ashton Larkin --- examples/worlds/thermal_camera.sdf | 119 +++-------- .../gazebo/components/TemperatureRange.hh | 99 +++++++++ src/rendering/RenderUtil.cc | 60 +++++- src/systems/sensors/Sensors.cc | 21 ++ src/systems/thermal/Thermal.cc | 92 ++++++++- test/integration/components.cc | 40 ++++ test/integration/thermal_system.cc | 90 ++++++++- test/worlds/thermal.sdf | 189 ++++++++++++++---- 8 files changed, 552 insertions(+), 158 deletions(-) create mode 100644 include/ignition/gazebo/components/TemperatureRange.hh diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index c8498d3cc2..3e2230f099 100644 --- a/examples/worlds/thermal_camera.sdf +++ b/examples/worlds/thermal_camera.sdf @@ -1,6 +1,6 @@ @@ -121,7 +121,14 @@ - 310 + 300 + + 0.1 @@ -157,7 +164,7 @@ - 0 0 0.5 0 0 0 + -1 1 0.5 0 0 0 @@ -192,93 +199,7 @@ - 200.0 - - - - - - - 0 1.5 0.5 0 0 0 - - - - 3 - 0 - 0 - 3 - 0 - 3 - - 3.0 - - - - - 0.5 - - - - - - - - 0.5 - - - - 0 0 1 1 - 0 0 1 1 - 0 0 1 1 - - - 600.0 - - - - - - - 0 -1.5 0.5 0 0 0 - - - - 2 - 0 - 0 - 2 - 0 - 2 - - 2.0 - - - - - 0.5 - 1.0 - - - - - - - - 0.5 - 1.0 - - - - 0 1 0 1 - 0 1 0 1 - 0 1 0 1 - - - 400.0 + 285.0 @@ -323,5 +244,23 @@ true + + 1 0 0 0 0 1.570796 + rescue_randy + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy + + + + 2.25 .5 .1 0 0 1.570796 + phone + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Samsung J8 Black + + + + 2.25 -.5 .1 0 0 1.570796 + backpack + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + + diff --git a/include/ignition/gazebo/components/TemperatureRange.hh b/include/ignition/gazebo/components/TemperatureRange.hh new file mode 100644 index 0000000000..99e4a26151 --- /dev/null +++ b/include/ignition/gazebo/components/TemperatureRange.hh @@ -0,0 +1,99 @@ +/* + * 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_COMPONENTS_TEMPERATURERANGE_HH_ +#define IGNITION_GAZEBO_COMPONENTS_TEMPERATURERANGE_HH_ + +#include +#include + +#include + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief Data structure to hold a temperature range, in kelvin + struct TemperatureRangeInfo + { + /// \brief The minimum temperature (kelvin) + math::Temperature min; + /// \brief The maximum temperature (kelvin) + math::Temperature max; + + public: bool operator==(const TemperatureRangeInfo &_info) const + { + return (this->min == _info.min) && + (this->max == _info.max); + } + + public: bool operator!=(const TemperatureRangeInfo &_info) const + { + return !(*this == _info); + } + }; +} + +namespace serializers +{ + /// \brief Serializer for components::TemperatureRangeInfo object + class TemperatureRangeInfoSerializer + { + /// \brief Serialization for components::TemperatureRangeInfo + /// \param[out] _out Output stream + /// \param[in] _info Object for the stream + /// \return The stream + public: static std::ostream &Serialize(std::ostream &_out, + const components::TemperatureRangeInfo &_info) + { + _out << _info.min << " " << _info.max; + return _out; + } + + /// \brief Deserialization for components::TemperatureRangeInfo + /// \param[in] _in Input stream + /// \param[out] _info The object to populate + /// \return The stream + public: static std::istream &Deserialize(std::istream &_in, + components::TemperatureRangeInfo &_info) + { + _in >> _info.min >> _info.max; + return _in; + } + }; +} + +namespace components +{ + /// \brief A component that stores a temperature range in kelvin + using TemperatureRange = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.TemperatureRange", + TemperatureRange) +} +} +} +} + +#endif diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index acf90e1347..5243a7a31b 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -16,7 +16,10 @@ */ #include +#include +#include #include +#include #include #include @@ -58,7 +61,9 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/RgbdCamera.hh" #include "ignition/gazebo/components/Scene.hh" +#include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Temperature.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" #include "ignition/gazebo/components/ThermalCamera.hh" #include "ignition/gazebo/components/Transparency.hh" #include "ignition/gazebo/components/Visibility.hh" @@ -167,8 +172,19 @@ class ignition::gazebo::RenderUtilPrivate public: std::map> actorTransforms; - /// \brief A map of entity ids and temperature - public: std::map entityTemp; + /// \brief A map of entity ids and temperature data. + /// The value of this map (tuple) represents either a single (uniform) + /// temperature, or a heat signature with a min/max temperature. If the string + /// in the tuple is empty, then this entity has a uniform temperature across + /// its surface, and this uniform temperature is stored in the first float of + /// the tuple (the second float and string are unused for uniform temperature + /// entities). If the string in the tuple is not empty, then the string + /// represents the entity's heat signature (a path to a heat signature texture + /// file), and the floats represent the min/max temperatures of the heat + /// signature, respectively. + /// + /// All temperatures are in Kelvin. + public: std::map> entityTemp; /// \brief A map of entity ids and wire boxes public: std::unordered_map wireBoxes; @@ -596,7 +612,7 @@ void RenderUtil::Update() } // set visual temperature - for (auto &temp : entityTemp) + for (const auto &temp : entityTemp) { auto node = this->dataPtr->sceneManager.NodeById(temp.first); if (!node) @@ -607,7 +623,15 @@ void RenderUtil::Update() if (!visual) continue; - visual->SetUserData("temperature", temp.second); + const auto &heatSignature = std::get<2>(temp.second); + if (heatSignature.empty()) + visual->SetUserData("temperature", std::get<0>(temp.second)); + else + { + visual->SetUserData("minTemp", std::get<0>(temp.second)); + visual->SetUserData("maxTemp", std::get<1>(temp.second)); + visual->SetUserData("temperature", heatSignature); + } } } @@ -724,13 +748,29 @@ void RenderUtilPrivate::CreateRenderingEntities( visual.SetMaterial(material->Data()); } - // todo(anyone) make visual updates more generic without using extra - // variables like entityTemp just for storing one specific visual - // param? - auto temp = _ecm.Component(_entity); - if (temp) + if (auto temp = _ecm.Component(_entity)) + { + // get the uniform temperature for the entity + this->entityTemp[_entity] = + std::make_tuple( + temp->Data().Kelvin(), 0.0, ""); + } + else { - this->entityTemp[_entity] = temp->Data().Kelvin(); + // entity doesn't have a uniform temperature. Check if it has + // a heat signature with an associated temperature range + auto heatSignature = + _ecm.Component(_entity); + auto tempRange = + _ecm.Component(_entity); + if (heatSignature && tempRange) + { + this->entityTemp[_entity] = + std::make_tuple( + tempRange->Data().min.Kelvin(), + tempRange->Data().max.Kelvin(), + std::string(heatSignature->Data())); + } } this->newVisuals.push_back( diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index d973d94a60..20a929854d 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -78,6 +78,10 @@ class ignition::gazebo::systems::SensorsPrivate /// sea level public: double ambientTemperature = 288.15; + /// \brief Temperature gradient with respect to increasing altitude at sea + /// level in units of K/m. + public: double ambientTemperatureGradient = -0.0065; + /// \brief Keep track of cameras, in case we need to handle stereo cameras. /// Key: Camera's parent scoped name /// Value: Pointer to camera @@ -386,6 +390,8 @@ void Sensors::Configure(const Entity &/*_id*/, { auto atmosphereSdf = atmosphere->Data(); this->dataPtr->ambientTemperature = atmosphereSdf.Temperature().Kelvin(); + this->dataPtr->ambientTemperatureGradient = + atmosphereSdf.TemperatureGradient(); } // Set render engine if specified from command line @@ -564,6 +570,21 @@ std::string Sensors::CreateSensor(const Entity &_entity, if (nullptr != thermalSensor) { thermalSensor->SetAmbientTemperature(this->dataPtr->ambientTemperature); + + // temperature gradient is in kelvin per meter - typically change in + // temperature over change in altitude. However the implementation of + // thermal sensor in ign-sensors varies temperature for all objects in its + // view. So we will do an approximation based on camera view's vertical + // distance. + auto camSdf = _sdf.CameraSensor(); + double farClip = camSdf->FarClip(); + double angle = camSdf->HorizontalFov().Radian(); + double aspect = camSdf->ImageWidth() / camSdf->ImageHeight(); + double vfov = 2.0 * atan(tan(angle / 2.0) / aspect); + double height = tan(vfov / 2.0) * farClip * 2.0; + double tempRange = + std::fabs(this->dataPtr->ambientTemperatureGradient * height); + thermalSensor->SetAmbientTemperatureRange(tempRange); } return sensor->Name(); diff --git a/src/systems/thermal/Thermal.cc b/src/systems/thermal/Thermal.cc index 2a0f346797..28bd118931 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -15,16 +15,23 @@ * */ -#include +#include "Thermal.hh" + +#include +#include + +#include +#include #include -#include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/Atmosphere.hh" +#include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Temperature.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" +#include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/Util.hh" -#include "Thermal.hh" - using namespace ignition; using namespace gazebo; using namespace systems; @@ -48,14 +55,79 @@ void Thermal::Configure(const Entity &_entity, gazebo::EntityComponentManager &_ecm, gazebo::EventManager & /*_eventMgr*/) { - if (!_sdf->HasElement("temperature")) + const std::string temperatureTag = "temperature"; + const std::string heatSignatureTag = "heat_signature"; + const std::string minTempTag = "min_temp"; + const std::string maxTempTag = "max_temp"; + + if (_sdf->HasElement(temperatureTag) && _sdf->HasElement(heatSignatureTag)) + { + ignwarn << "Both <" << temperatureTag << "> and <" << heatSignatureTag + << "> were specified, but the thermal system only uses one. " + << "<" << heatSignatureTag << "> will be used.\n"; + } + + if (_sdf->HasElement(heatSignatureTag)) + { + std::string heatSignature = _sdf->Get(heatSignatureTag); + auto modelEntity = topLevelModel(_entity, _ecm); + auto modelPath = + _ecm.ComponentData(modelEntity); + auto path = common::findFile(asFullPath(heatSignature, modelPath.value())); + + // make sure the specified heat signature can be found + if (path.empty()) + { + ignerr << "Failed to load thermal system. Heat signature [" + << heatSignature << "] could not be found\n"; + return; + } + _ecm.CreateComponent(_entity, components::SourceFilePath(path)); + + // see if the user defined a custom temperature range + // (default to ambient temperature if possible) + double min = 250.0; + double max = 300.0; + if (auto worldEntity = _ecm.EntityByComponents(components::World())) + { + if (auto atmosphere = + _ecm.Component(worldEntity)) + { + auto atmosphericTemp = atmosphere->Data().Temperature().Kelvin(); + min = atmosphericTemp; + max = atmosphericTemp; + } + } + if (_sdf->HasElement(minTempTag)) + min = _sdf->Get(minTempTag); + if (_sdf->HasElement(maxTempTag)) + max = _sdf->Get(maxTempTag); + // make sure that min is actually less than max + if (min > max) + { + auto temporary = max; + max = min; + min = temporary; + } + igndbg << "Thermal plugin, heat signature: using a minimum temperature of " + << min << " kelvin, and a max temperature of " << max << " kelvin.\n"; + + components::TemperatureRangeInfo rangeInfo; + rangeInfo.min = min; + rangeInfo.max = max; + _ecm.CreateComponent(_entity, components::TemperatureRange(rangeInfo)); + } + else if (_sdf->HasElement(temperatureTag)) + { + double temperature = _sdf->Get(temperatureTag); + _ecm.CreateComponent(_entity, components::Temperature(temperature)); + } + else { - ignerr << "Fail to load thermal system: is not specified" - << std::endl; - return; + ignerr << "Failed to load thermal system. " + << "Neither <" << temperatureTag << "> or <" << heatSignatureTag + << "> were specified.\n"; } - double temperature = _sdf->Get("temperature"); - _ecm.CreateComponent(_entity, components::Temperature(temperature)); } diff --git a/test/integration/components.cc b/test/integration/components.cc index 57bc96a2ba..fed087ef78 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -71,6 +71,7 @@ #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Static.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" #include "ignition/gazebo/components/ThreadPitch.hh" #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/components/World.hh" @@ -1376,6 +1377,45 @@ TEST_F(ComponentsTest, Static) EXPECT_FALSE(comp11 != comp12); } +///////////////////////////////////////////////// +TEST_F(ComponentsTest, TemperatureRange) +{ + // TODO(adlarkin) make sure min can't be >= max? + components::TemperatureRangeInfo range1; + range1.min = math::Temperature(125.0); + range1.max = math::Temperature(300.0); + + components::TemperatureRangeInfo range2; + range2.min = math::Temperature(140.0); + range2.max = math::Temperature(200.0); + + components::TemperatureRangeInfo range3; + range3.min = math::Temperature(125.0); + range3.max = math::Temperature(300.0); + + // Create components + auto comp1 = components::TemperatureRange(range1); + auto comp2 = components::TemperatureRange(range2); + auto comp3 = components::TemperatureRange(range3); + + // Equality operators + EXPECT_EQ(comp1, comp3); + EXPECT_NE(comp1, comp2); + EXPECT_NE(comp2, comp3); + EXPECT_FALSE(comp1 == comp2); + EXPECT_TRUE(comp1 != comp2); + + // Stream operators + std::ostringstream ostr; + comp1.Serialize(ostr); + EXPECT_EQ("125 300", ostr.str()); + + std::istringstream istr(ostr.str()); + components::TemperatureRange comp4; + comp4.Deserialize(istr); + EXPECT_EQ(comp1, comp4); +} + ///////////////////////////////////////////////// TEST_F(ComponentsTest, ThreadPitch) { diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index 4fffa35ee5..211f06b28d 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -21,7 +21,9 @@ #include #include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Temperature.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -29,8 +31,6 @@ #include "../helpers/Relay.hh" -#define tol 10e-4 - using namespace ignition; using namespace gazebo; @@ -62,6 +62,9 @@ TEST_F(ThermalTest, TemperatureComponent) test::Relay testSystem; std::map entityTemp; + std::map + entityTempRange; + std::map heatSignatures; testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) { @@ -76,20 +79,93 @@ TEST_F(ThermalTest, TemperatureComponent) // verify temperature data belongs to a visual EXPECT_NE(nullptr, _ecm.Component(_id)); + return true; + }); + + _ecm.Each( + [&](const ignition::gazebo::Entity &_id, + const components::TemperatureRange *_tempRange, + const components::SourceFilePath *_heatSigURI, + const components::Name *_name) -> bool + { + // store temperature range data + entityTempRange[_name->Data()] = _tempRange->Data(); + + // store heat signature URI data + heatSignatures[_name->Data()] = _heatSigURI->Data(); + + // verify temperature range data belongs to a visual + EXPECT_NE(nullptr, _ecm.Component(_id)); + return true; }); }); server.AddSystem(testSystem.systemPtr); - // verify nothing in map at beginning + // verify nothing in the maps at beginning EXPECT_TRUE(entityTemp.empty()); + EXPECT_TRUE(entityTempRange.empty()); + EXPECT_TRUE(heatSignatures.empty()); // Run server server.Run(true, 1, false); + const std::string sphereVisual = "sphere_visual"; + const std::string cylinderVisual = "cylinder_visual"; + const std::string visual = "visual"; + const std::string heatSignatureCylinderVisual = + "heat_signature_cylinder_visual"; + const std::string heatSignatureSphereVisual = + "heat_signature_sphere_visual"; + const std::string heatSignatureSphereVisual2 = + "heat_signature_sphere_visual_2"; + const std::string heatSignatureTestResource = "duck.png"; + // verify temperature components are created and the values are correct - EXPECT_EQ(3u, entityTemp.size()); - EXPECT_DOUBLE_EQ(200.0, entityTemp["box_visual"].Kelvin()); - EXPECT_DOUBLE_EQ(600.0, entityTemp["sphere_visual"].Kelvin()); - EXPECT_DOUBLE_EQ(400.0, entityTemp["cylinder_visual"].Kelvin()); + EXPECT_EQ(2u, entityTemp.size()); + ASSERT_TRUE(entityTemp.find(sphereVisual) != entityTemp.end()); + ASSERT_TRUE(entityTemp.find(cylinderVisual) != entityTemp.end()); + EXPECT_DOUBLE_EQ(600.0, entityTemp[sphereVisual].Kelvin()); + EXPECT_DOUBLE_EQ(400.0, entityTemp[cylinderVisual].Kelvin()); + + EXPECT_EQ(4u, entityTempRange.size()); + ASSERT_TRUE(entityTempRange.find(visual) != entityTempRange.end()); + ASSERT_TRUE(entityTempRange.find( + heatSignatureCylinderVisual) != entityTempRange.end()); + ASSERT_TRUE(entityTempRange.find( + heatSignatureSphereVisual) != entityTempRange.end()); + ASSERT_TRUE(entityTempRange.find( + heatSignatureSphereVisual2) != entityTempRange.end()); + EXPECT_DOUBLE_EQ(310.0, entityTempRange[visual].min.Kelvin()); + EXPECT_DOUBLE_EQ(310.0, entityTempRange[visual].max.Kelvin()); + EXPECT_DOUBLE_EQ(310.0, + entityTempRange[heatSignatureCylinderVisual].min.Kelvin()); + EXPECT_DOUBLE_EQ(310.0, + entityTempRange[heatSignatureCylinderVisual].max.Kelvin()); + EXPECT_DOUBLE_EQ(310.0, + entityTempRange[heatSignatureSphereVisual].min.Kelvin()); + EXPECT_DOUBLE_EQ(500.0, + entityTempRange[heatSignatureSphereVisual].max.Kelvin()); + EXPECT_DOUBLE_EQ(310.0, + entityTempRange[heatSignatureSphereVisual2].min.Kelvin()); + EXPECT_DOUBLE_EQ(400.0, + entityTempRange[heatSignatureSphereVisual2].max.Kelvin()); + + EXPECT_EQ(4u, heatSignatures.size()); + ASSERT_TRUE(heatSignatures.find(visual) != heatSignatures.end()); + ASSERT_TRUE(heatSignatures.find( + heatSignatureCylinderVisual) != heatSignatures.end()); + ASSERT_TRUE(heatSignatures.find( + heatSignatureSphereVisual) != heatSignatures.end()); + ASSERT_TRUE(heatSignatures.find( + heatSignatureSphereVisual2) != heatSignatures.end()); + EXPECT_TRUE(heatSignatures[visual].find( + "RescueRandy_Thermal.png") != std::string::npos); + EXPECT_TRUE(heatSignatures[heatSignatureCylinderVisual].find( + heatSignatureTestResource) != std::string::npos); + EXPECT_TRUE(heatSignatures[heatSignatureSphereVisual].find( + heatSignatureTestResource) != std::string::npos); + EXPECT_TRUE(heatSignatures[heatSignatureSphereVisual2].find( + heatSignatureTestResource) != std::string::npos); } diff --git a/test/worlds/thermal.sdf b/test/worlds/thermal.sdf index 223b04ba51..16a8436c0d 100644 --- a/test/worlds/thermal.sdf +++ b/test/worlds/thermal.sdf @@ -74,93 +74,100 @@ - - 0 0 0.5 0 0 0 - + + 0 1.5 0.5 0 0 0 + - 1 + 3 0 0 - 1 + 3 0 - 1 + 3 - 1.0 + 3.0 - + - - 1 1 1 - + + 0.5 + - + - - 1 1 1 - + + 0.5 + - 1 0 0 1 - 1 0 0 1 - 1 0 0 1 + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 - 200.0 + 600.0 - - 0 1.5 0.5 0 0 0 - + + 0 -1.5 0.5 0 0 0 + - 3 + 2 0 0 - 3 + 2 0 - 3 + 2 - 3.0 + 2.0 - + - + 0.5 - + 1.0 + - + - + 0.5 - + 1.0 + - 0 0 1 1 - 0 0 1 1 - 0 0 1 1 + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 - 600.0 + 400.0 - - 0 -1.5 0.5 0 0 0 - + + + -2 -1.5 0.5 0 0 0 + 2 @@ -172,7 +179,7 @@ 2.0 - + 0.5 @@ -181,7 +188,7 @@ - + 0.5 @@ -196,10 +203,110 @@ + ../media/duck.png 400.0 + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + ../media/duck.png + 500.0 + + + + + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + ../media/duck.png + 400.0 + + + + + + + + 0 0 0 0 0 1.570796 + rescue_randy + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy + + From 9bc088de6289fbeb78e19ead6a29ee38af6c0a1f Mon Sep 17 00:00:00 2001 From: Luca Della Vedova Date: Wed, 3 Feb 2021 02:39:05 +0800 Subject: [PATCH 22/55] Add service and GUI to configure physics parameters (step size and real time factor) (#536) Signed-off-by: Maganty Rushyendra Signed-off-by: Luca Della Vedova Co-authored-by: mrushyendra Co-authored-by: Louise Poubel --- include/ignition/gazebo/Conversions.hh | 39 ++- include/ignition/gazebo/components/Physics.hh | 56 ++++ .../ignition/gazebo/components/PhysicsCmd.hh | 46 +++ src/Conversions.cc | 20 ++ src/Conversions_TEST.cc | 23 ++ src/LevelManager.cc | 9 + src/SdfEntityCreator.cc | 11 + src/SdfEntityCreator_TEST.cc | 10 +- src/SimulationRunner.cc | 55 +++- src/SimulationRunner.hh | 7 + src/SimulationRunner_TEST.cc | 4 + .../component_inspector/ComponentInspector.cc | 43 +++ .../component_inspector/ComponentInspector.hh | 14 + .../ComponentInspector.qml | 7 + .../ComponentInspector.qrc | 1 + .../plugins/component_inspector/Physics.qml | 263 ++++++++++++++++++ src/gui/plugins/plotting/Plotting.cc | 21 ++ src/gui/plugins/plotting/Plotting.hh | 8 + src/systems/user_commands/UserCommands.cc | 82 ++++++ test/integration/user_commands.cc | 64 +++++ 20 files changed, 776 insertions(+), 7 deletions(-) create mode 100644 include/ignition/gazebo/components/Physics.hh create mode 100644 include/ignition/gazebo/components/PhysicsCmd.hh create mode 100644 src/gui/plugins/component_inspector/Physics.qml diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index f02c9b4fff..a8740a291e 100644 --- a/include/ignition/gazebo/Conversions.hh +++ b/include/ignition/gazebo/Conversions.hh @@ -26,6 +26,7 @@ #include #include #include +#include #include #include #include @@ -46,6 +47,7 @@ #include #include #include +#include #include #include @@ -417,6 +419,41 @@ namespace ignition sdf::Atmosphere convert(const msgs::Atmosphere &_in); + /// \brief Generic conversion from an SDF Physics to another type. + /// \param[in] _in SDF Physics. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const sdf::Physics &/*_in*/) + { + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from an SDF physics to a physics + /// message. + /// \param[in] _in SDF physics. + /// \return Physics message. + template<> + msgs::Physics convert(const sdf::Physics &_in); + + /// \brief Generic conversion from a physics message to another type. + /// \param[in] _in Physics message. + /// \return Conversion result. + /// \tparam Out Output type. + template + Out convert(const msgs::Physics &/*_in*/) + { + Out::ConversionNotImplemented; + } + + /// \brief Specialized conversion from a physics message to a physics + /// SDF object. + /// \param[in] _in Physics message. + /// \return SDF physics. + template<> + sdf::Physics convert(const msgs::Physics &_in); + + /// \brief Generic conversion from an SDF Sensor to another type. /// \param[in] _in SDF Sensor. /// \return Conversion result. @@ -429,7 +466,7 @@ namespace ignition /// \brief Specialized conversion from an SDF sensor to a sensor /// message. - /// \param[in] _in SDF geometry. + /// \param[in] _in SDF sensor. /// \return Sensor message. template<> msgs::Sensor convert(const sdf::Sensor &_in); diff --git a/include/ignition/gazebo/components/Physics.hh b/include/ignition/gazebo/components/Physics.hh new file mode 100644 index 0000000000..804059dedc --- /dev/null +++ b/include/ignition/gazebo/components/Physics.hh @@ -0,0 +1,56 @@ +/* + * 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_COMPONENTS_PHYSICS_HH_ +#define IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ + +#include + +#include + +#include +#include + +#include +#include "ignition/gazebo/components/Component.hh" +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using PhysicsSerializer = + serializers::ComponentToMsgSerializer; +} +namespace components +{ + /// \brief A component type that contains the physics properties of + /// the World entity. + using Physics = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics", + Physics) +} +} +} +} + +#endif diff --git a/include/ignition/gazebo/components/PhysicsCmd.hh b/include/ignition/gazebo/components/PhysicsCmd.hh new file mode 100644 index 0000000000..f72dc328b0 --- /dev/null +++ b/include/ignition/gazebo/components/PhysicsCmd.hh @@ -0,0 +1,46 @@ +/* + * 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_COMPONENTS_PHYSICSCMD_HH_ +#define IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_ + +#include + +#include +#include + +#include +#include "ignition/gazebo/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains the physics properties of + /// the World entity. + using PhysicsCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsCmd", + PhysicsCmd) +} +} +} +} + +#endif diff --git a/src/Conversions.cc b/src/Conversions.cc index edbc024d77..4f4d102191 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -721,6 +721,26 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg, _msg->set_paused(_in.paused); } +////////////////////////////////////////////////// +template<> +msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) +{ + msgs::Physics out; + out.set_max_step_size(_in.MaxStepSize()); + out.set_real_time_factor(_in.RealTimeFactor()); + return out; +} + +////////////////////////////////////////////////// +template<> +sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) +{ + sdf::Physics out; + out.SetRealTimeFactor(_in.real_time_factor()); + out.SetMaxStepSize(_in.max_step_size()); + return out; +} + ////////////////////////////////////////////////// void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) { diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index fe155e00a5..76fad52775 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -157,6 +158,28 @@ TEST(Conversions, Entity) EXPECT_EQ(msgs::Entity_Type_NONE, entityType2); } +///////////////////////////////////////////////// +TEST(Conversions, Physics) +{ + // Test conversion from msg to sdf + msgs::Physics msg; + msg.set_real_time_factor(1.23); + msg.set_max_step_size(0.12); + + auto physics = convert(msg); + EXPECT_DOUBLE_EQ(1.23, physics.RealTimeFactor()); + EXPECT_DOUBLE_EQ(0.12, physics.MaxStepSize()); + + // Test conversion from sdf to msg + sdf::Physics physSdf; + physSdf.SetMaxStepSize(0.34); + physSdf.SetRealTimeFactor(2.34); + + auto physMsg = convert(physSdf); + EXPECT_DOUBLE_EQ(2.34, physMsg.real_time_factor()); + EXPECT_DOUBLE_EQ(0.34, physMsg.max_step_size()); +} + ///////////////////////////////////////////////// TEST(Conversions, Pose) { diff --git a/src/LevelManager.cc b/src/LevelManager.cc index 1b54f01848..74e2f71020 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -46,6 +46,7 @@ #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/components/Performer.hh" #include "ignition/gazebo/components/PerformerLevels.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/PhysicsEnginePlugin.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/RenderEngineGuiPlugin.hh" @@ -102,6 +103,14 @@ void LevelManager::ReadLevelPerformerInfo() this->runner->entityCompMgr.CreateComponent(this->worldEntity, components::Gravity(this->runner->sdfWorld->Gravity())); + auto physics = this->runner->sdfWorld->PhysicsByIndex(0); + if (!physics) + { + physics = this->runner->sdfWorld->PhysicsDefault(); + } + this->runner->entityCompMgr.CreateComponent(this->worldEntity, + components::Physics(*physics)); + this->runner->entityCompMgr.CreateComponent(this->worldEntity, components::MagneticField(this->runner->sdfWorld->MagneticField())); diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 414e871cd8..cc9c2c0794 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -54,6 +54,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentLinkName.hh" #include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/RgbdCamera.hh" #include "ignition/gazebo/components/Scene.hh" @@ -202,6 +203,16 @@ Entity SdfEntityCreator::CreateEntities(const sdf::World *_world) this->dataPtr->ecm->CreateComponent(worldEntity, components::Gravity(_world->Gravity())); + // Physics + // \todo(anyone) Support picking a specific physics profile + auto physics = _world->PhysicsByIndex(0); + if (!physics) + { + physics = _world->PhysicsDefault(); + } + this->dataPtr->ecm->CreateComponent(worldEntity, + components::Physics(*physics)); + // MagneticField this->dataPtr->ecm->CreateComponent(worldEntity, components::MagneticField(_world->MagneticField())); diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index b46eb95322..71c392c5e0 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -42,6 +42,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/components/ParentLinkName.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/Transparency.hh" #include "ignition/gazebo/components/Visibility.hh" @@ -111,15 +112,20 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) unsigned int worldCount{0}; Entity worldEntity = kNullEntity; this->ecm.Each( + components::Name, + components::Physics>( [&](const Entity &_entity, const components::World *_world, - const components::Name *_name)->bool + const components::Name *_name, + const components::Physics *_physics)->bool { EXPECT_NE(nullptr, _world); EXPECT_NE(nullptr, _name); + EXPECT_NE(nullptr, _physics); EXPECT_EQ("default", _name->Data()); + EXPECT_DOUBLE_EQ(0.001, _physics->Data().MaxStepSize()); + EXPECT_DOUBLE_EQ(1.0, _physics->Data().RealTimeFactor()); worldCount++; diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index bdd21a1cb8..e3d0bc8a4b 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -27,6 +27,8 @@ #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/components/World.hh" +#include "ignition/gazebo/components/Physics.hh" +#include "ignition/gazebo/components/PhysicsCmd.hh" #include "ignition/gazebo/Events.hh" #include "ignition/gazebo/SdfEntityCreator.hh" #include "ignition/gazebo/Util.hh" @@ -60,8 +62,8 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, // Keep system loader so plugins can be loaded at runtime this->systemLoader = _systemLoader; - // Get the first physics profile - // \todo(louise) Support picking a specific profile + // Get the physics profile + // TODO(luca): remove duplicated logic in SdfEntityCreator and LevelManager auto physics = _world->PhysicsByIndex(0); if (!physics) { @@ -76,7 +78,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, dur); // Desired real time factor - double desiredRtf = _world->PhysicsDefault()->RealTimeFactor(); + this->desiredRtf = physics->RealTimeFactor(); // The instantaneous real time factor is given as: // @@ -102,7 +104,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, // // period = step_size / RTF this->updatePeriod = std::chrono::nanoseconds( - static_cast(this->stepSize.count() / desiredRtf)); + static_cast(this->stepSize.count() / this->desiredRtf)); this->pauseConn = this->eventMgr.Connect( std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1)); @@ -330,6 +332,47 @@ void SimulationRunner::UpdateCurrentInfo() } } +///////////////////////////////////////////////// +void SimulationRunner::UpdatePhysicsParams() +{ + auto worldEntity = + this->entityCompMgr.EntityByComponents(components::World()); + const auto physicsCmdComp = + this->entityCompMgr.Component(worldEntity); + if (!physicsCmdComp) + { + return; + } + auto physicsComp = + this->entityCompMgr.Component(worldEntity); + + const auto& physicsParams = physicsCmdComp->Data(); + const auto newStepSize = + std::chrono::duration(physicsParams.max_step_size()); + const double newRTF = physicsParams.real_time_factor(); + + const double eps = 0.00001; + if (newStepSize != this->stepSize || + std::abs(newRTF - this->desiredRtf) > eps) + { + this->SetStepSize( + std::chrono::duration_cast( + newStepSize)); + this->desiredRtf = newRTF; + this->updatePeriod = std::chrono::nanoseconds( + static_cast(this->stepSize.count() / this->desiredRtf)); + + this->simTimes.clear(); + this->realTimes.clear(); + // Update physics components + physicsComp->Data().SetMaxStepSize(physicsParams.max_step_size()); + physicsComp->Data().SetRealTimeFactor(newRTF); + this->entityCompMgr.SetChanged(worldEntity, components::Physics::typeId, + ComponentState::OneTimeChange); + } + this->entityCompMgr.RemoveComponent(worldEntity); +} + ///////////////////////////////////////////////// void SimulationRunner::PublishStats() { @@ -647,6 +690,10 @@ bool SimulationRunner::Run(const uint64_t _iterations) processedIterations < _iterations)) { IGN_PROFILE("SimulationRunner::Run - Iteration"); + + // Update the step size and desired rtf + this->UpdatePhysicsParams(); + // Compute the time to sleep in order to match, as closely as possible, // the update period. sleepTime = 0ns; diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh index faf8e3518b..e9d0316f63 100644 --- a/src/SimulationRunner.hh +++ b/src/SimulationRunner.hh @@ -372,6 +372,10 @@ namespace ignition /// \brief Set the next step to be blocking and paused. public: void SetNextStepAsBlockingPaused(const bool value); + /// \brief Updates the physics parameters of the simulation based on the + /// Physics component of the world, if any. + public: void UpdatePhysicsParams(); + /// \brief This is used to indicate that a stop event has been received. private: std::atomic stopReceived{false}; @@ -462,6 +466,9 @@ namespace ignition /// \brief Step size private: ignition::math::clock::duration stepSize{10ms}; + /// \brief Desired real time factor + private: double desiredRtf{1.0}; + /// \brief Connection to the pause event. private: ignition::common::ConnectionPtr pauseConn; diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 64b75f6c1f..21f84aafc2 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -176,6 +176,10 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(1u, worldCount); EXPECT_NE(kNullEntity, worldEntity); + // Test step size, real time factor is not testable since it has no public API + auto stepSize = std::chrono::duration(runner.StepSize()).count(); + EXPECT_DOUBLE_EQ(0.001, stepSize); + // Check models unsigned int modelCount{0}; Entity boxModelEntity = kNullEntity; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index de0cf8afee..1c2de965b9 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -46,6 +46,7 @@ #include "ignition/gazebo/components/ParentLinkName.hh" #include "ignition/gazebo/components/Performer.hh" #include "ignition/gazebo/components/PerformerAffinity.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" #include "ignition/gazebo/components/SelfCollide.hh" @@ -174,6 +175,18 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) _item->setData(_data, ComponentsModel::RoleNames().key("data")); } +////////////////////////////////////////////////// +template<> +void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +{ + _item->setData(QString("Physics"), + ComponentsModel::RoleNames().key("dataType")); + _item->setData(QList({ + QVariant(_data.MaxStepSize()), + QVariant(_data.RealTimeFactor()) + }), ComponentsModel::RoleNames().key("data")); +} + ////////////////////////////////////////////////// void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) { @@ -521,6 +534,12 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::Physics::typeId) + { + auto comp = _ecm.Component(this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); @@ -728,6 +747,30 @@ void ComponentInspector::OnPose(double _x, double _y, double _z, double _roll, this->dataPtr->node.Request(poseCmdService, req, cb); } +///////////////////////////////////////////////// +void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) +{ + std::function cb = + [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + { + if (!_result) + ignerr << "Error setting physics parameters" << std::endl; + }; + + ignition::msgs::Physics req; + req.set_max_step_size(_stepSize); + req.set_real_time_factor(_realTimeFactor); + auto physicsCmdService = "/world/" + this->dataPtr->worldName + + "/set_physics"; + physicsCmdService = transport::TopicUtils::AsValidTopic(physicsCmdService); + if (physicsCmdService.empty()) + { + ignerr << "Invalid physics command service topic provided" << std::endl; + return; + } + this->dataPtr->node.Request(physicsCmdService, req, cb); +} + ///////////////////////////////////////////////// bool ComponentInspector::NestedModel() const { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 470c7b508f..8df6eb585b 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -28,6 +28,8 @@ #include #include +#include "ignition/gazebo/components/Physics.hh" + Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) namespace ignition @@ -75,6 +77,12 @@ namespace gazebo template<> void setData(QStandardItem *_item, const math::Vector3d &_data); + /// \brief Specialized to set Physics data. + /// \param[in] _item Item whose data will be set. + /// \param[in] _data Data to set. + template<> + void setData(QStandardItem *_item, const sdf::Physics &_data); + /// \brief Specialized to set boolean data. /// \param[in] _item Item whose data will be set. /// \param[in] _data Data to set. @@ -207,6 +215,12 @@ namespace gazebo public: Q_INVOKABLE void OnPose(double _x, double _y, double _z, double _roll, double _pitch, double _yaw); + /// \brief Callback in Qt thread when physics' properties change. + /// \param[in] _stepSize step size + /// \param[in] _realTimeFactor real time factor + public: Q_INVOKABLE void OnPhysics(double _stepSize, + double _realTimeFactor); + /// \brief Get whether the entity is a nested model or not /// \return True if the entity is a nested model, false otherwise public: Q_INVOKABLE bool NestedModel() const; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index aa058cae4f..e48bc4b393 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -85,6 +85,13 @@ Rectangle { ComponentInspector.OnPose(_x, _y, _z, _roll, _pitch, _yaw) } + /** + * Forward physics changes to C++ + */ + function onPhysics(_stepSize, _realTimeFactor) { + ComponentInspector.OnPhysics(_stepSize, _realTimeFactor) + } + Rectangle { id: header height: lockButton.height diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qrc b/src/gui/plugins/component_inspector/ComponentInspector.qrc index 43efec19d1..f50f8e7616 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qrc +++ b/src/gui/plugins/component_inspector/ComponentInspector.qrc @@ -3,6 +3,7 @@ Boolean.qml ComponentInspector.qml NoData.qml + Physics.qml Pose3d.qml String.qml TypeHeader.qml diff --git a/src/gui/plugins/component_inspector/Physics.qml b/src/gui/plugins/component_inspector/Physics.qml new file mode 100644 index 0000000000..71f0a34fda --- /dev/null +++ b/src/gui/plugins/component_inspector/Physics.qml @@ -0,0 +1,263 @@ +/* + * 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 1.4 +import QtQuick.Controls 2.2 +import QtQuick.Controls.Material 2.1 +import QtQuick.Dialogs 1.0 +import QtQuick.Layouts 1.3 +import QtQuick.Controls.Styles 1.4 +import "qrc:/ComponentInspector" +import "qrc:/qml" + +// Item displaying physics information. +Rectangle { + height: header.height + content.height + width: componentInspector.width + color: index % 2 == 0 ? lightGrey : darkGrey + + // Left indentation + property int indentation: 10 + + // Minimum parameter value, step size and RTF must be strictly positive + property double minPhysParam: 0.000001 + + // Maximum parameter value + property double maxPhysParam: 100000 + + // Horizontal margins + property int margin: 5 + + property int iconWidth: 20 + property int iconHeight: 20 + + // Loaded item for physics step size + property var stepSizeItem: {} + + // Loaded item for real time factor + property var realTimeFactorItem: {} + + // Send new physics data to C++ + function sendPhysics() { + // TODO(anyone) There's a loss of precision when these values get to C++ + componentInspector.onPhysics( + stepSizeItem.value, + realTimeFactorItem.value + ); + } + + FontMetrics { + id: fontMetrics + font.family: "Roboto" + } + + /** + * Used to create a spin box + */ + + Component { + id: writablePositiveNumber + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: minPhysParam + maximumValue: maxPhysParam + decimals: 6 + stepSize: 0.001 + onEditingFinished: { + sendPhysics() + } + } + } + + Component { + id: plotIcon + Image { + property string componentInfo: "" + source: "plottable_icon.svg" + anchors.top: parent.top + anchors.left: parent.left + + Drag.mimeData: { "text/plain" : (model === null) ? "" : + "Component," + model.entity + "," + model.typeId + "," + + model.dataType + "," + componentInfo + "," + model.shortName + } + Drag.dragType: Drag.Automatic + Drag.supportedActions : Qt.CopyAction + Drag.active: dragMouse.drag.active + // a point to drag from + Drag.hotSpot.x: 0 + Drag.hotSpot.y: y + MouseArea { + id: dragMouse + anchors.fill: parent + drag.target: (model === null) ? null : parent + onPressed: parent.grabToImage(function(result) {parent.Drag.imageSource = result.url }) + onReleased: parent.Drag.drop(); + cursorShape: Qt.DragCopyCursor + } + } + } + + Column { + anchors.fill: parent + + // Header + Rectangle { + id: header + width: parent.width + height: typeHeader.height + color: "transparent" + + RowLayout { + anchors.fill: parent + Item { + width: margin + } + Image { + id: icon + sourceSize.height: indentation + sourceSize.width: indentation + fillMode: Image.Pad + Layout.alignment : Qt.AlignVCenter + source: content.show ? + "qrc:/Gazebo/images/minus.png" : "qrc:/Gazebo/images/plus.png" + } + TypeHeader { + id: typeHeader + } + Item { + Layout.fillWidth: true + } + } + MouseArea { + anchors.fill: parent + hoverEnabled: true + cursorShape: Qt.PointingHandCursor + onClicked: { + content.show = !content.show + } + onEntered: { + header.color = highlightColor + } + onExited: { + header.color = "transparent" + } + } + } + + // Content + Rectangle { + id: content + property bool show: false + width: parent.width + height: show ? grid.height : 0 + clip: true + color: "transparent" + + Behavior on height { + NumberAnimation { + duration: 200; + easing.type: Easing.InOutQuad + } + } + + GridLayout { + id: grid + width: parent.width + columns: 3 + + // Left spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: stepSizeText.width + indentation*3 + Loader { + id: loaderStepSize + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderStepSize.item.componentInfo = "stepSize" + + Text { + id : stepSizeText + text: ' Step Size (s)' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: stepSizeLoader + anchors.fill: parent + property double numberValue: model.data[0] + sourceComponent: writablePositiveNumber + onLoaded: { + stepSizeItem = stepSizeLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: realTimeFactorText.width + indentation*3 + Loader { + id: loaderRealTimeFactor + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderRealTimeFactor.item.componentInfo = "realTimeFactor" + + Text { + id : realTimeFactorText + text: ' Real time factor' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: realTimeFactorLoader + anchors.fill: parent + property double numberValue: model.data[1] + sourceComponent: writablePositiveNumber + onLoaded: { + realTimeFactorItem = realTimeFactorLoader.item + } + } + } + } + } + } +} diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index ef20533382..876e3e613a 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -28,6 +28,7 @@ #include "ignition/gazebo/components/LinearVelocitySeed.hh" #include "ignition/gazebo/components/MagneticField.hh" #include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" #include "ignition/gazebo/components/Static.hh" @@ -96,6 +97,11 @@ PlotComponent::PlotComponent(const std::string &_type, } else if (_type == "double") this->dataPtr->data["value"] = std::make_shared(); + else if (_type == "Physics") + { + this->dataPtr->data["stepSize"] = std::make_shared(); + this->dataPtr->data["realTimeFactor"] = std::make_shared(); + } else ignwarn << "Invalid Plot Component Type:" << _type << std::endl; } @@ -215,6 +221,15 @@ void Plotting::SetData(std::string _Id, const ignition::math::Pose3d &_pose) this->dataPtr->components[_Id]->SetAttributeValue("yaw", _pose.Rot().Yaw()); } +////////////////////////////////////////////////// +void Plotting::SetData(std::string _Id, const sdf::Physics &_physics) +{ + this->dataPtr->components[_Id]->SetAttributeValue("stepSize", + _physics.MaxStepSize()); + this->dataPtr->components[_Id]->SetAttributeValue("realTimeFactor", + _physics.RealTimeFactor()); +} + ////////////////////////////////////////////////// void Plotting::SetData(std::string _Id, const double &_value) { @@ -325,6 +340,12 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, if (comp) this->SetData(component.first, comp->Data()); } + else if (typeId == components::Physics::typeId) + { + auto comp = _ecm.Component(entity); + if (comp) + this->SetData(component.first, comp->Data()); + } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(entity); diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index bf9c54c69b..24601bdc6b 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -24,6 +24,8 @@ #include #include +#include "sdf/Physics.hh" + #include #include #include @@ -119,6 +121,12 @@ class Plotting : public ignition::gazebo::GuiSystem public: void SetData(std::string _Id, const ignition::math::Pose3d &_pose); + /// \brief Set the Component data of giving id to the giving + /// physics properties + /// \param [in] _Id Component Key of the components map + /// \param [in] _value physics Data to be set to the component + public: void SetData(std::string _Id, const sdf::Physics &_physics); + /// \brief Set the Component data of giving id to the giving number /// \param [in] _Id Component Key of the components map /// \param [in] _value double Data to be set to the component diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index d334c246a2..8ff22c10c8 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -28,6 +29,7 @@ #include +#include #include #include @@ -42,7 +44,9 @@ #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" +#include "ignition/gazebo/components/PhysicsCmd.hh" #include "ignition/gazebo/components/World.hh" +#include "ignition/gazebo/Conversions.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/SdfEntityCreator.hh" @@ -146,6 +150,19 @@ class PoseCommand : public UserCommandBase math::equal(_a.Rot().W(), _b.Rot().W(), 1e-6); }}; }; + +/// \brief Command to modify the physics parameters of a simulation. +class PhysicsCommand : public UserCommandBase +{ + /// \brief Constructor + /// \param[in] _msg Message containing the new physics parameters. + /// \param[in] _iface Pointer to user commands interface. + public: PhysicsCommand(msgs::Physics *_msg, + std::shared_ptr &_iface); + + // Documentation inherited + public: bool Execute() final; +}; } } } @@ -185,6 +202,13 @@ class ignition::gazebo::systems::UserCommandsPrivate /// \return True if successful. public: bool PoseService(const msgs::Pose &_req, msgs::Boolean &_res); + /// \brief Callback for physics service + /// \param[in] _req Request containing updates to the physics parameters. + /// \param[in] _res True if message successfully received and queued. + /// It does not mean that the physics parameters will be successfully updated. + /// \return True if successful. + public: bool PhysicsService(const msgs::Physics &_req, msgs::Boolean &_res); + /// \brief Queue of commands pending execution. public: std::vector> pendingCmds; @@ -258,6 +282,13 @@ void UserCommands::Configure(const Entity &_entity, &UserCommandsPrivate::PoseService, this->dataPtr.get()); ignmsg << "Pose service on [" << poseService << "]" << std::endl; + + // Physics service + std::string physicsService{"/world/" + validWorldName + "/set_physics"}; + this->dataPtr->node.Advertise(physicsService, + &UserCommandsPrivate::PhysicsService, this->dataPtr.get()); + + ignmsg << "Physics service on [" << physicsService << "]" << std::endl; } ////////////////////////////////////////////////// @@ -369,6 +400,24 @@ bool UserCommandsPrivate::PoseService(const msgs::Pose &_req, return true; } +////////////////////////////////////////////////// +bool UserCommandsPrivate::PhysicsService(const msgs::Physics &_req, + msgs::Boolean &_res) +{ + // Create command and push it to queue + auto msg = _req.New(); + msg->CopyFrom(_req); + auto cmd = std::make_unique(msg, this->iface); + // Push to pending + { + std::lock_guard lock(this->pendingMutex); + this->pendingCmds.push_back(std::move(cmd)); + } + + _res.set_data(true); + return true; +} + ////////////////////////////////////////////////// UserCommandBase::UserCommandBase(google::protobuf::Message *_msg, std::shared_ptr &_iface) @@ -715,6 +764,39 @@ bool PoseCommand::Execute() return true; } +////////////////////////////////////////////////// +PhysicsCommand::PhysicsCommand(msgs::Physics *_msg, + std::shared_ptr &_iface) + : UserCommandBase(_msg, _iface) +{ +} + +////////////////////////////////////////////////// +bool PhysicsCommand::Execute() +{ + auto physicsMsg = dynamic_cast(this->msg); + if (nullptr == physicsMsg) + { + ignerr << "Internal error, null physics message" << std::endl; + return false; + } + + auto worldEntity = this->iface->ecm->EntityByComponents(components::World()); + if (worldEntity == kNullEntity) + { + ignmsg << "Failed to find world entity" << std::endl; + return false; + } + + if (!this->iface->ecm->EntityHasComponentType(worldEntity, + components::PhysicsCmd().TypeId())) + { + this->iface->ecm->CreateComponent(worldEntity, + components::PhysicsCmd(*physicsMsg)); + } + + return true; +} IGNITION_ADD_PLUGIN(UserCommands, System, UserCommands::ISystemConfigure, diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index b87473e9b1..347135fc59 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -27,7 +27,9 @@ #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" +#include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" @@ -690,3 +692,65 @@ TEST_F(UserCommandsTest, Pose) ASSERT_NE(nullptr, poseComp); EXPECT_NEAR(500.0, poseComp->Data().Pos().Y(), 0.2); } + +///////////////////////////////////////////////// +TEST_F(UserCommandsTest, Physics) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/shapes.sdf"; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system just to get the ECM + EntityComponentManager *ecm{nullptr}; + test::Relay testSystem; + testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + ecm = &_ecm; + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server and check we have the ECM + EXPECT_EQ(nullptr, ecm); + server.Run(true, 1, false); + EXPECT_NE(nullptr, ecm); + + // Check that the physics properties are the ones specified in the sdf + auto worldEntity = ecm->EntityByComponents(components::World()); + EXPECT_NE(kNullEntity, worldEntity); + auto physicsComp = ecm->Component(worldEntity); + ASSERT_NE(nullptr, physicsComp); + EXPECT_DOUBLE_EQ(0.001, physicsComp->Data().MaxStepSize()); + EXPECT_DOUBLE_EQ(1.0, physicsComp->Data().RealTimeFactor()); + + // Set physics properties + msgs::Physics req; + req.set_max_step_size(0.123); + req.set_real_time_factor(4.567); + + msgs::Boolean res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/default/set_physics"}; + + transport::Node node; + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + // Run two iterations, in the first one the PhysicsCmd component is created + // in the second one it is processed + server.Run(true, 2, false); + + // Check updated physics properties + physicsComp = ecm->Component(worldEntity); + EXPECT_DOUBLE_EQ(0.123, physicsComp->Data().MaxStepSize()); + EXPECT_DOUBLE_EQ(4.567, physicsComp->Data().RealTimeFactor()); +} From 701b6eea76031a514e0a37d78c7c6411530b75ea Mon Sep 17 00:00:00 2001 From: Jose Luis Rivero Date: Tue, 2 Feb 2021 19:45:59 +0100 Subject: [PATCH 23/55] =?UTF-8?q?=F0=9F=91=A9=E2=80=8D=F0=9F=8C=BE=20Refac?= =?UTF-8?q?tor=20UNIT=5FServer=5FTEST:=20move=20tests=20to=20integration?= =?UTF-8?q?=20(#594)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Move several server interactions and fuel cached to their own tests in integration. Signed-off-by: Jose Luis Rivero --- src/Server_TEST.cc | 113 +------------------------ test/helpers/EnvTestFixture.hh | 36 ++++++++ test/integration/CMakeLists.txt | 2 + test/integration/fuel_cached_server.cc | 57 +++++++++++++ test/integration/multiple_servers.cc | 104 +++++++++++++++++++++++ 5 files changed, 200 insertions(+), 112 deletions(-) create mode 100644 test/helpers/EnvTestFixture.hh create mode 100644 test/integration/fuel_cached_server.cc create mode 100644 test/integration/multiple_servers.cc diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index d625f936f5..672c64ca11 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -18,7 +18,6 @@ #include #include #include -#include #include #include #include @@ -39,23 +38,12 @@ #include "plugins/MockSystem.hh" #include "../test/helpers/Relay.hh" +#include "../test/helpers/EnvTestFixture.hh" using namespace ignition; using namespace ignition::gazebo; using namespace std::chrono_literals; -class ServerFixture : public ::testing::TestWithParam -{ - protected: void SetUp() override - { - // Augment the system plugin path. In SetUp to avoid test order issues. - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - - ignition::common::Console::SetVerbosity(4); - } -}; - ///////////////////////////////////////////////// TEST_P(ServerFixture, DefaultServerConfig) { @@ -624,79 +612,6 @@ TEST_P(ServerFixture, SigInt) EXPECT_FALSE(*server.Running(0)); } -///////////////////////////////////////////////// -TEST_P(ServerFixture, TwoServersNonBlocking) -{ - ignition::gazebo::ServerConfig serverConfig; - serverConfig.SetSdfString(TestWorldSansPhysics::World()); - - gazebo::Server server1(serverConfig); - gazebo::Server server2(serverConfig); - EXPECT_FALSE(server1.Running()); - EXPECT_FALSE(*server1.Running(0)); - EXPECT_FALSE(server2.Running()); - EXPECT_FALSE(*server2.Running(0)); - EXPECT_EQ(0u, *server1.IterationCount()); - EXPECT_EQ(0u, *server2.IterationCount()); - - // Make the servers run fast. - server1.SetUpdatePeriod(1ns); - server2.SetUpdatePeriod(1ns); - - // Start non-blocking - const size_t iters1 = 9999; - EXPECT_TRUE(server1.Run(false, iters1, false)); - - // Expect that we can't start another instance. - EXPECT_FALSE(server1.Run(true, 10, false)); - - // It's okay to start another server - EXPECT_TRUE(server2.Run(false, 500, false)); - - while (*server1.IterationCount() < iters1 || *server2.IterationCount() < 500) - IGN_SLEEP_MS(100); - - EXPECT_EQ(iters1, *server1.IterationCount()); - EXPECT_EQ(500u, *server2.IterationCount()); - EXPECT_FALSE(server1.Running()); - EXPECT_FALSE(*server1.Running(0)); - EXPECT_FALSE(server2.Running()); - EXPECT_FALSE(*server2.Running(0)); -} - -///////////////////////////////////////////////// -TEST_P(ServerFixture, TwoServersMixedBlocking) -{ - ignition::gazebo::ServerConfig serverConfig; - serverConfig.SetSdfString(TestWorldSansPhysics::World()); - - gazebo::Server server1(serverConfig); - gazebo::Server server2(serverConfig); - EXPECT_FALSE(server1.Running()); - EXPECT_FALSE(*server1.Running(0)); - EXPECT_FALSE(server2.Running()); - EXPECT_FALSE(*server2.Running(0)); - EXPECT_EQ(0u, *server1.IterationCount()); - EXPECT_EQ(0u, *server2.IterationCount()); - - // Make the servers run fast. - server1.SetUpdatePeriod(1ns); - server2.SetUpdatePeriod(1ns); - - server1.Run(false, 10, false); - server2.Run(true, 1000, false); - - while (*server1.IterationCount() < 10) - IGN_SLEEP_MS(100); - - EXPECT_EQ(10u, *server1.IterationCount()); - EXPECT_EQ(1000u, *server2.IterationCount()); - EXPECT_FALSE(server1.Running()); - EXPECT_FALSE(*server1.Running(0)); - EXPECT_FALSE(server2.Running()); - EXPECT_FALSE(*server2.Running(0)); -} - ///////////////////////////////////////////////// TEST_P(ServerFixture, AddSystemWhileRunning) { @@ -902,32 +817,6 @@ TEST_P(ServerFixture, GetResourcePaths) EXPECT_EQ("/home/user/another_path", res.data(1)); } -///////////////////////////////////////////////// -TEST_P(ServerFixture, CachedFuelWorld) -{ - auto cachedWorldPath = - common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds"); - setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1); - - ServerConfig serverConfig; - auto fuelWorldURL = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; - EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL)); - - EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile()); - EXPECT_TRUE(serverConfig.SdfString().empty()); - - // Check that world was loaded - auto server = Server(serverConfig); - EXPECT_NE(std::nullopt, server.Running(0)); - EXPECT_FALSE(*server.Running(0)); - - server.Run(true /*blocking*/, 1, false/*paused*/); - - EXPECT_NE(std::nullopt, server.Running(0)); - EXPECT_FALSE(*server.Running(0)); -} - ///////////////////////////////////////////////// TEST_P(ServerFixture, AddResourcePaths) { diff --git a/test/helpers/EnvTestFixture.hh b/test/helpers/EnvTestFixture.hh new file mode 100644 index 0000000000..e74f1a6ca1 --- /dev/null +++ b/test/helpers/EnvTestFixture.hh @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2020 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_TEST_HELPERS_ENVTESTFIXTURE_HH_ +#define IGNITION_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_ + +#include + +#include +#include "ignition/gazebo/test_config.hh" + +class ServerFixture : public ::testing::TestWithParam +{ + protected: void SetUp() override + { + // Augment the system plugin path. In SetUp to avoid test order issues. + setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + + ignition::common::Console::SetVerbosity(4); + } +}; +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 1f228c1f88..a2e4eb484f 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -17,6 +17,7 @@ set(tests events.cc examples_build.cc follow_actor_system.cc + fuel_cached_server.cc imu_system.cc joint_controller_system.cc joint_position_controller_system.cc @@ -31,6 +32,7 @@ set(tests magnetometer_system.cc model.cc multicopter.cc + multiple_servers.cc network_handshake.cc performer_detector.cc physics_system.cc diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc new file mode 100644 index 0000000000..7003459ff7 --- /dev/null +++ b/test/integration/fuel_cached_server.cc @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2018 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 "ignition/gazebo/Server.hh" +#include "ignition/gazebo/ServerConfig.hh" + +#include "../test/helpers/EnvTestFixture.hh" + +using namespace ignition; +using namespace ignition::gazebo; +using namespace std::chrono_literals; + +///////////////////////////////////////////////// +TEST_P(ServerFixture, CachedFuelWorld) +{ + auto cachedWorldPath = + common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds"); + setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1); + + ServerConfig serverConfig; + auto fuelWorldURL = + "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; + EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL)); + + EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile()); + EXPECT_TRUE(serverConfig.SdfString().empty()); + + // Check that world was loaded + auto server = Server(serverConfig); + EXPECT_NE(std::nullopt, server.Running(0)); + EXPECT_FALSE(*server.Running(0)); + + server.Run(true /*blocking*/, 1, false/*paused*/); + + EXPECT_NE(std::nullopt, server.Running(0)); + EXPECT_FALSE(*server.Running(0)); +} + +// Run multiple times. We want to make sure that static globals don't cause +// problems. +INSTANTIATE_TEST_SUITE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2)); diff --git a/test/integration/multiple_servers.cc b/test/integration/multiple_servers.cc new file mode 100644 index 0000000000..71f89ab663 --- /dev/null +++ b/test/integration/multiple_servers.cc @@ -0,0 +1,104 @@ +/* + * Copyright (C) 2018 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 "ignition/gazebo/Server.hh" +#include "ignition/gazebo/ServerConfig.hh" + +#include "../test/helpers/EnvTestFixture.hh" + +using namespace ignition; +using namespace ignition::gazebo; +using namespace std::chrono_literals; + +///////////////////////////////////////////////// +TEST_P(ServerFixture, TwoServersNonBlocking) +{ + ignition::gazebo::ServerConfig serverConfig; + serverConfig.SetSdfString(TestWorldSansPhysics::World()); + + gazebo::Server server1(serverConfig); + gazebo::Server server2(serverConfig); + EXPECT_FALSE(server1.Running()); + EXPECT_FALSE(*server1.Running(0)); + EXPECT_FALSE(server2.Running()); + EXPECT_FALSE(*server2.Running(0)); + EXPECT_EQ(0u, *server1.IterationCount()); + EXPECT_EQ(0u, *server2.IterationCount()); + + // Make the servers run fast. + server1.SetUpdatePeriod(1ns); + server2.SetUpdatePeriod(1ns); + + // Start non-blocking + const size_t iters1 = 9999; + EXPECT_TRUE(server1.Run(false, iters1, false)); + + // Expect that we can't start another instance. + EXPECT_FALSE(server1.Run(true, 10, false)); + + // It's okay to start another server + EXPECT_TRUE(server2.Run(false, 500, false)); + + while (*server1.IterationCount() < iters1 || *server2.IterationCount() < 500) + IGN_SLEEP_MS(100); + + EXPECT_EQ(iters1, *server1.IterationCount()); + EXPECT_EQ(500u, *server2.IterationCount()); + EXPECT_FALSE(server1.Running()); + EXPECT_FALSE(*server1.Running(0)); + EXPECT_FALSE(server2.Running()); + EXPECT_FALSE(*server2.Running(0)); +} + +///////////////////////////////////////////////// +TEST_P(ServerFixture, TwoServersMixedBlocking) +{ + ignition::gazebo::ServerConfig serverConfig; + serverConfig.SetSdfString(TestWorldSansPhysics::World()); + + gazebo::Server server1(serverConfig); + gazebo::Server server2(serverConfig); + EXPECT_FALSE(server1.Running()); + EXPECT_FALSE(*server1.Running(0)); + EXPECT_FALSE(server2.Running()); + EXPECT_FALSE(*server2.Running(0)); + EXPECT_EQ(0u, *server1.IterationCount()); + EXPECT_EQ(0u, *server2.IterationCount()); + + // Make the servers run fast. + server1.SetUpdatePeriod(1ns); + server2.SetUpdatePeriod(1ns); + + server1.Run(false, 10, false); + server2.Run(true, 1000, false); + + while (*server1.IterationCount() < 10) + IGN_SLEEP_MS(100); + + EXPECT_EQ(10u, *server1.IterationCount()); + EXPECT_EQ(1000u, *server2.IterationCount()); + EXPECT_FALSE(server1.Running()); + EXPECT_FALSE(*server1.Running(0)); + EXPECT_FALSE(server2.Running()); + EXPECT_FALSE(*server2.Running(0)); +} + +// Run multiple times. We want to make sure that static globals don't cause +// problems. +INSTANTIATE_TEST_SUITE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2)); From 4eda53fa44139db8c3cd45a78077a7de4004854f Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 2 Feb 2021 11:43:41 -0800 Subject: [PATCH 24/55] Also use Ignition GUI render event (#598) Signed-off-by: Louise Poubel --- src/gui/plugins/scene3d/Scene3D.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index af6c3ef967..4f7730d67b 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -836,10 +836,16 @@ void IgnRenderer::Render() if (ignition::gui::App()) { - gui::events::Render event; + ignition::gui::events::Render event; ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), &event); + + // This will be deprecated on v5 and removed on v6 + ignition::gazebo::gui::events::Render oldEvent; + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &oldEvent); } // only has an effect in video recording lockstep mode From 71e6c314e703e510e3a05a5f728d877f25ad3c26 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 2 Feb 2021 11:54:44 -0800 Subject: [PATCH 25/55] Address deprecation warning and add note to migration guide (#602) Signed-off-by: Louise Poubel --- Migration.md | 4 ++++ src/gui/plugins/scene3d/Scene3D.cc | 5 +++-- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Migration.md b/Migration.md index 30fded54d3..680026a02d 100644 --- a/Migration.md +++ b/Migration.md @@ -27,6 +27,10 @@ in SDF by setting the `` SDF element. * Log playback using `` SDF parameter is removed. Use --playback command line argument instead. +* `rendering::SceneManager` + * **Deprecated**: `Entity EntityFromNode(const rendering::NodePtr &_node) const;` + * **Replacement**: `Entity entity = std::get(visual->UserData("gazebo-entity"));` + ## Ignition Gazebo 2.x to 3.x * Use ign-rendering3, ign-sensors3 and ign-gui3. diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 22c93fff6e..b22da15d99 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -816,11 +816,12 @@ void IgnRenderer::Render() { rendering::NodePtr targetNode = scene->NodeByName(this->dataPtr->viewCollisionsTarget); + auto targetVis = std::dynamic_pointer_cast(targetNode); - if (targetNode) + if (targetVis) { Entity targetEntity = - this->dataPtr->renderUtil.SceneManager().EntityFromNode(targetNode); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewCollisions(targetEntity); } else From 0f284ba7f14863e449cdbbe9fae821f5bd31d445 Mon Sep 17 00:00:00 2001 From: Ashton Larkin Date: Tue, 2 Feb 2021 16:31:55 -0500 Subject: [PATCH 26/55] 4.3.0 (#605) Signed-off-by: Ashton Larkin --- CMakeLists.txt | 2 +- Changelog.md | 56 ++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 57 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 274e168a10..d9ceb3e6fa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo4 VERSION 4.2.0) +project(ignition-gazebo4 VERSION 4.3.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 60ee6dc27d..8a76252c42 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,61 @@ ## Ignition Gazebo 4.x +### Ignition Gazebo 4.3.0 (2020-02-02) + +1. Non-blocking paths request. + * [Pull Request 555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + +1. Parallelize State call in ECM. + * [Pull Request 451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + +1. Allow to create light with the create service. + * [Pull Request 513](https://github.com/ignitionrobotics/ign-gazebo/pull/513) + +1. Added size to ground_plane in examples. + * [Pull Request 573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + +1. Fix finding PBR materials. + * [Pull Request 575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + +1. Publish all periodic change components in Scene Broadcaster. + * [Pull Request 544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + +1. Backport state update changes from pull request [#486](https://github.com/ignitionrobotics/ign-gazebo/pull/486). + * [Pull Request 583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) + +1. Fix code_check errors. + * [Pull Request 582](https://github.com/ignitionrobotics/ign-gazebo/pull/582) + +1. Visualize collisions. + * [Pull Request 531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + +1. Remove playback SDF param in Dome. + * [Pull Request 570](https://github.com/ignitionrobotics/ign-gazebo/pull/570) + +1. Tutorial on migrating SDF files from Gazebo classic. + * [Pull Request 400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + +1. World Exporter. + * [Pull Request 474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + +1. Model Creation tutorial using services. + * [Pull Request 530](https://github.com/ignitionrobotics/ign-gazebo/pull/530) + +1. Fix topLevelModel Method. + * [Pull Request 600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + +1. Add heat signature option to thermal system. + * [Pull Request 498](https://github.com/ignitionrobotics/ign-gazebo/pull/498) + +1. Add service and GUI to configure physics parameters (step size and RTF). + * [Pull Request 536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) + +1. Refactor UNIT_Server_TEST. + * [Pull Request 594](https://github.com/ignitionrobotics/ign-gazebo/pull/594) + +1. Use Ignition GUI render event. + * [Pull Request 598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) + ### Ignition Gazebo 4.2.0 (2020-01-13) 1. Automatically load a subset of world plugins. From c37e4822c1cf59f7302358d0b4dc7b8ba3db5a1d Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Thu, 4 Feb 2021 18:53:05 -0800 Subject: [PATCH 27/55] added issue & PR templates (#613) Signed-off-by: Jenn Nguyen --- .github/ISSUE_TEMPLATE/bug_report.md | 29 +++++++++++++ .github/ISSUE_TEMPLATE/feature_request.md | 23 ++++++++++ .github/PULL_REQUEST_TEMPLATE.md | 52 +++++++++++++++++++++++ .github/PULL_REQUEST_TEMPLATE/port.md | 6 +++ 4 files changed, 110 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE/bug_report.md create mode 100644 .github/ISSUE_TEMPLATE/feature_request.md create mode 100644 .github/PULL_REQUEST_TEMPLATE.md create mode 100644 .github/PULL_REQUEST_TEMPLATE/port.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md new file mode 100644 index 0000000000..3d89f64143 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -0,0 +1,29 @@ +--- +name: Bug report +about: Report a bug +labels: bug +--- + + + +## Environment +* OS Version: +* Source or binary build? + + + +## Description +* Expected behavior: +* Actual behavior: + +## Steps to reproduce + + +1. +2. +3. + +## Output + diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md new file mode 100644 index 0000000000..f49727a0ce --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature_request.md @@ -0,0 +1,23 @@ +--- +name: Feature request +about: Request a new feature +labels: enhancement +--- + + + +## Desired behavior + + +## Alternatives considered + + +## Implementation suggestion + + +## Additional context + diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md new file mode 100644 index 0000000000..6c88bd5465 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -0,0 +1,52 @@ + + +# Bug Report + +Fixes issue # + +## Summary + + +## Checklist +- [ ] Signed all commits for DCO +- [ ] Added tests +- [ ] Updated documentation (as needed) +- [ ] Updated migration guide (as needed) +- [ ] `codecheck` passed (See + [contributing](https://ignitionrobotics.org/docs/all/contributing#contributing-code)) +- [ ] All tests passed (See + [test coverage](https://ignitionrobotics.org/docs/all/contributing#test-coverage)) +- [ ] While waiting for a review on your PR, please help review +[another open pull request](https://github.com/pulls?q=is%3Aopen+is%3Apr+user%3Aignitionrobotics+archived%3Afalse+) +to support the maintainers + +**Note to maintainers**: Remember to use **Squash-Merge** + +--- + +# New feature + +Closes # + +## Summary + + +## Test it + + +## Checklist +- [ ] Signed all commits for DCO +- [ ] Added tests +- [ ] Added example world and/or tutorial +- [ ] Updated documentation (as needed) +- [ ] Updated migration guide (as needed) +- [ ] `codecheck` passed (See [contributing](https://ignitionrobotics.org/docs/all/contributing#contributing-code)) +- [ ] All tests passed (See [test coverage](https://ignitionrobotics.org/docs/all/contributing#test-coverage)) +- [ ] While waiting for a review on your PR, please help review +[another open pull request](https://github.com/pulls?q=is%3Aopen+is%3Apr+user%3Aignitionrobotics+archived%3Afalse+) +to support the maintainers + +**Note to maintainers**: Remember to use **Squash-Merge** diff --git a/.github/PULL_REQUEST_TEMPLATE/port.md b/.github/PULL_REQUEST_TEMPLATE/port.md new file mode 100644 index 0000000000..758127f585 --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE/port.md @@ -0,0 +1,6 @@ +Port to + +Branch comparison: https://github.com/ignitionrobotics/ign-gazebo/compare/... + +**Note to maintainers**: Remember to **Merge** with commit (not squash-merge +or rebase) From 766bb23eaca85ff60941e2ef852c4f286356fbcc Mon Sep 17 00:00:00 2001 From: Rushyendra Maganty Date: Mon, 8 Feb 2021 17:26:34 -0500 Subject: [PATCH 28/55] Fix seg fault in `SetRemovedComponentsMsgs` when TransformControl tool is used (#495) * Fix seg fault due to invalid iterator to mutable_entities Signed-off-by: mrushyendra * Elaborate comment on need to insert entity into message Signed-off-by: mrushyendra * Add types filter to SetRemovedComponentsMsgs Signed-off-by: mrushyendra * Add unit tests for checking StateMap msg with latest changes Verifies the message created in situations where components are only removed but not changed, and when a list of types to filter is passed to the function. Signed-off-by: Maganty Rushyendra * Fix traversal of removedComponents in multimap Signed-off-by: Maganty Rushyendra Co-authored-by: Ian Chen Co-authored-by: Louise Poubel Co-authored-by: Ashton Larkin --- src/EntityComponentManager.cc | 67 ++++++++++++++++--------- src/EntityComponentManager_TEST.cc | 80 ++++++++++++++++++++++++++++++ 2 files changed, 124 insertions(+), 23 deletions(-) diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 3b2cd2f924..4c1089f1aa 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -56,15 +56,21 @@ class ignition::gazebo::EntityComponentManagerPrivate /// \brief Create a message for the removed components /// \param[in] _entity Entity with the removed components - /// \param[out] _msg Entity message + /// \param[in, out] _msg Entity message + /// \param[in] _types _types Type IDs of components to be serialized. Leave + /// empty to get all removed components. public: void SetRemovedComponentsMsgs(Entity &_entity, - msgs::SerializedEntity *_msg); + msgs::SerializedEntity *_msg, + const std::unordered_set &_types = {}); /// \brief Create a message for the removed components /// \param[in] _entity Entity with the removed components - /// \param[out] _msg State message + /// \param[in, out] _msg State message + /// \param[in] _types _types Type IDs of components to be serialized. Leave + /// empty to get all removed components. public: void SetRemovedComponentsMsgs(Entity &_entity, - msgs::SerializedStateMap &_msg); + msgs::SerializedStateMap &_msg, + const std::unordered_set &_types = {}); /// \brief Map of component storage classes. The key is a component /// type id, and the value is a pointer to the component storage. @@ -774,46 +780,63 @@ void EntityComponentManager::RebuildViews() ////////////////////////////////////////////////// void EntityComponentManagerPrivate::SetRemovedComponentsMsgs(Entity &_entity, - msgs::SerializedEntity *_entityMsg) + msgs::SerializedEntity *_entityMsg, + const std::unordered_set &_types) { std::lock_guard lock(this->removedComponentsMutex); - uint64_t nEntityKeys = this->removedComponents.count(_entity); - if (nEntityKeys == 0) - return; - - auto it = this->removedComponents.find(_entity); - for (uint64_t i = 0; i < nEntityKeys; ++i) + auto entRemovedComps = this->removedComponents.equal_range(_entity); + for (auto it = entRemovedComps.first; it != entRemovedComps.second; ++it) { - auto compMsg = _entityMsg->add_components(); - auto removedComponent = it->second; + if (!_types.empty() && _types.find(removedComponent.first) == _types.end()) + { + continue; + } + + auto compMsg = _entityMsg->add_components(); + // Empty data is needed for the component to be processed afterwards compMsg->set_component(" "); compMsg->set_type(removedComponent.first); compMsg->set_remove(true); - - it++; } } ////////////////////////////////////////////////// void EntityComponentManagerPrivate::SetRemovedComponentsMsgs(Entity &_entity, - msgs::SerializedStateMap &_msg) + msgs::SerializedStateMap &_msg, + const std::unordered_set &_types) { std::lock_guard lock(this->removedComponentsMutex); uint64_t nEntityKeys = this->removedComponents.count(_entity); if (nEntityKeys == 0) return; - // Find the entity in the message + // The message need not necessarily contain the entity initially. For + // instance, when AddEntityToMessage() calls this function, the entity may + // have some removed components but none in entityComponents that changed, + // so the entity may not have been added to the message beforehand. auto entIter = _msg.mutable_entities()->find(_entity); + if (entIter == _msg.mutable_entities()->end()) + { + msgs::SerializedEntityMap ent; + ent.set_id(_entity); + entIter = + (_msg.mutable_entities())->insert({static_cast(_entity), ent}) + .first; + } - auto it = this->removedComponents.find(_entity); - for (uint64_t i = 0; i < nEntityKeys; ++i) + auto entRemovedComps = this->removedComponents.equal_range(_entity); + for (auto it = entRemovedComps.first; it != entRemovedComps.second; ++it) { auto removedComponent = it->second; + if (!_types.empty() && _types.find(removedComponent.first) == _types.end()) + { + continue; + } + msgs::SerializedComponent compMsg; // Empty data is needed for the component to be processed afterwards @@ -823,8 +846,6 @@ void EntityComponentManagerPrivate::SetRemovedComponentsMsgs(Entity &_entity, (*(entIter->second.mutable_components()))[ static_cast(removedComponent.first)] = compMsg; - - it++; } } @@ -878,7 +899,7 @@ void EntityComponentManager::AddEntityToMessage(msgs::SerializedState &_msg, // Add a component to the message and set it to be removed if the component // exists in the removedComponents map. - this->dataPtr->SetRemovedComponentsMsgs(_entity, entityMsg); + this->dataPtr->SetRemovedComponentsMsgs(_entity, entityMsg, _types); } ////////////////////////////////////////////////// @@ -980,7 +1001,7 @@ void EntityComponentManager::AddEntityToMessage(msgs::SerializedStateMap &_msg, // Add a component to the message and set it to be removed if the component // exists in the removedComponents map. - this->dataPtr->SetRemovedComponentsMsgs(_entity, _msg); + this->dataPtr->SetRemovedComponentsMsgs(_entity, _msg, _types); } ////////////////////////////////////////////////// diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 1a77d1daf1..b29fb53aef 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -2288,6 +2288,86 @@ TEST_P(EntityComponentManagerFixture, SerializedStateMsgAfterRemoveComponent) } } +////////////////////////////////////////////////// +// Verify SerializedStateMap message with no changed components, +// but some removed components +TEST_P(EntityComponentManagerFixture, SerializedStateMapMsgCompsRemovedOnly) +{ + // Create entity + Entity e1 = manager.CreateEntity(); + auto e1c0 = + manager.CreateComponent(e1, IntComponent(123)); + manager.CreateComponent(e1, DoubleComponent(0.0)); + auto e1c2 = + manager.CreateComponent(e1, StringComponent("int")); + + manager.RunSetAllComponentsUnchanged(); + manager.RemoveComponent(e1, e1c0); + manager.RemoveComponent(e1, e1c2); + // Serialize into a message + msgs::SerializedStateMap stateMsg; + manager.State(stateMsg); + + // Check message + { + auto iter = stateMsg.entities().find(e1); + const auto &e1Msg = iter->second; + auto compIter = e1Msg.components().begin(); + + // Check number of components + ASSERT_EQ(e1Msg.components().size(), 2u); + + // First component + const auto &c0 = compIter->second; + compIter++; + ASSERT_EQ(c0.remove(), true); + + // Second component + const auto &c2 = compIter->second; + ASSERT_EQ(c2.remove(), true); + } +} + +////////////////////////////////////////////////// +// Verify that removed components are correctly filtered when creating a +// SerializedStateMap message +TEST_P(EntityComponentManagerFixture, SetRemovedComponentsMsgTypesFilter) +{ + // Create entity + Entity e1 = manager.CreateEntity(); + auto e1c0 = + manager.CreateComponent(e1, IntComponent(123)); + auto e1c1 = + manager.CreateComponent(e1, DoubleComponent(0.0)); + auto e1c2 = + manager.CreateComponent(e1, StringComponent("foo")); + + manager.RunSetAllComponentsUnchanged(); + manager.RemoveComponent(e1, e1c0); + manager.RemoveComponent(e1, e1c2); + + // Serialize into a message, providing a list of types to be included + msgs::SerializedStateMap stateMsg; + std::unordered_set entitySet{e1}; + std::unordered_set types{e1c0.first, e1c1.first}; + manager.State(stateMsg, entitySet, types, false); + + // Check message + { + auto iter = stateMsg.entities().find(e1); + const auto &e1Msg = iter->second; + auto compIter = e1Msg.components().begin(); + + // Check number of components + ASSERT_EQ(e1Msg.components().size(), 1u); + + // Only component in message should be e1c2 + const auto &c0 = compIter->second; + EXPECT_EQ(c0.remove(), true); + EXPECT_EQ(c0.type(), e1c0.first); + } +} + ////////////////////////////////////////////////// TEST_P(EntityComponentManagerFixture, RemovedComponentsSyncBetweenServerAndGUI) { From ac1089278a063cfddc9b1322d1abcbb1ce760c00 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 9 Feb 2021 09:48:45 -0800 Subject: [PATCH 29/55] Make topics configurable for joint controllers (#584) Signed-off-by: Louise Poubel --- examples/worlds/joint_position_controller.sdf | 7 ++++--- src/systems/joint_controller/JointController.cc | 4 ++++ .../joint_position_controller/JointPositionController.cc | 4 ++++ 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/examples/worlds/joint_position_controller.sdf b/examples/worlds/joint_position_controller.sdf index 6d2ad62e83..b2bd104509 100644 --- a/examples/worlds/joint_position_controller.sdf +++ b/examples/worlds/joint_position_controller.sdf @@ -4,9 +4,9 @@ Try sending joint position commands: - ign topic -t "/model/joint_position_controller_demo/joint/j1/0/cmd_pos" -m ignition.msgs.Double -p "data: -1.0" + ign topic -t "/rotor_cmd" -m ignition.msgs.Double -p "data: -1.0" - ign topic -t "/model/joint_position_controller_demo/joint/j1/0/cmd_pos" -m ignition.msgs.Double -p "data: 1.0" + ign topic -t "/rotor_cmd" -m ignition.msgs.Double -p "data: 1.0" --> @@ -45,7 +45,7 @@ 72 121 1 - + floating @@ -156,6 +156,7 @@ filename="ignition-gazebo-joint-position-controller-system" name="ignition::gazebo::systems::JointPositionController"> j1 + rotor_cmd 1 0.1 0.01 diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 42990d4447..695ee62d6d 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -133,6 +133,10 @@ void JointController::Configure(const Entity &_entity, // Subscribe to commands std::string topic{"/model/" + this->dataPtr->model.Name(_ecm) + "/joint/" + this->dataPtr->jointName + "/cmd_vel"}; + if (_sdf->HasElement("topic")) + { + topic = _sdf->Get("topic"); + } this->dataPtr->node.Subscribe(topic, &JointControllerPrivate::OnCmdVel, this->dataPtr.get()); diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index c048ff0e23..691336d901 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -150,6 +150,10 @@ void JointPositionController::Configure(const Entity &_entity, std::string topic{"/model/" + this->dataPtr->model.Name(_ecm) + "/joint/" + this->dataPtr->jointName + "/" + std::to_string(this->dataPtr->jointIndex) + "/cmd_pos"}; + if (_sdf->HasElement("topic")) + { + topic = _sdf->Get("topic"); + } this->dataPtr->node.Subscribe( topic, &JointPositionControllerPrivate::OnCmdPos, this->dataPtr.get()); From 87b2f4ba27cc10a1a586bda8d635aa929e1070ce Mon Sep 17 00:00:00 2001 From: Atharva Pusalkar Date: Thu, 11 Feb 2021 02:48:59 +0530 Subject: [PATCH 30/55] Add About dialog (#609) Signed-off-by: atharva-18 --- src/gui/AboutDialogHandler.cc | 67 ++++++++++++++++++++++++++++++ src/gui/AboutDialogHandler.hh | 58 ++++++++++++++++++++++++++ src/gui/CMakeLists.txt | 1 + src/gui/Gui.cc | 5 +++ src/gui/resources/GazeboDrawer.qml | 55 +++++++++++++++++++----- 5 files changed, 176 insertions(+), 10 deletions(-) create mode 100644 src/gui/AboutDialogHandler.cc create mode 100644 src/gui/AboutDialogHandler.hh diff --git a/src/gui/AboutDialogHandler.cc b/src/gui/AboutDialogHandler.cc new file mode 100644 index 0000000000..545f6fbb66 --- /dev/null +++ b/src/gui/AboutDialogHandler.cc @@ -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. + * + */ + +#include "AboutDialogHandler.hh" + +#include +#include +#include + +using namespace ignition; +using namespace gazebo; +using namespace gazebo::gui; + +///////////////////////////////////////////////// +AboutDialogHandler::AboutDialogHandler() +{ + aboutText += std::string(IGNITION_GAZEBO_VERSION_HEADER); + aboutText += "" + "" + "" + "" + "" + "" + "" + "" + "" + "
Documentation:" + "" + "" + "https://ignitionrobotics.org/libs/gazebo" + "" + "
" + "Tutorials:" + "" + "" + "https://ignitionrobotics.org/docs/" + "" + "
"; +} + +///////////////////////////////////////////////// +QString AboutDialogHandler::getVersionInformation() +{ + return QString::fromStdString(this->aboutText); +} + +///////////////////////////////////////////////// +void AboutDialogHandler::openURL(QString _url) +{ + QDesktopServices::openUrl(QUrl(_url)); +} diff --git a/src/gui/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh new file mode 100644 index 0000000000..b5f71b543d --- /dev/null +++ b/src/gui/AboutDialogHandler.hh @@ -0,0 +1,58 @@ +/* + * 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_GUI_ABOUTDIALOGHANDLER_HH_ +#define IGNITION_GAZEBO_GUI_ABOUTDIALOGHANDLER_HH_ + +#include +#include +#include + +#include "ignition/gazebo/EntityComponentManager.hh" +#include "ignition/gazebo/Export.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace gui +{ +/// \brief Class for handling about dialog +class IGNITION_GAZEBO_VISIBLE AboutDialogHandler : public QObject +{ + Q_OBJECT + + /// \brief Constructor + public: AboutDialogHandler(); + + /// \brief Get version information + /// \return Version information in rich text format + Q_INVOKABLE QString getVersionInformation(); + + /// \brief Function called from QML when user clicks on a link + /// \param[in] _url Url to web page. + Q_INVOKABLE void openURL(QString _url); + + /// \brief Version information and links to online resources + private: std::string aboutText; +}; +} +} +} +} +#endif diff --git a/src/gui/CMakeLists.txt b/src/gui/CMakeLists.txt index 5d53622322..46d4be7f5c 100644 --- a/src/gui/CMakeLists.txt +++ b/src/gui/CMakeLists.txt @@ -1,4 +1,5 @@ set (gui_sources + AboutDialogHandler.cc Gui.cc GuiFileHandler.cc GuiRunner.cc diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index 00c3b7215f..04340d116d 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -28,6 +28,7 @@ #include "ignition/gazebo/gui/TmpIface.hh" #include "ignition/gazebo/gui/Gui.hh" +#include "AboutDialogHandler.hh" #include "GuiFileHandler.hh" #include "PathManager.hh" @@ -63,6 +64,9 @@ std::unique_ptr createGui( auto tmp = new ignition::gazebo::TmpIface(); tmp->setParent(app->Engine()); + auto aboutDialogHandler = new ignition::gazebo::gui::AboutDialogHandler(); + aboutDialogHandler->setParent(app->Engine()); + auto guiFileHandler = new ignition::gazebo::gui::GuiFileHandler(); guiFileHandler->setParent(app->Engine()); @@ -102,6 +106,7 @@ std::unique_ptr createGui( // Let QML files use TmpIface' functions and properties auto context = new QQmlContext(app->Engine()->rootContext()); context->setContextProperty("TmpIface", tmp); + context->setContextProperty("AboutDialogHandler", aboutDialogHandler); context->setContextProperty("GuiFileHandler", guiFileHandler); // Instantiate GazeboDrawer.qml file into a component diff --git a/src/gui/resources/GazeboDrawer.qml b/src/gui/resources/GazeboDrawer.qml index 8ca3f273a7..647883da34 100644 --- a/src/gui/resources/GazeboDrawer.qml +++ b/src/gui/resources/GazeboDrawer.qml @@ -60,6 +60,9 @@ Rectangle { case "loadWorld": loadWorldDialog.open(); break + case "aboutDialog": + aboutDialog.open(); + break // Forward others to default drawer default: parent.onAction(_action); @@ -73,46 +76,50 @@ Rectangle { // Custom action which calls custom C++ code /*ListElement { title: "New world" - action: "newWorld" + actionElement: "newWorld" type: "world" } ListElement { title: "Load world" - action: "loadWorld" + actionElement: "loadWorld" type: "world" }*/ ListElement { title: "Save world" - action: "saveWorld" + actionElement: "saveWorld" enabled: false type: "world" } ListElement { title: "Save world as..." - action: "saveWorldAs" + actionElement: "saveWorldAs" type: "world" } // Actions provided by Ignition GUI, with custom titles ListElement { title: "Load client configuration" - action: "loadConfig" + actionElement: "loadConfig" } ListElement { title: "Save client configuration" - action: "saveConfig" + actionElement: "saveConfig" } ListElement { title: "Save client configuration as" - action: "saveConfigAs" + actionElement: "saveConfigAs" } ListElement { title: "Style settings" - action: "styleSettings" + actionElement: "styleSettings" + } + ListElement { + title: "About" + actionElement: "aboutDialog" } ListElement { title: "Quit" - action: "close" + actionElement: "close" } } @@ -125,7 +132,7 @@ Rectangle { text: title highlighted: ListView.isCurrentItem onClicked: { - customDrawer.onAction(action); + customDrawer.onAction(actionElement); customDrawer.parent.closeDrawer(); } } @@ -165,6 +172,34 @@ Rectangle { } } + /** + * About dialog + */ + Dialog { + id: aboutDialog + title: "Ignition Gazebo" + + modal: true + focus: true + parent: ApplicationWindow.overlay + width: parent.width / 3 > 500 ? 500 : parent.width / 3 + x: (parent.width - width) / 2 + y: (parent.height - height) / 2 + closePolicy: Popup.CloseOnEscape + standardButtons: StandardButton.Ok + + Text { + anchors.fill: parent + id: aboutMessage + wrapMode: Text.Wrap + verticalAlignment: Text.AlignVCenter + color: Material.theme == Material.Light ? "black" : "white" + textFormat: Text.RichText + text: AboutDialogHandler.getVersionInformation() + onLinkActivated: AboutDialogHandler.openURL(link) + } + } + /** * Dialog with configurations for SDF generation */ From e647570f25f962d63af75cf669ff72731d57bd5e Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 10 Feb 2021 14:59:20 -0800 Subject: [PATCH 31/55] Add thermal sensor system for configuring thermal camera properties (#614) Signed-off-by: Ian Chen Co-authored-by: Ashton Larkin --- examples/worlds/thermal_camera.sdf | 62 +++++ .../ignition/gazebo/components/Temperature.hh | 6 + .../ignition/gazebo/rendering/RenderUtil.hh | 6 + src/rendering/RenderUtil.cc | 118 ++++++++++ src/systems/sensors/Sensors.cc | 12 + src/systems/sensors/Sensors.hh | 5 + src/systems/thermal/CMakeLists.txt | 6 + src/systems/thermal/ThermalSensor.cc | 93 ++++++++ src/systems/thermal/ThermalSensor.hh | 60 +++++ test/integration/CMakeLists.txt | 3 +- test/integration/thermal_sensor_system.cc | 219 ++++++++++++++++++ test/integration/thermal_system.cc | 76 +++++- test/worlds/thermal.sdf | 46 ++++ test/worlds/thermal_invalid.sdf | 152 ++++++++++++ 14 files changed, 862 insertions(+), 2 deletions(-) create mode 100644 src/systems/thermal/ThermalSensor.cc create mode 100644 src/systems/thermal/ThermalSensor.hh create mode 100644 test/integration/thermal_sensor_system.cc create mode 100644 test/worlds/thermal_invalid.sdf diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index cf5c92b3f4..e21215537a 100644 --- a/examples/worlds/thermal_camera.sdf +++ b/examples/worlds/thermal_camera.sdf @@ -104,6 +104,18 @@ thermal_camera false
+ + + Thermal camera 8 Bit + floating + 350 + 315 + 500 + + thermal_camera_8bit/image + false + + @@ -230,6 +242,7 @@ 320 240 + L16 0.1 @@ -245,6 +258,55 @@ true + + 4.5 0 0.5 0.0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + L8 + + + 0.1 + 100 + + + 1 + 30 + true + thermal_camera_8bit/image + + 253.15 + 673.15 + 3.0 + + + + + true + + + 1 0 0 0 0 1.570796 rescue_randy diff --git a/include/ignition/gazebo/components/Temperature.hh b/include/ignition/gazebo/components/Temperature.hh index 228e208518..cfd8df5327 100644 --- a/include/ignition/gazebo/components/Temperature.hh +++ b/include/ignition/gazebo/components/Temperature.hh @@ -35,6 +35,12 @@ namespace components using Temperature = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Temperature", Temperature) + + /// \brief A component that stores temperature linear resolution in Kelvin + using TemperatureLinearResolution = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.TemperatureLinearResolution", + TemperatureLinearResolution) } } } diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 600744db97..5d64553867 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -66,6 +66,12 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \return Pointer to the scene public: rendering::ScenePtr Scene() const; + /// \brief Helper Update function for updating the scene + /// \param[in] _info Sim update info + /// \param[in] _ecm Mutable reference to the entity component manager + public: void UpdateECM(const UpdateInfo &_info, + EntityComponentManager &_ecm); + /// \brief Helper PostUpdate function for updating the scene public: void UpdateFromECM(const UpdateInfo &_info, const EntityComponentManager &_ecm); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 563078231a..c1c507713b 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -262,6 +262,12 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of created collision entities and if they are currently /// visible public: std::map viewingCollisions; + + /// \brief A map of entity id to thermal camera sensor configuration + /// properties. The elements in the tuple are: + /// + public:std::unordered_map> thermalCameraData; }; ////////////////////////////////////////////////// @@ -278,6 +284,53 @@ rendering::ScenePtr RenderUtil::Scene() const return this->dataPtr->scene; } +////////////////////////////////////////////////// +void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) +{ + std::lock_guard lock(this->dataPtr->updateMutex); + // Update thermal cameras + _ecm.Each( + [&](const Entity &_entity, + const components::ThermalCamera *)->bool + { + // set properties from thermal sensor plugin + // Set defaults to invaid values so we know they have not been set. + // set UpdateECM(). We check for valid values first before setting + // these thermal camera properties.. + double resolution = 0.0; + components::TemperatureRangeInfo range; + range.min = std::numeric_limits::max(); + range.max = 0; + + // resolution + auto resolutionComp = + _ecm.Component(_entity); + if (resolutionComp != nullptr) + { + resolution = resolutionComp->Data(); + _ecm.RemoveComponent( + _entity); + } + + // min / max temp + auto tempRangeComp = + _ecm.Component(_entity); + if (tempRangeComp != nullptr) + { + range = tempRangeComp->Data(); + _ecm.RemoveComponent(_entity); + } + + if (resolutionComp || tempRangeComp) + { + this->dataPtr->thermalCameraData[_entity] = + std::make_tuple(resolution, range); + } + return true; + }); +} + ////////////////////////////////////////////////// void RenderUtil::UpdateFromECM(const UpdateInfo &_info, const EntityComponentManager &_ecm) @@ -367,6 +420,7 @@ void RenderUtil::Update() auto actorAnimationData = std::move(this->dataPtr->actorAnimationData); auto entityTemp = std::move(this->dataPtr->entityTemp); auto newCollisionLinks = std::move(this->dataPtr->newCollisionLinks); + auto thermalCameraData = std::move(this->dataPtr->thermalCameraData); this->dataPtr->newScenes.clear(); this->dataPtr->newModels.clear(); @@ -381,6 +435,7 @@ void RenderUtil::Update() this->dataPtr->actorAnimationData.clear(); this->dataPtr->entityTemp.clear(); this->dataPtr->newCollisionLinks.clear(); + this->dataPtr->thermalCameraData.clear(); this->dataPtr->markerManager.Update(); @@ -734,6 +789,44 @@ void RenderUtil::Update() } } } + + // update thermal camera + for (const auto &thermal : this->dataPtr->thermalCameraData) + { + Entity id = thermal.first; + rendering::ThermalCameraPtr camera = + std::dynamic_pointer_cast( + this->dataPtr->sceneManager.NodeById(id)); + if (camera) + { + double resolution = std::get<0>(thermal.second); + + if (resolution > 0.0) + { + camera->SetLinearResolution(resolution); + } + else + { + ignwarn << "Unable to set thermal camera temperature linear resolution." + << " Value must be greater than 0. Using the default value: " + << camera->LinearResolution() << ". " << std::endl; + } + double minTemp = std::get<1>(thermal.second).min.Kelvin(); + double maxTemp = std::get<1>(thermal.second).max.Kelvin(); + if (maxTemp >= minTemp) + { + camera->SetMinTemperature(minTemp); + camera->SetMaxTemperature(maxTemp); + } + else + { + ignwarn << "Unable to set thermal camera temperature range." + << "Max temperature must be greater or equal to min. " + << "Using the default values : [" << camera->MinTemperature() + << ", " << camera->MaxTemperature() << "]." << std::endl; + } + } + } } ////////////////////////////////////////////////// @@ -1062,6 +1155,31 @@ void RenderUtilPrivate::CreateRenderingEntities( visual.SetMaterial(material->Data()); } + if (auto temp = _ecm.Component(_entity)) + { + // get the uniform temperature for the entity + this->entityTemp[_entity] = + std::make_tuple( + temp->Data().Kelvin(), 0.0, ""); + } + else + { + // entity doesn't have a uniform temperature. Check if it has + // a heat signature with an associated temperature range + auto heatSignature = + _ecm.Component(_entity); + auto tempRange = + _ecm.Component(_entity); + if (heatSignature && tempRange) + { + this->entityTemp[_entity] = + std::make_tuple( + tempRange->Data().min.Kelvin(), + tempRange->Data().max.Kelvin(), + std::string(heatSignature->Data())); + } + } + this->newVisuals.push_back( std::make_tuple(_entity, visual, _parent->Data())); return true; diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 20a929854d..93d14fb354 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -412,6 +412,17 @@ void Sensors::Configure(const Entity &/*_id*/, this->dataPtr->Run(); } +////////////////////////////////////////////////// +void Sensors::Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) +{ + IGN_PROFILE("Sensors::Update"); + if (this->dataPtr->running && this->dataPtr->initialized) + { + this->dataPtr->renderUtil.UpdateECM(_info, _ecm); + } +} + ////////////////////////////////////////////////// void Sensors::PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) @@ -592,6 +603,7 @@ std::string Sensors::CreateSensor(const Entity &_entity, IGNITION_ADD_PLUGIN(Sensors, System, Sensors::ISystemConfigure, + Sensors::ISystemUpdate, Sensors::ISystemPostUpdate ) diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index b295159cf8..3ee5807268 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -42,6 +42,7 @@ namespace systems class IGNITION_GAZEBO_VISIBLE Sensors: public System, public ISystemConfigure, + public ISystemUpdate, public ISystemPostUpdate { /// \brief Constructor @@ -56,6 +57,10 @@ namespace systems EntityComponentManager &_ecm, EventManager &_eventMgr) final; + // Documentation inherited + public: void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) final; + // Documentation inherited public: void PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) final; diff --git a/src/systems/thermal/CMakeLists.txt b/src/systems/thermal/CMakeLists.txt index ff3e7aa265..c6d6dfc3ba 100644 --- a/src/systems/thermal/CMakeLists.txt +++ b/src/systems/thermal/CMakeLists.txt @@ -5,3 +5,9 @@ gz_add_system(thermal ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} ) +gz_add_system(thermal-sensor + SOURCES + ThermalSensor.cc + PUBLIC_LINK_LIBS + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} +) diff --git a/src/systems/thermal/ThermalSensor.cc b/src/systems/thermal/ThermalSensor.cc new file mode 100644 index 0000000000..72e5f60a45 --- /dev/null +++ b/src/systems/thermal/ThermalSensor.cc @@ -0,0 +1,93 @@ +/* + * 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 "ThermalSensor.hh" + +#include +#include + +#include +#include + +#include "ignition/gazebo/components/ThermalCamera.hh" +#include "ignition/gazebo/components/Temperature.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" +#include "ignition/gazebo/EntityComponentManager.hh" +#include "ignition/gazebo/Util.hh" + +using namespace ignition; +using namespace gazebo; +using namespace systems; + +/// \brief Private Thermal sensor data class. +class ignition::gazebo::systems::ThermalSensorPrivate +{ +}; + +////////////////////////////////////////////////// +ThermalSensor::ThermalSensor() : System(), + dataPtr(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +ThermalSensor::~ThermalSensor() = default; + +////////////////////////////////////////////////// +void ThermalSensor::Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + gazebo::EntityComponentManager &_ecm, + gazebo::EventManager & /*_eventMgr*/) +{ + const std::string resolutionTag = "resolution"; + const std::string minTempTag = "min_temp"; + const std::string maxTempTag = "max_temp"; + + auto sensorComp = _ecm.Component(_entity); + if (sensorComp == nullptr) + { + ignerr << "The thermal sensor system can only be used to configure " + << "parameters of thermal camera sensor " << std::endl; + return; + } + + if (_sdf->HasElement(resolutionTag)) + { + double resolution = _sdf->Get(resolutionTag); + _ecm.CreateComponent(_entity, + components::TemperatureLinearResolution(resolution)); + } + + if (_sdf->HasElement(minTempTag) || _sdf->HasElement(maxTempTag)) + { + double min = 0.0; + double max = std::numeric_limits::max(); + min = _sdf->Get(minTempTag, min).first; + max = _sdf->Get(maxTempTag, max).first; + components::TemperatureRangeInfo rangeInfo; + rangeInfo.min = min; + rangeInfo.max = max; + _ecm.CreateComponent(_entity, components::TemperatureRange(rangeInfo)); + } +} + +IGNITION_ADD_PLUGIN(ThermalSensor, System, + ThermalSensor::ISystemConfigure +) + +IGNITION_ADD_PLUGIN_ALIAS(ThermalSensor, + "ignition::gazebo::systems::ThermalSensor") diff --git a/src/systems/thermal/ThermalSensor.hh b/src/systems/thermal/ThermalSensor.hh new file mode 100644 index 0000000000..ed2fb431f2 --- /dev/null +++ b/src/systems/thermal/ThermalSensor.hh @@ -0,0 +1,60 @@ +/* + * 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_SYSTEMS_THERMALSENSOR_HH_ +#define IGNITION_GAZEBO_SYSTEMS_THERMALSENSOR_HH_ + +#include +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems +{ + // Forward declarations. + class ThermalSensorPrivate; + + /// \brief A thermal sensor plugin for configuring thermal sensor properties + class IGNITION_GAZEBO_VISIBLE ThermalSensor: + public System, + public ISystemConfigure + { + /// \brief Constructor + public: explicit ThermalSensor(); + + /// \brief Destructor + public: ~ThermalSensor() override; + + /// Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + gazebo::EventManager &_eventMgr) final; + + /// \brief Private data pointer. + private: std::unique_ptr dataPtr; + }; + } +} +} +} +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index a2e4eb484f..5e2233fbd0 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -42,7 +42,6 @@ set(tests scene_broadcaster_system.cc sdf_frame_semantics.cc sdf_include.cc - thermal_system.cc touch_plugin.cc triggered_publisher.cc user_commands.cc @@ -60,6 +59,8 @@ set(tests_needing_display gpu_lidar.cc rgbd_camera.cc sensors_system.cc + thermal_system.cc + thermal_sensor_system.cc ) # Add systems that need a valid display here. diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc new file mode 100644 index 0000000000..472a8a60ff --- /dev/null +++ b/test/integration/thermal_sensor_system.cc @@ -0,0 +1,219 @@ +/* + * 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 "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/Temperature.hh" +#include "ignition/gazebo/components/TemperatureRange.hh" +#include "ignition/gazebo/components/ThermalCamera.hh" +#include "ignition/gazebo/components/Visual.hh" +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/SystemLoader.hh" +#include "ignition/gazebo/test_config.hh" + +#include "../helpers/Relay.hh" + +using namespace ignition; +using namespace gazebo; + +/// \brief Test Thermal system +class ThermalSensorTest : public ::testing::Test +{ + // Documentation inherited + protected: void SetUp() override + { + common::Console::SetVerbosity(4); + setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + } +}; + + +std::mutex g_mutex; +std::vector g_imageMsgs; +unsigned char *g_image = nullptr; + +///////////////////////////////////////////////// +void thermalCb(const msgs::Image &_msg) +{ + std::lock_guard g_lock(g_mutex); + g_imageMsgs.push_back(_msg); + + unsigned int width = _msg.width(); + unsigned int height = _msg.height(); + unsigned int size = width * height * sizeof(unsigned char); + if (!g_image) + { + g_image = new unsigned char[size]; + } + memcpy(g_image, _msg.data().c_str(), size); +} + +///////////////////////////////////////////////// +TEST_F(ThermalSensorTest, + IGN_UTILS_TEST_DISABLED_ON_MAC(ThermalSensorSystemInvalidConfig)) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, + "test/worlds/thermal_invalid.sdf")); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system that checks for thermal component + test::Relay testSystem; + + double resolution = 0; + double minTemp = std::numeric_limits::max(); + double maxTemp = 0.0; + std::map entityTemp; + std::string name; + sdf::Sensor sensorSdf; + + testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &_id, + const components::Temperature *_temp, + const components::Name *_name) -> bool + { + // store temperature data + entityTemp[_name->Data()] = _temp->Data(); + + // verify temperature data belongs to a visual + EXPECT_NE(nullptr, _ecm.Component(_id)); + + return true; + }); + }); + testSystem.OnUpdate([&](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &_id, + const components::ThermalCamera *_sensor, + const components::Name *_name) -> bool + { + // store temperature data + sensorSdf = _sensor->Data(); + name = _name->Data(); + + auto resolutionComp = + _ecm.Component( + _id); + if (resolutionComp) + resolution = resolutionComp->Data(); + + auto temperatureRangeComp = + _ecm.Component(_id); + if (temperatureRangeComp) + { + auto info = temperatureRangeComp->Data(); + minTemp = info.min.Kelvin(); + maxTemp = info.max.Kelvin(); + } + return true; + }); + }); + + server.AddSystem(testSystem.systemPtr); + + // subscribe to thermal topic + transport::Node node; + node.Subscribe("/thermal_camera_invalid/image", &thermalCb); + + // Run server + server.Run(true, 1, false); + + // verify camera properties from sdf + unsigned int width = 320u; + unsigned int height = 240u; + EXPECT_EQ("thermal_camera_invalid", name); + const sdf::Camera *cameraSdf = sensorSdf.CameraSensor(); + ASSERT_NE(nullptr, cameraSdf); + EXPECT_EQ(width, cameraSdf->ImageWidth()); + EXPECT_EQ(height, cameraSdf->ImageHeight()); + EXPECT_EQ(sdf::PixelFormatType::L_INT8, cameraSdf->PixelFormat()); + + // verify camera properties set through plugin + // the resolution, min and max are invalid range values. Ign-gazebo should + // print out warnings and use default values + EXPECT_DOUBLE_EQ(0.0, resolution); + EXPECT_DOUBLE_EQ(999.0, minTemp); + EXPECT_DOUBLE_EQ(-590.0, maxTemp); + + // verify temperature of heat source + const std::string sphereVisual = "sphere_visual"; + const std::string cylinderVisual = "cylinder_visual"; + EXPECT_EQ(2u, entityTemp.size()); + ASSERT_TRUE(entityTemp.find(sphereVisual) != entityTemp.end()); + ASSERT_TRUE(entityTemp.find(cylinderVisual) != entityTemp.end()); + EXPECT_DOUBLE_EQ(600.0, entityTemp[sphereVisual].Kelvin()); + // the user specified temp is larger than the max value representable by an + // 8 bit 3 degree resolution camera - this value should be clamped + EXPECT_DOUBLE_EQ(800.0, entityTemp[cylinderVisual].Kelvin()); + + // Run server + server.Run(true, 10, false); + + // wait for image + bool received = false; + for (unsigned int i = 0; i < 20; ++i) + { + { + std::lock_guard lock(g_mutex); + received = !g_imageMsgs.empty(); + } + if (received) + break; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + EXPECT_TRUE(received); + + // check temperature in actual image output + { + std::lock_guard lock(g_mutex); + unsigned int leftIdx = height * 0.5 * width; + unsigned int rightIdx = leftIdx + width-1; + unsigned int defaultResolution = 3u; + unsigned int cylinderTemp = g_image[leftIdx] * defaultResolution; + unsigned int sphereTemp = g_image[rightIdx] * defaultResolution; + // default resolution, min, max values used so we should get correct + // temperature value + EXPECT_EQ(600u, sphereTemp); + // 8 bit 3 degree resolution camera - this value should be clamped + // in the image output to: + // 2^(bitDepth) - 1 * resolution = 2^8 - 1 * 3 = 765 + EXPECT_EQ(765u, cylinderTemp); + } + + g_imageMsgs.clear(); + delete [] g_image; + g_image = nullptr; +} diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index 211f06b28d..25b8a98bb0 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -16,14 +16,21 @@ */ #include + +#include +#include + #include +#include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/SourceFilePath.hh" #include "ignition/gazebo/components/Temperature.hh" #include "ignition/gazebo/components/TemperatureRange.hh" +#include "ignition/gazebo/components/ThermalCamera.hh" #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -47,7 +54,7 @@ class ThermalTest : public ::testing::Test }; ///////////////////////////////////////////////// -TEST_F(ThermalTest, TemperatureComponent) +TEST_F(ThermalTest, IGN_UTILS_TEST_DISABLED_ON_MAC(TemperatureComponent)) { // Start server ServerConfig serverConfig; @@ -169,3 +176,70 @@ TEST_F(ThermalTest, TemperatureComponent) EXPECT_TRUE(heatSignatures[heatSignatureSphereVisual2].find( heatSignatureTestResource) != std::string::npos); } + +///////////////////////////////////////////////// +TEST_F(ThermalTest, IGN_UTILS_TEST_DISABLED_ON_MAC(ThermalSensorSystem)) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, + "test/worlds/thermal.sdf")); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system that checks for thermal component + test::Relay testSystem; + + double resolution = 0; + double minTemp = std::numeric_limits::max(); + double maxTemp = 0.0; + std::string name; + sdf::Sensor sensorSdf; + testSystem.OnUpdate([&](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &_id, + const components::ThermalCamera *_sensor, + const components::Name *_name) -> bool + { + // store temperature data + sensorSdf = _sensor->Data(); + name = _name->Data(); + + auto resolutionComp = + _ecm.Component( + _id); + EXPECT_NE(nullptr, resolutionComp); + resolution = resolutionComp->Data(); + + auto temperatureRangeComp = + _ecm.Component(_id); + EXPECT_NE(nullptr, temperatureRangeComp); + auto info = temperatureRangeComp->Data(); + minTemp = info.min.Kelvin(); + maxTemp = info.max.Kelvin(); + return true; + }); + + }); + server.AddSystem(testSystem.systemPtr); + + // Run server + server.Run(true, 1, false); + + // verify camera properties from sdf + EXPECT_EQ("thermal_camera_8bit", name); + const sdf::Camera *cameraSdf = sensorSdf.CameraSensor(); + ASSERT_NE(nullptr, cameraSdf); + EXPECT_EQ(320u, cameraSdf->ImageWidth()); + EXPECT_EQ(240u, cameraSdf->ImageHeight()); + EXPECT_EQ(sdf::PixelFormatType::L_INT8, cameraSdf->PixelFormat()); + + // verify camera properties set through plugin + EXPECT_DOUBLE_EQ(3.0, resolution); + EXPECT_DOUBLE_EQ(253.15, minTemp); + EXPECT_DOUBLE_EQ(673.15, maxTemp); +} diff --git a/test/worlds/thermal.sdf b/test/worlds/thermal.sdf index 73cc58c228..5274b749b0 100644 --- a/test/worlds/thermal.sdf +++ b/test/worlds/thermal.sdf @@ -309,5 +309,51 @@ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy + + 4.5 0 0.5 0.0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + L8 + + + 0.1 + 100 + + + 1 + 30 + true + thermal_camera_8bit/image + + 253.15 + 673.15 + 3.0 + + + + true + diff --git a/test/worlds/thermal_invalid.sdf b/test/worlds/thermal_invalid.sdf new file mode 100644 index 0000000000..89c621b9c9 --- /dev/null +++ b/test/worlds/thermal_invalid.sdf @@ -0,0 +1,152 @@ + + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + -0.5 0.1 -0.9 + + + + 310 + + + + true` + 0 0.5 0.5 0 0 0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + 600.0 + + + + + + + true` + 0 -0.5 0.5 0 0 0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + 800.0 + + + + + + + 1.0 0 0.5 0.0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + L8 + + + 0.1 + 100 + + + 1 + 30 + true + thermal_camera_invalid/image + + 999 + -590 + 0.0 + + + + true + + + From d959c41136713b7f9dc48aee92ac6a8726116976 Mon Sep 17 00:00:00 2001 From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> Date: Wed, 10 Feb 2021 21:42:23 -0500 Subject: [PATCH 32/55] 4.4.0 (#625) * 4.4.0 Signed-off-by: Ashton Larkin * fix typo Signed-off-by: Ian Chen Co-authored-by: Ian Chen --- CMakeLists.txt | 2 +- Changelog.md | 17 +++++++++++++++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d9ceb3e6fa..f11b8106de 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo4 VERSION 4.3.0) +project(ignition-gazebo4 VERSION 4.4.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 8a76252c42..5e7fc77a9b 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,22 @@ ## Ignition Gazebo 4.x +### Ignition Gazebo 4.4.0 (2020-02-10) + +1. Added issue and PR templates + * [Pull Request 613](https://github.com/ignitionrobotics/ign-gazebo/pull/613) + +1. Fix segfault in SetRemovedComponentsMsgs method + * [Pull Request 495](https://github.com/ignitionrobotics/ign-gazebo/pull/495) + +1. Make topics configurable for joint controllers + * [Pull Request 584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + +1. Add about dialog + * [Pull Request 609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + +1. Add thermal sensor system for configuring thermal camera properties + * [Pull Request 614](https://github.com/ignitionrobotics/ign-gazebo/pull/614) + ### Ignition Gazebo 4.3.0 (2020-02-02) 1. Non-blocking paths request. From 14cc8370f052bf5139018d472914491cf6fef3a4 Mon Sep 17 00:00:00 2001 From: Andrej Orsula Date: Thu, 11 Feb 2021 19:50:34 +0100 Subject: [PATCH 33/55] Add JointTrajectoryController system plugin (#473) Signed-off-by: Andrej Orsula Co-authored-by: Louise Poubel --- CMakeLists.txt | 2 +- .../worlds/joint_trajectory_controller.sdf | 722 +++++++++++ src/systems/CMakeLists.txt | 1 + .../CMakeLists.txt | 7 + .../JointTrajectoryController.cc | 1067 +++++++++++++++++ .../JointTrajectoryController.hh | 164 +++ test/integration/CMakeLists.txt | 1 + .../joint_trajectory_controller_system.cc | 399 ++++++ test/worlds/joint_trajectory_controller.sdf | 420 +++++++ 9 files changed, 2782 insertions(+), 1 deletion(-) create mode 100644 examples/worlds/joint_trajectory_controller.sdf create mode 100644 src/systems/joint_trajectory_controller/CMakeLists.txt create mode 100644 src/systems/joint_trajectory_controller/JointTrajectoryController.cc create mode 100644 src/systems/joint_trajectory_controller/JointTrajectoryController.hh create mode 100644 test/integration/joint_trajectory_controller_system.cc create mode 100644 test/worlds/joint_trajectory_controller.sdf diff --git a/CMakeLists.txt b/CMakeLists.txt index f11b8106de..b616eadfec 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -53,7 +53,7 @@ set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR}) #-------------------------------------- # Find ignition-msgs -ign_find_package(ignition-msgs6 REQUIRED) +ign_find_package(ignition-msgs6 REQUIRED VERSION 6.2) set(IGN_MSGS_VER ${ignition-msgs6_VERSION_MAJOR}) #-------------------------------------- diff --git a/examples/worlds/joint_trajectory_controller.sdf b/examples/worlds/joint_trajectory_controller.sdf new file mode 100644 index 0000000000..29b68f69a5 --- /dev/null +++ b/examples/worlds/joint_trajectory_controller.sdf @@ -0,0 +1,722 @@ + + + + + + + + + + + + + 0.4 0.4 0.4 + false + + + + + + + + + + 3D View + false + docked + + ogre + scene + 1 0 0 0 0 3.1416 + + + + + + World control + false + false + 50 + 100 + 1 + floating + + + + + + true + true + true + + + + + + World stats + false + false + 250 + 110 + 1 + floating + + + + + + true + true + true + true + + + + + + + + false + 5 5 5 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -1 -1 -1 + + + + + + + -0.1 0 0 0 1.5708 0 + true + + + + + 0 0 1 + 5 5 + + + + 0.5 0.5 0.5 1 + 0.5 0.5 0.5 1 + + + + + + + + + 0 0 0.25 -2.3561945 0 0 + + + world + RR_position_control_link0 + + + + + + + 0.025 + + + + + + + 0.025 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.0125 + + + + + + + 0.01 + 0.2 + + + + 0.5 0 0 1 + 0.8 0 0 1 + 0.8 0 0 1 + + + + 0 0 0.2 0 0 0 + + + 0.0125 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.01 + 0.2 + + + + 0.5 0 0 1 + 0.8 0 0 1 + 0.8 0 0 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + + 0 0 0 0 0 0 + RR_position_control_link0 + RR_position_control_link1 + + 1 0 0 + + 0.5 + + + + + 0 0 0.1 0 0 0 + RR_position_control_link1 + RR_position_control_link2 + + 1 0 0 + + 0.25 + + + + + + RR_position_control_joint1 + 0.7854 + 20 + 0.4 + 1.0 + -1 + 1 + -20 + 20 + + RR_position_control_joint2 + -1.5708 + 10 + 0.2 + 0.5 + -1 + 1 + -10 + 10 + + + + + + + 0 -0.5 -0.25 0 0 0 + + + world + RR_velocity_control_link0 + + + + + + + 0.025 + + + + + + + 0.025 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.0125 + + + + + + + 0.01 + 0.2 + + + + 0 0.5 0 1 + 0 0.8 0 1 + 0 0.8 0 1 + + + + 0 0 0.2 0 0 0 + + + 0.0125 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.01 + 0.2 + + + + 0 0.5 0 1 + 0 0.8 0 1 + 0 0.8 0 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + + 0 0 0 0 0 0 + RR_velocity_control_link0 + RR_velocity_control_link1 + + 1 0 0 + + + 0.02 + + + + 0 0 0.1 0 0 0 + RR_velocity_control_link1 + RR_velocity_control_link2 + + 1 0 0 + + + 0.01 + + + + + + 0.6 + 175 + -10 + 10 + + 0.1 + 200 + -5 + 5 + + + + + + + 0 0.5 -0.25 -0.7854 0 0 + + + world + RR_effort_control_link0 + + + + + + + 0.025 + + + + + + + 0.025 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.0125 + + + + + + + 0.01 + 0.2 + + + + 0 0 0.5 1 + 0 0 0.8 1 + 0 0 0.8 1 + + + + 0 0 0.2 0 0 0 + + + 0.0125 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.01 + 0.2 + + + + 0 0 0.5 1 + 0 0 0.8 1 + 0 0 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + + 0 0 0 0 0 0 + RR_effort_control_link0 + RR_effort_control_link1 + + 1 0 0 + + 0.02 + + + + + 0 0 0.1 0 0 0 + RR_effort_control_link1 + RR_effort_control_link2 + + 1 0 0 + + 0.01 + + + + + + + custom_topic_effort_control + + + + + diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index d8b61a4056..07b88dfba4 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -86,6 +86,7 @@ add_subdirectory(imu) add_subdirectory(joint_controller) add_subdirectory(joint_position_controller) add_subdirectory(joint_state_publisher) +add_subdirectory(joint_trajectory_controller) add_subdirectory(kinetic_energy_monitor) add_subdirectory(lift_drag) add_subdirectory(log) diff --git a/src/systems/joint_trajectory_controller/CMakeLists.txt b/src/systems/joint_trajectory_controller/CMakeLists.txt new file mode 100644 index 0000000000..c4150b372e --- /dev/null +++ b/src/systems/joint_trajectory_controller/CMakeLists.txt @@ -0,0 +1,7 @@ +gz_add_system(joint-trajectory-controller + SOURCES + JointTrajectoryController.cc + PUBLIC_LINK_LIBS + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} + ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} +) diff --git a/src/systems/joint_trajectory_controller/JointTrajectoryController.cc b/src/systems/joint_trajectory_controller/JointTrajectoryController.cc new file mode 100644 index 0000000000..d7cb345e60 --- /dev/null +++ b/src/systems/joint_trajectory_controller/JointTrajectoryController.cc @@ -0,0 +1,1067 @@ +/* + * 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 + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "JointTrajectoryController.hh" + +using namespace ignition; +using namespace gazebo; +using namespace systems; + +/// \brief Helper class that contains all parameters required to create and +/// configure an instance of ActuatedJoint +class JointParameters +{ + /// \brief Parse all parameters required for creation of ActuatedJoint and + /// return them in a map + /// \param[in] _sdf SDF reference used to obtain the parameters + /// \param[in] _ecm Ignition Entity Component Manager + /// \param[in] _enabledJoints List of joint entities that are enabled and + /// need to be created + /// \return Map of parameters for each joint, the first entry of pair + /// indicates the joint name + public: static std::map ParseAll( + const std::shared_ptr &_sdf, + ignition::gazebo::EntityComponentManager &_ecm, + std::vector _enabledJoints); + + /// \brief Parse all values of a single parameter that is specified multiple + /// times in SDF + /// \param[in] _sdf SDF reference used to obtain the parameters + /// \param[in] _parameterName Name of the repeated parameter to parse all + /// values for + /// \return Ordered list of all values for a given repeated parameter + public: template static std::vector Parse( + const std::shared_ptr &_sdf, + const std::string &_parameterName); + + /// \brief Return value from `_vec` at `_index`, or `_alternative_value` if + /// `_vec` is not large enough + /// \param[in] _vec Vector that contains desired value of type T + /// \param[in] _index Index at which the value is stored + /// \param[in] _alternative_value Alternative or default value of type T + /// \return Value from `_vec` at `_index`, or `_alternative_value` if `_vec` + /// is not large enough + public: template static T NthElementOr( + const std::vector &_vec, + const size_t &_index, + const T &_alternative_value); + + /// \brief Initial position of the joint + public: double initialPosition; + /// \brief Default value for initial position of the joint + public: static constexpr double initialPositionDefault = 0.0; + + /// \brief Parameters required for creation of new PID controller + public: struct PID + { + /// \brief Proportional gain + double pGain; + /// \brief Default value for proportional gain + static constexpr double pGainDefault = 0.0; + + /// \brief Integral gain + double iGain; + /// \brief Default value for integral gain + static constexpr double iGainDefault = 0.0; + + /// \brief Derivative gain + double dGain; + /// \brief Default value for derivative gain + static constexpr double dGainDefault = 0.0; + + /// \brief Integral lower limit + double iMin; + /// \brief Default value for integral lower limit + static constexpr double iMinDefault = 0.0; + + /// \brief Integral upper limit + double iMax; + /// \brief Default value for integral upper limit + static constexpr double iMaxDefault = -1.0; + + /// \brief Output min value + double cmdMin; + /// \brief Default value for output min value + static constexpr double cmdMinDefault = 0.0; + + /// \brief Output max value + double cmdMax; + /// \brief Default value for output max value + static constexpr double cmdMaxDefault = -1.0; + + /// \brief Output offset + double cmdOffset; + /// \brief Default value for output offset + static constexpr double cmdOffsetDefault = 0.0; + } positionPID, velocityPID; +}; + +/// \brief A single 1-axis joint that is controlled by JointTrajectoryController +/// plugin +class ActuatedJoint +{ + /// \brief Default contructor + public: ActuatedJoint() = default; + + /// \brief Constructor that properly configures the actuated joint + /// \param[in] _entity Entity of the joint + /// \param[in] _params All parameters of the joint required for its + /// configuration + public: ActuatedJoint(const Entity &_entity, + const JointParameters &_params); + + /// \brief Setup components required for control of this joint + /// \param[in,out] _ecm Ignition Entity Component Manager + public: void SetupComponents( + ignition::gazebo::EntityComponentManager &_ecm) const; + + /// \brief Set target of the joint that the controller will attempt to reach + /// \param[in] _targetPoint Targets of all controlled joint + /// \param[in] _jointIndex Index of the joint, used to determine what index + /// of `_targetPoint` to use + public: void SetTarget( + const ignition::msgs::JointTrajectoryPoint &_targetPoint, + const size_t &_jointIndex); + + /// \brief Update command force that is applied on the joint + /// \param[in,out] _ecm Ignition Entity Component Manager + /// \param[in] _dt Time difference to update for + public: void Update(ignition::gazebo::EntityComponentManager &_ecm, + const std::chrono::steady_clock::duration &_dt); + + /// \brief Reset the target of the joint + public: void ResetTarget(); + + /// \brief Reset the position and velocity PID error on the joint + public: void ResetPIDs(); + + /// \brief Entity of the joint + public: Entity entity; + + /// \brief Target state that the joint controller should reach + public: struct TargetState + { + /// \brief Target position of the joint + double position; + /// \brief Target position of the joint + double velocity; + /// \brief Target acceleration of the joint + /// \attention Acceleration control is NOT implemented at the moment + double acceleration; + /// \brief Target force or torque of the joint + double effort; + } target; + + /// \brief Initial position of the joint + public: double initialPosition; + + /// \brief List of PID controllers used for the control of this actuated joint + public: struct PIDs + { + /// \brief Position PID controller + ignition::math::PID position; + /// \brief Velocity PID controller + ignition::math::PID velocity; + } pids; +}; + +/// \brief Information about trajectory that is followed by +/// JointTrajectoryController plugin +class Trajectory +{ + /// \brief Update index of trajectory points, such that it directs to a point + /// that needs to be currently followed + /// \param[in] _simTime Current simulation time + /// \return True if index of the trajectory point was updated, False otherwise + public: bool UpdateCurrentPoint( + const std::chrono::steady_clock::duration &_simTime); + + /// \brief Determine if the trajectory goal was reached + /// \return True if trajectory goal was reached, False otherwise + public: bool IsGoalReached() const; + + /// \brief Compute progress of the current trajectory + /// \return Fraction of the completed points in range (0.0, 1.0] + public: float ComputeProgress() const; + + /// \brief Reset trajectory internals, i.e. clean list of joint names, points + /// and reset index of the current point + public: void Reset(); + + /// \brief Status of the trajectory + public: enum TrajectoryStatus + { + /// \brief Trajectory is new and needs to be configure on the next update + /// loop + New, + /// \brief Trajectory is currently being followed + Active, + /// \brief Trajectory goal is reached + Reached, + } status; + + /// \brief Start time of trajectory + public: std::chrono::steady_clock::duration startTime; + + /// \brief Index of the current trajectory point + public: unsigned int pointIndex; + + /// \brief Ordered joints that need to be actuated to follow the current + /// trajectory + public: std::vector jointNames; + + /// \brief Trajectory defined in terms of temporal points, whose members are + /// ordered according to `jointNames` + public: std::vector points; +}; + +/// \brief Private data of the JointTrajectoryController plugin +class ignition::gazebo::systems::JointTrajectoryControllerPrivate +{ + /// \brief Get a list of enabled, unique, 1-axis joints of the model. If no + /// joint names are specified in the plugin configuration, all valid 1-axis + /// joints are returned + /// \param[in] _entity Entity of the model that the plugin is being + /// configured for + /// \param[in] _sdf SDF reference used to determine enabled joints + /// \param[in] _ecm Ignition Entity Component Manager + /// \return List of entities containinig all enabled joints + public: std::vector GetEnabledJoints( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm) const; + + /// \brief Callback for joint trajectory subscription + /// \param[in] _msg A new message describing a joint trajectory that needs + /// to be followed + public: void JointTrajectoryCallback( + const ignition::msgs::JointTrajectory &_msg); + + /// \brief Reset internals of the plugin, without affecting already created + /// components + public: void Reset(); + + /// \brief Ignition communication node + public: transport::Node node; + + /// \brief Publisher of the progress for currently followed trajectory + public: transport::Node::Publisher progressPub; + + /// \brief Map of actuated joints, where the first entry of pair is the name + /// of the joint + public: std::map actuatedJoints; + + /// \brief Mutex projecting trajectory + public: std::mutex trajectoryMutex; + + /// \brief Information about trajectory that should be followed + public: Trajectory trajectory; + + /// \brief Flag that determines whether to use message header timestamp as + /// the trajectory start, where simulation time at the beginning of execution + /// is used otherwise + public: bool useHeaderStartTime; + + /// \brief Flag that determines if all components required for control are + /// already setup + public: bool componentSetupFinished; +}; + +///////////////////////////////// +/// JointTrajectoryController /// +///////////////////////////////// + +////////////////////////////////////////////////// +JointTrajectoryController::JointTrajectoryController() + : dataPtr(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +void JointTrajectoryController::Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager & /*_eventManager*/) +{ + // Make sure the controller is attached to a valid model + const auto model = Model(_entity); + if (!model.Valid(_ecm)) + { + ignerr << "[JointTrajectoryController] Failed to initialize because [" + << model.Name(_ecm) << "(Entity=" << _entity + << ")] is not a model. Please make sure that" + " JointTrajectoryController is attached to a valid model.\n"; + return; + } + ignmsg << "[JointTrajectoryController] Setting up controller for [" + << model.Name(_ecm) << "(Entity=" << _entity << ")].\n"; + + // Get list of enabled joints + const auto enabledJoints = this->dataPtr->GetEnabledJoints(_entity, + _sdf, + _ecm); + + // For each enabled joint, parse all of its parameters from SDF + auto jointParameters = JointParameters::ParseAll(_sdf, _ecm, enabledJoints); + + // Iterate over all enabled joints and create/configure them + for (const auto &jointEntity : enabledJoints) + { + const auto jointName = + _ecm.Component(jointEntity)->Data(); + this->dataPtr->actuatedJoints[jointName] = + ActuatedJoint(jointEntity, jointParameters[jointName]); + ignmsg << "[JointTrajectoryController] Configured joint [" + << jointName << "(Entity=" << jointEntity << ")].\n"; + } + + // Make sure at least one joint is configured + if (this->dataPtr->actuatedJoints.empty()) + { + ignerr << "[JointTrajectoryController] Failed to initialize because [" + << model.Name(_ecm) << "(Entity=" << _entity + << ")] has no supported joints.\n"; + return; + } + + // Get additional parameters from SDF + if (_sdf->HasAttribute("use_header_start_time")) + { + this->dataPtr->useHeaderStartTime = + _sdf->Get("use_header_start_time"); + } + else + { + this->dataPtr->useHeaderStartTime = false; + } + + // Subscribe to joint trajectory commands + auto trajectoryTopic = _sdf->Get("topic"); + if (trajectoryTopic.empty()) + { + // If not specified, use the default topic based on model name + trajectoryTopic = "/model/" + model.Name(_ecm) + "/joint_trajectory"; + } + // Make sure the topic is valid + const auto validTrajectoryTopic = transport::TopicUtils::AsValidTopic( + trajectoryTopic); + if (validTrajectoryTopic.empty()) + { + ignerr << "[JointTrajectoryController] Cannot subscribe to invalid topic [" + << trajectoryTopic << "].\n"; + return; + } + // Subscribe + ignmsg << "[JointTrajectoryController] Subscribing to joint trajectory" + " commands on topic [" << validTrajectoryTopic << "].\n"; + this->dataPtr->node.Subscribe( + validTrajectoryTopic, + &JointTrajectoryControllerPrivate::JointTrajectoryCallback, + this->dataPtr.get()); + + // Advertise progress + const auto progressTopic = validTrajectoryTopic + "_progress"; + ignmsg << "[JointTrajectoryController] Advertising joint trajectory progress" + " on topic [" << progressTopic << "].\n"; + this->dataPtr->progressPub = + this->dataPtr->node.Advertise(progressTopic); +} + +////////////////////////////////////////////////// +void JointTrajectoryController::PreUpdate( + const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) +{ + IGN_PROFILE("JointTrajectoryController::PreUpdate"); + + // Create required components for each joint (only once) + if (!this->dataPtr->componentSetupFinished) + { + for (auto &actuatedJoint : this->dataPtr->actuatedJoints) + { + ActuatedJoint *joint = &actuatedJoint.second; + joint->SetupComponents(_ecm); + } + this->dataPtr->componentSetupFinished = true; + } + + // Reset plugin if jump back in time is detected + if (_info.dt < std::chrono::steady_clock::duration::zero()) + { + ignmsg << "[JointTrajectoryController] Resetting plugin because jump back" + " in time [" + << std::chrono::duration_cast(_info.dt).count() + << " s] was detected.\n"; + this->dataPtr->Reset(); + } + + // Nothing else to do if paused + if (_info.paused) + { + return; + } + + // Update joint targets based on the current trajectory + { + auto isTargetUpdateRequired = false; + + // Lock mutex before accessing trajectory + std::lock_guard lock(this->dataPtr->trajectoryMutex); + + if (this->dataPtr->trajectory.status == Trajectory::New) + { + // Set trajectory start time if not set before + if (this->dataPtr->trajectory.startTime.count() == 0) + { + this->dataPtr->trajectory.startTime = _info.simTime; + this->dataPtr->trajectory.status = Trajectory::Active; + } + + // If the new trajectory has no points, consider it reached + if (this->dataPtr->trajectory.points.empty()) + { + this->dataPtr->trajectory.status = Trajectory::Reached; + } + + // Update is always needed for a new trajectory + isTargetUpdateRequired = true; + } + + if (this->dataPtr->trajectory.status == Trajectory::Active) + { + // Determine what point needs to be reached at the current time + if (this->dataPtr->trajectory.UpdateCurrentPoint(_info.simTime)) + { + // Update is needed if point was updated + isTargetUpdateRequired = true; + } + } + + // Update the target for each joint that is defined in the + // trajectory, if needed + if (isTargetUpdateRequired && + this->dataPtr->trajectory.status != Trajectory::Reached) + { + const auto targetPoint = + this->dataPtr->trajectory.points[this->dataPtr->trajectory + .pointIndex]; + for (auto jointIndex = 0u; + jointIndex < this->dataPtr->trajectory.jointNames.size(); + ++jointIndex) + { + const auto jointName = this->dataPtr->trajectory.jointNames[jointIndex]; + if (this->dataPtr->actuatedJoints.count(jointName) == 0) + { + // Warning about unconfigured joint is already logged above + continue; + } + auto *joint = &this->dataPtr->actuatedJoints[jointName]; + joint->SetTarget(targetPoint, jointIndex); + } + + // If there are no more points after the current one, set the trajectory + // to Reached + if (this->dataPtr->trajectory.IsGoalReached()) + { + this->dataPtr->trajectory.status = Trajectory::Reached; + } + + // Publish current progress of the trajectory + ignition::msgs::Float progressMsg; + progressMsg.set_data(this->dataPtr->trajectory.ComputeProgress()); + this->dataPtr->progressPub.Publish(progressMsg); + } + } + + // Control loop + for (auto &actuatedJoint : this->dataPtr->actuatedJoints) + { + auto *joint = &actuatedJoint.second; + joint->Update(_ecm, _info.dt); + } +} + +//////////////////////////////////////// +/// JointTrajectoryControllerPrivate /// +//////////////////////////////////////// + +////////////////////////////////////////////////// +std::vector JointTrajectoryControllerPrivate::GetEnabledJoints( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm) const +{ + std::vector output; + + // Get list of user-enabled joint names. If empty, enable all 1-axis joints + const auto enabledJoints = JointParameters::Parse(_sdf, + "joint_name"); + + // Get list of joint entities of the model + // If there are joints explicitely enabled by the user, get only those + std::vector jointEntities; + if (!enabledJoints.empty()) + { + for (const auto &enabledJointName : enabledJoints) + { + auto enabledJointEntity = _ecm.ChildrenByComponents( + _entity, components::Joint(), components::Name(enabledJointName)); + // Check that model has exactly one joint that matches the name + if (enabledJointEntity.empty()) + { + ignerr << "[JointTrajectoryController] Model does not contain joint [" + << enabledJointName << "], which was explicitly enabled.\n"; + continue; + } + else if (enabledJointEntity.size() > 1) + { + ignwarn << "[JointTrajectoryController] Model has " + << enabledJointEntity.size() << " duplicate joints named [" + << enabledJointName << "]. Only the first (Entity=" + << enabledJointEntity[0] << ") will be configured.\n"; + } + // Add entity to the list of enabled joints + jointEntities.push_back(enabledJointEntity[0]); + } + } + else + { + jointEntities = _ecm.ChildrenByComponents(_entity, components::Joint()); + } + + // Iterate over all joints and verify whether they can be enabled or not + for (const auto &jointEntity : jointEntities) + { + const auto jointName = _ecm.Component( + jointEntity)->Data(); + + // Ignore duplicate joints + for (const auto &actuatedJoint : this->actuatedJoints) + { + if (actuatedJoint.second.entity == jointEntity) + { + ignwarn << "[JointTrajectoryController] Ignoring duplicate joint [" + << jointName << "(Entity=" << jointEntity << ")].\n"; + continue; + } + } + + // Make sure the joint type is supported, i.e. it has exactly one + // actuated axis + const auto *jointType = _ecm.Component(jointEntity); + switch (jointType->Data()) + { + case sdf::JointType::PRISMATIC: + case sdf::JointType::REVOLUTE: + case sdf::JointType::CONTINUOUS: + case sdf::JointType::GEARBOX: + { + // Supported joint type + break; + } + case sdf::JointType::FIXED: + { + igndbg << "[JointTrajectoryController] Fixed joint [" << jointName + << "(Entity=" << jointEntity << ")] is skipped.\n"; + continue; + } + case sdf::JointType::REVOLUTE2: + case sdf::JointType::SCREW: + case sdf::JointType::BALL: + case sdf::JointType::UNIVERSAL: + { + ignwarn << "[JointTrajectoryController] Joint [" << jointName + << "(Entity=" << jointEntity + << ")] is of unsupported type. Only joints with a single axis" + " are supported.\n"; + continue; + } + default: + { + ignwarn << "[JointTrajectoryController] Joint [" << jointName + << "(Entity=" << jointEntity << ")] is of unknown type.\n"; + continue; + } + } + output.push_back(jointEntity); + } + + return output; +} + +////////////////////////////////////////////////// +void JointTrajectoryControllerPrivate::JointTrajectoryCallback( + const ignition::msgs::JointTrajectory &_msg) +{ + // Make sure the message is valid + if (_msg.joint_names_size() == 0) + { + ignwarn << "[JointTrajectoryController] JointTrajectory message does not" + " contain any joint names.\n"; + return; + } + + // Warn user that accelerations are currently ignored if the first point + // contains them + if (_msg.points(0).accelerations_size() > 0) + { + ignwarn << "[JointTrajectoryController] JointTrajectory message contains" + " acceleration commands, which are currently ignored.\n"; + } + + // Lock mutex guarding the trajectory + std::lock_guard lock(this->trajectoryMutex); + + if (this->trajectory.status != Trajectory::Reached) + { + ignwarn << "[JointTrajectoryController] A new JointTrajectory message was" + " received while executing a previous trajectory.\n"; + } + + // Get start time of the trajectory from message header if desired + // If not enabled or there is no header, set start time to 0 and determine + // it later from simTime + if (this->useHeaderStartTime && _msg.has_header()) + { + if (_msg.header().has_stamp()) + { + const auto stamp = _msg.header().stamp(); + this->trajectory.startTime = std::chrono::seconds(stamp.sec()) + + std::chrono::nanoseconds(stamp.nsec()); + } + } + else + { + this->trajectory.startTime = std::chrono::nanoseconds(0); + } + + // Reset for a new trajectory + this->trajectory.Reset(); + + // Extract joint names and points + for (const auto &joint_name : _msg.joint_names()) + { + this->trajectory.jointNames.push_back(joint_name); + } + for (const auto &point : _msg.points()) + { + this->trajectory.points.push_back(point); + } +} + +////////////////////////////////////////////////// +void JointTrajectoryControllerPrivate::Reset() +{ + for (auto &actuatedJoint : this->actuatedJoints) + { + auto *joint = &actuatedJoint.second; + // Reset joint target + joint->ResetTarget(); + // Reset PIDs + joint->ResetPIDs(); + } + + // Reset trajectory + this->trajectory.Reset(); +} + +/////////////////////// +/// JointParameters /// +/////////////////////// + +////////////////////////////////////////////////// +std::map JointParameters::ParseAll( + const std::shared_ptr &_sdf, + ignition::gazebo::EntityComponentManager &_ecm, + std::vector _enabledJoints) +{ + std::map output; + + const auto initialPositionAll = JointParameters::Parse(_sdf, + "initial_position"); + + const auto positionPGainAll = JointParameters::Parse(_sdf, + "position_p_gain"); + const auto positionIGainAll = JointParameters::Parse(_sdf, + "position_i_gain"); + const auto positionDGainAll = JointParameters::Parse(_sdf, + "position_d_gain"); + const auto positionIMinAll = JointParameters::Parse(_sdf, + "position_i_min"); + const auto positionIMaxAll = JointParameters::Parse(_sdf, + "position_i_max"); + const auto positionCmdMinAll = JointParameters::Parse(_sdf, + "position_cmd_min"); + const auto positionCmdMaxAll = JointParameters::Parse(_sdf, + "position_cmd_max"); + const auto positionCmdOffsetAll = JointParameters::Parse(_sdf, + "position_cmd_offset"); + + const auto velocityPGainAll = JointParameters::Parse(_sdf, + "velocity_p_gain"); + const auto velocityIGainAll = JointParameters::Parse(_sdf, + "velocity_i_gain"); + const auto velocityDGainAll = JointParameters::Parse(_sdf, + "velocity_d_gain"); + const auto velocityIMinAll = JointParameters::Parse(_sdf, + "velocity_i_min"); + const auto velocityIMaxAll = JointParameters::Parse(_sdf, + "velocity_i_max"); + const auto velocityCmdMinAll = JointParameters::Parse(_sdf, + "velocity_cmd_min"); + const auto velocityCmdMaxAll = JointParameters::Parse(_sdf, + "velocity_cmd_max"); + const auto velocityCmdOffsetAll = JointParameters::Parse(_sdf, + "velocity_cmd_offset"); + + for (std::size_t i = 0; i < _enabledJoints.size(); ++i) + { + JointParameters params; + params.initialPosition = params.NthElementOr(initialPositionAll, i, + params.initialPositionDefault); + + params.positionPID.pGain = params.NthElementOr(positionPGainAll, i, + params.positionPID.pGainDefault); + params.positionPID.iGain = params.NthElementOr(positionIGainAll, i, + params.positionPID.iGainDefault); + params.positionPID.dGain = params.NthElementOr(positionDGainAll, i, + params.positionPID.dGainDefault); + params.positionPID.iMin = params.NthElementOr(positionIMinAll, i, + params.positionPID.iMinDefault); + params.positionPID.iMax = params.NthElementOr(positionIMaxAll, i, + params.positionPID.iMaxDefault); + params.positionPID.cmdMin = params.NthElementOr(positionCmdMinAll, i, + params.positionPID.cmdMinDefault); + params.positionPID.cmdMax = params.NthElementOr(positionCmdMaxAll, i, + params.positionPID.cmdMaxDefault); + params.positionPID.cmdOffset = params.NthElementOr(positionCmdOffsetAll, i, + params.positionPID.cmdOffsetDefault); + + params.velocityPID.pGain = params.NthElementOr(velocityPGainAll, i, + params.velocityPID.pGainDefault); + params.velocityPID.iGain = params.NthElementOr(velocityIGainAll, i, + params.velocityPID.iGainDefault); + params.velocityPID.dGain = params.NthElementOr(velocityDGainAll, i, + params.velocityPID.dGainDefault); + params.velocityPID.iMin = params.NthElementOr(velocityIMinAll, i, + params.velocityPID.iMinDefault); + params.velocityPID.iMax = params.NthElementOr(velocityIMaxAll, i, + params.velocityPID.iMaxDefault); + params.velocityPID.cmdMin = params.NthElementOr(velocityCmdMinAll, i, + params.velocityPID.cmdMinDefault); + params.velocityPID.cmdMax = params.NthElementOr(velocityCmdMaxAll, i, + params.velocityPID.cmdMaxDefault); + params.velocityPID.cmdOffset = params.NthElementOr(velocityCmdOffsetAll, i, + params.velocityPID.cmdOffsetDefault); + + const auto jointName = _ecm.Component( + _enabledJoints[i])->Data(); + output[jointName] = params; + } + + return output; +} + +////////////////////////////////////////////////// +template +std::vector JointParameters::Parse( + const std::shared_ptr &_sdf, + const std::string &_parameterName) +{ + std::vector output; + + if (_sdf->HasElement(_parameterName)) + { + sdf::ElementPtr param = const_cast( + _sdf.get())->GetElement(_parameterName); + while (param) + { + output.push_back(param->Get()); + param = param->GetNextElement(_parameterName); + } + } + + return output; +} + +//////////////////////////////////////////////// +template +T JointParameters::NthElementOr(const std::vector &_vec, + const size_t &_index, + const T &_alternative_value) +{ + if (_index < _vec.size()) + { + return _vec[_index]; + } + else + { + return _alternative_value; + } +} + +///////////////////// +/// ActuatedJoint /// +///////////////////// + +////////////////////////////////////////////////// +ActuatedJoint::ActuatedJoint(const Entity &_entity, + const JointParameters &_params) +{ + this->entity = _entity; + + this->initialPosition = _params.initialPosition; + this->target.position = _params.initialPosition; + this->target.velocity = 0.0; + this->target.acceleration = 0.0; + this->target.effort = 0.0; + + this->pids.position = ignition::math::PID(_params.positionPID.pGain, + _params.positionPID.iGain, + _params.positionPID.dGain, + _params.positionPID.iMax, + _params.positionPID.iMin, + _params.positionPID.cmdMax, + _params.positionPID.cmdMin, + _params.positionPID.cmdOffset); + + this->pids.velocity = ignition::math::PID(_params.velocityPID.pGain, + _params.velocityPID.iGain, + _params.velocityPID.dGain, + _params.velocityPID.iMax, + _params.velocityPID.iMin, + _params.velocityPID.cmdMax, + _params.velocityPID.cmdMin, + _params.velocityPID.cmdOffset); + + igndbg << "[JointTrajectoryController] Parameters for joint (Entity=" + << _entity << "):\n" + << "initial_position: [" << _params.initialPosition << "]\n" + << "position_p_gain: [" << _params.positionPID.pGain << "]\n" + << "position_i_gain: [" << _params.positionPID.iGain << "]\n" + << "position_d_gain: [" << _params.positionPID.dGain << "]\n" + << "position_i_min: [" << _params.positionPID.iMax << "]\n" + << "position_i_max: [" << _params.positionPID.iMax << "]\n" + << "position_cmd_min: [" << _params.positionPID.cmdMin << "]\n" + << "position_cmd_max: [" << _params.positionPID.cmdMax << "]\n" + << "position_cmd_offset: [" << _params.positionPID.cmdOffset << "]\n" + << "velocity_p_gain: [" << _params.velocityPID.pGain << "]\n" + << "velocity_i_gain: [" << _params.velocityPID.iGain << "]\n" + << "velocity_d_gain: [" << _params.velocityPID.dGain << "]\n" + << "velocity_i_min: [" << _params.velocityPID.iMax << "]\n" + << "velocity_i_max: [" << _params.velocityPID.iMax << "]\n" + << "velocity_cmd_min: [" << _params.velocityPID.cmdMin << "]\n" + << "velocity_cmd_max: [" << _params.velocityPID.cmdMax << "]\n" + << "velocity_cmd_offset: [" << _params.velocityPID.cmdOffset << "]\n"; +} + +////////////////////////////////////////////////// +void ActuatedJoint::SetupComponents( + ignition::gazebo::EntityComponentManager &_ecm) const +{ + // Create JointPosition component if one does not exist + if (nullptr == _ecm.Component(this->entity)) + { + _ecm.CreateComponent(this->entity, components::JointPosition()); + } + + // Create JointVelocity component if one does not exist + if (nullptr == _ecm.Component(this->entity)) + { + _ecm.CreateComponent(this->entity, components::JointVelocity()); + } + + // Create JointForceCmd component if one does not exist + if (nullptr == _ecm.Component(this->entity)) + { + _ecm.CreateComponent(this->entity, components::JointForceCmd({0.0})); + } +} + +////////////////////////////////////////////////// +void ActuatedJoint::SetTarget( + const ignition::msgs::JointTrajectoryPoint &_targetPoint, + const size_t &_jointIndex) +{ + if ((signed)_jointIndex < _targetPoint.positions_size()) + { + this->target.position = _targetPoint.positions(_jointIndex); + } + if ((signed)_jointIndex < _targetPoint.velocities_size()) + { + this->target.velocity = _targetPoint.velocities(_jointIndex); + } + if ((signed)_jointIndex < _targetPoint.accelerations_size()) + { + this->target.acceleration = _targetPoint.accelerations(_jointIndex); + } + if ((signed)_jointIndex < _targetPoint.effort_size()) + { + this->target.effort = _targetPoint.effort(_jointIndex); + } +} + +////////////////////////////////////////////////// +void ActuatedJoint::Update(ignition::gazebo::EntityComponentManager &_ecm, + const std::chrono::steady_clock::duration &_dt) +{ + // Get JointPosition and JointVelocity components + const auto jointPositionComponent = _ecm.Component( + this->entity); + const auto jointVelocityComponent = _ecm.Component( + this->entity); + + // Compute control errors and force for each PID controller + double forcePosition = 0.0, forceVelocity = 0.0; + if (!jointPositionComponent->Data().empty()) + { + double errorPosition = jointPositionComponent->Data()[0] - + this->target.position; + forcePosition = this->pids.position.Update(errorPosition, _dt); + } + if (!jointVelocityComponent->Data().empty()) + { + double errorVelocity = jointVelocityComponent->Data()[0] - + this->target.velocity; + forceVelocity = this->pids.velocity.Update(errorVelocity, _dt); + } + + // Sum all forces + const double force = forcePosition + forceVelocity + this->target.effort; + + // Get JointForceCmd component and apply command force + auto jointForceCmdComponent = _ecm.Component( + this->entity); + jointForceCmdComponent->Data()[0] = force; +} + +////////////////////////////////////////////////// +void ActuatedJoint::ResetTarget() +{ + this->target.position = this->initialPosition; + this->target.velocity = 0.0; + this->target.acceleration = 0.0; + this->target.effort = 0.0; +} + +////////////////////////////////////////////////// +void ActuatedJoint::ResetPIDs() +{ + this->pids.position.Reset(); + this->pids.velocity.Reset(); +} + +////////////////// +/// Trajectory /// +////////////////// + +////////////////////////////////////////////////// +bool Trajectory::UpdateCurrentPoint( + const std::chrono::steady_clock::duration &_simTime) +{ + bool isUpdated = false; + + const auto trajectoryTime = _simTime - this->startTime; + while (true) + { + // Break if end of trajectory is reached (there are no more points after + // the current one) + if (this->IsGoalReached()) + { + break; + } + + // Break if point needs to be followed + const auto pointTFS = this->points[this->pointIndex].time_from_start(); + const auto pointTime = std::chrono::seconds(pointTFS.sec()) + + std::chrono::nanoseconds(pointTFS.nsec()); + if (pointTime >= trajectoryTime) + { + break; + } + + // Otherwise increment and try again (joint targets need to be updated) + ++this->pointIndex; + isUpdated = true; + }; + + // Return true if a point index was updated + return isUpdated; +} + +////////////////////////////////////////////////// +bool Trajectory::IsGoalReached() const +{ + return this->pointIndex + 1 >= this->points.size(); +} + +////////////////////////////////////////////////// +float Trajectory::ComputeProgress() const +{ + if (this->points.size() == 0) + { + return 1.0; + } + else + { + return static_cast(this->pointIndex + 1) / + static_cast(this->points.size()); + } +} + +////////////////////////////////////////////////// +void Trajectory::Reset() +{ + this->status = Trajectory::New; + this->pointIndex = 0; + this->jointNames.clear(); + this->points.clear(); +} + +// Register plugin +IGNITION_ADD_PLUGIN(JointTrajectoryController, + ignition::gazebo::System, + JointTrajectoryController::ISystemConfigure, + JointTrajectoryController::ISystemPreUpdate) +IGNITION_ADD_PLUGIN_ALIAS( + JointTrajectoryController, + "ignition::gazebo::systems::JointTrajectoryController") diff --git a/src/systems/joint_trajectory_controller/JointTrajectoryController.hh b/src/systems/joint_trajectory_controller/JointTrajectoryController.hh new file mode 100644 index 0000000000..8f895b77e0 --- /dev/null +++ b/src/systems/joint_trajectory_controller/JointTrajectoryController.hh @@ -0,0 +1,164 @@ +/* + * 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_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ +#define IGNITION_GAZEBO_SYSTEMS_JOINT_TRAJECTORY_CONTROLLER_HH_ + +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems +{ + // Forward declaration + class IGNITION_GAZEBO_HIDDEN JointTrajectoryControllerPrivate; + + /// \brief Joint trajectory controller, which can be attached to a model with + /// reference to one or more 1-axis joints in order to follow a trajectory. + /// + /// Joint trajectories can be sent to this plugin via Ignition Transport. + /// The default topic name is "/model/${MODEL_NAME}/joint_trajectory" that + /// can be configured with the `` system parameter. + /// + /// This topic accepts ignition::msgs::JointTrajectory messages that represent + /// a full trajectory, defined as temporal `points` with their fields ordered + /// according to `joint_names` field. The fields under `points` are + /// `positions` - Controlled by position PID controller for each joint + /// `velocities` - Controlled by velocity PID controller for each joint + /// `accelerations` - This field is currently ignored + /// `effort` - Controlled directly for each joint + /// `time_from_start` - Temporal information about the point + /// + /// Forces/torques from `position`, `velocity` and `effort` are summed and + /// applied to the joint. Each PID controller can be configured with system + /// parameters described below. + /// + /// Input trajectory can be produced by a motion planning framework such as + /// MoveIt2. For smooth execution of the trajectory, its points should to be + /// interpolated before sending them via Ignition Transport (interpolation + /// might already be implemented in the motion planning framework of your + /// choice). + /// + /// The progress of the current trajectory can be tracked on topic whose name + /// is derived as `_progress`. This progress is indicated in the range + /// of (0.0, 1.0] and is currently based purely on `time_from_start` contained + /// in the trajectory points. + /// + /// ## System Parameters + /// + /// `` The name of the topic that this plugin subscribes to. + /// Optional parameter. + /// Defaults to "/model/${MODEL_NAME}/joint_trajectory". + /// + /// `` If enabled, trajectory execution begins at the + /// timestamp contained in the header of received trajectory messages. + /// Optional parameter. + /// Defaults to false. + /// + /// `` Name of a joint to control. + /// This parameter can be specified multiple times, i.e. once for each joint. + /// Optional parameter. + /// Defaults to all 1-axis joints contained in the model SDF (order is kept). + /// + /// `` Initial position of a joint (for position control). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// Defaults to 0 for all joints. + /// + /// `<%s_p_gain>` The proportional gain of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (disabled). + /// + /// `<%s_i_gain>` The integral gain of the PID. Optional parameter. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (disabled). + /// + /// `<%s_d_gain>` The derivative gain of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (disabled). + /// + /// `<%s_i_min>` The integral lower limit of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (no limit if higher than `%s_i_max`). + /// + /// `<%s_i_max>` The integral upper limit of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is -1 (no limit if lower than `%s_i_min`). + /// + /// `<%s_cmd_min>` Output min value of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (no limit if higher than `%s_i_max`). + /// + /// `<%s_cmd_max>` Output max value of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is -1 (no limit if lower than `%s_i_min`). + /// + /// `<%s_cmd_offset>` Command offset (feed-forward) of the PID. + /// Substitute '%s' for "position" or "velocity" (e.g. "position_p_gain"). + /// This parameter can be specified multiple times. Follows joint_name order. + /// Optional parameter. + /// The default value is 0 (no offset). + class IGNITION_GAZEBO_VISIBLE JointTrajectoryController + : public System, + public ISystemConfigure, + public ISystemPreUpdate + { + /// \brief Constructor + public: JointTrajectoryController(); + + /// \brief Destructor + public: ~JointTrajectoryController() override = default; + + // Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) override; + + // Documentation inherited + public: void PreUpdate( + const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) override; + + /// \brief Private data pointer + private: std::unique_ptr dataPtr; + }; +} // namespace systems +} // namespace IGNITION_GAZEBO_VERSION_NAMESPACE +} // namespace gazebo +} // namespace ignition + +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 5e2233fbd0..c306ec83bc 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -22,6 +22,7 @@ set(tests joint_controller_system.cc joint_position_controller_system.cc joint_state_publisher_system.cc + joint_trajectory_controller_system.cc kinetic_energy_monitor_system.cc lift_drag_system.cc level_manager.cc diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc new file mode 100644 index 0000000000..70ca0aad3f --- /dev/null +++ b/test/integration/joint_trajectory_controller_system.cc @@ -0,0 +1,399 @@ +/* + * 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 "ignition/gazebo/components/Joint.hh" +#include "ignition/gazebo/components/JointPosition.hh" +#include "ignition/gazebo/components/JointVelocity.hh" +#include "ignition/gazebo/components/Name.hh" + +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/SystemLoader.hh" +#include "ignition/gazebo/test_config.hh" + +#include "../helpers/Relay.hh" + +#define TOL 1e-4 + +using namespace ignition; +using namespace gazebo; + +/// \brief Test fixture for JointTrajectoryController system +class JointTrajectoryControllerTestFixture : public ::testing::Test +{ + // Documentation inherited +protected: + void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + } +}; + +///////////////////////////////////////////////// +// Tests that JointTrajectoryController accepts position-controlled joint +// trajectory +TEST_F(JointTrajectoryControllerTestFixture, + JointTrajectoryControllerPositionControl) +{ + using namespace std::chrono_literals; + + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/joint_trajectory_controller.sdf"; + + // Define joints of the model to investigate + const size_t kNumberOfJoints = 2; + const std::string jointNames[kNumberOfJoints] = {"RR_position_control_joint1", + "RR_position_control_joint2"}; + + // Define names of Ignition Transport topics + const std::string trajectoryTopic = + "/model/RR_position_control/joint_trajectory"; + const std::string feedbackTopic = + "/model/RR_position_control/joint_trajectory_feedback"; + + // Define initial joint positions + const std::array initialPositions = {0.0, 0.0}; + + // Define a trajectory to follow + msgs::Duration timeFromStart; + std::vector trajectoryTimes; + std::vector> trajectoryPositions; + // Point1 + timeFromStart.set_sec(0); + timeFromStart.set_nsec(666000000); + trajectoryTimes.push_back(timeFromStart); + trajectoryPositions.push_back({-0.7854, 0.7854}); + // Point2 + timeFromStart.set_sec(1); + timeFromStart.set_nsec(333000000); + trajectoryTimes.push_back(timeFromStart); + trajectoryPositions.push_back({1.5708, -0.7854}); + // Point3 + timeFromStart.set_sec(2); + timeFromStart.set_nsec(0); + trajectoryTimes.push_back(timeFromStart); + trajectoryPositions.push_back({3.1416, -1.5708}); + + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + // Setup test system + test::Relay testSystem; + double currentPositions[kNumberOfJoints]; + testSystem.OnPreUpdate( + [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + { + // Create a JointPosition component for each joint if it doesn't exist + for (const auto &jointName : jointNames) + { + const auto joint = _ecm.EntityByComponents(components::Joint(), + components::Name( + jointName)); + if (nullptr == _ecm.Component(joint)) + { + _ecm.CreateComponent(joint, components::JointPosition()); + } + } + }); + testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + // Get the current position of each joint + for (std::size_t i = 0; i < kNumberOfJoints; ++i) + { + const auto joint = _ecm.EntityByComponents(components::Joint(), + components::Name( + jointNames[i])); + const auto jointPositionComponent = + _ecm.Component(joint); + if (nullptr != jointPositionComponent) + { + currentPositions[i] = jointPositionComponent->Data()[0]; + } + } + }); + server.AddSystem(testSystem.systemPtr); + + // Step few iterations and assert that the initial position is kept + const std::size_t initIters = 10; + server.Run(true, initIters, false); + for (size_t i = 0; i < kNumberOfJoints; ++i) + { + EXPECT_NEAR(currentPositions[i], initialPositions[i], TOL); + } + + // Create new JointTrajectory message based on the defined trajectory + ignition::msgs::JointTrajectory msg; + for (const auto &jointName : jointNames) + { + msg.add_joint_names(jointName); + } + for (size_t i = 0; i < trajectoryPositions.size(); ++i) + { + ignition::msgs::JointTrajectoryPoint point; + + // Set the temporal information for the point + auto time = point.mutable_time_from_start(); + time->set_sec(trajectoryTimes[i].sec()); + time->set_nsec(trajectoryTimes[i].nsec()); + + // Add target positions to the point + for (size_t j = 0; j < kNumberOfJoints; ++j) + { + point.add_positions(trajectoryPositions[i][j]); + } + + // Add point to the trajectory + msg.add_points(); + msg.mutable_points(i)->CopyFrom(point); + } + + // Verify that feedback is strictly increasing and reaches value of 1.0 + size_t count = 0; + std::function feedbackCallback = + [&](const ignition::msgs::Float &_msg) { + count++; + if (trajectoryPositions.size() == count) + { + EXPECT_FLOAT_EQ(_msg.data(), 1.0f); + } + else + { + EXPECT_FLOAT_EQ(_msg.data(), static_cast(count) / + static_cast(trajectoryPositions.size())); + } + }; + transport::Node node; + node.Subscribe(feedbackTopic, feedbackCallback); + + // Publish joint trajectory + auto pub = node.Advertise(trajectoryTopic); + pub.Publish(msg); + + // Wait for message to be published + std::this_thread::sleep_for(100ms); + + // Run the simulation while asserting the target position of all joints at + // each trajectory point + auto previousIterFromStart = 0; + for (size_t i = 0; i < trajectoryPositions.size(); ++i) + { + // Number of iters required to reach time_from_start of the current + // point (1ms step size) + auto iterFromStart = trajectoryTimes[i].sec() * 1000 + + trajectoryTimes[i].nsec() / 1000000; + auto neededIters = iterFromStart - previousIterFromStart; + + // Run the simulation + server.Run(true, neededIters, false); + + // Assert that each joint reached its target position + for (size_t j = 0; j < kNumberOfJoints; ++j) + { + EXPECT_NEAR(currentPositions[j], trajectoryPositions[i][j], TOL); + } + + // Keep track of how many iterations have already passed + previousIterFromStart = iterFromStart; + } +} + +///////////////////////////////////////////////// +// Tests that JointTrajectoryController accepts velocity-controlled joint +// trajectory +TEST_F(JointTrajectoryControllerTestFixture, + JointTrajectoryControllerVelocityControl) +{ + using namespace std::chrono_literals; + + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/joint_trajectory_controller.sdf"; + + // Define joints of the model to investigate + const size_t kNumberOfJoints = 2; + const std::string jointNames[kNumberOfJoints] = {"RR_velocity_control_joint1", + "RR_velocity_control_joint2"}; + + // Define names of Ignition Transport topics + const std::string trajectoryTopic = "/test_custom_topic/velocity_control"; + const std::string feedbackTopic = + "/test_custom_topic/velocity_control_feedback"; + + // Define initial joint velocities + const std::array initialVelocities = {0.0, 0.0}; + + // Define a trajectory to follow + msgs::Duration timeFromStart; + std::vector trajectoryTimes; + std::vector> trajectoryVelocities; + // Point1 + timeFromStart.set_sec(0); + timeFromStart.set_nsec(500000000); + trajectoryTimes.push_back(timeFromStart); + trajectoryVelocities.push_back({0.5, 0.5}); + // Point2 + timeFromStart.set_sec(1); + timeFromStart.set_nsec(0); + trajectoryTimes.push_back(timeFromStart); + trajectoryVelocities.push_back({-1.0, 1.0}); + + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + // Setup test system + test::Relay testSystem; + double currentVelocities[kNumberOfJoints]; + testSystem.OnPreUpdate( + [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + { + // Create a JointVelocity component for each joint if it doesn't exist + for (const auto &jointName : jointNames) + { + const auto joint = _ecm.EntityByComponents(components::Joint(), + components::Name( + jointName)); + if (nullptr == _ecm.Component(joint)) + { + _ecm.CreateComponent(joint, components::JointVelocity()); + } + } + }); + testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + // Get the current velocity of each joint + for (std::size_t i = 0; i < kNumberOfJoints; ++i) + { + const auto joint = _ecm.EntityByComponents(components::Joint(), + components::Name( + jointNames[i])); + const auto jointVelocityComponent = + _ecm.Component(joint); + if (nullptr != jointVelocityComponent) + { + currentVelocities[i] = jointVelocityComponent->Data()[0]; + } + } + }); + server.AddSystem(testSystem.systemPtr); + + // Step few iterations and assert that the initial velocity is kept + const std::size_t initIters = 10; + server.Run(true, initIters, false); + for (size_t i = 0; i < kNumberOfJoints; ++i) + { + EXPECT_NEAR(currentVelocities[i], initialVelocities[i], TOL); + } + + // Create new JointTrajectory message based on the defined trajectory + ignition::msgs::JointTrajectory msg; + for (const auto &jointName : jointNames) + { + msg.add_joint_names(jointName); + } + for (size_t i = 0; i < trajectoryVelocities.size(); ++i) + { + ignition::msgs::JointTrajectoryPoint point; + + // Set the temporal information for the point + auto time = point.mutable_time_from_start(); + time->set_sec(trajectoryTimes[i].sec()); + time->set_nsec(trajectoryTimes[i].nsec()); + + // Add target velocities to the point + for (size_t j = 0; j < kNumberOfJoints; ++j) + { + point.add_velocities(trajectoryVelocities[i][j]); + } + + // Add point to the trajectory + msg.add_points(); + msg.mutable_points(i)->CopyFrom(point); + } + + // Verify that feedback is strictly increasing and reaches value of 1.0 + size_t count = 0; + std::function feedbackCallback = + [&](const ignition::msgs::Float &_msg) { + count++; + if (trajectoryVelocities.size() == count) + { + EXPECT_FLOAT_EQ(_msg.data(), 1.0f); + } + else + { + EXPECT_FLOAT_EQ(_msg.data(), static_cast(count) / + static_cast(trajectoryVelocities.size())); + } + }; + transport::Node node; + node.Subscribe(feedbackTopic, feedbackCallback); + + // Publish joint trajectory + auto pub = node.Advertise(trajectoryTopic); + pub.Publish(msg); + + // Wait for message to be published + std::this_thread::sleep_for(100ms); + + // Run the simulation while asserting the target velocity of all joints at + // each trajectory point + auto previousIterFromStart = 0; + for (size_t i = 0; i < trajectoryVelocities.size(); ++i) + { + // Number of iters required to reach time_from_start of the current + // point (1ms step size) + auto iterFromStart = trajectoryTimes[i].sec() * 1000 + + trajectoryTimes[i].nsec() / 1000000; + auto neededIters = iterFromStart - previousIterFromStart; + + // Run the simulation + server.Run(true, neededIters, false); + + // Assert that each joint reached its target velocity + for (size_t j = 0; j < kNumberOfJoints; ++j) + { + EXPECT_NEAR(currentVelocities[j], trajectoryVelocities[i][j], TOL); + } + + // Keep track of how many iterations have already passed + previousIterFromStart = iterFromStart; + } +} diff --git a/test/worlds/joint_trajectory_controller.sdf b/test/worlds/joint_trajectory_controller.sdf new file mode 100644 index 0000000000..4aaee68ca5 --- /dev/null +++ b/test/worlds/joint_trajectory_controller.sdf @@ -0,0 +1,420 @@ + + + + + + + + + + + + 0.4 0.4 0.4 + false + + + + + + + + + + 3D View + false + docked + + ogre + scene + 0 0 1 0 1.5708 0 + + + + + + World control + false + false + 50 + 100 + 1 + floating + + + + + + true + true + true + + + + + + World stats + false + false + 250 + 110 + 1 + floating + + + + + + true + true + true + true + + + + + + + + false + 5 5 5 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -1 -1 -1 + + + + + + + + 0 -0.5 0 0 1.5708 0 + + + world + RR_position_control_link0 + + + + + + + 0.025 + + + + + + + 0.025 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.0125 + + + + + + + 0.01 + 0.2 + + + + 0.5 0 0 1 + 0.8 0 0 1 + 0.8 0 0 1 + + + + 0 0 0.2 0 0 0 + + + 0.0125 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.01 + 0.2 + + + + 0.5 0 0 1 + 0.8 0 0 1 + 0.8 0 0 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + + 0 0 0 0 0 0 + RR_position_control_link0 + RR_position_control_link1 + + 1 0 0 + + 0.5 + + + + + 0 0 0.1 0 0 0 + RR_position_control_link1 + RR_position_control_link2 + + 1 0 0 + + 0.25 + + + + + + + RR_position_control_joint2 + 25 + 400 + 0.1 + -0.5 + 0.5 + -5 + 5 + + RR_position_control_joint1 + 50 + 600 + 0.8 + -1 + 1 + -10 + 10 + + + + + + + 0 0.5 0 0 1.5708 0 + + + world + RR_velocity_control_link0 + + + + + + + 0.025 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + 0.025 + + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.0125 + + + + + + + 0.01 + 0.2 + + + + 0 0.5 0 1 + 0 0.8 0 1 + 0 0.8 0 1 + + + + 0 0 0.2 0 0 0 + + + 0.0125 + + + + 0.5 0.5 0.5 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + 0 0 0.1 0 0 0 + + + + 0.01 + 0.2 + + + + + + + 0.01 + 0.2 + + + + 0 0.5 0 1 + 0 0.8 0 1 + 0 0.8 0 1 + + + + 0.1 + + 0.0003358 + 0.0003358 + 0.000005 + + + + + + 0 0 0 0 0 0 + RR_velocity_control_link0 + RR_velocity_control_link1 + + 1 0 0 + + + 0.02 + + + + 0 0 0.1 0 0 0 + RR_velocity_control_link1 + RR_velocity_control_link2 + + 1 0 0 + + + 0.01 + + + + + + test_custom_topic/velocity_control + + + 0.6 + 175 + -10 + 10 + + 0.1 + 200 + -5 + 5 + + + + + From 18475130310f114afa1647e13cdcdc23e9c7dbe2 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Thu, 11 Feb 2021 18:55:05 -0600 Subject: [PATCH 34/55] Fix pose of plane visual with non-default normal vector (#574) Signed-off-by: Addisu Z. Taddese Co-authored-by: Louise Poubel --- src/rendering/SceneManager.cc | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 0be6da0be2..98e3cbecc5 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -258,17 +258,19 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, /// localPose is currently used to handle the normal vector in plane visuals /// In general, this can be used to store any local transforms between the /// parent Visual and geometry. - rendering::VisualPtr geomVis; if (localPose != math::Pose3d::Zero) { - geomVis = this->dataPtr->scene->CreateVisual(name + "_geom"); - geomVis->SetUserData("gazebo-entity", static_cast(_id)); - geomVis->SetUserData("pause-update", static_cast(0)); - geomVis->SetLocalPose(_visual.RawPose() * localPose); - visualVis = geomVis; + rendering::VisualPtr geomVis = + this->dataPtr->scene->CreateVisual(name + "_geom"); + geomVis->AddGeometry(geom); + geomVis->SetLocalPose(localPose); + visualVis->AddChild(geomVis); + } + else + { + visualVis->AddGeometry(geom); } - visualVis->AddGeometry(geom); visualVis->SetLocalScale(scale); // set material From 3465bbececc259b9486601ea5be3db1c95ceed83 Mon Sep 17 00:00:00 2001 From: "G.Doisy" Date: Fri, 12 Feb 2021 05:42:21 +0100 Subject: [PATCH 35/55] Add laser_retro support (#603) Signed-off-by: Guillaume Doisy Co-authored-by: Louise Poubel --- .../worlds/gpu_lidar_retro_values_sensor.sdf | 214 ++++++++++++++++++ .../ignition/gazebo/components/LaserRetro.hh | 41 ++++ src/SdfEntityCreator.cc | 7 + src/SdfEntityCreator_TEST.cc | 7 + src/rendering/RenderUtil.cc | 13 ++ src/rendering/SceneManager.cc | 5 + test/worlds/shapes.sdf | 3 + 7 files changed, 290 insertions(+) create mode 100644 examples/worlds/gpu_lidar_retro_values_sensor.sdf create mode 100644 include/ignition/gazebo/components/LaserRetro.hh diff --git a/examples/worlds/gpu_lidar_retro_values_sensor.sdf b/examples/worlds/gpu_lidar_retro_values_sensor.sdf new file mode 100644 index 0000000000..f2d7a27c76 --- /dev/null +++ b/examples/worlds/gpu_lidar_retro_values_sensor.sdf @@ -0,0 +1,214 @@ + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + 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 + + + + + + + 0 -1 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 1 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + 500 + + + 1 1 1 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + 4 0 0.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 + + + + + + lidar + 10 + + + + 640 + 1 + -1.396263 + 1.396263 + + + 16 + 1 + -0.261799 + 0.261799 + + + + 0.08 + 10.0 + 0.01 + + + 1 + true + + + + true + + + + + diff --git a/include/ignition/gazebo/components/LaserRetro.hh b/include/ignition/gazebo/components/LaserRetro.hh new file mode 100644 index 0000000000..75d1145e92 --- /dev/null +++ b/include/ignition/gazebo/components/LaserRetro.hh @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2020 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_COMPONENTS_LASERRETRO_HH_ +#define IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_ + +#include +#include +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component used to indicate an lidar reflective value + using LaserRetro = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LaserRetro", + LaserRetro) +} +} +} +} + +#endif diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 3845830acb..ca14ac7c4b 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -41,6 +41,7 @@ #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/JointAxis.hh" #include "ignition/gazebo/components/JointType.hh" +#include "ignition/gazebo/components/LaserRetro.hh" #include "ignition/gazebo/components/Lidar.hh" #include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" @@ -503,6 +504,12 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Visual *_visual) this->dataPtr->ecm->CreateComponent(visualEntity, components::Transparency(_visual->Transparency())); + if (_visual->HasLaserRetro()) + { + this->dataPtr->ecm->CreateComponent(visualEntity, + components::LaserRetro(_visual->LaserRetro())); + } + if (_visual->Geom()) { this->dataPtr->ecm->CreateComponent(visualEntity, diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 94101b4b00..17e776b44d 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -35,6 +35,7 @@ #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/JointAxis.hh" #include "ignition/gazebo/components/JointType.hh" +#include "ignition/gazebo/components/LaserRetro.hh" #include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Material.hh" @@ -101,6 +102,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_TRUE(this->ecm.HasComponentType(components::Geometry::typeId)); EXPECT_TRUE(this->ecm.HasComponentType(components::Material::typeId)); EXPECT_TRUE(this->ecm.HasComponentType(components::Inertial::typeId)); + EXPECT_TRUE(this->ecm.HasComponentType(components::LaserRetro::typeId)); // Check entities // 1 x world + 3 x model + 3 x link + 3 x collision + 3 x visual + 1 x light @@ -356,6 +358,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) unsigned int visualCount{0}; this->ecm.Eachecm.ParentEntity(_entity)); EXPECT_DOUBLE_EQ(0.0, _transparency->Data()); + EXPECT_DOUBLE_EQ(1150.0, _laserRetro->Data()); EXPECT_TRUE(_castShadows->Data()); EXPECT_EQ(sdf::GeometryType::BOX, _geometry->Data().Type()); @@ -417,6 +422,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ(cylLinkEntity, this->ecm.ParentEntity(_entity)); EXPECT_DOUBLE_EQ(0.0, _transparency->Data()); + EXPECT_DOUBLE_EQ(1654.0, _laserRetro->Data()); EXPECT_TRUE(_castShadows->Data()); EXPECT_EQ(sdf::GeometryType::CYLINDER, _geometry->Data().Type()); @@ -440,6 +446,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ(sphLinkEntity, this->ecm.ParentEntity(_entity)); EXPECT_DOUBLE_EQ(0.5, _transparency->Data()); + EXPECT_DOUBLE_EQ(50.0, _laserRetro->Data()); EXPECT_FALSE(_castShadows->Data()); EXPECT_EQ(sdf::GeometryType::SPHERE, _geometry->Data().Type()); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 1dde5ba785..43c2ca676c 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -48,6 +48,7 @@ #include "ignition/gazebo/components/DepthCamera.hh" #include "ignition/gazebo/components/GpuLidar.hh" #include "ignition/gazebo/components/Geometry.hh" +#include "ignition/gazebo/components/LaserRetro.hh" #include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Material.hh" @@ -671,6 +672,12 @@ void RenderUtilPrivate::CreateRenderingEntities( visual.SetMaterial(material->Data()); } + auto laserRetro = _ecm.Component(_entity); + if (laserRetro != nullptr) + { + visual.SetLaserRetro(laserRetro->Data()); + } + // todo(anyone) make visual updates more generic without using extra // variables like entityTemp just for storing one specific visual // param? @@ -863,6 +870,12 @@ void RenderUtilPrivate::CreateRenderingEntities( visual.SetMaterial(material->Data()); } + auto laserRetro = _ecm.Component(_entity); + if (laserRetro != nullptr) + { + visual.SetLaserRetro(laserRetro->Data()); + } + this->newVisuals.push_back( std::make_tuple(_entity, visual, _parent->Data())); return true; diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 98e3cbecc5..41c8a5a81c 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -248,6 +248,11 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, visualVis->SetUserData("pause-update", static_cast(0)); visualVis->SetLocalPose(_visual.RawPose()); + if (_visual.HasLaserRetro()) + { + visualVis->SetUserData("laser_retro", _visual.LaserRetro()); + } + math::Vector3d scale = math::Vector3d::One; math::Pose3d localPose; rendering::GeometryPtr geom = diff --git a/test/worlds/shapes.sdf b/test/worlds/shapes.sdf index ac254fa80b..dad5d0a8db 100644 --- a/test/worlds/shapes.sdf +++ b/test/worlds/shapes.sdf @@ -64,6 +64,7 @@ + 1150 0.12 0.12 0.12 0 0 0 @@ -105,6 +106,7 @@ + 1654 0.22 0.22 0.22 0 0 0 @@ -146,6 +148,7 @@ + 50 0.32 0.32 0.32 0 0 0 0.5 false From 0f6c2b7ca3ea45a99e12193550890e9034e9ba65 Mon Sep 17 00:00:00 2001 From: Atharva Pusalkar Date: Mon, 15 Feb 2021 14:17:37 +0530 Subject: [PATCH 36/55] Add SDF topic validity check (#632) * Add SDF topic validity check Signed-off-by: Atharva Pusalkar * Fix SDF topic error message Signed-off-by: Atharva Pusalkar --- src/systems/joint_controller/JointController.cc | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index cd35d55805..9e78162403 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -142,7 +142,16 @@ void JointController::Configure(const Entity &_entity, } if (_sdf->HasElement("topic")) { - topic = _sdf->Get("topic"); + topic = transport::TopicUtils::AsValidTopic( + _sdf->Get("topic")); + + if (topic.empty()) + { + ignerr << "Failed to create topic [" << this->dataPtr->jointName + << "]" << " for joint [" << _sdf->Get("topic") + << "]" << std::endl; + return; + } } this->dataPtr->node.Subscribe(topic, &JointControllerPrivate::OnCmdVel, this->dataPtr.get()); From 215c8ed22c672107edaedfd5602b876acd2417b7 Mon Sep 17 00:00:00 2001 From: ddengster Date: Wed, 17 Feb 2021 03:55:32 +0800 Subject: [PATCH 37/55] Fix EntityComponentManager race condition (#601) Signed-off-by: ddengster Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- src/gui/GuiRunner.cc | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index 6f88a441fe..1925efa8a5 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -79,7 +79,16 @@ void GuiRunner::RequestState() } reqSrv = reqSrvValid; - this->node.Advertise(reqSrv, &GuiRunner::OnStateAsyncService, this); + auto advertised = this->node.AdvertisedServices(); + if (std::find(advertised.begin(), advertised.end(), reqSrv) == + advertised.end()) + { + if (!this->node.Advertise(reqSrv, &GuiRunner::OnStateAsyncService, this)) + { + ignerr << "Failed to advertise [" << reqSrv << "]" << std::endl; + } + } + ignition::msgs::StringMsg req; req.set_data(reqSrv); @@ -98,7 +107,7 @@ void GuiRunner::OnPluginAdded(const QString &_objectName) return; } - plugin->Update(this->updateInfo, this->ecm); + this->RequestState(); } ///////////////////////////////////////////////// From a5c66591704b8d2a6aab0b8b7c16c56ba208e58c Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Tue, 16 Feb 2021 20:56:31 +0100 Subject: [PATCH 38/55] Added link to HW-accelerated video recording (#627) Signed-off-by: Martin Pecka Co-authored-by: Michael Carroll --- tutorials/video_recorder.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index 50bbef75d9..47454230cf 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -105,3 +105,10 @@ going to the world SDF file, locate the * **bitrate**: Video encoding bitrate in bps. This affects the quality of the generated video. The default bitrate is 2Mbps. + +## Hardware-accelerated encoding + +Since Ignition Common 3.10.2, there is support for utilizing the power of GPUs +to speed up the video encoding process. See the +[Hardware-accelerated Video Encoding tutorial](https://ignitionrobotics.org/api/common/3.10/hw-encoding.html) +for more details. From 5e0c773cb64275604061575333a7384252fd2f31 Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Tue, 16 Feb 2021 14:07:04 -0800 Subject: [PATCH 39/55] Remove issue & PR templates (#631) Signed-off-by: Jenn Nguyen --- .github/ISSUE_TEMPLATE/bug_report.md | 29 ------------- .github/ISSUE_TEMPLATE/feature_request.md | 23 ---------- .github/PULL_REQUEST_TEMPLATE.md | 52 ----------------------- .github/PULL_REQUEST_TEMPLATE/port.md | 6 --- 4 files changed, 110 deletions(-) delete mode 100644 .github/ISSUE_TEMPLATE/bug_report.md delete mode 100644 .github/ISSUE_TEMPLATE/feature_request.md delete mode 100644 .github/PULL_REQUEST_TEMPLATE.md delete mode 100644 .github/PULL_REQUEST_TEMPLATE/port.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md deleted file mode 100644 index 3d89f64143..0000000000 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ /dev/null @@ -1,29 +0,0 @@ ---- -name: Bug report -about: Report a bug -labels: bug ---- - - - -## Environment -* OS Version: -* Source or binary build? - - - -## Description -* Expected behavior: -* Actual behavior: - -## Steps to reproduce - - -1. -2. -3. - -## Output - diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md deleted file mode 100644 index f49727a0ce..0000000000 --- a/.github/ISSUE_TEMPLATE/feature_request.md +++ /dev/null @@ -1,23 +0,0 @@ ---- -name: Feature request -about: Request a new feature -labels: enhancement ---- - - - -## Desired behavior - - -## Alternatives considered - - -## Implementation suggestion - - -## Additional context - diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md deleted file mode 100644 index 6c88bd5465..0000000000 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ /dev/null @@ -1,52 +0,0 @@ - - -# Bug Report - -Fixes issue # - -## Summary - - -## Checklist -- [ ] Signed all commits for DCO -- [ ] Added tests -- [ ] Updated documentation (as needed) -- [ ] Updated migration guide (as needed) -- [ ] `codecheck` passed (See - [contributing](https://ignitionrobotics.org/docs/all/contributing#contributing-code)) -- [ ] All tests passed (See - [test coverage](https://ignitionrobotics.org/docs/all/contributing#test-coverage)) -- [ ] While waiting for a review on your PR, please help review -[another open pull request](https://github.com/pulls?q=is%3Aopen+is%3Apr+user%3Aignitionrobotics+archived%3Afalse+) -to support the maintainers - -**Note to maintainers**: Remember to use **Squash-Merge** - ---- - -# New feature - -Closes # - -## Summary - - -## Test it - - -## Checklist -- [ ] Signed all commits for DCO -- [ ] Added tests -- [ ] Added example world and/or tutorial -- [ ] Updated documentation (as needed) -- [ ] Updated migration guide (as needed) -- [ ] `codecheck` passed (See [contributing](https://ignitionrobotics.org/docs/all/contributing#contributing-code)) -- [ ] All tests passed (See [test coverage](https://ignitionrobotics.org/docs/all/contributing#test-coverage)) -- [ ] While waiting for a review on your PR, please help review -[another open pull request](https://github.com/pulls?q=is%3Aopen+is%3Apr+user%3Aignitionrobotics+archived%3Afalse+) -to support the maintainers - -**Note to maintainers**: Remember to use **Squash-Merge** diff --git a/.github/PULL_REQUEST_TEMPLATE/port.md b/.github/PULL_REQUEST_TEMPLATE/port.md deleted file mode 100644 index 758127f585..0000000000 --- a/.github/PULL_REQUEST_TEMPLATE/port.md +++ /dev/null @@ -1,6 +0,0 @@ -Port to - -Branch comparison: https://github.com/ignitionrobotics/ign-gazebo/compare/... - -**Note to maintainers**: Remember to **Merge** with commit (not squash-merge -or rebase) From 44a6713bb6ef041703b0dc32ce9156296b134cc2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 17 Feb 2021 19:55:34 +0100 Subject: [PATCH 40/55] Add Light Usercommand and include Light parameters in the componentInspector (#482) Signed-off-by: ahcorde Co-authored-by: Louise Poubel --- .../standalone/light_control/CMakeLists.txt | 12 + .../standalone/light_control/light_control.cc | 179 +++ .../ignition/gazebo/components/LightCmd.hh | 48 + .../component_inspector/ComponentInspector.cc | 125 +- .../component_inspector/ComponentInspector.hh | 38 + .../ComponentInspector.qml | 15 + .../ComponentInspector.qrc | 1 + src/gui/plugins/component_inspector/Light.qml | 1099 +++++++++++++++++ src/gui/plugins/plotting/Plotting.cc | 83 ++ src/gui/plugins/plotting/Plotting.hh | 7 + src/gui/plugins/scene3d/Scene3D.cc | 1 + src/rendering/RenderUtil.cc | 163 ++- src/systems/user_commands/UserCommands.cc | 189 +++ test/integration/user_commands.cc | 227 ++++ test/worlds/lights.sdf | 6 +- test/worlds/lights_render.sdf | 116 ++ tutorials.md.in | 1 + tutorials/light_config.md | 45 + 18 files changed, 2343 insertions(+), 12 deletions(-) create mode 100644 examples/standalone/light_control/CMakeLists.txt create mode 100644 examples/standalone/light_control/light_control.cc create mode 100644 include/ignition/gazebo/components/LightCmd.hh create mode 100644 src/gui/plugins/component_inspector/Light.qml create mode 100644 test/worlds/lights_render.sdf create mode 100644 tutorials/light_config.md diff --git a/examples/standalone/light_control/CMakeLists.txt b/examples/standalone/light_control/CMakeLists.txt new file mode 100644 index 0000000000..be27581c40 --- /dev/null +++ b/examples/standalone/light_control/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +find_package(ignition-transport9 QUIET REQUIRED OPTIONAL_COMPONENTS log) +set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR}) + +find_package(ignition-gazebo4 REQUIRED) +set(IGN_GAZEBO_VER ${ignition-gazebo4_VERSION_MAJOR}) + +add_executable(light_control light_control.cc) +target_link_libraries(light_control + ignition-transport${IGN_TRANSPORT_VER}::core + ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER}) diff --git a/examples/standalone/light_control/light_control.cc b/examples/standalone/light_control/light_control.cc new file mode 100644 index 0000000000..4f499787c2 --- /dev/null +++ b/examples/standalone/light_control/light_control.cc @@ -0,0 +1,179 @@ +/* + * Copyright (C) 2020 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 + +using namespace std::chrono_literals; + +// Create a transport node. +ignition::transport::Node node; + +bool result; +// timeout used for services +constexpr unsigned int timeout = 5000; + +std::mt19937 twister(std::time(0)); +std::uniform_real_distribution distr(0, 1000); +constexpr double epsilon = 0.1; + +float directionX = 0.5; +float directionY = 0.2; +float directionZ = -0.9; + +void createLight() +{ + ignition::msgs::Boolean rep; +//! [create light] + ignition::msgs::EntityFactory entityFactoryRequest; + + entityFactoryRequest.mutable_light()->set_name("point"); + entityFactoryRequest.mutable_light()->set_range(4); + entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5); + entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); + entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); + entityFactoryRequest.mutable_light()->set_cast_shadows(false); + entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT); + ignition::msgs::Set( + entityFactoryRequest.mutable_light()->mutable_direction(), + ignition::math::Vector3d(directionX, directionY, directionZ)); + ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), + ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); +//! [create light] + + bool executedEntityFactory = node.Request("/world/empty/create", + entityFactoryRequest, timeout, rep, result); + if (executedEntityFactory) + { + if (result) + std::cout << "Light was created : [" << rep.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +} + +void createSphere() +{ + auto modelStr = R"( + + + + + 0 0 0.5 0 0 0 + + 1 + + + 1 + + + + )"; + + ignition::msgs::EntityFactory req; + ignition::msgs::Boolean res; + req.set_sdf(modelStr); + + bool executed = node.Request("/world/empty/create", + req, timeout, res, result); + if (executed) + { + if (result) + std::cout << "Sphere was created : [" << res.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +} + +////////////////////////////////////////////////// +int main(int argc, char **argv) +{ + ignition::msgs::Boolean rep; + ignition::msgs::Light lightRequest; + auto lightConfigService = "/world/empty/light_config"; + + createSphere(); + createLight(); + + while (1) + { + float r, g, b; + double m = 0; +//! [random numbers] + while (m < epsilon) + { + r = distr(twister); + g = distr(twister); + b = distr(twister); + m = std::sqrt(r*r + b*b + g*g); + } + r /= m; + b /= m; + b /= m; +//! [random numbers] + +//! [modify light] + lightRequest.set_name("point"); + lightRequest.set_range(4); + lightRequest.set_attenuation_linear(0.5); + lightRequest.set_attenuation_constant(0.2); + lightRequest.set_attenuation_quadratic(0.01); + lightRequest.set_cast_shadows(false); + lightRequest.set_type(ignition::msgs::Light::POINT); + // direction field only affects spot / directional lights + ignition::msgs::Set(lightRequest.mutable_direction(), + ignition::math::Vector3d(directionX, directionY, directionZ)); + ignition::msgs::Set(lightRequest.mutable_pose(), + ignition::math::Pose3d(0.0, -1.5, 3.0, 0.0, 0.0, 0.0)); + ignition::msgs::Set(lightRequest.mutable_diffuse(), + ignition::math::Color(r, g, b, 1)); + ignition::msgs::Set(lightRequest.mutable_specular(), + ignition::math::Color(r, g, b, 1)); +//! [modify light] + bool executed = node.Request(lightConfigService, lightRequest, timeout, + rep, result); + std::cout << "Service called: [" << r << ", " << g << ", " << b << "]" + << std::endl; + + if (executed) + { + if (result) + std::cout << "Response: [" << rep.data() << "]" << std::endl; + else + std::cout << "Service call failed" << std::endl; + } + else + std::cerr << "Service call timed out" << std::endl; + + std::this_thread::sleep_for(1s); + } +} diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh new file mode 100644 index 0000000000..fdba5858fc --- /dev/null +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2020 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_COMPONENTS_LIGHTCMD_HH_ +#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ + +#include + +#include +#include +#include +#include +#include + +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains commanded light of an + /// entity in the world frame represented by msgs::Light. + using LightCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", + LightCmd) +} +} +} +} +#endif diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 1c2de965b9..4d95c66b3e 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -35,6 +35,7 @@ #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/Level.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -77,6 +78,9 @@ namespace ignition::gazebo /// \brief Name of the world public: std::string worldName; + /// \brief Entity name + public: std::string entityName; + /// \brief Entity type, such as 'world' or 'model'. public: QString type; @@ -113,6 +117,50 @@ void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) }), ComponentsModel::RoleNames().key("data")); } +////////////////////////////////////////////////// +template<> +void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) +{ + int lightType = -1; + if (_data.type() == msgs::Light::POINT) + { + lightType = 0; + } + else if (_data.type() == msgs::Light::SPOT) + { + lightType = 1; + } + else if (_data.type() == msgs::Light::DIRECTIONAL) + { + lightType = 2; + } + + _item->setData(QString("Light"), + ComponentsModel::RoleNames().key("dataType")); + _item->setData(QList({ + QVariant(_data.specular().r()), + QVariant(_data.specular().g()), + QVariant(_data.specular().b()), + QVariant(_data.specular().a()), + QVariant(_data.diffuse().r()), + QVariant(_data.diffuse().g()), + QVariant(_data.diffuse().b()), + QVariant(_data.diffuse().a()), + QVariant(_data.range()), + QVariant(_data.attenuation_linear()), + QVariant(_data.attenuation_constant()), + QVariant(_data.attenuation_quadratic()), + QVariant(_data.cast_shadows()), + QVariant(_data.direction().x()), + QVariant(_data.direction().y()), + QVariant(_data.direction().z()), + QVariant(_data.spot_inner_angle()), + QVariant(_data.spot_outer_angle()), + QVariant(_data.spot_falloff()), + QVariant(lightType) + }), ComponentsModel::RoleNames().key("data")); +} + ////////////////////////////////////////////////// template<> void ignition::gazebo::setData(QStandardItem *_item, @@ -383,12 +431,6 @@ void ComponentInspector::Update(const UpdateInfo &, continue; } - if (typeId == components::Light::typeId) - { - this->SetType("light"); - continue; - } - if (typeId == components::Actor::typeId) { this->SetType("actor"); @@ -512,6 +554,7 @@ void ComponentInspector::Update(const UpdateInfo &, if (this->dataPtr->entity == this->dataPtr->worldEntity) this->dataPtr->worldName = comp->Data(); + this->dataPtr->entityName = comp->Data(); } else if (typeId == components::ParentEntity::typeId) { @@ -534,6 +577,16 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::Light::typeId) + { + this->SetType("light"); + auto comp = _ecm.Component(this->dataPtr->entity); + if (comp) + { + msgs::Light lightMsgs = convert(comp->Data()); + setData(item, lightMsgs); + } + } else if (typeId == components::Physics::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); @@ -747,6 +800,66 @@ void ComponentInspector::OnPose(double _x, double _y, double _z, double _roll, this->dataPtr->node.Request(poseCmdService, req, cb); } +///////////////////////////////////////////////// +void ComponentInspector::OnLight( + double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, + double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, + double _attRange, double _attLinear, double _attConstant, + double _attQuadratic, bool _castShadows, double _directionX, + double _directionY, double _directionZ, double _innerAngle, + double _outerAngle, double _falloff, int _type) +{ + std::function cb = + [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + { + if (!_result) + ignerr << "Error setting light configuration" << std::endl; + }; + + ignition::msgs::Light req; + req.set_name(this->dataPtr->entityName); + req.set_id(this->dataPtr->entity); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); + req.set_range(_attRange); + req.set_attenuation_linear(_attLinear); + req.set_attenuation_constant(_attConstant); + req.set_attenuation_quadratic(_attQuadratic); + req.set_cast_shadows(_castShadows); + if (_type == 0) + req.set_type(ignition::msgs::Light::POINT); + else if (_type == 1) + req.set_type(ignition::msgs::Light::SPOT); + else + req.set_type(ignition::msgs::Light::DIRECTIONAL); + + if (_type == 1) // sdf::LightType::SPOT + { + req.set_spot_inner_angle(_innerAngle); + req.set_spot_outer_angle(_outerAngle); + req.set_spot_falloff(_falloff); + } + + // if sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL + if (_type == 1 || _type == 2) + { + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(_directionX, _directionY, _directionZ)); + } + + auto lightConfigService = "/world/" + this->dataPtr->worldName + + "/light_config"; + lightConfigService = transport::TopicUtils::AsValidTopic(lightConfigService); + if (lightConfigService.empty()) + { + ignerr << "Invalid light command service topic provided" << std::endl; + return; + } + this->dataPtr->node.Request(lightConfigService, req, cb); +} + ///////////////////////////////////////////////// void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 8df6eb585b..cd6cc470b2 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -30,6 +30,8 @@ #include "ignition/gazebo/components/Physics.hh" +#include + Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) namespace ignition @@ -71,6 +73,12 @@ namespace gazebo template<> void setData(QStandardItem *_item, const math::Pose3d &_data); + /// \brief Specialized to set light data. + /// \param[in] _item Item whose data will be set. + /// \param[in] _data Data to set. + template<> + void setData(QStandardItem *_item, const msgs::Light &_data); + /// \brief Specialized to set vector data. /// \param[in] _item Item whose data will be set. /// \param[in] _data Data to set. @@ -215,6 +223,36 @@ namespace gazebo public: Q_INVOKABLE void OnPose(double _x, double _y, double _z, double _roll, double _pitch, double _yaw); + /// \brief Callback in Qt thread when specular changes. + /// \param[in] _rSpecular specular red + /// \param[in] _gSpecular specular green + /// \param[in] _bSpecular specular blue + /// \param[in] _aSpecular specular alpha + /// \param[in] _rDiffuse Diffuse red + /// \param[in] _gDiffuse Diffuse green + /// \param[in] _bDiffuse Diffuse blue + /// \param[in] _aDiffuse Diffuse alpha + /// \param[in] _attRange Range attenuation + /// \param[in] _attLinear Linear attenuation + /// \param[in] _attConstant Constant attenuation + /// \param[in] _attQuadratic Quadratic attenuation + /// \param[in] _castShadows Specify if this light should cast shadows + /// \param[in] _directionX X direction of the light + /// \param[in] _directionY Y direction of the light + /// \param[in] _directionZ Z direction of the light + /// \param[in] _innerAngle Inner angle of the spotlight + /// \param[in] _outerAngle Outer angle of the spotlight + /// \param[in] _falloff Falloff of the spotlight + /// \param[in] _type light type + public: Q_INVOKABLE void OnLight( + double _rSpecular, double _gSpecular, double _bSpecular, + double _aSpecular, double _rDiffuse, double _gDiffuse, + double _bDiffuse, double _aDiffuse, double _attRange, + double _attLinear, double _attConstant, double _attQuadratic, + bool _castShadows, double _directionX, double _directionY, + double _directionZ, double _innerAngle, double _outerAngle, + double _falloff, int _type); + /// \brief Callback in Qt thread when physics' properties change. /// \param[in] _stepSize step size /// \param[in] _realTimeFactor real time factor diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index e48bc4b393..1c3ed07414 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -86,6 +86,21 @@ Rectangle { } /** + * Forward light changes to C++ + */ + function onLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, + _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, + _attRange, _attLinear, _attConstant, _attQuadratic, + _castShadows, _directionX, _directionY, _directionZ, + _innerAngle, _outerAngle, _falloff, _type) { + ComponentInspector.OnLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, + _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, + _attRange, _attLinear, _attConstant, _attQuadratic, + _castShadows, _directionX, _directionY, _directionZ, + _innerAngle, _outerAngle, _falloff, _type) + } + + /* * Forward physics changes to C++ */ function onPhysics(_stepSize, _realTimeFactor) { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qrc b/src/gui/plugins/component_inspector/ComponentInspector.qrc index f50f8e7616..1996720cbc 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qrc +++ b/src/gui/plugins/component_inspector/ComponentInspector.qrc @@ -2,6 +2,7 @@ Boolean.qml ComponentInspector.qml + Light.qml NoData.qml Physics.qml Pose3d.qml diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml new file mode 100644 index 0000000000..68314d7053 --- /dev/null +++ b/src/gui/plugins/component_inspector/Light.qml @@ -0,0 +1,1099 @@ +/* + * Copyright (C) 2020 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 1.4 +import QtQuick.Controls 2.2 +import QtQuick.Controls.Material 2.1 +import QtQuick.Dialogs 1.0 +import QtQuick.Layouts 1.3 +import QtQuick.Controls.Styles 1.4 +import "qrc:/ComponentInspector" +import "qrc:/qml" + +// Item displaying light information. +Rectangle { + height: header.height + content.height + width: componentInspector.width + color: index % 2 == 0 ? lightGrey : darkGrey + + // Left indentation + property int indentation: 10 + + // Horizontal margins + property int margin: 5 + + property int iconWidth: 20 + property int iconHeight: 20 + + // Loaded item for specular red + property var rSpecularItem: {} + + // Loaded item for specular green + property var gSpecularItem: {} + + // Loaded item for specular blue + property var bSpecularItem: {} + + // Loaded item for specular alpha + property var aSpecularItem: {} + + // Loaded item for diffuse red + property var rDiffuseItem: {} + + // Loaded item for diffuse green + property var gDiffuseItem: {} + + // Loaded item for diffuse blue + property var bDiffuseItem: {} + + // Loaded item for diffuse alpha + property var aDiffuseItem: {} + + // Loaded item for attenuation range + property var attRangeItem: {} + + // Loaded item for attenuation linear + property var attLinearItem: {} + + // Loaded item for attenuation constant + property var attConstantItem: {} + + // Loaded item for attenuation quadratic + property var attQuadraticItem: {} + + // Loaded item for cast shadows + property var castShadowsItem: {} + + // Loaded item for direction X (spotlight or directional) + property var directionXItem: {} + + // Loaded item for direction Y (spotlight or directional) + property var directionYItem: {} + + // Loaded item for direction Z (spotlight or directional) + property var directionZItem: {} + + // Loaded item for inner angle (spotlight) + property var innerAngleItem: {} + + // Loaded item for inner angle (spotlight) + property var outerAngleItem: {} + + // Loaded item for falloff (spotlight) + property var falloffItem: {} + + // Send new light data to C++ + function sendLight() { + // TODO(anyone) There's a loss of precision when these values get to C++ + componentInspector.onLight( + rSpecularItem.value, + gSpecularItem.value, + bSpecularItem.value, + aSpecularItem.value, + rDiffuseItem.value, + gDiffuseItem.value, + bDiffuseItem.value, + aDiffuseItem.value, + attRangeItem.value, + attLinearItem.value, + attConstantItem.value, + attQuadraticItem.value, + castShadowsItem.checked, + directionXItem.value, + directionYItem.value, + directionZItem.value, + innerAngleItem.value, + outerAngleItem.value, + falloffItem.value, + model.data[19] + ); + } + + FontMetrics { + id: fontMetrics + font.family: "Roboto" + } + + /** + * Used to create a spin box + */ + Component { + id: sliderZeroOne + Slider { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + from: 0.0 + to: 1.0 + onValueChanged: { + if (hovered){ + sendLight() + } + } + } + } + + Component { + id: ignSwitch + Switch { + id: booleanSwitch + checked: numberValue + enabled: true + onToggled: { + sendLight() + } + } + } + + Component { + id: spinZeroMax + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: 0 + maximumValue: 1000000 + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } + Component { + id: spinNoLimit + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: -100000 + maximumValue: 100000 + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } + + Component { + id: plotIcon + Image { + property string componentInfo: "" + source: "plottable_icon.svg" + anchors.top: parent.top + anchors.left: parent.left + + Drag.mimeData: { "text/plain" : (model === null) ? "" : + "Component," + model.entity + "," + model.typeId + "," + + model.dataType + "," + componentInfo + "," + model.shortName + } + Drag.dragType: Drag.Automatic + Drag.supportedActions : Qt.CopyAction + Drag.active: dragMouse.drag.active + // a point to drag from + Drag.hotSpot.x: 0 + Drag.hotSpot.y: y + MouseArea { + id: dragMouse + anchors.fill: parent + drag.target: (model === null) ? null : parent + onPressed: parent.grabToImage(function(result) {parent.Drag.imageSource = result.url }) + onReleased: parent.Drag.drop(); + cursorShape: Qt.DragCopyCursor + } + } + } + + Column { + anchors.fill: parent + + // Header + Rectangle { + id: header + width: parent.width + height: typeHeader.height + color: "transparent" + + RowLayout { + anchors.fill: parent + Item { + width: margin + } + Image { + id: icon + sourceSize.height: indentation + sourceSize.width: indentation + fillMode: Image.Pad + Layout.alignment : Qt.AlignVCenter + source: content.show ? + "qrc:/Gazebo/images/minus.png" : "qrc:/Gazebo/images/plus.png" + } + TypeHeader { + id: typeHeader + } + Item { + Layout.fillWidth: true + } + } + MouseArea { + anchors.fill: parent + hoverEnabled: true + cursorShape: Qt.PointingHandCursor + onClicked: { + content.show = !content.show + } + onEntered: { + header.color = highlightColor + } + onExited: { + header.color = "transparent" + } + } + } + + // Content + Rectangle { + id: content + property bool show: false + width: parent.width + height: show ? grid.height : 0 + clip: true + color: "transparent" + + Behavior on height { + NumberAnimation { + duration: 200; + easing.type: Easing.InOutQuad + } + } + + ColumnLayout { + id: grid + width: parent.width + + RowLayout { + Layout.alignment : Qt.AlignLeft + Text { + text: " Specular" + color: "dimgrey" + width: margin + indentation + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rSpecularText.width + indentation*3 + Loader { + id: loaderSpecularR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularR.item.componentInfo = "specularR" + + Text { + id : rSpecularText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rSpecularLoader + anchors.fill: parent + property double numberValue: model.data[0] + sourceComponent: sliderZeroOne + onLoaded: { + rSpecularItem = rSpecularLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gSpecularText.width + indentation*3 + Loader { + id: loaderSpecularG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularG.item.componentInfo = "specularG" + + Text { + id : gSpecularText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gSpecularLoader + anchors.fill: parent + property double numberValue: model.data[1] + sourceComponent: sliderZeroOne + onLoaded: { + gSpecularItem = gSpecularLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bSpecularText.width + indentation*3 + Loader { + id: loaderSpecularB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularB.item.componentInfo = "specularB" + + Text { + id : bSpecularText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bSpecularLoader + anchors.fill: parent + property double numberValue: model.data[2] + sourceComponent: sliderZeroOne + onLoaded: { + bSpecularItem = bSpecularLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aSpecularText.width + indentation*3 + Loader { + id: loaderSpecularA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularA.item.componentInfo = "specularA" + + Text { + id : aSpecularText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aSpecularLoader + anchors.fill: parent + property double numberValue: model.data[3] + sourceComponent: sliderZeroOne + onLoaded: { + aSpecularItem = aSpecularLoader.item + } + } + } + } + RowLayout { + Layout.alignment: Qt.AlignHCenter + Button { + Layout.alignment: Qt.AlignHCenter + id: specularColor + text: qsTr("Specular Color") + onClicked: colorDialog.open() + ColorDialog { + id: colorDialog + title: "Choose a specular color" + visible: false + onAccepted: { + rSpecularLoader.item.value = colorDialog.color.r + gSpecularLoader.item.value = colorDialog.color.g + bSpecularLoader.item.value = colorDialog.color.b + aSpecularLoader.item.value = colorDialog.color.a + sendLight() + colorDialog.close() + } + onRejected: { + colorDialog.close() + } + } + } + } + RowLayout { + Text { + Layout.columnSpan: 6 + text: " Diffuse" + color: "dimgrey" + width: margin + indentation + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseR.item.componentInfo = "diffuseR" + + Text { + id : rDiffuseText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[4] + sourceComponent: sliderZeroOne + onLoaded: { + rDiffuseItem = rDiffuseLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseG.item.componentInfo = "diffuseG" + + Text { + id : gDiffuseText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[5] + sourceComponent: sliderZeroOne + onLoaded: { + gDiffuseItem = gDiffuseLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseB.item.componentInfo = "diffuseB" + + Text { + id : bDiffuseText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[6] + sourceComponent: sliderZeroOne + onLoaded: { + bDiffuseItem = bDiffuseLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseA.item.componentInfo = "diffuseA" + + Text { + id : aDiffuseText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[7] + sourceComponent: sliderZeroOne + onLoaded: { + aDiffuseItem = aDiffuseLoader.item + } + } + } + } + RowLayout { + Layout.alignment: Qt.AlignHCenter + Button { + Layout.alignment: Qt.AlignHCenter + id: diffuseColor + text: qsTr("Diffuse Color") + onClicked: colorDialogDiffuse.open() + ColorDialog { + id: colorDialogDiffuse + title: "Choose a diffuse color" + visible: false + onAccepted: { + rDiffuseLoader.item.value = colorDialogDiffuse.color.r + gDiffuseLoader.item.value = colorDialogDiffuse.color.g + bDiffuseLoader.item.value = colorDialogDiffuse.color.b + aDiffuseLoader.item.value = colorDialogDiffuse.color.a + sendLight() + colorDialogDiffuse.close() + } + onRejected: { + colorDialogDiffuse.close() + } + } + } + } + RowLayout { + Text { + Layout.columnSpan: 6 + text: " Attenuation" + color: "dimgrey" + width: margin + indentation + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attRangeText.width + indentation*3 + Loader { + id: loaderAttRange + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttRange.item.componentInfo = "attRange" + + Text { + id : attRangeText + text: ' Range' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attRangeLoader + anchors.fill: parent + property double numberValue: model.data[8] + sourceComponent: spinZeroMax + onLoaded: { + attRangeItem = attRangeLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attLinearText.width + indentation*3 + Loader { + id: loaderAttLinear + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttLinear.item.componentInfo = "attLinear" + + Text { + id : attLinearText + text: ' Linear' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attLinearLoader + anchors.fill: parent + property double numberValue: model.data[9] + sourceComponent: sliderZeroOne + onLoaded: { + attLinearItem = attLinearLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attConstantText.width + indentation*3 + Loader { + id: loaderAttConstant + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttConstant.item.componentInfo = "attConstant" + + Text { + id : attConstantText + text: ' Constant' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attConstantLoader + anchors.fill: parent + property double numberValue: model.data[10] + sourceComponent: sliderZeroOne + onLoaded: { + attConstantItem = attConstantLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attQuadraticText.width + indentation*3 + Loader { + id: loaderAttQuadratic + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttQuadratic.item.componentInfo = "attQuadratic" + + Text { + id : attQuadraticText + text: ' Quadratic' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attQuadraticLoader + anchors.fill: parent + property double numberValue: model.data[11] + sourceComponent: spinZeroMax + onLoaded: { + attQuadraticItem = attQuadraticLoader.item + } + } + } + } + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: castShadowsText.width + indentation*3 + Loader { + id: loaderCastShadows + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderCastShadows.item.componentInfo = "castshadows" + + Text { + id : castShadowsText + text: ' Cast shadows' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + + Loader { + id: castShadowLoader + anchors.fill: parent + property double numberValue: model.data[12] + sourceComponent: ignSwitch + onLoaded: { + castShadowsItem = castShadowLoader.item + } + } + } + } + RowLayout { + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + Layout.columnSpan: 6 + text: " Direction" + color: "dimgrey" + width: margin + indentation + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: xDirectionText.width + indentation*3 + Loader { + id: loaderDirectionX + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionX.item.componentInfo = "directionX" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : xDirectionText + text: ' X:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 || model.data[19] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: xDirectionLoader + anchors.fill: parent + property double numberValue: model.data[13] + sourceComponent: spinNoLimit + onLoaded: { + directionXItem = xDirectionLoader.item + } + } + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: yDirectionText.width + indentation*3 + Loader { + id: loaderDirectionY + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionY.item.componentInfo = "directionY" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : yDirectionText + text: ' Y:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 || model.data[19] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: yDirectionLoader + anchors.fill: parent + property double numberValue: model.data[14] + sourceComponent: spinNoLimit + onLoaded: { + directionYItem = yDirectionLoader.item + } + } + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: zDirectionText.width + indentation*3 + Loader { + id: loaderDirectionZ + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionZ.item.componentInfo = "directionZ" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : zDirectionText + text: ' Z:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 || model.data[19] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: zDirectionLoader + anchors.fill: parent + property double numberValue: model.data[15] + sourceComponent: spinNoLimit + onLoaded: { + directionZItem = zDirectionLoader.item + } + } + } + } + RowLayout { + Text { + visible: model.data[19] === 1 + Layout.columnSpan: 6 + text: " Spot features" + color: "dimgrey" + width: margin + indentation + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: innerAngleText.width + indentation*3 + Loader { + id: loaderInnerAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderInnerAngle.item.componentInfo = "innerAngle" + + Text { + visible: model.data[19] === 1 + id : innerAngleText + text: ' Inner Angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: innerAngleLoader + anchors.fill: parent + property double numberValue: model.data[16] + sourceComponent: spinNoLimit + onLoaded: { + innerAngleItem = innerAngleLoader.item + } + } + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: outerAngleText.width + indentation*3 + Loader { + id: loaderOuterAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderOuterAngle.item.componentInfo = "outerAngle" + + Text { + visible: model.data[19] === 1 + id : outerAngleText + text: ' Outer angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: outerAngleLoader + anchors.fill: parent + property double numberValue: model.data[17] + sourceComponent: spinNoLimit + onLoaded: { + outerAngleItem = outerAngleLoader.item + } + } + } + } + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: fallOffText.width + indentation*3 + Loader { + id: loaderFallOff + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderFallOff.item.componentInfo = "falloff" + + Text { + visible: model.data[19] === 1 + id : fallOffText + text: ' Falloff:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: fallOffLoader + anchors.fill: parent + property double numberValue: model.data[18] + sourceComponent: spinZeroMax + onLoaded: { + falloffItem = fallOffLoader.item + } + } + } + } + } + } + } +} diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 876e3e613a..864eebb1c9 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -23,6 +23,7 @@ #include "ignition/gazebo/components/CastShadows.hh" #include "ignition/gazebo/components/Factory.hh" #include "ignition/gazebo/components/Gravity.hh" +#include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -95,6 +96,28 @@ PlotComponent::PlotComponent(const std::string &_type, this->dataPtr->data["pitch"] = std::make_shared(); this->dataPtr->data["yaw"] = std::make_shared(); } + else if (_type == "Light") + { + this->dataPtr->data["diffuseR"] = std::make_shared(); + this->dataPtr->data["diffuseG"] = std::make_shared(); + this->dataPtr->data["diffuseB"] = std::make_shared(); + this->dataPtr->data["diffuseA"] = std::make_shared(); + this->dataPtr->data["specularR"] = std::make_shared(); + this->dataPtr->data["specularG"] = std::make_shared(); + this->dataPtr->data["specularB"] = std::make_shared(); + this->dataPtr->data["specularA"] = std::make_shared(); + this->dataPtr->data["attRange"] = std::make_shared(); + this->dataPtr->data["attConstant"] = std::make_shared(); + this->dataPtr->data["attLinear"] = std::make_shared(); + this->dataPtr->data["attQuadratic"] = std::make_shared(); + this->dataPtr->data["castshadows"] = std::make_shared(); + this->dataPtr->data["directionX"] = std::make_shared(); + this->dataPtr->data["directionY"] = std::make_shared(); + this->dataPtr->data["directionZ"] = std::make_shared(); + this->dataPtr->data["innerAngle"] = std::make_shared(); + this->dataPtr->data["outerAngle"] = std::make_shared(); + this->dataPtr->data["falloff"] = std::make_shared(); + } else if (_type == "double") this->dataPtr->data["value"] = std::make_shared(); else if (_type == "Physics") @@ -209,6 +232,57 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) this->dataPtr->components[_Id]->SetAttributeValue("z", _vector.Z()); } +void Plotting::SetData(std::string _Id, const msgs::Light &_light) +{ + if (_light.has_specular()) + { + this->dataPtr->components[_Id]->SetAttributeValue("specularR", + _light.specular().r()); + this->dataPtr->components[_Id]->SetAttributeValue("specularG", + _light.specular().g()); + this->dataPtr->components[_Id]->SetAttributeValue("specularB", + _light.specular().b()); + this->dataPtr->components[_Id]->SetAttributeValue("specularA", + _light.specular().a()); + } + if (_light.has_diffuse()) + { + this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", + _light.diffuse().r()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", + _light.diffuse().g()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", + _light.diffuse().b()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", + _light.diffuse().a()); + } + this->dataPtr->components[_Id]->SetAttributeValue("attRange", + _light.range()); + this->dataPtr->components[_Id]->SetAttributeValue("attLinear", + _light.attenuation_linear()); + this->dataPtr->components[_Id]->SetAttributeValue("attConstant", + _light.attenuation_constant()); + this->dataPtr->components[_Id]->SetAttributeValue("attQuadratic", + _light.attenuation_quadratic()); + this->dataPtr->components[_Id]->SetAttributeValue("castshadows", + _light.cast_shadows()); + if (_light.has_direction()) + { + this->dataPtr->components[_Id]->SetAttributeValue("directionX", + _light.direction().x()); + this->dataPtr->components[_Id]->SetAttributeValue("directionY", + _light.direction().y()); + this->dataPtr->components[_Id]->SetAttributeValue("directionZ", + _light.direction().z()); + } + this->dataPtr->components[_Id]->SetAttributeValue("innerAngle", + _light.spot_inner_angle()); + this->dataPtr->components[_Id]->SetAttributeValue("outerAngle", + _light.spot_outer_angle()); + this->dataPtr->components[_Id]->SetAttributeValue("falloff", + _light.spot_falloff()); +} + ////////////////////////////////////////////////// void Plotting::SetData(std::string _Id, const ignition::math::Pose3d &_pose) { @@ -403,6 +477,15 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, if (comp) this->SetData(component.first, comp->Data()); } + else if (typeId == components::Light::typeId) + { + auto comp = _ecm.Component(entity); + if (comp) + { + msgs::Light lightMsgs = convert(comp->Data()); + this->SetData(component.first, lightMsgs); + } + } for (auto attribute : component.second->Data()) { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index 24601bdc6b..534d9a5008 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -23,6 +23,7 @@ #include #include #include +#include #include "sdf/Physics.hh" @@ -115,6 +116,12 @@ class Plotting : public ignition::gazebo::GuiSystem public: void SetData(std::string _Id, const ignition::math::Vector3d &_vector); + /// \brief Set the Component data of giving id to the giving light + /// \param [in] _Id Component Key of the components map + /// \param [in] _light Vector Data to be set to the component + public: void SetData(std::string _Id, + const msgs::Light &_light); + /// \brief Set the Component data of giving id to the giving pose /// \param [in] _Id Component Key of the components map /// \param [in] _pose Position Data to be set to the component diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b22da15d99..e43b749893 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2752,6 +2752,7 @@ void Scene3D::Update(const UpdateInfo &_info, msgs::Pose poseMsg = msgs::Convert(renderWindow->CameraPose()); this->dataPtr->cameraPosePub.Publish(poseMsg); } + this->dataPtr->renderUtil->UpdateECM(_info, _ecm); this->dataPtr->renderUtil->UpdateFromECM(_info, _ecm); // check if video recording is enabled and if we need to lock step diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index c1c507713b..ae94373ebd 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -42,6 +42,8 @@ #include #include +#include + #include #include #include @@ -55,6 +57,7 @@ #include "ignition/gazebo/components/GpuLidar.hh" #include "ignition/gazebo/components/Geometry.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Material.hh" #include "ignition/gazebo/components/Model.hh" @@ -170,6 +173,12 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of entity ids and pose updates. public: std::unordered_map entityPoses; + /// \brief A map of entity ids and light updates. + public: std::unordered_map entityLights; + + /// \brief A map of entity ids and light updates. + public: std::vector entityLightsCmdToDelete; + /// \brief A map of entity ids and actor transforms. public: std::map> actorTransforms; @@ -218,6 +227,36 @@ class ignition::gazebo::RenderUtilPrivate public: std::function createSensorCb; + /// \brief Light equality comparison function. + public: std::function + lightEql { [](const sdf::Light &_a, const sdf::Light &_b) + { + return + _a.Type() == _b.Type() && + _a.Name() == _b.Name() && + _a.Diffuse() == _b.Diffuse() && + _a.Specular() == _b.Specular() && + math::equal( + _a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && + math::equal( + _a.LinearAttenuationFactor(), + _b.LinearAttenuationFactor(), + 1e-6) && + math::equal( + _a.ConstantAttenuationFactor(), + _b.ConstantAttenuationFactor(), + 1e-6) && + math::equal( + _a.QuadraticAttenuationFactor(), + _b.QuadraticAttenuationFactor(), + 1e-6) && + _a.CastShadows() == _b.CastShadows() && + _a.Direction() == _b.Direction() && + _a.SpotInnerAngle() == _b.SpotInnerAngle() && + _a.SpotOuterAngle() == _b.SpotOuterAngle() && + math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); + }}; + /// \brief Callback function for removing sensors. /// The function arg is the entity id public: std::function removeSensorCb; @@ -289,6 +328,37 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, EntityComponentManager &_ecm) { std::lock_guard lock(this->dataPtr->updateMutex); + + // Update lights + auto olderEntitiesLightsCmdToDelete = + std::move(this->dataPtr->entityLightsCmdToDelete); + this->dataPtr->entityLightsCmdToDelete.clear(); + + _ecm.Each( + [&](const Entity &_entity, + const components::LightCmd * _lightCmd) -> bool + { + this->dataPtr->entityLights[_entity] = _lightCmd->Data(); + this->dataPtr->entityLightsCmdToDelete.push_back(_entity); + + auto lightComp = _ecm.Component(_entity); + if (lightComp) + { + sdf::Light sdfLight = convert(_lightCmd->Data()); + auto state = lightComp->SetData(sdfLight, + this->dataPtr->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + _ecm.SetChanged(_entity, components::Light::typeId, state); + } + return true; + }); + + for (const auto entity : olderEntitiesLightsCmdToDelete) + { + _ecm.RemoveComponent(entity); + } + // Update thermal cameras _ecm.Each( [&](const Entity &_entity, @@ -415,6 +485,7 @@ void RenderUtil::Update() auto newLights = std::move(this->dataPtr->newLights); auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); + auto entityLights = std::move(this->dataPtr->entityLights); auto trajectoryPoses = std::move(this->dataPtr->trajectoryPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); auto actorAnimationData = std::move(this->dataPtr->actorAnimationData); @@ -430,6 +501,7 @@ void RenderUtil::Update() this->dataPtr->newLights.clear(); this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); + this->dataPtr->entityLights.clear(); this->dataPtr->trajectoryPoses.clear(); this->dataPtr->actorTransforms.clear(); this->dataPtr->actorAnimationData.clear(); @@ -562,6 +634,95 @@ void RenderUtil::Update() } } + // update lights + { + IGN_PROFILE("RenderUtil::Update Lights"); + for (const auto &light : entityLights) { + auto node = this->dataPtr->sceneManager.NodeById(light.first); + if (!node) + continue; + auto l = std::dynamic_pointer_cast(node); + if (l) + { + if (light.second.has_diffuse()) + { + if (l->DiffuseColor() != msgs::Convert(light.second.diffuse())) + l->SetDiffuseColor(msgs::Convert(light.second.diffuse())); + } + if (light.second.has_specular()) + { + if (l->SpecularColor() != msgs::Convert(light.second.specular())) + { + l->SetSpecularColor(msgs::Convert(light.second.specular())); + } + } + if (!ignition::math::equal( + l->AttenuationRange(), + static_cast(light.second.range()))) + { + l->SetAttenuationRange(light.second.range()); + } + if (!ignition::math::equal( + l->AttenuationLinear(), + static_cast(light.second.attenuation_linear()))) + { + l->SetAttenuationLinear(light.second.attenuation_linear()); + } + if (!ignition::math::equal( + l->AttenuationConstant(), + static_cast(light.second.attenuation_constant()))) + { + l->SetAttenuationConstant(light.second.attenuation_constant()); + } + if (!ignition::math::equal( + l->AttenuationQuadratic(), + static_cast(light.second.attenuation_quadratic()))) + { + l->SetAttenuationQuadratic(light.second.attenuation_quadratic()); + } + if (l->CastShadows() != light.second.cast_shadows()) + l->SetCastShadows(light.second.cast_shadows()); + auto lDirectional = + std::dynamic_pointer_cast(node); + if (lDirectional) + { + if (light.second.has_direction()) + { + if (lDirectional->Direction() != + msgs::Convert(light.second.direction())) + { + lDirectional->SetDirection( + msgs::Convert(light.second.direction())); + } + } + } + auto lSpotLight = + std::dynamic_pointer_cast(node); + if (lSpotLight) + { + if (light.second.has_direction()) + { + if (lSpotLight->Direction() != + msgs::Convert(light.second.direction())) + { + lSpotLight->SetDirection( + msgs::Convert(light.second.direction())); + } + } + if (lSpotLight->InnerAngle() != light.second.spot_inner_angle()) + lSpotLight->SetInnerAngle(light.second.spot_inner_angle()); + if (lSpotLight->OuterAngle() != light.second.spot_outer_angle()) + lSpotLight->SetOuterAngle(light.second.spot_outer_angle()); + if (!ignition::math::equal( + lSpotLight->Falloff(), + static_cast(light.second.spot_falloff()))) + { + lSpotLight->SetFalloff(light.second.spot_falloff()); + } + } + } + } + } // update entities' pose { IGN_PROFILE("RenderUtil::Update Poses"); @@ -1367,7 +1528,7 @@ void RenderUtilPrivate::UpdateRenderingEntities( return true; }); - // lights + // update lights _ecm.Each( [&](const Entity &_entity, const components::Light *, diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 8ff22c10c8..c98d4e91df 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include #include @@ -32,6 +33,7 @@ #include #include #include +#include #include #include @@ -39,6 +41,8 @@ #include "ignition/common/Profiler.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" +#include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" @@ -127,6 +131,70 @@ class RemoveCommand : public UserCommandBase public: bool Execute() final; }; +/// \brief Command to modify a light entity from simulation. +class LightCommand : public UserCommandBase +{ + /// \brief Constructor + /// \param[in] _msg Message identifying the entity to be edited. + /// \param[in] _iface Pointer to user commands interface. + public: LightCommand(msgs::Light *_msg, + std::shared_ptr &_iface); + + // Documentation inherited + public: bool Execute() final; + + /// \brief Light equality comparison function. + public: std::function + lightEql { [](const msgs::Light &_a, const msgs::Light &_b) + { + return + _a.type() == _b.type() && + _a.name() == _b.name() && + math::equal( + _a.diffuse().a(), _b.diffuse().a(), 1e-6f) && + math::equal( + _a.diffuse().r(), _b.diffuse().r(), 1e-6f) && + math::equal( + _a.diffuse().g(), _b.diffuse().g(), 1e-6f) && + math::equal( + _a.diffuse().b(), _b.diffuse().b(), 1e-6f) && + math::equal( + _a.specular().a(), _b.specular().a(), 1e-6f) && + math::equal( + _a.specular().r(), _b.specular().r(), 1e-6f) && + math::equal( + _a.specular().g(), _b.specular().g(), 1e-6f) && + math::equal( + _a.specular().b(), _b.specular().b(), 1e-6f) && + math::equal( + _a.range(), _b.range(), 1e-6f) && + math::equal( + _a.attenuation_linear(), + _b.attenuation_linear(), + 1e-6f) && + math::equal( + _a.attenuation_constant(), + _b.attenuation_constant(), + 1e-6f) && + math::equal( + _a.attenuation_quadratic(), + _b.attenuation_quadratic(), + 1e-6f) && + _a.cast_shadows() == _b.cast_shadows() && + math::equal( + _a.direction().x(), _b.direction().x(), 1e-6) && + math::equal( + _a.direction().y(), _b.direction().y(), 1e-6) && + math::equal( + _a.direction().z(), _b.direction().z(), 1e-6) && + math::equal( + _a.spot_inner_angle(), _b.spot_inner_angle(), 1e-6f) && + math::equal( + _a.spot_outer_angle(), _b.spot_outer_angle(), 1e-6f) && + math::equal(_a.spot_falloff(), _b.spot_falloff(), 1e-6f); + }}; +}; + /// \brief Command to update an entity's pose transform. class PoseCommand : public UserCommandBase { @@ -195,6 +263,13 @@ class ignition::gazebo::systems::UserCommandsPrivate public: bool RemoveService(const msgs::Entity &_req, msgs::Boolean &_res); + /// \brief Callback for light service + /// \param[in] _req Request containing light update of an entity. + /// \param[in] _res True if message successfully received and queued. + /// It does not mean that the light will be successfully updated. + /// \return True if successful. + public: bool LightService(const msgs::Light &_req, msgs::Boolean &_res); + /// \brief Callback for pose service /// \param[in] _req Request containing pose update of an entity. /// \param[in] _res True if message successfully received and queued. @@ -283,6 +358,14 @@ void UserCommands::Configure(const Entity &_entity, ignmsg << "Pose service on [" << poseService << "]" << std::endl; + // Light service + std::string lightService{"/world/" + validWorldName + "/light_config"}; + this->dataPtr->node.Advertise(lightService, + &UserCommandsPrivate::LightService, this->dataPtr.get()); + + ignmsg << "Light configuration service on [" << lightService << "]" + << std::endl; + // Physics service std::string physicsService{"/world/" + validWorldName + "/set_physics"}; this->dataPtr->node.Advertise(physicsService, @@ -381,6 +464,25 @@ bool UserCommandsPrivate::RemoveService(const msgs::Entity &_req, return true; } +////////////////////////////////////////////////// +bool UserCommandsPrivate::LightService(const msgs::Light &_req, + msgs::Boolean &_res) +{ + // Create command and push it to queue + auto msg = _req.New(); + msg->CopyFrom(_req); + auto cmd = std::make_unique(msg, this->iface); + + // Push to pending + { + std::lock_guard lock(this->pendingMutex); + this->pendingCmds.push_back(std::move(cmd)); + } + + _res.set_data(true); + return true; +} + ////////////////////////////////////////////////// bool UserCommandsPrivate::PoseService(const msgs::Pose &_req, msgs::Boolean &_res) @@ -706,6 +808,93 @@ bool RemoveCommand::Execute() return true; } + +////////////////////////////////////////////////// +LightCommand::LightCommand(msgs::Light *_msg, + std::shared_ptr &_iface) + : UserCommandBase(_msg, _iface) +{ +} + +////////////////////////////////////////////////// +bool LightCommand::Execute() +{ + auto lightMsg = dynamic_cast(this->msg); + if (nullptr == lightMsg) + { + ignerr << "Internal error, null light message" << std::endl; + return false; + } + + Entity lightEntity{kNullEntity}; + + if (lightMsg->id() != kNullEntity) + { + lightEntity = lightMsg->id(); + } + else if (!lightMsg->name().empty()) + { + if (lightMsg->parent_id() != kNullEntity) + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name()), + components::ParentEntity(lightMsg->parent_id())); + } + else + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name())); + } + } + if (kNullEntity == lightEntity) + { + ignerr << "Failed to find light with name [" << lightMsg->name() + << "], ID [" << lightMsg->id() << "] and parent ID [" + << lightMsg->parent_id() << "]." << std::endl; + return false; + } + + if (!lightEntity) + { + ignmsg << "Failed to find light entity named [" << lightMsg->name() + << "]." << std::endl; + return false; + } + + auto lightPose = this->iface->ecm->Component(lightEntity); + if (nullptr == lightPose) + lightEntity = kNullEntity; + + if (!lightEntity) + { + ignmsg << "Pose component not available" << std::endl; + return false; + } + + if (lightMsg->has_pose()) + { + lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); + } + + auto lightCmdComp = + this->iface->ecm->Component(lightEntity); + if (!lightCmdComp) + { + this->iface->ecm->CreateComponent( + lightEntity, components::LightCmd(*lightMsg)); + } + else + { + auto state = lightCmdComp->SetData(*lightMsg, this->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, + state); + } + + return true; +} + ////////////////////////////////////////////////// PoseCommand::PoseCommand(msgs::Pose *_msg, std::shared_ptr &_iface) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 347135fc59..381a5a961e 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -693,6 +694,232 @@ TEST_F(UserCommandsTest, Pose) EXPECT_NEAR(500.0, poseComp->Data().Pos().Y(), 0.2); } +///////////////////////////////////////////////// +TEST_F(UserCommandsTest, Light) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = ignition::common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "lights_render.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system just to get the ECM + EntityComponentManager *ecm{nullptr}; + test::Relay testSystem; + testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + ecm = &_ecm; + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server and check we have the ECM + EXPECT_EQ(nullptr, ecm); + server.Run(true, 1, false); + EXPECT_NE(nullptr, ecm); + + msgs::Light req; + msgs::Boolean res; + transport::Node node; + bool result; + unsigned int timeout = 1000; + std::string service{"/world/lights_command/light_config"}; + + // Point light + auto pointLightEntity = ecm->EntityByComponents(components::Name("point")); + EXPECT_NE(kNullEntity, pointLightEntity); + + // Check point light entity has not been edited yet - Initial values + auto pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + EXPECT_EQ( + math::Pose3d(0, -1.5, 3, 0, 0, 0), pointLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(1, 0, 0, 1), pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.1, 0.1, 0.1, 1), pointLightComp->Data().Specular()); + EXPECT_NEAR(4.0, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.5, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.2, pointLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(0.01, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_FALSE(pointLightComp->Data().CastShadows()); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(0, 1, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.2, 0.2, 0.2, 0.2)); + req.set_range(2.6); + req.set_name("point"); + req.set_type(ignition::msgs::Light::POINT); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(0.001); + req.set_cast_shadows(true); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + // Check point light entity has been edited using the service + pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + + EXPECT_EQ(math::Color(0, 1, 1, 0), pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 0.2), + pointLightComp->Data().Specular()); + EXPECT_NEAR(2.6, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, pointLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(0.001, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_TRUE(pointLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); + + // Check directional light entity has not been edited yet - Initial values + auto directionalLightEntity = ecm->EntityByComponents( + components::Name("directional")); + EXPECT_NE(kNullEntity, directionalLightEntity); + + auto directionalLightComp = + ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ( + math::Pose3d(0, 0, 10, 0, 0, 0), directionalLightComp->Data().RawPose()); + EXPECT_EQ( + math::Color(0.8, 0.8, 0.8, 1), directionalLightComp->Data().Diffuse()); + EXPECT_EQ( + math::Color(0.2, 0.2, 0.2, 1), directionalLightComp->Data().Specular()); + EXPECT_NEAR(100, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR( + 0.01, directionalLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR( + 0.9, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.001, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.001); + EXPECT_EQ( + math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction()); + EXPECT_TRUE(directionalLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(0, 1, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.3, 0.3, 0.3, 0.3)); + req.set_range(2.6); + req.set_name("directional"); + req.set_type(ignition::msgs::Light::DIRECTIONAL); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(1); + req.set_cast_shadows(false); + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(1, 2, 3)); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + // Check directional light entity has been edited using the service + directionalLightComp = + ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ(math::Color(0, 1, 1, 0), directionalLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3, 0.3, 0.3, 0.3), + directionalLightComp->Data().Specular()); + EXPECT_NEAR(2.6, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR( + 0.7, directionalLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.6, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_EQ(math::Vector3d(1, 2, 3), directionalLightComp->Data().Direction()); + EXPECT_FALSE(directionalLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::DIRECTIONAL, + directionalLightComp->Data().Type()); + + // spot light + auto spotLightEntity = ecm->EntityByComponents( + components::Name("spot")); + EXPECT_NE(kNullEntity, spotLightEntity); + + // Check spot light entity has not been edited yet - Initial values + auto spotLightComp = + ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), spotLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(0, 1, 0, 1), spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), spotLightComp->Data().Specular()); + EXPECT_NEAR(5, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.4, spotLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR(0.3, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.001, spotLightComp->Data().QuadraticAttenuationFactor(), 0.001); + EXPECT_EQ(math::Vector3d(0, 0, -1), spotLightComp->Data().Direction()); + EXPECT_FALSE(spotLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); + EXPECT_NEAR(0.1, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); + EXPECT_NEAR(0.5, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); + EXPECT_NEAR(0.8, spotLightComp->Data().SpotFalloff(), 0.1); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(1, 0, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.3, 0.3, 0.3, 0.3)); + req.set_range(2.6); + req.set_name("spot"); + req.set_type(ignition::msgs::Light::SPOT); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(1); + req.set_cast_shadows(true); + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(1, 2, 3)); + req.set_spot_inner_angle(1.5); + req.set_spot_outer_angle(0.3); + req.set_spot_falloff(0.9); + + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 100, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + // Check spot light entity has been edited using the service + spotLightComp = ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Color(1, 0, 1, 0), spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3, 0.3, 0.3, 0.3), + spotLightComp->Data().Specular()); + EXPECT_NEAR(2.6, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, spotLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(1, spotLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_EQ(math::Vector3d(1, 2, 3), spotLightComp->Data().Direction()); + EXPECT_TRUE(spotLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); + EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); + EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); + EXPECT_NEAR(0.9, spotLightComp->Data().SpotFalloff(), 0.1); +} + ///////////////////////////////////////////////// TEST_F(UserCommandsTest, Physics) { diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index 5454c28fd6..6f5daa40af 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -13,7 +13,6 @@ filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"> - true 0 0 10 0 0 0 @@ -63,7 +62,7 @@ 0 0.0 0.0 0 0 0 - + 0.5 @@ -75,7 +74,6 @@ 0.3 0.3 0.3 1 - 0 0 1.0 0 0 0 0 0 1 1 @@ -88,9 +86,7 @@ false - - diff --git a/test/worlds/lights_render.sdf b/test/worlds/lights_render.sdf new file mode 100644 index 0000000000..3f4d677460 --- /dev/null +++ b/test/worlds/lights_render.sdf @@ -0,0 +1,116 @@ + + + + + 0.001 + 1.0 + + + + + + + ogre + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 100 + 0.9 + 0.01 + 0.001 + + 0.5 0.2 -0.9 + + + + 0 -1.5 3 0 0 0 + 1 0 0 1 + .1 .1 .1 1 + + 4 + 0.2 + 0.5 + 0.01 + + false + + + + 0 1.5 3 0 0 0 + 0 1 0 1 + .2 .2 .2 1 + + 5 + 0.3 + 0.4 + 0.001 + + 0 0 -1 + + 0.1 + 0.5 + 0.8 + + false + + + + 0 0.0 0.0 0 0 0 + + + + 1 0 1.3 0 0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + false + camera + + + + + 0.5 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + + + + 0 0 1.0 0 0 0 + 0 0 1 1 + .1 .1 .1 1 + + 2 + 0.05 + 0.02 + 0.01 + + false + + + + + diff --git a/tutorials.md.in b/tutorials.md.in index 2fb4a7d3c7..4b5976a5cd 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -15,6 +15,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage entity_creation "Entity creation": Insert models or lights using services. * \subpage log "Logging": Record and play back time series of world state. * \subpage physics "Physics engines": Loading different physics engines. +* \subpage light_config "Light config": Configure lights in the scene. * \subpage battery "Battery": Keep track of battery charge on robot models. * \subpage gui_config "GUI configuration": Customizing your layout. * \subpage server_config "Server configuration": Customizing what system plugins are loaded. diff --git a/tutorials/light_config.md b/tutorials/light_config.md new file mode 100644 index 0000000000..8a87170faf --- /dev/null +++ b/tutorials/light_config.md @@ -0,0 +1,45 @@ +\page light_config Light config + +This tutorial gives an introduction to Ignition Gazebo's service `/world//light_config`. +This service will allow to modify lights in the scene. + +# Modifying lights + +To modify lights inside the scene we need to use the service `/world//light_config` and +fill the message [`ignition::msgs::Light`](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). +In particular this example modifies the point light that we introduced with the function `createLight()`. + +\snippet examples/standalone/light_control/light_control.cc create light + +**NOTE:**: You can check the [entity creation](entity_creation.html) tutorial to learn how to include models and lights in the scene. + +As you can see in the snippet we modify the specular and diffuse colors of the light in the scene. + +\snippet examples/standalone/light_control/light_control.cc modify light + +In this case we are creating random numbers to fill the diffuse and specular. + +\snippet examples/standalone/light_control/light_control.cc random numbers + +# Run the example + +To run this example you should `cd` into `examples/standalone/light_control` and build the code: + +```bash +mkdir build +cd build +cmake .. +make +``` + +Then you should open two terminals and run: + + - Terminal one: + ```bash + ign gazebo -r -v 4 empty.sdf + ``` + + - Terminal two: + ```bash + ./light_control + ``` From e77e3763cc69a72f34f0b992fc8867ab7aa3f34c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 18 Feb 2021 02:49:39 +0100 Subject: [PATCH 41/55] Particle system - Part2 (#562) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero Co-authored-by: Ashton Larkin Co-authored-by: Ian Chen --- examples/worlds/particle_emitter.sdf | 90 +++++ .../gazebo/components/ParticleEmitter.hh | 7 + .../ignition/gazebo/rendering/SceneManager.hh | 17 + src/gui/plugins/scene3d/Scene3D.cc | 1 + src/rendering/RenderUtil.cc | 83 +++++ src/rendering/SceneManager.cc | 192 +++++++++- src/systems/CMakeLists.txt | 1 + src/systems/particle_emitter/CMakeLists.txt | 9 + .../particle_emitter/ParticleEmitter.cc | 335 ++++++++++++++++++ .../particle_emitter/ParticleEmitter.hh | 141 ++++++++ test/integration/CMakeLists.txt | 1 + test/integration/components.cc | 21 ++ test/integration/particle_emitter.cc | 170 +++++++++ test/worlds/particle_emitter.sdf | 148 ++++++++ 14 files changed, 1201 insertions(+), 15 deletions(-) create mode 100644 examples/worlds/particle_emitter.sdf create mode 100644 src/systems/particle_emitter/CMakeLists.txt create mode 100644 src/systems/particle_emitter/ParticleEmitter.cc create mode 100644 src/systems/particle_emitter/ParticleEmitter.hh create mode 100644 test/integration/particle_emitter.cc create mode 100644 test/worlds/particle_emitter.sdf diff --git a/examples/worlds/particle_emitter.sdf b/examples/worlds/particle_emitter.sdf new file mode 100644 index 0000000000..58fb36c3be --- /dev/null +++ b/examples/worlds/particle_emitter.sdf @@ -0,0 +1,90 @@ + + + + + + + + + 0.001 + 1.0 + + + + + + + + + + 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 + + + + + + + 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 + + + + + + + https://fuel.ignitionrobotics.org/1.0/caguero/models/smoke_generator + + + + + + diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index a6ec2a242c..86fc36bd88 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -37,6 +37,13 @@ namespace components serializers::MsgSerializer>; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", ParticleEmitter) + + /// \brief A component that contains a particle emitter command. + using ParticleEmitterCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd", + ParticleEmitterCmd) } } } diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 113c8731a8..f7643e250f 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -34,6 +34,8 @@ #include #include +#include + #include #include @@ -161,6 +163,21 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: rendering::LightPtr CreateLight(Entity _id, const sdf::Light &_light, Entity _parentId); + /// \brief Create a particle emitter. + /// \param[in] _id Unique particle emitter id + /// \param[in] _emitter Particle emitter data + /// \param[in] _parentId Parent id + /// \return Default particle emitter object created + public: rendering::ParticleEmitterPtr CreateParticleEmitter( + Entity _id, const msgs::ParticleEmitter &_emitter, Entity _parentId); + + /// \brief Update an existing particle emitter + /// \brief _id Emitter id to update + /// \brief _emitter Data to update the particle emitter + /// \return Particle emitter updated + public: rendering::ParticleEmitterPtr UpdateParticleEmitter(Entity _id, + const msgs::ParticleEmitter &_emitter); + /// \brief Ignition sensors is the one responsible for adding sensors /// to the scene. Here we just keep track of it and make sure it has /// the correct parent. diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b22da15d99..e43b749893 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2752,6 +2752,7 @@ void Scene3D::Update(const UpdateInfo &_info, msgs::Pose poseMsg = msgs::Convert(renderWindow->CameraPose()); this->dataPtr->cameraPosePub.Publish(poseMsg); } + this->dataPtr->renderUtil->UpdateECM(_info, _ecm); this->dataPtr->renderUtil->UpdateFromECM(_info, _ecm); // check if video recording is enabled and if we need to lock step diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index c1c507713b..d1f833d12d 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -42,6 +42,8 @@ #include #include +#include + #include #include #include @@ -60,6 +62,7 @@ #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/components/ParticleEmitter.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/RgbdCamera.hh" #include "ignition/gazebo/components/Scene.hh" @@ -163,6 +166,17 @@ class ignition::gazebo::RenderUtilPrivate public: std::vector> newSensors; + /// \brief New particle emitter to be created. The elements in the tuple are: + /// [0] entity id, [1], particle emitter, [2] parent entity id + public: std::vector> + newParticleEmitters; + + /// \brief New particle emitter commands to be requested. + /// The map key and value are: entity id of the particle emitter to + /// update, and particle emitter msg + public: std::unordered_map + newParticleEmittersCmds; + /// \brief Map of ids of entites to be removed and sim iteration when the /// remove request is received public: std::unordered_map removeEntities; @@ -289,6 +303,28 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, EntityComponentManager &_ecm) { std::lock_guard lock(this->dataPtr->updateMutex); + + // particle emitters commands + _ecm.Each( + [&](const Entity &_entity, + const components::ParticleEmitterCmd *_emitterCmd) -> bool + { + // store emitter properties and update them in rendering thread + this->dataPtr->newParticleEmittersCmds[_entity] = + _emitterCmd->Data(); + + // update pose comp here + if (_emitterCmd->Data().has_pose()) + { + auto poseComp = _ecm.Component(_entity); + if (poseComp) + poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose()); + } + _ecm.RemoveComponent(_entity); + + return true; + }); + // Update thermal cameras _ecm.Each( [&](const Entity &_entity, @@ -413,6 +449,9 @@ void RenderUtil::Update() auto newVisuals = std::move(this->dataPtr->newVisuals); auto newActors = std::move(this->dataPtr->newActors); auto newLights = std::move(this->dataPtr->newLights); + auto newParticleEmitters = std::move(this->dataPtr->newParticleEmitters); + auto newParticleEmittersCmds = + std::move(this->dataPtr->newParticleEmittersCmds); auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); auto trajectoryPoses = std::move(this->dataPtr->trajectoryPoses); @@ -428,6 +467,8 @@ void RenderUtil::Update() this->dataPtr->newVisuals.clear(); this->dataPtr->newActors.clear(); this->dataPtr->newLights.clear(); + this->dataPtr->newParticleEmitters.clear(); + this->dataPtr->newParticleEmittersCmds.clear(); this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); this->dataPtr->trajectoryPoses.clear(); @@ -529,6 +570,18 @@ void RenderUtil::Update() std::get<0>(light), std::get<1>(light), std::get<2>(light)); } + for (const auto &emitter : newParticleEmitters) + { + this->dataPtr->sceneManager.CreateParticleEmitter( + std::get<0>(emitter), std::get<1>(emitter), std::get<2>(emitter)); + } + + for (const auto &emitterCmd : newParticleEmittersCmds) + { + this->dataPtr->sceneManager.UpdateParticleEmitter( + emitterCmd.first, emitterCmd.second); + } + if (this->dataPtr->enableSensors && this->dataPtr->createSensorCb) { for (const auto &sensor : newSensors) @@ -1013,6 +1066,17 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // particle emitters + _ecm.Each( + [&](const Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::ParentEntity *_parent) -> bool + { + this->newParticleEmitters.push_back( + std::make_tuple(_entity, _emitter->Data(), _parent->Data())); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -1224,6 +1288,17 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // particle emitters + _ecm.EachNew( + [&](const Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::ParentEntity *_parent) -> bool + { + this->newParticleEmitters.push_back( + std::make_tuple(_entity, _emitter->Data(), _parent->Data())); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -1465,6 +1540,14 @@ void RenderUtilPrivate::RemoveRenderingEntities( return true; }); + // particle emitters + _ecm.EachRemoved( + [&](const Entity &_entity, const components::ParticleEmitter *)->bool + { + this->removeEntities[_entity] = _info.iterations; + return true; + }); + // cameras _ecm.EachRemoved( [&](const Entity &_entity, const components::Camera *)->bool diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 9bdfe0b1bb..c4e603d430 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -29,16 +29,20 @@ #include #include #include +#include #include #include -#include + +#include #include #include #include +#include #include #include +#include "ignition/gazebo/Conversions.hh" #include "ignition/gazebo/Util.hh" #include "ignition/gazebo/rendering/SceneManager.hh" @@ -75,6 +79,10 @@ class ignition::gazebo::SceneManagerPrivate /// \brief Map of light entity in Gazebo to light pointers. public: std::map lights; + /// \brief Map of particle emitter entity in Gazebo to particle emitter + /// rendering pointers. + public: std::map particleEmitters; + /// \brief Map of sensor entity in Gazebo to sensor pointers. public: std::map sensors; @@ -960,6 +968,148 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, return light; } +///////////////////////////////////////////////// +rendering::ParticleEmitterPtr SceneManager::CreateParticleEmitter( + Entity _id, const msgs::ParticleEmitter &_emitter, Entity _parentId) +{ + if (!this->dataPtr->scene) + return rendering::ParticleEmitterPtr(); + + if (this->dataPtr->particleEmitters.find(_id) != + this->dataPtr->particleEmitters.end()) + { + ignerr << "Particle emitter with Id: [" << _id << "] already exists in the " + <<" scene" << std::endl; + return rendering::ParticleEmitterPtr(); + } + + rendering::VisualPtr parent; + if (_parentId != this->dataPtr->worldId) + { + auto it = this->dataPtr->visuals.find(_parentId); + if (it == this->dataPtr->visuals.end()) + { + // It is possible to get here if the model entity is created then + // removed in between render updates. + return rendering::ParticleEmitterPtr(); + } + parent = it->second; + } + + // Name. + std::string name = _emitter.name().empty() ? std::to_string(_id) : + _emitter.name(); + if (parent) + name = parent->Name() + "::" + name; + + rendering::ParticleEmitterPtr emitter; + emitter = this->dataPtr->scene->CreateParticleEmitter(name); + + this->dataPtr->particleEmitters[_id] = emitter; + + if (parent) + parent->AddChild(emitter); + + this->UpdateParticleEmitter(_id, _emitter); + + return emitter; +} + +///////////////////////////////////////////////// +rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, + const msgs::ParticleEmitter &_emitter) +{ + if (!this->dataPtr->scene) + return rendering::ParticleEmitterPtr(); + + // Sanity check: Make sure that the id exists. + auto emitterIt = this->dataPtr->particleEmitters.find(_id); + if (emitterIt == this->dataPtr->particleEmitters.end()) + { + ignerr << "Particle emitter with Id: [" << _id << "] not found in the " + << "scene" << std::endl; + return rendering::ParticleEmitterPtr(); + } + auto emitter = emitterIt->second; + + // Type. + switch (_emitter.type()) + { + case ignition::msgs::ParticleEmitter_EmitterType_BOX: + { + emitter->SetType(ignition::rendering::EmitterType::EM_BOX); + break; + } + case ignition::msgs::ParticleEmitter_EmitterType_CYLINDER: + { + emitter->SetType(ignition::rendering::EmitterType::EM_CYLINDER); + break; + } + case ignition::msgs::ParticleEmitter_EmitterType_ELLIPSOID: + { + emitter->SetType(ignition::rendering::EmitterType::EM_ELLIPSOID); + break; + } + default: + { + emitter->SetType(ignition::rendering::EmitterType::EM_POINT); + } + } + + // Emitter size. + if (_emitter.has_size()) + emitter->SetEmitterSize(ignition::msgs::Convert(_emitter.size())); + + // Rate. + emitter->SetRate(_emitter.rate()); + + // Duration. + emitter->SetDuration(_emitter.duration()); + + // Emitting. + emitter->SetEmitting(_emitter.emitting()); + + // Particle size. + emitter->SetParticleSize( + ignition::msgs::Convert(_emitter.particle_size())); + + // Lifetime. + emitter->SetLifetime(_emitter.lifetime()); + + // Material. + if (_emitter.has_material()) + { + ignition::rendering::MaterialPtr material = + this->LoadMaterial(convert(_emitter.material())); + emitter->SetMaterial(material); + } + + // Velocity range. + emitter->SetVelocityRange(_emitter.min_velocity(), _emitter.max_velocity()); + + // Color range image. + if (!_emitter.color_range_image().empty()) + { + emitter->SetColorRangeImage(_emitter.color_range_image()); + } + // Color range. + else if (_emitter.has_color_start() && _emitter.has_color_end()) + { + emitter->SetColorRange( + ignition::msgs::Convert(_emitter.color_start()), + ignition::msgs::Convert(_emitter.color_end())); + } + + // Scale rate. + emitter->SetScaleRate(_emitter.scale_rate()); + + // pose + if (_emitter.has_pose()) + emitter->SetLocalPose(msgs::Convert(_emitter.pose())); + + return emitter; +} + ///////////////////////////////////////////////// bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName, Entity _parentGazeboId) @@ -1010,6 +1160,8 @@ bool SceneManager::HasEntity(Entity _id) const return this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end() || this->dataPtr->actors.find(_id) != this->dataPtr->actors.end() || this->dataPtr->lights.find(_id) != this->dataPtr->lights.end() || + this->dataPtr->particleEmitters.find(_id) != + this->dataPtr->particleEmitters.end() || this->dataPtr->sensors.find(_id) != this->dataPtr->sensors.end(); } @@ -1021,22 +1173,22 @@ rendering::NodePtr SceneManager::NodeById(Entity _id) const { return vIt->second; } - else + auto lIt = this->dataPtr->lights.find(_id); + if (lIt != this->dataPtr->lights.end()) { - auto lIt = this->dataPtr->lights.find(_id); - if (lIt != this->dataPtr->lights.end()) - { - return lIt->second; - } - else - { - auto sIt = this->dataPtr->sensors.find(_id); - if (sIt != this->dataPtr->sensors.end()) - { - return sIt->second; - } - } + return lIt->second; } + auto sIt = this->dataPtr->sensors.find(_id); + if (sIt != this->dataPtr->sensors.end()) + { + return sIt->second; + } + auto pIt = this->dataPtr->particleEmitters.find(_id); + if (pIt != this->dataPtr->particleEmitters.end()) + { + return pIt->second; + } + return rendering::NodePtr(); } @@ -1258,6 +1410,16 @@ void SceneManager::RemoveEntity(Entity _id) } } + { + auto it = this->dataPtr->particleEmitters.find(_id); + if (it != this->dataPtr->particleEmitters.end()) + { + this->dataPtr->scene->DestroyVisual(it->second); + this->dataPtr->particleEmitters.erase(it); + return; + } + } + { auto it = this->dataPtr->sensors.find(_id); if (it != this->dataPtr->sensors.end()) diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index 07b88dfba4..ff95341dac 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -97,6 +97,7 @@ add_subdirectory(magnetometer) add_subdirectory(multicopter_motor_model) add_subdirectory(multicopter_control) add_subdirectory(optical_tactile_plugin) +add_subdirectory(particle_emitter) add_subdirectory(performer_detector) add_subdirectory(physics) add_subdirectory(pose_publisher) diff --git a/src/systems/particle_emitter/CMakeLists.txt b/src/systems/particle_emitter/CMakeLists.txt new file mode 100644 index 0000000000..9e75a90abf --- /dev/null +++ b/src/systems/particle_emitter/CMakeLists.txt @@ -0,0 +1,9 @@ +gz_add_system(particle-emitter + SOURCES + ParticleEmitter.cc + PUBLIC_LINK_LIBS + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} + ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} + ignition-plugin${IGN_PLUGIN_VER}::ignition-plugin${IGN_PLUGIN_VER} + ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} +) diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc new file mode 100644 index 0000000000..072bd50dd2 --- /dev/null +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -0,0 +1,335 @@ +/* + * 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include "ParticleEmitter.hh" + +using namespace ignition; +using namespace gazebo; +using namespace systems; + +// Private data class. +class ignition::gazebo::systems::ParticleEmitterPrivate +{ + /// \brief Callback for receiving particle emitter commands. + /// \param[in] _msg Particle emitter message. + public: void OnCmd(const ignition::msgs::ParticleEmitter &_msg); + + /// \brief The particle emitter parsed from SDF. + public: ignition::msgs::ParticleEmitter emitter; + + /// \brief The transport node. + public: ignition::transport::Node node; + + /// \brief Particle emitter entity. + public: Entity emitterEntity{kNullEntity}; + + /// \brief The particle emitter command requested externally. + public: ignition::msgs::ParticleEmitter userCmd; + + public: bool newDataReceived = false; + + /// \brief A mutex to protect the user command. + public: std::mutex mutex; +}; + +////////////////////////////////////////////////// +void ParticleEmitterPrivate::OnCmd(const msgs::ParticleEmitter &_msg) +{ + std::lock_guard lock(this->mutex); + this->userCmd = _msg; + this->newDataReceived = true; +} + +////////////////////////////////////////////////// +ParticleEmitter::ParticleEmitter() + : System(), dataPtr(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +void ParticleEmitter::Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) +{ + Model model = Model(_entity); + + if (!model.Valid(_ecm)) + { + ignerr << "ParticleEmitter plugin should be attached to a model entity. " + << "Failed to initialize." << std::endl; + return; + } + + // Create a particle emitter entity. + this->dataPtr->emitterEntity = _ecm.CreateEntity(); + if (this->dataPtr->emitterEntity == kNullEntity) + { + ignerr << "Failed to create a particle emitter entity" << std::endl; + return; + } + + // allow_renaming + bool allowRenaming = false; + if (_sdf->HasElement("allow_renaming")) + allowRenaming = _sdf->Get("allow_renaming"); + + // Name. + std::string name = "particle_emitter_entity_" + + std::to_string(this->dataPtr->emitterEntity); + if (_sdf->HasElement("emitter_name")) + { + std::set emitterNames; + std::string emitterName = _sdf->Get("emitter_name"); + + // check to see if name is already taken + _ecm.Each( + [&emitterNames](const Entity &, const components::Name *_name, + const components::ParticleEmitter *) + { + emitterNames.insert(_name->Data()); + return true; + }); + + name = emitterName; + + // rename emitter if needed + if (emitterNames.find(emitterName) != emitterNames.end()) + { + if (!allowRenaming) + { + ignwarn << "Entity named [" << name + << "] already exists and " + << "[allow_renaming] is false. Entity not spawned." + << std::endl; + return; + } + int counter = 0; + while (emitterNames.find(name) != emitterNames.end()) + { + name = emitterName + "_" + std::to_string(++counter); + } + ignmsg << "Entity named [" << emitterName + << "] already exists. Renaming it to " << name << std::endl; + } + } + this->dataPtr->emitter.set_name(name); + + // Type. The default type is point. + this->dataPtr->emitter.set_type( + ignition::msgs::ParticleEmitter_EmitterType_POINT); + std::string type = _sdf->Get("type", "point").first; + if (type == "box") + { + this->dataPtr->emitter.set_type( + ignition::msgs::ParticleEmitter_EmitterType_BOX); + } + else if (type == "cylinder") + { + this->dataPtr->emitter.set_type( + ignition::msgs::ParticleEmitter_EmitterType_CYLINDER); + } + else if (type == "ellipsoid") + { + this->dataPtr->emitter.set_type( + ignition::msgs::ParticleEmitter_EmitterType_ELLIPSOID); + } + else if (type != "point") + { + ignerr << "Unknown emitter type [" << type << "]. Using [point] instead" + << std::endl; + } + + // Pose. + ignition::math::Pose3d pose = + _sdf->Get("pose"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_pose(), pose); + + // Size. + ignition::math::Vector3d size = ignition::math::Vector3d::One; + if (_sdf->HasElement("size")) + size = _sdf->Get("size"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_size(), size); + + // Rate. + this->dataPtr->emitter.set_rate(_sdf->Get("rate", 10).first); + + // Duration. + this->dataPtr->emitter.set_duration(_sdf->Get("duration", 0).first); + + // Emitting. + this->dataPtr->emitter.set_emitting(_sdf->Get("emitting", false).first); + + // Particle size. + size = ignition::math::Vector3d::One; + if (_sdf->HasElement("particle_size")) + size = _sdf->Get("particle_size"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_particle_size(), size); + + // Lifetime. + this->dataPtr->emitter.set_lifetime(_sdf->Get("lifetime", 5).first); + + // Material. + if (_sdf->HasElement("material")) + { + auto materialElem = _sdf->GetElementImpl("material"); + sdf::Material material; + material.Load(materialElem); + ignition::msgs::Material materialMsg = convert(material); + this->dataPtr->emitter.mutable_material()->CopyFrom(materialMsg); + } + + // Min velocity. + this->dataPtr->emitter.set_min_velocity( + _sdf->Get("min_velocity", 1).first); + + // Max velocity. + this->dataPtr->emitter.set_max_velocity( + _sdf->Get("max_velocity", 1).first); + + // Color start. + ignition::math::Color color = ignition::math::Color::White; + if (_sdf->HasElement("color_start")) + color = _sdf->Get("color_start"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_color_start(), color); + + // Color end. + color = ignition::math::Color::White; + if (_sdf->HasElement("color_end")) + color = _sdf->Get("color_end"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), color); + + // Scale rate. + this->dataPtr->emitter.set_scale_rate( + _sdf->Get("scale_rate", 1).first); + + // Color range image. + if (_sdf->HasElement("color_range_image")) + { + auto modelPath = _ecm.ComponentData(_entity); + auto colorRangeImagePath = _sdf->Get("color_range_image"); + auto path = asFullPath(colorRangeImagePath, modelPath.value()); + + common::SystemPaths systemPaths; + systemPaths.SetFilePathEnv(kResourcePathEnv); + auto absolutePath = systemPaths.FindFile(path); + + this->dataPtr->emitter.set_color_range_image(absolutePath); + } + + igndbg << "Loading particle emitter:" << std::endl + << this->dataPtr->emitter.DebugString() << std::endl; + + // Create components. + SdfEntityCreator sdfEntityCreator(_ecm, _eventMgr); + sdfEntityCreator.SetParent(this->dataPtr->emitterEntity, _entity); + + _ecm.CreateComponent(this->dataPtr->emitterEntity, + components::Name(this->dataPtr->emitter.name())); + + _ecm.CreateComponent(this->dataPtr->emitterEntity, + components::ParticleEmitter(this->dataPtr->emitter)); + + _ecm.CreateComponent(this->dataPtr->emitterEntity, components::Pose(pose)); + + // Advertise the topic to receive particle emitter commands. + const std::string kDefaultTopic = + "/model/" + model.Name(_ecm) + "/particle_emitter/" + name; + std::string topic = _sdf->Get("topic", kDefaultTopic).first; + if (!this->dataPtr->node.Subscribe( + topic, &ParticleEmitterPrivate::OnCmd, this->dataPtr.get())) + { + ignerr << "Error subscribing to topic [" << topic << "]. " + << "Particle emitter will not receive updates." << std::endl; + return; + } + igndbg << "Subscribed to " << topic << " for receiving particle emitter " + << "updates" << std::endl; +} + +////////////////////////////////////////////////// +void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) +{ + IGN_PROFILE("ParticleEmitter::PreUpdate"); + + std::lock_guard lock(this->dataPtr->mutex); + + if (!this->dataPtr->newDataReceived) + return; + + // Nothing left to do if paused. + if (_info.paused) + return; + + this->dataPtr->newDataReceived = false; + + // Create component. + auto emitterComp = _ecm.Component( + this->dataPtr->emitterEntity); + if (!emitterComp) + { + _ecm.CreateComponent( + this->dataPtr->emitterEntity, + components::ParticleEmitterCmd(this->dataPtr->userCmd)); + } + else + { + emitterComp->Data() = this->dataPtr->userCmd; + + // Note: we process the cmd component in RenderUtil but if there is only + // rendering on the gui side, it will not be able to remove the cmd + // component from the ECM. It seems like adding OneTimeChange here will make + // sure the cmd component is found again in Each call on GUI side. + // todo(anyone) find a better way to process this cmd component in + // RenderUtil.cc + _ecm.SetChanged(this->dataPtr->emitterEntity, + components::ParticleEmitterCmd::typeId, + ComponentState::OneTimeChange); + } + + igndbg << "New ParticleEmitterCmd component created" << std::endl; +} + +IGNITION_ADD_PLUGIN(ParticleEmitter, + ignition::gazebo::System, + ParticleEmitter::ISystemConfigure, + ParticleEmitter::ISystemPreUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter, + "ignition::gazebo::systems::ParticleEmitter") diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh new file mode 100644 index 0000000000..5b3df5e476 --- /dev/null +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -0,0 +1,141 @@ +/* + * 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_SYSTEMS_PARTICLE_EMITTER_HH_ +#define IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ + +#include + +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems +{ + class ParticleEmitterPrivate; + + /// \brief A system for creating a particle emitter. + /// + /// System parameters + /// + /// ``: Unique name for the particle emitter. The name will be + /// automatically generated if this parameter is not set. + /// ``: Rename the particle emitter if one with the same name + /// already exists. Default is false. + /// ``: The emitter type (point, box, cylinder, ellipsoid). + /// Default value is point. + /// ``: The pose of the emitter. Default value is {0, 0, 0, 0, 0, 0}. + /// ``: The size of the emitter where the particles are sampled. + /// Default value is (1, 1, 1). + /// Note that the interpretation of the emitter area varies + /// depending on the emmiter type: + /// - point: The area is ignored. + /// - box: The area is interpreted as width X height X depth. + /// - cylinder: The area is interpreted as the bounding box of the + /// cilinder. The cylinder is oriented along the + /// Z-axis. + /// - ellipsoid: The area is interpreted as the bounding box of an + /// ellipsoid shaped area, i.e. a sphere or + /// squashed-sphere area. The parameters are again + /// identical to EM_BOX, except that the dimensions + /// describe the widest points along each of the + /// axes. + /// ``: How many particles per second should be emitted. + /// Default value is 10. + /// `: The number of seconds the emitter is active. A value of 0 + /// means infinite duration. Default value is 0. + /// ``: This is used to turn on or off particle emission. + /// Default value is false. + /// ``: Set the particle dimensions (width, height, depth). + /// Default value is {1, 1, 1}. + /// ``: Set the number of seconds each particle will ’live’ for + /// before being destroyed. Default value is 5. + /// ``: Sets the material which all particles in the emitter will + /// use. + /// ``: Sets a minimum velocity for each particle (m/s). + /// Default value is 1. + /// ``: Sets a maximum velocity for each particle (m/s). + /// Default value is 1. + /// ``: Sets the starting color for all particle emitted. + /// The actual color will be interpolated between this color + /// and the one set under . + /// Color::White is the default color for the particles + /// unless a specific function is used. + /// To specify a color, RGB values should be passed in. + /// For example, to specify red, a user should enter: + /// 1 0 0 + /// Note that this function overrides the particle colors set + /// with . + /// ``: Sets the end color for all particle emitted. + /// The actual color will be interpolated between this color + /// and the one set under . + /// Color::White is the default color for the particles + /// unless a specific function is used (see color_start for + /// more information about defining custom colors with RGB + /// values). + /// Note that this function overrides the particle colors set + /// with . + /// ``: Sets the amount by which to scale the particles in both x + /// and y direction per second. Default value is 1. + /// ``: Sets the path to the color image used as an + /// affector. This affector modifies the color of + /// particles in flight. The colors are taken from a + /// specified image file. The range of color values + /// begins from the left side of the image and move to + /// the right over the lifetime of the particle, + /// therefore only the horizontal dimension of the + /// image is used. + /// Note that this function overrides the particle + /// colors set with and . + /// ``: Topic used to update particle emitter properties at runtime. + /// The default topic is + /// /model//particle_emitter/ + /// Note that the emitter id and name may not be changed. + /// See the examples/worlds/particle_emitter.sdf example world for + /// example usage. + class IGNITION_GAZEBO_VISIBLE ParticleEmitter + : public System, + public ISystemConfigure, + public ISystemPreUpdate + { + /// \brief Constructor + public: ParticleEmitter(); + + // Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) override; + + // Documentation inherited + public: void PreUpdate( + const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) override; + + /// \brief Private data pointer + private: std::unique_ptr dataPtr; + }; + } +} +} +} + +#endif + diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index c306ec83bc..7250621ca8 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -35,6 +35,7 @@ set(tests multicopter.cc multiple_servers.cc network_handshake.cc + particle_emitter.cc performer_detector.cc physics_system.cc play_pause.cc diff --git a/test/integration/components.cc b/test/integration/components.cc index c48b60ddef..28b1053329 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -1580,3 +1580,24 @@ TEST_F(ComponentsTest, ParticleEmitter) comp3.Deserialize(istr); EXPECT_EQ(comp1.Data().id(), comp3.Data().id()); } + +////////////////////////////////////////////////// +TEST_F(ComponentsTest, ParticleEmitterCmd) +{ + msgs::ParticleEmitter emitter1; + emitter1.set_name("emitter1"); + emitter1.set_emitting(true); + + // Create components. + auto comp1 = components::ParticleEmitterCmd(emitter1); + + // Stream operators. + std::ostringstream ostr; + comp1.Serialize(ostr); + + std::istringstream istr(ostr.str()); + components::ParticleEmitter comp3; + comp3.Deserialize(istr); + EXPECT_EQ(comp1.Data().emitting(), comp3.Data().emitting()); + EXPECT_EQ(comp1.Data().name(), comp3.Data().name()); +} diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc new file mode 100644 index 0000000000..4e26133118 --- /dev/null +++ b/test/integration/particle_emitter.cc @@ -0,0 +1,170 @@ +/* + * 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 "ignition/gazebo/Entity.hh" +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/SystemLoader.hh" +#include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/ParticleEmitter.hh" +#include "ignition/gazebo/components/Pose.hh" +#include "ignition/gazebo/test_config.hh" + +#include "helpers/Relay.hh" + +using namespace ignition; +using namespace gazebo; + +class ParticleEmitterTest : public ::testing::Test +{ + // Documentation inherited + protected: void SetUp() override + { + ignition::common::Console::SetVerbosity(4); + setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + } + public: void LoadWorld(const std::string &_path, bool _useLevels = false) + { + this->serverConfig.SetSdfFile( + common::joinPaths(PROJECT_SOURCE_PATH, _path)); + this->serverConfig.SetUseLevels(_useLevels); + + this->server = std::make_unique(this->serverConfig); + EXPECT_FALSE(this->server->Running()); + EXPECT_FALSE(*this->server->Running(0)); + using namespace std::chrono_literals; + this->server->SetUpdatePeriod(1ns); + } + + public: ServerConfig serverConfig; + public: std::unique_ptr server; +}; + +///////////////////////////////////////////////// +// Load an SDF with a particle emitter and verify its properties. +TEST_F(ParticleEmitterTest, SDFLoad) +{ + bool updateCustomChecked{false}; + bool updateDefaultChecked{false}; + + this->LoadWorld("test/worlds/particle_emitter.sdf"); + + // Create a system that checks a particle emitter. + test::Relay testSystem; + testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::Name *_name, + const components::Pose *_pose) -> bool + { + + if (_name->Data() == "smoke_emitter") + { + updateCustomChecked = true; + + EXPECT_EQ("smoke_emitter", _name->Data()); + EXPECT_EQ(_name->Data(), _emitter->Data().name()); + EXPECT_EQ(msgs::ParticleEmitter_EmitterType_BOX, + _emitter->Data().type()); + EXPECT_EQ(math::Pose3d(0, 1, 0, 0, 0, 0), _pose->Data()); + EXPECT_EQ(_pose->Data(), + msgs::Convert(_emitter->Data().pose())); + EXPECT_EQ(math::Vector3d(2, 2, 2), + msgs::Convert(_emitter->Data().size())); + EXPECT_DOUBLE_EQ(5.0, _emitter->Data().rate()); + EXPECT_DOUBLE_EQ(1.0, _emitter->Data().duration()); + EXPECT_TRUE(_emitter->Data().emitting()); + EXPECT_EQ(math::Vector3d(3, 3, 3), + msgs::Convert(_emitter->Data().particle_size())); + EXPECT_DOUBLE_EQ(2.0, _emitter->Data().lifetime()); + // TODO(anyone) add material check here + EXPECT_DOUBLE_EQ(10.0, _emitter->Data().min_velocity()); + EXPECT_DOUBLE_EQ(20.0, _emitter->Data().max_velocity()); + EXPECT_EQ(math::Color::Blue, + msgs::Convert(_emitter->Data().color_start())); + EXPECT_EQ(math::Color::Green, + msgs::Convert(_emitter->Data().color_end())); + EXPECT_DOUBLE_EQ(10.0, _emitter->Data().scale_rate()); + + // color range image is empty because the emitter system + // will not be able to find a file that does not exist + // TODO(anyone) this should return "/path/to/dummy_image.png" + // and let rendering do the findFile instead + EXPECT_EQ(std::string(), + _emitter->Data().color_range_image()); + } + else + { + updateDefaultChecked = true; + + EXPECT_TRUE(_name->Data().find(std::to_string(_entity)) + != std::string::npos); + EXPECT_EQ(_name->Data(), _emitter->Data().name()); + EXPECT_EQ(msgs::ParticleEmitter_EmitterType_POINT, + _emitter->Data().type()); + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); + EXPECT_EQ(_pose->Data(), + msgs::Convert(_emitter->Data().pose())); + EXPECT_EQ(math::Vector3d(1, 1, 1), + msgs::Convert(_emitter->Data().size())); + EXPECT_DOUBLE_EQ(10.0, _emitter->Data().rate()); + EXPECT_DOUBLE_EQ(0.0, _emitter->Data().duration()); + EXPECT_FALSE(_emitter->Data().emitting()); + EXPECT_EQ(math::Vector3d(1, 1, 1), + msgs::Convert(_emitter->Data().particle_size())); + EXPECT_DOUBLE_EQ(5.0, _emitter->Data().lifetime()); + // TODO(anyone) add material check here + EXPECT_DOUBLE_EQ(1.0, _emitter->Data().min_velocity()); + EXPECT_DOUBLE_EQ(1.0, _emitter->Data().max_velocity()); + EXPECT_EQ(math::Color::White, + msgs::Convert(_emitter->Data().color_start())); + EXPECT_EQ(math::Color::White, + msgs::Convert(_emitter->Data().color_end())); + EXPECT_DOUBLE_EQ(1.0, _emitter->Data().scale_rate()); + EXPECT_EQ("", _emitter->Data().color_range_image()); + } + + return true; + }); + }); + + this->server->AddSystem(testSystem.systemPtr); + this->server->Run(true, 1, false); + + EXPECT_TRUE(updateCustomChecked); + EXPECT_TRUE(updateDefaultChecked); +} + +///////////////////////////////////////////////// +/// Main +int main(int _argc, char **_argv) +{ + ::testing::InitGoogleTest(&_argc, _argv); + return RUN_ALL_TESTS(); +} diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf new file mode 100644 index 0000000000..1da40a4919 --- /dev/null +++ b/test/worlds/particle_emitter.sdf @@ -0,0 +1,148 @@ + + + + + + 0.001 + 1.0 + + + + + + + + 3D View + false + false + 0 + + + + + + + ogre + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -1 0 1 0 0.5 0 + + + + + + World control + false + false + 72 + 121 + 1 + + + + + true + true + true + + + + + + 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 + + + + + + + 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 + true + + + + + 1 1 1 + + + + + + + smoke_emitter + box + 0 1 0 0 0 0 + 2 2 2 + 5 + 1 + true + 3 3 3 + 2 + + 10 + 20 + 0 0 1 + 0 1 0 + 10 + /path/to/dummy_image.png + + + + + + 5 5 0 0 0 0 + true + + + + + 1 1 1 + + + + + + + + + + + + From 7f122de9f141d781e263c2349e4b76e9de8bd0b1 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 17 Feb 2021 18:28:35 -0800 Subject: [PATCH 42/55] bump msgs version to 6.3.0 Signed-off-by: Ian Chen --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b616eadfec..0d77e1feeb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -53,7 +53,7 @@ set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR}) #-------------------------------------- # Find ignition-msgs -ign_find_package(ignition-msgs6 REQUIRED VERSION 6.2) +ign_find_package(ignition-msgs6 REQUIRED VERSION 6.3) set(IGN_MSGS_VER ${ignition-msgs6_VERSION_MAJOR}) #-------------------------------------- From 8a1db3d3012bfdcfb673c266c998952d77475716 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 17 Feb 2021 21:00:15 -0800 Subject: [PATCH 43/55] Remove extra main Signed-off-by: Nate Koenig --- test/integration/particle_emitter.cc | 8 -------- 1 file changed, 8 deletions(-) diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 4e26133118..29dd17fa0c 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -160,11 +160,3 @@ TEST_F(ParticleEmitterTest, SDFLoad) EXPECT_TRUE(updateCustomChecked); EXPECT_TRUE(updateDefaultChecked); } - -///////////////////////////////////////////////// -/// Main -int main(int _argc, char **_argv) -{ - ::testing::InitGoogleTest(&_argc, _argv); - return RUN_ALL_TESTS(); -} From 494a11ee37ad9e573cdbe65a190048a30543c129 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 17 Feb 2021 21:07:56 -0800 Subject: [PATCH 44/55] Added missing Signed-off-by: Nate Koenig --- src/systems/particle_emitter/ParticleEmitter.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc index 072bd50dd2..697b260544 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -18,6 +18,7 @@ #include #include +#include #include #include From 04721d33ad4f711f99a9dae093c892eeb6bd3655 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 17 Feb 2021 21:48:41 -0800 Subject: [PATCH 45/55] 4.5.0 Signed-off-by: Nate Koenig --- CMakeLists.txt | 2 +- Changelog.md | 20 ++++++++++++++++++++ 2 files changed, 21 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0d77e1feeb..95585b11f1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo4 VERSION 4.4.0) +project(ignition-gazebo4 VERSION 4.5.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 5e7fc77a9b..6e030ad5e1 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,25 @@ ## Ignition Gazebo 4.x +### Ignition Gazebo 4.5.0 (2020-02-17) + +1. Added particle system. + * [Pull Request 516](https://github.com/ignitionrobotics/ign-gazebo/pull/516) + +1. Add Light Usercommand and include Light parameters in the componentInspector + * [Pull Request 482](https://github.com/ignitionrobotics/ign-gazebo/pull/482) + +1. Added link to HW-accelerated video recording. + * [Pull Request 627](https://github.com/ignitionrobotics/ign-gazebo/pull/627) + +1. Fix EntityComponentManager race condition. + * [Pull Request 601](https://github.com/ignitionrobotics/ign-gazebo/pull/601) + +1. Add SDF topic validity check. + * [Pull Request 632](https://github.com/ignitionrobotics/ign-gazebo/pull/632) + +1. Add JointTrajectoryController system plugin. + * [Pull Request 473](https://github.com/ignitionrobotics/ign-gazebo/pull/473) + ### Ignition Gazebo 4.4.0 (2020-02-10) 1. Added issue and PR templates From 4c2f498344b0316aca689271015951a23ad6cf9e Mon Sep 17 00:00:00 2001 From: Atharva Pusalkar Date: Fri, 19 Feb 2021 23:55:48 +0530 Subject: [PATCH 46/55] Validity check for user defined topics in JointPositionController (#639) Signed-off-by: Atharva Pusalkar --- src/systems/joint_controller/JointController.cc | 4 ++-- .../JointPositionController.cc | 11 ++++++++++- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 9e78162403..dce17b55c3 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -147,8 +147,8 @@ void JointController::Configure(const Entity &_entity, if (topic.empty()) { - ignerr << "Failed to create topic [" << this->dataPtr->jointName - << "]" << " for joint [" << _sdf->Get("topic") + ignerr << "Failed to create topic [" << _sdf->Get("topic") + << "]" << " for joint [" << this->dataPtr->jointName << "]" << std::endl; return; } diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index ccb3644705..5c14e0f082 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -158,7 +158,16 @@ void JointPositionController::Configure(const Entity &_entity, } if (_sdf->HasElement("topic")) { - topic = _sdf->Get("topic"); + topic = transport::TopicUtils::AsValidTopic( + _sdf->Get("topic")); + + if (topic.empty()) + { + ignerr << "Failed to create topic [" << _sdf->Get("topic") + << "]" << " for joint [" << this->dataPtr->jointName + << "]" << std::endl; + return; + } } this->dataPtr->node.Subscribe( topic, &JointPositionControllerPrivate::OnCmdPos, this->dataPtr.get()); From f8c9050878bff0832a280bc47546d65819a7dd33 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 19 Feb 2021 18:21:12 -0800 Subject: [PATCH 47/55] =?UTF-8?q?=F0=9F=91=A9=E2=80=8D=F0=9F=8C=BE=20Impro?= =?UTF-8?q?ve=20velocity=20control=20test=20(#642)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- test/integration/velocity_control_system.cc | 36 ++++++++------------- 1 file changed, 13 insertions(+), 23 deletions(-) diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 02b230c844..3d50d57451 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -96,43 +96,33 @@ class VelocityControlTest : public ::testing::TestWithParam // and max velocity (0.5 m/s). // See parameters // in "/test/worlds/velocity_control.sdf". - test::Relay velocityRamp; const double desiredLinVel = 10.5; const double desiredAngVel = 0.2; - velocityRamp.OnPreUpdate( - [&](const gazebo::UpdateInfo &/*_info*/, - const gazebo::EntityComponentManager &) - { - msgs::Set(msg.mutable_linear(), - math::Vector3d(desiredLinVel, 0, 0)); - msgs::Set(msg.mutable_angular(), - math::Vector3d(0.0, 0, desiredAngVel)); - pub.Publish(msg); - }); - - server.AddSystem(velocityRamp.systemPtr); + msgs::Set(msg.mutable_linear(), + math::Vector3d(desiredLinVel, 0, 0)); + msgs::Set(msg.mutable_angular(), + math::Vector3d(0.0, 0, desiredAngVel)); + pub.Publish(msg); + + // Give some time for message to be received + std::this_thread::sleep_for(std::chrono::milliseconds(100)); server.Run(true, 3000, false); // Poses for 4s ASSERT_EQ(4000u, poses.size()); - int sleep = 0; - int maxSleep = 30; - - ASSERT_NE(maxSleep, sleep); - // verify that the vehicle is moving in +x and rotating towards +y for (unsigned int i = 1001; i < poses.size(); ++i) { - EXPECT_GT(poses[i].Pos().X(), poses[i-1].Pos().X()); - EXPECT_GT(poses[i].Pos().Y(), poses[i-1].Pos().Y()); + EXPECT_GT(poses[i].Pos().X(), poses[i-1].Pos().X()) << i; + EXPECT_GT(poses[i].Pos().Y(), poses[i-1].Pos().Y()) << i; EXPECT_NEAR(poses[i].Pos().Z(), poses[i-1].Pos().Z(), 1e-5); EXPECT_NEAR(poses[i].Rot().Euler().X(), - poses[i-1].Rot().Euler().X(), 1e-5); + poses[i-1].Rot().Euler().X(), 1e-5) << i; EXPECT_NEAR(poses[i].Rot().Euler().Y(), - poses[i-1].Rot().Euler().Y(), 1e-5); - EXPECT_GT(poses[i].Rot().Euler().Z(), poses[i-1].Rot().Euler().Z()); + poses[i-1].Rot().Euler().Y(), 1e-5) << i; + EXPECT_GT(poses[i].Rot().Euler().Z(), poses[i-1].Rot().Euler().Z()) << i; } } }; From 7b4b258e869a6d5bbb7ae0e2de609df534faff79 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 22 Feb 2021 14:19:19 -0800 Subject: [PATCH 48/55] =?UTF-8?q?=F0=9F=91=A9=E2=80=8D=F0=9F=8C=BE=20Relax?= =?UTF-8?q?=20performance=20test=20(#640)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel Co-authored-by: Michael Carroll --- test/performance/each.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/performance/each.cc b/test/performance/each.cc index 272d04bff9..d67f343ac1 100644 --- a/test/performance/each.cc +++ b/test/performance/each.cc @@ -54,10 +54,10 @@ TEST(EntityComponentManagerPerfrormance, Each) // Initial allocation of resources can throw off calculations. warmstart(); - for (int matchingEntityCount = 1; matchingEntityCount < maxEntityCount; + for (int matchingEntityCount = 10; matchingEntityCount < maxEntityCount; matchingEntityCount += step) { - for (int nonmatchingEntityCount = 1; + for (int nonmatchingEntityCount = 10; nonmatchingEntityCount < maxEntityCount; nonmatchingEntityCount += step) { From 60d9eb87464f4d410d1927101f437f952a9bf934 Mon Sep 17 00:00:00 2001 From: "G.Doisy" Date: Tue, 23 Feb 2021 01:17:38 +0100 Subject: [PATCH 49/55] Add TF/Pose_V publisher in DiffDrive (#548) Signed-off-by: Guillaume Doisy --- src/systems/diff_drive/DiffDrive.cc | 20 +- src/systems/diff_drive/DiffDrive.hh | 16 ++ test/integration/diff_drive_system.cc | 184 ++++++++++++++++ test/worlds/diff_drive_custom_tf_topic.sdf | 244 +++++++++++++++++++++ 4 files changed, 463 insertions(+), 1 deletion(-) create mode 100644 test/worlds/diff_drive_custom_tf_topic.sdf diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index 496b6cd50f..e8a49f4356 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -119,6 +119,9 @@ class ignition::gazebo::systems::DiffDrivePrivate /// \brief Diff drive odometry message publisher. public: transport::Node::Publisher odomPub; + /// \brief Diff drive tf message publisher. + public: transport::Node::Publisher tfPub; + /// \brief Linear velocity limiter. public: std::unique_ptr limiterLin; @@ -271,6 +274,13 @@ void DiffDrive::Configure(const Entity &_entity, this->dataPtr->odomPub = this->dataPtr->node.Advertise( odomTopic); + std::string tfTopic{"/model/" + this->dataPtr->model.Name(_ecm) + + "/tf"}; + if (_sdf->HasElement("tf_topic")) + tfTopic = _sdf->Get("tf_topic"); + this->dataPtr->tfPub = this->dataPtr->node.Advertise( + tfTopic); + if (_sdf->HasElement("frame_id")) this->dataPtr->sdfFrameId = _sdf->Get("frame_id"); @@ -465,9 +475,17 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, childFrame->add_value(this->sdfChildFrameId); } + // Construct the Pose_V/tf message and publish it. + msgs::Pose_V tfMsg; + ignition::msgs::Pose *tfMsgPose = nullptr; + tfMsgPose = tfMsg.add_pose(); + tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); + tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); + tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); - // Publish the message + // Publish the messages this->odomPub.Publish(msg); + this->tfPub.Publish(tfMsg); } ////////////////////////////////////////////////// diff --git a/src/systems/diff_drive/DiffDrive.hh b/src/systems/diff_drive/DiffDrive.hh index adedf7b002..d2905a23ca 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -61,6 +61,22 @@ namespace systems /// ``: Custom topic on which this system will publish odometry /// messages. This element if optional, and the default value is /// `/model/{name_of_model}/odometry`. + /// + /// ``: Custom topic on which this system will publish the + /// transform from `frame_id` to `child_frame_id`. This element if optional, + /// and the default value is `/model/{name_of_model}/tf`. + /// + /// ``: Custom `frame_id` field that this system will use as the + /// origin of the odometry transform in both the `` + /// `ignition.msgs.Pose_V` message and the `` + /// `ignition.msgs.Odometry` message. This element if optional, and the + /// default value is `{name_of_model}/odom`. + /// + /// ``: Custom `child_frame_id` that this system will use as + /// the target of the odometry trasnform in both the `` + /// `ignition.msgs.Pose_V` message and the `` + /// `ignition.msgs.Odometry` message. This element if optional, + /// and the default value is `{name_of_model}/{name_of_link}`. class IGNITION_GAZEBO_VISIBLE DiffDrive : public System, public ISystemConfigure, diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 1d55d2b576..d1c6f86d32 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -404,6 +404,190 @@ TEST_P(DiffDriveTest, OdomCustomFrameId) 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.2)); + + pub.Publish(msg); + + server.Run(true, 100, false); + + int sleep = 0; + int maxSleep = 30; + for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_NE(maxSleep, sleep); + + EXPECT_EQ(5u, odomPosesCount); +} + +///////////////////////////////////////////////// +TEST_P(DiffDriveTest, Pose_VFrameId) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/diff_drive.sdf"); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + unsigned int odomPosesCount = 0; + std::function pose_VCb = + [&odomPosesCount](const msgs::Pose_V &_msg) + { + ASSERT_TRUE(_msg.pose(0).has_header()); + ASSERT_TRUE(_msg.pose(0).header().has_stamp()); + + ASSERT_GT(_msg.pose(0).header().data_size(), 1); + + EXPECT_STREQ(_msg.pose(0).header().data(0).key().c_str(), + "frame_id"); + EXPECT_STREQ(_msg.pose(0).header().data(0).value().Get(0).c_str(), + "vehicle/odom"); + + EXPECT_STREQ(_msg.pose(0).header().data(1).key().c_str(), + "child_frame_id"); + EXPECT_STREQ(_msg.pose(0).header().data(1).value().Get(0).c_str(), + "vehicle/chassis"); + + odomPosesCount++; + }; + + transport::Node node; + auto pub = node.Advertise("/model/vehicle/cmd_vel"); + node.Subscribe("/model/vehicle/tf", pose_VCb); + + 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.2)); + + pub.Publish(msg); + + server.Run(true, 100, false); + + int sleep = 0; + int maxSleep = 30; + for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_NE(maxSleep, sleep); + + EXPECT_EQ(5u, odomPosesCount); +} + +///////////////////////////////////////////////// +TEST_P(DiffDriveTest, Pose_VCustomFrameId) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/diff_drive_custom_frame_id.sdf"); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + unsigned int odomPosesCount = 0; + std::function Pose_VCb = + [&odomPosesCount](const msgs::Pose_V &_msg) + { + ASSERT_TRUE(_msg.pose(0).has_header()); + ASSERT_TRUE(_msg.pose(0).header().has_stamp()); + + ASSERT_GT(_msg.pose(0).header().data_size(), 1); + + EXPECT_STREQ(_msg.pose(0).header().data(0).key().c_str(), + "frame_id"); + EXPECT_STREQ(_msg.pose(0).header().data(0).value().Get(0).c_str(), + "odom"); + + EXPECT_STREQ(_msg.pose(0).header().data(1).key().c_str(), + "child_frame_id"); + EXPECT_STREQ(_msg.pose(0).header().data(1).value().Get(0).c_str(), + "base_footprint"); + + odomPosesCount++; + }; + + transport::Node node; + auto pub = node.Advertise("/model/vehicle/cmd_vel"); + node.Subscribe("/model/vehicle/tf", Pose_VCb); + + 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.2)); + + pub.Publish(msg); + + server.Run(true, 100, false); + + int sleep = 0; + int maxSleep = 30; + for (; odomPosesCount < 5 && sleep < maxSleep; ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_NE(maxSleep, sleep); + + EXPECT_EQ(5u, odomPosesCount); +} + +///////////////////////////////////////////////// +TEST_P(DiffDriveTest, Pose_VCustomTfTopic) +{ + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/diff_drive_custom_tf_topic.sdf"); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + server.SetUpdatePeriod(0ns); + + unsigned int odomPosesCount = 0; + std::function pose_VCb = + [&odomPosesCount](const msgs::Pose_V &_msg) + { + ASSERT_TRUE(_msg.pose(0).has_header()); + ASSERT_TRUE(_msg.pose(0).header().has_stamp()); + + ASSERT_GT(_msg.pose(0).header().data_size(), 1); + + EXPECT_STREQ(_msg.pose(0).header().data(0).key().c_str(), "frame_id"); + EXPECT_STREQ( + _msg.pose(0).header().data(0).value().Get(0).c_str(), + "vehicle/odom"); + + EXPECT_STREQ( + _msg.pose(0).header().data(1).key().c_str(), "child_frame_id"); + EXPECT_STREQ( + _msg.pose(0).header().data(1).value().Get(0).c_str(), + "vehicle/chassis"); + + odomPosesCount++; + }; + + transport::Node node; + auto pub = node.Advertise("/model/vehicle/cmd_vel"); + node.Subscribe("/tf_foo", pose_VCb); + + 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.2)); + + pub.Publish(msg); + server.Run(true, 100, false); int sleep = 0; diff --git a/test/worlds/diff_drive_custom_tf_topic.sdf b/test/worlds/diff_drive_custom_tf_topic.sdf new file mode 100644 index 0000000000..131207f3ef --- /dev/null +++ b/test/worlds/diff_drive_custom_tf_topic.sdf @@ -0,0 +1,244 @@ + + + + + + 0.001 + 1.0 + + + + + + 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 + + + + + + + 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.325 0 -0 0 + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 0.5 1.0 1 + 0.5 0.5 1.0 1 + 0.0 0.0 1.0 1 + + + + + + 2.01142 1 0.568726 + + + + + + + 0.554283 0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + + 0.554282 -0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + + -0.957138 -0 -0.125 0 -0 0 + + 1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + + 0.2 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.2 + + + + + + + chassis + left_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + right_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + caster + + + + left_wheel_joint + right_wheel_joint + 1.25 + 0.3 + 1 + 0.5 + tf_foo + + + + + + + + + + + From 20b6a9da65a98fccebf247346fd4e83c08da5a1d Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 22 Feb 2021 16:19:52 -0800 Subject: [PATCH 50/55] Add console message to show computed temp range (#643) Signed-off-by: Ian Chen --- src/systems/sensors/Sensors.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 93d14fb354..a20b5c3280 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -596,6 +596,12 @@ std::string Sensors::CreateSensor(const Entity &_entity, double tempRange = std::fabs(this->dataPtr->ambientTemperatureGradient * height); thermalSensor->SetAmbientTemperatureRange(tempRange); + + ignmsg << "Setting ambient temperature to " + << this->dataPtr->ambientTemperature << " Kelvin and gradient to " + << this->dataPtr->ambientTemperatureGradient << " K/m. " + << "The resulting temperature range is: " << tempRange + << " Kelvin." << std::endl; } return sensor->Name(); From 159f6202af80a480e8820318aa0b84d0c67ccfef Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Tue, 23 Feb 2021 19:46:06 +0100 Subject: [PATCH 51/55] Add a convenience function for getting possibly non-existing components. (#629) Signed-off-by: Martin Pecka --- .../ignition/gazebo/EntityComponentManager.hh | 13 ++++++++++ .../gazebo/detail/EntityComponentManager.hh | 14 +++++++++++ src/EntityComponentManager_TEST.cc | 25 +++++++++++++++++++ 3 files changed, 52 insertions(+) diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index da70f606ea..768432498d 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -214,6 +214,19 @@ namespace ignition public: template ComponentTypeT *Component(const ComponentKey &_key); + /// \brief Get a mutable component assigned to an entity based on a + /// component type. If the component doesn't exist, create it and + /// initialize with the given default value. + /// \param[in] _entity The entity. + /// \param[in] _default The value that should be used to construct + /// the component in case the component doesn't exist. + /// \return The component of the specified type assigned to the specified + /// entity. + public: template + ComponentTypeT *ComponentDefault(Entity _entity, + const typename ComponentTypeT::Type &_default = + typename ComponentTypeT::Type()); + /// \brief Get the data from a component. /// * If the component type doesn't hold any data, this won't compile. /// * If the entity doesn't have that component, it will return nullopt. diff --git a/include/ignition/gazebo/detail/EntityComponentManager.hh b/include/ignition/gazebo/detail/EntityComponentManager.hh index 880dba745c..dcdb37324b 100644 --- a/include/ignition/gazebo/detail/EntityComponentManager.hh +++ b/include/ignition/gazebo/detail/EntityComponentManager.hh @@ -127,6 +127,20 @@ ComponentTypeT *EntityComponentManager::Component(const ComponentKey &_key) this->ComponentImplementation(_key)); } +////////////////////////////////////////////////// +template +ComponentTypeT *EntityComponentManager::ComponentDefault(Entity _entity, + const typename ComponentTypeT::Type &_default) +{ + auto comp = this->Component(_entity); + if (!comp) + { + this->CreateComponent(_entity, ComponentTypeT(_default)); + comp = this->Component(_entity); + } + return comp; +} + ////////////////////////////////////////////////// template std::optional diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index b29fb53aef..cf42727bdd 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -437,6 +437,31 @@ TEST_P(EntityComponentManagerFixture, EntitiesAndComponents) EXPECT_FALSE(manager.EntityHasComponentType(entity, DoubleComponent::typeId)); EXPECT_FALSE(manager.EntityHasComponentType(entity2, IntComponent::typeId)); + // Query non-existing component, the default value is default-constructed + BoolComponent *boolComp = manager.ComponentDefault(entity); + ASSERT_NE(nullptr, boolComp); + EXPECT_TRUE(manager.HasComponentType(BoolComponent::typeId)); + EXPECT_TRUE(manager.EntityHasComponentType(entity, BoolComponent::typeId)); + EXPECT_EQ(false, boolComp->Data()); + + // Query non-existing component, the default value is used + DoubleComponent *doubleComp = + manager.ComponentDefault(entity, 1.0); + ASSERT_NE(nullptr, doubleComp); + EXPECT_TRUE(manager.HasComponentType(DoubleComponent::typeId)); + EXPECT_TRUE(manager.EntityHasComponentType(entity, IntComponent::typeId)); + EXPECT_TRUE(manager.EntityHasComponentType(entity, DoubleComponent::typeId)); + EXPECT_FALSE( + manager.EntityHasComponentType(entity2, DoubleComponent::typeId)); + EXPECT_FLOAT_EQ(1.0, doubleComp->Data()); + + // Query existing component, the default value is not used + IntComponent *intComp = manager.ComponentDefault(entity, 124); + ASSERT_NE(nullptr, intComp); + EXPECT_TRUE(manager.HasComponentType(IntComponent::typeId)); + EXPECT_TRUE(manager.EntityHasComponentType(entity, IntComponent::typeId)); + EXPECT_EQ(123, intComp->Data()); + // Remove all entities manager.RequestRemoveEntities(); EXPECT_EQ(3u, manager.EntityCount()); From 4a4951e838a98f3c94352887583213f417971243 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 23 Feb 2021 15:23:10 -0800 Subject: [PATCH 52/55] Fix flaky SceneBoradcaster test (#641) Signed-off-by: Louise Poubel Co-authored-by: Michael Carroll --- test/integration/scene_broadcaster_system.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index b5ae9c0f9c..bee470ef2e 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -438,6 +438,7 @@ TEST_P(SceneBroadcasterTest, State) while (!received && sleep++ < maxSleep) IGN_SLEEP_MS(100); EXPECT_TRUE(received); + EXPECT_TRUE(node.Unsubscribe("/world/default/state")); // test async state request received = false; From 3702dc84c9bf0a390b20f0133256a5e5af9fc6ec Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 25 Feb 2021 10:12:18 -0800 Subject: [PATCH 53/55] =?UTF-8?q?=F0=9F=91=A9=E2=80=8D=F0=9F=8C=BE=20Set?= =?UTF-8?q?=20LD=5FLIBRARY=5FPATH=20on=20Actions=20CI=20(fix=20user=5Fcomm?= =?UTF-8?q?ands=20test)=20(#650)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- .github/ci/after_make.sh | 1 + CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/ci/after_make.sh b/.github/ci/after_make.sh index eb81ef7985..8e619ed869 100644 --- a/.github/ci/after_make.sh +++ b/.github/ci/after_make.sh @@ -5,6 +5,7 @@ set -e # Install (needed for some tests) make install +export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:/usr/local/lib # For ign-tools export IGN_CONFIG_PATH=/usr/local/share/ignition diff --git a/CMakeLists.txt b/CMakeLists.txt index 95585b11f1..abc409f202 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,7 +38,7 @@ endif() # Search for project-specific dependencies #============================================================================ -ign_find_package(sdformat10 REQUIRED) +ign_find_package(sdformat10 REQUIRED VERSION 10.3) set(SDF_VER ${sdformat10_VERSION_MAJOR}) #-------------------------------------- From 8e29cda909adb529b9cbd0acba9b56f257520d51 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 26 Feb 2021 14:06:21 -0800 Subject: [PATCH 54/55] codecheck Signed-off-by: Louise Poubel --- src/systems/physics/Physics.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 84b5276e31..2a4a05cbbd 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -27,6 +27,7 @@ #include #include #include +#include #include #include From dc60a3aeb76784c891bbd19f63b5d5728c147792 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 1 Mar 2021 13:22:43 -0800 Subject: [PATCH 55/55] Fix Windows compilation (#622) Signed-off-by: Louise Poubel --- src/Conversions.cc | 2 ++ src/gui/AboutDialogHandler.hh | 2 +- src/gui/plugins/plotting/Plotting.cc | 6 ++++-- src/systems/collada_world_exporter/ColladaWorldExporter.hh | 2 +- .../JointTrajectoryController.hh | 4 ++-- src/systems/particle_emitter/ParticleEmitter.hh | 2 +- src/systems/thermal/ThermalSensor.hh | 2 +- test/integration/fuel_cached_server.cc | 3 ++- test/integration/joint_trajectory_controller_system.cc | 7 +++++-- test/integration/particle_emitter.cc | 6 ++++-- test/integration/thermal_sensor_system.cc | 5 +++-- test/integration/user_commands.cc | 1 + 12 files changed, 27 insertions(+), 15 deletions(-) diff --git a/src/Conversions.cc b/src/Conversions.cc index 9765e88011..d7fb552857 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -841,6 +841,7 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg, ////////////////////////////////////////////////// template<> +IGNITION_GAZEBO_VISIBLE msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) { msgs::Physics out; @@ -851,6 +852,7 @@ msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) ////////////////////////////////////////////////// template<> +IGNITION_GAZEBO_VISIBLE sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) { sdf::Physics out; diff --git a/src/gui/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh index b5f71b543d..14f1bbd20c 100644 --- a/src/gui/AboutDialogHandler.hh +++ b/src/gui/AboutDialogHandler.hh @@ -33,7 +33,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace gui { /// \brief Class for handling about dialog -class IGNITION_GAZEBO_VISIBLE AboutDialogHandler : public QObject +class AboutDialogHandler : public QObject { Q_OBJECT diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 864eebb1c9..9a78d4de15 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -18,6 +18,7 @@ #include "Plotting.hh" #include + #include "ignition/gazebo/components/AngularAcceleration.hh" #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/CastShadows.hh" @@ -232,7 +233,7 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) this->dataPtr->components[_Id]->SetAttributeValue("z", _vector.Z()); } -void Plotting::SetData(std::string _Id, const msgs::Light &_light) +void Plotting::SetData(std::string _Id, const ignition::msgs::Light &_light) { if (_light.has_specular()) { @@ -482,7 +483,8 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, auto comp = _ecm.Component(entity); if (comp) { - msgs::Light lightMsgs = convert(comp->Data()); + ignition::msgs::Light lightMsgs = + convert(comp->Data()); this->SetData(component.first, lightMsgs); } } diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.hh b/src/systems/collada_world_exporter/ColladaWorldExporter.hh index c31a175b0a..731c9ec2ee 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.hh +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.hh @@ -35,7 +35,7 @@ namespace systems /// \brief A plugin that exports a world to a mesh. /// When loaded the plugin will dump a mesh containing all the models in /// the world to the current directory. - class IGNITION_GAZEBO_VISIBLE ColladaWorldExporter: + class ColladaWorldExporter: public System, public ISystemPostUpdate { diff --git a/src/systems/joint_trajectory_controller/JointTrajectoryController.hh b/src/systems/joint_trajectory_controller/JointTrajectoryController.hh index 8f895b77e0..fb60279d1d 100644 --- a/src/systems/joint_trajectory_controller/JointTrajectoryController.hh +++ b/src/systems/joint_trajectory_controller/JointTrajectoryController.hh @@ -30,7 +30,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace systems { // Forward declaration - class IGNITION_GAZEBO_HIDDEN JointTrajectoryControllerPrivate; + class JointTrajectoryControllerPrivate; /// \brief Joint trajectory controller, which can be attached to a model with /// reference to one or more 1-axis joints in order to follow a trajectory. @@ -131,7 +131,7 @@ namespace systems /// This parameter can be specified multiple times. Follows joint_name order. /// Optional parameter. /// The default value is 0 (no offset). - class IGNITION_GAZEBO_VISIBLE JointTrajectoryController + class JointTrajectoryController : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 5b3df5e476..7a9ab1e278 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -110,7 +110,7 @@ namespace systems /// Note that the emitter id and name may not be changed. /// See the examples/worlds/particle_emitter.sdf example world for /// example usage. - class IGNITION_GAZEBO_VISIBLE ParticleEmitter + class ParticleEmitter : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/thermal/ThermalSensor.hh b/src/systems/thermal/ThermalSensor.hh index ed2fb431f2..c0a27306d3 100644 --- a/src/systems/thermal/ThermalSensor.hh +++ b/src/systems/thermal/ThermalSensor.hh @@ -34,7 +34,7 @@ namespace systems class ThermalSensorPrivate; /// \brief A thermal sensor plugin for configuring thermal sensor properties - class IGNITION_GAZEBO_VISIBLE ThermalSensor: + class ThermalSensor: public System, public ISystemConfigure { diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc index 7003459ff7..a0182cc5d2 100644 --- a/test/integration/fuel_cached_server.cc +++ b/test/integration/fuel_cached_server.cc @@ -16,6 +16,7 @@ */ #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/ServerConfig.hh" @@ -31,7 +32,7 @@ TEST_P(ServerFixture, CachedFuelWorld) { auto cachedWorldPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds"); - setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1); + common::setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str()); ServerConfig serverConfig; auto fuelWorldURL = diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 70ca0aad3f..7e8bc21a09 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -20,7 +20,10 @@ #include #include +#include + #include +#include #include #include "ignition/gazebo/components/Joint.hh" @@ -47,8 +50,8 @@ class JointTrajectoryControllerTestFixture : public ::testing::Test void SetUp() override { ignition::common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); } }; diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 29dd17fa0c..f2527b8357 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -19,6 +19,8 @@ #include +#include + #include #include @@ -41,8 +43,8 @@ class ParticleEmitterTest : public ::testing::Test protected: void SetUp() override { ignition::common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); + ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); } public: void LoadWorld(const std::string &_path, bool _useLevels = false) { diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc index 472a8a60ff..be34ca4a8b 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -151,7 +151,7 @@ TEST_F(ThermalSensorTest, // Run server server.Run(true, 1, false); - // verify camera properties from sdf + // verify camera properties from sdf unsigned int width = 320u; unsigned int height = 240u; EXPECT_EQ("thermal_camera_invalid", name); @@ -180,7 +180,7 @@ TEST_F(ThermalSensorTest, EXPECT_DOUBLE_EQ(800.0, entityTemp[cylinderVisual].Kelvin()); // Run server - server.Run(true, 10, false); + server.Run(true, 35, false); // wait for image bool received = false; @@ -195,6 +195,7 @@ TEST_F(ThermalSensorTest, std::this_thread::sleep_for(std::chrono::milliseconds(100)); } EXPECT_TRUE(received); + ASSERT_NE(nullptr, g_image); // check temperature in actual image output { diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index aceaaafaff..d9d398d154 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -19,6 +19,7 @@ #include #include +#include #include #include